diff --git a/.editorconfig b/.editorconfig index a0fa3eff170e..b8f6ef7f8e32 100644 --- a/.editorconfig +++ b/.editorconfig @@ -4,10 +4,10 @@ root = true [{*.patch,syntax_test_*}] trim_trailing_whitespace = false -[{*.c,*.cpp,*.h}] +[{*.c,*.cpp,*.h,*.ino}] charset = utf-8 -[{*.c,*.cpp,*.h,Makefile}] +[{*.c,*.cpp,*.h,*.ino,Makefile}] trim_trailing_whitespace = true insert_final_newline = true end_of_line = lf diff --git a/.gitattributes b/.gitattributes index 2588229e0544..83897cba6ed3 100644 --- a/.gitattributes +++ b/.gitattributes @@ -17,3 +17,5 @@ *.png binary *.jpg binary *.fon binary +*.bin binary +*.woff binary diff --git a/.github/ISSUE_TEMPLATE/bug_report.md b/.github/ISSUE_TEMPLATE/bug_report.md deleted file mode 100644 index 6e735974a921..000000000000 --- a/.github/ISSUE_TEMPLATE/bug_report.md +++ /dev/null @@ -1,59 +0,0 @@ ---- -name: Bug report -about: Report a bug in Marlin -title: "[BUG] (short description)" -labels: '' -assignees: '' - ---- - - - -### Bug Description - - - -### Configuration Files - -**Required:** Include a ZIP file containing `Configuration.h` and `Configuration_adv.h`. - -If you've made any other modifications describe them in detail here. - -### Steps to Reproduce - - - -1. [First Step] -2. [Second Step] -3. [and so on...] - -**Expected behavior:** - - - -**Actual behavior:** - - - -#### Additional Information - -* Provide pictures or links to videos that clearly demonstrate the issue. -* See [Contributing to Marlin](https://github.com/MarlinFirmware/Marlin/blob/2.0.x/.github/contributing.md) for additional guidelines. diff --git a/.github/ISSUE_TEMPLATE/bug_report.yml b/.github/ISSUE_TEMPLATE/bug_report.yml new file mode 100644 index 000000000000..0e6028a31df7 --- /dev/null +++ b/.github/ISSUE_TEMPLATE/bug_report.yml @@ -0,0 +1,169 @@ +name: 🪲 Report a bug +description: Create a bug report to help improve Marlin Firmware +title: "[BUG] (bug summary)" +body: + - type: markdown + attributes: + value: > + Do you want to ask a question? Are you looking for support? Please use one of the [support links](https://github.com/MarlinFirmware/Marlin/issues/new/choose). + + - type: markdown + attributes: + value: | + **Thank you for reporting a bug in Marlin Firmware!** + + ## Before Reporting a Bug + + - Read and understand Marlin's [Code of Conduct](https://github.com/MarlinFirmware/Marlin/blob/master/.github/code_of_conduct.md). You are expected to comply with it, including treating everyone with respect. + + - Test with the [`bugfix-2.0.x` branch](https://github.com/MarlinFirmware/Marlin/archive/bugfix-2.0.x.zip) to see whether the issue still exists. + + ## Instructions + + Please follow the instructions below. Failure to do so may result in your issue being closed. See [Contributing to Marlin](https://github.com/MarlinFirmware/Marlin/blob/2.0.x/.github/contributing.md) for additional guidelines. + + 1. Provide a good title starting with [BUG]. + 2. Fill out all sections of this bug report form. + 3. Always attach configuration files so we can build and test your setup. + + - type: dropdown + attributes: + label: Did you test the latest `bugfix-2.0.x` code? + description: >- + Always try the latest code to make sure the issue you are reporting is not already fixed. To download + the latest code just [click this link](https://github.com/MarlinFirmware/Marlin/archive/bugfix-2.0.x.zip). + options: + - Yes, and the problem still exists. + - No, but I will test it now! + validations: + required: true + + - type: markdown + attributes: + value: | + # Bug Details + + - type: textarea + attributes: + label: Bug Description + description: >- + Describe the bug in this section. Tell us what you were trying to do and what + happened that you did not expect. Provide a clear and concise description of the + problem and include as many details as possible. + placeholder: | + Marlin doesn't work. + validations: + required: true + + - type: input + attributes: + label: Bug Timeline + description: Is this a new bug or an old issue? When did it first start? + + - type: textarea + attributes: + label: Expected behavior + description: >- + What did you expect to happen? + placeholder: I expected it to move left. + + - type: textarea + attributes: + label: Actual behavior + description: What actually happened instead? + placeholder: It moved right instead of left. + + - type: textarea + attributes: + label: Steps to Reproduce + description: >- + Please describe the steps needed to reproduce the issue. + placeholder: | + 1. [First Step] ... + 2. [Second Step] ... + 3. [and so on] ... + + - type: markdown + attributes: + value: | + # Your Setup + + - type: input + attributes: + label: Version of Marlin Firmware + description: "See the About Menu on the LCD or the output of `M115`. NOTE: For older releases we only patch critical bugs." + validations: + required: true + + - type: input + attributes: + label: Printer model + description: Creality Ender 3, Prusa mini, or Kossel Delta? + + - type: input + attributes: + label: Electronics + description: Stock electronics, upgrade board, or something else? + + - type: input + attributes: + label: Add-ons + description: Please list any hardware add-ons that could be involved. + + - type: dropdown + attributes: + label: Bed Leveling + description: What kind of bed leveling compensation are you using? + options: + - UBL Bilinear mesh + - ABL Bilinear mesh + - ABL Linear grid + - ABL 3-point + - MBL Manual Bed Leveling + - No Bed Leveling + + - type: dropdown + attributes: + label: Your Slicer + description: Do you use Slic3r, Prusa Slicer, Simplify3D, IdeaMaker...? + options: + - Slic3r + - Simplify3D + - Prusa Slicer + - IdeaMaker + - Cura + - Other (explain below) + + - type: dropdown + attributes: + label: Host Software + description: Do you use OctoPrint, Repetier Host, Pronterface...? + options: + - SD Card (headless) + - Repetier Host + - OctoPrint + - Pronterface + - Cura + - Same as my slicer + - Other (explain below) + + - type: markdown + attributes: + value: >- + ## Other things to include + + Please also be sure to include these items to help with troubleshooting: + + * **A ZIP file** containing your `Configuration.h` and `Configuration_adv.h`. + (Please don't paste lengthy configuration text here.) + * **Log output** from the host. (`M111 S247` for maximum logging.) + * **Images or videos** demonstrating the problem, if it helps to make it clear. + * **A G-Code file** that exposes the problem, if not affecting _all_ G-code. + + If you've made any other modifications to the firmware, please describe them in detail in the space provided. + + When pasting formatted text into the box below don't forget to put ` ``` ` (on its own line) before and after to make it readable. + + - type: textarea + attributes: + label: Additional information & file uploads diff --git a/.github/ISSUE_TEMPLATE/config.yml b/.github/ISSUE_TEMPLATE/config.yml index 4b283d26005c..3f5d6fe5517d 100644 --- a/.github/ISSUE_TEMPLATE/config.yml +++ b/.github/ISSUE_TEMPLATE/config.yml @@ -1,17 +1,20 @@ blank_issues_enabled: false contact_links: - - name: Marlin Documentation + - name: 📖 Marlin Documentation url: http://marlinfw.org/ about: Lots of documentation on installing and using Marlin. - - name: MarlinFirmware Facebook group + - name: 👤 MarlinFirmware Facebook group url: https://www.facebook.com/groups/1049718498464482 about: Please ask and answer questions here. - - name: Marlin on Discord + - name: 🕹 Marlin on Discord url: https://discord.gg/n5NJ59y about: Join the Discord server for support and discussion. - - name: Marlin Discussion Forum + - name: 🔗 Marlin Discussion Forum url: http://forums.reprap.org/list.php?415 about: A searchable web forum hosted by RepRap dot org. - - name: Marlin Videos on YouTube + - name: 📺 Marlin Videos on YouTube url: https://www.youtube.com/results?search_query=marlin+firmware about: Tutorials and more from Marlin users all around the world. Great for new users! + - name: 💸 Want to donate? + url: https://www.thinkyhead.com/donate-to-marlin + about: Please take a look at the various options to support Marlin Firmware's development financially! diff --git a/.github/ISSUE_TEMPLATE/feature_request.md b/.github/ISSUE_TEMPLATE/feature_request.md deleted file mode 100644 index 24de8d01419b..000000000000 --- a/.github/ISSUE_TEMPLATE/feature_request.md +++ /dev/null @@ -1,35 +0,0 @@ ---- -name: Feature request -about: Request a Feature -title: "[FR] (feature request title)" -labels: 'T: Feature Request' -assignees: '' - ---- - - - -### Description - - - -### Feature Workflow - - - -1. [First Action] -2. [Second Action] -3. [and so on...] - -#### Additional Information - -* Provide pictures or links that demonstrate a similar feature or concept. -* See [How Can I Contribute](#how-can-i-contribute) for additional guidelines. diff --git a/.github/ISSUE_TEMPLATE/feature_request.yml b/.github/ISSUE_TEMPLATE/feature_request.yml new file mode 100644 index 000000000000..df1938ccd84a --- /dev/null +++ b/.github/ISSUE_TEMPLATE/feature_request.yml @@ -0,0 +1,44 @@ +name: ✨ Request a feature +description: Request a new Marlin Firmware feature +title: "[FR] (feature summary)" +labels: 'T: Feature Request' +body: + - type: markdown + attributes: + value: > + Do you want to ask a question? Are you looking for support? Please use one of the [support links](https://github.com/MarlinFirmware/Marlin/issues/new/choose). + + - type: markdown + attributes: + value: > + **Thank you for requesting a new Marlin Firmware feature!** + + ## Before Requesting a Feature + + - Read and understand Marlin's [Code of Conduct](https://github.com/MarlinFirmware/Marlin/blob/master/.github/code_of_conduct.md). You are expected to comply with it, including treating everyone with respect. + + - Check the latest [`bugfix-2.0.x` branch](https://github.com/MarlinFirmware/Marlin/archive/bugfix-2.0.x.zip) to see if the feature already exists. + + - Before you proceed with your request, please consider if it is necessary to make it into a firmware feature, or if it may be better suited for a slicer or host feature. + + - type: textarea + attributes: + label: Is your feature request related to a problem? Please describe. + description: A clear description of the problem (e.g., "I need X but Marlin can't do it [...]"). + + - type: textarea + attributes: + label: Are you looking for hardware support? + description: Tell us the printer, board, or peripheral that needs support. + + - type: textarea + attributes: + label: Describe the feature you want + description: A clear description of the feature and how you think it should work. + validations: + required: true + + - type: textarea + attributes: + label: Additional context + description: Add any other context or screenshots about the feature request here. diff --git a/.github/issue_template.md b/.github/issue_template.md index a211ca5e2715..6cb34b8f588a 100644 --- a/.github/issue_template.md +++ b/.github/issue_template.md @@ -1,11 +1,35 @@ -# NO SUPPORT REQUESTS PLEASE + + +### Description + + + +### Steps to Reproduce + + + +1. [First Step] +2. [Second Step] +3. [and so on...] + +**Expected behavior:** [What you expect to happen] + +**Actual behavior:** [What actually happens] + +#### Additional Information + +* Include a ZIP file containing your `Configuration.h` and `Configuration_adv.h` files. +* Provide pictures or links to videos that clearly demonstrate the issue. +* See [How Can I Contribute](#how-can-i-contribute) for additional guidelines. diff --git a/.github/pull_request_template.md b/.github/pull_request_template.md index d82fb0f9e37b..cd5158b3ce8c 100644 --- a/.github/pull_request_template.md +++ b/.github/pull_request_template.md @@ -1,23 +1,33 @@ -### Requirements + ### Description +### Requirements + + + ### Benefits - + ### Configurations - + ### Related Issues - + diff --git a/.github/workflows/bump-date.yml b/.github/workflows/bump-date.yml index 54902da8c908..a1942777d1ae 100644 --- a/.github/workflows/bump-date.yml +++ b/.github/workflows/bump-date.yml @@ -28,6 +28,7 @@ jobs: # Inline Bump Script DIST=$( date +"%Y-%m-%d" ) eval "sed -E -i 's/(#define +STRING_DISTRIBUTION_DATE) .*$/\1 \"$DIST\"/g' Marlin/src/inc/Version.h" && \ + eval "sed -E -i 's/(#define +STRING_DISTRIBUTION_DATE) .*$/\1 \"$DIST\"/g' Marlin/Version.h" && \ git config user.name "${GITHUB_ACTOR}" && \ git config user.email "${GITHUB_ACTOR}@users.noreply.github.com" && \ git add . && \ diff --git a/.github/workflows/check-pr.yml b/.github/workflows/check-pr.yml index aa4a2c59c9a4..b30513f7ccb0 100644 --- a/.github/workflows/check-pr.yml +++ b/.github/workflows/check-pr.yml @@ -20,9 +20,8 @@ jobs: runs-on: ubuntu-latest steps: - - uses: peter-evans/close-pull@v1 + - uses: superbrothers/close-pull-request@v3 with: - delete-branch: false comment: > Thanks for your contribution! Unfortunately we can't accept PRs directed at release branches. We make patches to the bugfix branches and only later do we push them out as releases. diff --git a/.github/workflows/clean-closed.yml b/.github/workflows/clean-closed.yml new file mode 100644 index 000000000000..befec4498f25 --- /dev/null +++ b/.github/workflows/clean-closed.yml @@ -0,0 +1,39 @@ +# +# clean-closed.yml +# Remove obsolete labels when an Issue or PR is closed +# + +name: Clean Closed + +on: + pull_request: + types: [closed] + issues: + types: [closed] + +jobs: + remove_label: + runs-on: ubuntu-latest + + strategy: + matrix: + label: + - "S: Don't Merge" + - "S: Hold for 2.1" + - "S: Please Merge" + - "S: Please Test" + - "help wanted" + - "Needs: Discussion" + - "Needs: Documentation" + - "Needs: More Data" + - "Needs: Patch" + - "Needs: Testing" + - "Needs: Work" + + steps: + - uses: actions/checkout@v2 + - name: Remove Labels + uses: actions-ecosystem/action-remove-labels@v1 + with: + github_token: ${{ github.token }} + labels: ${{ matrix.label }} diff --git a/.github/workflows/close-stale.yml b/.github/workflows/close-stale.yml index 89d5d65351d9..f017907d2934 100644 --- a/.github/workflows/close-stale.yml +++ b/.github/workflows/close-stale.yml @@ -20,8 +20,9 @@ jobs: - uses: actions/stale@v3 with: repo-token: ${{ secrets.GITHUB_TOKEN }} - stale-issue-message: 'This issue has had no activity in the last 30 days. Please add a reply if you want to keep this issue active, otherwise it will be automatically closed within 7 days.' - days-before-stale: 30 - days-before-close: 7 + stale-issue-message: 'This issue has had no activity in the last 60 days. Please add a reply if you want to keep this issue active, otherwise it will be automatically closed within 10 days.' + days-before-stale: 60 + days-before-close: 10 stale-issue-label: 'stale-closing-soon' - exempt-issue-labels: 'T: Feature Request' + exempt-all-assignees: true + exempt-issue-labels: 'Bug: Confirmed !,T: Feature Request,Needs: Discussion,Needs: Documentation,Needs: More Data,Needs: Patch,Needs: Work,Needs: Testing,help wanted,no-locking' diff --git a/.github/workflows/lock-closed.yml b/.github/workflows/lock-closed.yml index 8cdcd7a8369e..81145688288b 100644 --- a/.github/workflows/lock-closed.yml +++ b/.github/workflows/lock-closed.yml @@ -22,7 +22,7 @@ jobs: github-token: ${{ github.token }} process-only: 'issues' issue-lock-inactive-days: '60' - issue-exclude-created-before: '' + issue-exclude-created-before: '2017-07-01T00:00:00Z' issue-exclude-labels: 'no-locking' issue-lock-labels: '' issue-lock-comment: > diff --git a/.github/workflows/test-builds.yml b/.github/workflows/test-builds.yml index b2287837998b..c6afaffebf7a 100644 --- a/.github/workflows/test-builds.yml +++ b/.github/workflows/test-builds.yml @@ -36,9 +36,11 @@ jobs: # Base Environments - DUE + - DUE_archim - esp32 - linux_native - mega2560 + - at90usb1286_dfu - teensy31 - teensy35 - teensy41 @@ -46,21 +48,34 @@ jobs: # Extended AVR Environments - - FYSETC_F6_13 + - FYSETC_F6 - mega1280 - rambo - sanguino1284p - sanguino644p - # Extended STM32 Environments + # STM32F1 (Maple) Environments + + #- STM32F103RC_btt_maple + - STM32F103RC_btt_USB_maple + - STM32F103RC_fysetc_maple + - STM32F103RC_meeb + - jgaurora_a5s_a1_maple + - STM32F103VE_longer_maple + #- mks_robin_maple + - mks_robin_lite_maple + - mks_robin_pro_maple + #- mks_robin_nano35_maple + #- STM32F103RET6_creality_maple + - STM32F103VE_ZM3E4V2_USB_maple + + # STM32 (ST) Environments - STM32F103RC_btt - - STM32F103RC_btt_USB + #- STM32F103RC_btt_USB - STM32F103RE_btt - STM32F103RE_btt_USB - - STM32F103RC_fysetc - - STM32F103RC_meeb - - jgaurora_a5s_a1 + - STM32F103RET6_creality - STM32F103VE_longer - STM32F407VE_black - STM32F401VE_STEVAL @@ -68,40 +83,53 @@ jobs: - BIGTREE_SKR_PRO - BIGTREE_GTR_V1_0 - mks_robin - - mks_robin_stm32 - ARMED - FYSETC_S6 - STM32F070CB_malyan - STM32F070RB_malyan - malyan_M300 - - mks_robin_lite - FLYF407ZG - rumba32 - - mks_robin_pro - - STM32F103RET6_creality - LERDGEX + - LERDGEK - mks_robin_nano35 + - NUCLEO_F767ZI + - REMRAM_V1 + - BTT_SKR_SE_BX + - chitu_f103 # Put lengthy tests last - LPC1768 - LPC1769 - # STM32 with non-STM framework. both broken for now. they should use HAL_STM32 which is working. - - #- STM32F4 - #- STM32F7 - # Non-working environment tests #- at90usb1286_cdc - #- at90usb1286_dfu #- STM32F103CB_malyan + #- STM32F103RE #- mks_robin_mini steps: + - name: Check out the PR + uses: actions/checkout@v2 + + - name: Cache pip + uses: actions/cache@v2 + with: + path: ~/.cache/pip + key: ${{ runner.os }}-pip-${{ hashFiles('**/requirements.txt') }} + restore-keys: | + ${{ runner.os }}-pip- + + - name: Cache PlatformIO + uses: actions/cache@v2 + with: + path: ~/.platformio + key: ${{ runner.os }}-${{ hashFiles('**/lockfiles') }} + - name: Select Python 3.7 - uses: actions/setup-python@v1 + uses: actions/setup-python@v2 with: python-version: '3.7' # Version range or exact version of a Python version to use, using semvers version range syntax. architecture: 'x64' # optional x64 or x86. Defaults to x64 if not specified @@ -111,13 +139,6 @@ jobs: pip install -U https://github.com/platformio/platformio-core/archive/develop.zip platformio update - - name: Check out the PR - uses: actions/checkout@v2 - - name: Run ${{ matrix.test-platform }} Tests run: | - # Inline tests script - chmod +x buildroot/bin/* - chmod +x buildroot/tests/* - export PATH=./buildroot/bin/:./buildroot/tests/:${PATH} - run_tests . ${{ matrix.test-platform }} + make tests-single-ci TEST_TARGET=${{ matrix.test-platform }} diff --git a/.gitignore b/.gitignore index c163d339dff3..bc603ba38b0d 100755 --- a/.gitignore +++ b/.gitignore @@ -19,9 +19,9 @@ # along with this program. If not, see . # -# Our automatic versioning scheme generates the following file -# NEVER put it in the repository +# Generated files _Version.h +bdf2u8g # # OS @@ -77,7 +77,6 @@ tags *.out *.app - # # C # @@ -123,33 +122,10 @@ tags .gcc-flags.json /lib/ -# Workaround for Deviot+platformio quirks -Marlin/lib -Marlin/platformio.ini -Marlin/*/platformio.ini -Marlin/*/*/platformio.ini -Marlin/*/*/*/platformio.ini -Marlin/*/*/*/*/platformio.ini -Marlin/.travis.yml -Marlin/*/.travis.yml -Marlin/*/*/.travis.yml -Marlin/*/*/*/.travis.yml -Marlin/*/*/*/*/.travis.yml -Marlin/.gitignore -Marlin/*/.gitignore -Marlin/*/*/.gitignore -Marlin/*/*/*/.gitignore -Marlin/*/*/*/*/.gitignore -Marlin/readme.txt -Marlin/*/readme.txt -Marlin/*/*/readme.txt -Marlin/*/*/*/readme.txt -Marlin/*/*/*/*/readme.txt - # Secure Credentials Configuration_Secure.h -#Visual Studio +# Visual Studio *.sln *.vcxproj *.vcxproj.user @@ -160,27 +136,38 @@ __vm/ .vs/ vc-fileutils.settings -#Visual Studio Code +# Visual Studio Code .vscode .vscode/.browse.c_cpp.db* .vscode/c_cpp_properties.json .vscode/launch.json .vscode/*.db +#Simulation +imgui.ini +eeprom.dat + #cmake CMakeLists.txt src/CMakeLists.txt CMakeListsPrivate.txt -#CLion +# CLion cmake-build-* -#Eclipse +# Eclipse .project .cproject .pydevproject .settings .classpath -#Python +# Python __pycache__ + +# IOLogger logs +*_log.csv + +# Simulation / Native +eeprom.dat +imgui.ini diff --git a/Makefile b/Makefile new file mode 100644 index 000000000000..ebcdf25e2d6a --- /dev/null +++ b/Makefile @@ -0,0 +1,52 @@ +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-compose" + @echo "* tests-all-local: Run all tests locally" + @echo "* tests-all-local-docker: Run all tests locally, using docker-compose" + @echo "* setup-local-docker: Setup local docker-compose" + @echo "" + @echo "Options for testing:" + @echo " TEST_TARGET Set when running tests-single-*, to select the" + @echo " test. If you set it to ALL it will run all " + @echo " tests, but some of them are broken: use " + @echo " tests-all-* instead to run only the ones that " + @echo " run on GitHub CI" + @echo " ONLY_TEST Limit tests to only those that contain this, or" + @echo " the index of the test (1-based)" + @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 + +tests-single-ci: + export GIT_RESET_HARD=true + $(MAKE) tests-single-local TEST_TARGET=$(TEST_TARGET) +.PHONY: tests-single-ci + +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 + docker-compose run --rm marlin $(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 $$(./get_test_targets.py) ; do echo "Running tests for $$TEST_TARGET" ; run_tests . $$TEST_TARGET ; done +.PHONY: tests-all-local + +tests-all-local-docker: + docker-compose run --rm marlin $(MAKE) tests-all-local VERBOSE_PLATFORMIO=$(VERBOSE_PLATFORMIO) GIT_RESET_HARD=$(GIT_RESET_HARD) +.PHONY: tests-all-local-docker + +setup-local-docker: + docker-compose build +.PHONY: setup-local-docker diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index cc45fd2fe2cb..6daf93a376d9 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -35,37 +35,36 @@ * * Advanced settings can be found in Configuration_adv.h */ -#define CONFIGURATION_H_VERSION 020008 +#define CONFIGURATION_H_VERSION 02000901 //=========================================================================== //============================= Getting Started ============================= //=========================================================================== /** - * Here are some standard links for getting your machine calibrated: + * Here are some useful links to help get your machine configured and calibrated: * - * https://reprap.org/wiki/Calibration - * https://youtu.be/wAL9d7FgInk - * http://calculator.josefprusa.cz - * https://reprap.org/wiki/Triffid_Hunter%27s_Calibration_Guide - * https://www.thingiverse.com/thing:5573 - * https://sites.google.com/site/repraplogphase/calibration-of-your-reprap - * https://www.thingiverse.com/thing:298812 + * Example Configs: https://github.com/MarlinFirmware/Configurations/branches/all + * + * Průša Calculator: https://blog.prusaprinters.org/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://youtu.be/wAL9d7FgInk + * + * Calibration Objects: https://www.thingiverse.com/thing:5573 + * https://www.thingiverse.com/thing:1278865 */ //=========================================================================== -//============================= DELTA Printer =============================== +//========================== DELTA / SCARA / TPARA ========================== //=========================================================================== -// For a Delta printer start with one of the configuration files in the -// config/examples/delta directory and customize for your machine. // - -//=========================================================================== -//============================= SCARA Printer =============================== -//=========================================================================== -// For a SCARA printer start with the configuration files in -// config/examples/SCARA and customize for your machine. +// Download configurations from the link above and customize for your machine. +// Examples are located in config/examples/delta, .../SCARA, and .../TPARA. // +//=========================================================================== // @section info @@ -106,14 +105,9 @@ #define SERIAL_PORT 0 /** - * Select a secondary serial port on the board to use for communication with the host. - * Currently Ethernet (-2) is only supported on Teensy 4.1 boards. - * :[-2, -1, 0, 1, 2, 3, 4, 5, 6, 7] - */ -//#define SERIAL_PORT_2 -1 - -/** - * This setting determines the communication speed of the printer. + * Serial Port Baud Rate + * This is the default communication speed for all serial ports. + * Set the baud rate defaults for additional serial ports below. * * 250000 works in most cases, but you might try a lower speed if * you commonly experience drop-outs during host printing. @@ -122,6 +116,23 @@ * :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000] */ #define BAUDRATE 250000 +//#define BAUD_RATE_GCODE // Enable G-code M575 to set the baud rate + +/** + * Select a secondary serial port on the board to use for communication with the host. + * Currently Ethernet (-2) is only supported on Teensy 4.1 boards. + * :[-2, -1, 0, 1, 2, 3, 4, 5, 6, 7] + */ +//#define SERIAL_PORT_2 -1 +//#define BAUDRATE_2 250000 // Enable to override BAUDRATE + +/** + * Select a third serial port on the board to use for communication with the host. + * Currently only supported for AVR, DUE, LPC1768/9 and STM32/STM32F1 + * :[-1, 0, 1, 2, 3, 4, 5, 6, 7] + */ +//#define SERIAL_PORT_3 1 +//#define BAUDRATE_3 250000 // Enable to override BAUDRATE // Enable the Bluetooth serial interface on AT90USB devices //#define BLUETOOTH @@ -138,6 +149,45 @@ // Choose your own or use a service like https://www.uuidgenerator.net/version4 //#define MACHINE_UUID "00000000-0000-0000-0000-000000000000" +/** + * Define the number of coordinated linear axes. + * See https://github.com/DerAndere1/Marlin/wiki + * Each linear axis gets its own stepper control and endstop: + * + * Steppers: *_STEP_PIN, *_ENABLE_PIN, *_DIR_PIN, *_ENABLE_ON + * Endstops: *_STOP_PIN, USE_*MIN_PLUG, USE_*MAX_PLUG + * Axes: *_MIN_POS, *_MAX_POS, INVERT_*_DIR + * Planner: DEFAULT_AXIS_STEPS_PER_UNIT, DEFAULT_MAX_FEEDRATE + * DEFAULT_MAX_ACCELERATION, AXIS_RELATIVE_MODES, + * MICROSTEP_MODES, MANUAL_FEEDRATE + * + * :[3, 4, 5, 6] + */ +//#define LINEAR_AXES 3 + +/** + * Axis codes for additional axes: + * This defines the axis code that is used in G-code commands to + * reference a specific axis. + * 'A' for rotational axis parallel to X + * 'B' for rotational axis parallel to Y + * 'C' for rotational axis parallel to Z + * 'U' for secondary linear axis parallel to X + * 'V' for secondary linear axis parallel to Y + * 'W' for secondary linear axis parallel to Z + * Regardless of the settings, firmware-internal axis IDs are + * I (AXIS4), J (AXIS5), K (AXIS6). + */ +#if LINEAR_AXES >= 4 + #define AXIS4_NAME 'A' // :['A', 'B', 'C', 'U', 'V', 'W'] +#endif +#if LINEAR_AXES >= 5 + #define AXIS5_NAME 'B' // :['A', 'B', 'C', 'U', 'V', 'W'] +#endif +#if LINEAR_AXES >= 6 + #define AXIS6_NAME 'C' // :['A', 'B', 'C', 'U', 'V', 'W'] +#endif + // @section extruder // This defines the number of extruders @@ -158,33 +208,19 @@ #endif /** - * Průša MK2 Single Nozzle Multi-Material Multiplexer, and variants. + * Multi-Material Unit + * Set to one of these predefined models: * - * This device allows one stepper driver on a control board to drive - * two to eight stepper motors, one at a time, in a manner suitable - * for extruders. - * - * This option only allows the multiplexer to switch on tool-change. - * Additional options to configure custom E moves are pending. - */ -//#define MK2_MULTIPLEXER -#if ENABLED(MK2_MULTIPLEXER) - // Override the default DIO selector pins here, if needed. - // Some pins files may provide defaults for these pins. - //#define E_MUX0_PIN 40 // Always Required - //#define E_MUX1_PIN 42 // Needed for 3 to 8 inputs - //#define E_MUX2_PIN 44 // Needed for 5 to 8 inputs -#endif - -/** - * Průša Multi-Material Unit v2 + * PRUSA_MMU1 : Průša MMU1 (The "multiplexer" version) + * PRUSA_MMU2 : Průša MMU2 + * PRUSA_MMU2S : Průša MMU2S (Requires MK3S extruder with motion sensor, EXTRUDERS = 5) + * EXTENDABLE_EMU_MMU2 : MMU with configurable number of filaments (ERCF, SMuFF or similar with Průša MMU2 compatible firmware) + * EXTENDABLE_EMU_MMU2S : MMUS with configurable number of filaments (ERCF, SMuFF or similar with Průša MMU2 compatible firmware) * * Requires NOZZLE_PARK_FEATURE to park print head in case MMU unit fails. - * Requires EXTRUDERS = 5 - * - * For additional configuration see Configuration_adv.h + * See additional options in Configuration_adv.h. */ -//#define PRUSA_MMU2 +//#define MMU_MODEL PRUSA_MMU2 // A dual extruder that uses a single stepper motor //#define SWITCHING_EXTRUDER @@ -344,8 +380,10 @@ #define AUTO_POWER_E_FANS #define AUTO_POWER_CONTROLLERFAN #define AUTO_POWER_CHAMBER_FAN + #define AUTO_POWER_COOLER_FAN //#define AUTO_POWER_E_TEMP 50 // (°C) Turn on PSU if any extruder is over this temperature //#define AUTO_POWER_CHAMBER_TEMP 30 // (°C) Turn on PSU if the chamber is over this temperature + //#define AUTO_POWER_COOLER_TEMP 26 // (°C) Turn on PSU if the cooler is over this temperature #define POWER_TIMEOUT 30 // (s) Turn off power if the machine is idle for this duration //#define POWER_OFF_DELAY 60 // (s) Delay of poweroff after M81 command. Useful to let fans run for extra time. #endif @@ -357,68 +395,92 @@ // @section temperature /** - * --NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table + * --NORMAL IS 4.7kΩ PULLUP!-- 1kΩ pullup can be used on hotend sensor, using correct resistor and table * * Temperature sensors available: * - * -5 : PT100 / PT1000 with MAX31865 (only for sensors 0-1) - * -3 : thermocouple with MAX31855 (only for sensors 0-1) - * -2 : thermocouple with MAX6675 (only for sensors 0-1) - * -4 : thermocouple with AD8495 - * -1 : thermocouple with AD595 + * 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 + * + * 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 + * 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 High Temperature Thermistor + * 67 : 500kΩ SliceEngineering 450°C Thermistor + * 70 : 100kΩ bq Hephestos 2 + * 75 : 100kΩ Generic Silicon Heat Pad with NTC100K MGB18-104F39050L32 + * + * 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 + * + * Analog RTDs (Pt100/Pt1000) + * ------- + * 110 : Pt100 with 1kΩ pullup (atypical) + * 147 : Pt100 with 4.7kΩ pullup + * 1010 : Pt1000 with 1kΩ pullup (atypical) + * 1047 : Pt1000 with 4.7kΩ pullup (E3D) + * 20 : Pt100 with circuit in the Ultimainboard V2.x with mainboard ADC reference voltage = INA826 amplifier-board supply voltage. + * NOTE: (1) Must use an ADC input with no pullup. (2) Some INA826 amplifiers are unreliable at 3.3V so consider using sensor 147, 110, or 21. + * 21 : Pt100 with circuit in the Ultimainboard V2.x with 3.3v ADC reference voltage (STM32, LPC176x....) and 5V INA826 amplifier board supply. + * 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 + * + * Custom/Dummy/Other Thermos + * ------ * 0 : not used - * 1 : 100k thermistor - best choice for EPCOS 100k (4.7k pullup) - * 331 : (3.3V scaled thermistor 1 table for MEGA) - * 332 : (3.3V scaled thermistor 1 table for DUE) - * 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup) - * 202 : 200k thermistor - Copymaster 3D - * 3 : Mendel-parts thermistor (4.7k pullup) - * 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !! - * 5 : 100K thermistor - ATC Semitec 104GT-2/104NT-4-R025H42G (Used in ParCan, J-Head, and E3D) (4.7k pullup) - * 501 : 100K Zonestar (Tronxy X3A) Thermistor - * 502 : 100K Zonestar Thermistor used by hot bed in Zonestar Průša P802M - * 512 : 100k RPW-Ultra hotend thermistor (4.7k pullup) - * 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup) - * 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup) - * 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup) - * 8 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) - * 9 : 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup) - * 10 : 100k RS thermistor 198-961 (4.7k pullup) - * 11 : 100k beta 3950 1% thermistor (Used in Keenovo AC silicone mats and most Wanhao i3 machines) (4.7k pullup) - * 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed) - * 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE" - * 15 : 100k thermistor calibration for JGAurora A5 hotend - * 18 : ATC Semitec 204GT-2 (4.7k pullup) Dagoma.Fr - MKS_Base_DKU001327 - * 20 : Pt100 with circuit in the Ultimainboard V2.x with 5v excitation (AVR) - * 21 : Pt100 with circuit in the Ultimainboard V2.x with 3.3v excitation (STM32 \ LPC176x....) - * 22 : 100k (hotend) with 4.7k pullup to 3.3V and 220R to analog input (as in GTM32 Pro vB) - * 23 : 100k (bed) with 4.7k pullup to 3.3v and 220R to analog input (as in GTM32 Pro vB) - * 30 : Kis3d Silicone heating mat 200W/300W with 6mm precision cast plate (EN AW 5083) NTC100K / B3950 (4.7k pullup) - * 201 : Pt100 with circuit in Overlord, similar to Ultimainboard V2.x - * 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950 - * 61 : 100k Formbot / Vivedino 3950 350C thermistor 4.7k pullup - * 66 : 4.7M High Temperature thermistor from Dyze Design - * 67 : 450C thermistor from SliceEngineering - * 70 : the 100K thermistor found in the bq Hephestos 2 - * 75 : 100k Generic Silicon Heat Pad with NTC 100K MGB18-104F39050L32 thermistor - * 99 : 100k thermistor with a 10K pull-up resistor (found on some Wanhao i3 machines) - * - * 1k ohm pullup tables - This is atypical, and requires changing out the 4.7k pullup for 1k. - * (but gives greater accuracy and more stable PID) - * 51 : 100k thermistor - EPCOS (1k pullup) - * 52 : 200k thermistor - ATC Semitec 204GT-2 (1k pullup) - * 55 : 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup) - * - * 1047 : Pt1000 with 4k7 pullup (E3D) - * 1010 : Pt1000 with 1k pullup (non standard) - * 147 : Pt100 with 4k7 pullup - * 110 : Pt100 with 1k pullup (non standard) - * * 1000 : Custom - Specify parameters in Configuration_adv.h * - * Use these for Testing or Development purposes. NEVER for production machine. + * !!! 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 @@ -431,29 +493,52 @@ #define TEMP_SENSOR_BED 1 #define TEMP_SENSOR_PROBE 0 #define TEMP_SENSOR_CHAMBER 0 +#define TEMP_SENSOR_COOLER 0 +#define TEMP_SENSOR_REDUNDANT 0 // Dummy thermistor constant temperature readings, for use with 998 and 999 -#define DUMMY_THERMISTOR_998_VALUE 25 +#define DUMMY_THERMISTOR_998_VALUE 25 #define DUMMY_THERMISTOR_999_VALUE 100 -// Resistor values when using a MAX31865 (sensor -5) -// Sensor value is typically 100 (PT100) or 1000 (PT1000) -// Calibration value is typically 430 ohm for AdaFruit PT100 modules and 4300 ohm for AdaFruit PT1000 modules. -//#define MAX31865_SENSOR_OHMS 100 -//#define MAX31865_CALIBRATION_OHMS 430 +// Resistor values when using MAX31865 sensors (-5) on TEMP_SENSOR_0 / 1 +//#define MAX31865_SENSOR_OHMS_0 100 // (Ω) Typically 100 or 1000 (PT100 or PT1000) +//#define MAX31865_CALIBRATION_OHMS_0 430 // (Ω) Typically 430 for Adafruit PT100; 4300 for Adafruit PT1000 +//#define MAX31865_SENSOR_OHMS_1 100 +//#define MAX31865_CALIBRATION_OHMS_1 430 -// Use temp sensor 1 as a redundant sensor with sensor 0. If the readings -// from the two sensors differ too much the print will be aborted. -//#define TEMP_SENSOR_1_AS_REDUNDANT -#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10 +#define TEMP_RESIDENCY_TIME 10 // (seconds) Time to wait for hotend to "settle" in M109 +#define TEMP_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer +#define TEMP_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target -#define TEMP_RESIDENCY_TIME 10 // (seconds) Time to wait for hotend to "settle" in M109 -#define TEMP_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer -#define TEMP_HYSTERESIS 5 // (°C) Temperature proximity considered "close enough" to the target +#define TEMP_BED_RESIDENCY_TIME 10 // (seconds) Time to wait for bed to "settle" in M190 +#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer +#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target -#define TEMP_BED_RESIDENCY_TIME 10 // (seconds) Time to wait for bed to "settle" in M190 -#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer -#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target +#define TEMP_CHAMBER_RESIDENCY_TIME 10 // (seconds) Time to wait for chamber to "settle" in M191 +#define TEMP_CHAMBER_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer +#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target + +/** + * Redundant Temperature Sensor (TEMP_SENSOR_REDUNDANT) + * + * Use a temp sensor as a redundant sensor for another reading. Select an unused temperature sensor, and another + * sensor you'd like it to be redundant for. If the two thermistors differ by TEMP_SENSOR_REDUNDANT_MAX_DIFF (°C), + * the print will be aborted. Whichever sensor is selected will have its normal functions disabled; i.e. selecting + * the Bed sensor (-1) will disable bed heating/monitoring. + * + * Use the following to select temp sensors: + * -5 : Cooler + * -4 : Probe + * -3 : not used + * -2 : Chamber + * -1 : Bed + * 0-7 : E0 through E7 + */ +#if TEMP_SENSOR_REDUNDANT + #define TEMP_SENSOR_REDUNDANT_SOURCE 1 // The sensor that will provide the redundant reading. + #define TEMP_SENSOR_REDUNDANT_TARGET 0 // The sensor that we are providing a redundant reading for. + #define TEMP_SENSOR_REDUNDANT_MAX_DIFF 10 // (°C) Temperature difference that will trigger a print abort. +#endif // Below this temperature the heater will be switched off // because it probably indicates a broken thermistor wire. @@ -466,6 +551,7 @@ #define HEATER_6_MINTEMP 5 #define HEATER_7_MINTEMP 5 #define BED_MINTEMP 5 +#define CHAMBER_MINTEMP 5 // Above this temperature the heater will be switched off. // This can protect components from overheating, but NOT from shorts and failures. @@ -479,6 +565,17 @@ #define HEATER_6_MAXTEMP 275 #define HEATER_7_MAXTEMP 275 #define BED_MAXTEMP 150 +#define CHAMBER_MAXTEMP 60 + +/** + * Thermal Overshoot + * During heatup (and printing) the temperature can often "overshoot" the target by many degrees + * (especially before PID tuning). Setting the target temperature too close to MAXTEMP guarantees + * a MAXTEMP shutdown! Use these values to forbid temperatures being set too close to MAXTEMP. + */ +#define HOTEND_OVERSHOOT 15 // (°C) Forbid temperatures over MAXTEMP - OVERSHOOT +#define BED_OVERSHOOT 10 // (°C) Forbid temperatures over MAXTEMP - OVERSHOOT +#define COOLER_OVERSHOOT 2 // (°C) Forbid temperatures closer than OVERSHOOT //=========================================================================== //============================= PID Settings ================================ @@ -552,7 +649,51 @@ // FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles. #endif // PIDTEMPBED -#if EITHER(PIDTEMP, PIDTEMPBED) +//=========================================================================== +//==================== PID > Chamber Temperature Control ==================== +//=========================================================================== + +/** + * PID Chamber Heating + * + * If this option is enabled set PID constants below. + * If this option is disabled, bang-bang will be used and CHAMBER_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 200W + * heater. If your configuration is significantly different than this and you don't understand + * the issues involved, don't use chamber PID until someone else verifies that your hardware works. + */ +//#define PIDTEMPCHAMBER +//#define CHAMBER_LIMIT_SWITCHING + +/** + * Max Chamber Power + * Applies to all forms of chamber control (PID, bang-bang, and bang-bang with hysteresis). + * When set to any value below 255, enables a form of PWM to the chamber heater that acts like a divider + * so don't use it unless you are OK with PWM on your heater. (See the comment on enabling PIDTEMPCHAMBER) + */ +#define MAX_CHAMBER_POWER 255 // limits duty cycle to chamber heater; 255=full current + +#if ENABLED(PIDTEMPCHAMBER) + #define MIN_CHAMBER_POWER 0 + //#define PID_CHAMBER_DEBUG // Sends debug data to the serial port. + + // Lasko "MyHeat Personal Heater" (200w) modified with a Fotek SSR-10DA to control only the heating element + // and placed inside the small Creality printer enclosure tent. + // + #define DEFAULT_chamberKp 37.04 + #define DEFAULT_chamberKi 1.40 + #define DEFAULT_chamberKd 655.17 + // M309 P37.04 I1.04 D655.17 + + // FIND YOUR OWN: "M303 E-2 C8 S50" to run autotune on the chamber at 50 degreesC for 8 cycles. +#endif // PIDTEMPCHAMBER + +#if ANY(PIDTEMP, PIDTEMPBED, PIDTEMPCHAMBER) //#define PID_DEBUG // Sends debug data to the serial port. Use 'M303 D' to toggle activation. //#define PID_OPENLOOP // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX //#define SLOW_PWM_HEATERS // PWM with very low frequency (roughly 0.125Hz=8s) and minimum state time of approximately 1s useful for heaters driven by a relay @@ -599,6 +740,7 @@ #define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders #define THERMAL_PROTECTION_BED // Enable thermal protection for the heated bed #define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber +#define THERMAL_PROTECTION_COOLER // Enable thermal protection for the laser cooling //=========================================================================== //============================= Mechanical Settings ========================= @@ -628,9 +770,15 @@ #define USE_XMIN_PLUG #define USE_YMIN_PLUG #define USE_ZMIN_PLUG +//#define USE_IMIN_PLUG +//#define USE_JMIN_PLUG +//#define USE_KMIN_PLUG //#define USE_XMAX_PLUG //#define USE_YMAX_PLUG //#define USE_ZMAX_PLUG +//#define USE_IMAX_PLUG +//#define USE_JMAX_PLUG +//#define USE_KMAX_PLUG // Enable pullup for all endstops to prevent a floating state #define ENDSTOPPULLUPS @@ -639,9 +787,15 @@ //#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_ZMAX + //#define ENDSTOPPULLUP_IMAX + //#define ENDSTOPPULLUP_JMAX + //#define ENDSTOPPULLUP_KMAX //#define ENDSTOPPULLUP_XMIN //#define ENDSTOPPULLUP_YMIN //#define ENDSTOPPULLUP_ZMIN + //#define ENDSTOPPULLUP_IMIN + //#define ENDSTOPPULLUP_JMIN + //#define ENDSTOPPULLUP_KMIN //#define ENDSTOPPULLUP_ZMIN_PROBE #endif @@ -652,9 +806,15 @@ //#define ENDSTOPPULLDOWN_XMAX //#define ENDSTOPPULLDOWN_YMAX //#define ENDSTOPPULLDOWN_ZMAX + //#define ENDSTOPPULLDOWN_IMAX + //#define ENDSTOPPULLDOWN_JMAX + //#define ENDSTOPPULLDOWN_KMAX //#define ENDSTOPPULLDOWN_XMIN //#define ENDSTOPPULLDOWN_YMIN //#define ENDSTOPPULLDOWN_ZMIN + //#define ENDSTOPPULLDOWN_IMIN + //#define ENDSTOPPULLDOWN_JMIN + //#define ENDSTOPPULLDOWN_KMIN //#define ENDSTOPPULLDOWN_ZMIN_PROBE #endif @@ -662,9 +822,15 @@ #define X_MIN_ENDSTOP_INVERTING true // Set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING true // Set to true to invert the logic of the endstop. #define Z_MIN_ENDSTOP_INVERTING true // Set to true to invert the logic of the endstop. +#define I_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. +#define J_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. +#define K_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. #define X_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. #define Y_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. #define Z_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. +#define I_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. +#define J_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. +#define K_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. #define Z_MIN_PROBE_ENDSTOP_INVERTING false // Set to true to invert the logic of the probe. /** @@ -693,6 +859,9 @@ #define Z2_DRIVER_TYPE TMC2100 //#define Z3_DRIVER_TYPE A4988 //#define Z4_DRIVER_TYPE A4988 +//#define I_DRIVER_TYPE A4988 +//#define J_DRIVER_TYPE A4988 +//#define K_DRIVER_TYPE A4988 #define E0_DRIVER_TYPE TMC2100 //#define E1_DRIVER_TYPE A4988 //#define E2_DRIVER_TYPE A4988 @@ -746,7 +915,7 @@ /** * Default Axis Steps Per Unit (steps/mm) * Override with M92 - * X, Y, Z, E0 [, E1[, E2...]] + * X, Y, Z [, I [, J [, K]]], E0 [, E1[, E2...]] */ #define DEFAULT_AXIS_STEPS_PER_UNIT { 80.121, 80.121, 399.778, 414.26 } // default config was E445, calibrated via https://teachingtechyt.github.io/calibration.html#esteps @@ -754,7 +923,7 @@ /** * Default Max Feed Rate (mm/s) * Override with M203 - * X, Y, Z, E0 [, E1[, E2...]] + * X, Y, Z [, I [, J [, K]]], E0 [, E1[, E2...]] */ #define DEFAULT_MAX_FEEDRATE { 300, 300, 50, 40 } @@ -767,7 +936,7 @@ * Default Max Acceleration (change/s) change = mm/s * (Maximum start speed for accelerated moves) * Override with M201 - * X, Y, Z, E0 [, E1[, E2...]] + * X, Y, Z [, I [, J [, K]]], E0 [, E1[, E2...]] */ #define DEFAULT_MAX_ACCELERATION { 2000, 2000, 100, 10000 } @@ -801,6 +970,9 @@ #define DEFAULT_XJERK 8.0 #define DEFAULT_YJERK 8.0 #define DEFAULT_ZJERK 0.3 + //#define DEFAULT_IJERK 0.3 + //#define DEFAULT_JJERK 0.3 + //#define DEFAULT_KJERK 0.3 //#define TRAVEL_EXTRA_XYJERK 0.0 // Additional jerk allowance for all travel moves @@ -884,7 +1056,6 @@ * or (with LCD_BED_LEVELING) the LCD controller. */ //#define PROBE_MANUALLY -//#define MANUAL_PROBE_START_Z 0.2 /** * A Fix-Mounted Probe either doesn't deploy or needs manual deployment. @@ -909,11 +1080,6 @@ */ //#define BLTOUCH -/** - * Pressure sensor with a BLTouch-like interface - */ -//#define CREALITY_TOUCH - /** * Touch-MI Probe by hotends.fr * @@ -946,7 +1112,7 @@ #endif // Duet Smart Effector (for delta printers) - https://bit.ly/2ul5U7J -// When the pin is defined you can use M672 to set/reset the probe sensivity. +// When the pin is defined you can use M672 to set/reset the probe sensitivity. //#define DUET_SMART_EFFECTOR #if ENABLED(DUET_SMART_EFFECTOR) #define SMART_EFFECTOR_MOD_PIN -1 // Connect a GPIO pin to the Smart Effector MOD pin @@ -967,10 +1133,20 @@ /** * Nozzle-to-Probe offsets { X, Y, Z } * - * - Use a caliper or ruler to measure the distance from the tip of + * X and Y offset + * Use a caliper or ruler to measure the distance from the tip of * the Nozzle to the center-point of the Probe in the X and Y axes. + * + * Z offset * - For the Z offset use your best known value and adjust at runtime. - * - Probe Offsets can be tuned at runtime with 'M851', LCD menus, babystepping, etc. + * - Common probes trigger below the nozzle and have negative values for Z offset. + * - Probes triggering above the nozzle height are uncommon but do exist. When using + * probes such as this, carefully set Z_CLEARANCE_DEPLOY_PROBE and Z_CLEARANCE_BETWEEN_PROBES + * to avoid collisions during probing. + * + * 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. * * Assuming the typical work area orientation: * - Probe to RIGHT of the Nozzle has a Positive X offset @@ -1001,13 +1177,40 @@ #define PROBING_MARGIN 10 // X and Y axis travel speed (mm/min) between probes -#define XY_PROBE_SPEED (133*60) +#define XY_PROBE_FEEDRATE (133*60) // Feedrate (mm/min) for the first approach when double-probing (MULTIPLE_PROBING == 2) -#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z +#define Z_PROBE_FEEDRATE_FAST (4*60) // Feedrate (mm/min) for the "accurate" probe of each point -#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2) +#define Z_PROBE_FEEDRATE_SLOW (Z_PROBE_FEEDRATE_FAST / 2) + +/** + * Probe Activation Switch + * A switch indicating proper deployment, or an optical + * switch triggered when the carriage is near the bed. + */ +//#define PROBE_ACTIVATION_SWITCH +#if ENABLED(PROBE_ACTIVATION_SWITCH) + #define PROBE_ACTIVATION_SWITCH_STATE LOW // State indicating probe is active + //#define PROBE_ACTIVATION_SWITCH_PIN PC6 // Override default pin +#endif + +/** + * Tare Probe (determine zero-point) prior to each probe. + * Useful for a strain gauge or piezo sensor that needs to factor out + * elements such as cables pulling on the carriage. + */ +//#define PROBE_TARE +#if ENABLED(PROBE_TARE) + #define PROBE_TARE_TIME 200 // (ms) Time to hold tare pin + #define PROBE_TARE_DELAY 200 // (ms) Delay after tare before + #define PROBE_TARE_STATE HIGH // State to write pin for tare + //#define PROBE_TARE_PIN PA5 // Override default pin + #if ENABLED(PROBE_ACTIVATION_SWITCH) + //#define PROBE_TARE_ONLY_WHILE_INACTIVE // Fail to tare/probe if PROBE_ACTIVATION_SWITCH is active + #endif +#endif /** * Multiple Probing @@ -1065,23 +1268,38 @@ //#define PROBING_HEATERS_OFF // Turn heaters off when probing #if ENABLED(PROBING_HEATERS_OFF) //#define WAIT_FOR_BED_HEATER // Wait for bed to heat back up between probes (to improve accuracy) + //#define WAIT_FOR_HOTEND // Wait for hotend to heat back up between probes (to improve accuracy & prevent cold extrude) #endif //#define PROBING_FANS_OFF // Turn fans off when probing -//#define PROBING_STEPPERS_OFF // Turn steppers off (unless needed to hold position) when probing +//#define PROBING_ESTEPPERS_OFF // Turn all extruder steppers off when probing +//#define PROBING_STEPPERS_OFF // Turn all steppers off (unless needed to hold position) when probing (including extruders) //#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors +// Require minimum nozzle and/or bed temperature for probing +//#define PREHEAT_BEFORE_PROBING +#if ENABLED(PREHEAT_BEFORE_PROBING) + #define PROBING_NOZZLE_TEMP 120 // (°C) Only applies to E0 at this time + #define PROBING_BED_TEMP 50 +#endif + // For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1 // :{ 0:'Low', 1:'High' } #define X_ENABLE_ON 0 #define Y_ENABLE_ON 0 #define Z_ENABLE_ON 0 #define E_ENABLE_ON 0 // For all extruders +//#define I_ENABLE_ON 0 +//#define J_ENABLE_ON 0 +//#define K_ENABLE_ON 0 // 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 // Turn off the display blinking that warns about possible accuracy reduction //#define DISABLE_REDUCED_ACCURACY_WARNING @@ -1097,6 +1315,9 @@ #define INVERT_X_DIR false #define INVERT_Y_DIR false #define INVERT_Z_DIR true +//#define INVERT_I_DIR false +//#define INVERT_J_DIR false +//#define INVERT_K_DIR false // @section extruder @@ -1112,9 +1333,15 @@ // @section homing -//#define NO_MOTION_BEFORE_HOMING // Inhibit movement until all axes have been homed +//#define NO_MOTION_BEFORE_HOMING // Inhibit movement until all axes have been homed. Also enable HOME_AFTER_DEACTIVATE for extra safety. +//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated. Also enable NO_MOTION_BEFORE_HOMING for extra safety. -//#define UNKNOWN_Z_NO_RAISE // Don't raise Z (lower the bed) if Z is "unknown." For beds that fall when Z is powered off. +/** + * Set Z_IDLE_HEIGHT if the Z-Axis moves on its own when steppers are disabled. + * - Use a low value (i.e., Z_MIN_POS) if the nozzle falls down to the bed. + * - Use a large value (i.e., Z_MAX_POS) if the bed falls down, away from the nozzle. + */ +//#define Z_IDLE_HEIGHT Z_HOME_POS //#define Z_HOMING_HEIGHT 4 // (mm) Minimal Z height before homing (G28) for Z clearance above the bed, clamps, ... // Be sure to have this much clearance over your Z_MAX_POS to prevent grinding. @@ -1126,10 +1353,13 @@ #define X_HOME_DIR -1 #define Y_HOME_DIR -1 #define Z_HOME_DIR -1 +//#define I_HOME_DIR -1 +//#define J_HOME_DIR -1 +//#define K_HOME_DIR -1 // @section machine -// The size of the print bed +// The size of the printable area #define X_BED_SIZE 220 #define Y_BED_SIZE 230 @@ -1140,6 +1370,12 @@ #define X_MAX_POS X_BED_SIZE #define Y_MAX_POS Y_BED_SIZE #define Z_MAX_POS 250 +//#define I_MIN_POS 0 +//#define I_MAX_POS 50 +//#define J_MIN_POS 0 +//#define J_MAX_POS 50 +//#define K_MIN_POS 0 +//#define K_MAX_POS 50 /** * Software Endstops @@ -1156,6 +1392,9 @@ #define MIN_SOFTWARE_ENDSTOP_X #define MIN_SOFTWARE_ENDSTOP_Y #define MIN_SOFTWARE_ENDSTOP_Z + #define MIN_SOFTWARE_ENDSTOP_I + #define MIN_SOFTWARE_ENDSTOP_J + #define MIN_SOFTWARE_ENDSTOP_K #endif // Max software endstops constrain movement within maximum coordinate bounds @@ -1164,6 +1403,9 @@ #define MAX_SOFTWARE_ENDSTOP_X #define MAX_SOFTWARE_ENDSTOP_Y #define MAX_SOFTWARE_ENDSTOP_Z + #define MAX_SOFTWARE_ENDSTOP_I + #define MAX_SOFTWARE_ENDSTOP_J + #define MAX_SOFTWARE_ENDSTOP_K #endif #if EITHER(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS) @@ -1189,28 +1431,47 @@ #define NUM_RUNOUT_SENSORS 1 // Number of sensors, up to one per extruder. Define a FIL_RUNOUT#_PIN for each. #define FIL_RUNOUT_STATE LOW // Pin state indicating that filament is NOT present. - #define FIL_RUNOUT_PULL // Use internal pullup / pulldown for filament runout pins. + #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins. + //#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins. + //#define WATCH_ALL_RUNOUT_SENSORS // Execute runout script on any triggering sensor, not only for the active extruder. + // This is automatically enabled for MIXING_EXTRUDERs. // Override individually if the runout sensors vary //#define FIL_RUNOUT1_STATE LOW - //#define FIL_RUNOUT1_PULL + //#define FIL_RUNOUT1_PULLUP + //#define FIL_RUNOUT1_PULLDOWN + //#define FIL_RUNOUT2_STATE LOW - //#define FIL_RUNOUT2_PULL + //#define FIL_RUNOUT2_PULLUP + //#define FIL_RUNOUT2_PULLDOWN + //#define FIL_RUNOUT3_STATE LOW - //#define FIL_RUNOUT3_PULL + //#define FIL_RUNOUT3_PULLUP + //#define FIL_RUNOUT3_PULLDOWN + //#define FIL_RUNOUT4_STATE LOW - //#define FIL_RUNOUT4_PULL + //#define FIL_RUNOUT4_PULLUP + //#define FIL_RUNOUT4_PULLDOWN + //#define FIL_RUNOUT5_STATE LOW - //#define FIL_RUNOUT5_PULL + //#define FIL_RUNOUT5_PULLUP + //#define FIL_RUNOUT5_PULLDOWN + //#define FIL_RUNOUT6_STATE LOW - //#define FIL_RUNOUT6_PULL + //#define FIL_RUNOUT6_PULLUP + //#define FIL_RUNOUT6_PULLDOWN + //#define FIL_RUNOUT7_STATE LOW - //#define FIL_RUNOUT7_PULL + //#define FIL_RUNOUT7_PULLUP + //#define FIL_RUNOUT7_PULLDOWN + //#define FIL_RUNOUT8_STATE LOW - //#define FIL_RUNOUT8_PULL + //#define FIL_RUNOUT8_PULLUP + //#define FIL_RUNOUT8_PULLDOWN - // Set one or more commands to execute on filament runout. - // (After 'M412 H' Marlin will ask the host to handle the process.) + // Commands to execute on filament runout. + // With multiple runout sensors use the %c placeholder for the current tool in commands (e.g., "M600 T%c") + // NOTE: After 'M412 H1' the host handles filament runout and this script does not apply. #define FILAMENT_RUNOUT_SCRIPT "M600" // After a runout is detected, continue printing this length of filament @@ -1271,10 +1532,21 @@ //#define MESH_BED_LEVELING /** - * Normally G28 leaves leveling disabled on completion. Enable - * this option to have G28 restore the prior leveling state. + * Normally G28 leaves leveling disabled on completion. Enable one of + * these options to restore the prior leveling state or to always enable + * leveling immediately after G28. */ //#define RESTORE_LEVELING_AFTER_G28 +//#define ENABLE_LEVELING_AFTER_G28 + +/** + * Auto-leveling needs preheating + */ +//#define PREHEAT_BEFORE_LEVELING +#if ENABLED(PREHEAT_BEFORE_LEVELING) + #define LEVELING_NOZZLE_TEMP 120 // (°C) Only applies to E0 at this time + #define LEVELING_BED_TEMP 50 +#endif /** * Enable detailed logging of G28, G29, M48, etc. @@ -1283,11 +1555,19 @@ */ //#define DEBUG_LEVELING_FEATURE +#if ANY(MESH_BED_LEVELING, AUTO_BED_LEVELING_UBL, PROBE_MANUALLY) + // Set a height for the start of manual adjustment + #define MANUAL_PROBE_START_Z 0.2 // (mm) Comment out to use the last-measured height +#endif + #if ANY(MESH_BED_LEVELING, AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_UBL) // Gradually reduce leveling correction until a set height is reached, // at which point movement will be level to the machine's XY plane. // The height can be set with M420 Z #define ENABLE_LEVELING_FADE_HEIGHT + #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) + #define DEFAULT_LEVELING_FADE_HEIGHT 10.0 // (mm) Default fade height. + #endif // For Cartesian machines, instead of dividing moves on mesh boundaries, // split up moves into short segments like a Delta. This follows the @@ -1301,10 +1581,11 @@ //#define G26_MESH_VALIDATION #if ENABLED(G26_MESH_VALIDATION) #define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle. - #define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool. - #define MESH_TEST_HOTEND_TEMP 205 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool. - #define MESH_TEST_BED_TEMP 60 // (°C) Default bed temperature for the G26 Mesh Validation Tool. - #define G26_XY_FEEDRATE 20 // (mm/s) Feedrate for XY Moves for the G26 Mesh Validation Tool. + #define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for G26. + #define MESH_TEST_HOTEND_TEMP 205 // (°C) Default nozzle temperature for G26. + #define MESH_TEST_BED_TEMP 60 // (°C) Default bed temperature for G26. + #define G26_XY_FEEDRATE 20 // (mm/s) Feedrate for G26 XY moves. + #define G26_XY_FEEDRATE_TRAVEL 100 // (mm/s) Feedrate for G26 XY travel moves. #define G26_RETRACT_MULTIPLIER 1.0 // G26 Q (retraction) used by default between mesh test elements. #endif @@ -1349,12 +1630,16 @@ #define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited. #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X + //#define UBL_HILBERT_CURVE // Use Hilbert distribution for less travel when probing multiple points + #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle #define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500 //#define UBL_Z_RAISE_WHEN_OFF_MESH 2.5 // When the nozzle is off the mesh, this value is used // as the Z-Height correction value. + //#define UBL_MESH_WIZARD // Run several commands in a row to get a complete mesh + #elif ENABLED(MESH_BED_LEVELING) //=========================================================================== @@ -1389,6 +1674,31 @@ #define LEVEL_CORNERS_HEIGHT 0.0 // (mm) Z height of nozzle at leveling points #define LEVEL_CORNERS_Z_HOP 4.0 // (mm) Z height of nozzle between leveling points //#define LEVEL_CENTER_TOO // Move to the center after the last corner + //#define LEVEL_CORNERS_USE_PROBE + #if ENABLED(LEVEL_CORNERS_USE_PROBE) + #define LEVEL_CORNERS_PROBE_TOLERANCE 0.1 + #define LEVEL_CORNERS_VERIFY_RAISED // After adjustment triggers the probe, re-probe to verify + //#define LEVEL_CORNERS_AUDIO_FEEDBACK + #endif + + /** + * Corner Leveling Order + * + * Set 2 or 4 points. When 2 points are given, the 3rd is the center of the opposite edge. + * + * LF Left-Front RF Right-Front + * LB Left-Back RB Right-Back + * + * Examples: + * + * Default {LF,RB,LB,RF} {LF,RF} {LB,LF} + * LB --------- RB LB --------- RB LB --------- RB LB --------- RB + * | 4 3 | | 3 2 | | <3> | | 1 | + * | | | | | | | <3>| + * | 1 2 | | 1 4 | | 1 2 | | 2 | + * LF --------- RF LF --------- RF LF --------- RF LF --------- RF + */ + #define LEVEL_CORNERS_LEVELING_ORDER { LF, RF, RB, LB } #endif /** @@ -1407,16 +1717,17 @@ //#define MANUAL_X_HOME_POS 0 //#define MANUAL_Y_HOME_POS 0 //#define MANUAL_Z_HOME_POS 0 +//#define MANUAL_I_HOME_POS 0 +//#define MANUAL_J_HOME_POS 0 +//#define MANUAL_K_HOME_POS 0 -// Use "Z Safe Homing" to avoid homing with a Z probe outside the bed area. -// -// With this feature enabled: -// -// - Allow Z homing only after X and Y homing AND stepper drivers still enabled. -// - If stepper drivers time out, it will need X and Y homing again before Z homing. -// - Move the Z probe (or nozzle) to a defined XY point before Z Homing. -// - Prevent Z homing when the Z probe is outside bed area. -// +/** + * Use "Z Safe Homing" to avoid homing with a Z probe outside the bed area. + * + * - Moves the Z probe (or nozzle) to a defined XY point before Z homing. + * - Allows Z homing only when XY positions are known and trusted. + * - If stepper drivers sleep, XY homing may be required again before Z homing. + */ //#define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) @@ -1425,8 +1736,7 @@ #endif // Homing speeds (mm/min) -#define HOMING_FEEDRATE_XY (80*60) -#define HOMING_FEEDRATE_Z (20*60) +#define HOMING_FEEDRATE_MM_M { (50*60), (50*60), (4*60) } // had XY 80*60, Z 20*60 // Validate that endstops are triggered on homing moves #define VALIDATE_HOMING_ENDSTOPS @@ -1533,15 +1843,19 @@ // @section temperature -// Preheat Constants +// +// Preheat Constants - Up to 5 are supported without changes +// #define PREHEAT_1_LABEL "PLA" #define PREHEAT_1_TEMP_HOTEND 180 #define PREHEAT_1_TEMP_BED 70 +#define PREHEAT_1_TEMP_CHAMBER 35 #define PREHEAT_1_FAN_SPEED 0 // Value from 0 to 255 #define PREHEAT_2_LABEL "ABS" #define PREHEAT_2_TEMP_HOTEND 240 #define PREHEAT_2_TEMP_BED 110 +#define PREHEAT_2_TEMP_CHAMBER 35 #define PREHEAT_2_FAN_SPEED 0 // Value from 0 to 255 /** @@ -1634,6 +1948,10 @@ // For a purge/clean station mounted on the X axis //#define NOZZLE_CLEAN_NO_Y + // Require a minimum hotend temperature for cleaning + #define NOZZLE_CLEAN_MIN_TEMP 170 + //#define NOZZLE_CLEAN_HEATUP // Heat up the nozzle instead of skipping wipe + // Explicit wipe G-code script applies to a G12 with no arguments. //#define WIPE_SEQUENCE_COMMANDS "G1 X-17 Y25 Z10 F4000\nG1 Z1\nM114\nG1 X-17 Y25\nG1 X-17 Y95\nG1 X-17 Y25\nG1 X-17 Y95\nG1 X-17 Y25\nG1 X-17 Y95\nG1 X-17 Y25\nG1 X-17 Y95\nG1 X-17 Y25\nG1 X-17 Y95\nG1 X-17 Y25\nG1 X-17 Y95\nG1 Z15\nM400\nG0 X-10.0 Y-9.0" @@ -1642,11 +1960,20 @@ /** * Print Job Timer * - * Automatically start and stop the print job timer on M104/M109/M190. + * Automatically start and stop the print job timer on M104/M109/M140/M190/M141/M191. + * The print job timer will only be stopped if the bed/chamber target temp is + * below BED_MINTEMP/CHAMBER_MINTEMP. * - * M104 (hotend, no wait) - high temp = none, low temp = stop timer - * M109 (hotend, wait) - high temp = start timer, low temp = stop timer - * M190 (bed, wait) - high temp = start timer, low temp = none + * M104 (hotend, no wait) - high temp = none, low temp = stop timer + * M109 (hotend, wait) - high temp = start timer, low temp = stop timer + * M140 (bed, no wait) - high temp = none, low temp = stop timer + * M190 (bed, wait) - high temp = start timer, low temp = none + * M141 (chamber, no wait) - high temp = none, low temp = stop timer + * M191 (chamber, wait) - high temp = start timer, low temp = none + * + * For M104/M109, high temp is anything over EXTRUDE_MINTEMP / 2. + * For M140/M190, high temp is anything over BED_MINTEMP. + * For M141/M191, high temp is anything over CHAMBER_MINTEMP. * * The timer can also be controlled with the following commands: * @@ -1669,6 +1996,9 @@ * View the current statistics with M78. */ //#define PRINTCOUNTER +#if ENABLED(PRINTCOUNTER) + #define PRINTCOUNTER_SAVE_INTERVAL 60 // (minutes) EEPROM save interval during print +#endif /** * Password @@ -1713,9 +2043,9 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cz, da, de, el, el_gr, es, eu, fi, fr, gl, hr, hu, it, - * jp_kana, ko_KR, nl, pl, pt, pt_br, ro, ru, sk, tr, uk, vi, zh_CN, zh_TW, test + * jp_kana, ko_KR, nl, pl, pt, pt_br, ro, ru, sk, sv, tr, uk, vi, zh_CN, zh_TW * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cz':'Czech', 'da':'Danish', 'de':'German', 'el':'Greek', 'el_gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'hu':'Hungarian', 'it':'Italian', 'jp_kana':'Japanese', 'ko_KR':'Korean (South Korea)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt_br':'Portuguese (Brazilian)', 'ro':'Romanian', 'ru':'Russian', 'sk':'Slovak', 'tr':'Turkish', 'uk':'Ukrainian', 'vi':'Vietnamese', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Traditional)', 'test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cz':'Czech', 'da':'Danish', 'de':'German', 'el':'Greek', 'el_gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'hu':'Hungarian', 'it':'Italian', 'jp_kana':'Japanese', 'ko_KR':'Korean (South Korea)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt_br':'Portuguese (Brazilian)', 'ro':'Romanian', 'ru':'Russian', 'sk':'Slovak', 'sv':'Swedish', 'tr':'Turkish', 'uk':'Ukrainian', 'vi':'Vietnamese', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Traditional)' } */ #define LCD_LANGUAGE en @@ -1758,16 +2088,6 @@ */ //#define SDSUPPORT -/** - * SD CARD: SPI SPEED - * - * Enable one of the following items for a slower SPI transfer speed. - * This may be required to resolve "volume init" errors. - */ -//#define SPI_SPEED SPI_HALF_SPEED -//#define SPI_SPEED SPI_QUARTER_SPEED -//#define SPI_SPEED SPI_EIGHTH_SPEED - /** * SD CARD: ENABLE CRC * @@ -1869,6 +2189,14 @@ // //#define REPRAP_DISCOUNT_SMART_CONTROLLER +// +// GT2560 (YHCB2004) LCD Display +// +// Requires Testato, Koepel softwarewire library and +// Andriy Golovnya's LiquidCrystal_AIP31068 library. +// +//#define YHCB2004 + // // Original RADDS LCD Display+Encoder+SDCardReader // http://doku.radds.org/dokumentation/lcd-display/ @@ -2019,6 +2347,11 @@ // //#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER +// +// K.3D Full Graphic Smart Controller +// +//#define K3D_FULL_GRAPHIC_SMART_CONTROLLER + // // ReprapWorld Graphical LCD // https://reprapworld.com/?products_details&products_id/1218 @@ -2080,11 +2413,17 @@ // //#define MKS_MINI_12864 +// +// MKS MINI12864 V3 is an alias for FYSETC_MINI_12864_2_1. Type A/B. NeoPixel RGB Backlight. +// +//#define MKS_MINI_12864_V3 + // // MKS LCD12864A/B with graphic controller and SD support. Follows MKS_MINI_12864 pinout. // https://www.aliexpress.com/item/33018110072.html // -//#define MKS_LCD12864 +//#define MKS_LCD12864A +//#define MKS_LCD12864B // // FYSETC variant of the MINI12864 graphic controller with SD support @@ -2156,7 +2495,7 @@ //#define OLED_PANEL_TINYBOY2 // -// MKS OLED 1.3" 128×64 FULL GRAPHICS CONTROLLER +// MKS OLED 1.3" 128×64 Full Graphics Controller // https://reprap.org/wiki/MKS_12864OLED // // Tiny, but very sharp OLED display @@ -2165,7 +2504,7 @@ //#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller // -// Zonestar OLED 128×64 FULL GRAPHICS CONTROLLER +// Zonestar OLED 128×64 Full Graphics Controller // //#define ZONESTAR_12864LCD // Graphical (DOGM) with ST7920 controller //#define ZONESTAR_12864OLED // 1.3" OLED with SH1106 controller (default) @@ -2182,10 +2521,15 @@ //#define OVERLORD_OLED // -// FYSETC OLED 2.42" 128×64 FULL GRAPHICS CONTROLLER with WS2812 RGB +// FYSETC OLED 2.42" 128×64 Full Graphics Controller with WS2812 RGB // Where to find : https://www.aliexpress.com/item/4000345255731.html //#define FYSETC_242_OLED_12864 // Uses the SSD1309 controller +// +// K.3D SSD1309 OLED 2.42" 128×64 Full Graphics Controller +// +//#define K3D_242_OLED_CONTROLLER // Software SPI + //============================================================================= //========================== Extensible UI Displays =========================== //============================================================================= @@ -2194,10 +2538,37 @@ // DGUS Touch Display with DWIN OS. (Choose one.) // ORIGIN : https://www.aliexpress.com/item/32993409517.html // FYSETC : https://www.aliexpress.com/item/32961471929.html +// MKS : https://www.aliexpress.com/item/1005002008179262.html +// +// 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. +// +// ORIGIN (Marlin DWIN_SET) +// - Download https://github.com/coldtobi/Marlin_DGUS_Resources +// - Copy the downloaded DWIN_SET folder to the SD card. +// +// FYSETC (Supplier default) +// - Download https://github.com/FYSETC/FYSTLCD-2.0 +// - Copy the downloaded SCREEN folder to the SD card. +// +// HIPRECY (Supplier default) +// - Download https://github.com/HiPrecy/Touch-Lcd-LEO +// - Copy the downloaded DWIN_SET folder to the SD card. +// +// MKS (MKS-H43) (Supplier default) +// - Download https://github.com/makerbase-mks/MKS-H43 +// - Copy the downloaded DWIN_SET folder to the SD card. // //#define DGUS_LCD_UI_ORIGIN //#define DGUS_LCD_UI_FYSETC //#define DGUS_LCD_UI_HIPRECY +//#define DGUS_LCD_UI_MKS +#if ENABLED(DGUS_LCD_UI_MKS) + #define USE_MKS_GREEN_UI +#endif // // CR-6 OEM touch screen. A DWIN display with touch. @@ -2228,6 +2599,14 @@ //#define ANYCUBIC_LCD_DEBUG #endif +// +// 320x240 Nextion 2.8" serial TFT Resistive Touch Screen NX3224T028 +// +//#define NEXTION_TFT +#if ENABLED(NEXTION_TFT) + #define LCD_SERIAL_PORT 1 // Default is 1 for Nextion +#endif + // // Third-party or vendor-customized controller interfaces. // Sources should be installed in 'src/lcd/extui'. @@ -2303,6 +2682,21 @@ // //#define LONGER_LK_TFT28 +// +// 320x240, 2.8", FSMC Stock Display from ET4 +// +//#define ANET_ET4_TFT28 + +// +// 480x320, 3.5", FSMC Stock Display from ET5 +// +//#define ANET_ET5_TFT35 + +// +// 1024x600, 7", RGB Stock Display from BIQU-BX +// +//#define BIQU_BX_TFT70 + // // Generic TFT with detailed options // @@ -2335,6 +2729,10 @@ //#define TFT_COLOR_UI //#define TFT_LVGL_UI +#if ENABLED(TFT_LVGL_UI) + //#define MKS_WIFI_MODULE // MKS WiFi module +#endif + /** * TFT Rotation. Set to one of the following values: * @@ -2355,7 +2753,7 @@ //#define DWIN_CREALITY_LCD // -// ADS7843/XPT2046 ADC Touchscreen such as ILI9341 2.8 +// Touch Screen Settings // //#define TOUCH_SCREEN #if ENABLED(TOUCH_SCREEN) @@ -2364,10 +2762,15 @@ #define TOUCH_SCREEN_CALIBRATION - //#define XPT2046_X_CALIBRATION 12316 - //#define XPT2046_Y_CALIBRATION -8981 - //#define XPT2046_X_OFFSET -43 - //#define XPT2046_Y_OFFSET 257 + //#define TOUCH_CALIBRATION_X 12316 + //#define TOUCH_CALIBRATION_Y -8981 + //#define TOUCH_OFFSET_X -43 + //#define TOUCH_OFFSET_Y 257 + //#define TOUCH_ORIENTATION TOUCH_LANDSCAPE + + #if BOTH(TOUCH_SCREEN_CALIBRATION, EEPROM_SETTINGS) + #define TOUCH_CALIBRATION_AUTO_SAVE // Auto save successful calibration values to EEPROM + #endif #if ENABLED(TFT_COLOR_UI) //#define SINGLE_TOUCH_NAVIGATION @@ -2464,7 +2867,7 @@ //#define NEOPIXEL_LED #if ENABLED(NEOPIXEL_LED) #define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h) - #define NEOPIXEL_PIN 4 // LED driving pin + //#define NEOPIXEL_PIN 4 // LED driving pin //#define NEOPIXEL2_TYPE NEOPIXEL_TYPE //#define NEOPIXEL2_PIN 5 #define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip. (Longest strip when NEOPIXEL2_SEPARATE is disabled.) @@ -2482,9 +2885,11 @@ //#define NEOPIXEL2_INSERIES // Default behavior is NeoPixel 2 in parallel #endif - // Use a single NeoPixel LED for static (background) lighting - //#define NEOPIXEL_BKGD_LED_INDEX 0 // Index of the LED to use - //#define NEOPIXEL_BKGD_COLOR { 255, 255, 255, 0 } // R, G, B, W + // 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_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 748337004e3c..a6ac581cccff 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -30,7 +30,7 @@ * * Basic settings can be found in Configuration.h */ -#define CONFIGURATION_ADV_H_VERSION 020008 +#define CONFIGURATION_ADV_H_VERSION 02000901 //=========================================================================== //============================= Thermal Settings ============================ @@ -113,10 +113,39 @@ #define CHAMBER_BETA 3950 // Beta value #endif -// -// Hephestos 2 24V heated bed upgrade kit. -// https://store.bq.com/en/heated-bed-kit-hephestos2 -// +#if TEMP_SENSOR_COOLER == 1000 + #define COOLER_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define COOLER_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define COOLER_BETA 3950 // Beta value +#endif + +#if TEMP_SENSOR_PROBE == 1000 + #define PROBE_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define PROBE_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define PROBE_BETA 3950 // Beta value +#endif + +#if TEMP_SENSOR_REDUNDANT == 1000 + #define REDUNDANT_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define REDUNDANT_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define REDUNDANT_BETA 3950 // Beta value +#endif + +/** + * Configuration options for MAX Thermocouples (-2, -3, -5). + * FORCE_HW_SPI: Ignore SCK/MOSI/MISO pins and just use the CS pin & default SPI bus. + * MAX31865_WIRES: Set the number of wires for the probe connected to a MAX31865 board, 2-4. Default: 2 + * MAX31865_50HZ: Enable 50Hz filter instead of the default 60Hz. + */ +//#define TEMP_SENSOR_FORCE_HW_SPI +//#define MAX31865_SENSOR_WIRES_0 2 +//#define MAX31865_SENSOR_WIRES_1 2 +//#define MAX31865_50HZ_FILTER + +/** + * Hephestos 2 24V heated bed upgrade kit. + * https://store.bq.com/en/heated-bed-kit-hephestos2 + */ //#define HEPHESTOS2_HEATED_BED_KIT #if ENABLED(HEPHESTOS2_HEATED_BED_KIT) #undef TEMP_SENSOR_BED @@ -137,17 +166,21 @@ // // Heated Chamber options // +#if DISABLED(PIDTEMPCHAMBER) + #define CHAMBER_CHECK_INTERVAL 5000 // (ms) Interval between checks in bang-bang control + #if ENABLED(CHAMBER_LIMIT_SWITCHING) + #define CHAMBER_HYSTERESIS 2 // (°C) Only set the relevant heater state when ABS(T-target) > CHAMBER_HYSTERESIS + #endif +#endif + #if TEMP_SENSOR_CHAMBER - #define CHAMBER_MINTEMP 5 - #define CHAMBER_MAXTEMP 60 - #define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target - //#define CHAMBER_LIMIT_SWITCHING - //#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin + //#define HEATER_CHAMBER_PIN P2_04 // Required heater on/off pin (example: SKR 1.4 Turbo HE1 plug) //#define HEATER_CHAMBER_INVERTING false + //#define FAN1_PIN -1 // Remove the fan signal on pin P2_04 (example: SKR 1.4 Turbo HE1 plug) //#define CHAMBER_FAN // Enable a fan on the chamber #if ENABLED(CHAMBER_FAN) - #define CHAMBER_FAN_MODE 2 // Fan control mode: 0=Static; 1=Linear increase when temp is higher than target; 2=V-shaped curve. + #define CHAMBER_FAN_MODE 2 // Fan control mode: 0=Static; 1=Linear increase when temp is higher than target; 2=V-shaped curve; 3=similar to 1 but fan is always on. #if CHAMBER_FAN_MODE == 0 #define CHAMBER_FAN_BASE 255 // Chamber fan PWM (0-255) #elif CHAMBER_FAN_MODE == 1 @@ -156,6 +189,9 @@ #elif CHAMBER_FAN_MODE == 2 #define CHAMBER_FAN_BASE 128 // Minimum chamber fan PWM (0-255) #define CHAMBER_FAN_FACTOR 25 // PWM increase per °C difference from target + #elif CHAMBER_FAN_MODE == 3 + #define CHAMBER_FAN_BASE 128 // Base chamber fan PWM (0-255) + #define CHAMBER_FAN_FACTOR 25 // PWM increase per °C above target #endif #endif @@ -163,12 +199,45 @@ #if ENABLED(CHAMBER_VENT) #define CHAMBER_VENT_SERVO_NR 1 // Index of the vent servo #define HIGH_EXCESS_HEAT_LIMIT 5 // How much above target temp to consider there is excess heat in the chamber - #define LOW_EXCESS_HEAT_LIMIT 3 + #define LOW_EXCESS_HEAT_LIMIT 3 #define MIN_COOLING_SLOPE_TIME_CHAMBER_VENT 20 #define MIN_COOLING_SLOPE_DEG_CHAMBER_VENT 1.5 #endif #endif +// +// Laser Cooler options +// +#if TEMP_SENSOR_COOLER + #define COOLER_MINTEMP 8 // (°C) + #define COOLER_MAXTEMP 26 // (°C) + #define COOLER_DEFAULT_TEMP 16 // (°C) + #define TEMP_COOLER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target + #define COOLER_PIN 8 // Laser cooler on/off pin used to control power to the cooling element (e.g., TEC, External chiller via relay) + #define COOLER_INVERTING false + #define TEMP_COOLER_PIN 15 // Laser/Cooler temperature sensor pin. ADC is required. + #define COOLER_FAN // Enable a fan on the cooler, Fan# 0,1,2,3 etc. + #define COOLER_FAN_INDEX 0 // FAN number 0, 1, 2 etc. e.g. + #if ENABLED(COOLER_FAN) + #define COOLER_FAN_BASE 100 // Base Cooler fan PWM (0-255); turns on when Cooler temperature is above the target + #define COOLER_FAN_FACTOR 25 // PWM increase per °C above target + #endif +#endif + +// +// Laser Coolant Flow Meter +// +//#define LASER_COOLANT_FLOW_METER +#if ENABLED(LASER_COOLANT_FLOW_METER) + #define FLOWMETER_PIN 20 // Requires an external interrupt-enabled pin (e.g., RAMPS 2,3,18,19,20,21) + #define FLOWMETER_PPL 5880 // (pulses/liter) Flow meter pulses-per-liter on the input pin + #define FLOWMETER_INTERVAL 1000 // (ms) Flow rate calculation interval in milliseconds + #define FLOWMETER_SAFETY // Prevent running the laser without the minimum flow rate set below + #if ENABLED(FLOWMETER_SAFETY) + #define FLOWMETER_MIN_LITERS_PER_MINUTE 1.5 // (liters/min) Minimum flow required when enabled + #endif +#endif + /** * Thermal Protection provides additional protection to your printer from damage * and fire. Marlin always includes safe min and max temperature ranges which @@ -206,7 +275,7 @@ * and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set * below 2. */ - #define WATCH_TEMP_PERIOD 20 // Seconds + #define WATCH_TEMP_PERIOD 20 // Seconds #define WATCH_TEMP_INCREASE 2 // Degrees Celsius #endif @@ -238,6 +307,20 @@ #define WATCH_CHAMBER_TEMP_INCREASE 2 // Degrees Celsius #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 + + /** + * Laser cooling watch settings (M143/M193). + */ + #define WATCH_COOLER_TEMP_PERIOD 60 // Seconds + #define WATCH_COOLER_TEMP_INCREASE 3 // Degrees Celsius +#endif + #if ENABLED(PIDTEMP) // Add an experimental additional term to the heater power, proportional to the extrusion speed. // A well-chosen Kc value should add just enough power to melt the increased material volume. @@ -284,8 +367,8 @@ // 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 - #define PID_FAN_SCALING_AT_MIN_SPEED 6.0 //=PID_FAN_SCALING_LIN_FACTOR*PID_FAN_SCALING_MIN_SPEED+DEFAULT_Kf - #define PID_FAN_SCALING_MIN_SPEED 10.0 // Minimum fan speed at which to enable PID_FAN_SCALING + #define PID_FAN_SCALING_AT_MIN_SPEED 6.0 //=PID_FAN_SCALING_LIN_FACTOR*PID_FAN_SCALING_MIN_SPEED+DEFAULT_Kf + #define PID_FAN_SCALING_MIN_SPEED 10.0 // Minimum fan speed at which to enable PID_FAN_SCALING #define DEFAULT_Kf (255.0*PID_FAN_SCALING_AT_MIN_SPEED-PID_FAN_SCALING_AT_FULL_SPEED*PID_FAN_SCALING_MIN_SPEED)/(255.0-PID_FAN_SCALING_MIN_SPEED) #define PID_FAN_SCALING_LIN_FACTOR (PID_FAN_SCALING_AT_FULL_SPEED-DEFAULT_Kf)/255.0 @@ -331,7 +414,7 @@ * High Temperature Thermistor Support * * Thermistors able to support high temperature tend to have a hard time getting - * good readings at room and lower temperatures. This means HEATER_X_RAW_LO_TEMP + * good readings at room and lower temperatures. This means TEMP_SENSOR_X_RAW_LO_TEMP * will probably be caught when the heating element first turns on during the * preheating process, which will trigger a min_temp_error as a safety measure * and force stop everything. @@ -462,6 +545,11 @@ //#define USE_OCR2A_AS_TOP #endif +/** + * Use one of the PWM fans as a redundant part-cooling fan + */ +//#define REDUNDANT_PART_COOLING_FAN 2 // Index of the fan to sync with FAN 0. + // @section extruder /** @@ -485,11 +573,15 @@ #define E6_AUTO_FAN_PIN -1 #define E7_AUTO_FAN_PIN -1 #define CHAMBER_AUTO_FAN_PIN -1 +#define COOLER_AUTO_FAN_PIN -1 +#define COOLER_FAN_PIN -1 #define EXTRUDER_AUTO_FAN_TEMPERATURE 50 #define EXTRUDER_AUTO_FAN_SPEED 255 // 255 == full speed #define CHAMBER_AUTO_FAN_TEMPERATURE 30 #define CHAMBER_AUTO_FAN_SPEED 255 +#define COOLER_AUTO_FAN_TEMPERATURE 18 +#define COOLER_AUTO_FAN_SPEED 255 /** * Part-Cooling Fan Multiplexer @@ -511,12 +603,17 @@ #define INVERT_CASE_LIGHT false // Set true if Case Light is ON when pin is LOW #define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on #define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin) - //#define CASE_LIGHT_MAX_PWM 128 // Limit pwm - //#define CASE_LIGHT_MENU // Add Case Light options to the LCD menu //#define CASE_LIGHT_NO_BRIGHTNESS // Disable brightness control. Enable for non-PWM lighting. - //#define CASE_LIGHT_USE_NEOPIXEL // Use NeoPixel LED as case light, requires NEOPIXEL_LED. - #if ENABLED(CASE_LIGHT_USE_NEOPIXEL) - #define CASE_LIGHT_NEOPIXEL_COLOR { 255, 255, 255, 255 } // { Red, Green, Blue, White } + //#define CASE_LIGHT_MAX_PWM 128 // Limit PWM duty cycle (0-255) + //#define CASE_LIGHT_MENU // Add Case Light options to the LCD menu + #if ENABLED(NEOPIXEL_LED) + //#define CASE_LIGHT_USE_NEOPIXEL // Use NeoPixel LED as case light + #endif + #if EITHER(RGB_LED, RGBW_LED) + //#define CASE_LIGHT_USE_RGB_LED // Use RGB / RGBW LED as case light + #endif + #if EITHER(CASE_LIGHT_USE_NEOPIXEL, CASE_LIGHT_USE_RGB_LED) + #define CASE_LIGHT_DEFAULT_COLOR { 255, 255, 255, 255 } // { Red, Green, Blue, White } #endif #endif @@ -554,7 +651,7 @@ //#define X_DUAL_STEPPER_DRIVERS #if ENABLED(X_DUAL_STEPPER_DRIVERS) - #define INVERT_X2_VS_X_DIR true // Set 'true' if X motors should rotate in opposite directions + //#define INVERT_X2_VS_X_DIR // Enable if X2 direction signal is opposite to X //#define X_DUAL_ENDSTOPS #if ENABLED(X_DUAL_ENDSTOPS) #define X2_USE_ENDSTOP _XMAX_ @@ -564,7 +661,7 @@ //#define Y_DUAL_STEPPER_DRIVERS #if ENABLED(Y_DUAL_STEPPER_DRIVERS) - #define INVERT_Y2_VS_Y_DIR true // Set 'true' if Y motors should rotate in opposite directions + //#define INVERT_Y2_VS_Y_DIR // Enable if Y2 direction signal is opposite to Y //#define Y_DUAL_ENDSTOPS #if ENABLED(Y_DUAL_ENDSTOPS) #define Y2_USE_ENDSTOP _YMAX_ @@ -578,6 +675,11 @@ #define NUM_Z_STEPPER_DRIVERS 2 // (1-4) Z options change based on how many #if NUM_Z_STEPPER_DRIVERS > 1 + // Enable if Z motor direction signals are the opposite of Z1 + //#define INVERT_Z2_VS_Z_DIR + //#define INVERT_Z3_VS_Z_DIR + //#define INVERT_Z4_VS_Z_DIR + //#define Z_MULTI_ENDSTOPS #if ENABLED(Z_MULTI_ENDSTOPS) #define Z2_USE_ENDSTOP _XMAX_ @@ -593,6 +695,12 @@ #endif #endif +// Drive the E axis with two synchronized steppers +//#define E_DUAL_STEPPER_DRIVERS +#if ENABLED(E_DUAL_STEPPER_DRIVERS) + //#define INVERT_E1_VS_E0_DIR // Enable if the E motors need opposite DIR states +#endif + /** * Dual X Carriage * @@ -639,6 +747,9 @@ // Default x offset in duplication mode (typically set to half print bed width) #define DEFAULT_DUPLICATION_X_OFFSET 100 + + // Default action to execute following M605 mode change commands. Typically G28X to apply new mode. + //#define EVENT_GCODE_IDEX_AFTER_MODECHANGE "G28X" #endif // Activate a solenoid on the active extruder with M380. Disable all with M381. @@ -653,7 +764,7 @@ * the position of the toolhead relative to the workspace. */ -//#define SENSORLESS_BACKOFF_MM { 2, 2 } // (mm) Backoff from endstops before sensorless homing +//#define SENSORLESS_BACKOFF_MM { 2, 2, 0 } // (mm) Backoff from endstops before sensorless homing #define HOMING_BUMP_MM { 5, 5, 2 } // (mm) Backoff from endstops after first bump #define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate) @@ -662,6 +773,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 CODEPENDENT_XY_HOMING // If X/Y can't home without homing Y/X first // @section bltouch @@ -723,8 +835,8 @@ /** * Use "HIGH SPEED" mode for probing. * Danger: Disable if your probe sometimes fails. Only suitable for stable well-adjusted systems. - * This feature was designed for Delta's with very fast Z moves however higher speed cartesians may function - * If the machine cannot raise the probe fast enough after a trigger, it may enter a fault state. + * This feature was designed for Deltabots with very fast Z moves; however, higher speed Cartesians + * might be able to use it. If the machine can't raise Z fast enough the BLTouch may go into ALARM. */ //#define BLTOUCH_HS_MODE @@ -799,10 +911,10 @@ //#define ASSISTED_TRAMMING #if ENABLED(ASSISTED_TRAMMING) - // Define positions for probing points, use the hotend as reference not the sensor. - #define TRAMMING_POINT_XY { { 20, 20 }, { 200, 20 }, { 200, 200 }, { 20, 200 } } + // Define positions for probe points. + #define TRAMMING_POINT_XY { { 20, 20 }, { 180, 20 }, { 180, 180 }, { 20, 180 } } - // Define positions names for probing points. + // Define position names for probe points. #define TRAMMING_POINT_NAME_1 "Front-Left" #define TRAMMING_POINT_NAME_2 "Front-Right" #define TRAMMING_POINT_NAME_3 "Back-Right" @@ -811,8 +923,8 @@ #define RESTORE_LEVELING_AFTER_G35 // Enable to restore leveling setup after operation //#define REPORT_TRAMMING_MM // Report Z deviation (mm) for each point relative to the first - //#define ASSISTED_TRAMMING_MENU_ITEM // Add a menu item to run G35 Assisted Tramming (MarlinUI) - //#define ASSISTED_TRAMMING_WIZARD // Make the menu item open a Tramming Wizard sub-menu + //#define ASSISTED_TRAMMING_WIZARD // Add a Tramming Wizard to the LCD menu + //#define ASSISTED_TRAMMING_WAIT_POSITION { X_CENTER, Y_CENTER, 30 } // Move the nozzle out of the way for adjustment /** @@ -836,6 +948,9 @@ #define INVERT_X_STEP_PIN false #define INVERT_Y_STEP_PIN false #define INVERT_Z_STEP_PIN false +#define INVERT_I_STEP_PIN false +#define INVERT_J_STEP_PIN false +#define INVERT_K_STEP_PIN false #define INVERT_E_STEP_PIN false /** @@ -847,13 +962,11 @@ #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_E true -// If the Nozzle or Bed falls when the Z stepper is disabled, set its resting position here. -//#define Z_AFTER_DEACTIVATE Z_HOME_POS - -//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated - // Default Minimum Feedrates for printing and travel moves #define DEFAULT_MINIMUMFEEDRATE 0.0 // (mm/s) Minimum feedrate. Set with M205 S. #define DEFAULT_MINTRAVELFEEDRATE 0.0 // (mm/s) Minimum travel feedrate. Set with M205 T. @@ -892,9 +1005,12 @@ #if ENABLED(BACKLASH_COMPENSATION) // Define values for backlash distance and correction. // If BACKLASH_GCODE is enabled these values are the defaults. - #define BACKLASH_DISTANCE_MM { 0, 0, 0 } // (mm) + #define BACKLASH_DISTANCE_MM { 0, 0, 0 } // (mm) One value for each linear axis #define BACKLASH_CORRECTION 0.0 // 0.0 = no correction; 1.0 = full correction + // Add steps for motor direction changes on CORE kinematics + //#define CORE_BACKLASH + // Set BACKLASH_SMOOTHING_MM to spread backlash correction over multiple segments // to reduce print artifacts. (Enabling this is costly in memory and computation!) //#define BACKLASH_SMOOTHING_MM 3 // (mm) @@ -912,7 +1028,7 @@ // increments while checking for the contact to be broken. #define BACKLASH_MEASUREMENT_LIMIT 0.5 // (mm) #define BACKLASH_MEASUREMENT_RESOLUTION 0.005 // (mm) - #define BACKLASH_MEASUREMENT_FEEDRATE Z_PROBE_SPEED_SLOW // (mm/min) + #define BACKLASH_MEASUREMENT_FEEDRATE Z_PROBE_FEEDRATE_SLOW // (mm/min) #endif #endif #endif @@ -960,6 +1076,13 @@ #define CALIBRATION_MEASURE_LEFT #define CALIBRATION_MEASURE_BACK + //#define CALIBRATION_MEASURE_IMIN + //#define CALIBRATION_MEASURE_IMAX + //#define CALIBRATION_MEASURE_JMIN + //#define CALIBRATION_MEASURE_JMAX + //#define CALIBRATION_MEASURE_KMIN + //#define CALIBRATION_MEASURE_KMAX + // 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. //#define CALIBRATION_MEASURE_AT_TOP_EDGES @@ -1022,7 +1145,7 @@ /** * I2C-based DIGIPOTs (e.g., Azteeg X3 Pro) */ -//#define DIGIPOT_MCP4018 // Requires https://github.com/stawel/SlowSoftI2CMaster +//#define DIGIPOT_MCP4018 // Requires https://github.com/felias-fogg/SlowSoftI2CMaster //#define DIGIPOT_MCP4451 #if EITHER(DIGIPOT_MCP4018, DIGIPOT_MCP4451) #define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT:4 AZTEEG_X3_PRO:8 MKS_SBASE:5 MIGHTYBOARD_REVE:5 @@ -1055,7 +1178,7 @@ #if EITHER(IS_ULTIPANEL, EXTENSIBLE_UI) #define MANUAL_FEEDRATE { 50*60, 50*60, 4*60, 2*60 } // (mm/min) Feedrates for manual moves along X, Y, Z, E from panel - #define SHORT_MANUAL_Z_MOVE 0.025 // (mm) Smallest manual Z move (< 0.1mm) + #define FINE_MANUAL_MOVE 0.025 // (mm) Smallest manual move (< 0.1mm) applying to Z on most machines #if IS_ULTIPANEL #define MANUAL_E_MOVES_RELATIVE // Display extruder move distance rather than "position" #define ULTIPANEL_FEEDMULTIPLY // Encoder sets the feedrate multiplier on the Status Screen @@ -1082,7 +1205,15 @@ #if HAS_BED_PROBE //#define PROBE_OFFSET_WIZARD #if ENABLED(PROBE_OFFSET_WIZARD) - #define PROBE_OFFSET_START -4.0 // Estimated nozzle-to-probe Z offset, plus a little extra + // + // Enable to init the Probe Z-Offset when starting the Wizard. + // Use a height slightly above the estimated nozzle-to-probe Z offset. + // For example, with an offset of -5, consider a starting height of -4. + // + //#define PROBE_OFFSET_WIZARD_START_Z -4.0 + + // Set a convenient position to do the calibration (probing point and nozzle/bed-distance) + //#define PROBE_OFFSET_WIZARD_XY_POS { X_CENTER, Y_CENTER } #endif #endif @@ -1124,35 +1255,46 @@ #endif #endif + // Insert a menu for preheating at the top level to allow for quick access + //#define PREHEAT_SHORTCUT_MENU_ITEM + #endif // HAS_LCD_MENU -// Scroll a longer status message into view -//#define STATUS_MESSAGE_SCROLLING +#if HAS_DISPLAY + // The timeout (in ms) to return to the status screen from sub-menus + //#define LCD_TIMEOUT_TO_STATUS 15000 -// On the Info Screen, display XY with one decimal place when possible -//#define LCD_DECIMAL_SMALL_XY + #if ENABLED(SHOW_BOOTSCREEN) + #define BOOTSCREEN_TIMEOUT 4000 // (ms) Total Duration to display the boot screen(s) + #if EITHER(HAS_MARLINUI_U8GLIB, TFT_COLOR_UI) + #define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving lots of flash) + #endif + #endif -// The timeout (in ms) to return to the status screen from sub-menus -//#define LCD_TIMEOUT_TO_STATUS 15000 + // Scroll a longer status message into view + //#define STATUS_MESSAGE_SCROLLING -// Add an 'M73' G-code to set the current percentage -//#define LCD_SET_PROGRESS_MANUALLY + // On the Info Screen, display XY with one decimal place when possible + //#define LCD_DECIMAL_SMALL_XY -// Show the E position (filament used) during printing -//#define LCD_SHOW_E_TOTAL + // Add an 'M73' G-code to set the current percentage + //#define LCD_SET_PROGRESS_MANUALLY -#if ENABLED(SHOW_BOOTSCREEN) - #define BOOTSCREEN_TIMEOUT 4000 // (ms) Total Duration to display the boot screen(s) + // Show the E position (filament used) during printing + //#define LCD_SHOW_E_TOTAL #endif -#if EITHER(SDSUPPORT, LCD_SET_PROGRESS_MANUALLY) && ANY(HAS_MARLINUI_U8GLIB, HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL) - //#define SHOW_REMAINING_TIME // Display estimated time to completion - #if ENABLED(SHOW_REMAINING_TIME) - //#define USE_M73_REMAINING_TIME // Use remaining time from M73 command instead of estimation - //#define ROTATE_PROGRESS_DISPLAY // Display (P)rogress, (E)lapsed, and (R)emaining time +// LCD Print Progress options +#if EITHER(SDSUPPORT, LCD_SET_PROGRESS_MANUALLY) + #if ANY(HAS_MARLINUI_U8GLIB, EXTENSIBLE_UI, HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL) + //#define SHOW_REMAINING_TIME // Display estimated time to completion + #if ENABLED(SHOW_REMAINING_TIME) + //#define USE_M73_REMAINING_TIME // Use remaining time from M73 command instead of estimation + //#define ROTATE_PROGRESS_DISPLAY // Display (P)rogress, (E)lapsed, and (R)emaining time + #endif #endif - #if HAS_MARLINUI_U8GLIB + #if EITHER(HAS_MARLINUI_U8GLIB, EXTENSIBLE_UI) //#define PRINT_PROGRESS_SHOW_DECIMALS // Show progress with decimal digits #endif @@ -1169,13 +1311,26 @@ #endif #if ENABLED(SDSUPPORT) + /** + * SD Card SPI Speed + * May be required to resolve "volume init" errors. + * + * Enable and set to SPI_HALF_SPEED, SPI_QUARTER_SPEED, or SPI_EIGHTH_SPEED + * otherwise full speed will be applied. + * + * :['SPI_HALF_SPEED', 'SPI_QUARTER_SPEED', 'SPI_EIGHTH_SPEED'] + */ + //#define SD_SPI_SPEED SPI_HALF_SPEED // The standard SD detect circuit reads LOW when media is inserted and HIGH when empty. // Enable this option and set to HIGH if your SD cards are incorrectly detected. //#define SD_DETECT_STATE HIGH + //#define SD_IGNORE_AT_STARTUP // Don't mount the SD card when starting up //#define SDCARD_READONLY // Read-only SD card (to save over 2K of flash) + //#define GCODE_REPEAT_MARKERS // Enable G-code M808 to set repeat markers and do looping + #define SD_PROCEDURE_DEPTH 1 // Increase if you need more nested M32 calls #define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished @@ -1187,8 +1342,13 @@ #define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing + //#define NO_SD_AUTOSTART // Remove auto#.g file support completely to save some Flash, SRAM //#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files + //#define BROWSE_MEDIA_ON_INSERT // Open the file browser when media is inserted + + //#define MEDIA_MENU_AT_TOP // Force the media menu to be listed on the top of the main menu + #define EVENT_GCODE_SD_ABORT "G28XY" // G-code to run on SD Abort Print (e.g., "G28XY" or "G27") #if ENABLED(PRINTER_EVENT_LEDS) @@ -1207,17 +1367,23 @@ #if ENABLED(POWER_LOSS_RECOVERY) #define PLR_ENABLED_DEFAULT false // Power Loss Recovery enabled by default. (Set with 'M413 Sn' & M500) //#define BACKUP_POWER_SUPPLY // Backup power / UPS to move the steppers on power loss - //#define POWER_LOSS_RECOVER_ZHOME // Z homing is needed for proper recovery. 99.9% of the time this should be disabled! //#define POWER_LOSS_ZRAISE 2 // (mm) Z axis raise on resume (on power loss with UPS) //#define POWER_LOSS_PIN 44 // Pin to detect power loss. Set to -1 to disable default pin on boards without module. //#define POWER_LOSS_STATE HIGH // State of pin indicating power loss - //#define POWER_LOSS_PULL // Set pullup / pulldown as appropriate + //#define POWER_LOSS_PULLUP // Set pullup / pulldown as appropriate for your sensor + //#define POWER_LOSS_PULLDOWN //#define POWER_LOSS_PURGE_LEN 20 // (mm) Length of filament to purge on resume //#define POWER_LOSS_RETRACT_LEN 10 // (mm) Length of filament to retract on fail. Requires backup power. // Without a POWER_LOSS_PIN the following option helps reduce wear on the SD card, // especially with "vase mode" printing. Set too high and vases cannot be continued. #define POWER_LOSS_MIN_Z_CHANGE 0.05 // (mm) Minimum Z change before saving power-loss data + + // Enable if Z homing is needed for proper recovery. 99.9% of the time this should be disabled! + //#define POWER_LOSS_RECOVER_ZHOME + #if ENABLED(POWER_LOSS_RECOVER_ZHOME) + //#define POWER_LOSS_ZHOME_POS { 0, 0 } // Safe XY position to home Z while avoiding objects on the bed + #endif #endif /** @@ -1258,6 +1424,10 @@ // Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM. #endif + // Allow international symbols in long filenames. To display correctly, the + // LCD's font must contain the characters. Check your selected LCD language. + //#define UTF_FILENAME_SUPPORT + // This allows hosts to request long names for files and folders with M33 //#define LONG_FILENAME_HOST_SUPPORT @@ -1302,9 +1472,6 @@ */ //#define USB_FLASH_DRIVE_SUPPORT #if ENABLED(USB_FLASH_DRIVE_SUPPORT) - #define USB_CS_PIN SDSS - #define USB_INTR_PIN SD_DETECT_PIN - /** * USB Host Shield Library * @@ -1315,7 +1482,18 @@ * is less tested and is known to interfere with Servos. * [1] This requires USB_INTR_PIN to be interrupt-capable. */ + //#define USE_UHS2_USB //#define USE_UHS3_USB + + /** + * Native USB Host supported by some boards (USB OTG) + */ + //#define USE_OTG_USB_HOST + + #if DISABLED(USE_OTG_USB_HOST) + #define USB_CS_PIN SDSS + #define USB_INTR_PIN SD_DETECT_PIN + #endif #endif /** @@ -1341,13 +1519,25 @@ * Set this option to one of the following (or the board's defaults apply): * * LCD - Use the SD drive in the external LCD controller. - * ONBOARD - Use the SD drive on the control board. (No SD_DETECT_PIN. M21 to init.) + * ONBOARD - Use the SD drive on the control board. * CUSTOM_CABLE - Use a custom cable to access the SD (as defined in a pins file). * * :[ 'LCD', 'ONBOARD', 'CUSTOM_CABLE' ] */ //#define SDCARD_CONNECTION LCD + // Enable if SD detect is rendered useless (e.g., by using an SD extender) + //#define NO_SD_DETECT + + // Multiple volume support - EXPERIMENTAL. + //#define MULTI_VOLUME + #if ENABLED(MULTI_VOLUME) + #define VOLUME_SD_ONBOARD + #define VOLUME_USB_FLASH_DRIVE + #define DEFAULT_VOLUME SV_SD_ONBOARD + #define DEFAULT_SHARED_VOLUME SV_USB_FLASH_DRIVE + #endif + #endif // SDSUPPORT /** @@ -1420,16 +1610,17 @@ */ //#define STATUS_COMBINE_HEATERS // Use combined heater images instead of separate ones //#define STATUS_HOTEND_NUMBERLESS // Use plain hotend icons instead of numbered ones (with 2+ hotends) - #define STATUS_HOTEND_INVERTED // Show solid nozzle bitmaps when heating (Requires STATUS_HOTEND_ANIM) + #define STATUS_HOTEND_INVERTED // Show solid nozzle bitmaps when heating (Requires STATUS_HOTEND_ANIM for numbered hotends) #define STATUS_HOTEND_ANIM // Use a second bitmap to indicate hotend heating #define STATUS_BED_ANIM // Use a second bitmap to indicate bed heating #define STATUS_CHAMBER_ANIM // Use a second bitmap to indicate chamber heating //#define STATUS_CUTTER_ANIM // Use a second bitmap to indicate spindle / laser active + //#define STATUS_COOLER_ANIM // Use a second bitmap to indicate laser cooling + //#define STATUS_FLOWMETER_ANIM // Use multiple bitmaps to indicate coolant flow //#define STATUS_ALT_BED_BITMAP // Use the alternative bed bitmap //#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap //#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames //#define STATUS_HEAT_PERCENT // Show heating in a progress bar - //#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash) //#define BOOT_MARLIN_LOGO_ANIMATED // Animated Marlin logo. Costs ~‭3260 (or ~940) bytes of PROGMEM. // Frivolous Game Options @@ -1453,12 +1644,12 @@ #define DGUS_UPDATE_INTERVAL_MS 500 // (ms) Interval between automatic screen updates - #if EITHER(DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_HIPRECY) + #if ANY(DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_MKS, DGUS_LCD_UI_HIPRECY) #define DGUS_PRINT_FILENAME // Display the filename during printing #define DGUS_PREHEAT_UI // Display a preheat screen during heatup - #if ENABLED(DGUS_LCD_UI_FYSETC) - //#define DGUS_UI_MOVE_DIS_OPTION // Disabled by default for UI_FYSETC + #if EITHER(DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_MKS) + //#define DGUS_UI_MOVE_DIS_OPTION // Disabled by default for FYSETC and MKS #else #define DGUS_UI_MOVE_DIS_OPTION // Enabled by default for UI_HIPRECY #endif @@ -1477,6 +1668,44 @@ #endif #endif // HAS_DGUS_LCD +// +// Additional options for AnyCubic Chiron TFT displays +// +#if ENABLED(ANYCUBIC_LCD_CHIRON) + // By default the type of panel is automatically detected. + // Enable one of these options if you know the panel type. + //#define CHIRON_TFT_STANDARD + //#define CHIRON_TFT_NEW + + // Enable the longer Anycubic powerup startup tune + //#define AC_DEFAULT_STARTUP_TUNE + + /** + * Display Folders + * By default the file browser lists all G-code files (including those in subfolders) in a flat list. + * Enable this option to display a hierarchical file browser. + * + * NOTES: + * - Without this option it helps to enable SDCARD_SORT_ALPHA so files are sorted before/after folders. + * - When used with the "new" panel, folder names will also have '.gcode' appended to their names. + * This hack is currently required to force the panel to show folders. + */ + #define AC_SD_FOLDER_VIEW +#endif + +// +// Specify additional languages for the UI. Default specified by LCD_LANGUAGE. +// +#if ANY(DOGLCD, TFT_COLOR_UI, TOUCH_UI_FTDI_EVE) + //#define LCD_LANGUAGE_2 fr + //#define LCD_LANGUAGE_3 de + //#define LCD_LANGUAGE_4 es + //#define LCD_LANGUAGE_5 it + #ifdef LCD_LANGUAGE_2 + //#define LCD_LANGUAGE_AUTO_SAVE // Automatically save language to EEPROM on change + #endif +#endif + // // Touch UI for the FTDI Embedded Video Engine (EVE) // @@ -1488,6 +1717,8 @@ //#define LCD_HAOYU_FT810CB // Haoyu with 5" (800x480) //#define LCD_ALEPHOBJECTS_CLCD_UI // Aleph Objects Color LCD UI //#define LCD_FYSETC_TFT81050 // FYSETC with 5" (800x480) + //#define LCD_EVE3_50G // Matrix Orbital 5.0", 800x480, BT815 + //#define LCD_EVE2_50G // Matrix Orbital 5.0", 800x480, FT813 // Correct the resolution if not using the stock TFT panel. //#define TOUCH_UI_320x240 @@ -1544,18 +1775,14 @@ //#define TOUCH_UI_UTF8_FRACTIONS // ¼ ½ ¾ //#define TOUCH_UI_UTF8_SYMBOLS // µ ¶ ¦ § ¬ #endif + + // Cyrillic character set, costs about 27KiB of flash + //#define TOUCH_UI_UTF8_CYRILLIC_CHARSET #endif // Use a smaller font when labels don't fit buttons #define TOUCH_UI_FIT_TEXT - // Allow language selection from menu at run-time (otherwise use LCD_LANGUAGE) - //#define LCD_LANGUAGE_1 en - //#define LCD_LANGUAGE_2 fr - //#define LCD_LANGUAGE_3 de - //#define LCD_LANGUAGE_4 es - //#define LCD_LANGUAGE_5 it - // Use a numeric passcode for "Screen lock" keypad. // (recommended for smaller displays) //#define TOUCH_UI_PASSCODE @@ -1715,6 +1942,10 @@ //#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET) #endif +#if BOTH(AUTO_BED_LEVELING_UBL, EEPROM_SETTINGS) + //#define OPTIMIZED_MESH_STORAGE // Store mesh with less precision to save EEPROM space +#endif + /** * Repeatedly attempt G29 leveling until it succeeds. * Stop after G29_MAX_RETRIES attempts. @@ -1757,30 +1988,30 @@ //#define USE_TEMP_EXT_COMPENSATION // Probe temperature calibration generates a table of values starting at PTC_SAMPLE_START - // (e.g. 30), in steps of PTC_SAMPLE_RES (e.g. 5) with PTC_SAMPLE_COUNT (e.g. 10) samples. + // (e.g., 30), in steps of PTC_SAMPLE_RES (e.g., 5) with PTC_SAMPLE_COUNT (e.g., 10) samples. - //#define PTC_SAMPLE_START 30.0f - //#define PTC_SAMPLE_RES 5.0f - //#define PTC_SAMPLE_COUNT 10U + //#define PTC_SAMPLE_START 30 // (°C) + //#define PTC_SAMPLE_RES 5 // (°C) + //#define PTC_SAMPLE_COUNT 10 // Bed temperature calibration builds a similar table. - //#define BTC_SAMPLE_START 60.0f - //#define BTC_SAMPLE_RES 5.0f - //#define BTC_SAMPLE_COUNT 10U + //#define BTC_SAMPLE_START 60 // (°C) + //#define BTC_SAMPLE_RES 5 // (°C) + //#define BTC_SAMPLE_COUNT 10 // The temperature the probe should be at while taking measurements during bed temperature // calibration. - //#define BTC_PROBE_TEMP 30.0f + //#define BTC_PROBE_TEMP 30 // (°C) - // Height above Z=0.0f to raise the nozzle. Lowering this can help the probe to heat faster. - // Note: the Z=0.0f offset is determined by the probe offset which can be set using M851. - //#define PTC_PROBE_HEATING_OFFSET 0.5f + // Height above Z=0.0 to raise the nozzle. Lowering this can help the probe to heat faster. + // Note: the Z=0.0 offset is determined by the probe offset which can be set using M851. + //#define PTC_PROBE_HEATING_OFFSET 0.5 // Height to raise the Z-probe between heating and taking the next measurement. Some probes // may fail to untrigger if they have been triggered for a long time, which can be solved by // increasing the height the probe is raised to. - //#define PTC_PROBE_RAISE 15U + //#define PTC_PROBE_RAISE 15 // If the probe is outside of the defined range, use linear extrapolation using the closest // point and the PTC_LINEAR_EXTRAPOLATION'th next point. E.g. if set to 4 it will use data[0] @@ -1895,7 +2126,7 @@ // @section motion // 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) +// The value of BLOCK_BUFFER_SIZE must be a power of 2 (e.g., 8, 16, 32) #if BOTH(SDSUPPORT, DIRECT_STEPPING) #define BLOCK_BUFFER_SIZE 8 #elif ENABLED(SDSUPPORT) @@ -1931,9 +2162,6 @@ //#define SERIAL_XON_XOFF #endif -// Add M575 G-code to change the baud rate -//#define BAUD_RATE_GCODE - #if ENABLED(SDSUPPORT) // Enable this option to collect and display the maximum // RX queue usage after transferring a file to SD. @@ -1944,6 +2172,12 @@ //#define SERIAL_STATS_DROPPED_RX #endif +// Monitor RX buffer usage +// Dump an error to the serial port if the serial receive buffer overflows. +// If you see these errors, increase the RX_BUFFER_SIZE value. +// Not supported on all platforms. +//#define RX_BUFFER_MONITOR + /** * Emergency Command Parser * @@ -1954,6 +2188,26 @@ */ //#define EMERGENCY_PARSER +/** + * Realtime Reporting (requires EMERGENCY_PARSER) + * + * - Report position and state of the machine (like Grbl). + * - Auto-report position during long moves. + * - Useful for CNC/LASER. + * + * Adds support for commands: + * S000 : Report State and Position while moving. + * P000 : Instant Pause / Hold while moving. + * R000 : Resume from Pause / Hold. + * + * - During Hold all Emergency Parser commands are available, as usual. + * - Enable NANODLP_Z_SYNC and NANODLP_ALL_AXIS for move command end-state reports. + */ +//#define REALTIME_REPORTING_COMMANDS +#if ENABLED(REALTIME_REPORTING_COMMANDS) + //#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'. @@ -1997,21 +2251,21 @@ */ //#define FWRETRACT #if ENABLED(FWRETRACT) - #define FWRETRACT_AUTORETRACT // Override slicer retractions + #define FWRETRACT_AUTORETRACT // Override slicer retractions #if ENABLED(FWRETRACT_AUTORETRACT) - #define MIN_AUTORETRACT 0.1 // (mm) Don't convert E moves under this length - #define MAX_AUTORETRACT 10.0 // (mm) Don't convert E moves over this length - #endif - #define RETRACT_LENGTH 3 // (mm) Default retract length (positive value) - #define RETRACT_LENGTH_SWAP 13 // (mm) Default swap retract length (positive value) - #define RETRACT_FEEDRATE 45 // (mm/s) Default feedrate for retracting - #define RETRACT_ZRAISE 0 // (mm) Default retract Z-raise - #define RETRACT_RECOVER_LENGTH 0 // (mm) Default additional recover length (added to retract length on recover) - #define RETRACT_RECOVER_LENGTH_SWAP 0 // (mm) Default additional swap recover length (added to retract length on recover from toolchange) - #define RETRACT_RECOVER_FEEDRATE 8 // (mm/s) Default feedrate for recovering from retraction - #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // (mm/s) Default feedrate for recovering from swap retraction + #define MIN_AUTORETRACT 0.1 // (mm) Don't convert E moves under this length + #define MAX_AUTORETRACT 10.0 // (mm) Don't convert E moves over this length + #endif + #define RETRACT_LENGTH 3 // (mm) Default retract length (positive value) + #define RETRACT_LENGTH_SWAP 13 // (mm) Default swap retract length (positive value) + #define RETRACT_FEEDRATE 45 // (mm/s) Default feedrate for retracting + #define RETRACT_ZRAISE 0 // (mm) Default retract Z-raise + #define RETRACT_RECOVER_LENGTH 0 // (mm) Default additional recover length (added to retract length on recover) + #define RETRACT_RECOVER_LENGTH_SWAP 0 // (mm) Default additional swap recover length (added to retract length on recover from toolchange) + #define RETRACT_RECOVER_FEEDRATE 8 // (mm/s) Default feedrate for recovering from retraction + #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // (mm/s) Default feedrate for recovering from swap retraction #if ENABLED(MIXING_EXTRUDER) - //#define RETRACT_SYNC_MIXING // Retract and restore all mixing steppers simultaneously + //#define RETRACT_SYNC_MIXING // Retract and restore all mixing steppers simultaneously #endif #endif @@ -2028,6 +2282,19 @@ //#define EVENT_GCODE_AFTER_TOOLCHANGE "G12X" // Extra G-code to run after tool-change #endif + /** + * Extra G-code to run while executing tool-change commands. Can be used to use an additional + * stepper motor (I axis, see option LINEAR_AXES 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 + + /** + * Tool Sensors detect when tools have been picked up or dropped. + * Requires the pins TOOL_SENSOR1_PIN, TOOL_SENSOR2_PIN, etc. + */ + //#define TOOL_SENSOR + /** * Retract and prime filament on tool-change to reduce * ooze and stringing and to get cleaner transitions. @@ -2086,14 +2353,15 @@ #endif // HAS_MULTI_EXTRUDER /** - * Advanced Pause - * Experimental feature for filament change support and for parking the nozzle when paused. - * Adds the GCode M600 for initiating filament change. - * If PARK_HEAD_ON_PAUSE enabled, adds the GCode M125 to pause printing and park the nozzle. + * Advanced Pause for Filament Change + * - Adds the G-code M600 Filament Change to initiate a filament change. + * - This feature is required for the default FILAMENT_RUNOUT_SCRIPT. * - * Requires an LCD display. - * Requires NOZZLE_PARK_FEATURE. - * This feature is required for the default FILAMENT_RUNOUT_SCRIPT. + * Requirements: + * - For Filament Change parking enable and configure NOZZLE_PARK_FEATURE. + * - For user interaction enable an LCD display, HOST_PROMPT_SUPPORT, or EMERGENCY_PARSER. + * + * Enable PARK_HEAD_ON_PAUSE to add the G-code M125 Pause and Park. */ //#define ADVANCED_PAUSE_FEATURE #if ENABLED(ADVANCED_PAUSE_FEATURE) @@ -2159,7 +2427,7 @@ #if AXIS_DRIVER_TYPE_X2(TMC26X) #define X2_MAX_CURRENT 1000 #define X2_SENSE_RESISTOR 91 - #define X2_MICROSTEPS 16 + #define X2_MICROSTEPS X_MICROSTEPS #endif #if AXIS_DRIVER_TYPE_Y(TMC26X) @@ -2171,7 +2439,7 @@ #if AXIS_DRIVER_TYPE_Y2(TMC26X) #define Y2_MAX_CURRENT 1000 #define Y2_SENSE_RESISTOR 91 - #define Y2_MICROSTEPS 16 + #define Y2_MICROSTEPS Y_MICROSTEPS #endif #if AXIS_DRIVER_TYPE_Z(TMC26X) @@ -2183,19 +2451,37 @@ #if AXIS_DRIVER_TYPE_Z2(TMC26X) #define Z2_MAX_CURRENT 1000 #define Z2_SENSE_RESISTOR 91 - #define Z2_MICROSTEPS 16 + #define Z2_MICROSTEPS Z_MICROSTEPS #endif #if AXIS_DRIVER_TYPE_Z3(TMC26X) #define Z3_MAX_CURRENT 1000 #define Z3_SENSE_RESISTOR 91 - #define Z3_MICROSTEPS 16 + #define Z3_MICROSTEPS Z_MICROSTEPS #endif #if AXIS_DRIVER_TYPE_Z4(TMC26X) #define Z4_MAX_CURRENT 1000 #define Z4_SENSE_RESISTOR 91 - #define Z4_MICROSTEPS 16 + #define Z4_MICROSTEPS Z_MICROSTEPS + #endif + + #if AXIS_DRIVER_TYPE_I(TMC26X) + #define I_MAX_CURRENT 1000 + #define I_SENSE_RESISTOR 91 + #define I_MICROSTEPS 16 + #endif + + #if AXIS_DRIVER_TYPE_J(TMC26X) + #define J_MAX_CURRENT 1000 + #define J_SENSE_RESISTOR 91 + #define J_MICROSTEPS 16 + #endif + + #if AXIS_DRIVER_TYPE_K(TMC26X) + #define K_MAX_CURRENT 1000 + #define K_SENSE_RESISTOR 91 + #define K_MICROSTEPS 16 #endif #if AXIS_DRIVER_TYPE_E0(TMC26X) @@ -2207,43 +2493,43 @@ #if AXIS_DRIVER_TYPE_E1(TMC26X) #define E1_MAX_CURRENT 1000 #define E1_SENSE_RESISTOR 91 - #define E1_MICROSTEPS 16 + #define E1_MICROSTEPS E0_MICROSTEPS #endif #if AXIS_DRIVER_TYPE_E2(TMC26X) #define E2_MAX_CURRENT 1000 #define E2_SENSE_RESISTOR 91 - #define E2_MICROSTEPS 16 + #define E2_MICROSTEPS E0_MICROSTEPS #endif #if AXIS_DRIVER_TYPE_E3(TMC26X) #define E3_MAX_CURRENT 1000 #define E3_SENSE_RESISTOR 91 - #define E3_MICROSTEPS 16 + #define E3_MICROSTEPS E0_MICROSTEPS #endif #if AXIS_DRIVER_TYPE_E4(TMC26X) #define E4_MAX_CURRENT 1000 #define E4_SENSE_RESISTOR 91 - #define E4_MICROSTEPS 16 + #define E4_MICROSTEPS E0_MICROSTEPS #endif #if AXIS_DRIVER_TYPE_E5(TMC26X) #define E5_MAX_CURRENT 1000 #define E5_SENSE_RESISTOR 91 - #define E5_MICROSTEPS 16 + #define E5_MICROSTEPS E0_MICROSTEPS #endif #if AXIS_DRIVER_TYPE_E6(TMC26X) #define E6_MAX_CURRENT 1000 #define E6_SENSE_RESISTOR 91 - #define E6_MICROSTEPS 16 + #define E6_MICROSTEPS E0_MICROSTEPS #endif #if AXIS_DRIVER_TYPE_E7(TMC26X) #define E7_MAX_CURRENT 1000 #define E7_SENSE_RESISTOR 91 - #define E7_MICROSTEPS 16 + #define E7_MICROSTEPS E0_MICROSTEPS #endif #endif // TMC26X @@ -2288,7 +2574,7 @@ #if AXIS_IS_TMC(X2) #define X2_CURRENT 800 #define X2_CURRENT_HOME X2_CURRENT - #define X2_MICROSTEPS 16 + #define X2_MICROSTEPS X_MICROSTEPS #define X2_RSENSE 0.11 #define X2_CHAIN_POS -1 //#define X2_INTERPOLATE true @@ -2306,7 +2592,7 @@ #if AXIS_IS_TMC(Y2) #define Y2_CURRENT 800 #define Y2_CURRENT_HOME Y2_CURRENT - #define Y2_MICROSTEPS 16 + #define Y2_MICROSTEPS Y_MICROSTEPS #define Y2_RSENSE 0.11 #define Y2_CHAIN_POS -1 //#define Y2_INTERPOLATE true @@ -2324,7 +2610,7 @@ #if AXIS_IS_TMC(Z2) #define Z2_CURRENT 800 #define Z2_CURRENT_HOME Z2_CURRENT - #define Z2_MICROSTEPS 16 + #define Z2_MICROSTEPS Z_MICROSTEPS #define Z2_RSENSE 0.11 #define Z2_CHAIN_POS -1 //#define Z2_INTERPOLATE true @@ -2333,7 +2619,7 @@ #if AXIS_IS_TMC(Z3) #define Z3_CURRENT 800 #define Z3_CURRENT_HOME Z3_CURRENT - #define Z3_MICROSTEPS 16 + #define Z3_MICROSTEPS Z_MICROSTEPS #define Z3_RSENSE 0.11 #define Z3_CHAIN_POS -1 //#define Z3_INTERPOLATE true @@ -2342,12 +2628,39 @@ #if AXIS_IS_TMC(Z4) #define Z4_CURRENT 800 #define Z4_CURRENT_HOME Z4_CURRENT - #define Z4_MICROSTEPS 16 + #define Z4_MICROSTEPS Z_MICROSTEPS #define Z4_RSENSE 0.11 #define Z4_CHAIN_POS -1 //#define Z4_INTERPOLATE true #endif + #if AXIS_IS_TMC(I) + #define I_CURRENT 800 + #define I_CURRENT_HOME I_CURRENT + #define I_MICROSTEPS 16 + #define I_RSENSE 0.11 + #define I_CHAIN_POS -1 + //#define I_INTERPOLATE true + #endif + + #if AXIS_IS_TMC(J) + #define J_CURRENT 800 + #define J_CURRENT_HOME J_CURRENT + #define J_MICROSTEPS 16 + #define J_RSENSE 0.11 + #define J_CHAIN_POS -1 + //#define J_INTERPOLATE true + #endif + + #if AXIS_IS_TMC(K) + #define K_CURRENT 800 + #define K_CURRENT_HOME K_CURRENT + #define K_MICROSTEPS 16 + #define K_RSENSE 0.11 + #define K_CHAIN_POS -1 + //#define K_INTERPOLATE true + #endif + #if AXIS_IS_TMC(E0) #define E0_CURRENT 800 #define E0_MICROSTEPS 16 @@ -2358,7 +2671,7 @@ #if AXIS_IS_TMC(E1) #define E1_CURRENT 800 - #define E1_MICROSTEPS 16 + #define E1_MICROSTEPS E0_MICROSTEPS #define E1_RSENSE 0.11 #define E1_CHAIN_POS -1 //#define E1_INTERPOLATE true @@ -2366,7 +2679,7 @@ #if AXIS_IS_TMC(E2) #define E2_CURRENT 800 - #define E2_MICROSTEPS 16 + #define E2_MICROSTEPS E0_MICROSTEPS #define E2_RSENSE 0.11 #define E2_CHAIN_POS -1 //#define E2_INTERPOLATE true @@ -2374,7 +2687,7 @@ #if AXIS_IS_TMC(E3) #define E3_CURRENT 800 - #define E3_MICROSTEPS 16 + #define E3_MICROSTEPS E0_MICROSTEPS #define E3_RSENSE 0.11 #define E3_CHAIN_POS -1 //#define E3_INTERPOLATE true @@ -2382,7 +2695,7 @@ #if AXIS_IS_TMC(E4) #define E4_CURRENT 800 - #define E4_MICROSTEPS 16 + #define E4_MICROSTEPS E0_MICROSTEPS #define E4_RSENSE 0.11 #define E4_CHAIN_POS -1 //#define E4_INTERPOLATE true @@ -2390,7 +2703,7 @@ #if AXIS_IS_TMC(E5) #define E5_CURRENT 800 - #define E5_MICROSTEPS 16 + #define E5_MICROSTEPS E0_MICROSTEPS #define E5_RSENSE 0.11 #define E5_CHAIN_POS -1 //#define E5_INTERPOLATE true @@ -2398,7 +2711,7 @@ #if AXIS_IS_TMC(E6) #define E6_CURRENT 800 - #define E6_MICROSTEPS 16 + #define E6_MICROSTEPS E0_MICROSTEPS #define E6_RSENSE 0.11 #define E6_CHAIN_POS -1 //#define E6_INTERPOLATE true @@ -2406,7 +2719,7 @@ #if AXIS_IS_TMC(E7) #define E7_CURRENT 800 - #define E7_MICROSTEPS 16 + #define E7_MICROSTEPS E0_MICROSTEPS #define E7_RSENSE 0.11 #define E7_CHAIN_POS -1 //#define E7_INTERPOLATE true @@ -2423,6 +2736,10 @@ //#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 E0_CS_PIN -1 //#define E1_CS_PIN -1 //#define E2_CS_PIN -1 @@ -2454,22 +2771,25 @@ * Set *_SERIAL_TX_PIN and *_SERIAL_RX_PIN to match for all drivers * on the same serial port, either here or in your board's pins file. */ - #define X_SLAVE_ADDRESS 0 - #define Y_SLAVE_ADDRESS 0 - #define Z_SLAVE_ADDRESS 0 - #define X2_SLAVE_ADDRESS 0 - #define Y2_SLAVE_ADDRESS 0 - #define Z2_SLAVE_ADDRESS 0 - #define Z3_SLAVE_ADDRESS 0 - #define Z4_SLAVE_ADDRESS 0 - #define E0_SLAVE_ADDRESS 0 - #define E1_SLAVE_ADDRESS 0 - #define E2_SLAVE_ADDRESS 0 - #define E3_SLAVE_ADDRESS 0 - #define E4_SLAVE_ADDRESS 0 - #define E5_SLAVE_ADDRESS 0 - #define E6_SLAVE_ADDRESS 0 - #define E7_SLAVE_ADDRESS 0 + //#define X_SLAVE_ADDRESS 0 + //#define Y_SLAVE_ADDRESS 0 + //#define Z_SLAVE_ADDRESS 0 + //#define X2_SLAVE_ADDRESS 0 + //#define Y2_SLAVE_ADDRESS 0 + //#define Z2_SLAVE_ADDRESS 0 + //#define Z3_SLAVE_ADDRESS 0 + //#define Z4_SLAVE_ADDRESS 0 + //#define I_SLAVE_ADDRESS 0 + //#define J_SLAVE_ADDRESS 0 + //#define K_SLAVE_ADDRESS 0 + //#define E0_SLAVE_ADDRESS 0 + //#define E1_SLAVE_ADDRESS 0 + //#define E2_SLAVE_ADDRESS 0 + //#define E3_SLAVE_ADDRESS 0 + //#define E4_SLAVE_ADDRESS 0 + //#define E5_SLAVE_ADDRESS 0 + //#define E6_SLAVE_ADDRESS 0 + //#define E7_SLAVE_ADDRESS 0 /** * Software enable @@ -2486,6 +2806,9 @@ */ #define STEALTHCHOP_XY #define STEALTHCHOP_Z + #define STEALTHCHOP_I + #define STEALTHCHOP_J + #define STEALTHCHOP_K #define STEALTHCHOP_E /** @@ -2503,23 +2826,23 @@ * Define your own with: * { , , hysteresis_start[1..8] } */ - #define CHOPPER_TIMING CHOPPER_DEFAULT_24V // All axes (override below) - //#define CHOPPER_TIMING_X CHOPPER_DEFAULT_12V // For X Axes (override below) - //#define CHOPPER_TIMING_X2 CHOPPER_DEFAULT_12V - //#define CHOPPER_TIMING_Y CHOPPER_DEFAULT_12V // For Y Axes (override below) - //#define CHOPPER_TIMING_Y2 CHOPPER_DEFAULT_12V - //#define CHOPPER_TIMING_Z CHOPPER_DEFAULT_12V // For Z Axes (override below) - //#define CHOPPER_TIMING_Z2 CHOPPER_DEFAULT_12V - //#define CHOPPER_TIMING_Z3 CHOPPER_DEFAULT_12V - //#define CHOPPER_TIMING_Z4 CHOPPER_DEFAULT_12V - //#define CHOPPER_TIMING_E CHOPPER_DEFAULT_12V // For Extruders (override below) - //#define CHOPPER_TIMING_E1 CHOPPER_DEFAULT_12V - //#define CHOPPER_TIMING_E2 CHOPPER_DEFAULT_12V - //#define CHOPPER_TIMING_E3 CHOPPER_DEFAULT_12V - //#define CHOPPER_TIMING_E4 CHOPPER_DEFAULT_12V - //#define CHOPPER_TIMING_E5 CHOPPER_DEFAULT_12V - //#define CHOPPER_TIMING_E6 CHOPPER_DEFAULT_12V - //#define CHOPPER_TIMING_E7 CHOPPER_DEFAULT_12V + #define CHOPPER_TIMING CHOPPER_DEFAULT_12V // All axes (override below) // TODO 24V? + //#define CHOPPER_TIMING_X CHOPPER_TIMING // For X Axes (override below) + //#define CHOPPER_TIMING_X2 CHOPPER_TIMING_X + //#define CHOPPER_TIMING_Y CHOPPER_TIMING // For Y Axes (override below) + //#define CHOPPER_TIMING_Y2 CHOPPER_TIMING_Y + //#define CHOPPER_TIMING_Z CHOPPER_TIMING // For Z Axes (override below) + //#define CHOPPER_TIMING_Z2 CHOPPER_TIMING_Z + //#define CHOPPER_TIMING_Z3 CHOPPER_TIMING_Z + //#define CHOPPER_TIMING_Z4 CHOPPER_TIMING_Z + //#define CHOPPER_TIMING_E CHOPPER_TIMING // For Extruders (override below) + //#define CHOPPER_TIMING_E1 CHOPPER_TIMING_E + //#define CHOPPER_TIMING_E2 CHOPPER_TIMING_E + //#define CHOPPER_TIMING_E3 CHOPPER_TIMING_E + //#define CHOPPER_TIMING_E4 CHOPPER_TIMING_E + //#define CHOPPER_TIMING_E5 CHOPPER_TIMING_E + //#define CHOPPER_TIMING_E6 CHOPPER_TIMING_E + //#define CHOPPER_TIMING_E7 CHOPPER_TIMING_E /** * Monitor Trinamic drivers @@ -2557,6 +2880,9 @@ #define Z2_HYBRID_THRESHOLD 3 #define Z3_HYBRID_THRESHOLD 3 #define Z4_HYBRID_THRESHOLD 3 + #define I_HYBRID_THRESHOLD 3 + #define J_HYBRID_THRESHOLD 3 + #define K_HYBRID_THRESHOLD 3 #define E0_HYBRID_THRESHOLD 30 #define E1_HYBRID_THRESHOLD 30 #define E2_HYBRID_THRESHOLD 30 @@ -2582,7 +2908,7 @@ * * It is recommended to set HOMING_BUMP_MM to { 0, 0, 0 }. * - * SPI_ENDSTOPS *** Beta feature! *** TMC2130 Only *** + * SPI_ENDSTOPS *** Beta feature! *** 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. * @@ -2603,6 +2929,9 @@ //#define Z2_STALL_SENSITIVITY Z_STALL_SENSITIVITY //#define Z3_STALL_SENSITIVITY Z_STALL_SENSITIVITY //#define Z4_STALL_SENSITIVITY Z_STALL_SENSITIVITY + //#define I_STALL_SENSITIVITY 8 + //#define J_STALL_SENSITIVITY 8 + //#define K_STALL_SENSITIVITY 8 //#define SPI_ENDSTOPS // TMC2130 only //#define IMPROVE_HOMING_RELIABILITY #endif @@ -2627,7 +2956,7 @@ /** * Enable M122 debugging command for TMC stepper drivers. - * M122 S0/1 will enable continous reporting. + * M122 S0/1 will enable continuous reporting. */ //#define TMC_DEBUG @@ -2681,138 +3010,165 @@ #endif #if AXIS_IS_L64XX(X2) - #define X2_MICROSTEPS 128 - #define X2_OVERCURRENT 2000 - #define X2_STALLCURRENT 1500 - #define X2_MAX_VOLTAGE 127 - #define X2_CHAIN_POS -1 - #define X2_SLEW_RATE 1 + #define X2_MICROSTEPS X_MICROSTEPS + #define X2_OVERCURRENT 2000 + #define X2_STALLCURRENT 1500 + #define X2_MAX_VOLTAGE 127 + #define X2_CHAIN_POS -1 + #define X2_SLEW_RATE 1 #endif #if AXIS_IS_L64XX(Y) - #define Y_MICROSTEPS 128 - #define Y_OVERCURRENT 2000 - #define Y_STALLCURRENT 1500 - #define Y_MAX_VOLTAGE 127 - #define Y_CHAIN_POS -1 - #define Y_SLEW_RATE 1 + #define Y_MICROSTEPS 128 + #define Y_OVERCURRENT 2000 + #define Y_STALLCURRENT 1500 + #define Y_MAX_VOLTAGE 127 + #define Y_CHAIN_POS -1 + #define Y_SLEW_RATE 1 #endif #if AXIS_IS_L64XX(Y2) - #define Y2_MICROSTEPS 128 - #define Y2_OVERCURRENT 2000 - #define Y2_STALLCURRENT 1500 - #define Y2_MAX_VOLTAGE 127 - #define Y2_CHAIN_POS -1 - #define Y2_SLEW_RATE 1 + #define Y2_MICROSTEPS Y_MICROSTEPS + #define Y2_OVERCURRENT 2000 + #define Y2_STALLCURRENT 1500 + #define Y2_MAX_VOLTAGE 127 + #define Y2_CHAIN_POS -1 + #define Y2_SLEW_RATE 1 #endif #if AXIS_IS_L64XX(Z) - #define Z_MICROSTEPS 128 - #define Z_OVERCURRENT 2000 - #define Z_STALLCURRENT 1500 - #define Z_MAX_VOLTAGE 127 - #define Z_CHAIN_POS -1 - #define Z_SLEW_RATE 1 + #define Z_MICROSTEPS 128 + #define Z_OVERCURRENT 2000 + #define Z_STALLCURRENT 1500 + #define Z_MAX_VOLTAGE 127 + #define Z_CHAIN_POS -1 + #define Z_SLEW_RATE 1 #endif #if AXIS_IS_L64XX(Z2) - #define Z2_MICROSTEPS 128 - #define Z2_OVERCURRENT 2000 - #define Z2_STALLCURRENT 1500 - #define Z2_MAX_VOLTAGE 127 - #define Z2_CHAIN_POS -1 - #define Z2_SLEW_RATE 1 + #define Z2_MICROSTEPS Z_MICROSTEPS + #define Z2_OVERCURRENT 2000 + #define Z2_STALLCURRENT 1500 + #define Z2_MAX_VOLTAGE 127 + #define Z2_CHAIN_POS -1 + #define Z2_SLEW_RATE 1 #endif #if AXIS_IS_L64XX(Z3) - #define Z3_MICROSTEPS 128 - #define Z3_OVERCURRENT 2000 - #define Z3_STALLCURRENT 1500 - #define Z3_MAX_VOLTAGE 127 - #define Z3_CHAIN_POS -1 - #define Z3_SLEW_RATE 1 + #define Z3_MICROSTEPS Z_MICROSTEPS + #define Z3_OVERCURRENT 2000 + #define Z3_STALLCURRENT 1500 + #define Z3_MAX_VOLTAGE 127 + #define Z3_CHAIN_POS -1 + #define Z3_SLEW_RATE 1 #endif #if AXIS_IS_L64XX(Z4) - #define Z4_MICROSTEPS 128 - #define Z4_OVERCURRENT 2000 - #define Z4_STALLCURRENT 1500 - #define Z4_MAX_VOLTAGE 127 - #define Z4_CHAIN_POS -1 - #define Z4_SLEW_RATE 1 + #define Z4_MICROSTEPS Z_MICROSTEPS + #define Z4_OVERCURRENT 2000 + #define Z4_STALLCURRENT 1500 + #define Z4_MAX_VOLTAGE 127 + #define Z4_CHAIN_POS -1 + #define Z4_SLEW_RATE 1 + #endif + + #if AXIS_DRIVER_TYPE_I(L6470) + #define I_MICROSTEPS 128 + #define I_OVERCURRENT 2000 + #define I_STALLCURRENT 1500 + #define I_MAX_VOLTAGE 127 + #define I_CHAIN_POS -1 + #define I_SLEW_RATE 1 + #endif + + #if AXIS_DRIVER_TYPE_J(L6470) + #define J_MICROSTEPS 128 + #define J_OVERCURRENT 2000 + #define J_STALLCURRENT 1500 + #define J_MAX_VOLTAGE 127 + #define J_CHAIN_POS -1 + #define J_SLEW_RATE 1 + #endif + + #if AXIS_DRIVER_TYPE_K(L6470) + #define K_MICROSTEPS 128 + #define K_OVERCURRENT 2000 + #define K_STALLCURRENT 1500 + #define K_MAX_VOLTAGE 127 + #define K_CHAIN_POS -1 + #define K_SLEW_RATE 1 #endif #if AXIS_IS_L64XX(E0) - #define E0_MICROSTEPS 128 - #define E0_OVERCURRENT 2000 - #define E0_STALLCURRENT 1500 - #define E0_MAX_VOLTAGE 127 - #define E0_CHAIN_POS -1 - #define E0_SLEW_RATE 1 + #define E0_MICROSTEPS 128 + #define E0_OVERCURRENT 2000 + #define E0_STALLCURRENT 1500 + #define E0_MAX_VOLTAGE 127 + #define E0_CHAIN_POS -1 + #define E0_SLEW_RATE 1 #endif #if AXIS_IS_L64XX(E1) - #define E1_MICROSTEPS 128 - #define E1_OVERCURRENT 2000 - #define E1_STALLCURRENT 1500 - #define E1_MAX_VOLTAGE 127 - #define E1_CHAIN_POS -1 - #define E1_SLEW_RATE 1 + #define E1_MICROSTEPS E0_MICROSTEPS + #define E1_OVERCURRENT 2000 + #define E1_STALLCURRENT 1500 + #define E1_MAX_VOLTAGE 127 + #define E1_CHAIN_POS -1 + #define E1_SLEW_RATE 1 #endif #if AXIS_IS_L64XX(E2) - #define E2_MICROSTEPS 128 - #define E2_OVERCURRENT 2000 - #define E2_STALLCURRENT 1500 - #define E2_MAX_VOLTAGE 127 - #define E2_CHAIN_POS -1 - #define E2_SLEW_RATE 1 + #define E2_MICROSTEPS E0_MICROSTEPS + #define E2_OVERCURRENT 2000 + #define E2_STALLCURRENT 1500 + #define E2_MAX_VOLTAGE 127 + #define E2_CHAIN_POS -1 + #define E2_SLEW_RATE 1 #endif #if AXIS_IS_L64XX(E3) - #define E3_MICROSTEPS 128 - #define E3_OVERCURRENT 2000 - #define E3_STALLCURRENT 1500 - #define E3_MAX_VOLTAGE 127 - #define E3_CHAIN_POS -1 - #define E3_SLEW_RATE 1 + #define E3_MICROSTEPS E0_MICROSTEPS + #define E3_OVERCURRENT 2000 + #define E3_STALLCURRENT 1500 + #define E3_MAX_VOLTAGE 127 + #define E3_CHAIN_POS -1 + #define E3_SLEW_RATE 1 #endif #if AXIS_IS_L64XX(E4) - #define E4_MICROSTEPS 128 - #define E4_OVERCURRENT 2000 - #define E4_STALLCURRENT 1500 - #define E4_MAX_VOLTAGE 127 - #define E4_CHAIN_POS -1 - #define E4_SLEW_RATE 1 + #define E4_MICROSTEPS E0_MICROSTEPS + #define E4_OVERCURRENT 2000 + #define E4_STALLCURRENT 1500 + #define E4_MAX_VOLTAGE 127 + #define E4_CHAIN_POS -1 + #define E4_SLEW_RATE 1 #endif #if AXIS_IS_L64XX(E5) - #define E5_MICROSTEPS 128 - #define E5_OVERCURRENT 2000 - #define E5_STALLCURRENT 1500 - #define E5_MAX_VOLTAGE 127 - #define E5_CHAIN_POS -1 - #define E5_SLEW_RATE 1 + #define E5_MICROSTEPS E0_MICROSTEPS + #define E5_OVERCURRENT 2000 + #define E5_STALLCURRENT 1500 + #define E5_MAX_VOLTAGE 127 + #define E5_CHAIN_POS -1 + #define E5_SLEW_RATE 1 #endif #if AXIS_IS_L64XX(E6) - #define E6_MICROSTEPS 128 - #define E6_OVERCURRENT 2000 - #define E6_STALLCURRENT 1500 - #define E6_MAX_VOLTAGE 127 - #define E6_CHAIN_POS -1 - #define E6_SLEW_RATE 1 + #define E6_MICROSTEPS E0_MICROSTEPS + #define E6_OVERCURRENT 2000 + #define E6_STALLCURRENT 1500 + #define E6_MAX_VOLTAGE 127 + #define E6_CHAIN_POS -1 + #define E6_SLEW_RATE 1 #endif #if AXIS_IS_L64XX(E7) - #define E7_MICROSTEPS 128 - #define E7_OVERCURRENT 2000 - #define E7_STALLCURRENT 1500 - #define E7_MAX_VOLTAGE 127 - #define E7_CHAIN_POS -1 - #define E7_SLEW_RATE 1 + #define E7_MICROSTEPS E0_MICROSTEPS + #define E7_OVERCURRENT 2000 + #define E7_STALLCURRENT 1500 + #define E7_MAX_VOLTAGE 127 + #define E7_CHAIN_POS -1 + #define E7_SLEW_RATE 1 #endif /** @@ -2948,10 +3304,22 @@ #define SPINDLE_LASER_FREQUENCY 2500 // (Hz) Spindle/laser frequency (only on supported HALs: AVR and LPC) - //#define SPINDLE_SERVO // A servo converting an angle to spindle power + //#define AIR_EVACUATION // Cutter Vacuum / Laser Blower motor control with G-codes M10-M11 + #if ENABLED(AIR_EVACUATION) + #define AIR_EVACUATION_ACTIVE LOW // Set to "HIGH" if the on/off function is active HIGH + //#define AIR_EVACUATION_PIN 42 // Override the default Cutter Vacuum or Laser Blower pin + #endif + + //#define AIR_ASSIST // Air Assist control with G-codes M8-M9 + #if ENABLED(AIR_ASSIST) + #define AIR_ASSIST_ACTIVE LOW // Active state on air assist pin + //#define AIR_ASSIST_PIN 44 // Override the default Air Assist pin + #endif + + //#define SPINDLE_SERVO // A servo converting an angle to spindle power #ifdef SPINDLE_SERVO - #define SPINDLE_SERVO_NR 0 // Index of servo used for spindle control - #define SPINDLE_SERVO_MIN 10 // Minimum angle for servo spindle + #define SPINDLE_SERVO_NR 0 // Index of servo used for spindle control + #define SPINDLE_SERVO_MIN 10 // Minimum angle for servo spindle #endif /** @@ -3002,6 +3370,10 @@ #define SPEED_POWER_MAX 100 // (%) 0-100 #define SPEED_POWER_STARTUP 80 // (%) M3/M4 speed/power default (with no arguments) + // Define the minimum and maximum test pulse time values for a laser test fire function + #define LASER_TEST_PULSE_MIN 1 // Used with Laser Control Menu + #define LASER_TEST_PULSE_MAX 999 // Caution: Menu may not show more than 3 characters + /** * Enable inline laser power to be handled in the planner / stepper routines. * Inline power is specified by the I (inline) flag in an M3 command (e.g., M3 S20 I) @@ -3076,8 +3448,30 @@ #define SPINDLE_LASER_POWERDOWN_DELAY 50 // (ms) Delay to allow the spindle to stop #endif + + // + // Laser I2C Ammeter (High precision INA226 low/high side module) + // + //#define I2C_AMMETER + #if ENABLED(I2C_AMMETER) + #define I2C_AMMETER_IMAX 0.1 // (Amps) Calibration value for the expected current range + #define I2C_AMMETER_SHUNT_RESISTOR 0.1 // (Ohms) Calibration shunt resistor value + #endif + #endif -#endif +#endif // SPINDLE_FEATURE || LASER_FEATURE + +/** + * Synchronous Laser Control with M106/M107 + * + * Marlin normally applies M106/M107 fan speeds at a time "soon after" processing + * a planner block. This is too inaccurate for a PWM/TTL laser attached to the fan + * header (as with some add-on laser kits). Enable this option to set fan/laser + * speeds with much more exact timing for improved print fidelity. + * + * NOTE: This option sacrifices some cooling fan speed options. + */ +//#define LASER_SYNCHRONOUS_M106_M107 /** * Coolant Control @@ -3138,13 +3532,27 @@ */ //#define POWER_MONITOR_CURRENT // Monitor the system current //#define POWER_MONITOR_VOLTAGE // Monitor the system voltage -#if EITHER(POWER_MONITOR_CURRENT, POWER_MONITOR_VOLTAGE) - #define POWER_MONITOR_VOLTS_PER_AMP 0.05000 // Input voltage to the MCU analog pin per amp - DO NOT apply more than ADC_VREF! - #define POWER_MONITOR_CURRENT_OFFSET -1 // Offset value for current sensors with linear function output - #define POWER_MONITOR_VOLTS_PER_VOLT 0.11786 // Input voltage to the MCU analog pin per volt - DO NOT apply more than ADC_VREF! + +#if ENABLED(POWER_MONITOR_CURRENT) + #define POWER_MONITOR_VOLTS_PER_AMP 0.05000 // Input voltage to the MCU analog pin per amp - DO NOT apply more than ADC_VREF! + #define POWER_MONITOR_CURRENT_OFFSET 0 // Offset (in amps) applied to the calculated current #define POWER_MONITOR_FIXED_VOLTAGE 13.6 // Voltage for a current sensor with no voltage sensor (for power display) #endif +#if ENABLED(POWER_MONITOR_VOLTAGE) + #define POWER_MONITOR_VOLTS_PER_VOLT 0.077933 // Input voltage to the MCU analog pin per volt - DO NOT apply more than ADC_VREF! + #define POWER_MONITOR_VOLTAGE_OFFSET 0 // Offset (in volts) applied to the calculated voltage +#endif + +/** + * Stepper Driver Anti-SNAFU Protection + * + * If the SAFE_POWER_PIN is defined for your board, Marlin will check + * that stepper drivers are properly plugged in before applying power. + * Disable protection if your stepper drivers don't support the feature. + */ +//#define DISABLE_DRIVER_SAFE_POWER_PROTECT + /** * CNC Coordinate Systems * @@ -3158,6 +3566,11 @@ */ #define AUTO_REPORT_TEMPERATURES +/** + * Auto-report position with M154 S + */ +//#define AUTO_REPORT_POSITION + /** * Include capabilities in M115 output */ @@ -3227,7 +3640,7 @@ #define PROPORTIONAL_FONT_RATIO 1.0 /** - * Spend 28 bytes of SRAM to optimize the GCode parser + * Spend 28 bytes of SRAM to optimize the G-code parser */ #define FASTER_GCODE_PARSER @@ -3235,6 +3648,10 @@ //#define GCODE_QUOTED_STRINGS // Support for quoted string parameters #endif +// Support for MeatPack G-code compression (https://github.com/scottmudge/OctoPrint-MeatPack) +//#define MEATPACK_ON_SERIAL_PORT_1 +//#define MEATPACK_ON_SERIAL_PORT_2 + //#define GCODE_CASE_INSENSITIVE // Accept G-code sent to the firmware in lowercase //#define REPETIER_GCODE_M360 // Add commands originally from Repetier FW @@ -3274,29 +3691,99 @@ #endif /** - * User-defined menu items that execute custom GCode + * User-defined menu items to run custom G-code. + * Up to 25 may be defined, but the actual number is LCD-dependent. */ -//#define CUSTOM_USER_MENUS -#if ENABLED(CUSTOM_USER_MENUS) - //#define CUSTOM_USER_MENU_TITLE "Custom Commands" - #define USER_SCRIPT_DONE "M117 User Script Done" - #define USER_SCRIPT_AUDIBLE_FEEDBACK - //#define USER_SCRIPT_RETURN // Return to status screen after a script - #define USER_DESC_1 "Home & UBL Info" - #define USER_GCODE_1 "G28\nG29 W" +// Custom Menu: Main Menu +//#define CUSTOM_MENU_MAIN +#if ENABLED(CUSTOM_MENU_MAIN) + //#define CUSTOM_MENU_MAIN_TITLE "Custom Commands" + #define CUSTOM_MENU_MAIN_SCRIPT_DONE "M117 User Script Done" + #define CUSTOM_MENU_MAIN_SCRIPT_AUDIBLE_FEEDBACK + //#define CUSTOM_MENU_MAIN_SCRIPT_RETURN // Return to status screen after a script + #define CUSTOM_MENU_MAIN_ONLY_IDLE // Only show custom menu when the machine is idle + + #define MAIN_MENU_ITEM_1_DESC "Home & UBL Info" + #define MAIN_MENU_ITEM_1_GCODE "G28\nG29 W" + //#define MAIN_MENU_ITEM_1_CONFIRM // Show a confirmation dialog before this action + + #define MAIN_MENU_ITEM_2_DESC "Preheat for " PREHEAT_1_LABEL + #define MAIN_MENU_ITEM_2_GCODE "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) + //#define MAIN_MENU_ITEM_2_CONFIRM + + //#define MAIN_MENU_ITEM_3_DESC "Preheat for " PREHEAT_2_LABEL + //#define MAIN_MENU_ITEM_3_GCODE "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) + //#define MAIN_MENU_ITEM_3_CONFIRM + + //#define MAIN_MENU_ITEM_4_DESC "Heat Bed/Home/Level" + //#define MAIN_MENU_ITEM_4_GCODE "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29" + //#define MAIN_MENU_ITEM_4_CONFIRM + + //#define MAIN_MENU_ITEM_5_DESC "Home & Info" + //#define MAIN_MENU_ITEM_5_GCODE "G28\nM503" + //#define MAIN_MENU_ITEM_5_CONFIRM +#endif - #define USER_DESC_2 "Preheat for " PREHEAT_1_LABEL - #define USER_GCODE_2 "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) +// Custom Menu: Configuration Menu +//#define CUSTOM_MENU_CONFIG +#if ENABLED(CUSTOM_MENU_CONFIG) + //#define CUSTOM_MENU_CONFIG_TITLE "Custom Commands" + #define CUSTOM_MENU_CONFIG_SCRIPT_DONE "M117 Wireless Script Done" + #define CUSTOM_MENU_CONFIG_SCRIPT_AUDIBLE_FEEDBACK + //#define CUSTOM_MENU_CONFIG_SCRIPT_RETURN // Return to status screen after a script + #define CUSTOM_MENU_CONFIG_ONLY_IDLE // Only show custom menu when the machine is idle + + #define CONFIG_MENU_ITEM_1_DESC "Wifi ON" + #define CONFIG_MENU_ITEM_1_GCODE "M118 [ESP110] WIFI-STA pwd=12345678" + //#define CONFIG_MENU_ITEM_1_CONFIRM // Show a confirmation dialog before this action + + #define CONFIG_MENU_ITEM_2_DESC "Bluetooth ON" + #define CONFIG_MENU_ITEM_2_GCODE "M118 [ESP110] BT pwd=12345678" + //#define CONFIG_MENU_ITEM_2_CONFIRM + + //#define CONFIG_MENU_ITEM_3_DESC "Radio OFF" + //#define CONFIG_MENU_ITEM_3_GCODE "M118 [ESP110] OFF pwd=12345678" + //#define CONFIG_MENU_ITEM_3_CONFIRM + + //#define CONFIG_MENU_ITEM_4_DESC "Wifi ????" + //#define CONFIG_MENU_ITEM_4_GCODE "M118 ????" + //#define CONFIG_MENU_ITEM_4_CONFIRM + + //#define CONFIG_MENU_ITEM_5_DESC "Wifi ????" + //#define CONFIG_MENU_ITEM_5_GCODE "M118 ????" + //#define CONFIG_MENU_ITEM_5_CONFIRM +#endif - #define USER_DESC_3 "Preheat for " PREHEAT_2_LABEL - #define USER_GCODE_3 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) +/** + * User-defined buttons to run custom G-code. + * Up to 25 may be defined. + */ +//#define CUSTOM_USER_BUTTONS +#if ENABLED(CUSTOM_USER_BUTTONS) + //#define BUTTON1_PIN -1 + #if PIN_EXISTS(BUTTON1) + #define BUTTON1_HIT_STATE LOW // State of the triggered button. NC=LOW. NO=HIGH. + #define BUTTON1_WHEN_PRINTING false // Button allowed to trigger during printing? + #define BUTTON1_GCODE "G28" + #define BUTTON1_DESC "Homing" // Optional string to set the LCD status + #endif - #define USER_DESC_4 "Heat Bed/Home/Level" - #define USER_GCODE_4 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29" + //#define BUTTON2_PIN -1 + #if PIN_EXISTS(BUTTON2) + #define BUTTON2_HIT_STATE LOW + #define BUTTON2_WHEN_PRINTING false + #define BUTTON2_GCODE "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) + #define BUTTON2_DESC "Preheat for " PREHEAT_1_LABEL + #endif - #define USER_DESC_5 "Home & Info" - #define USER_GCODE_5 "G28\nM503" + //#define BUTTON3_PIN -1 + #if PIN_EXISTS(BUTTON3) + #define BUTTON3_HIT_STATE LOW + #define BUTTON3_WHEN_PRINTING false + #define BUTTON3_GCODE "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) + #define BUTTON3_DESC "Preheat for " PREHEAT_2_LABEL + #endif #endif /** @@ -3325,6 +3812,9 @@ * Implement M486 to allow Marlin to skip objects */ //#define CANCEL_OBJECTS +#if ENABLED(CANCEL_OBJECTS) + #define CANCEL_OBJECTS_REPORTING // Emit the current object as a status message +#endif /** * I2C position encoders for closed loop control. @@ -3401,7 +3891,7 @@ */ #define I2CPE_MIN_UPD_TIME_MS 4 // (ms) Minimum time between encoder checks. - // Use a rolling average to identify persistant errors that indicate skips, as opposed to vibration and noise. + // Use a rolling average to identify persistent errors that indicate skips, as opposed to vibration and noise. #define I2CPE_ERR_ROLLING_AVERAGE #endif // I2C_POSITION_ENCODERS @@ -3440,12 +3930,22 @@ #define GANTRY_CALIBRATION_FEEDRATE 500 // Feedrate for correction move //#define GANTRY_CALIBRATION_TO_MIN // Enable to calibrate Z in the MIN direction - //#define GANTRY_CALIBRATION_SAFE_POSITION { X_CENTER, Y_CENTER } // Safe position for nozzle + //#define GANTRY_CALIBRATION_SAFE_POSITION XY_CENTER // Safe position for nozzle //#define GANTRY_CALIBRATION_XY_PARK_FEEDRATE 3000 // XY Park Feedrate - MMM //#define GANTRY_CALIBRATION_COMMANDS_PRE "" #define GANTRY_CALIBRATION_COMMANDS_POST "G28" // G28 highly recommended to ensure an accurate position #endif +/** + * Instant freeze / unfreeze functionality + * Specified pin has pullup and connecting to ground will instantly pause motion. + * Potentially useful for emergency stop that allows being resumed. + */ +//#define FREEZE_FEATURE +#if ENABLED(FREEZE_FEATURE) + //#define FREEZE_PIN 41 // Override the default (KILL) pin here +#endif + /** * MAX7219 Debug Matrix * @@ -3482,14 +3982,20 @@ /** * NanoDLP Sync support * - * Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp" - * string to enable synchronization with DLP projector exposure. This change will allow to use - * [[WaitForDoneMessage]] instead of populating your gcode with M400 commands + * Support for Synchronized Z moves when used with NanoDLP. G0/G1 axis moves will + * output a "Z_move_comp" string to enable synchronization with DLP projector exposure. + * This feature allows you to use [[WaitForDoneMessage]] instead of M400 commands. */ //#define NANODLP_Z_SYNC #if ENABLED(NANODLP_Z_SYNC) - //#define NANODLP_ALL_AXIS // Enables "Z_move_comp" output on any axis move. - // Default behavior is limited to Z axis only. + //#define NANODLP_ALL_AXIS // Send a "Z_move_comp" report for any axis move (not just Z). +#endif + +/** + * Ethernet. Use M552 to enable and set the IP address. + */ +#if HAS_ETHERNET + #define MAC_ADDRESS { 0xDE, 0xAD, 0xBE, 0xEF, 0xF0, 0x0D } // A MAC address unique to your network #endif /** @@ -3522,16 +4028,26 @@ #endif /** - * Průša Multi-Material Unit v2 + * Průša Multi-Material Unit (MMU) * Enable in Configuration.h + * + * These devices allow a single stepper driver on the board to drive + * multi-material feeders with any number of stepper motors. */ -#if ENABLED(PRUSA_MMU2) - +#if HAS_PRUSA_MMU1 + /** + * This option only allows the multiplexer to switch on tool-change. + * Additional options to configure custom E moves are pending. + * + * Override the default DIO selector pins here, if needed. + * Some pins files may provide defaults for these pins. + */ + //#define E_MUX0_PIN 40 // Always Required + //#define E_MUX1_PIN 42 // Needed for 3 to 8 inputs + //#define E_MUX2_PIN 44 // Needed for 5 to 8 inputs +#elif HAS_PRUSA_MMU2 // Serial port used for communication with MMU2. - // For AVR enable the UART port used for the MMU. (e.g., mmuSerial) - // For 32-bit boards check your HAL for available serial ports. (e.g., Serial2) #define MMU2_SERIAL_PORT 2 - #define MMU2_SERIAL mmuSerial // Use hardware reset for MMU if a pin is defined for it //#define MMU2_RST_PIN 23 @@ -3544,44 +4060,29 @@ // Add an LCD menu for MMU2 //#define MMU2_MENUS - - // Settings for filament load / unload. - // 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 } - - /** - * MMU Extruder Sensor - * - * Support for a Průša (or other) IR Sensor to detect filament near the extruder - * and make loading more reliable. Suitable for an extruder equipped with a filament - * sensor less than 38mm from the gears. - * - * During loading the extruder will stop when the sensor is triggered, then do a last - * move up to the gears. If no filament is detected, the MMU2 can make some more attempts. - * If all attempts fail, a filament runout will be triggered. - */ - //#define MMU_EXTRUDER_SENSOR - #if ENABLED(MMU_EXTRUDER_SENSOR) - #define MMU_LOADING_ATTEMPTS_NR 5 // max. number of attempts to load filament if first load fail + #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 /** @@ -3589,8 +4090,7 @@ * 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 */ - //#define PRUSA_MMU2_S_MODE - #if ENABLED(PRUSA_MMU2_S_MODE) + #if HAS_PRUSA_MMU2S #define MMU2_C0_RETRY 5 // Number of retries (total time = timeout*retries) #define MMU2_CAN_LOAD_FEEDRATE 800 // (mm/min) @@ -3606,11 +4106,29 @@ #define MMU2_CAN_LOAD_INCREMENT_SEQUENCE \ { -MMU2_CAN_LOAD_INCREMENT, MMU2_CAN_LOAD_FEEDRATE } + #else + + /** + * MMU1 Extruder Sensor + * + * Support for a Průša (or other) IR Sensor to detect filament near the extruder + * and make loading more reliable. Suitable for an extruder equipped with a filament + * sensor less than 38mm from the gears. + * + * During loading the extruder will stop when the sensor is triggered, then do a last + * move up to the gears. If no filament is detected, the MMU2 can make some more attempts. + * If all attempts fail, a filament runout will be triggered. + */ + //#define MMU_EXTRUDER_SENSOR + #if ENABLED(MMU_EXTRUDER_SENSOR) + #define MMU_LOADING_ATTEMPTS_NR 5 // max. number of attempts to load filament if first load fail + #endif + #endif //#define MMU2_DEBUG // Write debug info to serial output -#endif // PRUSA_MMU2 +#endif // HAS_PRUSA_MMU2 /** * Advanced Print Counter settings @@ -3645,3 +4163,16 @@ // Enable Marlin dev mode which adds some special commands //#define MARLIN_DEV_MODE + +/** + * Postmortem Debugging captures misbehavior and outputs the CPU status and backtrace to serial. + * When running in the debugger it will break for debugging. This is useful to help understand + * a crash from a remote location. Requires ~400 bytes of SRAM and 5Kb of flash. + */ +//#define POSTMORTEM_DEBUGGING + +/** + * Software Reset options + */ +//#define SOFT_RESET_VIA_SERIAL // 'KILL' and '^X' commands will soft-reset the controller +//#define SOFT_RESET_ON_KILL // Use a digital button to soft-reset the controller after KILL diff --git a/Marlin/Makefile b/Marlin/Makefile index 49cb960b92fe..d09e5828f5b2 100644 --- a/Marlin/Makefile +++ b/Marlin/Makefile @@ -110,7 +110,7 @@ LIQUID_TWI2 ?= 0 WIRE ?= 0 # This defines if Tone is needed (i.e SPEAKER is defined in Configuration.h) -# Disabling this (and SPEAKER) saves approximatively 350 bytes of memory. +# Disabling this (and SPEAKER) saves approximately 350 bytes of memory. TONE ?= 1 # This defines if U8GLIB is needed (may require RELOC_WORKAROUND) @@ -219,7 +219,7 @@ else ifeq ($(HARDWARE_MOTHERBOARD),1111) else ifeq ($(HARDWARE_MOTHERBOARD),1112) # MKS GEN L else ifeq ($(HARDWARE_MOTHERBOARD),1113) -# zrib V2.0 control board (Chinese knock off RAMPS replica) +# zrib V2.0 control board (Chinese RAMPS replica) else ifeq ($(HARDWARE_MOTHERBOARD),1114) # BigTreeTech or BIQU KFB2.0 else ifeq ($(HARDWARE_MOTHERBOARD),1115) @@ -323,6 +323,8 @@ else ifeq ($(HARDWARE_MOTHERBOARD),1203) else ifeq ($(HARDWARE_MOTHERBOARD),1204) # abee Scoovo X9H else ifeq ($(HARDWARE_MOTHERBOARD),1205) +# Rambo ThinkerV2 +else ifeq ($(HARDWARE_MOTHERBOARD),1206) # # Other ATmega1280, ATmega2560 @@ -991,5 +993,5 @@ clean: .PHONY: all build elf hex eep lss sym program coff extcoff clean depend sizebefore sizeafter -# Automaticaly include the dependency files created by gcc +# Automatically include the dependency files created by gcc -include ${patsubst %.o, %.d, ${OBJ}} diff --git a/Marlin/Version.h b/Marlin/Version.h index 60e068ba3521..2a5f451c7918 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -28,7 +28,7 @@ /** * Marlin release version identifier */ -//#define SHORT_BUILD_VERSION "2.0.7.2" +//#define SHORT_BUILD_VERSION "2.0.9.1" /** * 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 "2020-07-09" +//#define STRING_DISTRIBUTION_DATE "2021-06-27" /** * Defines a generic printer name to be output to the LCD after booting Marlin. @@ -54,7 +54,7 @@ * has a distinct Github fork— the Source Code URL should just be the main * Marlin repository. */ -//#define SOURCE_CODE_URL "https://github.com/MarlinFirmware/Marlin" +//#define SOURCE_CODE_URL "github.com/MarlinFirmware/Marlin" /** * Default generic printer UUID. @@ -65,7 +65,7 @@ * The WEBSITE_URL is the location where users can get more information such as * documentation about a specific Marlin release. */ -//#define WEBSITE_URL "https://marlinfw.org" +//#define WEBSITE_URL "marlinfw.org" /** * Set the vendor info the serial USB interface, if changable diff --git a/Marlin/src/HAL/AVR/HAL.cpp b/Marlin/src/HAL/AVR/HAL.cpp index 58d57c8ee54b..708583b262a6 100644 --- a/Marlin/src/HAL/AVR/HAL.cpp +++ b/Marlin/src/HAL/AVR/HAL.cpp @@ -24,6 +24,13 @@ #include "../../inc/MarlinConfig.h" #include "HAL.h" +#ifdef USBCON + DefaultSerial1 MSerial0(false, Serial); + #ifdef BLUETOOTH + BTSerial btSerial(false, bluetoothSerial); + #endif +#endif + // ------------------------ // Public Variables // ------------------------ @@ -51,6 +58,15 @@ void HAL_init() { #endif } +void HAL_reboot() { + #if ENABLED(USE_WATCHDOG) + while (1) { /* run out the watchdog */ } + #else + void (*resetFunc)() = 0; // Declare resetFunc() at address 0 + resetFunc(); // Jump to address 0 + #endif +} + #if ENABLED(SDSUPPORT) #include "../../sd/SdFatUtil.h" diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h index 6e0afa8f10ed..a5896a0e970f 100644 --- a/Marlin/src/HAL/AVR/HAL.h +++ b/Marlin/src/HAL/AVR/HAL.h @@ -25,7 +25,7 @@ #include "watchdog.h" #include "math.h" -#ifdef IS_AT90USB +#ifdef USBCON #include #else #define HardwareSerial_h // Hack to prevent HardwareSerial.h header inclusion @@ -81,25 +81,47 @@ typedef int8_t pin_t; //extern uint8_t MCUSR; // Serial ports -#ifdef IS_AT90USB - #define MYSERIAL0 TERN(BLUETOOTH, bluetoothSerial, Serial) +#ifdef USBCON + #include "../../core/serial_hook.h" + typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1; + extern DefaultSerial1 MSerial0; + #ifdef BLUETOOTH + typedef ForwardSerial1Class< decltype(bluetoothSerial) > BTSerial; + extern BTSerial btSerial; + #endif + + #define MYSERIAL1 TERN(BLUETOOTH, btSerial, MSerial0) #else #if !WITHIN(SERIAL_PORT, -1, 3) - #error "SERIAL_PORT must be from -1 to 3. Please update your configuration." + #error "SERIAL_PORT must be from 0 to 3, or -1 for USB Serial." #endif - #define MYSERIAL0 customizedSerial1 + #define MYSERIAL1 customizedSerial1 #ifdef SERIAL_PORT_2 #if !WITHIN(SERIAL_PORT_2, -1, 3) - #error "SERIAL_PORT_2 must be from -1 to 3. Please update your configuration." + #error "SERIAL_PORT_2 must be from 0 to 3, or -1 for USB Serial." #endif - #define MYSERIAL1 customizedSerial2 + #define MYSERIAL2 customizedSerial2 + #endif + + #ifdef SERIAL_PORT_3 + #if !WITHIN(SERIAL_PORT_3, -1, 3) + #error "SERIAL_PORT_3 must be from 0 to 3, or -1 for USB Serial." + #endif + #define MYSERIAL3 customizedSerial3 #endif #endif +#ifdef MMU2_SERIAL_PORT + #if !WITHIN(MMU2_SERIAL_PORT, -1, 3) + #error "MMU2_SERIAL_PORT must be from 0 to 3, or -1 for USB Serial." + #endif + #define MMU2_SERIAL mmuSerial +#endif + #ifdef LCD_SERIAL_PORT #if !WITHIN(LCD_SERIAL_PORT, -1, 3) - #error "LCD_SERIAL_PORT must be from -1 to 3. Please update your configuration." + #error "LCD_SERIAL_PORT must be from 0 to 3, or -1 for USB Serial." #endif #define LCD_SERIAL lcdSerial #if HAS_DGUS_LCD @@ -120,14 +142,18 @@ void HAL_init(); inline void HAL_clear_reset_source() { MCUSR = 0; } inline uint8_t HAL_get_reset_source() { return MCUSR; } -inline void HAL_reboot() {} // reboot the board or restart the bootloader +void HAL_reboot(); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-function" -extern "C" { - int freeMemory(); -} -#pragma GCC diagnostic pop +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + +extern "C" int freeMemory(); + +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic pop +#endif // ADC #ifdef DIDR2 @@ -160,7 +186,7 @@ inline void HAL_adc_init() { #define GET_PIN_MAP_INDEX(pin) pin #define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) -#define HAL_SENSITIVE_PINS 0, 1 +#define HAL_SENSITIVE_PINS 0, 1, #ifdef __AVR_AT90USB1286__ #define JTAG_DISABLE() do{ MCUCR = 0x80; MCUCR = 0x80; }while(0) diff --git a/Marlin/src/HAL/AVR/HAL_SPI.cpp b/Marlin/src/HAL/AVR/HAL_SPI.cpp index 31e589746cf2..1a1b98b3dd2a 100644 --- a/Marlin/src/HAL/AVR/HAL_SPI.cpp +++ b/Marlin/src/HAL/AVR/HAL_SPI.cpp @@ -34,17 +34,17 @@ #include "../../inc/MarlinConfig.h" void spiBegin() { - OUT_WRITE(SS_PIN, HIGH); - SET_OUTPUT(SCK_PIN); - SET_INPUT(MISO_PIN); - SET_OUTPUT(MOSI_PIN); + OUT_WRITE(SD_SS_PIN, HIGH); + SET_OUTPUT(SD_SCK_PIN); + SET_INPUT(SD_MISO_PIN); + SET_OUTPUT(SD_MOSI_PIN); #if DISABLED(SOFTWARE_SPI) // SS must be in output mode even it is not chip select - //SET_OUTPUT(SS_PIN); + //SET_OUTPUT(SD_SS_PIN); // set SS high - may be chip select for another SPI device //#if SET_SPI_SS_HIGH - //WRITE(SS_PIN, HIGH); + //WRITE(SD_SS_PIN, HIGH); //#endif // set a default rate spiInit(1); @@ -88,7 +88,7 @@ void spiBegin() { } /** SPI read data */ - void spiRead(uint8_t* buf, uint16_t nbyte) { + void spiRead(uint8_t *buf, uint16_t nbyte) { if (nbyte-- == 0) return; SPDR = 0xFF; for (uint16_t i = 0; i < nbyte; i++) { @@ -107,7 +107,7 @@ void spiBegin() { } /** SPI send block */ - void spiSendBlock(uint8_t token, const uint8_t* buf) { + void spiSendBlock(uint8_t token, const uint8_t *buf) { SPDR = token; for (uint16_t i = 0; i < 512; i += 2) { while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } @@ -195,19 +195,19 @@ void spiBegin() { // no interrupts during byte receive - about 8µs cli(); // output pin high - like sending 0xFF - WRITE(MOSI_PIN, HIGH); + WRITE(SD_MOSI_PIN, HIGH); LOOP_L_N(i, 8) { - WRITE(SCK_PIN, HIGH); + WRITE(SD_SCK_PIN, HIGH); nop; // adjust so SCK is nice nop; data <<= 1; - if (READ(MISO_PIN)) data |= 1; + if (READ(SD_MISO_PIN)) data |= 1; - WRITE(SCK_PIN, LOW); + WRITE(SD_SCK_PIN, LOW); } sei(); @@ -215,7 +215,7 @@ void spiBegin() { } // Soft SPI read data - void spiRead(uint8_t* buf, uint16_t nbyte) { + void spiRead(uint8_t *buf, uint16_t nbyte) { for (uint16_t i = 0; i < nbyte; i++) buf[i] = spiRec(); } @@ -225,10 +225,10 @@ void spiBegin() { // no interrupts during byte send - about 8µs cli(); LOOP_L_N(i, 8) { - WRITE(SCK_PIN, LOW); - WRITE(MOSI_PIN, data & 0x80); + WRITE(SD_SCK_PIN, LOW); + WRITE(SD_MOSI_PIN, data & 0x80); data <<= 1; - WRITE(SCK_PIN, HIGH); + WRITE(SD_SCK_PIN, HIGH); } nop; // hold SCK high for a few ns @@ -236,13 +236,13 @@ void spiBegin() { nop; nop; - WRITE(SCK_PIN, LOW); + WRITE(SD_SCK_PIN, LOW); sei(); } // Soft SPI send block - void spiSendBlock(uint8_t token, const uint8_t* buf) { + void spiSendBlock(uint8_t token, const uint8_t *buf) { spiSend(token); for (uint16_t i = 0; i < 512; i++) spiSend(buf[i]); diff --git a/Marlin/src/HAL/AVR/MarlinSerial.cpp b/Marlin/src/HAL/AVR/MarlinSerial.cpp index 8feac32aa74c..cd8bf5e6903b 100644 --- a/Marlin/src/HAL/AVR/MarlinSerial.cpp +++ b/Marlin/src/HAL/AVR/MarlinSerial.cpp @@ -38,7 +38,7 @@ #include "../../inc/MarlinConfig.h" -#if !IS_AT90USB && (defined(UBRRH) || defined(UBRR0H) || defined(UBRR1H) || defined(UBRR2H) || defined(UBRR3H)) +#if !defined(USBCON) && (defined(UBRRH) || defined(UBRR0H) || defined(UBRR1H) || defined(UBRR2H) || defined(UBRR3H)) #include "MarlinSerial.h" #include "../../MarlinCore.h" @@ -556,161 +556,6 @@ void MarlinSerial::flushTX() { } } -/** - * Imports from print.h - */ - -template -void MarlinSerial::print(char c, int base) { - print((long)c, base); -} - -template -void MarlinSerial::print(unsigned char b, int base) { - print((unsigned long)b, base); -} - -template -void MarlinSerial::print(int n, int base) { - print((long)n, base); -} - -template -void MarlinSerial::print(unsigned int n, int base) { - print((unsigned long)n, base); -} - -template -void MarlinSerial::print(long n, int base) { - if (base == 0) write(n); - else if (base == 10) { - if (n < 0) { print('-'); n = -n; } - printNumber(n, 10); - } - else - printNumber(n, base); -} - -template -void MarlinSerial::print(unsigned long n, int base) { - if (base == 0) write(n); - else printNumber(n, base); -} - -template -void MarlinSerial::print(double n, int digits) { - printFloat(n, digits); -} - -template -void MarlinSerial::println() { - print('\r'); - print('\n'); -} - -template -void MarlinSerial::println(const String& s) { - print(s); - println(); -} - -template -void MarlinSerial::println(const char c[]) { - print(c); - println(); -} - -template -void MarlinSerial::println(char c, int base) { - print(c, base); - println(); -} - -template -void MarlinSerial::println(unsigned char b, int base) { - print(b, base); - println(); -} - -template -void MarlinSerial::println(int n, int base) { - print(n, base); - println(); -} - -template -void MarlinSerial::println(unsigned int n, int base) { - print(n, base); - println(); -} - -template -void MarlinSerial::println(long n, int base) { - print(n, base); - println(); -} - -template -void MarlinSerial::println(unsigned long n, int base) { - print(n, base); - println(); -} - -template -void MarlinSerial::println(double n, int digits) { - print(n, digits); - println(); -} - -// Private Methods - -template -void MarlinSerial::printNumber(unsigned long n, uint8_t base) { - if (n) { - unsigned char buf[8 * sizeof(long)]; // Enough space for base 2 - int8_t i = 0; - while (n) { - buf[i++] = n % base; - n /= base; - } - while (i--) - print((char)(buf[i] + (buf[i] < 10 ? '0' : 'A' - 10))); - } - else - print('0'); -} - -template -void MarlinSerial::printFloat(double number, uint8_t digits) { - // Handle negative numbers - if (number < 0.0) { - print('-'); - number = -number; - } - - // Round correctly so that print(1.999, 2) prints as "2.00" - double rounding = 0.5; - LOOP_L_N(i, digits) rounding *= 0.1; - number += rounding; - - // Extract the integer part of the number and print it - unsigned long int_part = (unsigned long)number; - double remainder = number - (double)int_part; - print(int_part); - - // Print the decimal point, but only if there are digits beyond - if (digits) { - print('.'); - // Extract digits from the remainder one at a time - while (digits--) { - remainder *= 10.0; - int toPrint = int(remainder); - print(toPrint); - remainder -= toPrint; - } - } -} - // Hookup ISR handlers ISR(SERIAL_REGNAME(USART, SERIAL_PORT, _RX_vect)) { MarlinSerial>::store_rxd_char(); @@ -720,11 +565,9 @@ ISR(SERIAL_REGNAME(USART, SERIAL_PORT, _UDRE_vect)) { MarlinSerial>::_tx_udr_empty_irq(); } -// Preinstantiate -template class MarlinSerial>; - -// Instantiate -MarlinSerial> customizedSerial1; +// Because of the template definition above, it's required to instantiate the template to have all methods generated +template class MarlinSerial< MarlinSerialCfg >; +MSerialT1 customizedSerial1(MSerialT1::HasEmergencyParser); #ifdef SERIAL_PORT_2 @@ -737,13 +580,26 @@ MarlinSerial> customizedSerial1; MarlinSerial>::_tx_udr_empty_irq(); } - // Preinstantiate - template class MarlinSerial>; + template class MarlinSerial< MarlinSerialCfg >; + MSerialT2 customizedSerial2(MSerialT2::HasEmergencyParser); - // Instantiate - MarlinSerial> customizedSerial2; +#endif // SERIAL_PORT_2 -#endif +#ifdef SERIAL_PORT_3 + + // Hookup ISR handlers + ISR(SERIAL_REGNAME(USART, SERIAL_PORT_3, _RX_vect)) { + MarlinSerial>::store_rxd_char(); + } + + ISR(SERIAL_REGNAME(USART, SERIAL_PORT_3, _UDRE_vect)) { + MarlinSerial>::_tx_udr_empty_irq(); + } + + template class MarlinSerial< MarlinSerialCfg >; + MSerialT3 customizedSerial3(MSerialT3::HasEmergencyParser); + +#endif // SERIAL_PORT_3 #ifdef MMU2_SERIAL_PORT @@ -755,13 +611,10 @@ MarlinSerial> customizedSerial1; MarlinSerial>::_tx_udr_empty_irq(); } - // Preinstantiate - template class MarlinSerial>; - - // Instantiate - MarlinSerial> mmuSerial; + template class MarlinSerial< MMU2SerialCfg >; + MSerialMMU2 mmuSerial(MSerialMMU2::HasEmergencyParser); -#endif +#endif // MMU2_SERIAL_PORT #ifdef LCD_SERIAL_PORT @@ -773,11 +626,8 @@ MarlinSerial> customizedSerial1; MarlinSerial>::_tx_udr_empty_irq(); } - // Preinstantiate - template class MarlinSerial>; - - // Instantiate - MarlinSerial> lcdSerial; + template class MarlinSerial< LCDSerialCfg >; + MSerialLCD lcdSerial(MSerialLCD::HasEmergencyParser); #if HAS_DGUS_LCD template @@ -790,13 +640,13 @@ MarlinSerial> customizedSerial1; } #endif -#endif +#endif // LCD_SERIAL_PORT -#endif // !IS_AT90USB && (UBRRH || UBRR0H || UBRR1H || UBRR2H || UBRR3H) +#endif // !USBCON && (UBRRH || UBRR0H || UBRR1H || UBRR2H || UBRR3H) // For AT90USB targets use the UART for BT interfacing -#if BOTH(IS_AT90USB, BLUETOOTH) - HardwareSerial bluetoothSerial; +#if defined(USBCON) && ENABLED(BLUETOOTH) + MSerialBT bluetoothSerial(false); #endif #endif // __AVR__ diff --git a/Marlin/src/HAL/AVR/MarlinSerial.h b/Marlin/src/HAL/AVR/MarlinSerial.h index 3850e2a47e2a..0565c7b9db9e 100644 --- a/Marlin/src/HAL/AVR/MarlinSerial.h +++ b/Marlin/src/HAL/AVR/MarlinSerial.h @@ -34,6 +34,7 @@ #include #include "../../inc/MarlinConfigPre.h" +#include "../../core/serial_hook.h" #ifndef SERIAL_PORT #define SERIAL_PORT 0 @@ -135,10 +136,6 @@ UART_DECL(3); #endif - #define DEC 10 - #define HEX 16 - #define OCT 8 - #define BIN 2 #define BYTE 0 // Templated type selector @@ -202,60 +199,30 @@ static FORCE_INLINE void atomic_set_rx_tail(ring_buffer_pos_t value); static FORCE_INLINE ring_buffer_pos_t atomic_read_rx_tail(); - public: - + public: FORCE_INLINE static void store_rxd_char(); FORCE_INLINE static void _tx_udr_empty_irq(); - public: - MarlinSerial() {}; - static void begin(const long); - static void end(); - static int peek(); - static int read(); - static void flush(); - static ring_buffer_pos_t available(); - static void write(const uint8_t c); - static void flushTX(); - #if HAS_DGUS_LCD - static ring_buffer_pos_t get_tx_buffer_free(); - #endif - - static inline bool emergency_parser_enabled() { return Cfg::EMERGENCYPARSER; } - - FORCE_INLINE static uint8_t dropped() { return Cfg::DROPPED_RX ? rx_dropped_bytes : 0; } - FORCE_INLINE static uint8_t buffer_overruns() { return Cfg::RX_OVERRUNS ? rx_buffer_overruns : 0; } - FORCE_INLINE static uint8_t framing_errors() { return Cfg::RX_FRAMING_ERRORS ? rx_framing_errors : 0; } - FORCE_INLINE static ring_buffer_pos_t rxMaxEnqueued() { return Cfg::MAX_RX_QUEUED ? rx_max_enqueued : 0; } - - FORCE_INLINE static void write(const char* str) { while (*str) write(*str++); } - FORCE_INLINE static void write(const uint8_t* buffer, size_t size) { while (size--) write(*buffer++); } - FORCE_INLINE static void print(const String& s) { for (int i = 0; i < (int)s.length(); i++) write(s[i]); } - FORCE_INLINE static void print(const char* str) { write(str); } - - static void print(char, int = BYTE); - static void print(unsigned char, int = BYTE); - static void print(int, int = DEC); - static void print(unsigned int, int = DEC); - static void print(long, int = DEC); - static void print(unsigned long, int = DEC); - static void print(double, int = 2); - - static void println(const String& s); - static void println(const char[]); - static void println(char, int = BYTE); - static void println(unsigned char, int = BYTE); - static void println(int, int = DEC); - static void println(unsigned int, int = DEC); - static void println(long, int = DEC); - static void println(unsigned long, int = DEC); - static void println(double, int = 2); - static void println(); - operator bool() { return true; } - - private: - static void printNumber(unsigned long, const uint8_t); - static void printFloat(double, uint8_t); + public: + static void begin(const long); + static void end(); + static int peek(); + static int read(); + static void flush(); + static ring_buffer_pos_t available(); + static void write(const uint8_t c); + static void flushTX(); + #if HAS_DGUS_LCD + static ring_buffer_pos_t get_tx_buffer_free(); + #endif + + enum { HasEmergencyParser = Cfg::EMERGENCYPARSER }; + static inline bool emergency_parser_enabled() { return Cfg::EMERGENCYPARSER; } + + FORCE_INLINE static uint8_t dropped() { return Cfg::DROPPED_RX ? rx_dropped_bytes : 0; } + FORCE_INLINE static uint8_t buffer_overruns() { return Cfg::RX_OVERRUNS ? rx_buffer_overruns : 0; } + FORCE_INLINE static uint8_t framing_errors() { return Cfg::RX_FRAMING_ERRORS ? rx_framing_errors : 0; } + FORCE_INLINE static ring_buffer_pos_t rxMaxEnqueued() { return Cfg::MAX_RX_QUEUED ? rx_max_enqueued : 0; } }; template @@ -270,12 +237,18 @@ static constexpr bool RX_FRAMING_ERRORS = ENABLED(SERIAL_STATS_RX_FRAMING_ERRORS); static constexpr bool MAX_RX_QUEUED = ENABLED(SERIAL_STATS_MAX_RX_QUEUED); }; - extern MarlinSerial> customizedSerial1; - #ifdef SERIAL_PORT_2 + typedef Serial1Class< MarlinSerial< MarlinSerialCfg > > MSerialT1; + extern MSerialT1 customizedSerial1; - extern MarlinSerial> customizedSerial2; + #ifdef SERIAL_PORT_2 + typedef Serial1Class< MarlinSerial< MarlinSerialCfg > > MSerialT2; + extern MSerialT2 customizedSerial2; + #endif + #ifdef SERIAL_PORT_3 + typedef Serial1Class< MarlinSerial< MarlinSerialCfg > > MSerialT3; + extern MSerialT3 customizedSerial3; #endif #endif // !USBCON @@ -284,49 +257,41 @@ template struct MMU2SerialCfg { static constexpr int PORT = serial; + static constexpr unsigned int RX_SIZE = 32; + static constexpr unsigned int TX_SIZE = 32; static constexpr bool XONOFF = false; static constexpr bool EMERGENCYPARSER = false; static constexpr bool DROPPED_RX = false; static constexpr bool RX_FRAMING_ERRORS = false; static constexpr bool MAX_RX_QUEUED = false; - static constexpr unsigned int RX_SIZE = 32; - static constexpr unsigned int TX_SIZE = 32; static constexpr bool RX_OVERRUNS = false; }; - extern MarlinSerial> mmuSerial; + typedef Serial1Class< MarlinSerial< MMU2SerialCfg > > MSerialMMU2; + extern MSerialMMU2 mmuSerial; #endif #ifdef LCD_SERIAL_PORT template struct LCDSerialCfg { - static constexpr int PORT = serial; - static constexpr bool XONOFF = false; - static constexpr bool EMERGENCYPARSER = ENABLED(EMERGENCY_PARSER); - static constexpr bool DROPPED_RX = false; - static constexpr bool RX_FRAMING_ERRORS = false; - static constexpr bool MAX_RX_QUEUED = false; - #if HAS_DGUS_LCD - static constexpr unsigned int RX_SIZE = DGUS_RX_BUFFER_SIZE; - static constexpr unsigned int TX_SIZE = DGUS_TX_BUFFER_SIZE; - static constexpr bool RX_OVERRUNS = ENABLED(SERIAL_STATS_RX_BUFFER_OVERRUNS); - #elif EITHER(ANYCUBIC_LCD_I3MEGA, ANYCUBIC_LCD_CHIRON) - static constexpr unsigned int RX_SIZE = 64; - static constexpr unsigned int TX_SIZE = 128; - static constexpr bool RX_OVERRUNS = false; - #else - static constexpr unsigned int RX_SIZE = 64; - static constexpr unsigned int TX_SIZE = 128; - static constexpr bool RX_OVERRUNS = false - #endif + static constexpr int PORT = serial; + static constexpr unsigned int RX_SIZE = TERN(HAS_DGUS_LCD, DGUS_RX_BUFFER_SIZE, 64); + static constexpr unsigned int TX_SIZE = TERN(HAS_DGUS_LCD, DGUS_TX_BUFFER_SIZE, 128); + static constexpr bool XONOFF = false; + static constexpr bool EMERGENCYPARSER = ENABLED(EMERGENCY_PARSER); + 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); }; - extern MarlinSerial> lcdSerial; - + typedef Serial1Class< MarlinSerial< LCDSerialCfg > > MSerialLCD; + extern MSerialLCD lcdSerial; #endif // Use the UART for Bluetooth in AT90USB configurations -#if BOTH(IS_AT90USB, BLUETOOTH) - extern HardwareSerial bluetoothSerial; +#if defined(USBCON) && ENABLED(BLUETOOTH) + typedef Serial1Class MSerialBT; + extern MSerialBT bluetoothSerial; #endif diff --git a/Marlin/src/HAL/AVR/eeprom.cpp b/Marlin/src/HAL/AVR/eeprom.cpp index c7906985eb60..8d084dec7fdf 100644 --- a/Marlin/src/HAL/AVR/eeprom.cpp +++ b/Marlin/src/HAL/AVR/eeprom.cpp @@ -40,13 +40,13 @@ bool PersistentStore::access_start() { return true; } bool PersistentStore::access_finish() { return true; } bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + uint16_t written = 0; while (size--) { uint8_t * const p = (uint8_t * const)pos; uint8_t v = *value; - // EEPROM has only ~100,000 write cycles, - // so only write bytes that have changed! - if (v != eeprom_read_byte(p)) { + if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed! eeprom_write_byte(p, v); + if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes if (eeprom_read_byte(p) != v) { SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); return true; @@ -59,7 +59,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui return false; } -bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { +bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { do { uint8_t c = eeprom_read_byte((uint8_t*)pos); if (writing) *value = c; diff --git a/Marlin/src/HAL/AVR/endstop_interrupts.h b/Marlin/src/HAL/AVR/endstop_interrupts.h index ae9a605accce..50f29c3356ce 100644 --- a/Marlin/src/HAL/AVR/endstop_interrupts.h +++ b/Marlin/src/HAL/AVR/endstop_interrupts.h @@ -124,7 +124,7 @@ void setup_endstop_interrupts() { #if (digitalPinToInterrupt(X_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(X_MAX_PIN); #else - static_assert(digitalPinHasPCICR(X_MAX_PIN), "X_MAX_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(X_MAX_PIN), "X_MAX_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(X_MAX_PIN); #endif #endif @@ -132,7 +132,7 @@ void setup_endstop_interrupts() { #if (digitalPinToInterrupt(X_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(X_MIN_PIN); #else - static_assert(digitalPinHasPCICR(X_MIN_PIN), "X_MIN_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(X_MIN_PIN), "X_MIN_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(X_MIN_PIN); #endif #endif @@ -140,7 +140,7 @@ void setup_endstop_interrupts() { #if (digitalPinToInterrupt(Y_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(Y_MAX_PIN); #else - static_assert(digitalPinHasPCICR(Y_MAX_PIN), "Y_MAX_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(Y_MAX_PIN), "Y_MAX_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(Y_MAX_PIN); #endif #endif @@ -148,7 +148,7 @@ void setup_endstop_interrupts() { #if (digitalPinToInterrupt(Y_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(Y_MIN_PIN); #else - static_assert(digitalPinHasPCICR(Y_MIN_PIN), "Y_MIN_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(Y_MIN_PIN), "Y_MIN_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(Y_MIN_PIN); #endif #endif @@ -156,7 +156,7 @@ void setup_endstop_interrupts() { #if (digitalPinToInterrupt(Z_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(Z_MAX_PIN); #else - static_assert(digitalPinHasPCICR(Z_MAX_PIN), "Z_MAX_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(Z_MAX_PIN), "Z_MAX_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(Z_MAX_PIN); #endif #endif @@ -164,15 +164,60 @@ void setup_endstop_interrupts() { #if (digitalPinToInterrupt(Z_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(Z_MIN_PIN); #else - static_assert(digitalPinHasPCICR(Z_MIN_PIN), "Z_MIN_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(Z_MIN_PIN), "Z_MIN_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(Z_MIN_PIN); #endif #endif + #if HAS_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"); + pciSetup(I_MAX_PIN); + #endif + #elif HAS_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"); + pciSetup(I_MIN_PIN); + #endif + #endif + #if HAS_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"); + pciSetup(J_MAX_PIN); + #endif + #elif HAS_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"); + pciSetup(J_MIN_PIN); + #endif + #endif + #if HAS_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"); + pciSetup(K_MAX_PIN); + #endif + #elif HAS_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"); + pciSetup(K_MIN_PIN); + #endif + #endif #if HAS_X2_MAX #if (digitalPinToInterrupt(X2_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(X2_MAX_PIN); #else - static_assert(digitalPinHasPCICR(X2_MAX_PIN), "X2_MAX_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(X2_MAX_PIN), "X2_MAX_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(X2_MAX_PIN); #endif #endif @@ -180,7 +225,7 @@ void setup_endstop_interrupts() { #if (digitalPinToInterrupt(X2_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(X2_MIN_PIN); #else - static_assert(digitalPinHasPCICR(X2_MIN_PIN), "X2_MIN_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(X2_MIN_PIN), "X2_MIN_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(X2_MIN_PIN); #endif #endif @@ -188,7 +233,7 @@ void setup_endstop_interrupts() { #if (digitalPinToInterrupt(Y2_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(Y2_MAX_PIN); #else - static_assert(digitalPinHasPCICR(Y2_MAX_PIN), "Y2_MAX_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(Y2_MAX_PIN), "Y2_MAX_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(Y2_MAX_PIN); #endif #endif @@ -196,7 +241,7 @@ void setup_endstop_interrupts() { #if (digitalPinToInterrupt(Y2_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(Y2_MIN_PIN); #else - static_assert(digitalPinHasPCICR(Y2_MIN_PIN), "Y2_MIN_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(Y2_MIN_PIN), "Y2_MIN_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(Y2_MIN_PIN); #endif #endif @@ -204,7 +249,7 @@ void setup_endstop_interrupts() { #if (digitalPinToInterrupt(Z2_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(Z2_MAX_PIN); #else - static_assert(digitalPinHasPCICR(Z2_MAX_PIN), "Z2_MAX_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(Z2_MAX_PIN), "Z2_MAX_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(Z2_MAX_PIN); #endif #endif @@ -212,7 +257,7 @@ void setup_endstop_interrupts() { #if (digitalPinToInterrupt(Z2_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(Z2_MIN_PIN); #else - static_assert(digitalPinHasPCICR(Z2_MIN_PIN), "Z2_MIN_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(Z2_MIN_PIN), "Z2_MIN_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(Z2_MIN_PIN); #endif #endif @@ -220,7 +265,7 @@ void setup_endstop_interrupts() { #if (digitalPinToInterrupt(Z3_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(Z3_MAX_PIN); #else - static_assert(digitalPinHasPCICR(Z3_MAX_PIN), "Z3_MAX_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(Z3_MAX_PIN), "Z3_MAX_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(Z3_MAX_PIN); #endif #endif @@ -228,7 +273,7 @@ void setup_endstop_interrupts() { #if (digitalPinToInterrupt(Z3_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(Z3_MIN_PIN); #else - static_assert(digitalPinHasPCICR(Z3_MIN_PIN), "Z3_MIN_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(Z3_MIN_PIN), "Z3_MIN_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(Z3_MIN_PIN); #endif #endif @@ -236,7 +281,7 @@ void setup_endstop_interrupts() { #if (digitalPinToInterrupt(Z4_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(Z4_MAX_PIN); #else - static_assert(digitalPinHasPCICR(Z4_MAX_PIN), "Z4_MAX_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(Z4_MAX_PIN), "Z4_MAX_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(Z4_MAX_PIN); #endif #endif @@ -244,7 +289,7 @@ void setup_endstop_interrupts() { #if (digitalPinToInterrupt(Z4_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(Z4_MIN_PIN); #else - static_assert(digitalPinHasPCICR(Z4_MIN_PIN), "Z4_MIN_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(Z4_MIN_PIN), "Z4_MIN_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(Z4_MIN_PIN); #endif #endif @@ -252,10 +297,9 @@ void setup_endstop_interrupts() { #if (digitalPinToInterrupt(Z_MIN_PROBE_PIN) != NOT_AN_INTERRUPT) _ATTACH(Z_MIN_PROBE_PIN); #else - static_assert(digitalPinHasPCICR(Z_MIN_PROBE_PIN), "Z_MIN_PROBE_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(Z_MIN_PROBE_PIN), "Z_MIN_PROBE_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(Z_MIN_PROBE_PIN); #endif #endif - // If we arrive here without raising an assertion, each pin has either an EXT-interrupt or a PCI. } diff --git a/Marlin/src/HAL/AVR/fastio.cpp b/Marlin/src/HAL/AVR/fastio.cpp index b51d7f97686a..70132e71ee54 100644 --- a/Marlin/src/HAL/AVR/fastio.cpp +++ b/Marlin/src/HAL/AVR/fastio.cpp @@ -241,7 +241,7 @@ uint8_t extDigitalRead(const int8_t pin) { * * DC values -1.0 to 1.0. Negative duty cycle inverts the pulse. */ -uint16_t set_pwm_frequency_hz(const float &hz, const float dca, const float dcb, const float dcc) { +uint16_t set_pwm_frequency_hz(const_float_t hz, const float dca, const float dcb, const float dcc) { float count = 0; if (hz > 0 && (dca || dcb || dcc)) { count = float(F_CPU) / hz; // 1x prescaler, TOP for 16MHz base freq. diff --git a/Marlin/src/HAL/AVR/fastio.h b/Marlin/src/HAL/AVR/fastio.h index dd0163466110..f77d4f666c7d 100644 --- a/Marlin/src/HAL/AVR/fastio.h +++ b/Marlin/src/HAL/AVR/fastio.h @@ -284,8 +284,8 @@ enum ClockSource2 : char { * PWM availability macros */ -// Determine which harware 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) +// 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 diff --git a/Marlin/src/HAL/AVR/inc/SanityCheck.h b/Marlin/src/HAL/AVR/inc/SanityCheck.h index 731cf9286582..51ba247953b4 100644 --- a/Marlin/src/HAL/AVR/inc/SanityCheck.h +++ b/Marlin/src/HAL/AVR/inc/SanityCheck.h @@ -56,3 +56,10 @@ #if BOTH(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 + +/** + * Postmortem debugging + */ +#if ENABLED(POSTMORTEM_DEBUGGING) + #error "POSTMORTEM_DEBUGGING is not supported on AVR boards." +#endif diff --git a/Marlin/src/HAL/AVR/pinsDebug.h b/Marlin/src/HAL/AVR/pinsDebug.h index dac6b1b150bd..55fddb05b862 100644 --- a/Marlin/src/HAL/AVR/pinsDebug.h +++ b/Marlin/src/HAL/AVR/pinsDebug.h @@ -38,7 +38,7 @@ // portModeRegister takes a different argument #define digitalPinToTimer_DEBUG(p) digitalPinToTimer(p) #define digitalPinToBitMask_DEBUG(p) digitalPinToBitMask(p) - #define digitalPinToPort_DEBUG(p) digitalPinToPort_Teensy(p) + #define digitalPinToPort_DEBUG(p) digitalPinToPort(p) #define GET_PINMODE(pin) (*portModeRegister(pin) & digitalPinToBitMask_DEBUG(pin)) #elif AVR_ATmega2560_FAMILY_PLUS_70 // So we can access/display all the pins on boards using more than 70 @@ -235,8 +235,8 @@ static void print_is_also_tied() { SERIAL_ECHOPGM(" is also tied to this pin"); inline void com_print(const uint8_t N, const uint8_t Z) { const uint8_t *TCCRA = (uint8_t*)TCCR_A(N); - SERIAL_ECHOPGM(" COM"); - SERIAL_CHAR('0' + N, Z); + SERIAL_ECHOPAIR(" COM", AS_CHAR('0' + N)); + SERIAL_CHAR(Z); SERIAL_ECHOPAIR(": ", int((*TCCRA >> (6 - Z * 2)) & 0x03)); } @@ -247,8 +247,8 @@ void timer_prefix(uint8_t T, char L, uint8_t N) { // T - timer L - pwm N - uint8_t WGM = (((*TCCRB & _BV(WGM_2)) >> 1) | (*TCCRA & (_BV(WGM_0) | _BV(WGM_1)))); if (N == 4) WGM |= ((*TCCRB & _BV(WGM_3)) >> 1); - SERIAL_ECHOPGM(" TIMER"); - SERIAL_CHAR(T + '0', L); + SERIAL_ECHOPAIR(" TIMER", AS_CHAR(T + '0')); + SERIAL_CHAR(L); SERIAL_ECHO_SP(3); if (N == 3) { @@ -262,19 +262,11 @@ void timer_prefix(uint8_t T, char L, uint8_t N) { // T - timer L - pwm N - SERIAL_ECHOPAIR(" WGM: ", WGM); com_print(T,L); SERIAL_ECHOPAIR(" CS: ", (*TCCRB & (_BV(CS_0) | _BV(CS_1) | _BV(CS_2)) )); - - SERIAL_ECHOPGM(" TCCR"); - SERIAL_CHAR(T + '0'); - SERIAL_ECHOPAIR("A: ", *TCCRA); - - SERIAL_ECHOPGM(" TCCR"); - SERIAL_CHAR(T + '0'); - SERIAL_ECHOPAIR("B: ", *TCCRB); + SERIAL_ECHOPAIR(" TCCR", AS_CHAR(T + '0'), "A: ", *TCCRA); + SERIAL_ECHOPAIR(" TCCR", AS_CHAR(T + '0'), "B: ", *TCCRB); const uint8_t *TMSK = (uint8_t*)TIMSK(T); - SERIAL_ECHOPGM(" TIMSK"); - SERIAL_CHAR(T + '0'); - SERIAL_ECHOPAIR(": ", *TMSK); + SERIAL_ECHOPAIR(" TIMSK", AS_CHAR(T + '0'), ": ", *TMSK); const uint8_t OCIE = L - 'A' + 1; if (N == 3) { if (WGM == 0 || WGM == 2 || WGM == 4 || WGM == 6) err_is_counter(); } diff --git a/Marlin/src/HAL/AVR/spi_pins.h b/Marlin/src/HAL/AVR/spi_pins.h index f3fa78e2bfaf..831972938a7b 100644 --- a/Marlin/src/HAL/AVR/spi_pins.h +++ b/Marlin/src/HAL/AVR/spi_pins.h @@ -51,15 +51,15 @@ #define AVR_SS_PIN 16 #endif -#ifndef SCK_PIN - #define SCK_PIN AVR_SCK_PIN +#ifndef SD_SCK_PIN + #define SD_SCK_PIN AVR_SCK_PIN #endif -#ifndef MISO_PIN - #define MISO_PIN AVR_MISO_PIN +#ifndef SD_MISO_PIN + #define SD_MISO_PIN AVR_MISO_PIN #endif -#ifndef MOSI_PIN - #define MOSI_PIN AVR_MOSI_PIN +#ifndef SD_MOSI_PIN + #define SD_MOSI_PIN AVR_MOSI_PIN #endif -#ifndef SS_PIN - #define SS_PIN AVR_SS_PIN +#ifndef SD_SS_PIN + #define SD_SS_PIN AVR_SS_PIN #endif 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 cb95a48cccec..9d928e7af3b0 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 @@ -62,7 +62,7 @@ #include "../shared/Marduino.h" #include "../shared/Delay.h" -#include +#include uint8_t u8g_bitData, u8g_bitNotData, u8g_bitClock, u8g_bitNotClock; volatile uint8_t *u8g_outData, *u8g_outClock; diff --git a/Marlin/src/HAL/DUE/DebugMonitor.cpp b/Marlin/src/HAL/DUE/DebugMonitor.cpp deleted file mode 100644 index 79759151d891..000000000000 --- a/Marlin/src/HAL/DUE/DebugMonitor.cpp +++ /dev/null @@ -1,342 +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 ARDUINO_ARCH_SAM - -#include "../../core/macros.h" -#include "../../core/serial.h" - -#include "../shared/backtrace/unwinder.h" -#include "../shared/backtrace/unwmemaccess.h" - -#include - -// Debug monitor that dumps to the Programming port all status when -// an exception or WDT timeout happens - And then resets the board - -// All the Monitor routines must run with interrupts disabled and -// under an ISR execution context. That is why we cannot reuse the -// Serial interrupt routines or any C runtime, as we don't know the -// state we are when running them - -// A SW memory barrier, to ensure GCC does not overoptimize loops -#define sw_barrier() __asm__ volatile("": : :"memory"); - -// (re)initialize UART0 as a monitor output to 250000,n,8,1 -static void TXBegin() { - - // Disable UART interrupt in NVIC - NVIC_DisableIRQ( UART_IRQn ); - - // We NEED memory barriers to ensure Interrupts are actually disabled! - // ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the ) - __DSB(); - __ISB(); - - // Disable clock - pmc_disable_periph_clk( ID_UART ); - - // Configure PMC - pmc_enable_periph_clk( ID_UART ); - - // Disable PDC channel - UART->UART_PTCR = UART_PTCR_RXTDIS | UART_PTCR_TXTDIS; - - // Reset and disable receiver and transmitter - UART->UART_CR = UART_CR_RSTRX | UART_CR_RSTTX | UART_CR_RXDIS | UART_CR_TXDIS; - - // Configure mode: 8bit, No parity, 1 bit stop - UART->UART_MR = UART_MR_CHMODE_NORMAL | US_MR_CHRL_8_BIT | US_MR_NBSTOP_1_BIT | UART_MR_PAR_NO; - - // Configure baudrate (asynchronous, no oversampling) to BAUDRATE bauds - UART->UART_BRGR = (SystemCoreClock / (BAUDRATE << 4)); - - // Enable receiver and transmitter - UART->UART_CR = UART_CR_RXEN | UART_CR_TXEN; -} - -// Send character through UART with no interrupts -static void TX(char c) { - while (!(UART->UART_SR & UART_SR_TXRDY)) { WDT_Restart(WDT); sw_barrier(); }; - UART->UART_THR = c; -} - -// Send String through UART -static void TX(const char* s) { - while (*s) TX(*s++); -} - -static void TXDigit(uint32_t d) { - if (d < 10) TX((char)(d+'0')); - else if (d < 16) TX((char)(d+'A'-10)); - else TX('?'); -} - -// Send Hex number thru UART -static void TXHex(uint32_t v) { - TX("0x"); - for (uint8_t i = 0; i < 8; i++, v <<= 4) - TXDigit((v >> 28) & 0xF); -} - -// Send Decimal number thru UART -static void TXDec(uint32_t v) { - if (!v) { - TX('0'); - return; - } - - char nbrs[14]; - char *p = &nbrs[0]; - while (v != 0) { - *p++ = '0' + (v % 10); - v /= 10; - } - do { - p--; - TX(*p); - } while (p != &nbrs[0]); -} - -// Dump a backtrace entry -static bool UnwReportOut(void* ctx, const UnwReport* bte) { - int* p = (int*)ctx; - - (*p)++; - TX('#'); TXDec(*p); TX(" : "); - TX(bte->name?bte->name:"unknown"); TX('@'); TXHex(bte->function); - TX('+'); TXDec(bte->address - bte->function); - TX(" PC:");TXHex(bte->address); TX('\n'); - return true; -} - -#ifdef UNW_DEBUG - void UnwPrintf(const char* format, ...) { - char dest[256]; - va_list argptr; - va_start(argptr, format); - vsprintf(dest, format, argptr); - va_end(argptr); - TX(&dest[0]); - } -#endif - -/* Table of function pointers for passing to the unwinder */ -static const UnwindCallbacks UnwCallbacks = { - UnwReportOut, - UnwReadW, - UnwReadH, - UnwReadB - #ifdef UNW_DEBUG - , UnwPrintf - #endif -}; - -/** - * HardFaultHandler_C: - * This is called from the HardFault_HandlerAsm with a pointer the Fault stack - * as the parameter. We can then read the values from the stack and place them - * into local variables for ease of reading. - * We then read the various Fault Status and Address Registers to help decode - * cause of the fault. - * The function ends with a BKPT instruction to force control back into the debugger - */ -extern "C" -void HardFault_HandlerC(unsigned long *sp, unsigned long lr, unsigned long cause) { - - static const char* causestr[] = { - "NMI","Hard","Mem","Bus","Usage","Debug","WDT","RSTC" - }; - - UnwindFrame btf; - - // Dump report to the Programming port (interrupts are DISABLED) - TXBegin(); - TX("\n\n## Software Fault detected ##\n"); - TX("Cause: "); TX(causestr[cause]); TX('\n'); - - TX("R0 : "); TXHex(((unsigned long)sp[0])); TX('\n'); - TX("R1 : "); TXHex(((unsigned long)sp[1])); TX('\n'); - TX("R2 : "); TXHex(((unsigned long)sp[2])); TX('\n'); - TX("R3 : "); TXHex(((unsigned long)sp[3])); TX('\n'); - TX("R12 : "); TXHex(((unsigned long)sp[4])); TX('\n'); - TX("LR : "); TXHex(((unsigned long)sp[5])); TX('\n'); - TX("PC : "); TXHex(((unsigned long)sp[6])); TX('\n'); - TX("PSR : "); TXHex(((unsigned long)sp[7])); TX('\n'); - - // Configurable Fault Status Register - // Consists of MMSR, BFSR and UFSR - TX("CFSR : "); TXHex((*((volatile unsigned long *)(0xE000ED28)))); TX('\n'); - - // Hard Fault Status Register - TX("HFSR : "); TXHex((*((volatile unsigned long *)(0xE000ED2C)))); TX('\n'); - - // Debug Fault Status Register - TX("DFSR : "); TXHex((*((volatile unsigned long *)(0xE000ED30)))); TX('\n'); - - // Auxiliary Fault Status Register - TX("AFSR : "); TXHex((*((volatile unsigned long *)(0xE000ED3C)))); TX('\n'); - - // Read the Fault Address Registers. These may not contain valid values. - // Check BFARVALID/MMARVALID to see if they are valid values - // MemManage Fault Address Register - TX("MMAR : "); TXHex((*((volatile unsigned long *)(0xE000ED34)))); TX('\n'); - - // Bus Fault Address Register - TX("BFAR : "); TXHex((*((volatile unsigned long *)(0xE000ED38)))); TX('\n'); - - TX("ExcLR: "); TXHex(lr); TX('\n'); - TX("ExcSP: "); TXHex((unsigned long)sp); TX('\n'); - - btf.sp = ((unsigned long)sp) + 8*4; // The original stack pointer - btf.fp = btf.sp; - btf.lr = ((unsigned long)sp[5]); - btf.pc = ((unsigned long)sp[6]) | 1; // Force Thumb, as CORTEX only support it - - // Perform a backtrace - TX("\nBacktrace:\n\n"); - int ctr = 0; - UnwindStart(&btf, &UnwCallbacks, &ctr); - - // Disable all NVIC interrupts - NVIC->ICER[0] = 0xFFFFFFFF; - NVIC->ICER[1] = 0xFFFFFFFF; - - // Relocate VTOR table to default position - SCB->VTOR = 0; - - // Disable USB - otg_disable(); - - // Restart watchdog - WDT_Restart(WDT); - - // Reset controller - NVIC_SystemReset(); - for (;;) WDT_Restart(WDT); -} - -__attribute__((naked)) void NMI_Handler() { - __asm__ __volatile__ ( - ".syntax unified" "\n\t" - A("tst lr, #4") - A("ite eq") - A("mrseq r0, msp") - A("mrsne r0, psp") - A("mov r1,lr") - A("mov r2,#0") - A("b HardFault_HandlerC") - ); -} - -__attribute__((naked)) void HardFault_Handler() { - __asm__ __volatile__ ( - ".syntax unified" "\n\t" - A("tst lr, #4") - A("ite eq") - A("mrseq r0, msp") - A("mrsne r0, psp") - A("mov r1,lr") - A("mov r2,#1") - A("b HardFault_HandlerC") - ); -} - -__attribute__((naked)) void MemManage_Handler() { - __asm__ __volatile__ ( - ".syntax unified" "\n\t" - A("tst lr, #4") - A("ite eq") - A("mrseq r0, msp") - A("mrsne r0, psp") - A("mov r1,lr") - A("mov r2,#2") - A("b HardFault_HandlerC") - ); -} - -__attribute__((naked)) void BusFault_Handler() { - __asm__ __volatile__ ( - ".syntax unified" "\n\t" - A("tst lr, #4") - A("ite eq") - A("mrseq r0, msp") - A("mrsne r0, psp") - A("mov r1,lr") - A("mov r2,#3") - A("b HardFault_HandlerC") - ); -} - -__attribute__((naked)) void UsageFault_Handler() { - __asm__ __volatile__ ( - ".syntax unified" "\n\t" - A("tst lr, #4") - A("ite eq") - A("mrseq r0, msp") - A("mrsne r0, psp") - A("mov r1,lr") - A("mov r2,#4") - A("b HardFault_HandlerC") - ); -} - -__attribute__((naked)) void DebugMon_Handler() { - __asm__ __volatile__ ( - ".syntax unified" "\n\t" - A("tst lr, #4") - A("ite eq") - A("mrseq r0, msp") - A("mrsne r0, psp") - A("mov r1,lr") - A("mov r2,#5") - A("b HardFault_HandlerC") - ); -} - -/* This is NOT an exception, it is an interrupt handler - Nevertheless, the framing is the same */ -__attribute__((naked)) void WDT_Handler() { - __asm__ __volatile__ ( - ".syntax unified" "\n\t" - A("tst lr, #4") - A("ite eq") - A("mrseq r0, msp") - A("mrsne r0, psp") - A("mov r1,lr") - A("mov r2,#6") - A("b HardFault_HandlerC") - ); -} - -__attribute__((naked)) void RSTC_Handler() { - __asm__ __volatile__ ( - ".syntax unified" "\n\t" - A("tst lr, #4") - A("ite eq") - A("mrseq r0, msp") - A("mrsne r0, psp") - A("mov r1,lr") - A("mov r2,#7") - A("b HardFault_HandlerC") - ); -} - -#endif // ARDUINO_ARCH_SAM diff --git a/Marlin/src/HAL/DUE/HAL.cpp b/Marlin/src/HAL/DUE/HAL.cpp index 6ce85a4643bb..a3985652e71d 100644 --- a/Marlin/src/HAL/DUE/HAL.cpp +++ b/Marlin/src/HAL/DUE/HAL.cpp @@ -40,6 +40,8 @@ uint16_t HAL_adc_result; // Public functions // ------------------------ +TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); + // HAL initialization task void HAL_init() { // Initialize the USB stack @@ -47,6 +49,7 @@ void HAL_init() { OUT_WRITE(SDSS, HIGH); // Try to set SDSS inactive before any other SPI users start up #endif usb_task_init(); + TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the min serial handler } // HAL idle task @@ -74,6 +77,8 @@ uint8_t HAL_get_reset_source() { } } +void HAL_reboot() { rstc_start_software_reset(RSTC); } + void _delay_ms(const int delay_ms) { // Todo: port for Due? delay(delay_ms); @@ -102,4 +107,18 @@ uint16_t HAL_adc_get_result() { return HAL_adc_result; } +// Forward the default serial ports +#if USING_HW_SERIAL0 + DefaultSerial1 MSerial0(false, Serial); +#endif +#if USING_HW_SERIAL1 + DefaultSerial2 MSerial1(false, Serial1); +#endif +#if USING_HW_SERIAL2 + DefaultSerial3 MSerial2(false, Serial2); +#endif +#if USING_HW_SERIAL3 + DefaultSerial4 MSerial3(false, Serial3); +#endif + #endif // ARDUINO_ARCH_SAM diff --git a/Marlin/src/HAL/DUE/HAL.h b/Marlin/src/HAL/DUE/HAL.h index 88ace5957535..92e26bcf4362 100644 --- a/Marlin/src/HAL/DUE/HAL.h +++ b/Marlin/src/HAL/DUE/HAL.h @@ -36,36 +36,61 @@ #include -#define _MSERIAL(X) Serial##X +#include "../../core/serial_hook.h" + +typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1; +typedef ForwardSerial1Class< decltype(Serial1) > DefaultSerial2; +typedef ForwardSerial1Class< decltype(Serial2) > DefaultSerial3; +typedef ForwardSerial1Class< decltype(Serial3) > DefaultSerial4; +extern DefaultSerial1 MSerial0; +extern DefaultSerial2 MSerial1; +extern DefaultSerial3 MSerial2; +extern DefaultSerial4 MSerial3; + +#define _MSERIAL(X) MSerial##X #define MSERIAL(X) _MSERIAL(X) -#define Serial0 Serial -// Define MYSERIAL0/1 before MarlinSerial includes! #if SERIAL_PORT == -1 || ENABLED(EMERGENCY_PARSER) - #define MYSERIAL0 customizedSerial1 + #define MYSERIAL1 customizedSerial1 #elif WITHIN(SERIAL_PORT, 0, 3) - #define MYSERIAL0 MSERIAL(SERIAL_PORT) + #define MYSERIAL1 MSERIAL(SERIAL_PORT) #else - #error "The required SERIAL_PORT must be from -1 to 3. Please update your configuration." + #error "The required SERIAL_PORT must be from 0 to 3, or -1 for USB Serial." #endif #ifdef SERIAL_PORT_2 #if SERIAL_PORT_2 == -1 || ENABLED(EMERGENCY_PARSER) - #define MYSERIAL1 customizedSerial2 + #define MYSERIAL2 customizedSerial2 #elif WITHIN(SERIAL_PORT_2, 0, 3) - #define MYSERIAL1 MSERIAL(SERIAL_PORT_2) + #define MYSERIAL2 MSERIAL(SERIAL_PORT_2) #else - #error "SERIAL_PORT_2 must be from -1 to 3. Please update your configuration." + #error "SERIAL_PORT_2 must be from 0 to 3, or -1 for USB Serial." + #endif +#endif + +#ifdef SERIAL_PORT_3 + #if SERIAL_PORT_3 == -1 || ENABLED(EMERGENCY_PARSER) + #define MYSERIAL3 customizedSerial3 + #elif WITHIN(SERIAL_PORT_3, 0, 3) + #define MYSERIAL3 MSERIAL(SERIAL_PORT_3) + #else + #error "SERIAL_PORT_3 must be from 0 to 3, or -1 for USB Serial." + #endif +#endif + +#ifdef MMU2_SERIAL_PORT + #if WITHIN(MMU2_SERIAL_PORT, 0, 3) + #define MMU2_SERIAL MSERIAL(MMU2_SERIAL_PORT) + #else + #error "MMU2_SERIAL_PORT must be from 0 to 3." #endif #endif #ifdef LCD_SERIAL_PORT - #if LCD_SERIAL_PORT == -1 - #define LCD_SERIAL lcdSerial - #elif WITHIN(LCD_SERIAL_PORT, 0, 3) + #if WITHIN(LCD_SERIAL_PORT, 0, 3) #define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT) #else - #error "LCD_SERIAL_PORT must be from -1 to 3. Please update your configuration." + #error "LCD_SERIAL_PORT must be from 0 to 3." #endif #endif @@ -75,16 +100,6 @@ // On AVR this is in math.h? #define square(x) ((x)*(x)) -#ifndef strncpy_P - #define strncpy_P(dest, src, num) strncpy((dest), (src), (num)) -#endif - -// Fix bug in pgm_read_ptr -#undef pgm_read_ptr -#define pgm_read_ptr(addr) (*((void**)(addr))) -#undef pgm_read_word -#define pgm_read_word(addr) (*((uint16_t*)(addr))) - typedef int8_t pin_t; #define SHARED_SERVOS HAS_SERVOS @@ -105,7 +120,7 @@ void sei(); // Enable interrupts void HAL_clear_reset_source(); // clear reset reason uint8_t HAL_get_reset_source(); // get reset reason -inline void HAL_reboot() {} // reboot the board or restart the bootloader +void HAL_reboot(); // // ADC @@ -153,10 +168,16 @@ void HAL_init(); // void _delay_ms(const int delay); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-function" +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + int freeMemory(); -#pragma GCC diagnostic pop + +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic pop +#endif #ifdef __cplusplus extern "C" { diff --git a/Marlin/src/HAL/DUE/HAL_MinSerial.cpp b/Marlin/src/HAL/DUE/HAL_MinSerial.cpp new file mode 100644 index 000000000000..93c4ed67d63c --- /dev/null +++ b/Marlin/src/HAL/DUE/HAL_MinSerial.cpp @@ -0,0 +1,91 @@ +/** + * 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 ARDUINO_ARCH_SAM + +#include "../../inc/MarlinConfigPre.h" + +#if ENABLED(POSTMORTEM_DEBUGGING) + +#include "../shared/HAL_MinSerial.h" + +#include + +static void TXBegin() { + // Disable UART interrupt in NVIC + NVIC_DisableIRQ( UART_IRQn ); + + // We NEED memory barriers to ensure Interrupts are actually disabled! + // ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the ) + __DSB(); + __ISB(); + + // Disable clock + pmc_disable_periph_clk( ID_UART ); + + // Configure PMC + pmc_enable_periph_clk( ID_UART ); + + // Disable PDC channel + UART->UART_PTCR = UART_PTCR_RXTDIS | UART_PTCR_TXTDIS; + + // Reset and disable receiver and transmitter + UART->UART_CR = UART_CR_RSTRX | UART_CR_RSTTX | UART_CR_RXDIS | UART_CR_TXDIS; + + // Configure mode: 8bit, No parity, 1 bit stop + UART->UART_MR = UART_MR_CHMODE_NORMAL | US_MR_CHRL_8_BIT | US_MR_NBSTOP_1_BIT | UART_MR_PAR_NO; + + // Configure baudrate (asynchronous, no oversampling) to BAUDRATE bauds + UART->UART_BRGR = (SystemCoreClock / (BAUDRATE << 4)); + + // Enable receiver and transmitter + UART->UART_CR = UART_CR_RXEN | UART_CR_TXEN; +} + +// A SW memory barrier, to ensure GCC does not overoptimize loops +#define sw_barrier() __asm__ volatile("": : :"memory"); +static void TX(char c) { + while (!(UART->UART_SR & UART_SR_TXRDY)) { WDT_Restart(WDT); sw_barrier(); }; + UART->UART_THR = c; +} + +void install_min_serial() { + HAL_min_serial_init = &TXBegin; + HAL_min_serial_out = &TX; +} + +#if DISABLED(DYNAMIC_VECTORTABLE) +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(); +} +#endif + +#endif // POSTMORTEM_DEBUGGING +#endif // ARDUINO_ARCH_SAM diff --git a/Marlin/src/HAL/DUE/HAL_SPI.cpp b/Marlin/src/HAL/DUE/HAL_SPI.cpp index 0451d8bcc4ff..d3d76e94e5dd 100644 --- a/Marlin/src/HAL/DUE/HAL_SPI.cpp +++ b/Marlin/src/HAL/DUE/HAL_SPI.cpp @@ -56,8 +56,8 @@ #pragma GCC optimize (3) typedef uint8_t (*pfnSpiTransfer)(uint8_t b); - typedef void (*pfnSpiRxBlock)(uint8_t* buf, uint32_t nbyte); - typedef void (*pfnSpiTxBlock)(const uint8_t* buf, uint32_t nbyte); + typedef void (*pfnSpiRxBlock)(uint8_t *buf, uint32_t nbyte); + typedef void (*pfnSpiTxBlock)(const uint8_t *buf, uint32_t nbyte); /* ---------------- Macros to be able to access definitions from asm */ #define _PORT(IO) DIO ## IO ## _WPORT @@ -69,10 +69,10 @@ // run at ~8 .. ~10Mhz - Tx version (Rx data discarded) static uint8_t spiTransferTx0(uint8_t bout) { // using Mode 0 - uint32_t MOSI_PORT_PLUS30 = ((uint32_t) PORT(MOSI_PIN)) + 0x30; /* SODR of port */ - uint32_t MOSI_MASK = PIN_MASK(MOSI_PIN); - uint32_t SCK_PORT_PLUS30 = ((uint32_t) PORT(SCK_PIN)) + 0x30; /* SODR of port */ - uint32_t SCK_MASK = PIN_MASK(SCK_PIN); + uint32_t MOSI_PORT_PLUS30 = ((uint32_t) PORT(SD_MOSI_PIN)) + 0x30; /* SODR of port */ + uint32_t MOSI_MASK = PIN_MASK(SD_MOSI_PIN); + uint32_t SCK_PORT_PLUS30 = ((uint32_t) PORT(SD_SCK_PIN)) + 0x30; /* SODR of port */ + uint32_t SCK_MASK = PIN_MASK(SD_SCK_PIN); uint32_t idx = 0; /* Negate bout, as the assembler requires a negated value */ @@ -154,9 +154,9 @@ static uint8_t spiTransferRx0(uint8_t) { // using Mode 0 uint32_t bin = 0; uint32_t work = 0; - uint32_t BITBAND_MISO_PORT = BITBAND_ADDRESS( ((uint32_t)PORT(MISO_PIN))+0x3C, PIN_SHIFT(MISO_PIN)); /* PDSR of port in bitband area */ - uint32_t SCK_PORT_PLUS30 = ((uint32_t) PORT(SCK_PIN)) + 0x30; /* SODR of port */ - uint32_t SCK_MASK = PIN_MASK(SCK_PIN); + uint32_t BITBAND_MISO_PORT = BITBAND_ADDRESS( ((uint32_t)PORT(SD_MISO_PIN))+0x3C, PIN_SHIFT(SD_MISO_PIN)); /* PDSR of port in bitband area */ + uint32_t SCK_PORT_PLUS30 = ((uint32_t) PORT(SD_SCK_PIN)) + 0x30; /* SODR of port */ + uint32_t SCK_MASK = PIN_MASK(SD_SCK_PIN); /* The software SPI routine */ __asm__ __volatile__( @@ -225,36 +225,36 @@ static uint8_t spiTransfer1(uint8_t b) { // using Mode 0 int bits = 8; do { - WRITE(MOSI_PIN, b & 0x80); + WRITE(SD_MOSI_PIN, b & 0x80); b <<= 1; // little setup time - WRITE(SCK_PIN, HIGH); + WRITE(SD_SCK_PIN, HIGH); DELAY_NS(125); // 10 cycles @ 84mhz - b |= (READ(MISO_PIN) != 0); + b |= (READ(SD_MISO_PIN) != 0); - WRITE(SCK_PIN, LOW); + WRITE(SD_SCK_PIN, LOW); DELAY_NS(125); // 10 cycles @ 84mhz } while (--bits); return b; } // all the others - static uint32_t spiDelayCyclesX4 = (F_CPU) / 1000000; // 4µs => 125khz + static uint16_t spiDelayNS = 4000; // 4000ns => 125khz static uint8_t spiTransferX(uint8_t b) { // using Mode 0 int bits = 8; do { - WRITE(MOSI_PIN, b & 0x80); + WRITE(SD_MOSI_PIN, b & 0x80); b <<= 1; // little setup time - WRITE(SCK_PIN, HIGH); - __delay_4cycles(spiDelayCyclesX4); + WRITE(SD_SCK_PIN, HIGH); + DELAY_NS(spiDelayNS); - b |= (READ(MISO_PIN) != 0); + b |= (READ(SD_MISO_PIN) != 0); - WRITE(SCK_PIN, LOW); - __delay_4cycles(spiDelayCyclesX4); + WRITE(SD_SCK_PIN, LOW); + DELAY_NS(spiDelayNS); } while (--bits); return b; } @@ -270,11 +270,11 @@ static pfnSpiTransfer spiTransferTx = (pfnSpiTransfer)spiTransferX; // Block transfers run at ~8 .. ~10Mhz - Tx version (Rx data discarded) - static void spiTxBlock0(const uint8_t* ptr, uint32_t todo) { - uint32_t MOSI_PORT_PLUS30 = ((uint32_t) PORT(MOSI_PIN)) + 0x30; /* SODR of port */ - uint32_t MOSI_MASK = PIN_MASK(MOSI_PIN); - uint32_t SCK_PORT_PLUS30 = ((uint32_t) PORT(SCK_PIN)) + 0x30; /* SODR of port */ - uint32_t SCK_MASK = PIN_MASK(SCK_PIN); + static void spiTxBlock0(const uint8_t *ptr, uint32_t todo) { + uint32_t MOSI_PORT_PLUS30 = ((uint32_t) PORT(SD_MOSI_PIN)) + 0x30; /* SODR of port */ + uint32_t MOSI_MASK = PIN_MASK(SD_MOSI_PIN); + uint32_t SCK_PORT_PLUS30 = ((uint32_t) PORT(SD_SCK_PIN)) + 0x30; /* SODR of port */ + uint32_t SCK_MASK = PIN_MASK(SD_SCK_PIN); uint32_t work = 0; uint32_t txval = 0; @@ -349,12 +349,12 @@ ); } - static void spiRxBlock0(uint8_t* ptr, uint32_t todo) { + static void spiRxBlock0(uint8_t *ptr, uint32_t todo) { uint32_t bin = 0; uint32_t work = 0; - uint32_t BITBAND_MISO_PORT = BITBAND_ADDRESS( ((uint32_t)PORT(MISO_PIN))+0x3C, PIN_SHIFT(MISO_PIN)); /* PDSR of port in bitband area */ - uint32_t SCK_PORT_PLUS30 = ((uint32_t) PORT(SCK_PIN)) + 0x30; /* SODR of port */ - uint32_t SCK_MASK = PIN_MASK(SCK_PIN); + uint32_t BITBAND_MISO_PORT = BITBAND_ADDRESS( ((uint32_t)PORT(SD_MISO_PIN))+0x3C, PIN_SHIFT(SD_MISO_PIN)); /* PDSR of port in bitband area */ + uint32_t SCK_PORT_PLUS30 = ((uint32_t) PORT(SD_SCK_PIN)) + 0x30; /* SODR of port */ + uint32_t SCK_MASK = PIN_MASK(SD_SCK_PIN); /* The software SPI routine */ __asm__ __volatile__( @@ -425,48 +425,48 @@ ); } - static void spiTxBlockX(const uint8_t* buf, uint32_t todo) { + static void spiTxBlockX(const uint8_t *buf, uint32_t todo) { do { (void)spiTransferTx(*buf++); } while (--todo); } - static void spiRxBlockX(uint8_t* buf, uint32_t todo) { + static void spiRxBlockX(uint8_t *buf, uint32_t todo) { do { *buf++ = spiTransferRx(0xFF); } while (--todo); } - // Pointers to generic functions for block tranfers + // Pointers to generic functions for block transfers static pfnSpiTxBlock spiTxBlock = (pfnSpiTxBlock)spiTxBlockX; static pfnSpiRxBlock spiRxBlock = (pfnSpiRxBlock)spiRxBlockX; #if MB(ALLIGATOR) - #define _SS_WRITE(S) WRITE(SS_PIN, S) + #define _SS_WRITE(S) WRITE(SD_SS_PIN, S) #else #define _SS_WRITE(S) NOOP #endif void spiBegin() { - SET_OUTPUT(SS_PIN); + SET_OUTPUT(SD_SS_PIN); _SS_WRITE(HIGH); - SET_OUTPUT(SCK_PIN); - SET_INPUT(MISO_PIN); - SET_OUTPUT(MOSI_PIN); + SET_OUTPUT(SD_SCK_PIN); + SET_INPUT(SD_MISO_PIN); + SET_OUTPUT(SD_MOSI_PIN); } uint8_t spiRec() { _SS_WRITE(LOW); - WRITE(MOSI_PIN, HIGH); // Output 1s 1 + WRITE(SD_MOSI_PIN, HIGH); // Output 1s 1 uint8_t b = spiTransferRx(0xFF); _SS_WRITE(HIGH); return b; } - void spiRead(uint8_t* buf, uint16_t nbyte) { + void spiRead(uint8_t *buf, uint16_t nbyte) { if (nbyte) { _SS_WRITE(LOW); - WRITE(MOSI_PIN, HIGH); // Output 1s 1 + WRITE(SD_MOSI_PIN, HIGH); // Output 1s 1 spiRxBlock(buf, nbyte); _SS_WRITE(HIGH); } @@ -478,7 +478,7 @@ _SS_WRITE(HIGH); } - void spiSendBlock(uint8_t token, const uint8_t* buf) { + void spiSendBlock(uint8_t token, const uint8_t *buf) { _SS_WRITE(LOW); (void)spiTransferTx(token); spiTxBlock(buf, 512); @@ -510,7 +510,7 @@ spiRxBlock = (pfnSpiRxBlock)spiRxBlockX; break; default: - spiDelayCyclesX4 = ((F_CPU) / 1000000) >> (6 - spiRate); + spiDelayNS = 4000 >> (6 - spiRate); // spiRate of 2 gives the maximum error with current CPU spiTransferTx = (pfnSpiTransfer)spiTransferX; spiTransferRx = (pfnSpiTransfer)spiTransferX; spiTxBlock = (pfnSpiTxBlock)spiTxBlockX; @@ -519,8 +519,8 @@ } _SS_WRITE(HIGH); - WRITE(MOSI_PIN, HIGH); - WRITE(SCK_PIN, LOW); + WRITE(SD_MOSI_PIN, HIGH); + WRITE(SD_SCK_PIN, LOW); } /** Begin SPI transaction, set clock, bit order, data mode */ @@ -575,20 +575,20 @@ // Configure SPI pins PIO_Configure( - g_APinDescription[SCK_PIN].pPort, - g_APinDescription[SCK_PIN].ulPinType, - g_APinDescription[SCK_PIN].ulPin, - g_APinDescription[SCK_PIN].ulPinConfiguration); + g_APinDescription[SD_SCK_PIN].pPort, + g_APinDescription[SD_SCK_PIN].ulPinType, + g_APinDescription[SD_SCK_PIN].ulPin, + g_APinDescription[SD_SCK_PIN].ulPinConfiguration); PIO_Configure( - g_APinDescription[MOSI_PIN].pPort, - g_APinDescription[MOSI_PIN].ulPinType, - g_APinDescription[MOSI_PIN].ulPin, - g_APinDescription[MOSI_PIN].ulPinConfiguration); + g_APinDescription[SD_MOSI_PIN].pPort, + g_APinDescription[SD_MOSI_PIN].ulPinType, + g_APinDescription[SD_MOSI_PIN].ulPin, + g_APinDescription[SD_MOSI_PIN].ulPinConfiguration); PIO_Configure( - g_APinDescription[MISO_PIN].pPort, - g_APinDescription[MISO_PIN].ulPinType, - g_APinDescription[MISO_PIN].ulPin, - g_APinDescription[MISO_PIN].ulPinConfiguration); + g_APinDescription[SD_MISO_PIN].pPort, + g_APinDescription[SD_MISO_PIN].ulPinType, + g_APinDescription[SD_MISO_PIN].ulPin, + g_APinDescription[SD_MISO_PIN].ulPinConfiguration); // set master mode, peripheral select, fault detection SPI_Configure(SPI0, ID_SPI0, SPI_MR_MSTR | SPI_MR_MODFDIS | SPI_MR_PS); @@ -606,7 +606,7 @@ WRITE(SPI_EEPROM1_CS, HIGH); WRITE(SPI_EEPROM2_CS, HIGH); WRITE(SPI_FLASH_CS, HIGH); - WRITE(SS_PIN, HIGH); + WRITE(SD_SS_PIN, HIGH); OUT_WRITE(SDSS, LOW); @@ -645,7 +645,7 @@ } // Read from SPI into buffer - void spiRead(uint8_t* buf, uint16_t nbyte) { + void spiRead(uint8_t *buf, uint16_t nbyte) { if (!nbyte) return; --nbyte; for (int i = 0; i < nbyte; i++) { @@ -668,7 +668,7 @@ //DELAY_US(1U); } - void spiSend(const uint8_t* buf, size_t nbyte) { + void spiSend(const uint8_t *buf, size_t nbyte) { if (!nbyte) return; --nbyte; for (size_t i = 0; i < nbyte; i++) { @@ -689,7 +689,7 @@ FLUSH_RX(); } - void spiSend(uint32_t chan, const uint8_t* buf, size_t nbyte) { + void spiSend(uint32_t chan, const uint8_t *buf, size_t nbyte) { if (!nbyte) return; --nbyte; for (size_t i = 0; i < nbyte; i++) { @@ -702,7 +702,7 @@ } // Write from buffer to SPI - void spiSendBlock(uint8_t token, const uint8_t* buf) { + void spiSendBlock(uint8_t token, const uint8_t *buf) { SPI0->SPI_TDR = (uint32_t)token | SPI_PCS(SPI_CHAN); WHILE_TX(0); //WHILE_RX(0); @@ -801,19 +801,19 @@ uint8_t spiRec() { return (uint8_t)spiTransfer(0xFF); } - void spiRead(uint8_t* buf, uint16_t nbyte) { + void spiRead(uint8_t *buf, uint16_t nbyte) { for (int i = 0; i < nbyte; i++) buf[i] = spiTransfer(0xFF); } void spiSend(uint8_t data) { spiTransfer(data); } - void spiSend(const uint8_t* buf, size_t nbyte) { + void spiSend(const uint8_t *buf, size_t nbyte) { for (uint16_t i = 0; i < nbyte; i++) spiTransfer(buf[i]); } - void spiSendBlock(uint8_t token, const uint8_t* buf) { + void spiSendBlock(uint8_t token, const uint8_t *buf) { spiTransfer(token); for (uint16_t i = 0; i < 512; i++) spiTransfer(buf[i]); diff --git a/Marlin/src/HAL/DUE/MarlinSerial.cpp b/Marlin/src/HAL/DUE/MarlinSerial.cpp index c9a372eeb14f..fe62ff5607d5 100644 --- a/Marlin/src/HAL/DUE/MarlinSerial.cpp +++ b/Marlin/src/HAL/DUE/MarlinSerial.cpp @@ -382,7 +382,7 @@ void MarlinSerial::flush() { } template -void MarlinSerial::write(const uint8_t c) { +size_t MarlinSerial::write(const uint8_t c) { _written = true; if (Cfg::TX_SIZE == 0) { @@ -400,7 +400,7 @@ void MarlinSerial::write(const uint8_t c) { // XOFF char at the RX isr, but it is properly handled there if (!(HWUART->UART_IMR & UART_IMR_TXRDY) && (HWUART->UART_SR & UART_SR_TXRDY)) { HWUART->UART_THR = c; - return; + return 1; } const uint8_t i = (tx_buffer.head + 1) & (Cfg::TX_SIZE - 1); @@ -428,6 +428,7 @@ void MarlinSerial::write(const uint8_t c) { // Enable TX isr - Non atomic, but it will eventually enable TX isr HWUART->UART_IER = UART_IER_TXRDY; } + return 1; } template @@ -473,169 +474,21 @@ void MarlinSerial::flushTX() { } } -/** - * Imports from print.h - */ - -template -void MarlinSerial::print(char c, int base) { - print((long)c, base); -} - -template -void MarlinSerial::print(unsigned char b, int base) { - print((unsigned long)b, base); -} - -template -void MarlinSerial::print(int n, int base) { - print((long)n, base); -} - -template -void MarlinSerial::print(unsigned int n, int base) { - print((unsigned long)n, base); -} - -template -void MarlinSerial::print(long n, int base) { - if (base == 0) write(n); - else if (base == 10) { - if (n < 0) { print('-'); n = -n; } - printNumber(n, 10); - } - else - printNumber(n, base); -} - -template -void MarlinSerial::print(unsigned long n, int base) { - if (base == 0) write(n); - else printNumber(n, base); -} - -template -void MarlinSerial::print(double n, int digits) { - printFloat(n, digits); -} - -template -void MarlinSerial::println() { - print('\r'); - print('\n'); -} - -template -void MarlinSerial::println(const String& s) { - print(s); - println(); -} - -template -void MarlinSerial::println(const char c[]) { - print(c); - println(); -} - -template -void MarlinSerial::println(char c, int base) { - print(c, base); - println(); -} - -template -void MarlinSerial::println(unsigned char b, int base) { - print(b, base); - println(); -} - -template -void MarlinSerial::println(int n, int base) { - print(n, base); - println(); -} - -template -void MarlinSerial::println(unsigned int n, int base) { - print(n, base); - println(); -} - -template -void MarlinSerial::println(long n, int base) { - print(n, base); - println(); -} - -template -void MarlinSerial::println(unsigned long n, int base) { - print(n, base); - println(); -} - -template -void MarlinSerial::println(double n, int digits) { - print(n, digits); - println(); -} - -// Private Methods -template -void MarlinSerial::printNumber(unsigned long n, uint8_t base) { - if (n) { - unsigned char buf[8 * sizeof(long)]; // Enough space for base 2 - int8_t i = 0; - while (n) { - buf[i++] = n % base; - n /= base; - } - while (i--) - print((char)(buf[i] + (buf[i] < 10 ? '0' : 'A' - 10))); - } - else - print('0'); -} - -template -void MarlinSerial::printFloat(double number, uint8_t digits) { - // Handle negative numbers - if (number < 0.0) { - print('-'); - number = -number; - } - - // Round correctly so that print(1.999, 2) prints as "2.00" - double rounding = 0.5; - LOOP_L_N(i, digits) rounding *= 0.1; - number += rounding; - - // Extract the integer part of the number and print it - unsigned long int_part = (unsigned long)number; - double remainder = number - (double)int_part; - print(int_part); - - // Print the decimal point, but only if there are digits beyond - if (digits) { - print('.'); - // Extract digits from the remainder one at a time - while (digits--) { - remainder *= 10.0; - int toPrint = int(remainder); - print(toPrint); - remainder -= toPrint; - } - } -} // If not using the USB port as serial port -#if SERIAL_PORT >= 0 - template class MarlinSerial>; // Define - MarlinSerial> customizedSerial1; // Instantiate +#if defined(SERIAL_PORT) && SERIAL_PORT >= 0 + template class MarlinSerial< MarlinSerialCfg >; + MSerialT1 customizedSerial1(MarlinSerialCfg::EMERGENCYPARSER); #endif #if defined(SERIAL_PORT_2) && SERIAL_PORT_2 >= 0 - template class MarlinSerial>; // Define - MarlinSerial> customizedSerial2; // Instantiate + template class MarlinSerial< MarlinSerialCfg >; + MSerialT2 customizedSerial2(MarlinSerialCfg::EMERGENCYPARSER); +#endif + +#if defined(SERIAL_PORT_3) && SERIAL_PORT_3 >= 0 + template class MarlinSerial< MarlinSerialCfg >; + MSerialT3 customizedSerial3(MarlinSerialCfg::EMERGENCYPARSER); #endif #endif // ARDUINO_ARCH_SAM diff --git a/Marlin/src/HAL/DUE/MarlinSerial.h b/Marlin/src/HAL/DUE/MarlinSerial.h index a194eba2f386..4a62e2834f7f 100644 --- a/Marlin/src/HAL/DUE/MarlinSerial.h +++ b/Marlin/src/HAL/DUE/MarlinSerial.h @@ -30,11 +30,7 @@ #include #include "../../inc/MarlinConfigPre.h" - -#define DEC 10 -#define HEX 16 -#define OCT 8 -#define BIN 2 +#include "../../core/serial_hook.h" // Define constants and variables for buffering incoming serial data. We're // using a ring buffer (I think), in which rx_buffer_head is the index of the @@ -119,7 +115,7 @@ class MarlinSerial { static int read(); static void flush(); static ring_buffer_pos_t available(); - static void write(const uint8_t c); + static size_t write(const uint8_t c); static void flushTX(); static inline bool emergency_parser_enabled() { return Cfg::EMERGENCYPARSER; } @@ -128,35 +124,6 @@ class MarlinSerial { FORCE_INLINE static uint8_t buffer_overruns() { return Cfg::RX_OVERRUNS ? rx_buffer_overruns : 0; } FORCE_INLINE static uint8_t framing_errors() { return Cfg::RX_FRAMING_ERRORS ? rx_framing_errors : 0; } FORCE_INLINE static ring_buffer_pos_t rxMaxEnqueued() { return Cfg::MAX_RX_QUEUED ? rx_max_enqueued : 0; } - - FORCE_INLINE static void write(const char* str) { while (*str) write(*str++); } - FORCE_INLINE static void write(const uint8_t* buffer, size_t size) { while (size--) write(*buffer++); } - FORCE_INLINE static void print(const String& s) { for (int i = 0; i < (int)s.length(); i++) write(s[i]); } - FORCE_INLINE static void print(const char* str) { write(str); } - - static void print(char, int = 0); - static void print(unsigned char, int = 0); - static void print(int, int = DEC); - static void print(unsigned int, int = DEC); - static void print(long, int = DEC); - static void print(unsigned long, int = DEC); - static void print(double, int = 2); - - static void println(const String& s); - static void println(const char[]); - static void println(char, int = 0); - static void println(unsigned char, int = 0); - static void println(int, int = DEC); - static void println(unsigned int, int = DEC); - static void println(long, int = DEC); - static void println(unsigned long, int = DEC); - static void println(double, int = 2); - static void println(); - operator bool() { return true; } - -private: - static void printNumber(unsigned long, const uint8_t); - static void printFloat(double, uint8_t); }; // Serial port configuration @@ -173,10 +140,17 @@ struct MarlinSerialCfg { static constexpr bool MAX_RX_QUEUED = ENABLED(SERIAL_STATS_MAX_RX_QUEUED); }; -#if SERIAL_PORT >= 0 - extern MarlinSerial> customizedSerial1; +#if defined(SERIAL_PORT) && SERIAL_PORT >= 0 + typedef Serial1Class< MarlinSerial< MarlinSerialCfg > > MSerialT1; + extern MSerialT1 customizedSerial1; #endif #if defined(SERIAL_PORT_2) && SERIAL_PORT_2 >= 0 - extern MarlinSerial> customizedSerial2; + typedef Serial1Class< MarlinSerial< MarlinSerialCfg > > MSerialT2; + extern MSerialT2 customizedSerial2; +#endif + +#if defined(SERIAL_PORT_3) && SERIAL_PORT_3 >= 0 + typedef Serial1Class< MarlinSerial< MarlinSerialCfg > > MSerialT3; + extern MSerialT3 customizedSerial3; #endif diff --git a/Marlin/src/HAL/DUE/MarlinSerialUSB.cpp b/Marlin/src/HAL/DUE/MarlinSerialUSB.cpp index a41dbfeb7a57..67c597da80c4 100644 --- a/Marlin/src/HAL/DUE/MarlinSerialUSB.cpp +++ b/Marlin/src/HAL/DUE/MarlinSerialUSB.cpp @@ -19,13 +19,13 @@ * along with this program. If not, see . * */ +#ifdef ARDUINO_ARCH_SAM /** * MarlinSerial_Due.cpp - Hardware serial library for Arduino DUE * Copyright (c) 2017 Eduardo José Tagle. All right reserved * Based on MarlinSerial for AVR, copyright (c) 2006 Nicholas Zambetti. All right reserved. */ -#ifdef ARDUINO_ARCH_SAM #include "../../inc/MarlinConfig.h" @@ -33,10 +33,6 @@ #include "MarlinSerialUSB.h" -#if ENABLED(EMERGENCY_PARSER) - #include "../../feature/e_parser.h" -#endif - // Imports from Atmel USB Stack/CDC implementation extern "C" { bool usb_task_cdc_isenabled(); @@ -50,10 +46,6 @@ extern "C" { // Pending character static int pending_char = -1; -#if ENABLED(EMERGENCY_PARSER) - static EmergencyParser::State emergency_state; // = EP_RESET -#endif - // Public Methods void MarlinSerialUSB::begin(const long) {} @@ -73,7 +65,7 @@ int MarlinSerialUSB::peek() { pending_char = udi_cdc_getc(); - TERN_(EMERGENCY_PARSER, emergency_parser.update(emergency_state, (char)pending_char)); + TERN_(EMERGENCY_PARSER, emergency_parser.update(static_cast(this)->emergency_state, (char)pending_char)); return pending_char; } @@ -95,29 +87,27 @@ int MarlinSerialUSB::read() { int c = udi_cdc_getc(); - TERN_(EMERGENCY_PARSER, emergency_parser.update(emergency_state, (char)c)); + TERN_(EMERGENCY_PARSER, emergency_parser.update(static_cast(this)->emergency_state, (char)c)); return c; } -bool MarlinSerialUSB::available() { - /* If Pending chars */ - return pending_char >= 0 || - /* or USB CDC enumerated and configured on the PC side and some - bytes where sent to us */ - (usb_task_cdc_isenabled() && udi_cdc_is_rx_ready()); +int MarlinSerialUSB::available() { + if (pending_char > 0) return pending_char; + return pending_char == 0 || + // or USB CDC enumerated and configured on the PC side and some bytes where sent to us */ + (usb_task_cdc_isenabled() && udi_cdc_is_rx_ready()); } void MarlinSerialUSB::flush() { } -void MarlinSerialUSB::flushTX() { } -void MarlinSerialUSB::write(const uint8_t c) { +size_t MarlinSerialUSB::write(const uint8_t c) { /* Do not even bother sending anything if USB CDC is not enumerated or not configured on the PC side or there is no program on the PC listening to our messages */ if (!usb_task_cdc_isenabled() || !usb_task_cdc_dtr_active()) - return; + return 0; /* Wait until the PC has read the pending to be sent data */ while (usb_task_cdc_isenabled() && @@ -129,161 +119,23 @@ void MarlinSerialUSB::write(const uint8_t c) { or not configured on the PC side or there is no program on the PC listening to our messages at this point */ if (!usb_task_cdc_isenabled() || !usb_task_cdc_dtr_active()) - return; + return 0; // Fifo full // udi_cdc_signal_overrun(); udi_cdc_putc(c); -} - -/** - * Imports from print.h - */ - -void MarlinSerialUSB::print(char c, int base) { - print((long)c, base); -} - -void MarlinSerialUSB::print(unsigned char b, int base) { - print((unsigned long)b, base); -} - -void MarlinSerialUSB::print(int n, int base) { - print((long)n, base); -} - -void MarlinSerialUSB::print(unsigned int n, int base) { - print((unsigned long)n, base); -} - -void MarlinSerialUSB::print(long n, int base) { - if (base == 0) - write(n); - else if (base == 10) { - if (n < 0) { - print('-'); - n = -n; - } - printNumber(n, 10); - } - else - printNumber(n, base); -} - -void MarlinSerialUSB::print(unsigned long n, int base) { - if (base == 0) write(n); - else printNumber(n, base); -} - -void MarlinSerialUSB::print(double n, int digits) { - printFloat(n, digits); -} - -void MarlinSerialUSB::println() { - print('\r'); - print('\n'); -} - -void MarlinSerialUSB::println(const String& s) { - print(s); - println(); -} - -void MarlinSerialUSB::println(const char c[]) { - print(c); - println(); -} - -void MarlinSerialUSB::println(char c, int base) { - print(c, base); - println(); -} - -void MarlinSerialUSB::println(unsigned char b, int base) { - print(b, base); - println(); -} - -void MarlinSerialUSB::println(int n, int base) { - print(n, base); - println(); -} - -void MarlinSerialUSB::println(unsigned int n, int base) { - print(n, base); - println(); -} - -void MarlinSerialUSB::println(long n, int base) { - print(n, base); - println(); -} - -void MarlinSerialUSB::println(unsigned long n, int base) { - print(n, base); - println(); -} - -void MarlinSerialUSB::println(double n, int digits) { - print(n, digits); - println(); -} - -// Private Methods - -void MarlinSerialUSB::printNumber(unsigned long n, uint8_t base) { - if (n) { - unsigned char buf[8 * sizeof(long)]; // Enough space for base 2 - int8_t i = 0; - while (n) { - buf[i++] = n % base; - n /= base; - } - while (i--) - print((char)(buf[i] + (buf[i] < 10 ? '0' : 'A' - 10))); - } - else - print('0'); -} - -void MarlinSerialUSB::printFloat(double number, uint8_t digits) { - // Handle negative numbers - if (number < 0.0) { - print('-'); - number = -number; - } - - // Round correctly so that print(1.999, 2) prints as "2.00" - double rounding = 0.5; - LOOP_L_N(i, digits) - rounding *= 0.1; - - number += rounding; - - // Extract the integer part of the number and print it - unsigned long int_part = (unsigned long)number; - double remainder = number - (double)int_part; - print(int_part); - - // Print the decimal point, but only if there are digits beyond - if (digits) { - print('.'); - // Extract digits from the remainder one at a time - while (digits--) { - remainder *= 10.0; - int toPrint = int(remainder); - print(toPrint); - remainder -= toPrint; - } - } + return 1; } // Preinstantiate #if SERIAL_PORT == -1 - MarlinSerialUSB customizedSerial1; + MSerialT1 customizedSerial1(TERN0(EMERGENCY_PARSER, true)); #endif #if SERIAL_PORT_2 == -1 - MarlinSerialUSB customizedSerial2; + MSerialT2 customizedSerial2(TERN0(EMERGENCY_PARSER, true)); +#endif +#if SERIAL_PORT_3 == -1 + MSerialT3 customizedSerial3(TERN0(EMERGENCY_PARSER, true)); #endif #endif // HAS_USB_SERIAL diff --git a/Marlin/src/HAL/DUE/MarlinSerialUSB.h b/Marlin/src/HAL/DUE/MarlinSerialUSB.h index 2e3622e5534a..6da1ef8c08f6 100644 --- a/Marlin/src/HAL/DUE/MarlinSerialUSB.h +++ b/Marlin/src/HAL/DUE/MarlinSerialUSB.h @@ -27,73 +27,39 @@ */ #include "../../inc/MarlinConfig.h" - -#if HAS_USB_SERIAL +#include "../../core/serial_hook.h" #include -#define DEC 10 -#define HEX 16 -#define OCT 8 -#define BIN 2 - -class MarlinSerialUSB { - -public: - MarlinSerialUSB() {}; - static void begin(const long); - static void end(); - static int peek(); - static int read(); - static void flush(); - static void flushTX(); - static bool available(); - static void write(const uint8_t c); +struct MarlinSerialUSB { + void begin(const long); + void end(); + int peek(); + int read(); + void flush(); + int available(); + size_t write(const uint8_t c); #if ENABLED(SERIAL_STATS_DROPPED_RX) - FORCE_INLINE static uint32_t dropped() { return 0; } + FORCE_INLINE uint32_t dropped() { return 0; } #endif #if ENABLED(SERIAL_STATS_MAX_RX_QUEUED) - FORCE_INLINE static int rxMaxEnqueued() { return 0; } + FORCE_INLINE int rxMaxEnqueued() { return 0; } #endif - - FORCE_INLINE static void write(const char* str) { while (*str) write(*str++); } - FORCE_INLINE static void write(const uint8_t* buffer, size_t size) { while (size--) write(*buffer++); } - FORCE_INLINE static void print(const String& s) { for (int i = 0; i < (int)s.length(); i++) write(s[i]); } - FORCE_INLINE static void print(const char* str) { write(str); } - - static void print(char, int = 0); - static void print(unsigned char, int = 0); - static void print(int, int = DEC); - static void print(unsigned int, int = DEC); - static void print(long, int = DEC); - static void print(unsigned long, int = DEC); - static void print(double, int = 2); - - static void println(const String& s); - static void println(const char[]); - static void println(char, int = 0); - static void println(unsigned char, int = 0); - static void println(int, int = DEC); - static void println(unsigned int, int = DEC); - static void println(long, int = DEC); - static void println(unsigned long, int = DEC); - static void println(double, int = 2); - static void println(); - operator bool() { return true; } - -private: - static void printNumber(unsigned long, const uint8_t); - static void printFloat(double, uint8_t); }; #if SERIAL_PORT == -1 - extern MarlinSerialUSB customizedSerial1; + typedef Serial1Class MSerialT1; + extern MSerialT1 customizedSerial1; #endif #if SERIAL_PORT_2 == -1 - extern MarlinSerialUSB customizedSerial2; + typedef Serial1Class MSerialT2; + extern MSerialT2 customizedSerial2; #endif -#endif // HAS_USB_SERIAL +#if SERIAL_PORT_3 == -1 + typedef Serial1Class MSerialT3; + extern MSerialT3 customizedSerial3; +#endif diff --git a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_shared_hw_spi.cpp b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_shared_hw_spi.cpp index be4b49c0f992..fcfcef88beb1 100644 --- a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_shared_hw_spi.cpp +++ b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_shared_hw_spi.cpp @@ -60,16 +60,15 @@ #if HAS_MARLINUI_U8GLIB -#include +#include #include "../../../MarlinCore.h" -void spiBegin(); -void spiInit(uint8_t spiRate); -void spiSend(uint8_t b); -void spiSend(const uint8_t* buf, size_t n); +#ifndef LCD_SPI_SPEED + #define LCD_SPI_SPEED SPI_QUARTER_SPEED +#endif -#include "../../shared/Marduino.h" +#include "../../shared/HAL_SPI.h" #include "../fastio.h" void u8g_SetPIOutput_DUE_hw_spi(u8g_t *u8g, uint8_t pin_index) { @@ -100,11 +99,7 @@ uint8_t u8g_com_HAL_DUE_shared_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_va spiBegin(); - #ifndef SPI_SPEED - #define SPI_SPEED SPI_FULL_SPEED // use same SPI speed as SD card - #endif - spiInit(2); - + spiInit(LCD_SPI_SPEED); break; case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */ diff --git a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_st7920_sw_spi.cpp b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_st7920_sw_spi.cpp index 47060d6a5be2..65bfd4f4e2d4 100644 --- a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_st7920_sw_spi.cpp +++ b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_st7920_sw_spi.cpp @@ -59,9 +59,10 @@ #if ENABLED(U8GLIB_ST7920) +#include "../../../inc/MarlinConfig.h" #include "../../shared/Delay.h" -#include +#include #include "u8g_com_HAL_DUE_sw_spi_shared.h" @@ -145,7 +146,7 @@ uint8_t u8g_com_HAL_DUE_ST7920_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_va } #if ENABLED(LIGHTWEIGHT_UI) - #include "../../../lcd/ultralcd.h" + #include "../../../lcd/marlinui.h" #include "../../shared/HAL_ST7920.h" #define ST7920_CS_PIN LCD_PINS_RS diff --git a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi.cpp b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi.cpp index ea7204fa366b..2b13c182d023 100644 --- a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi.cpp +++ b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi.cpp @@ -59,15 +59,12 @@ #if HAS_MARLINUI_U8GLIB && DISABLED(U8GLIB_ST7920) -#undef SPI_SPEED -#define SPI_SPEED 2 // About 2 MHz - #include "u8g_com_HAL_DUE_sw_spi_shared.h" #include "../../shared/Marduino.h" #include "../../shared/Delay.h" -#include +#include #if ENABLED(FYSETC_MINI_12864) #define SPISEND_SW_DUE u8g_spiSend_sw_DUE_mode_3 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 615a386c3542..904924793b4c 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 @@ -59,9 +59,10 @@ #if HAS_MARLINUI_U8GLIB +#include "../../../inc/MarlinConfig.h" #include "../../shared/Delay.h" -#include +#include #include "u8g_com_HAL_DUE_sw_spi_shared.h" diff --git a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.h b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.h index f076c503cac2..45231fd091eb 100644 --- a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.h +++ b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.h @@ -23,7 +23,7 @@ #include "../../../inc/MarlinConfigPre.h" #include "../../shared/Marduino.h" -#include +#include void u8g_SetPIOutput_DUE(u8g_t *u8g, uint8_t pin_index); void u8g_SetPILevel_DUE(u8g_t *u8g, uint8_t pin_index, uint8_t level); diff --git a/Marlin/src/HAL/DUE/eeprom_flash.cpp b/Marlin/src/HAL/DUE/eeprom_flash.cpp index 6f38da0967cb..b4cb9912b24f 100644 --- a/Marlin/src/HAL/DUE/eeprom_flash.cpp +++ b/Marlin/src/HAL/DUE/eeprom_flash.cpp @@ -135,11 +135,11 @@ static uint8_t buffer[256] = {0}, // The RAM buffer to accumulate writes #define DEBUG_OUT ENABLED(EE_EMU_DEBUG) #include "../../core/debug_out.h" -static void ee_Dump(const int page, const void* data) { +static void ee_Dump(const int page, const void *data) { #ifdef EE_EMU_DEBUG - const uint8_t* c = (const uint8_t*) data; + const uint8_t *c = (const uint8_t*) data; char buffer[80]; sprintf_P(buffer, PSTR("Page: %d (0x%04x)\n"), page, page); @@ -181,7 +181,7 @@ static void ee_Dump(const int page, const void* data) { * @param data (pointer to the data buffer) */ __attribute__ ((long_call, section (".ramfunc"))) -static bool ee_PageWrite(uint16_t page, const void* data) { +static bool ee_PageWrite(uint16_t page, const void *data) { uint16_t i; uint32_t addrflash = uint32_t(getFlashStorage(page)); @@ -293,8 +293,8 @@ static bool ee_PageWrite(uint16_t page, const void* data) { ee_Dump(-page, data); // Calculate count of changed bits - uint32_t* p1 = (uint32_t*)addrflash; - uint32_t* p2 = (uint32_t*)data; + uint32_t *p1 = (uint32_t*)addrflash; + uint32_t *p2 = (uint32_t*)data; int count = 0; for (i =0; i> 2; i++) { if (p1[i] != p2[i]) { @@ -470,7 +470,7 @@ static uint8_t ee_Read(uint32_t address, bool excludeRAMBuffer=false) { for (int page = curPage - 1; page >= 0; --page) { // Get a pointer to the flash page - uint8_t* pflash = (uint8_t*)getFlashStorage(page + curGroup * PagesPerGroup); + uint8_t *pflash = (uint8_t*)getFlashStorage(page + curGroup * PagesPerGroup); uint16_t i = 0; while (i <= (PageSize - 4)) { /* (PageSize - 4) because otherwise, there is not enough room for data and headers */ @@ -550,7 +550,7 @@ static uint32_t ee_GetAddrRange(uint32_t address, bool excludeRAMBuffer=false) { for (int page = curPage - 1; page >= 0; --page) { // Get a pointer to the flash page - uint8_t* pflash = (uint8_t*)getFlashStorage(page + curGroup * PagesPerGroup); + uint8_t *pflash = (uint8_t*)getFlashStorage(page + curGroup * PagesPerGroup); uint16_t i = 0; while (i <= (PageSize - 4)) { /* (PageSize - 4) because otherwise, there is not enough room for data and headers */ @@ -589,7 +589,7 @@ static uint32_t ee_GetAddrRange(uint32_t address, bool excludeRAMBuffer=false) { } static bool ee_IsPageClean(int page) { - uint32_t* pflash = (uint32_t*) getFlashStorage(page); + uint32_t *pflash = (uint32_t*) getFlashStorage(page); for (uint16_t i = 0; i < (PageSize >> 2); ++i) if (*pflash++ != 0xFFFFFFFF) return false; return true; @@ -599,7 +599,7 @@ static bool ee_Flush(uint32_t overrideAddress = 0xFFFFFFFF, uint8_t overrideData // Check if RAM buffer has something to be written bool isEmpty = true; - uint32_t* p = (uint32_t*) &buffer[0]; + uint32_t *p = (uint32_t*) &buffer[0]; for (uint16_t j = 0; j < (PageSize >> 2); j++) { if (*p++ != 0xFFFFFFFF) { isEmpty = false; @@ -976,14 +976,13 @@ bool PersistentStore::access_start() { ee_Init(); return true; } bool PersistentStore::access_finish() { ee_Flush(); return true; } bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + uint16_t written = 0; while (size--) { uint8_t * const p = (uint8_t * const)pos; uint8_t v = *value; - // EEPROM has only ~100,000 write cycles, - // so only write bytes that have changed! - if (v != ee_Read(uint32_t(p))) { + if (v != ee_Read(uint32_t(p))) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed! ee_Write(uint32_t(p), v); - delay(2); + if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes if (ee_Read(uint32_t(p)) != v) { SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); return true; @@ -996,7 +995,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui return false; } -bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { +bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { do { uint8_t c = ee_Read(uint32_t(pos)); if (writing) *value = c; diff --git a/Marlin/src/HAL/DUE/eeprom_wired.cpp b/Marlin/src/HAL/DUE/eeprom_wired.cpp index 4599d6a7cd44..557a2f2cffa5 100644 --- a/Marlin/src/HAL/DUE/eeprom_wired.cpp +++ b/Marlin/src/HAL/DUE/eeprom_wired.cpp @@ -42,14 +42,13 @@ bool PersistentStore::access_start() { eeprom_init(); return true; } bool PersistentStore::access_finish() { return true; } bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + uint16_t written = 0; while (size--) { uint8_t * const p = (uint8_t * const)pos; uint8_t v = *value; - // EEPROM has only ~100,000 write cycles, - // so only write bytes that have changed! - if (v != eeprom_read_byte(p)) { + if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed! eeprom_write_byte(p, v); - delay(2); + if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes if (eeprom_read_byte(p) != v) { SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); return true; @@ -62,7 +61,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui return false; } -bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { +bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { do { uint8_t c = eeprom_read_byte((uint8_t*)pos); if (writing) *value = c; diff --git a/Marlin/src/HAL/DUE/endstop_interrupts.h b/Marlin/src/HAL/DUE/endstop_interrupts.h index 999ada512761..9c7e2104882e 100644 --- a/Marlin/src/HAL/DUE/endstop_interrupts.h +++ b/Marlin/src/HAL/DUE/endstop_interrupts.h @@ -64,4 +64,10 @@ void setup_endstop_interrupts() { TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); TERN_(HAS_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)); } diff --git a/Marlin/src/HAL/DUE/fastio.h b/Marlin/src/HAL/DUE/fastio.h index 286319302dd2..a609210d8130 100644 --- a/Marlin/src/HAL/DUE/fastio.h +++ b/Marlin/src/HAL/DUE/fastio.h @@ -33,7 +33,7 @@ * For ARDUINO_ARCH_SAM * Note the code here was specifically crafted by disassembling what GCC produces * out of it, so GCC is able to optimize it out as much as possible to the least - * amount of instructions. Be very carefull if you modify them, as "clean code" + * amount of instructions. Be very careful if you modify them, as "clean code" * leads to less efficient compiled code!! */ @@ -50,7 +50,7 @@ #define PWM_PIN(P) WITHIN(P, 2, 13) #ifndef MASK - #define MASK(PIN) (1 << PIN) + #define MASK(PIN) _BV(PIN) #endif /** @@ -163,6 +163,9 @@ #define SET_INPUT(IO) _SET_INPUT(IO) // Set pin as input with pullup (wrapper) #define SET_INPUT_PULLUP(IO) do{ _SET_INPUT(IO); _PULLUP(IO, HIGH); }while(0) +// Set pin as input with pulldown (substitution) +#define SET_INPUT_PULLDOWN SET_INPUT + // Set pin as output (wrapper) - reads the pin and sets the output to that value #define SET_OUTPUT(IO) _SET_OUTPUT(IO) // Set pin as PWM @@ -477,7 +480,7 @@ #define DIO91_PIN 15 #define DIO91_WPORT PIOB -#if ARDUINO_SAM_ARCHIM +#ifdef ARDUINO_SAM_ARCHIM #define DIO92_PIN 11 #define DIO92_WPORT PIOC diff --git a/Marlin/src/HAL/DUE/inc/SanityCheck.h b/Marlin/src/HAL/DUE/inc/SanityCheck.h index 688069650630..87b09cf29257 100644 --- a/Marlin/src/HAL/DUE/inc/SanityCheck.h +++ b/Marlin/src/HAL/DUE/inc/SanityCheck.h @@ -40,7 +40,7 @@ * 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 == MOSI_PIN || TMC_SW_##P == MISO_PIN || TMC_SW_##P == SCK_PIN)) +#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)) #if ENABLED(SDSUPPORT) && HAS_DRIVER(TMC2130) #if ENABLED(TMC_USE_SW_SPI) @@ -57,5 +57,5 @@ #endif #if HAS_TMC_SW_SERIAL - #error "TMC220x Software Serial is not supported on this platform." + #error "TMC220x Software Serial is not supported on the DUE platform." #endif diff --git a/Marlin/src/HAL/DUE/spi_pins.h b/Marlin/src/HAL/DUE/spi_pins.h index e28eaf827020..cec22c2c374a 100644 --- a/Marlin/src/HAL/DUE/spi_pins.h +++ b/Marlin/src/HAL/DUE/spi_pins.h @@ -43,22 +43,22 @@ #define SPI_PIN 87 #define SPI_CHAN 1 #endif - #define SCK_PIN 76 - #define MISO_PIN 74 - #define MOSI_PIN 75 + #define SD_SCK_PIN 76 + #define SD_MISO_PIN 74 + #define SD_MOSI_PIN 75 #else // defaults #define DUE_SOFTWARE_SPI - #ifndef SCK_PIN - #define SCK_PIN 52 + #ifndef SD_SCK_PIN + #define SD_SCK_PIN 52 #endif - #ifndef MISO_PIN - #define MISO_PIN 50 + #ifndef SD_MISO_PIN + #define SD_MISO_PIN 50 #endif - #ifndef MOSI_PIN - #define MOSI_PIN 51 + #ifndef SD_MOSI_PIN + #define SD_MOSI_PIN 51 #endif #endif /* A.28, A.29, B.21, C.26, C.29 */ -#define SS_PIN SDSS +#define SD_SS_PIN SDSS diff --git a/Marlin/src/HAL/DUE/timers.cpp b/Marlin/src/HAL/DUE/timers.cpp index 9b937d1a7c83..65073c510d7c 100644 --- a/Marlin/src/HAL/DUE/timers.cpp +++ b/Marlin/src/HAL/DUE/timers.cpp @@ -121,7 +121,7 @@ void HAL_timer_disable_interrupt(const uint8_t timer_num) { // missing from CMSIS: Check if interrupt is enabled or not static bool NVIC_GetEnabledIRQ(IRQn_Type IRQn) { - return (NVIC->ISER[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F))) != 0; + return TEST(NVIC->ISER[uint32_t(IRQn) >> 5], uint32_t(IRQn) & 0x1F); } bool HAL_timer_interrupt_enabled(const uint8_t timer_num) { diff --git a/Marlin/src/HAL/DUE/usb/arduino_due_x.h b/Marlin/src/HAL/DUE/usb/arduino_due_x.h index d3b333fb349a..e7b6f3dcb303 100644 --- a/Marlin/src/HAL/DUE/usb/arduino_due_x.h +++ b/Marlin/src/HAL/DUE/usb/arduino_due_x.h @@ -71,7 +71,7 @@ /* ------------------------------------------------------------------------ */ /** - * \page arduino_due_x_board_info "Arduino Due/X - Board informations" + * \page arduino_due_x_board_info "Arduino Due/X - Board information" * This page lists several definition related to the board description. * */ 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 ea2936359d81..3dcbbaecd28f 100644 --- a/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.cpp +++ b/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.cpp @@ -32,7 +32,7 @@ Ctrl_status sd_mmc_spi_test_unit_ready() { Ctrl_status sd_mmc_spi_read_capacity(uint32_t *nb_sector) { if (!IS_SD_INSERTED() || IS_SD_PRINTING() || IS_SD_FILE_OPEN() || !card.isMounted()) return CTRL_NO_PRESENT; - *nb_sector = card.getSd2Card().cardSize() - 1; + *nb_sector = card.diskIODriver()->cardSize() - 1; return CTRL_GOOD; } @@ -68,30 +68,30 @@ Ctrl_status sd_mmc_spi_usb_read_10(uint32_t addr, uint16_t nb_sector) { { char buffer[80]; sprintf_P(buffer, PSTR("SDRD: %d @ 0x%08x\n"), nb_sector, addr); - PORT_REDIRECT(0); + PORT_REDIRECT(SERIAL_PORTMASK(0)); SERIAL_ECHO(buffer); } #endif // Start reading - if (!card.getSd2Card().readStart(addr)) + if (!card.diskIODriver()->readStart(addr)) return CTRL_FAIL; // For each specified sector while (nb_sector--) { // Read a sector - card.getSd2Card().readData(sector_buf); + card.diskIODriver()->readData(sector_buf); // RAM -> USB - if (!udi_msc_trans_block(true, sector_buf, SD_MMC_BLOCK_SIZE, NULL)) { - card.getSd2Card().readStop(); + if (!udi_msc_trans_block(true, sector_buf, SD_MMC_BLOCK_SIZE, nullptr)) { + card.diskIODriver()->readStop(); return CTRL_FAIL; } } // Stop reading - card.getSd2Card().readStop(); + card.diskIODriver()->readStop(); // Done return CTRL_GOOD; @@ -108,29 +108,29 @@ Ctrl_status sd_mmc_spi_usb_write_10(uint32_t addr, uint16_t nb_sector) { { char buffer[80]; sprintf_P(buffer, PSTR("SDWR: %d @ 0x%08x\n"), nb_sector, addr); - PORT_REDIRECT(0); + PORT_REDIRECT(SERIAL_PORTMASK(0)); SERIAL_ECHO(buffer); } #endif - if (!card.getSd2Card().writeStart(addr, nb_sector)) + if (!card.diskIODriver()->writeStart(addr, nb_sector)) return CTRL_FAIL; // For each specified sector while (nb_sector--) { // USB -> RAM - if (!udi_msc_trans_block(false, sector_buf, SD_MMC_BLOCK_SIZE, NULL)) { - card.getSd2Card().writeStop(); + if (!udi_msc_trans_block(false, sector_buf, SD_MMC_BLOCK_SIZE, nullptr)) { + card.diskIODriver()->writeStop(); return CTRL_FAIL; } // Write a sector - card.getSd2Card().writeData(sector_buf); + card.diskIODriver()->writeData(sector_buf); } // Stop writing - card.getSd2Card().writeStop(); + card.diskIODriver()->writeStop(); // Done return CTRL_GOOD; 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 d77e4f95232b..553fd3c29a88 100644 --- a/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.h +++ b/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.h @@ -74,7 +74,7 @@ #define SD_MMC_REMOVING 2 -//---- CONTROL FONCTIONS ---- +//---- CONTROL FUNCTIONS ---- //! //! @brief This function initializes the hw/sw resources required to drive the SD_MMC_SPI. //!/ @@ -134,7 +134,7 @@ extern bool sd_mmc_spi_wr_protect(void); extern bool sd_mmc_spi_removal(void); -//---- ACCESS DATA FONCTIONS ---- +//---- ACCESS DATA FUNCTIONS ---- #if ACCESS_USB == true // Standard functions for open in read/write mode the device diff --git a/Marlin/src/HAL/DUE/usb/udd.h b/Marlin/src/HAL/DUE/usb/udd.h index 7ec8c03dee63..319d8842f744 100644 --- a/Marlin/src/HAL/DUE/usb/udd.h +++ b/Marlin/src/HAL/DUE/usb/udd.h @@ -90,7 +90,7 @@ typedef struct { //! 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 transfered + //! 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 @@ -132,10 +132,10 @@ typedef void (*udd_callback_halt_cleared_t)(void); * * \param status UDD_EP_TRANSFER_OK, if transfer is complete * \param status UDD_EP_TRANSFER_ABORT, if transfer is aborted - * \param n number of data transfered + * \param n number of data transferred */ typedef void (*udd_callback_trans_t) (udd_ep_status_t status, - iram_size_t nb_transfered, udd_ep_id_t ep); + iram_size_t nb_transferred, udd_ep_id_t ep); /** * \brief Authorizes the VBUS event @@ -303,7 +303,7 @@ bool udd_ep_wait_stall_clear(udd_ep_id_t ep, * The driver uses a specific DMA USB to transfer data * from internal RAM to endpoint, if this one is available. * When the transfer is finished or aborted (stall, reset, ...), the \a callback is called. - * The \a callback returns the transfer status and eventually the number of byte transfered. + * The \a callback returns the transfer status and eventually the number of byte transferred. * Note: The control endpoint is not authorized. * * \param ep The ID of the endpoint to use diff --git a/Marlin/src/HAL/DUE/usb/udi_cdc.c b/Marlin/src/HAL/DUE/usb/udi_cdc.c index cbe23dbb68fb..89debe57f130 100644 --- a/Marlin/src/HAL/DUE/usb/udi_cdc.c +++ b/Marlin/src/HAL/DUE/usb/udi_cdc.c @@ -162,7 +162,7 @@ static void udi_cdc_ctrl_state_notify(uint8_t port, udd_ep_id_t ep); * * \param status UDD_EP_TRANSFER_OK, if transfer finished * \param status UDD_EP_TRANSFER_ABORT, if transfer aborted - * \param n number of data transfered + * \param n number of data transferred */ static void udi_cdc_serial_state_msg_sent(udd_ep_status_t status, iram_size_t n, udd_ep_id_t ep); @@ -200,7 +200,7 @@ static void udi_cdc_data_received(udd_ep_status_t status, iram_size_t n, udd_ep_ * * \param status UDD_EP_TRANSFER_OK, if transfer finished * \param status UDD_EP_TRANSFER_ABORT, if transfer aborted - * \param n number of data transfered + * \param n number of data transferred */ static void udi_cdc_data_sent(udd_ep_status_t status, iram_size_t n, udd_ep_id_t ep); diff --git a/Marlin/src/HAL/DUE/usb/udi_cdc.h b/Marlin/src/HAL/DUE/usb/udi_cdc.h index 0ecf7bb00e5e..b61845011aa2 100644 --- a/Marlin/src/HAL/DUE/usb/udi_cdc.h +++ b/Marlin/src/HAL/DUE/usb/udi_cdc.h @@ -675,11 +675,11 @@ iram_size_t udi_cdc_multi_write_buf(uint8_t port, const void* buf, iram_size_t s * - \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); + 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 + 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: diff --git a/Marlin/src/HAL/DUE/usb/udi_cdc_conf.h b/Marlin/src/HAL/DUE/usb/udi_cdc_conf.h index d406a87743f3..e61b8cbaadf4 100644 --- a/Marlin/src/HAL/DUE/usb/udi_cdc_conf.h +++ b/Marlin/src/HAL/DUE/usb/udi_cdc_conf.h @@ -106,7 +106,7 @@ extern "C" { */ //@{ # if UDI_CDC_PORT_NB > 2 -# error USBB, UDP, UDPHS and UOTGHS interfaces have not enought endpoints. +# error USBB, UDP, UDPHS and UOTGHS interfaces have not enough endpoints. # endif #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 diff --git a/Marlin/src/HAL/DUE/usb/udi_msc.c b/Marlin/src/HAL/DUE/usb/udi_msc.c index b7c3bb5ea016..dd3404877210 100644 --- a/Marlin/src/HAL/DUE/usb/udi_msc.c +++ b/Marlin/src/HAL/DUE/usb/udi_msc.c @@ -173,7 +173,7 @@ static void udi_msc_cbw_wait(void); * * \param status UDD_EP_TRANSFER_OK, if transfer is finished * \param status UDD_EP_TRANSFER_ABORT, if transfer is aborted - * \param nb_received number of data transfered + * \param nb_received number of data transferred */ static void udi_msc_cbw_received(udd_ep_status_t status, iram_size_t nb_received, udd_ep_id_t ep); @@ -211,7 +211,7 @@ static void udi_msc_data_send(uint8_t * buffer, uint8_t buf_size); * * \param status UDD_EP_TRANSFER_OK, if transfer finish * \param status UDD_EP_TRANSFER_ABORT, if transfer aborted - * \param nb_sent number of data transfered + * \param nb_sent number of data transferred */ static void udi_msc_data_sent(udd_ep_status_t status, iram_size_t nb_sent, udd_ep_id_t ep); @@ -244,7 +244,7 @@ void udi_msc_csw_send(void); * * \param status UDD_EP_TRANSFER_OK, if transfer is finished * \param status UDD_EP_TRANSFER_ABORT, if transfer is aborted - * \param nb_sent number of data transfered + * \param nb_sent number of data transferred */ static void udi_msc_csw_sent(udd_ep_status_t status, iram_size_t nb_sent, udd_ep_id_t ep); @@ -463,7 +463,7 @@ uint8_t udi_msc_getsetting(void) static void udi_msc_cbw_invalid(void) { if (!udi_msc_b_cbw_invalid) - return; // Don't re-stall endpoint if error reseted by setup + return; // Don't re-stall endpoint if error reset by setup udd_ep_set_halt(UDI_MSC_EP_OUT); // If stall cleared then re-stall it. Only Setup MSC Reset can clear it udd_ep_wait_stall_clear(UDI_MSC_EP_OUT, udi_msc_cbw_invalid); @@ -472,7 +472,7 @@ static void udi_msc_cbw_invalid(void) static void udi_msc_csw_invalid(void) { if (!udi_msc_b_cbw_invalid) - return; // Don't re-stall endpoint if error reseted by setup + return; // Don't re-stall endpoint if error reset by setup udd_ep_set_halt(UDI_MSC_EP_IN); // If stall cleared then re-stall it. Only Setup MSC Reset can clear it udd_ep_wait_stall_clear(UDI_MSC_EP_IN, udi_msc_csw_invalid); diff --git a/Marlin/src/HAL/DUE/usb/uotghs_device_due.c b/Marlin/src/HAL/DUE/usb/uotghs_device_due.c index e13232a39c7d..c7e8f8d99135 100644 --- a/Marlin/src/HAL/DUE/usb/uotghs_device_due.c +++ b/Marlin/src/HAL/DUE/usb/uotghs_device_due.c @@ -325,7 +325,7 @@ static void udd_sleep_mode(bool b_idle) /** * \name Control endpoint low level management routine. * - * This function performs control endpoint mangement. + * This function performs control endpoint management. * It handle the SETUP/DATA/HANDSHAKE phases of a control transaction. */ //@{ @@ -397,9 +397,9 @@ static void udd_ctrl_endofrequest(void); /** * \brief Main interrupt routine for control endpoint * - * This switchs control endpoint events to correct sub function. + * This switches control endpoint events to correct sub function. * - * \return \c 1 if an event about control endpoint is occured, otherwise \c 0. + * \return \c 1 if an event about control endpoint is occurred, otherwise \c 0. */ static bool udd_ctrl_interrupt(void); @@ -410,7 +410,7 @@ static bool udd_ctrl_interrupt(void); * \name Management of bulk/interrupt/isochronous endpoints * * The UDD manages the data transfer on endpoints: - * - Start data tranfer on endpoint with USB Device DMA + * - Start data transfer on endpoint with USB Device DMA * - Send a ZLP packet if requested * - Call callback registered to signal end of transfer * The transfer abort and stall feature are supported. @@ -431,7 +431,7 @@ typedef struct { uint8_t *buf; //! Size of buffer to send or fill iram_size_t buf_size; - //!< Size of data transfered + //!< Size of data transferred iram_size_t buf_cnt; //!< Size of data loaded (or prepared for DMA) last time iram_size_t buf_load; @@ -486,7 +486,7 @@ static void udd_ep_finish_job(udd_ep_job_t * ptr_job, bool b_abort, uint8_t ep_n #ifdef UDD_EP_DMA_SUPPORTED /** - * \brief Start the next transfer if necessary or complet the job associated. + * \brief Start the next transfer if necessary or complete the job associated. * * \param ep endpoint number without direction flag */ @@ -496,9 +496,9 @@ static void udd_ep_finish_job(udd_ep_job_t * ptr_job, bool b_abort, uint8_t ep_n /** * \brief Main interrupt routine for bulk/interrupt/isochronous endpoints * - * This switchs endpoint events to correct sub function. + * This switches endpoint events to correct sub function. * - * \return \c 1 if an event about bulk/interrupt/isochronous endpoints has occured, otherwise \c 0. + * \return \c 1 if an event about bulk/interrupt/isochronous endpoints has occurred, otherwise \c 0. */ static bool udd_ep_interrupt(void); @@ -520,7 +520,7 @@ static bool udd_ep_interrupt(void); * * Note: * Here, the global interrupt mask is not clear when an USB interrupt is enabled - * because this one can not be occured during the USB ISR (=during INTX is masked). + * because this one can not be occurred during the USB ISR (=during INTX is masked). * See Technical reference $3.8.3 Masking interrupt requests in peripheral modules. */ #ifdef UHD_ENABLE @@ -787,7 +787,7 @@ void udd_attach(void) udd_sleep_mode(true); otg_unfreeze_clock(); - // This section of clock check can be improved with a chek of + // This section of clock check can be improved with a check of // USB clock source via sysclk() // Check USB clock because the source can be a PLL while (!Is_otg_clock_usable()); @@ -803,7 +803,7 @@ void udd_attach(void) #ifdef USB_DEVICE_HS_SUPPORT udd_enable_msof_interrupt(); #endif - // Reset following interupts flag + // Reset following interrupts flag udd_ack_reset(); udd_ack_sof(); udd_ack_msof(); @@ -902,7 +902,7 @@ bool udd_ep_alloc(udd_ep_id_t ep, uint8_t bmAttributes, } dbg_print("alloc(%x, %d) ", ep, MaxEndpointSize); - // Bank choise + // Bank choice switch (bmAttributes & USB_EP_TYPE_MASK) { case USB_EP_TYPE_ISOCHRONOUS: nb_bank = UDD_ISOCHRONOUS_NB_BANK(ep); @@ -1228,7 +1228,7 @@ bool udd_ep_wait_stall_clear(udd_ep_id_t ep, if (Is_udd_endpoint_stall_requested(ep) || ptr_job->stall_requested) { - // Endpoint halted then registes the callback + // Endpoint halted then registers the callback ptr_job->busy = true; ptr_job->call_nohalt = callback; } else { @@ -1386,7 +1386,7 @@ static void udd_ctrl_setup_received(void) // Decode setup request if (udc_process_setup() == false) { - // Setup request unknow then stall it + // Setup request unknown then stall it udd_ctrl_stall_data(); udd_ack_setup_received(0); return; @@ -1447,7 +1447,7 @@ static void udd_ctrl_in_sent(void) udd_ctrl_prev_payload_buf_cnt += udd_ctrl_payload_buf_cnt; if ((udd_g_ctrlreq.req.wLength == udd_ctrl_prev_payload_buf_cnt) || b_shortpacket) { - // All data requested are transfered or a short packet has been sent + // All data requested are transferred or a short packet has been sent // then it is the end of data phase. // Generate an OUT ZLP for handshake phase. udd_ctrl_send_zlp_out(); @@ -1516,7 +1516,7 @@ static void udd_ctrl_out_received(void) // End of SETUP request: // - Data IN Phase aborted, // - or last Data IN Phase hidden by ZLP OUT sending quiclky, - // - or ZLP OUT received normaly. + // - or ZLP OUT received normally. udd_ctrl_endofrequest(); } else { // Protocol error during SETUP request @@ -1544,7 +1544,7 @@ static void udd_ctrl_out_received(void) (udd_ctrl_prev_payload_buf_cnt + udd_ctrl_payload_buf_cnt))) { // End of reception because it is a short packet - // Before send ZLP, call intermediat calback + // Before send ZLP, call intermediate callback // in case of data receiv generate a stall udd_g_ctrlreq.payload_size = udd_ctrl_payload_buf_cnt; if (NULL != udd_g_ctrlreq.over_under_run) { @@ -1565,7 +1565,7 @@ static void udd_ctrl_out_received(void) if (udd_g_ctrlreq.payload_size == udd_ctrl_payload_buf_cnt) { // Overrun then request a new payload buffer if (!udd_g_ctrlreq.over_under_run) { - // No callback availabled to request a new payload buffer + // No callback available to request a new payload buffer udd_ctrl_stall_data(); // Ack reception of OUT to replace NAK by a STALL udd_ack_out_received(0); @@ -1805,7 +1805,7 @@ static void udd_ep_trans_done(udd_ep_id_t ep) // transfer size of UDD_ENDPOINT_MAX_TRANS Bytes next_trans = UDD_ENDPOINT_MAX_TRANS; - // Set 0 to tranfer the maximum + // Set 0 to transfer the maximum udd_dma_ctrl = UOTGHS_DEVDMACONTROL_BUFF_LENGTH(0); } else { udd_dma_ctrl = UOTGHS_DEVDMACONTROL_BUFF_LENGTH(next_trans); @@ -1850,7 +1850,7 @@ static void udd_ep_trans_done(udd_ep_id_t ep) } cpu_irq_restore(flags); - // Here a ZLP has been recieved + // Here a ZLP has been received // and the DMA transfer must be not started. // It is the end of transfer ptr_job->buf_size = ptr_job->buf_cnt; @@ -1991,13 +1991,13 @@ static bool udd_ep_interrupt(void) } dbg_print("dma%x: ", ep); udd_disable_endpoint_dma_interrupt(ep); - // Save number of data no transfered + // Save number of data no transferred nb_remaining = (udd_endpoint_dma_get_status(ep) & UOTGHS_DEVDMASTATUS_BUFF_COUNT_Msk) >> UOTGHS_DEVDMASTATUS_BUFF_COUNT_Pos; if (nb_remaining) { // Transfer no complete (short packet or ZLP) then: - // Update number of data transfered + // Update number of data transferred ptr_job->buf_cnt -= nb_remaining; // Set transfer complete to stop the transfer ptr_job->buf_size = ptr_job->buf_cnt; @@ -2056,7 +2056,7 @@ static bool udd_ep_interrupt(void) udd_disable_endpoint_interrupt(ep); Assert(ptr_job->stall_requested); - // A stall has been requested during backgound transfer + // A stall has been requested during background transfer ptr_job->stall_requested = false; udd_disable_endpoint_bank_autoswitch(ep); udd_enable_stall_handshake(ep); diff --git a/Marlin/src/HAL/DUE/usb/usb_protocol_msc.h b/Marlin/src/HAL/DUE/usb/usb_protocol_msc.h index 0fef30804662..e1e59237d823 100644 --- a/Marlin/src/HAL/DUE/usb/usb_protocol_msc.h +++ b/Marlin/src/HAL/DUE/usb/usb_protocol_msc.h @@ -130,7 +130,7 @@ struct usb_msc_cbw { struct usb_msc_csw { le32_t dCSWSignature; //!< Must contain 'USBS' le32_t dCSWTag; //!< Same as dCBWTag - le32_t dCSWDataResidue; //!< Number of bytes not transfered + le32_t dCSWDataResidue; //!< Number of bytes not transferred uint8_t bCSWStatus; //!< Status code }; diff --git a/Marlin/src/HAL/DUE/usb/usb_task.c b/Marlin/src/HAL/DUE/usb/usb_task.c index 66bdb265d881..54a808d7f4f1 100644 --- a/Marlin/src/HAL/DUE/usb/usb_task.c +++ b/Marlin/src/HAL/DUE/usb/usb_task.c @@ -264,7 +264,7 @@ bool usb_task_extra_string(void) { ** Handle device requests that the ASF stack doesn't */ bool usb_task_other_requests(void) { - uint8_t* ptr = 0; + uint8_t *ptr = 0; uint16_t size = 0; if (Udd_setup_type() == USB_REQ_TYPE_VENDOR) { @@ -322,7 +322,7 @@ void usb_task_init(void) { char *sptr; // Patch in the filament diameter - sprintf_P(diam, PSTR("%d"), (int)((DEFAULT_NOMINAL_FILAMENT_DIA) * 1000.0)); + itoa((int)((DEFAULT_NOMINAL_FILAMENT_DIA) * 1000), diam, 10); // And copy it to the proper place, expanding it to unicode sptr = &diam[0]; diff --git a/Marlin/src/HAL/DUE/watchdog.cpp b/Marlin/src/HAL/DUE/watchdog.cpp index 0f4697183056..e144db8291e3 100644 --- a/Marlin/src/HAL/DUE/watchdog.cpp +++ b/Marlin/src/HAL/DUE/watchdog.cpp @@ -36,7 +36,7 @@ void watchdogSetup() { #if ENABLED(USE_WATCHDOG) // 4 seconds timeout - uint32_t timeout = 4000; + uint32_t timeout = TERN(WATCHDOG_DURATION_8S, 8000, 4000); // Calculate timeout value in WDT counter ticks: This assumes // the slow clock is running at 32.768 kHz watchdog diff --git a/Marlin/src/HAL/ESP32/FlushableHardwareSerial.cpp b/Marlin/src/HAL/ESP32/FlushableHardwareSerial.cpp index d4b2f42c5351..145662215a9b 100644 --- a/Marlin/src/HAL/ESP32/FlushableHardwareSerial.cpp +++ b/Marlin/src/HAL/ESP32/FlushableHardwareSerial.cpp @@ -20,14 +20,10 @@ * */ -#include "FlushableHardwareSerial.h" - #ifdef ARDUINO_ARCH_ESP32 -FlushableHardwareSerial::FlushableHardwareSerial(int uart_nr) - : HardwareSerial(uart_nr) -{} +#include "FlushableHardwareSerial.h" -FlushableHardwareSerial flushableSerial(0); +Serial1Class flushableSerial(false, 0); -#endif // ARDUINO_ARCH_ESP32 +#endif diff --git a/Marlin/src/HAL/ESP32/FlushableHardwareSerial.h b/Marlin/src/HAL/ESP32/FlushableHardwareSerial.h index b43caea13c1d..012dda8626b0 100644 --- a/Marlin/src/HAL/ESP32/FlushableHardwareSerial.h +++ b/Marlin/src/HAL/ESP32/FlushableHardwareSerial.h @@ -21,17 +21,14 @@ */ #pragma once -#ifdef ARDUINO_ARCH_ESP32 - #include +#include "../shared/Marduino.h" +#include "../../core/serial_hook.h" + class FlushableHardwareSerial : public HardwareSerial { public: - FlushableHardwareSerial(int uart_nr); - - inline void flushTX() { /* No need to flush the hardware serial, but defined here for compatibility. */ } + FlushableHardwareSerial(int uart_nr) : HardwareSerial(uart_nr) {} }; -extern FlushableHardwareSerial flushableSerial; - -#endif // ARDUINO_ARCH_ESP32 +extern Serial1Class flushableSerial; diff --git a/Marlin/src/HAL/ESP32/HAL.cpp b/Marlin/src/HAL/ESP32/HAL.cpp index 1e00df5177ad..7818dbdd87ea 100644 --- a/Marlin/src/HAL/ESP32/HAL.cpp +++ b/Marlin/src/HAL/ESP32/HAL.cpp @@ -40,6 +40,10 @@ #endif #endif +#if ENABLED(ESP3D_WIFISUPPORT) + DefaultSerial1 MSerial0(false, Serial2Socket); +#endif + // ------------------------ // Externs // ------------------------ @@ -86,8 +90,6 @@ volatile int numPWMUsed = 0, #endif -void HAL_init() { i2s_init(); } - void HAL_init_board() { #if ENABLED(ESP3D_WIFISUPPORT) @@ -122,6 +124,10 @@ void HAL_init_board() { #endif #endif + // Initialize the i2s peripheral only if the I2S stepper stream is enabled. + // The following initialization is performed after Serial1 and Serial2 are defined as + // their native pins might conflict with the i2s stream even when they are remapped. + TERN_(I2S_STEPPER_STREAM, i2s_init()); } void HAL_idletask() { @@ -135,6 +141,8 @@ void HAL_clear_reset_source() { } uint8_t HAL_get_reset_source() { return rtc_get_reset_reason(1); } +void HAL_reboot() { ESP.restart(); } + void _delay_ms(int delay_ms) { delay(delay_ms); } // return free memory between end of heap (or end bss) and whatever is current @@ -179,6 +187,7 @@ void HAL_adc_init() { TERN_(HAS_TEMP_ADC_7, adc3_set_attenuation(get_channel(TEMP_7_PIN), ADC_ATTEN_11db)); TERN_(HAS_HEATED_BED, adc1_set_attenuation(get_channel(TEMP_BED_PIN), ADC_ATTEN_11db)); TERN_(HAS_TEMP_CHAMBER, adc1_set_attenuation(get_channel(TEMP_CHAMBER_PIN), ADC_ATTEN_11db)); + TERN_(HAS_TEMP_COOLER, adc1_set_attenuation(get_channel(TEMP_COOLER_PIN), ADC_ATTEN_11db)); TERN_(FILAMENT_WIDTH_SENSOR, adc1_set_attenuation(get_channel(FILWIDTH_PIN), ADC_ATTEN_11db)); // Note that adc2 is shared with the WiFi module, which has higher priority, so the conversion may fail. diff --git a/Marlin/src/HAL/ESP32/HAL.h b/Marlin/src/HAL/ESP32/HAL.h index ebc16c9525e7..0f920520306f 100644 --- a/Marlin/src/HAL/ESP32/HAL.h +++ b/Marlin/src/HAL/ESP32/HAL.h @@ -51,13 +51,15 @@ extern portMUX_TYPE spinlock; -#define MYSERIAL0 flushableSerial +#define MYSERIAL1 flushableSerial #if EITHER(WIFISUPPORT, ESP3D_WIFISUPPORT) #if ENABLED(ESP3D_WIFISUPPORT) - #define MYSERIAL1 Serial2Socket + typedef ForwardSerial1Class< decltype(Serial2Socket) > DefaultSerial1; + extern DefaultSerial1 MSerial0; + #define MYSERIAL2 MSerial0 #else - #define MYSERIAL1 webSocketSerial + #define MYSERIAL2 webSocketSerial #endif #endif @@ -67,10 +69,6 @@ extern portMUX_TYPE spinlock; #define ENABLE_ISRS() if (spinlock.owner != portMUX_FREE_VAL) portEXIT_CRITICAL(&spinlock) #define DISABLE_ISRS() portENTER_CRITICAL(&spinlock) -// Fix bug in pgm_read_ptr -#undef pgm_read_ptr -#define pgm_read_ptr(addr) (*(addr)) - // ------------------------ // Types // ------------------------ @@ -90,20 +88,33 @@ extern uint16_t HAL_adc_result; // Public functions // ------------------------ +// +// Tone +// +void toneInit(); +void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0); +void noTone(const pin_t _pin); + // clear reset reason void HAL_clear_reset_source(); // reset reason uint8_t HAL_get_reset_source(); -inline void HAL_reboot() {} // reboot the board or restart the bootloader +void HAL_reboot(); void _delay_ms(int delay); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-function" +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + int freeMemory(); -#pragma GCC diagnostic pop + +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic pop +#endif void analogWrite(pin_t pin, int value); @@ -128,7 +139,7 @@ void HAL_adc_start_conversion(const uint8_t adc_pin); #define HAL_IDLETASK 1 #define BOARD_INIT() HAL_init_board(); void HAL_idletask(); -void HAL_init(); +inline void HAL_init() {} void HAL_init_board(); // diff --git a/Marlin/src/HAL/ESP32/HAL_SPI.cpp b/Marlin/src/HAL/ESP32/HAL_SPI.cpp index 8e5875fc388d..8743ac5be215 100644 --- a/Marlin/src/HAL/ESP32/HAL_SPI.cpp +++ b/Marlin/src/HAL/ESP32/HAL_SPI.cpp @@ -53,11 +53,11 @@ static SPISettings spiConfig; // ------------------------ void spiBegin() { - #if !PIN_EXISTS(SS) - #error "SS_PIN not defined!" + #if !PIN_EXISTS(SD_SS) + #error "SD_SS_PIN not defined!" #endif - OUT_WRITE(SS_PIN, HIGH); + OUT_WRITE(SD_SS_PIN, HIGH); } void spiInit(uint8_t spiRate) { @@ -85,7 +85,7 @@ uint8_t spiRec() { return returnByte; } -void spiRead(uint8_t* buf, uint16_t nbyte) { +void spiRead(uint8_t *buf, uint16_t nbyte) { SPI.beginTransaction(spiConfig); SPI.transferBytes(0, buf, nbyte); SPI.endTransaction(); @@ -97,7 +97,7 @@ void spiSend(uint8_t b) { SPI.endTransaction(); } -void spiSendBlock(uint8_t token, const uint8_t* buf) { +void spiSendBlock(uint8_t token, const uint8_t *buf) { SPI.beginTransaction(spiConfig); SPI.transfer(token); SPI.writeBytes(const_cast(buf), 512); diff --git a/Marlin/src/HAL/ESP32/Servo.h b/Marlin/src/HAL/ESP32/Servo.h index b0d929452732..8542092d66ea 100644 --- a/Marlin/src/HAL/ESP32/Servo.h +++ b/Marlin/src/HAL/ESP32/Servo.h @@ -30,7 +30,7 @@ class Servo { MAX_PULSE_WIDTH = 2400, // Longest pulse sent to a servo TAU_MSEC = 20, TAU_USEC = (TAU_MSEC * 1000), - MAX_COMPARE = ((1 << 16) - 1), // 65535 + MAX_COMPARE = _BV(16) - 1, // 65535 CHANNEL_MAX_NUM = 16; public: diff --git a/Marlin/src/HAL/ESP32/Tone.cpp b/Marlin/src/HAL/ESP32/Tone.cpp new file mode 100644 index 000000000000..376c0f32e129 --- /dev/null +++ b/Marlin/src/HAL/ESP32/Tone.cpp @@ -0,0 +1,59 @@ +/** + * 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 + * + * Copypaste of SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * Description: Tone function for ESP32 + * Derived from https://forum.arduino.cc/index.php?topic=136500.msg2903012#msg2903012 + */ + +#ifdef ARDUINO_ARCH_ESP32 + +#include "../../inc/MarlinConfig.h" +#include "HAL.h" + +static pin_t tone_pin; +volatile static int32_t toggles; + +void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration) { + tone_pin = _pin; + toggles = 2 * frequency * duration / 1000; + HAL_timer_start(TONE_TIMER_NUM, 2 * frequency); +} + +void noTone(const pin_t _pin) { + HAL_timer_disable_interrupt(TONE_TIMER_NUM); + WRITE(_pin, LOW); +} + +HAL_TONE_TIMER_ISR() { + HAL_timer_isr_prologue(TONE_TIMER_NUM); + + if (toggles) { + toggles--; + TOGGLE(tone_pin); + } + else noTone(tone_pin); // turn off interrupt +} + +#endif // ARDUINO_ARCH_ESP32 diff --git a/Marlin/src/HAL/ESP32/WebSocketSerial.cpp b/Marlin/src/HAL/ESP32/WebSocketSerial.cpp index ca7f47a1f8bd..eb5b9d60395a 100644 --- a/Marlin/src/HAL/ESP32/WebSocketSerial.cpp +++ b/Marlin/src/HAL/ESP32/WebSocketSerial.cpp @@ -29,7 +29,7 @@ #include "wifi.h" #include -WebSocketSerial webSocketSerial; +MSerialWebSocketT webSocketSerial(false); AsyncWebSocket ws("/ws"); // TODO Move inside the class. // RingBuffer impl @@ -137,16 +137,12 @@ size_t WebSocketSerial::write(const uint8_t c) { return ret; } -size_t WebSocketSerial::write(const uint8_t* buffer, size_t size) { +size_t WebSocketSerial::write(const uint8_t *buffer, size_t size) { size_t written = 0; for (size_t i = 0; i < size; i++) written += write(buffer[i]); return written; } -void WebSocketSerial::flushTX() { - // No need to do anything as there's no benefit to sending partial lines over the websocket connection. -} - #endif // WIFISUPPORT #endif // ARDUINO_ARCH_ESP32 diff --git a/Marlin/src/HAL/ESP32/WebSocketSerial.h b/Marlin/src/HAL/ESP32/WebSocketSerial.h index 7a25c6dc5e9c..6b3e419d10c5 100644 --- a/Marlin/src/HAL/ESP32/WebSocketSerial.h +++ b/Marlin/src/HAL/ESP32/WebSocketSerial.h @@ -22,6 +22,7 @@ #pragma once #include "../../inc/MarlinConfig.h" +#include "../../core/serial_hook.h" #include @@ -53,7 +54,7 @@ class RingBuffer { ring_buffer_pos_t read(uint8_t *buffer); void flush(); ring_buffer_pos_t write(const uint8_t c); - ring_buffer_pos_t write(const uint8_t* buffer, ring_buffer_pos_t size); + ring_buffer_pos_t write(const uint8_t *buffer, ring_buffer_pos_t size); }; class WebSocketSerial: public Stream { @@ -68,11 +69,8 @@ class WebSocketSerial: public Stream { int peek(); int read(); void flush(); - void flushTX(); size_t write(const uint8_t c); - size_t write(const uint8_t* buffer, size_t size); - - operator bool() { return true; } + size_t write(const uint8_t *buffer, size_t size); #if ENABLED(SERIAL_STATS_DROPPED_RX) FORCE_INLINE uint32_t dropped() { return 0; } @@ -83,4 +81,5 @@ class WebSocketSerial: public Stream { #endif }; -extern WebSocketSerial webSocketSerial; +typedef Serial1Class MSerialWebSocketT; +extern MSerialWebSocketT webSocketSerial; diff --git a/Marlin/src/HAL/ESP32/eeprom.cpp b/Marlin/src/HAL/ESP32/eeprom.cpp index 1bf687c6fe09..cb5f881284ec 100644 --- a/Marlin/src/HAL/ESP32/eeprom.cpp +++ b/Marlin/src/HAL/ESP32/eeprom.cpp @@ -44,7 +44,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui return false; } -bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { +bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { for (size_t i = 0; i < size; i++) { uint8_t c = EEPROM.read(pos++); if (writing) value[i] = c; diff --git a/Marlin/src/HAL/ESP32/endstop_interrupts.h b/Marlin/src/HAL/ESP32/endstop_interrupts.h index 743ccd99c904..4725df921b1a 100644 --- a/Marlin/src/HAL/ESP32/endstop_interrupts.h +++ b/Marlin/src/HAL/ESP32/endstop_interrupts.h @@ -59,4 +59,10 @@ void setup_endstop_interrupts() { TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); TERN_(HAS_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)); } diff --git a/Marlin/src/HAL/ESP32/fastio.h b/Marlin/src/HAL/ESP32/fastio.h index 2ded3a5f62e8..8db89dca12a1 100644 --- a/Marlin/src/HAL/ESP32/fastio.h +++ b/Marlin/src/HAL/ESP32/fastio.h @@ -52,6 +52,9 @@ // Set pin as input with pullup wrapper #define SET_INPUT_PULLUP(IO) do{ _SET_INPUT(IO); _PULLUP(IO, HIGH); }while(0) +// Set pin as input with pulldown (substitution) +#define SET_INPUT_PULLDOWN SET_INPUT + // Set pin as output wrapper #define SET_OUTPUT(IO) do{ _SET_OUTPUT(IO); }while(0) diff --git a/Marlin/src/HAL/ESP32/i2s.cpp b/Marlin/src/HAL/ESP32/i2s.cpp index 99b2f755e578..c28c00879390 100644 --- a/Marlin/src/HAL/ESP32/i2s.cpp +++ b/Marlin/src/HAL/ESP32/i2s.cpp @@ -139,7 +139,7 @@ static void IRAM_ATTR i2s_intr_handler_default(void *arg) { I2S0.int_clr.val = I2S0.int_st.val; //clear pending interrupt } -void stepperTask(void* parameter) { +void stepperTask(void *parameter) { uint32_t remaining = 0; while (1) { @@ -184,7 +184,7 @@ int i2s_init() { // Allocate the array of pointers to the buffers dma.buffers = (uint32_t **)malloc(sizeof(uint32_t*) * DMA_BUF_COUNT); - if (dma.buffers == nullptr) return -1; + if (!dma.buffers) return -1; // Allocate each buffer that can be used by the DMA controller for (int buf_idx = 0; buf_idx < DMA_BUF_COUNT; buf_idx++) { @@ -194,7 +194,7 @@ int i2s_init() { // Allocate the array of DMA descriptors dma.desc = (lldesc_t**) malloc(sizeof(lldesc_t*) * DMA_BUF_COUNT); - if (dma.desc == nullptr) return -1; + if (!dma.desc) return -1; // Allocate each DMA descriptor that will be used by the DMA controller for (int buf_idx = 0; buf_idx < DMA_BUF_COUNT; buf_idx++) { diff --git a/Marlin/src/HAL/ESP32/inc/SanityCheck.h b/Marlin/src/HAL/ESP32/inc/SanityCheck.h index f57a6c591028..8bbc68d8715b 100644 --- a/Marlin/src/HAL/ESP32/inc/SanityCheck.h +++ b/Marlin/src/HAL/ESP32/inc/SanityCheck.h @@ -30,9 +30,13 @@ #endif #if HAS_TMC_SW_SERIAL - #error "TMC220x Software Serial is not supported on this platform." + #error "TMC220x Software Serial is not supported on ESP32." #endif #if BOTH(WIFISUPPORT, ESP3D_WIFISUPPORT) #error "Only enable one WiFi option, either WIFISUPPORT or ESP3D_WIFISUPPORT." #endif + +#if ENABLED(POSTMORTEM_DEBUGGING) + #error "POSTMORTEM_DEBUGGING is not yet supported on ESP32." +#endif diff --git a/Marlin/src/HAL/ESP32/spi_pins.h b/Marlin/src/HAL/ESP32/spi_pins.h index 15f8f2ab6b07..cfe71eee4a75 100644 --- a/Marlin/src/HAL/ESP32/spi_pins.h +++ b/Marlin/src/HAL/ESP32/spi_pins.h @@ -18,7 +18,7 @@ */ #pragma once -#define SS_PIN SDSS -#define SCK_PIN 18 -#define MISO_PIN 19 -#define MOSI_PIN 23 +#define SD_SS_PIN SDSS +#define SD_SCK_PIN 18 +#define SD_MISO_PIN 19 +#define SD_MOSI_PIN 23 diff --git a/Marlin/src/HAL/ESP32/timers.cpp b/Marlin/src/HAL/ESP32/timers.cpp index 3300aea8a89c..57662a665882 100644 --- a/Marlin/src/HAL/ESP32/timers.cpp +++ b/Marlin/src/HAL/ESP32/timers.cpp @@ -45,7 +45,7 @@ const tTimerConfig TimerConfig [NUM_HARDWARE_TIMERS] = { { TIMER_GROUP_0, TIMER_0, STEPPER_TIMER_PRESCALE, stepTC_Handler }, // 0 - Stepper { TIMER_GROUP_0, TIMER_1, TEMP_TIMER_PRESCALE, tempTC_Handler }, // 1 - Temperature { TIMER_GROUP_1, TIMER_0, PWM_TIMER_PRESCALE, pwmTC_Handler }, // 2 - PWM - { TIMER_GROUP_1, TIMER_1, 1, nullptr }, // 3 + { TIMER_GROUP_1, TIMER_1, TONE_TIMER_PRESCALE, toneTC_Handler }, // 3 - Tone }; // ------------------------ diff --git a/Marlin/src/HAL/ESP32/timers.h b/Marlin/src/HAL/ESP32/timers.h index d722670f33cf..a47697113d5d 100644 --- a/Marlin/src/HAL/ESP32/timers.h +++ b/Marlin/src/HAL/ESP32/timers.h @@ -24,15 +24,9 @@ #include #include -// Includes needed to get I2S_STEPPER_STREAM. Note that pins.h -// is included in case this header is being included early. -#include "../../inc/MarlinConfig.h" -#include "../../pins/pins.h" - // ------------------------ // Defines // ------------------------ -// #define FORCE_INLINE __attribute__((always_inline)) inline typedef uint64_t hal_timer_t; @@ -50,6 +44,9 @@ typedef uint64_t hal_timer_t; #ifndef PWM_TIMER_NUM #define PWM_TIMER_NUM 2 // index of timer to use for PWM outputs #endif +#ifndef TONE_TIMER_NUM + #define TONE_TIMER_NUM 3 // index of timer for beeper tones +#endif #define HAL_TIMER_RATE APB_CLK_FREQ // frequency of timer peripherals @@ -65,6 +62,8 @@ typedef uint64_t hal_timer_t; #define STEP_TIMER_MIN_INTERVAL 8 // minimum time in µs between stepper interrupts +#define TONE_TIMER_PRESCALE 1000 // Arbitrary value, no idea what i'm doing here + #define TEMP_TIMER_PRESCALE 1000 // prescaler for setting Temp timer, 72Khz #define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency @@ -96,10 +95,16 @@ typedef uint64_t hal_timer_t; #ifndef HAL_PWM_TIMER_ISR #define HAL_PWM_TIMER_ISR() extern "C" void pwmTC_Handler() #endif +#ifndef HAL_TONE_TIMER_ISR + #define HAL_TONE_TIMER_ISR() extern "C" void toneTC_Handler() +#endif -extern "C" void tempTC_Handler(); -extern "C" void stepTC_Handler(); -extern "C" void pwmTC_Handler(); +extern "C" { + void tempTC_Handler(); + void stepTC_Handler(); + void pwmTC_Handler(); + void toneTC_Handler(); +} // ------------------------ // Types diff --git a/Marlin/src/HAL/ESP32/watchdog.cpp b/Marlin/src/HAL/ESP32/watchdog.cpp index f6fcfa3182c4..5ec03c46079b 100644 --- a/Marlin/src/HAL/ESP32/watchdog.cpp +++ b/Marlin/src/HAL/ESP32/watchdog.cpp @@ -25,6 +25,8 @@ #if ENABLED(USE_WATCHDOG) +#define WDT_TIMEOUT_US TERN(WATCHDOG_DURATION_8S, 8000000, 4000000) // 4 or 8 second timeout + #include "watchdog.h" void watchdogSetup() { diff --git a/Marlin/src/HAL/HAL.h b/Marlin/src/HAL/HAL.h index 5eca2f7eacfe..0cd836af2b68 100644 --- a/Marlin/src/HAL/HAL.h +++ b/Marlin/src/HAL/HAL.h @@ -23,14 +23,12 @@ #include "platforms.h" -#include HAL_PATH(.,HAL.h) - -#ifdef SERIAL_PORT_2 - #define NUM_SERIAL 2 -#else - #define NUM_SERIAL 1 +#ifndef GCC_VERSION + #define GCC_VERSION (__GNUC__ * 10000 + __GNUC_MINOR__ * 100 + __GNUC_PATCHLEVEL__) #endif +#include HAL_PATH(.,HAL.h) + #define HAL_ADC_RANGE _BV(HAL_ADC_RESOLUTION) #ifndef I2C_ADDRESS diff --git a/Marlin/src/HAL/LINUX/HAL.cpp b/Marlin/src/HAL/LINUX/HAL.cpp index d7d7c2d2b4f0..0b679170ef17 100644 --- a/Marlin/src/HAL/LINUX/HAL.cpp +++ b/Marlin/src/HAL/LINUX/HAL.cpp @@ -24,21 +24,16 @@ #include "../../inc/MarlinConfig.h" #include "../shared/Delay.h" -HalSerial usb_serial; +MSerialT usb_serial(TERN0(EMERGENCY_PARSER, true)); // U8glib required functions -extern "C" void u8g_xMicroDelay(uint16_t val) { - DELAY_US(val); -} -extern "C" void u8g_MicroDelay() { - u8g_xMicroDelay(1); -} -extern "C" void u8g_10MicroDelay() { - u8g_xMicroDelay(10); -} -extern "C" void u8g_Delay(uint16_t val) { - delay(val); +extern "C" { + void u8g_xMicroDelay(uint16_t val) { DELAY_US(val); } + void u8g_MicroDelay() { u8g_xMicroDelay(1); } + void u8g_10MicroDelay() { u8g_xMicroDelay(10); } + void u8g_Delay(uint16_t val) { delay(val); } } + //************************// // return free heap space @@ -78,4 +73,6 @@ void HAL_pwm_init() { } +void HAL_reboot() { /* Reset the application state and GPIO */ } + #endif // __PLAT_LINUX__ diff --git a/Marlin/src/HAL/LINUX/HAL.h b/Marlin/src/HAL/LINUX/HAL.h index 2e545e03d6f3..36906bffc869 100644 --- a/Marlin/src/HAL/LINUX/HAL.h +++ b/Marlin/src/HAL/LINUX/HAL.h @@ -23,7 +23,7 @@ #define CPU_32_BIT -#define F_CPU 100000000 +#define F_CPU 100000000UL #define SystemCoreClock F_CPU #include #include @@ -60,8 +60,8 @@ uint8_t _getc(); #define SHARED_SERVOS HAS_SERVOS -extern HalSerial usb_serial; -#define MYSERIAL0 usb_serial +extern MSerialT usb_serial; +#define MYSERIAL1 usb_serial #define ST7920_DELAY_1 DELAY_NS(600) #define ST7920_DELAY_2 DELAY_NS(750) @@ -79,10 +79,16 @@ extern HalSerial usb_serial; inline void HAL_init() {} // Utility functions -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-function" +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + int freeMemory(); -#pragma GCC diagnostic pop + +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic pop +#endif // ADC #define HAL_ADC_VREF 5.0 @@ -101,14 +107,9 @@ uint16_t HAL_adc_get_result(); inline void HAL_clear_reset_source(void) {} inline uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; } -inline void HAL_reboot() {} // reboot the board or restart the bootloader +void HAL_reboot(); // Reset the application state and GPIO /* ---------------- Delay in cycles */ FORCE_INLINE static void DELAY_CYCLES(uint64_t x) { Clock::delayCycles(x); } - -// Add strcmp_P if missing -#ifndef strcmp_P - #define strcmp_P(a, b) strcmp((a), (b)) -#endif diff --git a/Marlin/src/HAL/LINUX/eeprom.cpp b/Marlin/src/HAL/LINUX/eeprom.cpp index 967ca851abc1..532f323c6edb 100644 --- a/Marlin/src/HAL/LINUX/eeprom.cpp +++ b/Marlin/src/HAL/LINUX/eeprom.cpp @@ -40,7 +40,7 @@ size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } bool PersistentStore::access_start() { const char eeprom_erase_value = 0xFF; FILE * eeprom_file = fopen(filename, "rb"); - if (eeprom_file == nullptr) return false; + if (!eeprom_file) return false; fseek(eeprom_file, 0L, SEEK_END); std::size_t file_size = ftell(eeprom_file); @@ -59,7 +59,7 @@ bool PersistentStore::access_start() { bool PersistentStore::access_finish() { FILE * eeprom_file = fopen(filename, "wb"); - if (eeprom_file == nullptr) return false; + if (!eeprom_file) return false; fwrite(buffer, sizeof(uint8_t), sizeof(buffer), eeprom_file); fclose(eeprom_file); return true; @@ -78,7 +78,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui return (bytes_written != size); // return true for any error } -bool PersistentStore::read_data(int &pos, uint8_t* value, const size_t size, uint16_t *crc, const bool writing/*=true*/) { +bool PersistentStore::read_data(int &pos, uint8_t *value, const size_t size, uint16_t *crc, const bool writing/*=true*/) { std::size_t bytes_read = 0; if (writing) { for (std::size_t i = 0; i < size; i++) { diff --git a/Marlin/src/HAL/LINUX/hardware/Gpio.h b/Marlin/src/HAL/LINUX/hardware/Gpio.h index 9255ec1dfc91..f946be648466 100644 --- a/Marlin/src/HAL/LINUX/hardware/Gpio.h +++ b/Marlin/src/HAL/LINUX/hardware/Gpio.h @@ -40,7 +40,7 @@ struct GpioEvent { pin_type pin_id; GpioEvent::Type event; - GpioEvent(uint64_t timestamp, pin_type pin_id, GpioEvent::Type event){ + GpioEvent(uint64_t timestamp, pin_type pin_id, GpioEvent::Type event) { this->timestamp = timestamp; this->pin_id = pin_id; this->event = event; @@ -86,10 +86,10 @@ class Gpio { GpioEvent::Type evt_type = value > 1 ? GpioEvent::SET_VALUE : value > pin_map[pin].value ? GpioEvent::RISE : value < pin_map[pin].value ? GpioEvent::FALL : GpioEvent::NOP; pin_map[pin].value = value; GpioEvent evt(Clock::nanos(), pin, evt_type); - if (pin_map[pin].cb != nullptr) { + if (pin_map[pin].cb) { pin_map[pin].cb->interrupt(evt); } - if (Gpio::logger != nullptr) Gpio::logger->log(evt); + if (Gpio::logger) Gpio::logger->log(evt); } static uint16_t get(pin_type pin) { @@ -105,8 +105,8 @@ class Gpio { if (!valid_pin(pin)) return; pin_map[pin].mode = value; GpioEvent evt(Clock::nanos(), pin, GpioEvent::Type::SETM); - if (pin_map[pin].cb != nullptr) pin_map[pin].cb->interrupt(evt); - if (Gpio::logger != nullptr) Gpio::logger->log(evt); + if (pin_map[pin].cb) pin_map[pin].cb->interrupt(evt); + if (Gpio::logger) Gpio::logger->log(evt); } static uint8_t getMode(pin_type pin) { @@ -118,8 +118,8 @@ class Gpio { if (!valid_pin(pin)) return; pin_map[pin].dir = value; GpioEvent evt(Clock::nanos(), pin, GpioEvent::Type::SETD); - if (pin_map[pin].cb != nullptr) pin_map[pin].cb->interrupt(evt); - if (Gpio::logger != nullptr) Gpio::logger->log(evt); + if (pin_map[pin].cb) pin_map[pin].cb->interrupt(evt); + if (Gpio::logger) Gpio::logger->log(evt); } static uint8_t getDir(pin_type pin) { diff --git a/Marlin/src/HAL/LINUX/hardware/Heater.cpp b/Marlin/src/HAL/LINUX/hardware/Heater.cpp index 70df8161829a..44f11986c98b 100644 --- a/Marlin/src/HAL/LINUX/hardware/Heater.cpp +++ b/Marlin/src/HAL/LINUX/hardware/Heater.cpp @@ -54,7 +54,7 @@ void Heater::update() { } void Heater::interrupt(GpioEvent ev) { - // ununsed + // unused } #endif // __PLAT_LINUX__ diff --git a/Marlin/src/HAL/LINUX/hardware/LinearAxis.cpp b/Marlin/src/HAL/LINUX/hardware/LinearAxis.cpp index c5b3ccc98656..e122ef3666c5 100644 --- a/Marlin/src/HAL/LINUX/hardware/LinearAxis.cpp +++ b/Marlin/src/HAL/LINUX/hardware/LinearAxis.cpp @@ -51,7 +51,7 @@ void LinearAxis::update() { } void LinearAxis::interrupt(GpioEvent ev) { - if (ev.pin_id == step_pin && !Gpio::pin_map[enable_pin].value){ + if (ev.pin_id == step_pin && !Gpio::pin_map[enable_pin].value) { if (ev.event == GpioEvent::RISE) { last_update = ev.timestamp; position += -1 + 2 * Gpio::pin_map[dir_pin].value; diff --git a/Marlin/src/HAL/LINUX/hardware/Timer.h b/Marlin/src/HAL/LINUX/hardware/Timer.h index 757efdcdbd7e..1b3b800dca3d 100644 --- a/Marlin/src/HAL/LINUX/hardware/Timer.h +++ b/Marlin/src/HAL/LINUX/hardware/Timer.h @@ -52,7 +52,7 @@ class Timer { return (*(intptr_t*)timerid); } - static void handler(int sig, siginfo_t *si, void *uc){ + static void handler(int sig, siginfo_t *si, void *uc) { Timer* _this = (Timer*)si->si_value.sival_ptr; _this->avg_error += (Clock::nanos() - _this->start_time) - _this->period; //high_resolution_clock is also limited in precision, but best we have _this->avg_error /= 2; //very crude precision analysis (actually within +-500ns usually) diff --git a/Marlin/src/HAL/LINUX/inc/SanityCheck.h b/Marlin/src/HAL/LINUX/inc/SanityCheck.h index 84167c97a144..45bb2662ace5 100644 --- a/Marlin/src/HAL/LINUX/inc/SanityCheck.h +++ b/Marlin/src/HAL/LINUX/inc/SanityCheck.h @@ -35,5 +35,9 @@ #endif #if HAS_TMC_SW_SERIAL - #error "TMC220x Software Serial is not supported on this platform." + #error "TMC220x Software Serial is not supported on LINUX." +#endif + +#if ENABLED(POSTMORTEM_DEBUGGING) + #error "POSTMORTEM_DEBUGGING is not yet supported on LINUX." #endif diff --git a/Marlin/src/HAL/LINUX/include/Arduino.h b/Marlin/src/HAL/LINUX/include/Arduino.h index e28b474ede96..d4086e259a2f 100644 --- a/Marlin/src/HAL/LINUX/include/Arduino.h +++ b/Marlin/src/HAL/LINUX/include/Arduino.h @@ -67,34 +67,14 @@ void cli(); // Disable void sei(); // Enable void attachInterrupt(uint32_t pin, void (*callback)(), uint32_t mode); void detachInterrupt(uint32_t pin); -extern "C" void GpioEnableInt(uint32_t port, uint32_t pin, uint32_t mode); -extern "C" void GpioDisableInt(uint32_t port, uint32_t pin); - -// Program Memory -#define pgm_read_ptr(addr) (*((void**)(addr))) -#define pgm_read_byte_near(addr) (*((uint8_t*)(addr))) -#define pgm_read_float_near(addr) (*((float*)(addr))) -#define pgm_read_word_near(addr) (*((uint16_t*)(addr))) -#define pgm_read_dword_near(addr) (*((uint32_t*)(addr))) -#define pgm_read_byte(addr) pgm_read_byte_near(addr) -#define pgm_read_float(addr) pgm_read_float_near(addr) -#define pgm_read_word(addr) pgm_read_word_near(addr) -#define pgm_read_dword(addr) pgm_read_dword_near(addr) - -using std::memcpy; -#define memcpy_P memcpy -#define sprintf_P sprintf -#define strstr_P strstr -#define strncpy_P strncpy -#define vsnprintf_P vsnprintf -#define strcpy_P strcpy -#define snprintf_P snprintf -#define strlen_P strlen -// Time functions extern "C" { - void delay(const int milis); + void GpioEnableInt(uint32_t port, uint32_t pin, uint32_t mode); + void GpioDisableInt(uint32_t port, uint32_t pin); } + +// Time functions +extern "C" void delay(const int milis); void _delay_ms(const int delay); void delayMicroseconds(unsigned long); uint32_t millis(); diff --git a/Marlin/src/HAL/LINUX/include/pinmapping.cpp b/Marlin/src/HAL/LINUX/include/pinmapping.cpp index 870ab3a96e5f..5823668cd50d 100644 --- a/Marlin/src/HAL/LINUX/include/pinmapping.cpp +++ b/Marlin/src/HAL/LINUX/include/pinmapping.cpp @@ -25,43 +25,6 @@ #include "../../../gcode/parser.h" -uint8_t analog_offset = NUM_DIGITAL_PINS - NUM_ANALOG_INPUTS; - -// Get the digital pin for an analog index -pin_t analogInputToDigitalPin(const int8_t p) { - return (WITHIN(p, 0, NUM_ANALOG_INPUTS) ? analog_offset + p : P_NC); -} - -// Return the index of a pin number -int16_t GET_PIN_MAP_INDEX(const pin_t pin) { - return pin; -} - -// Test whether the pin is valid -bool VALID_PIN(const pin_t p) { - return WITHIN(p, 0, NUM_DIGITAL_PINS); -} - -// Get the analog index for a digital pin -int8_t DIGITAL_PIN_TO_ANALOG_PIN(const pin_t p) { - return (WITHIN(p, analog_offset, NUM_DIGITAL_PINS) ? p - analog_offset : P_NC); -} - -// Test whether the pin is PWM -bool PWM_PIN(const pin_t p) { - return false; -} - -// Test whether the pin is interruptable -bool INTERRUPT_PIN(const pin_t p) { - return false; -} - -// Get the pin number at the given index -pin_t GET_PIN_MAP_PIN(const int16_t ind) { - return ind; -} - int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) { return parser.intval(code, dval); } diff --git a/Marlin/src/HAL/LINUX/include/pinmapping.h b/Marlin/src/HAL/LINUX/include/pinmapping.h index 98f4b812e873..cfac5e3b48e4 100644 --- a/Marlin/src/HAL/LINUX/include/pinmapping.h +++ b/Marlin/src/HAL/LINUX/include/pinmapping.h @@ -34,26 +34,32 @@ constexpr uint8_t NUM_ANALOG_INPUTS = 16; #define HAL_SENSITIVE_PINS +constexpr uint8_t analog_offset = NUM_DIGITAL_PINS - NUM_ANALOG_INPUTS; + // Get the digital pin for an analog index -pin_t analogInputToDigitalPin(const int8_t p); +constexpr pin_t analogInputToDigitalPin(const int8_t p) { + return (WITHIN(p, 0, NUM_ANALOG_INPUTS) ? analog_offset + p : P_NC); +} + +// Get the analog index for a digital pin +constexpr int8_t DIGITAL_PIN_TO_ANALOG_PIN(const pin_t p) { + return (WITHIN(p, analog_offset, NUM_DIGITAL_PINS) ? p - analog_offset : P_NC); +} // Return the index of a pin number -int16_t GET_PIN_MAP_INDEX(const pin_t pin); +constexpr int16_t GET_PIN_MAP_INDEX(const pin_t pin) { return pin; } // Test whether the pin is valid -bool VALID_PIN(const pin_t p); - -// Get the analog index for a digital pin -int8_t DIGITAL_PIN_TO_ANALOG_PIN(const pin_t p); +constexpr bool VALID_PIN(const pin_t p) { return WITHIN(p, 0, NUM_DIGITAL_PINS); } // Test whether the pin is PWM -bool PWM_PIN(const pin_t p); +constexpr bool PWM_PIN(const pin_t p) { return false; } -// Test whether the pin is interruptable -bool INTERRUPT_PIN(const pin_t p); +// Test whether the pin is interruptible +constexpr bool INTERRUPT_PIN(const pin_t p) { return false; } // Get the pin number at the given index -pin_t GET_PIN_MAP_PIN(const int16_t ind); +constexpr pin_t GET_PIN_MAP_PIN(const int16_t ind) { return ind; } // Parse a G-code word into a pin index int16_t PARSED_PIN_INDEX(const char code, const int16_t dval); diff --git a/Marlin/src/HAL/LINUX/include/serial.h b/Marlin/src/HAL/LINUX/include/serial.h index e91624938978..ebae066c3a57 100644 --- a/Marlin/src/HAL/LINUX/include/serial.h +++ b/Marlin/src/HAL/LINUX/include/serial.h @@ -25,6 +25,7 @@ #if ENABLED(EMERGENCY_PARSER) #include "../../../feature/e_parser.h" #endif +#include "../../../core/serial_hook.h" #include #include @@ -73,19 +74,11 @@ template class RingBuffer { volatile uint32_t index_read; }; -class HalSerial { -public: - - #if ENABLED(EMERGENCY_PARSER) - EmergencyParser::State emergency_state; - static inline bool emergency_parser_enabled() { return true; } - #endif - +struct HalSerial { HalSerial() { host_connected = true; } void begin(int32_t) {} - - void end() {} + void end() {} int peek() { uint8_t value; @@ -100,7 +93,7 @@ class HalSerial { return transmit_buffer.write(c); } - operator bool() { return host_connected; } + bool connected() { return host_connected; } uint16_t available() { return (uint16_t)receive_buffer.available(); @@ -117,92 +110,9 @@ class HalSerial { while (transmit_buffer.available()) { /* nada */ } } - void printf(const char *format, ...) { - static char buffer[256]; - va_list vArgs; - va_start(vArgs, format); - int length = vsnprintf((char *) buffer, 256, (char const *) format, vArgs); - va_end(vArgs); - if (length > 0 && length < 256) { - if (host_connected) { - for (int i = 0; i < length;) { - if (transmit_buffer.write(buffer[i])) { - ++i; - } - } - } - } - } - - #define DEC 10 - #define HEX 16 - #define OCT 8 - #define BIN 2 - - void print_bin(uint32_t value, uint8_t num_digits) { - uint32_t mask = 1 << (num_digits -1); - for (uint8_t i = 0; i < num_digits; i++) { - if (!(i % 4) && i) write(' '); - if (!(i % 16) && i) write(' '); - if (value & mask) write('1'); - else write('0'); - value <<= 1; - } - } - - void print(const char value[]) { printf("%s" , value); } - void print(char value, int nbase = 0) { - if (nbase == BIN) print_bin(value, 8); - else if (nbase == OCT) printf("%3o", value); - else if (nbase == HEX) printf("%2X", value); - else if (nbase == DEC ) printf("%d", value); - else printf("%c" , value); - } - void print(unsigned char value, int nbase = 0) { - if (nbase == BIN) print_bin(value, 8); - else if (nbase == OCT) printf("%3o", value); - else if (nbase == HEX) printf("%2X", value); - else printf("%u" , value); - } - void print(int value, int nbase = 0) { - if (nbase == BIN) print_bin(value, 16); - else if (nbase == OCT) printf("%6o", value); - else if (nbase == HEX) printf("%4X", value); - else printf("%d", value); - } - void print(unsigned int value, int nbase = 0) { - if (nbase == BIN) print_bin(value, 16); - else if (nbase == OCT) printf("%6o", value); - else if (nbase == HEX) printf("%4X", value); - else printf("%u" , value); - } - void print(long value, int nbase = 0) { - if (nbase == BIN) print_bin(value, 32); - else if (nbase == OCT) printf("%11o", value); - else if (nbase == HEX) printf("%8X", value); - else printf("%ld" , value); - } - void print(unsigned long value, int nbase = 0) { - if (nbase == BIN) print_bin(value, 32); - else if (nbase == OCT) printf("%11o", value); - else if (nbase == HEX) printf("%8X", value); - else printf("%lu" , value); - } - void print(float value, int round = 6) { printf("%f" , value); } - void print(double value, int round = 6) { printf("%f" , value); } - - void println(const char value[]) { printf("%s\n" , value); } - void println(char value, int nbase = 0) { print(value, nbase); println(); } - void println(unsigned char value, int nbase = 0) { print(value, nbase); println(); } - void println(int value, int nbase = 0) { print(value, nbase); println(); } - void println(unsigned int value, int nbase = 0) { print(value, nbase); println(); } - void println(long value, int nbase = 0) { print(value, nbase); println(); } - void println(unsigned long value, int nbase = 0) { print(value, nbase); println(); } - void println(float value, int round = 6) { printf("%f\n" , value); } - void println(double value, int round = 6) { printf("%f\n" , value); } - void println() { print('\n'); } - volatile RingBuffer receive_buffer; volatile RingBuffer transmit_buffer; volatile bool host_connected; }; + +typedef Serial1Class MSerialT; diff --git a/Marlin/src/HAL/LINUX/main.cpp b/Marlin/src/HAL/LINUX/main.cpp index 481f059030b7..31f6de98ee8e 100644 --- a/Marlin/src/HAL/LINUX/main.cpp +++ b/Marlin/src/HAL/LINUX/main.cpp @@ -1,6 +1,5 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * This program is free software: you can redistribute it and/or modify @@ -19,22 +18,23 @@ */ #ifdef __PLAT_LINUX__ -extern void setup(); -extern void loop(); - -#include - -#include -#include +//#define GPIO_LOGGING // Full GPIO and Positional Logging #include "../../inc/MarlinConfig.h" -#include -#include #include "../shared/Delay.h" #include "hardware/IOLoggerCSV.h" #include "hardware/Heater.h" #include "hardware/LinearAxis.h" +#include +#include +#include +#include +#include + +extern void setup(); +extern void loop(); + // simple stdout / stdin implementation for fake serial port void write_serial_thread() { for (;;) { @@ -64,8 +64,6 @@ void simulation_loop() { LinearAxis z_axis(Z_ENABLE_PIN, Z_DIR_PIN, Z_STEP_PIN, Z_MIN_PIN, Z_MAX_PIN); LinearAxis extruder0(E0_ENABLE_PIN, E0_DIR_PIN, E0_STEP_PIN, P_NC, P_NC); - //#define GPIO_LOGGING // Full GPIO and Positional Logging - #ifdef GPIO_LOGGING IOLoggerCSV logger("all_gpio_log.csv"); Gpio::attachLogger(&logger); @@ -88,7 +86,7 @@ void simulation_loop() { #ifdef GPIO_LOGGING if (x_axis.position != x || y_axis.position != y || z_axis.position != z) { - uint64_t update = MAX3(x_axis.last_update, y_axis.last_update, z_axis.last_update); + uint64_t update = _MAX(x_axis.last_update, y_axis.last_update, z_axis.last_update); position_log << update << ", " << x_axis.position << ", " << y_axis.position << ", " << z_axis.position << std::endl; position_log.flush(); x = x_axis.position; @@ -107,8 +105,8 @@ int main() { std::thread write_serial (write_serial_thread); std::thread read_serial (read_serial_thread); - #ifdef MYSERIAL0 - MYSERIAL0.begin(BAUDRATE); + #ifdef MYSERIAL1 + MYSERIAL1.begin(BAUDRATE); SERIAL_ECHOLNPGM("x86_64 Initialized"); SERIAL_FLUSHTX(); #endif diff --git a/Marlin/src/HAL/LINUX/pinsDebug.h b/Marlin/src/HAL/LINUX/pinsDebug.h index a93ceddc61c3..8f8543ef5984 100644 --- a/Marlin/src/HAL/LINUX/pinsDebug.h +++ b/Marlin/src/HAL/LINUX/pinsDebug.h @@ -26,15 +26,15 @@ */ #define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS -#define pwm_details(pin) pin = pin // do nothing // print PWM details -#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 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 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 MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin +#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%3d "), p); 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 constexpr int8_t ADC_pin_mode(pin_t pin) { diff --git a/Marlin/src/HAL/LINUX/spi_pins.h b/Marlin/src/HAL/LINUX/spi_pins.h index 01ba28e5b604..33136ac9dd80 100644 --- a/Marlin/src/HAL/LINUX/spi_pins.h +++ b/Marlin/src/HAL/LINUX/spi_pins.h @@ -24,31 +24,32 @@ #include "../../core/macros.h" #include "../../inc/MarlinConfigPre.h" -#if BOTH(HAS_MARLINUI_U8GLIB, SDSUPPORT) && (LCD_PINS_D4 == SCK_PIN || LCD_PINS_ENABLE == MOSI_PIN || DOGLCD_SCK == SCK_PIN || DOGLCD_MOSI == MOSI_PIN) +#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) #define LPC_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 // spiBeginTransaction. #endif -/** onboard SD card */ -//#define SCK_PIN P0_07 -//#define MISO_PIN P0_08 -//#define MOSI_PIN P0_09 -//#define SS_PIN P0_06 -/** external */ -#ifndef SCK_PIN - #define SCK_PIN 50 +// Onboard SD +//#define SD_SCK_PIN P0_07 +//#define SD_MISO_PIN P0_08 +//#define SD_MOSI_PIN P0_09 +//#define SD_SS_PIN P0_06 + +// External SD +#ifndef SD_SCK_PIN + #define SD_SCK_PIN 50 #endif -#ifndef MISO_PIN - #define MISO_PIN 51 +#ifndef SD_MISO_PIN + #define SD_MISO_PIN 51 #endif -#ifndef MOSI_PIN - #define MOSI_PIN 52 +#ifndef SD_MOSI_PIN + #define SD_MOSI_PIN 52 #endif -#ifndef SS_PIN - #define SS_PIN 53 +#ifndef SD_SS_PIN + #define SD_SS_PIN 53 #endif #ifndef SDSS - #define SDSS SS_PIN + #define SDSS SD_SS_PIN #endif diff --git a/Marlin/src/HAL/LINUX/watchdog.cpp b/Marlin/src/HAL/LINUX/watchdog.cpp index c15b0e311c56..84202e48b6c5 100644 --- a/Marlin/src/HAL/LINUX/watchdog.cpp +++ b/Marlin/src/HAL/LINUX/watchdog.cpp @@ -27,6 +27,8 @@ #include "watchdog.h" +#define WDT_TIMEOUT_US TERN(WATCHDOG_DURATION_8S, 8000000, 4000000) // 4 or 8 second timeout + void watchdog_init() {} void HAL_watchdog_refresh() {} diff --git a/Marlin/src/HAL/LINUX/watchdog.h b/Marlin/src/HAL/LINUX/watchdog.h index 472624cc7845..49a0d9c631d8 100644 --- a/Marlin/src/HAL/LINUX/watchdog.h +++ b/Marlin/src/HAL/LINUX/watchdog.h @@ -21,7 +21,5 @@ */ #pragma once -#define WDT_TIMEOUT 4000000 // 4 second timeout - void watchdog_init(); void HAL_watchdog_refresh(); diff --git a/Marlin/src/HAL/LPC1768/DebugMonitor.cpp b/Marlin/src/HAL/LPC1768/DebugMonitor.cpp deleted file mode 100644 index 783b10cfac16..000000000000 --- a/Marlin/src/HAL/LPC1768/DebugMonitor.cpp +++ /dev/null @@ -1,322 +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 "../../core/macros.h" -#include "../../core/serial.h" -#include - -#include "../shared/backtrace/unwinder.h" -#include "../shared/backtrace/unwmemaccess.h" -#include "watchdog.h" -#include - - -// Debug monitor that dumps to the Programming port all status when -// an exception or WDT timeout happens - And then resets the board - -// All the Monitor routines must run with interrupts disabled and -// under an ISR execution context. That is why we cannot reuse the -// Serial interrupt routines or any C runtime, as we don't know the -// state we are when running them - -// A SW memory barrier, to ensure GCC does not overoptimize loops -#define sw_barrier() __asm__ volatile("": : :"memory"); - -// (re)initialize UART0 as a monitor output to 250000,n,8,1 -static void TXBegin() { -} - -// Send character through UART with no interrupts -static void TX(char c) { - _DBC(c); -} - -// Send String through UART -static void TX(const char* s) { - while (*s) TX(*s++); -} - -static void TXDigit(uint32_t d) { - if (d < 10) TX((char)(d+'0')); - else if (d < 16) TX((char)(d+'A'-10)); - else TX('?'); -} - -// Send Hex number thru UART -static void TXHex(uint32_t v) { - TX("0x"); - for (uint8_t i = 0; i < 8; i++, v <<= 4) - TXDigit((v >> 28) & 0xF); -} - -// Send Decimal number thru UART -static void TXDec(uint32_t v) { - if (!v) { - TX('0'); - return; - } - - char nbrs[14]; - char *p = &nbrs[0]; - while (v != 0) { - *p++ = '0' + (v % 10); - v /= 10; - } - do { - p--; - TX(*p); - } while (p != &nbrs[0]); -} - -// Dump a backtrace entry -static bool UnwReportOut(void* ctx, const UnwReport* bte) { - int* p = (int*)ctx; - - (*p)++; - TX('#'); TXDec(*p); TX(" : "); - TX(bte->name?bte->name:"unknown"); TX('@'); TXHex(bte->function); - TX('+'); TXDec(bte->address - bte->function); - TX(" PC:");TXHex(bte->address); TX('\n'); - return true; -} - -#ifdef UNW_DEBUG - void UnwPrintf(const char* format, ...) { - char dest[256]; - va_list argptr; - va_start(argptr, format); - vsprintf(dest, format, argptr); - va_end(argptr); - TX(&dest[0]); - } -#endif - -/* Table of function pointers for passing to the unwinder */ -static const UnwindCallbacks UnwCallbacks = { - UnwReportOut, - UnwReadW, - UnwReadH, - UnwReadB - #ifdef UNW_DEBUG - ,UnwPrintf - #endif -}; - - -/** - * HardFaultHandler_C: - * This is called from the HardFault_HandlerAsm with a pointer the Fault stack - * as the parameter. We can then read the values from the stack and place them - * into local variables for ease of reading. - * We then read the various Fault Status and Address Registers to help decode - * cause of the fault. - * The function ends with a BKPT instruction to force control back into the debugger - */ -extern "C" -void HardFault_HandlerC(unsigned long *sp, unsigned long lr, unsigned long cause) { - - static const char* causestr[] = { - "NMI","Hard","Mem","Bus","Usage","Debug","WDT","RSTC" - }; - - UnwindFrame btf; - - // Dump report to the Programming port (interrupts are DISABLED) - TXBegin(); - TX("\n\n## Software Fault detected ##\n"); - TX("Cause: "); TX(causestr[cause]); TX('\n'); - - TX("R0 : "); TXHex(((unsigned long)sp[0])); TX('\n'); - TX("R1 : "); TXHex(((unsigned long)sp[1])); TX('\n'); - TX("R2 : "); TXHex(((unsigned long)sp[2])); TX('\n'); - TX("R3 : "); TXHex(((unsigned long)sp[3])); TX('\n'); - TX("R12 : "); TXHex(((unsigned long)sp[4])); TX('\n'); - TX("LR : "); TXHex(((unsigned long)sp[5])); TX('\n'); - TX("PC : "); TXHex(((unsigned long)sp[6])); TX('\n'); - TX("PSR : "); TXHex(((unsigned long)sp[7])); TX('\n'); - - // Configurable Fault Status Register - // Consists of MMSR, BFSR and UFSR - TX("CFSR : "); TXHex((*((volatile unsigned long *)(0xE000ED28)))); TX('\n'); - - // Hard Fault Status Register - TX("HFSR : "); TXHex((*((volatile unsigned long *)(0xE000ED2C)))); TX('\n'); - - // Debug Fault Status Register - TX("DFSR : "); TXHex((*((volatile unsigned long *)(0xE000ED30)))); TX('\n'); - - // Auxiliary Fault Status Register - TX("AFSR : "); TXHex((*((volatile unsigned long *)(0xE000ED3C)))); TX('\n'); - - // Read the Fault Address Registers. These may not contain valid values. - // Check BFARVALID/MMARVALID to see if they are valid values - // MemManage Fault Address Register - TX("MMAR : "); TXHex((*((volatile unsigned long *)(0xE000ED34)))); TX('\n'); - - // Bus Fault Address Register - TX("BFAR : "); TXHex((*((volatile unsigned long *)(0xE000ED38)))); TX('\n'); - - TX("ExcLR: "); TXHex(lr); TX('\n'); - TX("ExcSP: "); TXHex((unsigned long)sp); TX('\n'); - - btf.sp = ((unsigned long)sp) + 8*4; // The original stack pointer - btf.fp = btf.sp; - btf.lr = ((unsigned long)sp[5]); - btf.pc = ((unsigned long)sp[6]) | 1; // Force Thumb, as CORTEX only support it - - // Perform a backtrace - TX("\nBacktrace:\n\n"); - int ctr = 0; - UnwindStart(&btf, &UnwCallbacks, &ctr); - - // Disable all NVIC interrupts - NVIC->ICER[0] = 0xFFFFFFFF; - NVIC->ICER[1] = 0xFFFFFFFF; - - // Relocate VTOR table to default position - SCB->VTOR = 0; - - // Clear cause of reset to prevent entering smoothie bootstrap - HAL_clear_reset_source(); - - // Restart watchdog - #if ENABLED(USE_WATCHDOG) - //WDT_Restart(WDT); - watchdog_init(); - #endif - - // Reset controller - NVIC_SystemReset(); - - // Nothing below here is compiled because NVIC_SystemReset loops forever - - for (;;) { TERN_(USE_WATCHDOG, watchdog_init()); } -} - -extern "C" { -__attribute__((naked)) void NMI_Handler() { - __asm__ __volatile__ ( - ".syntax unified" "\n\t" - A("tst lr, #4") - A("ite eq") - A("mrseq r0, msp") - A("mrsne r0, psp") - A("mov r1,lr") - A("mov r2,#0") - A("b HardFault_HandlerC") - ); -} - -__attribute__((naked)) void HardFault_Handler() { - __asm__ __volatile__ ( - ".syntax unified" "\n\t" - A("tst lr, #4") - A("ite eq") - A("mrseq r0, msp") - A("mrsne r0, psp") - A("mov r1,lr") - A("mov r2,#1") - A("b HardFault_HandlerC") - ); -} - -__attribute__((naked)) void MemManage_Handler() { - __asm__ __volatile__ ( - ".syntax unified" "\n\t" - A("tst lr, #4") - A("ite eq") - A("mrseq r0, msp") - A("mrsne r0, psp") - A("mov r1,lr") - A("mov r2,#2") - A("b HardFault_HandlerC") - ); -} - -__attribute__((naked)) void BusFault_Handler() { - __asm__ __volatile__ ( - ".syntax unified" "\n\t" - A("tst lr, #4") - A("ite eq") - A("mrseq r0, msp") - A("mrsne r0, psp") - A("mov r1,lr") - A("mov r2,#3") - A("b HardFault_HandlerC") - ); -} - -__attribute__((naked)) void UsageFault_Handler() { - __asm__ __volatile__ ( - ".syntax unified" "\n\t" - A("tst lr, #4") - A("ite eq") - A("mrseq r0, msp") - A("mrsne r0, psp") - A("mov r1,lr") - A("mov r2,#4") - A("b HardFault_HandlerC") - ); -} - -__attribute__((naked)) void DebugMon_Handler() { - __asm__ __volatile__ ( - ".syntax unified" "\n\t" - A("tst lr, #4") - A("ite eq") - A("mrseq r0, msp") - A("mrsne r0, psp") - A("mov r1,lr") - A("mov r2,#5") - A("b HardFault_HandlerC") - ); -} - -/* This is NOT an exception, it is an interrupt handler - Nevertheless, the framing is the same */ -__attribute__((naked)) void WDT_IRQHandler() { - __asm__ __volatile__ ( - ".syntax unified" "\n\t" - A("tst lr, #4") - A("ite eq") - A("mrseq r0, msp") - A("mrsne r0, psp") - A("mov r1,lr") - A("mov r2,#6") - A("b HardFault_HandlerC") - ); -} - -__attribute__((naked)) void RSTC_Handler() { - __asm__ __volatile__ ( - ".syntax unified" "\n\t" - A("tst lr, #4") - A("ite eq") - A("mrseq r0, msp") - A("mrsne r0, psp") - A("mov r1,lr") - A("mov r2,#7") - A("b HardFault_HandlerC") - ); -} -} -#endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/HAL.cpp b/Marlin/src/HAL/LPC1768/HAL.cpp index 939f1e8a9408..cee9cfc5f744 100644 --- a/Marlin/src/HAL/LPC1768/HAL.cpp +++ b/Marlin/src/HAL/LPC1768/HAL.cpp @@ -29,21 +29,18 @@ #include "watchdog.h" #endif +DefaultSerial1 USBSerial(false, UsbSerial); + uint32_t HAL_adc_reading = 0; // U8glib required functions -extern "C" void u8g_xMicroDelay(uint16_t val) { - DELAY_US(val); -} -extern "C" void u8g_MicroDelay() { - u8g_xMicroDelay(1); -} -extern "C" void u8g_10MicroDelay() { - u8g_xMicroDelay(10); -} -extern "C" void u8g_Delay(uint16_t val) { - delay(val); +extern "C" { + void u8g_xMicroDelay(uint16_t val) { DELAY_US(val); } + void u8g_MicroDelay() { u8g_xMicroDelay(1); } + void u8g_10MicroDelay() { u8g_xMicroDelay(10); } + void u8g_Delay(uint16_t val) { delay(val); } } + //************************// // return free heap space @@ -66,7 +63,12 @@ int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) { return ind > -1 ? ind : dval; } -void flashFirmware(const int16_t) { NVIC_SystemReset(); } +void flashFirmware(const int16_t) { + delay(500); // Give OS time to disconnect + USB_Connect(false); // USB clear connection + delay(1000); // Give OS time to notice + HAL_reboot(); +} void HAL_clear_reset_source(void) { TERN_(USE_WATCHDOG, watchdog_clear_timeout_flag()); @@ -79,4 +81,6 @@ uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; } +void HAL_reboot() { NVIC_SystemReset(); } + #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h index cb637e715dda..3f9cd2dfbd02 100644 --- a/Marlin/src/HAL/LPC1768/HAL.h +++ b/Marlin/src/HAL/LPC1768/HAL.h @@ -47,9 +47,6 @@ extern "C" volatile uint32_t _millis; #include #include -// i2c uses 8-bit shifted address -#define I2C_ADDRESS(A) uint8_t((A) << 1) - // // Default graphical display delays // @@ -63,35 +60,60 @@ extern "C" volatile uint32_t _millis; #define ST7920_DELAY_3 DELAY_NS(750) #endif +typedef ForwardSerial1Class< decltype(UsbSerial) > DefaultSerial1; +extern DefaultSerial1 USBSerial; + #define _MSERIAL(X) MSerial##X #define MSERIAL(X) _MSERIAL(X) -#define MSerial0 MSerial #if SERIAL_PORT == -1 - #define MYSERIAL0 UsbSerial + #define MYSERIAL1 USBSerial #elif WITHIN(SERIAL_PORT, 0, 3) - #define MYSERIAL0 MSERIAL(SERIAL_PORT) + #define MYSERIAL1 MSERIAL(SERIAL_PORT) #else - #error "SERIAL_PORT must be from -1 to 3. Please update your configuration." + #error "SERIAL_PORT must be from 0 to 3. You can also use -1 if the board supports Native USB." #endif #ifdef SERIAL_PORT_2 #if SERIAL_PORT_2 == -1 - #define MYSERIAL1 UsbSerial + #define MYSERIAL2 USBSerial #elif WITHIN(SERIAL_PORT_2, 0, 3) - #define MYSERIAL1 MSERIAL(SERIAL_PORT_2) + #define MYSERIAL2 MSERIAL(SERIAL_PORT_2) #else - #error "SERIAL_PORT_2 must be from -1 to 3. Please update your configuration." + #error "SERIAL_PORT_2 must be from 0 to 3. You can also use -1 if the board supports Native USB." + #endif +#endif + +#ifdef SERIAL_PORT_3 + #if SERIAL_PORT_3 == -1 + #define MYSERIAL3 USBSerial + #elif WITHIN(SERIAL_PORT_3, 0, 3) + #define MYSERIAL3 MSERIAL(SERIAL_PORT_3) + #else + #error "SERIAL_PORT_3 must be from 0 to 3. You can also use -1 if the board supports Native USB." + #endif +#endif + +#ifdef MMU2_SERIAL_PORT + #if MMU2_SERIAL_PORT == -1 + #define MMU2_SERIAL USBSerial + #elif WITHIN(MMU2_SERIAL_PORT, 0, 3) + #define MMU2_SERIAL MSERIAL(MMU2_SERIAL_PORT) + #else + #error "MMU2_SERIAL_PORT must be from 0 to 3. You can also use -1 if the board supports Native USB." #endif #endif #ifdef LCD_SERIAL_PORT #if LCD_SERIAL_PORT == -1 - #define LCD_SERIAL UsbSerial + #define LCD_SERIAL USBSerial #elif WITHIN(LCD_SERIAL_PORT, 0, 3) #define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT) #else - #error "LCD_SERIAL_PORT must be from -1 to 3. Please update your configuration." + #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() MSerial0.available() #endif #endif @@ -107,10 +129,16 @@ extern "C" volatile uint32_t _millis; // // Utility functions // -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-function" +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + int freeMemory(); -#pragma GCC diagnostic pop + +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic pop +#endif // // ADC API @@ -170,7 +198,7 @@ constexpr pin_t GET_PIN_MAP_PIN(const int16_t index) { // Parse a G-code word into a pin index int16_t PARSED_PIN_INDEX(const char code, const int16_t dval); // P0.6 thru P0.9 are for the onboard SD card -#define HAL_SENSITIVE_PINS P0_06, P0_07, P0_08, P0_09 +#define HAL_SENSITIVE_PINS P0_06, P0_07, P0_08, P0_09, #define HAL_IDLETASK 1 void HAL_idletask(); @@ -200,9 +228,4 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, void HAL_clear_reset_source(void); uint8_t HAL_get_reset_source(void); -inline void HAL_reboot() {} // reboot the board or restart the bootloader - -// Add strcmp_P if missing -#ifndef strcmp_P - #define strcmp_P(a, b) strcmp((a), (b)) -#endif +void HAL_reboot(); diff --git a/Marlin/src/HAL/LPC1768/HAL_MinSerial.cpp b/Marlin/src/HAL/LPC1768/HAL_MinSerial.cpp new file mode 100644 index 000000000000..57065c49ac83 --- /dev/null +++ b/Marlin/src/HAL/LPC1768/HAL_MinSerial.cpp @@ -0,0 +1,51 @@ +/** + * 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 TARGET_LPC1768 + +#include "../../inc/MarlinConfig.h" +#include "HAL.h" + +#if ENABLED(POSTMORTEM_DEBUGGING) + +#include "../shared/HAL_MinSerial.h" +#include + +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" + ); + } + 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 +#endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/HAL_SPI.cpp b/Marlin/src/HAL/LPC1768/HAL_SPI.cpp index b3d2908ac93e..29f9b43afef0 100644 --- a/Marlin/src/HAL/LPC1768/HAL_SPI.cpp +++ b/Marlin/src/HAL/LPC1768/HAL_SPI.cpp @@ -55,27 +55,29 @@ #include #include +#include "../shared/HAL_SPI.h" + // ------------------------ // Public functions // ------------------------ #if ENABLED(LPC_SOFTWARE_SPI) - #include - // Software SPI - static uint8_t SPI_speed = 0; + #include + + static uint8_t SPI_speed = SPI_FULL_SPEED; static uint8_t spiTransfer(uint8_t b) { - return swSpiTransfer(b, SPI_speed, SCK_PIN, MISO_PIN, MOSI_PIN); + return swSpiTransfer(b, SPI_speed, SD_SCK_PIN, SD_MISO_PIN, SD_MOSI_PIN); } void spiBegin() { - swSpiBegin(SCK_PIN, MISO_PIN, MOSI_PIN); + swSpiBegin(SD_SCK_PIN, SD_MISO_PIN, SD_MOSI_PIN); } void spiInit(uint8_t spiRate) { - SPI_speed = swSpiInit(spiRate, SCK_PIN, MOSI_PIN); + SPI_speed = swSpiInit(spiRate, SD_SCK_PIN, SD_MOSI_PIN); } uint8_t spiRec() { return spiTransfer(0xFF); } @@ -87,12 +89,12 @@ void spiSend(uint8_t b) { (void)spiTransfer(b); } - void spiSend(const uint8_t* buf, size_t nbyte) { + void spiSend(const uint8_t *buf, size_t nbyte) { for (uint16_t i = 0; i < nbyte; i++) (void)spiTransfer(buf[i]); } - void spiSendBlock(uint8_t token, const uint8_t* buf) { + void spiSendBlock(uint8_t token, const uint8_t *buf) { (void)spiTransfer(token); for (uint16_t i = 0; i < 512; i++) (void)spiTransfer(buf[i]); @@ -100,14 +102,18 @@ #else - void spiBegin() { // setup SCK, MOSI & MISO pins for SSP0 - spiInit(SPI_SPEED); - } + #ifdef SD_SPI_SPEED + #define INIT_SPI_SPEED SD_SPI_SPEED + #else + #define INIT_SPI_SPEED SPI_FULL_SPEED + #endif + + void spiBegin() { spiInit(INIT_SPI_SPEED); } // Set up SCK, MOSI & MISO pins for SSP0 void spiInit(uint8_t spiRate) { - #if MISO_PIN == BOARD_SPI1_MISO_PIN + #if SD_MISO_PIN == BOARD_SPI1_MISO_PIN SPI.setModule(1); - #elif MISO_PIN == BOARD_SPI2_MISO_PIN + #elif SD_MISO_PIN == BOARD_SPI2_MISO_PIN SPI.setModule(2); #endif SPI.setDataSize(DATA_SIZE_8BIT); @@ -123,15 +129,13 @@ void spiSend(uint8_t b) { doio(b); } - void spiSend(const uint8_t* buf, size_t nbyte) { + void spiSend(const uint8_t *buf, size_t nbyte) { for (uint16_t i = 0; i < nbyte; i++) doio(buf[i]); } - void spiSend(uint32_t chan, byte b) { - } + void spiSend(uint32_t chan, byte b) {} - void spiSend(uint32_t chan, const uint8_t* buf, size_t nbyte) { - } + void spiSend(uint32_t chan, const uint8_t *buf, size_t nbyte) {} // Read single byte from SPI uint8_t spiRec() { return doio(0xFF); } @@ -143,21 +147,18 @@ for (uint16_t i = 0; i < nbyte; i++) buf[i] = doio(0xFF); } - uint8_t spiTransfer(uint8_t b) { - return doio(b); - } + uint8_t spiTransfer(uint8_t b) { return doio(b); } // Write from buffer to SPI - void spiSendBlock(uint8_t token, const uint8_t* buf) { + void spiSendBlock(uint8_t token, const uint8_t *buf) { (void)spiTransfer(token); for (uint16_t i = 0; i < 512; i++) (void)spiTransfer(buf[i]); } - /** Begin SPI transaction, set clock, bit order, data mode */ + // Begin SPI transaction, set clock, bit order, data mode void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { - // TODO: to be implemented - + // TODO: Implement this method } #endif // LPC_SOFTWARE_SPI @@ -201,6 +202,15 @@ SPIClass::SPIClass(uint8_t device) { GPDMA_Init(); } +SPIClass::SPIClass(pin_t mosi, pin_t miso, pin_t sclk, pin_t ssel) { + #if BOARD_NR_SPI >= 1 + if (mosi == BOARD_SPI1_MOSI_PIN) SPIClass(1); + #endif + #if BOARD_NR_SPI >= 2 + if (mosi == BOARD_SPI2_MOSI_PIN) SPIClass(2); + #endif +} + void SPIClass::begin() { // Init the SPI pins in the first begin call if ((_currentSetting->spi_d == LPC_SSP0 && spiInitialised[0] == false) || @@ -263,8 +273,9 @@ uint16_t SPIClass::transfer16(const uint16_t data) { } void SPIClass::end() { - // SSP_Cmd(_currentSetting->spi_d, DISABLE); // stop device or SSP_DeInit? - SSP_DeInit(_currentSetting->spi_d); + // Neither is needed for Marlin + //SSP_Cmd(_currentSetting->spi_d, DISABLE); + //SSP_DeInit(_currentSetting->spi_d); } void SPIClass::send(uint8_t data) { @@ -330,25 +341,15 @@ void SPIClass::read(uint8_t *buf, uint32_t len) { for (uint16_t i = 0; i < len; i++) buf[i] = transfer(0xFF); } -void SPIClass::setClock(uint32_t clock) { - _currentSetting->clock = clock; -} +void SPIClass::setClock(uint32_t clock) { _currentSetting->clock = clock; } -void SPIClass::setModule(uint8_t device) { - _currentSetting = &_settings[device - 1];// SPI channels are called 1 2 and 3 but the array is zero indexed -} +void SPIClass::setModule(uint8_t device) { _currentSetting = &_settings[device - 1]; } // SPI channels are called 1, 2, and 3 but the array is zero-indexed -void SPIClass::setBitOrder(uint8_t bitOrder) { - _currentSetting->bitOrder = bitOrder; -} +void SPIClass::setBitOrder(uint8_t bitOrder) { _currentSetting->bitOrder = bitOrder; } -void SPIClass::setDataMode(uint8_t dataMode) { - _currentSetting->dataMode = dataMode; -} +void SPIClass::setDataMode(uint8_t dataMode) { _currentSetting->dataMode = dataMode; } -void SPIClass::setDataSize(uint32_t ds) { - _currentSetting->dataSize = ds; -} +void SPIClass::setDataSize(uint32_t dataSize) { _currentSetting->dataSize = dataSize; } /** * Set up/tear down @@ -356,8 +357,8 @@ void SPIClass::setDataSize(uint32_t ds) { void SPIClass::updateSettings() { //SSP_DeInit(_currentSetting->spi_d); //todo: need force de init?! - // divide PCLK by 2 for SSP0 - CLKPWR_SetPCLKDiv(_currentSetting->spi_d == LPC_SSP0 ? CLKPWR_PCLKSEL_SSP0 : CLKPWR_PCLKSEL_SSP1, CLKPWR_PCLKSEL_CCLK_DIV_2); + // Divide PCLK by 2 for SSP0 + //CLKPWR_SetPCLKDiv(_currentSetting->spi_d == LPC_SSP0 ? CLKPWR_PCLKSEL_SSP0 : CLKPWR_PCLKSEL_SSP1, CLKPWR_PCLKSEL_CCLK_DIV_2); SSP_CFG_Type HW_SPI_init; // data structure to hold init values SSP_ConfigStructInit(&HW_SPI_init); // set values for SPI mode @@ -396,9 +397,9 @@ void SPIClass::updateSettings() { SSP_Init(_currentSetting->spi_d, &HW_SPI_init); // puts the values into the proper bits in the SSP0 registers } -#if MISO_PIN == BOARD_SPI1_MISO_PIN +#if SD_MISO_PIN == BOARD_SPI1_MISO_PIN SPIClass SPI(1); -#elif MISO_PIN == BOARD_SPI2_MISO_PIN +#elif SD_MISO_PIN == BOARD_SPI2_MISO_PIN SPIClass SPI(2); #endif diff --git a/Marlin/src/HAL/LPC1768/MarlinSPI.h b/Marlin/src/HAL/LPC1768/MarlinSPI.h new file mode 100644 index 000000000000..fab245f904e3 --- /dev/null +++ b/Marlin/src/HAL/LPC1768/MarlinSPI.h @@ -0,0 +1,45 @@ +/** + * 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 + +#include + +/** + * Marlin currently requires 3 SPI classes: + * + * SPIClass: + * This class is normally provided by frameworks and has a semi-default interface. + * This is needed because some libraries reference it globally. + * + * SPISettings: + * Container for SPI configs for SPIClass. As above, libraries may reference it globally. + * + * These two classes are often provided by frameworks so we cannot extend them to add + * useful methods for Marlin. + * + * MarlinSPI: + * Provides the default SPIClass interface plus some Marlin goodies such as a simplified + * interface for SPI DMA transfer. + * + */ + +using MarlinSPI = SPIClass; diff --git a/Marlin/src/HAL/LPC1768/MarlinSerial.cpp b/Marlin/src/HAL/LPC1768/MarlinSerial.cpp index 5374e005d3da..f2aecf54a050 100644 --- a/Marlin/src/HAL/LPC1768/MarlinSerial.cpp +++ b/Marlin/src/HAL/LPC1768/MarlinSerial.cpp @@ -21,35 +21,51 @@ */ #ifdef TARGET_LPC1768 -#include "../../inc/MarlinConfigPre.h" #include "MarlinSerial.h" -#if USING_SERIAL_0 - MarlinSerial MSerial(LPC_UART0); - extern "C" void UART0_IRQHandler() { - MSerial.IRQHandler(); - } -#endif +#include "../../inc/MarlinConfig.h" -#if USING_SERIAL_1 - MarlinSerial MSerial1((LPC_UART_TypeDef *) LPC_UART1); - extern "C" void UART1_IRQHandler() { - MSerial1.IRQHandler(); - } +#if USING_HW_SERIAL0 + MarlinSerial _MSerial0(LPC_UART0); + MSerialT MSerial0(true, _MSerial0); + extern "C" void UART0_IRQHandler() { _MSerial0.IRQHandler(); } #endif - -#if USING_SERIAL_2 - MarlinSerial MSerial2(LPC_UART2); - extern "C" void UART2_IRQHandler() { - MSerial2.IRQHandler(); - } +#if USING_HW_SERIAL1 + MarlinSerial _MSerial1((LPC_UART_TypeDef *) LPC_UART1); + MSerialT MSerial1(true, _MSerial1); + extern "C" void UART1_IRQHandler() { _MSerial1.IRQHandler(); } +#endif +#if USING_HW_SERIAL2 + MarlinSerial _MSerial2(LPC_UART2); + MSerialT MSerial2(true, _MSerial2); + extern "C" void UART2_IRQHandler() { _MSerial2.IRQHandler(); } +#endif +#if USING_HW_SERIAL3 + MarlinSerial _MSerial3(LPC_UART3); + MSerialT MSerial3(true, _MSerial3); + extern "C" void UART3_IRQHandler() { _MSerial3.IRQHandler(); } #endif -#if USING_SERIAL_3 - MarlinSerial MSerial3(LPC_UART3); - extern "C" void UART3_IRQHandler() { - MSerial3.IRQHandler(); +#if ENABLED(EMERGENCY_PARSER) + + bool MarlinSerial::recv_callback(const char c) { + // Need to figure out which serial port we are and react in consequence (Marlin does not have CONTAINER_OF macro) + if (false) {} + #if USING_HW_SERIAL0 + else if (this == &_MSerial0) emergency_parser.update(MSerial0.emergency_state, c); + #endif + #if USING_HW_SERIAL1 + else if (this == &_MSerial1) emergency_parser.update(MSerial1.emergency_state, c); + #endif + #if USING_HW_SERIAL2 + else if (this == &_MSerial2) emergency_parser.update(MSerial2.emergency_state, c); + #endif + #if USING_HW_SERIAL3 + else if (this == &_MSerial3) emergency_parser.update(MSerial3.emergency_state, c); + #endif + return true; } + #endif #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/MarlinSerial.h b/Marlin/src/HAL/LPC1768/MarlinSerial.h index 8d6b64378a0a..808d19f8c52a 100644 --- a/Marlin/src/HAL/LPC1768/MarlinSerial.h +++ b/Marlin/src/HAL/LPC1768/MarlinSerial.h @@ -28,6 +28,7 @@ #if ENABLED(EMERGENCY_PARSER) #include "../../feature/e_parser.h" #endif +#include "../../core/serial_hook.h" #ifndef SERIAL_PORT #define SERIAL_PORT 0 @@ -41,27 +42,26 @@ class MarlinSerial : public HardwareSerial { public: - MarlinSerial(LPC_UART_TypeDef *UARTx) : - HardwareSerial(UARTx) - #if ENABLED(EMERGENCY_PARSER) - , emergency_state(EmergencyParser::State::EP_RESET) - #endif - { } + MarlinSerial(LPC_UART_TypeDef *UARTx) : HardwareSerial(UARTx) { } void end() {} #if ENABLED(EMERGENCY_PARSER) - bool recv_callback(const char c) override { - emergency_parser.update(emergency_state, c); - return true; // do not discard character - } - - EmergencyParser::State emergency_state; - static inline bool emergency_parser_enabled() { return true; } + bool recv_callback(const char c) override; #endif }; -extern MarlinSerial MSerial; -extern MarlinSerial MSerial1; -extern MarlinSerial MSerial2; -extern MarlinSerial MSerial3; +// On LPC176x framework, HardwareSerial does not implement the same interface as Arduino's Serial, so overloads +// of 'available' and 'read' method are not used in this multiple inheritance scenario. +// Instead, use a ForwardSerial here that adapts the interface. +typedef ForwardSerial1Class MSerialT; +extern MSerialT MSerial0; +extern MSerialT MSerial1; +extern MSerialT MSerial2; +extern MSerialT MSerial3; + +// Consequently, we can't use a RuntimeSerial either. The workaround would be to use +// a RuntimeSerial> type here. Ignore for now until it's actually required. +#if ENABLED(SERIAL_RUNTIME_HOOK) + #error "SERIAL_RUNTIME_HOOK is not yet supported for LPC176x." +#endif diff --git a/Marlin/src/HAL/LPC1768/eeprom_flash.cpp b/Marlin/src/HAL/LPC1768/eeprom_flash.cpp index 255848637520..38d2705d519a 100644 --- a/Marlin/src/HAL/LPC1768/eeprom_flash.cpp +++ b/Marlin/src/HAL/LPC1768/eeprom_flash.cpp @@ -25,7 +25,7 @@ * Emulate EEPROM storage using Flash Memory * * Use a single 32K flash sector to store EEPROM data. To reduce the - * number of erase operations a simple "levelling" scheme is used that + * number of erase operations a simple "leveling" scheme is used that * maintains a number of EEPROM "slots" within the larger flash sector. * Each slot is used in turn and the entire sector is only erased when all * slots have been used. @@ -119,7 +119,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui return false; // return true for any error } -bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { +bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { const uint8_t * const buff = writing ? &value[0] : &ram_eeprom[pos]; if (writing) for (size_t i = 0; i < size; i++) value[i] = ram_eeprom[pos + i]; crc16(crc, buff, size); diff --git a/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp b/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp index 9f2475f490ef..70395251df25 100644 --- a/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp +++ b/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp @@ -83,17 +83,16 @@ bool PersistentStore::access_finish() { static void debug_rw(const bool write, int &pos, const uint8_t *value, const size_t size, const FRESULT s, const size_t total=0) { PGM_P const rw_str = write ? PSTR("write") : PSTR("read"); SERIAL_CHAR(' '); - serialprintPGM(rw_str); - SERIAL_ECHOLNPAIR("_data(", pos, ",", int(value), ",", int(size), ", ...)"); + SERIAL_ECHOPGM_P(rw_str); + SERIAL_ECHOLNPAIR("_data(", pos, ",", value, ",", size, ", ...)"); if (total) { SERIAL_ECHOPGM(" f_"); - serialprintPGM(rw_str); - SERIAL_ECHOPAIR("()=", int(s), "\n size=", int(size), "\n bytes_"); - serialprintPGM(write ? PSTR("written=") : PSTR("read=")); - SERIAL_ECHOLN(total); + SERIAL_ECHOPGM_P(rw_str); + SERIAL_ECHOPAIR("()=", s, "\n size=", size, "\n bytes_"); + SERIAL_ECHOLNPAIR_P(write ? PSTR("written=") : PSTR("read="), total); } else - SERIAL_ECHOLNPAIR(" f_lseek()=", int(s)); + SERIAL_ECHOLNPAIR(" f_lseek()=", s); } // File function return codes for type FRESULT. This goes away soon, but @@ -143,7 +142,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui return bytes_written != size; // return true for any error } -bool PersistentStore::read_data(int &pos, uint8_t* value, const size_t size, uint16_t *crc, const bool writing/*=true*/) { +bool PersistentStore::read_data(int &pos, uint8_t *value, const size_t size, uint16_t *crc, const bool writing/*=true*/) { if (!eeprom_file_open) return true; UINT bytes_read = 0; FRESULT s; diff --git a/Marlin/src/HAL/LPC1768/eeprom_wired.cpp b/Marlin/src/HAL/LPC1768/eeprom_wired.cpp index 16c15eaf0063..f9286a74ac88 100644 --- a/Marlin/src/HAL/LPC1768/eeprom_wired.cpp +++ b/Marlin/src/HAL/LPC1768/eeprom_wired.cpp @@ -42,33 +42,29 @@ bool PersistentStore::access_start() { eeprom_init(); return true; } bool PersistentStore::access_finish() { return true; } bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + uint16_t written = 0; while (size--) { uint8_t v = *value; - - // EEPROM has only ~100,000 write cycles, - // so only write bytes that have changed! uint8_t * const p = (uint8_t * const)pos; - if (v != eeprom_read_byte(p)) { + if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed! eeprom_write_byte(p, v); + if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes if (eeprom_read_byte(p) != v) { SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); return true; } } - crc16(crc, &v, 1); pos++; value++; - }; - + } return false; } -bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { +bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { do { // Read from external EEPROM const uint8_t c = eeprom_read_byte((uint8_t*)pos); - if (writing) *value = c; crc16(crc, &c, 1); pos++; diff --git a/Marlin/src/HAL/LPC1768/endstop_interrupts.h b/Marlin/src/HAL/LPC1768/endstop_interrupts.h index b0d0c0ec5c0a..23bd0cc982b2 100644 --- a/Marlin/src/HAL/LPC1768/endstop_interrupts.h +++ b/Marlin/src/HAL/LPC1768/endstop_interrupts.h @@ -46,80 +46,113 @@ void setup_endstop_interrupts() { #if HAS_X_MAX #if !LPC1768_PIN_INTERRUPT_M(X_MAX_PIN) - #error "X_MAX_PIN is not INTERRUPT-capable." + #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 !LPC1768_PIN_INTERRUPT_M(X_MIN_PIN) - #error "X_MIN_PIN is not INTERRUPT-capable." + #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 !LPC1768_PIN_INTERRUPT_M(Y_MAX_PIN) - #error "Y_MAX_PIN is not INTERRUPT-capable." + #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 !LPC1768_PIN_INTERRUPT_M(Y_MIN_PIN) - #error "Y_MIN_PIN is not INTERRUPT-capable." + #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 !LPC1768_PIN_INTERRUPT_M(Z_MAX_PIN) - #error "Z_MAX_PIN is not INTERRUPT-capable." + #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 !LPC1768_PIN_INTERRUPT_M(Z_MIN_PIN) - #error "Z_MIN_PIN is not INTERRUPT-capable." + #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 !LPC1768_PIN_INTERRUPT_M(Z2_MAX_PIN) - #error "Z2_MAX_PIN is not INTERRUPT-capable." + #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 !LPC1768_PIN_INTERRUPT_M(Z2_MIN_PIN) - #error "Z2_MIN_PIN is not INTERRUPT-capable." + #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 !LPC1768_PIN_INTERRUPT_M(Z3_MAX_PIN) - #error "Z3_MIN_PIN is not INTERRUPT-capable." + #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 !LPC1768_PIN_INTERRUPT_M(Z3_MIN_PIN) - #error "Z3_MIN_PIN is not INTERRUPT-capable." + #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 !LPC1768_PIN_INTERRUPT_M(Z4_MAX_PIN) - #error "Z4_MIN_PIN is not INTERRUPT-capable." + #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 !LPC1768_PIN_INTERRUPT_M(Z4_MIN_PIN) - #error "Z4_MIN_PIN is not INTERRUPT-capable." + #error "Z4_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z4_MIN_PIN); #endif #if HAS_Z_MIN_PROBE_PIN #if !LPC1768_PIN_INTERRUPT_M(Z_MIN_PROBE_PIN) - #error "Z_MIN_PROBE_PIN is not INTERRUPT-capable." + #error "Z_MIN_PROBE_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z_MIN_PROBE_PIN); #endif + #if HAS_I_MAX + #if !LPC1768_PIN_INTERRUPT_M(I_MAX_PIN) + #error "I_MAX_PIN is not INTERRUPT-capable." + #endif + _ATTACH(I_MAX_PIN); + #elif HAS_I_MIN + #if !LPC1768_PIN_INTERRUPT_M(I_MIN_PIN) + #error "I_MIN_PIN is not INTERRUPT-capable." + #endif + _ATTACH(I_MIN_PIN); + #endif + #if HAS_J_MAX + #if !LPC1768_PIN_INTERRUPT_M(J_MAX_PIN) + #error "J_MAX_PIN is not INTERRUPT-capable." + #endif + _ATTACH(J_MAX_PIN); + #elif HAS_J_MIN + #if !LPC1768_PIN_INTERRUPT_M(J_MIN_PIN) + #error "J_MIN_PIN is not INTERRUPT-capable." + #endif + _ATTACH(J_MIN_PIN); + #endif + #if HAS_K_MAX + #if !LPC1768_PIN_INTERRUPT_M(K_MAX_PIN) + #error "K_MAX_PIN is not INTERRUPT-capable." + #endif + _ATTACH(K_MAX_PIN); + #elif HAS_K_MIN + #if !LPC1768_PIN_INTERRUPT_M(K_MIN_PIN) + #error "K_MIN_PIN is not INTERRUPT-capable." + #endif + _ATTACH(K_MIN_PIN); + #endif } diff --git a/Marlin/src/HAL/LPC1768/inc/Conditionals_adv.h b/Marlin/src/HAL/LPC1768/inc/Conditionals_adv.h index 5f1c4b16019d..8e7cab185f2a 100644 --- a/Marlin/src/HAL/LPC1768/inc/Conditionals_adv.h +++ b/Marlin/src/HAL/LPC1768/inc/Conditionals_adv.h @@ -20,3 +20,7 @@ * */ #pragma once + +#if DISABLED(NO_SD_HOST_DRIVE) + #define HAS_SD_HOST_DRIVE 1 +#endif diff --git a/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h b/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h index ce6d3fdde27f..be574a96e4ed 100644 --- a/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h +++ b/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h @@ -26,3 +26,9 @@ #elif EITHER(I2C_EEPROM, SPI_EEPROM) #define USE_SHARED_EEPROM 1 #endif + +// LPC1768 boards seem to lose steps when saving to EEPROM during print (issue #20785) +// TODO: Which other boards are incompatible? +#if defined(MCU_LPC1768) && PRINTCOUNTER_SAVE_INTERVAL > 0 + #define PRINTCOUNTER_SYNC 1 +#endif diff --git a/Marlin/src/HAL/LPC1768/inc/SanityCheck.h b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h index f5051d32a168..23d797b2ab76 100644 --- a/Marlin/src/HAL/LPC1768/inc/SanityCheck.h +++ b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h @@ -24,14 +24,14 @@ #if PIO_PLATFORM_VERSION < 1001 #error "nxplpc-arduino-lpc176x package is out of date, Please update the PlatformIO platforms, frameworks and libraries. You may need to remove the platform and let it reinstall automatically." #endif -#if PIO_FRAMEWORK_VERSION < 2005 +#if PIO_FRAMEWORK_VERSION < 2006 #error "framework-arduino-lpc176x package is out of date, Please update the PlatformIO platforms, frameworks and libraries." #endif /** * Detect an old pins file by checking for old ADC pins values. */ -#define _OLD_TEMP_PIN(P) PIN_EXISTS(P) && _CAT(P,_PIN) <= 7 && _CAT(P,_PIN) != 2 && _CAT(P,_PIN) != 3 +#define _OLD_TEMP_PIN(P) PIN_EXISTS(P) && _CAT(P,_PIN) <= 7 && !WITHIN(_CAT(P,_PIN), TERN(LPC1768_IS_SKRV1_3, 0, 2), 3) // Include P0_00 and P0_01 for SKR V1.3 board #if _OLD_TEMP_PIN(TEMP_BED) #error "TEMP_BED_PIN must be defined using the Pn_nn or Pn_nn_An format. (See the included pins files)." #elif _OLD_TEMP_PIN(TEMP_0) @@ -72,7 +72,7 @@ static_assert(!(NUM_SERVOS && ENABLED(FAST_PWM_FAN)), "BLTOUCH and Servos are in //#endif #if 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) - #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) && HAS_DRIVER(TMC2130) && DISABLED(TMC_USE_SW_SPI) + #if IS_RRD_FG_SC && HAS_DRIVER(TMC2130) && DISABLED(TMC_USE_SW_SPI) #error "Re-ARM with REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER and TMC2130 requires TMC_USE_SW_SPI." #endif #endif @@ -92,13 +92,13 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o #define ANY_TX(N,V...) DO(IS_TX##N,||,V) #define ANY_RX(N,V...) DO(IS_RX##N,||,V) -#if USING_SERIAL_0 +#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) #error "Serial port pins (0) conflict with Trinamic SPI pins!" - #elif ENABLED(MK2_MULTIPLEXER) && (IS_TX0(E_MUX1_PIN) || IS_RX0(E_MUX0_PIN)) - #error "Serial port pins (0) conflict with MK2 multiplexer 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!" #elif (AXIS_HAS_SPI(X) && IS_TX0(X_CS_PIN)) || (AXIS_HAS_SPI(Y) && IS_RX0(Y_CS_PIN)) #error "Serial port pins (0) conflict with X/Y axis SPI pins!" #endif @@ -106,7 +106,7 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o #undef IS_RX0 #endif -#if USING_SERIAL_1 +#if USING_HW_SERIAL1 #define IS_TX1(P) (P == P0_15) #define IS_RX1(P) (P == P0_16) #define _IS_TX1_1 IS_TX1 @@ -116,8 +116,8 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o #elif HAS_WIRED_LCD #if IS_TX1(BTN_EN2) || IS_RX1(BTN_EN1) #error "Serial port pins (1) conflict with Encoder Buttons!" - #elif ANY_TX(1, SCK_PIN, LCD_PINS_D4, DOGLCD_SCK, LCD_RESET_PIN, LCD_PINS_RS, SHIFT_CLK) \ - || ANY_RX(1, LCD_SDSS, LCD_PINS_RS, MISO_PIN, DOGLCD_A0, SS_PIN, LCD_SDSS, DOGLCD_CS, LCD_RESET_PIN, LCD_BACKLIGHT_PIN) + #elif ANY_TX(1, SD_SCK_PIN, LCD_PINS_D4, DOGLCD_SCK, LCD_RESET_PIN, LCD_PINS_RS, SHIFT_CLK_PIN) \ + || ANY_RX(1, LCD_SDSS, LCD_PINS_RS, SD_MISO_PIN, DOGLCD_A0, SD_SS_PIN, LCD_SDSS, DOGLCD_CS, LCD_RESET_PIN, LCD_BACKLIGHT_PIN) #error "Serial port pins (1) conflict with LCD pins!" #endif #endif @@ -127,7 +127,7 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o #undef _IS_RX1_1 #endif -#if USING_SERIAL_2 +#if USING_HW_SERIAL2 #define IS_TX2(P) (P == P0_10) #define IS_RX2(P) (P == P0_11) #define _IS_TX2_1 IS_TX2 @@ -144,9 +144,9 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o #error "Serial port pins (2) conflict with Z4 pins!" #elif ANY_RX(2, X_DIR_PIN, Y_DIR_PIN) #error "Serial port pins (2) conflict with other pins!" - #elif Y_HOME_DIR < 0 && IS_TX2(Y_STOP_PIN) + #elif Y_HOME_TO_MIN && IS_TX2(Y_STOP_PIN) #error "Serial port pins (2) conflict with Y endstop pin!" - #elif HAS_CUSTOM_PROBE_PIN && IS_TX2(Z_MIN_PROBE_PIN) + #elif USES_Z_MIN_PROBE_PIN && IS_TX2(Z_MIN_PROBE_PIN) #error "Serial port pins (2) conflict with probe pin!" #elif ANY_TX(2, X_ENABLE_PIN, Y_ENABLE_PIN) || ANY_RX(2, X_DIR_PIN, Y_DIR_PIN) #error "Serial port pins (2) conflict with X/Y stepper pins!" @@ -161,7 +161,7 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o #undef _IS_RX2_1 #endif -#if USING_SERIAL_3 +#if USING_HW_SERIAL3 #define PIN_IS_TX3(P) (PIN_EXISTS(P) && P##_PIN == P0_00) #define PIN_IS_RX3(P) (P##_PIN == P0_01) #if PIN_IS_TX3(X_MIN) || PIN_IS_RX3(X_MAX) @@ -205,8 +205,8 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o #error "SDA0 overlaps with BEEPER_PIN!" #elif IS_SCL0(BTN_ENC) #error "SCL0 overlaps with Encoder Button!" - #elif IS_SCL0(SS_PIN) - #error "SCL0 overlaps with SS_PIN!" + #elif IS_SCL0(SD_SS_PIN) + #error "SCL0 overlaps with SD_SS_PIN!" #elif IS_SCL0(LCD_SDSS) #error "SCL0 overlaps with LCD_SDSS!" #endif @@ -237,7 +237,7 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o #define PIN_IS_SCL2(P) (P##_PIN == P0_11) #if PIN_IS_SDA2(Y_STOP) #error "i2c SDA2 overlaps with Y endstop pin!" - #elif HAS_CUSTOM_PROBE_PIN && PIN_IS_SDA2(Z_MIN_PROBE) + #elif USES_Z_MIN_PROBE_PIN && PIN_IS_SDA2(Z_MIN_PROBE) #error "i2c SDA2 overlaps with Z probe pin!" #elif PIN_IS_SDA2(X_ENABLE) || PIN_IS_SDA2(Y_ENABLE) #error "i2c SDA2 overlaps with X/Y ENABLE pin!" @@ -270,7 +270,7 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o #endif #if ENABLED(SERIAL_STATS_MAX_RX_QUEUED) - #error "SERIAL_STATS_MAX_RX_QUEUED is not supported on this platform." + #error "SERIAL_STATS_MAX_RX_QUEUED is not supported on LPC176x." #elif ENABLED(SERIAL_STATS_DROPPED_RX) - #error "SERIAL_STATS_DROPPED_RX is not supported on this platform." + #error "SERIAL_STATS_DROPPED_RX is not supported on LPX176x." #endif diff --git a/Marlin/src/HAL/LPC1768/include/SPI.h b/Marlin/src/HAL/LPC1768/include/SPI.h index 9da2a32556e7..ecd91f6a3b73 100644 --- a/Marlin/src/HAL/LPC1768/include/SPI.h +++ b/Marlin/src/HAL/LPC1768/include/SPI.h @@ -37,13 +37,14 @@ #define DATA_SIZE_8BIT SSP_DATABIT_8 #define DATA_SIZE_16BIT SSP_DATABIT_16 -#define SPI_CLOCK_DIV2 8333333 //(SCR: 2) desired: 8,000,000 actual: 8,333,333 +4.2% SPI_FULL_SPEED -#define SPI_CLOCK_DIV4 4166667 //(SCR: 5) desired: 4,000,000 actual: 4,166,667 +4.2% SPI_HALF_SPEED -#define SPI_CLOCK_DIV8 2083333 //(SCR: 11) desired: 2,000,000 actual: 2,083,333 +4.2% SPI_QUARTER_SPEED -#define SPI_CLOCK_DIV16 1000000 //(SCR: 24) desired: 1,000,000 actual: 1,000,000 SPI_EIGHTH_SPEED -#define SPI_CLOCK_DIV32 500000 //(SCR: 49) desired: 500,000 actual: 500,000 SPI_SPEED_5 -#define SPI_CLOCK_DIV64 250000 //(SCR: 99) desired: 250,000 actual: 250,000 SPI_SPEED_6 -#define SPI_CLOCK_DIV128 125000 //(SCR:199) desired: 125,000 actual: 125,000 Default from HAL.h +#define SPI_CLOCK_MAX_TFT 30000000UL +#define SPI_CLOCK_DIV2 8333333 //(SCR: 2) desired: 8,000,000 actual: 8,333,333 +4.2% SPI_FULL_SPEED +#define SPI_CLOCK_DIV4 4166667 //(SCR: 5) desired: 4,000,000 actual: 4,166,667 +4.2% SPI_HALF_SPEED +#define SPI_CLOCK_DIV8 2083333 //(SCR: 11) desired: 2,000,000 actual: 2,083,333 +4.2% SPI_QUARTER_SPEED +#define SPI_CLOCK_DIV16 1000000 //(SCR: 24) desired: 1,000,000 actual: 1,000,000 SPI_EIGHTH_SPEED +#define SPI_CLOCK_DIV32 500000 //(SCR: 49) desired: 500,000 actual: 500,000 SPI_SPEED_5 +#define SPI_CLOCK_DIV64 250000 //(SCR: 99) desired: 250,000 actual: 250,000 SPI_SPEED_6 +#define SPI_CLOCK_DIV128 125000 //(SCR:199) desired: 125,000 actual: 125,000 Default from HAL.h #define SPI_CLOCK_MAX SPI_CLOCK_DIV2 @@ -125,6 +126,11 @@ class SPIClass { */ SPIClass(uint8_t spiPortNumber); + /** + * Init using pins + */ + SPIClass(pin_t mosi, pin_t miso, pin_t sclk, pin_t ssel = (pin_t)-1); + /** * Select and configure the current selected SPI device to use */ diff --git a/Marlin/src/HAL/LPC1768/main.cpp b/Marlin/src/HAL/LPC1768/main.cpp index 0b4045cb9927..ef0dc42c78ca 100644 --- a/Marlin/src/HAL/LPC1768/main.cpp +++ b/Marlin/src/HAL/LPC1768/main.cpp @@ -31,20 +31,23 @@ #include #include -extern "C" { - #include -} - -#include "../../sd/cardreader.h" #include "../../inc/MarlinConfig.h" #include "../../core/millis_t.h" +#include "../../sd/cardreader.h" + extern uint32_t MSC_SD_Init(uint8_t pdrv); -extern "C" int isLPC1769(); -extern "C" void disk_timerproc(); + +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 HAL_init() { // Init LEDs @@ -89,11 +92,11 @@ void HAL_init() { //debug_frmwrk_init(); //_DBG("\n\nDebug running\n"); // Initialize the SD card chip select pins as soon as possible - #if PIN_EXISTS(SS) - OUT_WRITE(SS_PIN, HIGH); + #if PIN_EXISTS(SD_SS) + OUT_WRITE(SD_SS_PIN, HIGH); #endif - #if PIN_EXISTS(ONBOARD_SD_CS) && ONBOARD_SD_CS_PIN != SS_PIN + #if PIN_EXISTS(ONBOARD_SD_CS) && ONBOARD_SD_CS_PIN != SD_SS_PIN OUT_WRITE(ONBOARD_SD_CS_PIN, HIGH); #endif @@ -114,17 +117,15 @@ void HAL_init() { PinCfg.Pinmode = 2; // no pull-up/pull-down PINSEL_ConfigPin(&PinCfg); // now set CLKOUT_EN bit - LPC_SC->CLKOUTCFG |= (1<<8); + SBI(LPC_SC->CLKOUTCFG, 8); #endif USB_Init(); // USB Initialization - USB_Connect(FALSE); // USB clear connection + USB_Connect(false); // USB clear connection delay(1000); // Give OS time to notice - USB_Connect(TRUE); + USB_Connect(true); - #if DISABLED(NO_SD_HOST_DRIVE) - MSC_SD_Init(0); // Enable USB SD card access - #endif + 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)) { @@ -136,6 +137,8 @@ void HAL_init() { } HAL_timer_init(); + + TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the min serial handler } // HAL idle task diff --git a/Marlin/src/HAL/LPC1768/spi_pins.h b/Marlin/src/HAL/LPC1768/spi_pins.h index b4da5d4df234..e7d774742f42 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 == SCK_PIN || LCD_PINS_ENABLE == MOSI_PIN || DOGLCD_SCK == SCK_PIN || DOGLCD_MOSI == MOSI_PIN) +#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) #define LPC_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 @@ -31,24 +31,24 @@ #endif /** onboard SD card */ -//#define SCK_PIN P0_07 -//#define MISO_PIN P0_08 -//#define MOSI_PIN P0_09 -//#define SS_PIN P0_06 +//#define SD_SCK_PIN P0_07 +//#define SD_MISO_PIN P0_08 +//#define SD_MOSI_PIN P0_09 +//#define SD_SS_PIN P0_06 /** external */ -#ifndef SCK_PIN - #define SCK_PIN P0_15 +#ifndef SD_SCK_PIN + #define SD_SCK_PIN P0_15 #endif -#ifndef MISO_PIN - #define MISO_PIN P0_17 +#ifndef SD_MISO_PIN + #define SD_MISO_PIN P0_17 #endif -#ifndef MOSI_PIN - #define MOSI_PIN P0_18 +#ifndef SD_MOSI_PIN + #define SD_MOSI_PIN P0_18 #endif -#ifndef SS_PIN - #define SS_PIN P1_23 +#ifndef SD_SS_PIN + #define SD_SS_PIN P1_23 #endif #if !defined(SDSS) || SDSS == P_NC // gets defaulted in pins.h #undef SDSS - #define SDSS SS_PIN + #define SDSS SD_SS_PIN #endif diff --git a/Marlin/src/HAL/LPC1768/tft/tft_spi.cpp b/Marlin/src/HAL/LPC1768/tft/tft_spi.cpp index 84907acd0702..a2cb66ab5bfd 100644 --- a/Marlin/src/HAL/LPC1768/tft/tft_spi.cpp +++ b/Marlin/src/HAL/LPC1768/tft/tft_spi.cpp @@ -89,7 +89,7 @@ void TFT_SPI::Init() { #elif TFT_MISO_PIN == BOARD_SPI2_MISO_PIN SPIx.setModule(2); #endif - SPIx.setClock(SPI_CLOCK_MAX); + SPIx.setClock(SPI_CLOCK_MAX_TFT); SPIx.setBitOrder(MSBFIRST); SPIx.setDataMode(SPI_MODE0); } @@ -125,7 +125,7 @@ uint32_t TFT_SPI::ReadID(uint16_t Reg) { } DataTransferEnd(); - SPIx.setClock(SPI_CLOCK_MAX); + SPIx.setClock(SPI_CLOCK_MAX_TFT); #endif return data >> 7; diff --git a/Marlin/src/HAL/LPC1768/tft/xpt2046.cpp b/Marlin/src/HAL/LPC1768/tft/xpt2046.cpp index 5f96630043c1..9c1e158981da 100644 --- a/Marlin/src/HAL/LPC1768/tft/xpt2046.cpp +++ b/Marlin/src/HAL/LPC1768/tft/xpt2046.cpp @@ -1,6 +1,9 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * 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 @@ -19,7 +22,7 @@ #include "../../../inc/MarlinConfig.h" -#if HAS_TFT_XPT2046 || HAS_TOUCH_XPT2046 +#if HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS #include "xpt2046.h" #include diff --git a/Marlin/src/HAL/LPC1768/tft/xpt2046.h b/Marlin/src/HAL/LPC1768/tft/xpt2046.h index 019f75efce12..aba0799e445f 100644 --- a/Marlin/src/HAL/LPC1768/tft/xpt2046.h +++ b/Marlin/src/HAL/LPC1768/tft/xpt2046.h @@ -1,6 +1,9 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * 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 @@ -25,16 +28,16 @@ #endif #ifndef TOUCH_MISO_PIN - #define TOUCH_MISO_PIN MISO_PIN + #define TOUCH_MISO_PIN SD_MISO_PIN #endif #ifndef TOUCH_MOSI_PIN - #define TOUCH_MOSI_PIN MOSI_PIN + #define TOUCH_MOSI_PIN SD_MOSI_PIN #endif #ifndef TOUCH_SCK_PIN - #define TOUCH_SCK_PIN SCK_PIN + #define TOUCH_SCK_PIN SD_SCK_PIN #endif #ifndef TOUCH_CS_PIN - #define TOUCH_CS_PIN CS_PIN + #define TOUCH_CS_PIN SD_SS_PIN #endif #ifndef TOUCH_INT_PIN #define TOUCH_INT_PIN -1 @@ -51,7 +54,7 @@ enum XPTCoordinate : uint8_t { XPT2046_Z2 = 0x40 | XPT2046_CONTROL | XPT2046_DFR_MODE, }; -#if !defined(XPT2046_Z1_THRESHOLD) +#ifndef XPT2046_Z1_THRESHOLD #define XPT2046_Z1_THRESHOLD 10 #endif diff --git a/Marlin/src/HAL/LPC1768/timers.h b/Marlin/src/HAL/LPC1768/timers.h index e6744fb005bf..4b638546856f 100644 --- a/Marlin/src/HAL/LPC1768/timers.h +++ b/Marlin/src/HAL/LPC1768/timers.h @@ -152,7 +152,7 @@ FORCE_INLINE static void HAL_timer_disable_interrupt(const uint8_t timer_num) { // This function is missing from CMSIS FORCE_INLINE static bool NVIC_GetEnableIRQ(IRQn_Type IRQn) { - return (NVIC->ISER[((uint32_t)IRQn) >> 5] & (1 << ((uint32_t)IRQn) & 0x1F)) != 0; + return TEST(NVIC->ISER[uint32_t(IRQn) >> 5], uint32_t(IRQn) & 0x1F); } FORCE_INLINE static bool HAL_timer_interrupt_enabled(const uint8_t timer_num) { 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 057e10e0f545..0118f92847de 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 @@ -59,13 +59,16 @@ #if HAS_MARLINUI_U8GLIB -#include +#include #include "../../shared/HAL_SPI.h" -void spiBegin(); -void spiInit(uint8_t spiRate); -void spiSend(uint8_t b); -void spiSend(const uint8_t* buf, size_t n); +#ifndef LCD_SPI_SPEED + #ifdef SD_SPI_SPEED + #define LCD_SPI_SPEED SD_SPI_SPEED // Assume SPI speed shared with SD + #else + #define LCD_SPI_SPEED SPI_FULL_SPEED // Use full speed if SD speed is not supplied + #endif +#endif uint8_t u8g_com_HAL_LPC1768_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) { switch (msg) { @@ -81,10 +84,7 @@ uint8_t u8g_com_HAL_LPC1768_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, u8g_SetPIOutput(u8g, U8G_PI_RESET); u8g_Delay(5); spiBegin(); - #ifndef SPI_SPEED - #define SPI_SPEED SPI_FULL_SPEED // use same SPI speed as SD card - #endif - spiInit(SPI_SPEED); + spiInit(LCD_SPI_SPEED); break; case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */ 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 6f7efba4ae20..bf76eaf0f491 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 @@ -79,7 +79,7 @@ #if HAS_MARLINUI_U8GLIB -#include +#include #define I2C_SLA (0x3C*2) //#define I2C_CMD_MODE 0x080 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 592e27f6c006..ce7b33801931 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 @@ -59,14 +59,14 @@ #if HAS_MARLINUI_U8GLIB -#include +#include #include "../../shared/HAL_SPI.h" #include "../../shared/Delay.h" void spiBegin(); void spiInit(uint8_t spiRate); void spiSend(uint8_t b); -void spiSend(const uint8_t* buf, size_t n); +void spiSend(const uint8_t *buf, size_t n); static uint8_t rs_last_state = 255; diff --git a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_sw_spi.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_sw_spi.cpp index 10d84941625f..039fa6769bbe 100644 --- a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_sw_spi.cpp +++ b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_sw_spi.cpp @@ -59,12 +59,14 @@ #if ENABLED(U8GLIB_ST7920) -#include +#include #include #include "../../shared/Delay.h" +#include "../../shared/HAL_SPI.h" -#undef SPI_SPEED -#define SPI_SPEED 3 // About 1 MHz +#ifndef LCD_SPI_SPEED + #define LCD_SPI_SPEED SPI_EIGHTH_SPEED // About 1 MHz +#endif static pin_t SCK_pin_ST7920_HAL, MOSI_pin_ST7920_HAL_HAL; static uint8_t SPI_speed = 0; @@ -92,7 +94,7 @@ uint8_t u8g_com_HAL_LPC1768_ST7920_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t ar u8g_SetPIOutput(u8g, U8G_PI_MOSI); u8g_Delay(5); - SPI_speed = swSpiInit(SPI_SPEED, SCK_pin_ST7920_HAL, MOSI_pin_ST7920_HAL_HAL); + SPI_speed = swSpiInit(LCD_SPI_SPEED, SCK_pin_ST7920_HAL, MOSI_pin_ST7920_HAL_HAL); u8g_SetPILevel(u8g, U8G_PI_CS, 0); u8g_SetPILevel(u8g, U8G_PI_SCK, 0); 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 ca9d6ecfbe25..3308d03e79f9 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 @@ -60,16 +60,18 @@ #if HAS_MARLINUI_U8GLIB && DISABLED(U8GLIB_ST7920) #include +#include "../../shared/HAL_SPI.h" -#undef SPI_SPEED -#define SPI_SPEED 2 // About 2 MHz +#ifndef LCD_SPI_SPEED + #define LCD_SPI_SPEED SPI_QUARTER_SPEED // About 2 MHz +#endif #include #include #include #include -#include +#include 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 ) { @@ -145,7 +147,7 @@ uint8_t u8g_com_HAL_LPC1768_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, u8g_SetPIOutput(u8g, U8G_PI_CS); u8g_SetPIOutput(u8g, U8G_PI_A0); if (U8G_PIN_NONE != u8g->pin_list[U8G_PI_RESET]) u8g_SetPIOutput(u8g, U8G_PI_RESET); - SPI_speed = swSpiInit(SPI_SPEED, u8g->pin_list[U8G_PI_SCK], u8g->pin_list[U8G_PI_MOSI]); + SPI_speed = swSpiInit(LCD_SPI_SPEED, u8g->pin_list[U8G_PI_SCK], u8g->pin_list[U8G_PI_MOSI]); u8g_SetPILevel(u8g, U8G_PI_SCK, 0); u8g_SetPILevel(u8g, U8G_PI_MOSI, 0); break; diff --git a/Marlin/src/HAL/LPC1768/upload_extra_script.py b/Marlin/src/HAL/LPC1768/upload_extra_script.py index 9b0d0617a0c9..fb3aaef7cd38 100755 --- a/Marlin/src/HAL/LPC1768/upload_extra_script.py +++ b/Marlin/src/HAL/LPC1768/upload_extra_script.py @@ -8,9 +8,7 @@ target_filename = "FIRMWARE.CUR" target_drive = "REARM" -import os -import getpass -import platform +import os,getpass,platform current_OS = platform.system() Import("env") @@ -22,124 +20,104 @@ def print_error(e): 'or copy the firmware (.pio/build/%s/firmware.bin) manually to the appropriate disk\n' \ %(e, env.get('PIOENV'))) -try: - if current_OS == 'Windows': +def before_upload(source, target, env): + try: # - # platformio.ini will accept this for a Windows upload port designation: 'upload_port = L:' - # Windows - doesn't care about the disk's name, only cares about the drive letter + # Find a disk for upload # - - # - # get all drives on this computer - # - import subprocess - # typical result (string): 'Drives: C:\ D:\ E:\ F:\ G:\ H:\ I:\ J:\ K:\ L:\ M:\ Y:\ Z:\' - driveStr = str(subprocess.check_output("fsutil fsinfo drives")) - # typical result (string): 'C:\ D:\ E:\ F:\ G:\ H:\ I:\ J:\ K:\ L:\ M:\ Y:\ Z:\' - # driveStr = driveStr.strip().lstrip('Drives: ') <- Doesn't work in other Languages as English. In German is "Drives:" = "Laufwerke:" - FirstFound = driveStr.find(':',0,-1) # Find the first ":" and - driveStr = driveStr[FirstFound + 1 : -1] # truncate to the rest - # typical result (array of stings): ['C:\\', 'D:\\', 'E:\\', 'F:\\', - # 'G:\\', 'H:\\', 'I:\\', 'J:\\', 'K:\\', 'L:\\', 'M:\\', 'Y:\\', 'Z:\\'] - drives = driveStr.split() - upload_disk = 'Disk not found' target_file_found = False target_drive_found = False - for drive in drives: - final_drive_name = drive.strip().rstrip('\\') # typical result (string): 'C:' - try: - volume_info = str(subprocess.check_output('cmd /C dir ' + final_drive_name, stderr=subprocess.STDOUT)) - except Exception as e: - continue - else: - if target_drive in volume_info and target_file_found == False: # set upload if not found target file yet - target_drive_found = True - upload_disk = final_drive_name - if target_filename in volume_info: - if target_file_found == False: + if current_OS == 'Windows': + # + # platformio.ini will accept this for a Windows upload port designation: 'upload_port = L:' + # Windows - doesn't care about the disk's name, only cares about the drive letter + import subprocess,string + from ctypes import windll + + # getting list of drives + # https://stackoverflow.com/questions/827371/is-there-a-way-to-list-all-the-available-drive-letters-in-python + drives = [] + bitmask = windll.kernel32.GetLogicalDrives() + for letter in string.ascii_uppercase: + if bitmask & 1: + drives.append(letter) + bitmask >>= 1 + + for drive in drives: + final_drive_name = drive + ':\\' + # print ('disc check: {}'.format(final_drive_name)) + try: + volume_info = str(subprocess.check_output('cmd /C dir ' + final_drive_name, stderr=subprocess.STDOUT)) + except Exception as e: + print ('error:{}'.format(e)) + continue + else: + if target_drive in volume_info and not target_file_found: # set upload if not found target file yet + target_drive_found = True upload_disk = final_drive_name - target_file_found = True + if target_filename in volume_info: + if not target_file_found: + upload_disk = final_drive_name + target_file_found = True - # - # set upload_port to drive if found - # + elif current_OS == 'Linux': + # + # platformio.ini will accept this for a Linux upload port designation: 'upload_port = /media/media_name/drive' + # + drives = os.listdir(os.path.join(os.sep, 'media', getpass.getuser())) + if target_drive in drives: # If target drive is found, use it. + target_drive_found = True + upload_disk = os.path.join(os.sep, 'media', getpass.getuser(), target_drive) + os.sep + else: + for drive in drives: + try: + files = os.listdir(os.path.join(os.sep, 'media', getpass.getuser(), drive)) + except: + continue + else: + if target_filename in files: + upload_disk = os.path.join(os.sep, 'media', getpass.getuser(), drive) + os.sep + target_file_found = True + break + # + # set upload_port to drive if found + # - if target_file_found == True or target_drive_found == True: - env.Replace( - UPLOAD_PORT=upload_disk - ) - print('upload disk: ', upload_disk) - else: - print_error('Autodetect Error') + if target_file_found or target_drive_found: + env.Replace( + UPLOAD_FLAGS="-P$UPLOAD_PORT" + ) - elif current_OS == 'Linux': - # - # platformio.ini will accept this for a Linux upload port designation: 'upload_port = /media/media_name/drive' - # - upload_disk = 'Disk not found' - target_file_found = False - target_drive_found = False - drives = os.listdir(os.path.join(os.sep, 'media', getpass.getuser())) - if target_drive in drives: # If target drive is found, use it. - target_drive_found = True - upload_disk = os.path.join(os.sep, 'media', getpass.getuser(), target_drive) + os.sep - else: + elif current_OS == 'Darwin': # MAC + # + # platformio.ini will accept this for a OSX upload port designation: 'upload_port = /media/media_name/drive' + # + drives = os.listdir('/Volumes') # human readable names + if target_drive in drives and not target_file_found: # set upload if not found target file yet + target_drive_found = True + upload_disk = '/Volumes/' + target_drive + '/' for drive in drives: try: - files = os.listdir(os.path.join(os.sep, 'media', getpass.getuser(), drive)) + filenames = os.listdir('/Volumes/' + drive + '/') # will get an error if the drive is protected except: continue else: - if target_filename in files: - upload_disk = os.path.join(os.sep, 'media', getpass.getuser(), drive) + os.sep + if target_filename in filenames: + if not target_file_found: + upload_disk = '/Volumes/' + drive + '/' target_file_found = True - break + # - # set upload_port to drive if found + # Set upload_port to drive if found # - if target_file_found or target_drive_found: - env.Replace( - UPLOAD_FLAGS="-P$UPLOAD_PORT", - UPLOAD_PORT=upload_disk - ) - print('upload disk: ', upload_disk) + env.Replace(UPLOAD_PORT=upload_disk) + print('\nUpload disk: ', upload_disk, '\n') else: print_error('Autodetect Error') - elif current_OS == 'Darwin': # MAC - # - # platformio.ini will accept this for a OSX upload port designation: 'upload_port = /media/media_name/drive' - # - upload_disk = 'Disk not found' - drives = os.listdir('/Volumes') # human readable names - target_file_found = False - target_drive_found = False - if target_drive in drives and target_file_found == False: # set upload if not found target file yet - target_drive_found = True - upload_disk = '/Volumes/' + target_drive + '/' - for drive in drives: - try: - filenames = os.listdir('/Volumes/' + drive + '/') # will get an error if the drive is protected - except: - continue - else: - if target_filename in filenames: - if target_file_found == False: - upload_disk = '/Volumes/' + drive + '/' - target_file_found = True - # - # set upload_port to drive if found - # - - if target_file_found == True or target_drive_found == True: - env.Replace( - UPLOAD_PORT=upload_disk - ) - print('\nupload disk: ', upload_disk, '\n') - else: - print_error('Autodetect Error') + except Exception as e: + print_error(str(e)) -except Exception as e: - print_error(str(e)) +env.AddPreAction("upload", before_upload) diff --git a/Marlin/src/HAL/LPC1768/usb_serial.cpp b/Marlin/src/HAL/LPC1768/usb_serial.cpp index d225ce418860..3c1fce54f95f 100644 --- a/Marlin/src/HAL/LPC1768/usb_serial.cpp +++ b/Marlin/src/HAL/LPC1768/usb_serial.cpp @@ -29,8 +29,8 @@ EmergencyParser::State emergency_state; -bool CDC_RecvCallback(const char buffer) { - emergency_parser.update(emergency_state, buffer); +bool CDC_RecvCallback(const char c) { + emergency_parser.update(emergency_state, c); return true; } diff --git a/Marlin/src/HAL/LPC1768/watchdog.cpp b/Marlin/src/HAL/LPC1768/watchdog.cpp index 3cd22d665168..f23ccf5b512d 100644 --- a/Marlin/src/HAL/LPC1768/watchdog.cpp +++ b/Marlin/src/HAL/LPC1768/watchdog.cpp @@ -28,6 +28,8 @@ #include #include "watchdog.h" +#define WDT_TIMEOUT_US TERN(WATCHDOG_DURATION_8S, 8000000, 4000000) // 4 or 8 second timeout + void watchdog_init() { #if ENABLED(WATCHDOG_RESET_MANUAL) // We enable the watchdog timer, but only for the interrupt. @@ -52,7 +54,7 @@ void watchdog_init() { #else WDT_Init(WDT_CLKSRC_IRC, WDT_MODE_RESET); #endif - WDT_Start(WDT_TIMEOUT); + WDT_Start(WDT_TIMEOUT_US); } void HAL_watchdog_refresh() { diff --git a/Marlin/src/HAL/LPC1768/watchdog.h b/Marlin/src/HAL/LPC1768/watchdog.h index cc170881f375..c843f0ed5571 100644 --- a/Marlin/src/HAL/LPC1768/watchdog.h +++ b/Marlin/src/HAL/LPC1768/watchdog.h @@ -21,8 +21,6 @@ */ #pragma once -#define WDT_TIMEOUT 4000000 // 4 second timeout - void watchdog_init(); void HAL_watchdog_refresh(); diff --git a/Marlin/src/HAL/NATIVE_SIM/HAL.h b/Marlin/src/HAL/NATIVE_SIM/HAL.h new file mode 100644 index 000000000000..d5c5782c36c3 --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/HAL.h @@ -0,0 +1,217 @@ +/** + * 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 + * + * 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 CPU_32_BIT +#define HAL_IDLETASK +void HAL_idletask(); + +#define F_CPU 100000000 +#define SystemCoreClock F_CPU +#include +#include + +#undef min +#undef max + +#include +#include "pinmapping.h" + +void _printf (const char *format, ...); +void _putc(uint8_t c); +uint8_t _getc(); + +//extern "C" volatile uint32_t _millis; + +//arduino: Print.h +#define DEC 10 +#define HEX 16 +#define OCT 8 +#define BIN 2 +//arduino: binary.h (weird defines) +#define B01 1 +#define B10 2 + +#include "../shared/Marduino.h" +#include "../shared/math_32bit.h" +#include "../shared/HAL_SPI.h" +#include "fastio.h" +#include "watchdog.h" +#include "serial.h" + +#define SHARED_SERVOS HAS_SERVOS + +extern MSerialT serial_stream_0; +extern MSerialT serial_stream_1; +extern MSerialT serial_stream_2; +extern MSerialT serial_stream_3; + +#define _MSERIAL(X) serial_stream_##X +#define MSERIAL(X) _MSERIAL(X) + +#if WITHIN(SERIAL_PORT, 0, 3) + #define MYSERIAL1 MSERIAL(SERIAL_PORT) +#else + #error "SERIAL_PORT must be from 0 to 3. Please update your configuration." +#endif + +#ifdef SERIAL_PORT_2 + #if WITHIN(SERIAL_PORT_2, 0, 3) + #define MYSERIAL2 MSERIAL(SERIAL_PORT_2) + #else + #error "SERIAL_PORT_2 must be from 0 to 3. Please update your configuration." + #endif +#endif + +#ifdef MMU2_SERIAL_PORT + #if WITHIN(MMU2_SERIAL_PORT, 0, 3) + #define MMU2_SERIAL MSERIAL(MMU2_SERIAL_PORT) + #else + #error "MMU2_SERIAL_PORT must be from 0 to 3. Please update your configuration." + #endif +#endif + +#ifdef LCD_SERIAL_PORT + #if WITHIN(LCD_SERIAL_PORT, 0, 3) + #define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT) + #else + #error "LCD_SERIAL_PORT must be from 0 to 3. Please update your configuration." + #endif +#endif + + +#define ST7920_DELAY_1 DELAY_NS(600) +#define ST7920_DELAY_2 DELAY_NS(750) +#define ST7920_DELAY_3 DELAY_NS(750) + +// +// Interrupts +// +#define CRITICAL_SECTION_START() +#define CRITICAL_SECTION_END() +#define ISRS_ENABLED() +#define ENABLE_ISRS() +#define DISABLE_ISRS() + +inline void HAL_init() {} + +// Utility functions +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wunused-function" +int freeMemory(); +#pragma GCC diagnostic pop + +// ADC +#define HAL_ADC_VREF 5.0 +#define HAL_ADC_RESOLUTION 10 +#define HAL_ANALOG_SELECT(ch) HAL_adc_enable_channel(ch) +#define HAL_START_ADC(ch) HAL_adc_start_conversion(ch) +#define HAL_READ_ADC() HAL_adc_get_result() +#define HAL_ADC_READY() true + +void HAL_adc_init(); +void HAL_adc_enable_channel(const uint8_t ch); +void HAL_adc_start_conversion(const uint8_t ch); +uint16_t HAL_adc_get_result(); + +// Reset source +inline void HAL_clear_reset_source(void) {} +inline uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; } + +/* ---------------- Delay in cycles */ + +#define DELAY_CYCLES(x) Kernel::delayCycles(x) +#define SYSTEM_YIELD() Kernel::yield() + +// Maple Compatibility +typedef void (*systickCallback_t)(void); +void systick_attach_callback(systickCallback_t cb); +extern volatile uint32_t systick_uptime_millis; + +// Marlin uses strstr in constexpr context, this is not supported, workaround by defining constexpr versions of the required functions. +#define strstr(a, b) strstr_constexpr((a), (b)) + +constexpr inline std::size_t strlen_constexpr(const char* str) { + // https://github.com/gcc-mirror/gcc/blob/5c7634a0e5f202935aa6c11b6ea953b8bf80a00a/libstdc%2B%2B-v3/include/bits/char_traits.h#L329 + if (str != nullptr) { + std::size_t i = 0; + while (str[i] != '\0') { + ++i; + } + + return i; + } + + return 0; +} + +constexpr inline int strncmp_constexpr(const char* lhs, const char* rhs, std::size_t count) { + // https://github.com/gcc-mirror/gcc/blob/13b9cbfc32fe3ac4c81c4dd9c42d141c8fb95db4/libstdc%2B%2B-v3/include/bits/char_traits.h#L655 + if (lhs == nullptr || rhs == nullptr) { + return rhs != nullptr ? -1 : 1; + } + + for (std::size_t i = 0; i < count; ++i) { + if (lhs[i] != rhs[i]) { + return lhs[i] < rhs[i] ? -1 : 1; + } else if (lhs[i] == '\0') { + return 0; + } + } + + return 0; +} + +constexpr inline const char* strstr_constexpr(const char* str, const char* target) { + // https://github.com/freebsd/freebsd/blob/master/sys/libkern/strstr.c + if (char c = target != nullptr ? *target++ : '\0'; c != '\0' && str != nullptr) { + std::size_t len = strlen_constexpr(target); + do { + char sc = {}; + do { + if ((sc = *str++) == '\0') { + return nullptr; + } + } while (sc != c); + } while (strncmp_constexpr(str, target, len) != 0); + --str; + } + + return str; +} + +constexpr inline char* strstr_constexpr(char* str, const char* target) { + // https://github.com/freebsd/freebsd/blob/master/sys/libkern/strstr.c + if (char c = target != nullptr ? *target++ : '\0'; c != '\0' && str != nullptr) { + std::size_t len = strlen_constexpr(target); + do { + char sc = {}; + do { + if ((sc = *str++) == '\0') { + return nullptr; + } + } while (sc != c); + } while (strncmp_constexpr(str, target, len) != 0); + --str; + } + return str; +} diff --git a/Marlin/src/HAL/NATIVE_SIM/MarlinSPI.h b/Marlin/src/HAL/NATIVE_SIM/MarlinSPI.h new file mode 100644 index 000000000000..b5cc6f02a45a --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/MarlinSPI.h @@ -0,0 +1,26 @@ +/** + * 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 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include + +using MarlinSPI = SPIClass; diff --git a/Marlin/src/HAL/NATIVE_SIM/fastio.h b/Marlin/src/HAL/NATIVE_SIM/fastio.h new file mode 100644 index 000000000000..de8013b1e542 --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/fastio.h @@ -0,0 +1,111 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * Fast I/O Routines for X86_64 + */ + +#include "../shared/Marduino.h" +#include + +#define SET_DIR_INPUT(IO) Gpio::setDir(IO, 1) +#define SET_DIR_OUTPUT(IO) Gpio::setDir(IO, 0) + +#define SET_MODE(IO, mode) Gpio::setMode(IO, mode) + +#define WRITE_PIN_SET(IO) Gpio::set(IO) +#define WRITE_PIN_CLR(IO) Gpio::clear(IO) + +#define READ_PIN(IO) Gpio::get(IO) +#define WRITE_PIN(IO,V) Gpio::set(IO, V) + +/** + * Magic I/O routines + * + * Now you can simply SET_OUTPUT(STEP); WRITE(STEP, HIGH); WRITE(STEP, LOW); + * + * Why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html + */ + +/// Read a pin +#define _READ(IO) READ_PIN(IO) + +/// Write to a pin +#define _WRITE(IO,V) WRITE_PIN(IO,V) + +/// toggle a pin +#define _TOGGLE(IO) _WRITE(IO, !READ(IO)) + +/// set pin as input +#define _SET_INPUT(IO) SET_DIR_INPUT(IO) + +/// set pin as output +#define _SET_OUTPUT(IO) SET_DIR_OUTPUT(IO) + +/// set pin as input with pullup mode +#define _PULLUP(IO,V) pinMode(IO, (V) ? INPUT_PULLUP : INPUT) + +/// set pin as input with pulldown mode +#define _PULLDOWN(IO,V) pinMode(IO, (V) ? INPUT_PULLDOWN : INPUT) + +// hg42: all pins can be input or output (I hope) +// hg42: undefined pins create compile error (IO, is no pin) +// hg42: currently not used, but was used by pinsDebug + +/// check if pin is an input +#define _IS_INPUT(IO) (IO >= 0) + +/// check if pin is an output +#define _IS_OUTPUT(IO) (IO >= 0) + +/// Read a pin wrapper +#define READ(IO) _READ(IO) + +/// Write to a pin wrapper +#define WRITE(IO,V) _WRITE(IO,V) + +/// toggle a pin wrapper +#define TOGGLE(IO) _TOGGLE(IO) + +/// set pin as input wrapper +#define SET_INPUT(IO) _SET_INPUT(IO) +/// set pin as input with pullup wrapper +#define SET_INPUT_PULLUP(IO) do{ _SET_INPUT(IO); _PULLUP(IO, HIGH); }while(0) +/// set pin as input with pulldown wrapper +#define SET_INPUT_PULLDOWN(IO) do{ _SET_INPUT(IO); _PULLDOWN(IO, HIGH); }while(0) +/// set pin as output wrapper - reads the pin and sets the output to that value +#define SET_OUTPUT(IO) do{ _WRITE(IO, _READ(IO)); _SET_OUTPUT(IO); }while(0) +// set pin as PWM +#define SET_PWM(IO) SET_OUTPUT(IO) + +/// check if pin is an input wrapper +#define IS_INPUT(IO) _IS_INPUT(IO) +/// check if pin is an output wrapper +#define IS_OUTPUT(IO) _IS_OUTPUT(IO) + +// Shorthand +#define OUT_WRITE(IO,V) do{ SET_OUTPUT(IO); WRITE(IO,V); }while(0) + +// digitalRead/Write wrappers +#define extDigitalRead(IO) digitalRead(IO) +#define extDigitalWrite(IO,V) digitalWrite(IO,V) diff --git a/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_LCD.h b/Marlin/src/HAL/NATIVE_SIM/inc/Conditionals_LCD.h similarity index 82% rename from Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_LCD.h rename to Marlin/src/HAL/NATIVE_SIM/inc/Conditionals_LCD.h index a9f1b5822215..1ac02f118285 100644 --- a/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_LCD.h +++ b/Marlin/src/HAL/NATIVE_SIM/inc/Conditionals_LCD.h @@ -1,6 +1,6 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm @@ -20,7 +20,3 @@ * */ #pragma once - -#if HAS_SPI_TFT || HAS_FSMC_TFT - #error "Sorry! TFT displays are not available for HAL/STM32F4_F7." -#endif diff --git a/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_adv.h b/Marlin/src/HAL/NATIVE_SIM/inc/Conditionals_adv.h similarity index 77% rename from Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_adv.h rename to Marlin/src/HAL/NATIVE_SIM/inc/Conditionals_adv.h index 5f1c4b16019d..69b6b4848f6e 100644 --- a/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_adv.h +++ b/Marlin/src/HAL/NATIVE_SIM/inc/Conditionals_adv.h @@ -1,6 +1,6 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm @@ -20,3 +20,12 @@ * */ #pragma once + +// Add strcmp_P if missing +#ifndef strcmp_P + #define strcmp_P(a, b) strcmp((a), (b)) +#endif + +#ifndef strcat_P + #define strcat_P(dest, src) strcat((dest), (src)) +#endif diff --git a/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h b/Marlin/src/HAL/NATIVE_SIM/inc/Conditionals_post.h similarity index 76% rename from Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h rename to Marlin/src/HAL/NATIVE_SIM/inc/Conditionals_post.h index b5d808e21acc..1ac02f118285 100644 --- a/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h +++ b/Marlin/src/HAL/NATIVE_SIM/inc/Conditionals_post.h @@ -1,6 +1,6 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm @@ -20,10 +20,3 @@ * */ #pragma once - -#if ENABLED(EEPROM_SETTINGS) && defined(STM32F7) - #undef USE_WIRED_EEPROM - #undef SRAM_EEPROM_EMULATION - #undef SDCARD_EEPROM_EMULATION - #define FLASH_EEPROM_EMULATION -#endif diff --git a/Marlin/src/HAL/NATIVE_SIM/inc/SanityCheck.h b/Marlin/src/HAL/NATIVE_SIM/inc/SanityCheck.h new file mode 100644 index 000000000000..104af9af5b20 --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/inc/SanityCheck.h @@ -0,0 +1,43 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * Test X86_64-specific configuration values for errors at compile-time. + */ + +// Emulating RAMPS +#if ENABLED(SPINDLE_LASER_PWM) && !(SPINDLE_LASER_PWM_PIN == 4 || SPINDLE_LASER_PWM_PIN == 6 || SPINDLE_LASER_PWM_PIN == 11) + #error "SPINDLE_LASER_PWM_PIN must use SERVO0, SERVO1 or SERVO3 connector" +#endif + +#if ENABLED(FAST_PWM_FAN) || SPINDLE_LASER_FREQUENCY + #error "Features requiring Hardware PWM (FAST_PWM_FAN, SPINDLE_LASER_FREQUENCY) are not yet supported on LINUX." +#endif + +#if HAS_TMC_SW_SERIAL + #error "TMC220x Software Serial is not supported on LINUX." +#endif + +#if ENABLED(POSTMORTEM_DEBUGGING) + #error "POSTMORTEM_DEBUGGING is not yet supported on LINUX." +#endif diff --git a/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h b/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h new file mode 100644 index 000000000000..7ba14574d0c7 --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h @@ -0,0 +1,61 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * Support routines for X86_64 + */ + +#pragma once + +/** + * Translation of routines & variables used by pinsDebug.h + */ + +#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS +#define pwm_details(pin) pin = pin // do nothing // print PWM details +#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 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)); +} diff --git a/Marlin/src/HAL/NATIVE_SIM/servo_private.h b/Marlin/src/HAL/NATIVE_SIM/servo_private.h new file mode 100644 index 000000000000..06be1893f6eb --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/servo_private.h @@ -0,0 +1,80 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * servo.h - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2 + * Copyright (c) 2009 Michael Margolis. 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 + */ + +/** + * Based on "servo.h - Interrupt driven Servo library for Arduino using 16 bit timers - + * Version 2 Copyright (c) 2009 Michael Margolis. All right reserved. + * + * The only modification was to update/delete macros to match the LPC176x. + * + */ + +#include + +// Macros +//values in microseconds +#define MIN_PULSE_WIDTH 544 // the shortest pulse sent to a servo +#define MAX_PULSE_WIDTH 2400 // the longest pulse sent to a servo +#define DEFAULT_PULSE_WIDTH 1500 // default pulse width when servo is attached +#define REFRESH_INTERVAL 20000 // minimum time to refresh servos in microseconds + +#define MAX_SERVOS 4 + +#define INVALID_SERVO 255 // flag indicating an invalid servo index + + +// Types + +typedef struct { + uint8_t nbr : 8 ; // a pin number from 0 to 254 (255 signals invalid pin) + uint8_t isActive : 1 ; // true if this channel is enabled, pin not pulsed if false +} ServoPin_t; + +typedef struct { + ServoPin_t Pin; + unsigned int pulse_width; // pulse width in microseconds +} ServoInfo_t; + +// Global variables + +extern uint8_t ServoCount; +extern ServoInfo_t servo_info[MAX_SERVOS]; diff --git a/Marlin/src/HAL/NATIVE_SIM/spi_pins.h b/Marlin/src/HAL/NATIVE_SIM/spi_pins.h new file mode 100644 index 000000000000..a5138e0ccbe8 --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/spi_pins.h @@ -0,0 +1,55 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#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) + #define LPC_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 + // spiBeginTransaction. +#endif + +// Onboard SD +//#define SD_SCK_PIN P0_07 +//#define SD_MISO_PIN P0_08 +//#define SD_MOSI_PIN P0_09 +//#define SD_SS_PIN P0_06 + +// External SD +#ifndef SD_SCK_PIN + #define SD_SCK_PIN 50 +#endif +#ifndef SD_MISO_PIN + #define SD_MISO_PIN 51 +#endif +#ifndef SD_MOSI_PIN + #define SD_MOSI_PIN 52 +#endif +#ifndef SD_SS_PIN + #define SD_SS_PIN 53 +#endif +#ifndef SDSS + #define SDSS SD_SS_PIN +#endif diff --git a/Marlin/src/HAL/NATIVE_SIM/tft/tft_spi.h b/Marlin/src/HAL/NATIVE_SIM/tft/tft_spi.h new file mode 100644 index 000000000000..b3e622f19ac4 --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/tft/tft_spi.h @@ -0,0 +1,64 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include "../../../inc/MarlinConfig.h" + +#ifndef LCD_READ_ID + #define LCD_READ_ID 0x04 // Read display identification information (0xD3 on ILI9341) +#endif +#ifndef LCD_READ_ID4 + #define LCD_READ_ID4 0xD3 // Read display identification information (0xD3 on ILI9341) +#endif + +#define DATASIZE_8BIT 8 +#define DATASIZE_16BIT 16 +#define TFT_IO_DRIVER TFT_SPI + +#define DMA_MINC_ENABLE 1 +#define DMA_MINC_DISABLE 0 + +class TFT_SPI { +private: + static uint32_t ReadID(uint16_t Reg); + static void Transmit(uint16_t Data); + static void TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count); + +public: + // static SPIClass SPIx; + + static void Init(); + static uint32_t GetID(); + static bool isBusy(); + static void Abort(); + + static void DataTransferBegin(uint16_t DataWidth = DATASIZE_16BIT); + static void DataTransferEnd(); + static void DataTransferAbort(); + + static void WriteData(uint16_t Data); + static void WriteReg(uint16_t Reg); + + static void WriteSequence(uint16_t *Data, uint16_t Count); + // static void WriteMultiple(uint16_t Color, uint16_t Count); + static void WriteMultiple(uint16_t Color, uint32_t Count); +}; diff --git a/Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h b/Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h new file mode 100644 index 000000000000..9ef1816c7b16 --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h @@ -0,0 +1,80 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include "../../../inc/MarlinConfig.h" + +#if ENABLED(TOUCH_BUTTONS_HW_SPI) + #include +#endif + +#ifndef TOUCH_MISO_PIN + #define TOUCH_MISO_PIN SD_MISO_PIN +#endif +#ifndef TOUCH_MOSI_PIN + #define TOUCH_MOSI_PIN SD_MOSI_PIN +#endif +#ifndef TOUCH_SCK_PIN + #define TOUCH_SCK_PIN SD_SCK_PIN +#endif +#ifndef TOUCH_CS_PIN + #define TOUCH_CS_PIN SD_SS_PIN +#endif +#ifndef TOUCH_INT_PIN + #define TOUCH_INT_PIN -1 +#endif + +#define XPT2046_DFR_MODE 0x00 +#define XPT2046_SER_MODE 0x04 +#define XPT2046_CONTROL 0x80 + +enum XPTCoordinate : uint8_t { + XPT2046_X = 0x10 | XPT2046_CONTROL | XPT2046_DFR_MODE, + XPT2046_Y = 0x50 | XPT2046_CONTROL | XPT2046_DFR_MODE, + XPT2046_Z1 = 0x30 | XPT2046_CONTROL | XPT2046_DFR_MODE, + XPT2046_Z2 = 0x40 | XPT2046_CONTROL | XPT2046_DFR_MODE, +}; + +#if !defined(XPT2046_Z1_THRESHOLD) + #define XPT2046_Z1_THRESHOLD 10 +#endif + +class XPT2046 { +private: + static bool isBusy() { return false; } + + static uint16_t getRawData(const XPTCoordinate coordinate); + static bool isTouched(); + + static inline void DataTransferBegin(); + static inline void DataTransferEnd(); + #if ENABLED(TOUCH_BUTTONS_HW_SPI) + static uint16_t HardwareIO(uint16_t data); + #endif + static uint16_t SoftwareIO(uint16_t data); + static uint16_t IO(uint16_t data = 0); + +public: + #if ENABLED(TOUCH_BUTTONS_HW_SPI) + static SPIClass SPIx; + #endif + + static void Init(); + static bool getRawPoint(int16_t *x, int16_t *y); +}; diff --git a/Marlin/src/HAL/NATIVE_SIM/timers.h b/Marlin/src/HAL/NATIVE_SIM/timers.h new file mode 100644 index 000000000000..c61eb29e76cf --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/timers.h @@ -0,0 +1,91 @@ +/** + * Marlin 3D Printer Firmware + * + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * + * 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 + +/** + * HAL timers for Linux X86_64 + */ + +#include + +// ------------------------ +// Defines +// ------------------------ + +#define FORCE_INLINE __attribute__((always_inline)) inline + +typedef uint64_t hal_timer_t; +#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFFFFFFFFF + +#define HAL_TIMER_RATE ((SystemCoreClock) / 4) // frequency of timers peripherals + +#ifndef STEP_TIMER_NUM + #define STEP_TIMER_NUM 0 // Timer Index for Stepper +#endif +#ifndef PULSE_TIMER_NUM + #define PULSE_TIMER_NUM STEP_TIMER_NUM +#endif +#ifndef TEMP_TIMER_NUM + #define TEMP_TIMER_NUM 1 // Timer Index for Temperature +#endif +#ifndef SYSTICK_TIMER_NUM + #define SYSTICK_TIMER_NUM 2 // Timer Index for Systick +#endif +#define SYSTICK_TIMER_FREQUENCY 1000 + +#define TEMP_TIMER_RATE 1000000 +#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency + +#define STEPPER_TIMER_RATE HAL_TIMER_RATE // frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) +#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs +#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US) + +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE +#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US + +#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM) +#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM) +#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM) + +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM) +#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM) + +#ifndef HAL_STEP_TIMER_ISR + #define HAL_STEP_TIMER_ISR() extern "C" void TIMER0_IRQHandler() +#endif +#ifndef HAL_TEMP_TIMER_ISR + #define HAL_TEMP_TIMER_ISR() extern "C" void TIMER1_IRQHandler() +#endif + +void HAL_timer_init(); +void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency); + +void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare); +hal_timer_t HAL_timer_get_compare(const uint8_t timer_num); +hal_timer_t HAL_timer_get_count(const uint8_t timer_num); + +void HAL_timer_enable_interrupt(const uint8_t timer_num); +void HAL_timer_disable_interrupt(const uint8_t timer_num); +bool HAL_timer_interrupt_enabled(const uint8_t timer_num); + +#define HAL_timer_isr_prologue(TIMER_NUM) +#define HAL_timer_isr_epilogue(TIMER_NUM) diff --git a/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_I2C_routines.cpp b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_I2C_routines.cpp new file mode 100644 index 000000000000..745454394aae --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_I2C_routines.cpp @@ -0,0 +1,52 @@ +/** + * 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 . + * + */ + +// adapted from I2C/master/master.c example +// https://www-users.cs.york.ac.uk/~pcc/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html + +#ifdef __PLAT_NATIVE_SIM__ + +#include + +#ifdef __cplusplus + extern "C" { +#endif + +uint8_t u8g_i2c_start(const uint8_t sla) { + return 1; +} + +void u8g_i2c_init(const uint8_t clock_option) { +} + +uint8_t u8g_i2c_send_byte(uint8_t data) { + return 1; +} + +void u8g_i2c_stop() { +} + +#ifdef __cplusplus + } +#endif + +#endif // __PLAT_NATIVE_SIM__ diff --git a/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_I2C_routines.h b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_I2C_routines.h new file mode 100644 index 000000000000..6d5f91d3ba45 --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_I2C_routines.h @@ -0,0 +1,37 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#ifdef __cplusplus + extern "C" { +#endif + +void u8g_i2c_init(const uint8_t clock_options); +//uint8_t u8g_i2c_wait(uint8_t mask, uint8_t pos); +uint8_t u8g_i2c_start(uint8_t sla); +uint8_t u8g_i2c_send_byte(uint8_t data); +void u8g_i2c_stop(); + +#ifdef __cplusplus + } +#endif + diff --git a/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_defines.h b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_defines.h new file mode 100644 index 000000000000..44ffbfeb90e5 --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_defines.h @@ -0,0 +1,44 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +void usleep(uint64_t microsec); +// The following are optional depending on the platform. + +// definitions of HAL specific com and device drivers. +uint8_t u8g_com_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); +uint8_t u8g_com_ST7920_sw_spi_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_SW_SPI u8g_com_sw_spi_fn +#define U8G_COM_ST7920_SW_SPI u8g_com_ST7920_sw_spi_fn + +// let these default for now +#define U8G_COM_HW_SPI u8g_com_null_fn +#define U8G_COM_ST7920_HW_SPI u8g_com_null_fn +#define U8G_COM_SSD_I2C u8g_com_null_fn +#define U8G_COM_PARALLEL u8g_com_null_fn +#define U8G_COM_T6963 u8g_com_null_fn +#define U8G_COM_FAST_PARALLEL u8g_com_null_fn +#define U8G_COM_UC_I2C u8g_com_null_fn + + diff --git a/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_delay.h b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_delay.h new file mode 100644 index 000000000000..297361cd448f --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_delay.h @@ -0,0 +1,43 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * LCD delay routines - used by all the drivers. + * + * These are based on the LPC1768 routines. + * + * Couldn't just call exact copies because the overhead + * results in a one microsecond delay taking about 4µS. + */ + +#ifdef __cplusplus + extern "C" { +#endif + +void U8g_delay(int msec); +void u8g_MicroDelay(); +void u8g_10MicroDelay(); + +#ifdef __cplusplus + } +#endif diff --git a/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_pin_routines.cpp b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_pin_routines.cpp new file mode 100644 index 000000000000..3b5acc1656cd --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_pin_routines.cpp @@ -0,0 +1,52 @@ +/** + * 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 . + * + */ + +/** + * Low level pin manipulation routines - used by all the drivers. + * + * These are based on the LPC1768 pinMode, digitalRead & digitalWrite routines. + * + * Couldn't just call exact copies because the overhead killed the LCD update speed + * With an intermediate level the softspi was running in the 10-20kHz range which + * resulted in using about about 25% of the CPU's time. + */ + +#ifdef __PLAT_NATIVE_SIM__ + +#include "../fastio.h" +#include "LCD_pin_routines.h" + +#ifdef __cplusplus + extern "C" { +#endif +void u8g_SetPinOutput(uint8_t internal_pin_number){SET_DIR_OUTPUT(internal_pin_number);} +void u8g_SetPinInput(uint8_t internal_pin_number){SET_DIR_INPUT(internal_pin_number);} +void u8g_SetPinLevel(uint8_t pin, uint8_t pin_status){WRITE_PIN(pin, pin_status);} +uint8_t u8g_GetPinLevel(uint8_t pin){return READ_PIN(pin);} +void usleep(uint64_t microsec){ +assert(false); // why we here? +} +#ifdef __cplusplus + } +#endif + +#endif // __PLAT_NATIVE_SIM__ diff --git a/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_pin_routines.h b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_pin_routines.h new file mode 100644 index 000000000000..c27c84e8c398 --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_pin_routines.h @@ -0,0 +1,46 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * Low level pin manipulation routines - used by all the drivers. + * + * These are based on the LPC1768 pinMode, digitalRead & digitalWrite routines. + * + * Couldn't just call exact copies because the overhead killed the LCD update speed + * With an intermediate level the softspi was running in the 10-20kHz range which + * resulted in using about about 25% of the CPU's time. + */ + + +#ifdef __cplusplus + extern "C" { +#endif + +void u8g_SetPinOutput(uint8_t internal_pin_number); +void u8g_SetPinInput(uint8_t internal_pin_number); +void u8g_SetPinLevel(uint8_t pin, uint8_t pin_status); +uint8_t u8g_GetPinLevel(uint8_t pin); + +#ifdef __cplusplus + } +#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 new file mode 100644 index 000000000000..c77c3d30f09a --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_st7920_sw_spi.cpp @@ -0,0 +1,171 @@ +/** + * 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 . + * + */ + +/** + * Based on u8g_com_st7920_hw_spi.c + * + * Universal 8bit Graphics Library + * + * Copyright (c) 2011, olikraus@gmail.com + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * * 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. + * + * 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. + */ + +#ifdef __PLAT_NATIVE_SIM__ + +#include "../../../inc/MarlinConfig.h" + +#if ENABLED(U8GLIB_ST7920) + +#include +#include "../../shared/Delay.h" + +#undef SPI_SPEED +#define SPI_SPEED 6 +#define SPI_DELAY_CYCLES (1 + SPI_SPEED * 10) + +static pin_t SCK_pin_ST7920_HAL, MOSI_pin_ST7920_HAL_HAL; +static uint8_t SPI_speed = 0; + +static uint8_t swSpiTransfer(uint8_t b, const uint8_t spi_speed, const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin) { + for (uint8_t i = 0; i < 8; i++) { + WRITE_PIN(mosi_pin, !!(b & 0x80)); + DELAY_CYCLES(SPI_SPEED); + WRITE_PIN(sck_pin, HIGH); + DELAY_CYCLES(SPI_SPEED); + b <<= 1; + if (miso_pin >= 0 && READ_PIN(miso_pin)) b |= 1; + WRITE_PIN(sck_pin, LOW); + DELAY_CYCLES(SPI_SPEED); + } + return b; +} + +static uint8_t swSpiInit(const uint8_t spiRate, const pin_t sck_pin, const pin_t mosi_pin) { + WRITE_PIN(mosi_pin, HIGH); + WRITE_PIN(sck_pin, LOW); + return spiRate; +} + +static void u8g_com_st7920_write_byte_sw_spi(uint8_t rs, uint8_t val) { + static uint8_t rs_last_state = 255; + if (rs != rs_last_state) { + // Transfer Data (FA) or Command (F8) + swSpiTransfer(rs ? 0x0FA : 0x0F8, SPI_speed, SCK_pin_ST7920_HAL, -1, MOSI_pin_ST7920_HAL_HAL); + rs_last_state = rs; + DELAY_US(40); // Give the controller time to process the data: 20 is bad, 30 is OK, 40 is safe + } + 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 + +uint8_t u8g_com_ST7920_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) { + switch (msg) { + case U8G_COM_MSG_INIT: + SCK_pin_ST7920_HAL = u8g->pin_list[U8G_PI_SCK]; + MOSI_pin_ST7920_HAL_HAL = u8g->pin_list[U8G_PI_MOSI]; + + u8g_SetPIOutput(u8g, U8G_PI_CS); + u8g_SetPIOutput(u8g, U8G_PI_SCK); + u8g_SetPIOutput(u8g, U8G_PI_MOSI); + u8g_Delay(5); + + SPI_speed = swSpiInit(SPI_SPEED, SCK_pin_ST7920_HAL, MOSI_pin_ST7920_HAL_HAL); + + u8g_SetPILevel(u8g, U8G_PI_CS, 0); + u8g_SetPILevel(u8g, U8G_PI_SCK, 0); + u8g_SetPILevel(u8g, U8G_PI_MOSI, 0); + + u8g->pin_list[U8G_PI_A0_STATE] = 0; /* initial RS state: command mode */ + break; + + case U8G_COM_MSG_STOP: + break; + + case U8G_COM_MSG_RESET: + 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) */ + u8g->pin_list[U8G_PI_A0_STATE] = arg_val; + break; + + case U8G_COM_MSG_CHIP_SELECT: + if (U8G_PIN_NONE != u8g->pin_list[U8G_PI_CS]) u8g_SetPILevel(u8g, U8G_PI_CS, arg_val); //note: the st7920 has an active high chip select + break; + + case U8G_COM_MSG_WRITE_BYTE: + u8g_com_st7920_write_byte_sw_spi(u8g->pin_list[U8G_PI_A0_STATE], arg_val); + break; + + case U8G_COM_MSG_WRITE_SEQ: { + uint8_t *ptr = (uint8_t*) arg_ptr; + while (arg_val > 0) { + u8g_com_st7920_write_byte_sw_spi(u8g->pin_list[U8G_PI_A0_STATE], *ptr++); + arg_val--; + } + } + break; + + case U8G_COM_MSG_WRITE_SEQ_P: { + uint8_t *ptr = (uint8_t*) arg_ptr; + while (arg_val > 0) { + u8g_com_st7920_write_byte_sw_spi(u8g->pin_list[U8G_PI_A0_STATE], *ptr++); + arg_val--; + } + } + break; + } + return 1; +} +#ifdef __cplusplus + } +#endif + +#endif // U8GLIB_ST7920 +#endif // TARGET_LPC1768 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 new file mode 100644 index 000000000000..085954803cf2 --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp @@ -0,0 +1,215 @@ +/** + * 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 . + * + */ + +/** + * Based on u8g_com_std_sw_spi.c + * + * Universal 8bit Graphics Library + * + * Copyright (c) 2015, olikraus@gmail.com + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * * 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. + * + * 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. + */ + +#ifdef __PLAT_NATIVE_SIM__ + +#include "../../../inc/MarlinConfig.h" + +#if HAS_MARLINUI_U8GLIB && DISABLED(U8GLIB_ST7920) + +#undef SPI_SPEED +#define SPI_SPEED 2 // About 2 MHz + +#include +#include + +#ifdef __cplusplus + extern "C" { +#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) { + if (spi_speed == 0) { + WRITE_PIN(mosi_pin, !!(b & 0x80)); + WRITE_PIN(sck_pin, HIGH); + b <<= 1; + if (miso_pin >= 0 && READ_PIN(miso_pin)) b |= 1; + WRITE_PIN(sck_pin, LOW); + } + else { + const uint8_t state = (b & 0x80) ? HIGH : LOW; + LOOP_L_N(j, spi_speed) + WRITE_PIN(mosi_pin, state); + + LOOP_L_N(j, spi_speed + (miso_pin >= 0 ? 0 : 1)) + WRITE_PIN(sck_pin, HIGH); + + b <<= 1; + if (miso_pin >= 0 && READ_PIN(miso_pin)) b |= 1; + + LOOP_L_N(j, spi_speed) + WRITE_PIN(sck_pin, LOW); + } + } + + return b; +} + +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) { + const uint8_t state = (b & 0x80) ? HIGH : LOW; + if (spi_speed == 0) { + WRITE_PIN(sck_pin, LOW); + WRITE_PIN(mosi_pin, state); + WRITE_PIN(mosi_pin, state); // need some setup time + WRITE_PIN(sck_pin, HIGH); + } + else { + LOOP_L_N(j, spi_speed + (miso_pin >= 0 ? 0 : 1)) + WRITE_PIN(sck_pin, LOW); + + LOOP_L_N(j, spi_speed) + WRITE_PIN(mosi_pin, state); + + LOOP_L_N(j, spi_speed) + WRITE_PIN(sck_pin, HIGH); + } + b <<= 1; + if (miso_pin >= 0 && READ_PIN(miso_pin)) b |= 1; + } + + return b; +} + +static uint8_t SPI_speed = 0; + +static uint8_t swSpiInit(const uint8_t spi_speed, const uint8_t clk_pin, const uint8_t mosi_pin) { + return spi_speed; +} + +static void u8g_sw_spi_shift_out(uint8_t dataPin, uint8_t clockPin, uint8_t val) { + #if EITHER(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); + #endif +} + +uint8_t u8g_com_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) { + switch (msg) { + case U8G_COM_MSG_INIT: + u8g_SetPIOutput(u8g, U8G_PI_SCK); + u8g_SetPIOutput(u8g, U8G_PI_MOSI); + u8g_SetPIOutput(u8g, U8G_PI_CS); + u8g_SetPIOutput(u8g, U8G_PI_A0); + if (U8G_PIN_NONE != u8g->pin_list[U8G_PI_RESET]) u8g_SetPIOutput(u8g, U8G_PI_RESET); + SPI_speed = swSpiInit(SPI_SPEED, u8g->pin_list[U8G_PI_SCK], u8g->pin_list[U8G_PI_MOSI]); + u8g_SetPILevel(u8g, U8G_PI_SCK, 0); + u8g_SetPILevel(u8g, U8G_PI_MOSI, 0); + break; + + case U8G_COM_MSG_STOP: + break; + + case U8G_COM_MSG_RESET: + if (U8G_PIN_NONE != u8g->pin_list[U8G_PI_RESET]) u8g_SetPILevel(u8g, U8G_PI_RESET, 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 + u8g_SetPILevel(u8g, U8G_PI_CS, LOW); + } + else { + u8g_SetPILevel(u8g, U8G_PI_CS, HIGH); + u8g_SetPILevel(u8g, U8G_PI_SCK, 0); // Set SCK to mode 0 idle state after CS goes inactive + } + #else + u8g_SetPILevel(u8g, U8G_PI_CS, !arg_val); + #endif + break; + + case U8G_COM_MSG_WRITE_BYTE: + u8g_sw_spi_shift_out(u8g->pin_list[U8G_PI_MOSI], u8g->pin_list[U8G_PI_SCK], arg_val); + break; + + case U8G_COM_MSG_WRITE_SEQ: { + uint8_t *ptr = (uint8_t *)arg_ptr; + while (arg_val > 0) { + u8g_sw_spi_shift_out(u8g->pin_list[U8G_PI_MOSI], u8g->pin_list[U8G_PI_SCK], *ptr++); + arg_val--; + } + } + break; + + case U8G_COM_MSG_WRITE_SEQ_P: { + uint8_t *ptr = (uint8_t *)arg_ptr; + while (arg_val > 0) { + u8g_sw_spi_shift_out(u8g->pin_list[U8G_PI_MOSI], u8g->pin_list[U8G_PI_SCK], u8g_pgm_read(ptr)); + ptr++; + arg_val--; + } + } + break; + + case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */ + u8g_SetPILevel(u8g, U8G_PI_A0, arg_val); + break; + } + return 1; +} + +#ifdef __cplusplus + } +#endif + +#elif !ANY(TFT_COLOR_UI, TFT_CLASSIC_UI, TFT_LVGL_UI, HAS_MARLINUI_HD44780) && HAS_MARLINUI_U8GLIB + #include + uint8_t u8g_com_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) {return 0;} +#endif // HAS_MARLINUI_U8GLIB && !U8GLIB_ST7920 +#endif // __PLAT_NATIVE_SIM__ diff --git a/Marlin/src/HAL/STM32_F4_F7/watchdog.h b/Marlin/src/HAL/NATIVE_SIM/watchdog.h similarity index 88% rename from Marlin/src/HAL/STM32_F4_F7/watchdog.h rename to Marlin/src/HAL/NATIVE_SIM/watchdog.h index 3dbc2d08c139..4e404c3887da 100644 --- a/Marlin/src/HAL/STM32_F4_F7/watchdog.h +++ b/Marlin/src/HAL/NATIVE_SIM/watchdog.h @@ -1,6 +1,6 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm @@ -21,7 +21,7 @@ */ #pragma once -extern IWDG_HandleTypeDef hiwdg; +#define WDT_TIMEOUT 4000000 // 4 second timeout void watchdog_init(); void HAL_watchdog_refresh(); diff --git a/Marlin/src/HAL/SAMD51/HAL.cpp b/Marlin/src/HAL/SAMD51/HAL.cpp index 9f24d30071a6..8baad31bc751 100644 --- a/Marlin/src/HAL/SAMD51/HAL.cpp +++ b/Marlin/src/HAL/SAMD51/HAL.cpp @@ -24,6 +24,24 @@ #include #include +#ifdef ADAFRUIT_GRAND_CENTRAL_M4 + #if USING_HW_SERIALUSB + DefaultSerial1 MSerial0(false, Serial); + #endif + #if USING_HW_SERIAL0 + DefaultSerial2 MSerial1(false, Serial1); + #endif + #if USING_HW_SERIAL1 + DefaultSerial3 MSerial2(false, Serial2); + #endif + #if USING_HW_SERIAL2 + DefaultSerial4 MSerial3(false, Serial3); + #endif + #if USING_HW_SERIAL3 + DefaultSerial5 MSerial4(false, Serial4); + #endif +#endif + // ------------------------ // Local defines // ------------------------ @@ -39,6 +57,7 @@ #define GET_PROBE_ADC() TERN(HAS_TEMP_PROBE, PIN_TO_ADC(TEMP_PROBE_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_COOLER_ADC() TERN(HAS_TEMP_ADC_COOLER, PIN_TO_ADC(TEMP_COOLER_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) @@ -48,6 +67,7 @@ || GET_PROBE_ADC() == n \ || GET_BED_ADC() == n \ || GET_CHAMBER_ADC() == n \ + || GET_COOLER_ADC() == n \ || GET_FILAMENT_WIDTH_ADC() == n \ || GET_BUTTONS_ADC() == n \ ) @@ -78,7 +98,7 @@ // Struct must be 32 bits aligned because of DMA accesses but fields needs to be 8 bits packed typedef struct __attribute__((aligned(4), packed)) { ADC_INPUTCTRL_Type INPUTCTRL; - } HAL_DMA_DAC_Registers; // DMA transfered registers + } HAL_DMA_DAC_Registers; // DMA transferred registers #endif @@ -126,6 +146,9 @@ uint16_t HAL_adc_result; #if GET_CHAMBER_ADC() == 0 TEMP_CHAMBER_PIN, #endif + #if GET_COOLER_ADC() == 0 + TEMP_COOLER_PIN, + #endif #if GET_FILAMENT_WIDTH_ADC() == 0 FILWIDTH_PIN, #endif @@ -166,6 +189,9 @@ uint16_t HAL_adc_result; #if GET_CHAMBER_ADC() == 1 TEMP_CHAMBER_PIN, #endif + #if GET_COOLER_ADC() == 1 + TEMP_COOLER_PIN, + #endif #if GET_FILAMENT_WIDTH_ADC() == 1 FILWIDTH_PIN, #endif @@ -214,6 +240,9 @@ uint16_t HAL_adc_result; #if GET_CHAMBER_ADC() == 0 { PIN_TO_INPUTCTRL(TEMP_CHAMBER_PIN) }, #endif + #if GET_COOLER_ADC() == 0 + { PIN_TO_INPUTCTRL(TEMP_COOLER_PIN) }, + #endif #if GET_FILAMENT_WIDTH_ADC() == 0 { PIN_TO_INPUTCTRL(FILWIDTH_PIN) }, #endif @@ -263,6 +292,9 @@ uint16_t HAL_adc_result; #if GET_CHAMBER_ADC() == 1 { PIN_TO_INPUTCTRL(TEMP_CHAMBER_PIN) }, #endif + #if GET_COOLER_ADC() == 1 + { PIN_TO_INPUTCTRL(TEMP_COOLER_PIN) }, + #endif #if GET_FILAMENT_WIDTH_ADC() == 1 { PIN_TO_INPUTCTRL(FILWIDTH_PIN) }, #endif @@ -300,7 +332,7 @@ uint16_t HAL_adc_result; DMA_ADDRESS_INCREMENT_STEP_SIZE_1, // STEPSIZE DMA_STEPSEL_SRC // STEPSEL ); - if (descriptor != nullptr) + if (descriptor) descriptor->BTCTRL.bit.EVOSEL = DMA_EVENT_OUTPUT_BEAT; adc0DMAProgram.startJob(); } @@ -337,7 +369,7 @@ uint16_t HAL_adc_result; DMA_ADDRESS_INCREMENT_STEP_SIZE_1, // STEPSIZE DMA_STEPSEL_SRC // STEPSEL ); - if (descriptor != nullptr) + if (descriptor) descriptor->BTCTRL.bit.EVOSEL = DMA_EVENT_OUTPUT_BEAT; adc1DMAProgram.startJob(); } @@ -404,6 +436,8 @@ uint8_t HAL_get_reset_source() { } #pragma pop_macro("WDT") +void HAL_reboot() { NVIC_SystemReset(); } + extern "C" { void * _sbrk(int incr); diff --git a/Marlin/src/HAL/SAMD51/HAL.h b/Marlin/src/HAL/SAMD51/HAL.h index 7cb3635bd7c9..491c3f82c4a6 100644 --- a/Marlin/src/HAL/SAMD51/HAL.h +++ b/Marlin/src/HAL/SAMD51/HAL.h @@ -32,38 +32,56 @@ #include "MarlinSerial_AGCM4.h" // Serial ports - - // MYSERIAL0 required before MarlinSerial includes! - - #define __MSERIAL(X) Serial##X + typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1; + typedef ForwardSerial1Class< decltype(Serial1) > DefaultSerial2; + typedef ForwardSerial1Class< decltype(Serial2) > DefaultSerial3; + typedef ForwardSerial1Class< decltype(Serial3) > DefaultSerial4; + typedef ForwardSerial1Class< decltype(Serial4) > DefaultSerial5; + extern DefaultSerial1 MSerial0; + extern DefaultSerial2 MSerial1; + extern DefaultSerial3 MSerial2; + extern DefaultSerial4 MSerial3; + extern DefaultSerial5 MSerial4; + + #define __MSERIAL(X) MSerial##X #define _MSERIAL(X) __MSERIAL(X) #define MSERIAL(X) _MSERIAL(INCREMENT(X)) #if SERIAL_PORT == -1 - #define MYSERIAL0 Serial + #define MYSERIAL1 MSerial0 #elif WITHIN(SERIAL_PORT, 0, 3) - #define MYSERIAL0 MSERIAL(SERIAL_PORT) + #define MYSERIAL1 MSERIAL(SERIAL_PORT) #else - #error "SERIAL_PORT must be from -1 to 3. Please update your configuration." + #error "SERIAL_PORT must be from 0 to 3. You can also use -1 if the board supports Native USB." #endif #ifdef SERIAL_PORT_2 #if SERIAL_PORT_2 == -1 - #define MYSERIAL1 Serial + #define MYSERIAL2 MSerial0 #elif WITHIN(SERIAL_PORT_2, 0, 3) - #define MYSERIAL1 MSERIAL(SERIAL_PORT_2) + #define MYSERIAL2 MSERIAL(SERIAL_PORT_2) + #else + #error "SERIAL_PORT_2 must be from 0 to 3. You can also use -1 if the board supports Native USB." + #endif + #endif + + #ifdef MMU2_SERIAL_PORT + #if MMU2_SERIAL_PORT == -1 + #define MMU2_SERIAL MSerial0 + #elif WITHIN(MMU2_SERIAL_PORT, 0, 3) + #define MMU2_SERIAL MSERIAL(MMU2_SERIAL_PORT) #else - #error "SERIAL_PORT_2 must be from -1 to 3. Please update your configuration." + #error "MMU2_SERIAL_PORT must be from 0 to 3. You can also use -1 if the board supports Native USB." #endif #endif #ifdef LCD_SERIAL_PORT #if LCD_SERIAL_PORT == -1 - #define LCD_SERIAL Serial + #define LCD_SERIAL MSerial0 #elif WITHIN(LCD_SERIAL_PORT, 0, 3) #define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT) #else - #error "LCD_SERIAL_PORT must be from -1 to 3. Please update your configuration." + #error "LCD_SERIAL_PORT must be from 0 to 3. You can also use -1 if the board supports Native USB." #endif #endif @@ -89,7 +107,7 @@ typedef int8_t pin_t; void HAL_clear_reset_source(); // clear reset reason uint8_t HAL_get_reset_source(); // get reset reason -inline void HAL_reboot() {} // reboot the board or restart the bootloader +void HAL_reboot(); // // ADC @@ -135,10 +153,16 @@ void HAL_idletask(); // FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); } -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-function" +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + int freeMemory(); -#pragma GCC diagnostic pop + +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic pop +#endif #ifdef __cplusplus extern "C" { diff --git a/Marlin/src/HAL/SAMD51/HAL_SPI.cpp b/Marlin/src/HAL/SAMD51/HAL_SPI.cpp index c3acd38237c6..77f4d5ecd513 100644 --- a/Marlin/src/HAL/SAMD51/HAL_SPI.cpp +++ b/Marlin/src/HAL/SAMD51/HAL_SPI.cpp @@ -103,7 +103,7 @@ * @param nbyte Number of bytes to receive. * @return Nothing */ - void spiRead(uint8_t* buf, uint16_t nbyte) { + void spiRead(uint8_t *buf, uint16_t nbyte) { if (nbyte == 0) return; memset(buf, 0xFF, nbyte); sdSPI.beginTransaction(spiConfig); @@ -132,7 +132,7 @@ * * @details Uses DMA */ - void spiSendBlock(uint8_t token, const uint8_t* buf) { + void spiSendBlock(uint8_t token, const uint8_t *buf) { sdSPI.beginTransaction(spiConfig); sdSPI.transfer(token); sdSPI.transfer((uint8_t*)buf, nullptr, 512); diff --git a/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.cpp b/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.cpp index abc5f3acbf77..a16ea2f75821 100644 --- a/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.cpp +++ b/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.cpp @@ -21,30 +21,30 @@ #ifdef ADAFRUIT_GRAND_CENTRAL_M4 /** - * Framework doesn't define some serial to save sercom resources + * Framework doesn't define some serials to save sercom resources * hence if these are used I need to define them */ #include "../../inc/MarlinConfig.h" -#if SERIAL_PORT == 1 || SERIAL_PORT_2 == 1 - Uart Serial2(&sercom4, PIN_SERIAL2_RX, PIN_SERIAL2_TX, PAD_SERIAL2_RX, PAD_SERIAL2_TX); +#if USING_HW_SERIAL1 + UartT Serial2(false, &sercom4, PIN_SERIAL2_RX, PIN_SERIAL2_TX, PAD_SERIAL2_RX, PAD_SERIAL2_TX); void SERCOM4_0_Handler() { Serial2.IrqHandler(); } void SERCOM4_1_Handler() { Serial2.IrqHandler(); } void SERCOM4_2_Handler() { Serial2.IrqHandler(); } void SERCOM4_3_Handler() { Serial2.IrqHandler(); } #endif -#if SERIAL_PORT == 2 || SERIAL_PORT_2 == 2 - Uart Serial3(&sercom1, PIN_SERIAL3_RX, PIN_SERIAL3_TX, PAD_SERIAL3_RX, PAD_SERIAL3_TX); +#if USING_HW_SERIAL2 + UartT Serial3(false, &sercom1, PIN_SERIAL3_RX, PIN_SERIAL3_TX, PAD_SERIAL3_RX, PAD_SERIAL3_TX); void SERCOM1_0_Handler() { Serial3.IrqHandler(); } void SERCOM1_1_Handler() { Serial3.IrqHandler(); } void SERCOM1_2_Handler() { Serial3.IrqHandler(); } void SERCOM1_3_Handler() { Serial3.IrqHandler(); } #endif -#if SERIAL_PORT == 3 || SERIAL_PORT_2 == 3 - Uart Serial4(&sercom5, PIN_SERIAL4_RX, PIN_SERIAL4_TX, PAD_SERIAL4_RX, PAD_SERIAL4_TX); +#if USING_HW_SERIAL3 + UartT Serial4(false, &sercom5, PIN_SERIAL4_RX, PIN_SERIAL4_TX, PAD_SERIAL4_RX, PAD_SERIAL4_TX); void SERCOM5_0_Handler() { Serial4.IrqHandler(); } void SERCOM5_1_Handler() { Serial4.IrqHandler(); } void SERCOM5_2_Handler() { Serial4.IrqHandler(); } diff --git a/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.h b/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.h index f3821d8d5a84..ac5a3793983e 100644 --- a/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.h +++ b/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.h @@ -20,6 +20,10 @@ */ #pragma once -extern Uart Serial2; -extern Uart Serial3; -extern Uart Serial4; +#include "../../core/serial_hook.h" + +typedef Serial1Class UartT; + +extern UartT Serial2; +extern UartT Serial3; +extern UartT Serial4; diff --git a/Marlin/src/HAL/SAMD51/QSPIFlash.cpp b/Marlin/src/HAL/SAMD51/QSPIFlash.cpp index 307eb3fd45f2..fc21a1ad8c80 100644 --- a/Marlin/src/HAL/SAMD51/QSPIFlash.cpp +++ b/Marlin/src/HAL/SAMD51/QSPIFlash.cpp @@ -35,10 +35,10 @@ uint8_t QSPIFlash::_buf[SFLASH_SECTOR_SIZE]; uint32_t QSPIFlash::_addr = INVALID_ADDR; void QSPIFlash::begin() { - if (_flashBase != nullptr) return; + if (_flashBase) return; _flashBase = new Adafruit_SPIFlashBase(new Adafruit_FlashTransport_QSPI()); - _flashBase->begin(NULL); + _flashBase->begin(nullptr); } size_t QSPIFlash::size() { diff --git a/Marlin/src/HAL/SAMD51/eeprom_flash.cpp b/Marlin/src/HAL/SAMD51/eeprom_flash.cpp index 429ef1c2d4f7..871bf22b7fc4 100644 --- a/Marlin/src/HAL/SAMD51/eeprom_flash.cpp +++ b/Marlin/src/HAL/SAMD51/eeprom_flash.cpp @@ -79,7 +79,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui return false; } -bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { +bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { while (size--) { SYNC(NVMCTRL->SEESTAT.bit.BUSY); uint8_t c = ((volatile uint8_t *)SEEPROM_ADDR)[pos]; diff --git a/Marlin/src/HAL/SAMD51/eeprom_qspi.cpp b/Marlin/src/HAL/SAMD51/eeprom_qspi.cpp index b403f7939fb9..faa763719707 100644 --- a/Marlin/src/HAL/SAMD51/eeprom_qspi.cpp +++ b/Marlin/src/HAL/SAMD51/eeprom_qspi.cpp @@ -56,7 +56,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui return false; } -bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { +bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { while (size--) { uint8_t c = qspi.readByte(pos); if (writing) *value = c; diff --git a/Marlin/src/HAL/SAMD51/eeprom_wired.cpp b/Marlin/src/HAL/SAMD51/eeprom_wired.cpp index 3283195897b0..3481fe539c3e 100644 --- a/Marlin/src/HAL/SAMD51/eeprom_wired.cpp +++ b/Marlin/src/HAL/SAMD51/eeprom_wired.cpp @@ -41,12 +41,13 @@ bool PersistentStore::access_start() { eeprom_init(); return true; } bool PersistentStore::access_finish() { return true; } bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + uint16_t written = 0; while (size--) { const uint8_t v = *value; uint8_t * const p = (uint8_t * const)pos; - if (v != eeprom_read_byte(p)) { + if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed! eeprom_write_byte(p, v); - delay(2); + if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes if (eeprom_read_byte(p) != v) { SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); return true; @@ -59,7 +60,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui return false; } -bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { +bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { while (size--) { uint8_t c = eeprom_read_byte((uint8_t*)pos); if (writing) *value = c; diff --git a/Marlin/src/HAL/SAMD51/endstop_interrupts.h b/Marlin/src/HAL/SAMD51/endstop_interrupts.h index daac7733875b..c46b6e072f90 100644 --- a/Marlin/src/HAL/SAMD51/endstop_interrupts.h +++ b/Marlin/src/HAL/SAMD51/endstop_interrupts.h @@ -47,80 +47,38 @@ #include "../../module/endstops.h" -#define MATCH_EILINE(P1,P2) (P1 != P2 && PIN_TO_EILINE(P1) == PIN_TO_EILINE(P2)) -#if HAS_X_MAX - #define MATCH_X_MAX_EILINE(P) MATCH_EILINE(P, X_MAX_PIN) -#else - #define MATCH_X_MAX_EILINE(P) false -#endif -#if HAS_X_MIN - #define MATCH_X_MIN_EILINE(P) MATCH_EILINE(P, X_MIN_PIN) -#else - #define MATCH_X_MIN_EILINE(P) false -#endif -#if HAS_Y_MAX - #define MATCH_Y_MAX_EILINE(P) MATCH_EILINE(P, Y_MAX_PIN) -#else - #define MATCH_Y_MAX_EILINE(P) false -#endif -#if HAS_Y_MIN - #define MATCH_Y_MIN_EILINE(P) MATCH_EILINE(P, Y_MIN_PIN) -#else - #define MATCH_Y_MIN_EILINE(P) false -#endif -#if HAS_Z_MAX - #define MATCH_Z_MAX_EILINE(P) MATCH_EILINE(P, Z_MAX_PIN) -#else - #define MATCH_Z_MAX_EILINE(P) false -#endif -#if HAS_Z_MIN - #define MATCH_Z_MIN_EILINE(P) MATCH_EILINE(P, Z_MIN_PIN) -#else - #define MATCH_Z_MIN_EILINE(P) false -#endif -#if HAS_Z2_MAX - #define MATCH_Z2_MAX_EILINE(P) MATCH_EILINE(P, Z2_MAX_PIN) -#else - #define MATCH_Z2_MAX_EILINE(P) false -#endif -#if HAS_Z2_MIN - #define MATCH_Z2_MIN_EILINE(P) MATCH_EILINE(P, Z2_MIN_PIN) -#else - #define MATCH_Z2_MIN_EILINE(P) false -#endif -#if HAS_Z3_MAX - #define MATCH_Z3_MAX_EILINE(P) MATCH_EILINE(P, Z3_MAX_PIN) -#else - #define MATCH_Z3_MAX_EILINE(P) false -#endif -#if HAS_Z3_MIN - #define MATCH_Z3_MIN_EILINE(P) MATCH_EILINE(P, Z3_MIN_PIN) -#else - #define MATCH_Z3_MIN_EILINE(P) false -#endif -#if HAS_Z4_MAX - #define MATCH_Z4_MAX_EILINE(P) MATCH_EILINE(P, Z4_MAX_PIN) -#else - #define MATCH_Z4_MAX_EILINE(P) false -#endif -#if HAS_Z4_MIN - #define MATCH_Z4_MIN_EILINE(P) MATCH_EILINE(P, Z4_MIN_PIN) -#else - #define MATCH_Z4_MIN_EILINE(P) false -#endif -#if HAS_Z_MIN_PROBE_PIN - #define MATCH_Z_MIN_PROBE_EILINE(P) MATCH_EILINE(P, Z_MIN_PROBE_PIN) -#else - #define MATCH_Z_MIN_PROBE_EILINE(P) false -#endif -#define AVAILABLE_EILINE(P) (PIN_TO_EILINE(P) != -1 \ - && !MATCH_X_MAX_EILINE(P) && !MATCH_X_MIN_EILINE(P) \ - && !MATCH_Y_MAX_EILINE(P) && !MATCH_Y_MIN_EILINE(P) \ - && !MATCH_Z_MAX_EILINE(P) && !MATCH_Z_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) \ - && !MATCH_Z_MIN_PROBE_EILINE(P)) +#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_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 AVAILABLE_EILINE(P) ( PIN_TO_EILINE(P) != -1 \ + && !MATCH_X_MAX_EILINE(P) && !MATCH_X_MIN_EILINE(P) \ + && !MATCH_Y_MAX_EILINE(P) && !MATCH_Y_MIN_EILINE(P) \ + && !MATCH_Z_MAX_EILINE(P) && !MATCH_Z_MIN_EILINE(P) \ + && !MATCH_I_MAX_EILINE(P) && !MATCH_I_MIN_EILINE(P) \ + && !MATCH_J_MAX_EILINE(P) && !MATCH_J_MIN_EILINE(P) \ + && !MATCH_K_MAX_EILINE(P) && !MATCH_K_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) \ + && !MATCH_Z_MIN_PROBE_EILINE(P) ) // One ISR for all EXT-Interrupts void endstop_ISR() { endstops.update(); } @@ -204,5 +162,37 @@ void setup_endstop_interrupts() { #error "Z_MIN_PROBE_PIN has no EXTINT line available." #endif _ATTACH(Z_MIN_PROBE_PIN); + #elif HAS_I_MAX + #if !AVAILABLE_EILINE(I_MAX_PIN) + #error "I_MAX_PIN has no EXTINT line available." + #endif + attachInterrupt(I_MAX_PIN, endstop_ISR, CHANGE); + #elif HAS_I_MIN + #if !AVAILABLE_EILINE(I_MIN_PIN) + #error "I_MIN_PIN has no EXTINT line available." + #endif + attachInterrupt(I_MIN_PIN, endstop_ISR, CHANGE); + #endif + #if HAS_J_MAX + #if !AVAILABLE_EILINE(J_MAX_PIN) + #error "J_MAX_PIN has no EXTINT line available." + #endif + attachInterrupt(J_MAX_PIN, endstop_ISR, CHANGE); + #elif HAS_J_MIN + #if !AVAILABLE_EILINE(J_MIN_PIN) + #error "J_MIN_PIN has no EXTINT line available." + #endif + attachInterrupt(J_MIN_PIN, endstop_ISR, CHANGE); + #endif + #if HAS_K_MAX + #if !AVAILABLE_EILINE(K_MAX_PIN) + #error "K_MAX_PIN has no EXTINT line available." + #endif + attachInterrupt(K_MAX_PIN, endstop_ISR, CHANGE); + #elif HAS_K_MIN + #if !AVAILABLE_EILINE(K_MIN_PIN) + #error "K_MIN_PIN has no EXTINT line available." + #endif + attachInterrupt(K_MIN_PIN, endstop_ISR, CHANGE); #endif } diff --git a/Marlin/src/HAL/SAMD51/fastio.h b/Marlin/src/HAL/SAMD51/fastio.h index c456dfce30cb..79aede579044 100644 --- a/Marlin/src/HAL/SAMD51/fastio.h +++ b/Marlin/src/HAL/SAMD51/fastio.h @@ -31,7 +31,7 @@ */ #ifndef MASK - #define MASK(PIN) (1 << PIN) + #define MASK(PIN) _BV(PIN) #endif /** @@ -131,7 +131,7 @@ */ #define PWM_PIN(P) (WITHIN(P, 2, 13) || WITHIN(P, 22, 23) || WITHIN(P, 44, 45) || P == 48) - // Return fullfilled ADCx->INPUTCTRL.reg + // Return fulfilled ADCx->INPUTCTRL.reg #define PIN_TO_INPUTCTRL(P) ( (PIN_TO_AIN(P) == 0) ? ADC_INPUTCTRL_MUXPOS_AIN0 \ : (PIN_TO_AIN(P) == 1) ? ADC_INPUTCTRL_MUXPOS_AIN1 \ : (PIN_TO_AIN(P) == 2) ? ADC_INPUTCTRL_MUXPOS_AIN2 \ diff --git a/Marlin/src/HAL/SAMD51/inc/SanityCheck.h b/Marlin/src/HAL/SAMD51/inc/SanityCheck.h index 5d610acac85c..38c6dd9e08de 100644 --- a/Marlin/src/HAL/SAMD51/inc/SanityCheck.h +++ b/Marlin/src/HAL/SAMD51/inc/SanityCheck.h @@ -31,7 +31,8 @@ #error "No custom SD drive cable defined for this board." #endif -#if defined(MAX6675_SCK_PIN) && defined(MAX6675_DO_PIN) && (MAX6675_SCK_PIN == SCK1 || MAX6675_DO_PIN == MISO1) +#if (defined(TEMP_0_SCK_PIN) && defined(TEMP_0_MISO_PIN) && (TEMP_0_SCK_PIN == SCK1 || TEMP_0_MISO_PIN == MISO1)) || \ + (defined(TEMP_1_SCK_PIN) && defined(TEMP_1_MISO_PIN) && (TEMP_1_SCK_PIN == SCK1 || TEMP_1_MISO_PIN == MISO1)) #error "OnBoard SPI BUS can't be shared with other devices." #endif @@ -50,3 +51,7 @@ #if ENABLED(FAST_PWM_FAN) || SPINDLE_LASER_FREQUENCY #error "Features requiring Hardware PWM (FAST_PWM_FAN, SPINDLE_LASER_FREQUENCY) are not yet supported on SAMD51." #endif + +#if ENABLED(POSTMORTEM_DEBUGGING) + #error "POSTMORTEM_DEBUGGING is not yet supported on AGCM4." +#endif diff --git a/Marlin/src/HAL/SAMD51/spi_pins.h b/Marlin/src/HAL/SAMD51/spi_pins.h index 5a9b1275ef88..2a667bcaa1ce 100644 --- a/Marlin/src/HAL/SAMD51/spi_pins.h +++ b/Marlin/src/HAL/SAMD51/spi_pins.h @@ -30,16 +30,16 @@ * SPI | 53 52 50 51 | * SPI1 | 83 81 80 82 | * +-------------------------+ - * Any pin can be used for Chip Select (SS_PIN) + * Any pin can be used for Chip Select (SD_SS_PIN) */ - #ifndef SCK_PIN - #define SCK_PIN 52 + #ifndef SD_SCK_PIN + #define SD_SCK_PIN 52 #endif - #ifndef MISO_PIN - #define MISO_PIN 50 + #ifndef SD_MISO_PIN + #define SD_MISO_PIN 50 #endif - #ifndef MOSI_PIN - #define MOSI_PIN 51 + #ifndef SD_MOSI_PIN + #define SD_MOSI_PIN 51 #endif #ifndef SDSS #define SDSS 53 @@ -51,4 +51,4 @@ #endif -#define SS_PIN SDSS +#define SD_SS_PIN SDSS diff --git a/Marlin/src/HAL/SAMD51/timers.cpp b/Marlin/src/HAL/SAMD51/timers.cpp index a68af2e074ae..7a535299db9a 100644 --- a/Marlin/src/HAL/SAMD51/timers.cpp +++ b/Marlin/src/HAL/SAMD51/timers.cpp @@ -107,7 +107,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { tc->COUNT32.INTENCLR.reg = TC_INTENCLR_OVF; // disable overflow interrupt // TCn clock setup - const uint8_t clockID = GCLK_CLKCTRL_IDs[TCC_INST_NUM + timer_num]; // TC clock are preceeded by TCC ones + const uint8_t clockID = GCLK_CLKCTRL_IDs[TCC_INST_NUM + timer_num]; // TC clock are preceded by TCC ones GCLK->PCHCTRL[clockID].bit.CHEN = false; SYNC(GCLK->PCHCTRL[clockID].bit.CHEN); GCLK->PCHCTRL[clockID].reg = GCLK_PCHCTRL_GEN_GCLK0 | GCLK_PCHCTRL_CHEN; // 120MHz startup code programmed @@ -157,7 +157,7 @@ void HAL_timer_disable_interrupt(const uint8_t timer_num) { // missing from CMSIS: Check if interrupt is enabled or not static bool NVIC_GetEnabledIRQ(IRQn_Type IRQn) { - return (NVIC->ISER[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F))) != 0; + return TEST(NVIC->ISER[uint32_t(IRQn) >> 5], uint32_t(IRQn) & 0x1F); } bool HAL_timer_interrupt_enabled(const uint8_t timer_num) { diff --git a/Marlin/src/HAL/SAMD51/watchdog.cpp b/Marlin/src/HAL/SAMD51/watchdog.cpp index ebc8dffe1300..9de451836aeb 100644 --- a/Marlin/src/HAL/SAMD51/watchdog.cpp +++ b/Marlin/src/HAL/SAMD51/watchdog.cpp @@ -24,28 +24,30 @@ #if ENABLED(USE_WATCHDOG) - #include "watchdog.h" +#include "watchdog.h" - void watchdog_init() { - // The low-power oscillator used by the WDT runs at 32,768 Hz with - // a 1:32 prescale, thus 1024 Hz, though probably not super precise. +#define WDT_TIMEOUT_REG TERN(WATCHDOG_DURATION_8S, WDT_CONFIG_PER_CYC8192, WDT_CONFIG_PER_CYC4096) // 4 or 8 second timeout - // Setup WDT clocks - MCLK->APBAMASK.bit.OSC32KCTRL_ = true; - MCLK->APBAMASK.bit.WDT_ = true; - OSC32KCTRL->OSCULP32K.bit.EN1K = true; // Enable out 1K (this is what WDT uses) +void watchdog_init() { + // The low-power oscillator used by the WDT runs at 32,768 Hz with + // a 1:32 prescale, thus 1024 Hz, though probably not super precise. - WDT->CTRLA.bit.ENABLE = false; // Disable watchdog for config - SYNC(WDT->SYNCBUSY.bit.ENABLE); + // Setup WDT clocks + MCLK->APBAMASK.bit.OSC32KCTRL_ = true; + MCLK->APBAMASK.bit.WDT_ = true; + OSC32KCTRL->OSCULP32K.bit.EN1K = true; // Enable out 1K (this is what WDT uses) - WDT->INTENCLR.reg = WDT_INTENCLR_EW; // Disable early warning interrupt - WDT->CONFIG.reg = WDT_CONFIG_PER_CYC4096; // Set at least 4s period for chip reset + WDT->CTRLA.bit.ENABLE = false; // Disable watchdog for config + SYNC(WDT->SYNCBUSY.bit.ENABLE); - HAL_watchdog_refresh(); + WDT->INTENCLR.reg = WDT_INTENCLR_EW; // Disable early warning interrupt + WDT->CONFIG.reg = WDT_TIMEOUT_REG; // Set a 4s or 8s period for chip reset - WDT->CTRLA.reg = WDT_CTRLA_ENABLE; // Start watchdog now in normal mode - SYNC(WDT->SYNCBUSY.bit.ENABLE); - } + HAL_watchdog_refresh(); + + WDT->CTRLA.reg = WDT_CTRLA_ENABLE; // Start watchdog now in normal mode + SYNC(WDT->SYNCBUSY.bit.ENABLE); +} #endif // USE_WATCHDOG diff --git a/Marlin/src/HAL/STM32/HAL.cpp b/Marlin/src/HAL/STM32/HAL.cpp index 83604b1104bb..a04a24c1123c 100644 --- a/Marlin/src/HAL/STM32/HAL.cpp +++ b/Marlin/src/HAL/STM32/HAL.cpp @@ -20,7 +20,9 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) +#include "../platforms.h" + +#ifdef HAL_STM32 #include "HAL.h" #include "usb_serial.h" @@ -28,6 +30,10 @@ #include "../../inc/MarlinConfig.h" #include "../shared/Delay.h" +#ifdef USBCON + DefaultSerial1 MSerial0(false, SerialUSB); +#endif + #if ENABLED(SRAM_EEPROM_EMULATION) #if STM32F7xx #include @@ -38,6 +44,11 @@ #endif #endif +#if HAS_SD_HOST_DRIVE + #include "msc_sd.h" + #include "usbd_cdc_if.h" +#endif + // ------------------------ // Public Variables // ------------------------ @@ -48,20 +59,15 @@ uint16_t HAL_adc_result; // Public functions // ------------------------ -// Needed for DELAY_NS() / DELAY_US() on CORTEX-M7 -#if (defined(__arm__) || defined(__thumb__)) && __CORTEX_M == 7 - // HAL pre-initialization task - // Force the preinit function to run between the premain() and main() function - // of the STM32 arduino core - __attribute__((constructor (102))) - void HAL_preinit() { - enableCycleCounter(); - } -#endif +TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); // HAL initialization task void HAL_init() { - FastIO_init(); + // Ensure F_CPU is a constant expression. + // If the compiler breaks here, it means that delay code that should compute at compile time will not work. + // So better safe than sorry here. + constexpr int cpuFreq = F_CPU; + UNUSED(cpuFreq); #if ENABLED(SDSUPPORT) && DISABLED(SDIO_SUPPORT) && (defined(SDSS) && SDSS != -1) OUT_WRITE(SDSS, HIGH); // Try to set SDSS inactive before any other SPI users start up @@ -81,7 +87,28 @@ void HAL_init() { SetTimerInterruptPriorities(); - TERN_(EMERGENCY_PARSER, USB_Hook_init()); + #if ENABLED(EMERGENCY_PARSER) && USBD_USE_CDC + USB_Hook_init(); + #endif + + TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the min serial handler + + TERN_(HAS_SD_HOST_DRIVE, MSC_SD_init()); // Enable USB SD card access + + #if PIN_EXISTS(USB_CONNECT) + OUT_WRITE(USB_CONNECT_PIN, !USB_CONNECT_INVERTING); // USB clear connection + delay(1000); // Give OS time to notice + WRITE(USB_CONNECT_PIN, USB_CONNECT_INVERTING); + #endif +} + +// HAL idle task +void HAL_idletask() { + #if HAS_SHARED_MEDIA + // Stm32duino currently doesn't have a "loop/idle" method + CDC_resume_receive(); + CDC_continue_transmit(); + #endif } void HAL_clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); } @@ -110,6 +137,8 @@ uint8_t HAL_get_reset_source() { ; } +void HAL_reboot() { NVIC_SystemReset(); } + void _delay_ms(const int delay_ms) { delay(delay_ms); } extern "C" { @@ -124,12 +153,16 @@ extern "C" { void HAL_adc_start_conversion(const uint8_t adc_pin) { HAL_adc_result = analogRead(adc_pin); } uint16_t HAL_adc_get_result() { return HAL_adc_result; } -// Reset the system (to initiate a firmware flash) -void flashFirmware(const int16_t) { NVIC_SystemReset(); } +// Reset the system to initiate a firmware flash +void flashFirmware(const int16_t) { HAL_reboot(); } // Maple Compatibility +volatile uint32_t systick_uptime_millis = 0; systickCallback_t systick_user_callback; void systick_attach_callback(systickCallback_t cb) { systick_user_callback = cb; } -void HAL_SYSTICK_Callback() { if (systick_user_callback) systick_user_callback(); } +void HAL_SYSTICK_Callback() { + systick_uptime_millis++; + if (systick_user_callback) systick_user_callback(); +} -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h index a1f7515d6b98..02bee57ba3ac 100644 --- a/Marlin/src/HAL/STM32/HAL.h +++ b/Marlin/src/HAL/STM32/HAL.h @@ -29,6 +29,7 @@ #include "../shared/math_32bit.h" #include "../shared/HAL_SPI.h" #include "fastio.h" +#include "Servo.h" #include "watchdog.h" #include "MarlinSerial.h" @@ -36,41 +37,64 @@ #include +// +// Serial Ports +// #ifdef USBCON #include + #include "../../core/serial_hook.h" + typedef ForwardSerial1Class< decltype(SerialUSB) > DefaultSerial1; + extern DefaultSerial1 MSerial0; #endif -// ------------------------ -// Defines -// ------------------------ #define _MSERIAL(X) MSerial##X #define MSERIAL(X) _MSERIAL(X) #if SERIAL_PORT == -1 - #define MYSERIAL0 SerialUSB + #define MYSERIAL1 MSerial0 #elif WITHIN(SERIAL_PORT, 1, 6) - #define MYSERIAL0 MSERIAL(SERIAL_PORT) + #define MYSERIAL1 MSERIAL(SERIAL_PORT) #else - #error "SERIAL_PORT must be -1 or from 1 to 6. Please update your configuration." + #error "SERIAL_PORT must be from 1 to 6. You can also use -1 if the board supports Native USB." #endif #ifdef SERIAL_PORT_2 #if SERIAL_PORT_2 == -1 - #define MYSERIAL1 SerialUSB + #define MYSERIAL2 MSerial0 #elif WITHIN(SERIAL_PORT_2, 1, 6) - #define MYSERIAL1 MSERIAL(SERIAL_PORT_2) + #define MYSERIAL2 MSERIAL(SERIAL_PORT_2) #else - #error "SERIAL_PORT_2 must be -1 or from 1 to 6. Please update your configuration." + #error "SERIAL_PORT_2 must be from 1 to 6. You can also use -1 if the board supports Native USB." + #endif +#endif + +#ifdef SERIAL_PORT_3 + #if SERIAL_PORT_3 == -1 + #define MYSERIAL3 MSerial0 + #elif WITHIN(SERIAL_PORT_3, 1, 6) + #define MYSERIAL3 MSERIAL(SERIAL_PORT_3) + #else + #error "SERIAL_PORT_3 must be from 1 to 6. You can also use -1 if the board supports Native USB." + #endif +#endif + +#ifdef MMU2_SERIAL_PORT + #if MMU2_SERIAL_PORT == -1 + #define MMU2_SERIAL MSerial0 + #elif WITHIN(MMU2_SERIAL_PORT, 1, 6) + #define MMU2_SERIAL MSERIAL(MMU2_SERIAL_PORT) + #else + #error "MMU2_SERIAL_PORT must be from 1 to 6. You can also use -1 if the board supports Native USB." #endif #endif #ifdef LCD_SERIAL_PORT #if LCD_SERIAL_PORT == -1 - #define LCD_SERIAL SerialUSB + #define LCD_SERIAL MSerial0 #elif WITHIN(LCD_SERIAL_PORT, 1, 6) #define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT) #else - #error "LCD_SERIAL_PORT must be -1 or from 1 to 6. Please update your configuration." + #error "LCD_SERIAL_PORT must be from 1 to 6. 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() @@ -95,14 +119,6 @@ // On AVR this is in math.h? #define square(x) ((x)*(x)) -#ifndef strncpy_P - #define strncpy_P(dest, src, num) strncpy((dest), (src), (num)) -#endif - -// Fix bug in pgm_read_ptr -#undef pgm_read_ptr -#define pgm_read_ptr(addr) (*(addr)) - // ------------------------ // Types // ------------------------ @@ -110,6 +126,8 @@ typedef int16_t pin_t; #define HAL_SERVO_LIB libServo +#define PAUSE_SERVO_OUTPUT() libServo::pause_all_servos() +#define RESUME_SERVO_OUTPUT() libServo::resume_all_servos() // ------------------------ // Public Variables @@ -127,6 +145,8 @@ extern uint16_t HAL_adc_result; // Enable hooks into setup for HAL void HAL_init(); +#define HAL_IDLETASK 1 +void HAL_idletask(); // Clear reset reason void HAL_clear_reset_source(); @@ -134,7 +154,7 @@ void HAL_clear_reset_source(); // Reset reason uint8_t HAL_get_reset_source(); -inline void HAL_reboot() {} // reboot the board or restart the bootloader +void HAL_reboot(); void _delay_ms(const int delay); @@ -156,14 +176,14 @@ static inline int freeMemory() { #define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT) -inline void HAL_adc_init() {} - #define HAL_ADC_VREF 3.3 -#define HAL_ADC_RESOLUTION 10 +#define HAL_ADC_RESOLUTION ADC_RESOLUTION // 12 #define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) #define HAL_READ_ADC() HAL_adc_result #define HAL_ADC_READY() true +inline void HAL_adc_init() { analogReadResolution(HAL_ADC_RESOLUTION); } + void HAL_adc_start_conversion(const uint8_t adc_pin); uint16_t HAL_adc_get_result(); @@ -175,6 +195,7 @@ uint16_t HAL_adc_get_result(); #ifdef STM32F1xx #define JTAG_DISABLE() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_JTAGDISABLE) #define JTAGSWD_DISABLE() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_DISABLE) + #define JTAGSWD_RESET() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_RESET); // Reset: FULL SWD+JTAG #endif #define PLATFORM_M997_SUPPORT @@ -184,3 +205,22 @@ void flashFirmware(const int16_t); typedef void (*systickCallback_t)(void); void systick_attach_callback(systickCallback_t cb); void HAL_SYSTICK_Callback(); + +extern volatile uint32_t systick_uptime_millis; + +#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment + +/** + * set_pwm_frequency + * Set the frequency of the timer corresponding to the provided pin + * All Timer PWM pins run at the same frequency + */ +void set_pwm_frequency(const pin_t pin, int f_desired); + +/** + * set_pwm_duty + * Set the PWM duty cycle of the provided pin to the provided value + * Optionally allows inverting the duty cycle [default = false] + * Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255] + */ +void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); diff --git a/Marlin/src/HAL/STM32/HAL_MinSerial.cpp b/Marlin/src/HAL/STM32/HAL_MinSerial.cpp new file mode 100644 index 000000000000..29826a890de4 --- /dev/null +++ b/Marlin/src/HAL/STM32/HAL_MinSerial.cpp @@ -0,0 +1,154 @@ +/** + * 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 + * 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 + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../platforms.h" + +#ifdef HAL_STM32 + +#include "../../inc/MarlinConfigPre.h" + +#if ENABLED(POSTMORTEM_DEBUGGING) + +#include "../shared/HAL_MinSerial.h" +#include "watchdog.h" + +/* Instruction Synchronization Barrier */ +#define isb() __asm__ __volatile__ ("isb" : : : "memory") + +/* Data Synchronization Barrier */ +#define dsb() __asm__ __volatile__ ("dsb" : : : "memory") + +// Dumb mapping over the registers of a USART device on STM32 +struct USARTMin { + volatile uint32_t SR; + volatile uint32_t DR; + volatile uint32_t BRR; + volatile uint32_t CR1; + volatile uint32_t CR2; +}; + +#if WITHIN(SERIAL_PORT, 1, 6) + // Depending on the CPU, the serial port is different for USART1 + static const uintptr_t regsAddr[] = { + TERN(STM32F1xx, 0x40013800, 0x40011000), // USART1 + 0x40004400, // USART2 + 0x40004800, // USART3 + 0x40004C00, // UART4_BASE + 0x40005000, // UART5_BASE + 0x40011400 // USART6 + }; + static USARTMin * regs = (USARTMin*)regsAddr[SERIAL_PORT - 1]; +#endif + +static void TXBegin() { + #if !WITHIN(SERIAL_PORT, 1, 6) + #warning "Using POSTMORTEM_DEBUGGING requires a physical U(S)ART hardware in case of severe error." + #warning "Disabling the severe error reporting feature currently because the used serial port is not a HW port." + #else + // This is common between STM32F1/STM32F2 and STM32F4 + const int nvicUART[] = { /* NVIC_USART1 */ 37, /* NVIC_USART2 */ 38, /* NVIC_USART3 */ 39, /* NVIC_UART4 */ 52, /* NVIC_UART5 */ 53, /* NVIC_USART6 */ 71 }; + int nvicIndex = nvicUART[SERIAL_PORT - 1]; + + struct NVICMin { + volatile uint32_t ISER[32]; + volatile uint32_t ICER[32]; + }; + + NVICMin *nvicBase = (NVICMin*)0xE000E100; + SBI32(nvicBase->ICER[nvicIndex >> 5], nvicIndex & 0x1F); + + // We NEED memory barriers to ensure Interrupts are actually disabled! + // ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the ) + dsb(); + isb(); + + // Example for USART1 disable: (RCC->APB2ENR &= ~(RCC_APB2ENR_USART1EN)) + // Too difficult to reimplement here, let's query the STM32duino macro here + #if SERIAL_PORT == 1 + __HAL_RCC_USART1_CLK_DISABLE(); + __HAL_RCC_USART1_CLK_ENABLE(); + #elif SERIAL_PORT == 2 + __HAL_RCC_USART2_CLK_DISABLE(); + __HAL_RCC_USART2_CLK_ENABLE(); + #elif SERIAL_PORT == 3 + __HAL_RCC_USART3_CLK_DISABLE(); + __HAL_RCC_USART3_CLK_ENABLE(); + #elif SERIAL_PORT == 4 + __HAL_RCC_UART4_CLK_DISABLE(); // BEWARE: UART4 and not USART4 here + __HAL_RCC_UART4_CLK_ENABLE(); + #elif SERIAL_PORT == 5 + __HAL_RCC_UART5_CLK_DISABLE(); // BEWARE: UART5 and not USART5 here + __HAL_RCC_UART5_CLK_ENABLE(); + #elif SERIAL_PORT == 6 + __HAL_RCC_USART6_CLK_DISABLE(); + __HAL_RCC_USART6_CLK_ENABLE(); + #endif + + uint32_t brr = regs->BRR; + regs->CR1 = 0; // Reset the USART + regs->CR2 = 0; // 1 stop bit + + // If we don't touch the BRR (baudrate register), we don't need to recompute. + regs->BRR = brr; + + regs->CR1 = _BV(3) | _BV(13); // 8 bits, no parity, 1 stop bit (TE | UE) + #endif +} + +// 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) + constexpr uint32_t usart_sr_txe = _BV(7); + while (!(regs->SR & usart_sr_txe)) { + TERN_(USE_WATCHDOG, HAL_watchdog_refresh()); + sw_barrier(); + } + regs->DR = c; + #else + // Let's hope a mystical guru will fix this, one day by writing interrupt-free USB CDC ACM code (or, at least, by polling the registers since interrupt will be queued but will never trigger) + // For now, it's completely lost to oblivion. + #endif +} + +void install_min_serial() { + HAL_min_serial_init = &TXBegin; + HAL_min_serial_out = &TX; +} + +#if DISABLED(DYNAMIC_VECTORTABLE) && DISABLED(STM32F0xx) // Cortex M0 can't jump to a symbol that's too far from the current function, so we work around this in exception_arm.cpp +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(); +} +#endif + +#endif // POSTMORTEM_DEBUGGING +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/HAL_SPI.cpp b/Marlin/src/HAL/STM32/HAL_SPI.cpp index f947e6ef3272..85a5238b54af 100644 --- a/Marlin/src/HAL/STM32/HAL_SPI.cpp +++ b/Marlin/src/HAL/STM32/HAL_SPI.cpp @@ -20,7 +20,9 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) +#include "../platforms.h" + +#ifdef HAL_STM32 #include "../../inc/MarlinConfig.h" @@ -45,24 +47,34 @@ static SPISettings spiConfig; #include "../shared/Delay.h" void spiBegin(void) { - OUT_WRITE(SS_PIN, HIGH); - OUT_WRITE(SCK_PIN, HIGH); - SET_INPUT(MISO_PIN); - OUT_WRITE(MOSI_PIN, HIGH); + OUT_WRITE(SD_SS_PIN, HIGH); + OUT_WRITE(SD_SCK_PIN, HIGH); + SET_INPUT(SD_MISO_PIN); + OUT_WRITE(SD_MOSI_PIN, HIGH); } - static uint16_t delay_STM32_soft_spi; + // Use function with compile-time value so we can actually reach the desired frequency + // Need to adjust this a little bit: on a 72MHz clock, we have 14ns/clock + // and we'll use ~3 cycles to jump to the method and going back, so it'll take ~40ns from the given clock here + #define CALLING_COST_NS (3U * 1000000000U) / (F_CPU) + void (*delaySPIFunc)(); + void delaySPI_125() { DELAY_NS(125 - CALLING_COST_NS); } + void delaySPI_250() { DELAY_NS(250 - CALLING_COST_NS); } + void delaySPI_500() { DELAY_NS(500 - CALLING_COST_NS); } + void delaySPI_1000() { DELAY_NS(1000 - CALLING_COST_NS); } + void delaySPI_2000() { DELAY_NS(2000 - CALLING_COST_NS); } + void delaySPI_4000() { DELAY_NS(4000 - CALLING_COST_NS); } void spiInit(uint8_t spiRate) { // Use datarates Marlin uses switch (spiRate) { - case SPI_FULL_SPEED: delay_STM32_soft_spi = 125; break; // desired: 8,000,000 actual: ~1.1M - case SPI_HALF_SPEED: delay_STM32_soft_spi = 125; break; // desired: 4,000,000 actual: ~1.1M - case SPI_QUARTER_SPEED:delay_STM32_soft_spi = 250; break; // desired: 2,000,000 actual: ~890K - case SPI_EIGHTH_SPEED: delay_STM32_soft_spi = 500; break; // desired: 1,000,000 actual: ~590K - case SPI_SPEED_5: delay_STM32_soft_spi = 1000; break; // desired: 500,000 actual: ~360K - case SPI_SPEED_6: delay_STM32_soft_spi = 2000; break; // desired: 250,000 actual: ~210K - default: delay_STM32_soft_spi = 4000; break; // desired: 125,000 actual: ~123K + case SPI_FULL_SPEED: delaySPIFunc = &delaySPI_125; break; // desired: 8,000,000 actual: ~1.1M + case SPI_HALF_SPEED: delaySPIFunc = &delaySPI_125; break; // desired: 4,000,000 actual: ~1.1M + case SPI_QUARTER_SPEED:delaySPIFunc = &delaySPI_250; break; // desired: 2,000,000 actual: ~890K + case SPI_EIGHTH_SPEED: delaySPIFunc = &delaySPI_500; break; // desired: 1,000,000 actual: ~590K + case SPI_SPEED_5: delaySPIFunc = &delaySPI_1000; break; // desired: 500,000 actual: ~360K + case SPI_SPEED_6: delaySPIFunc = &delaySPI_2000; break; // desired: 250,000 actual: ~210K + default: delaySPIFunc = &delaySPI_4000; break; // desired: 125,000 actual: ~123K } SPI.begin(); } @@ -72,15 +84,15 @@ static SPISettings spiConfig; uint8_t HAL_SPI_STM32_SpiTransfer_Mode_3(uint8_t b) { // using Mode 3 for (uint8_t bits = 8; bits--;) { - WRITE(SCK_PIN, LOW); - WRITE(MOSI_PIN, b & 0x80); + WRITE(SD_SCK_PIN, LOW); + WRITE(SD_MOSI_PIN, b & 0x80); - DELAY_NS(delay_STM32_soft_spi); - WRITE(SCK_PIN, HIGH); - DELAY_NS(delay_STM32_soft_spi); + delaySPIFunc(); + WRITE(SD_SCK_PIN, HIGH); + delaySPIFunc(); b <<= 1; // little setup time - b |= (READ(MISO_PIN) != 0); + b |= (READ(SD_MISO_PIN) != 0); } DELAY_NS(125); return b; @@ -132,8 +144,8 @@ static SPISettings spiConfig; * @details Only configures SS pin since stm32duino creates and initialize the SPI object */ void spiBegin() { - #if PIN_EXISTS(SS) - OUT_WRITE(SS_PIN, HIGH); + #if PIN_EXISTS(SD_SS) + OUT_WRITE(SD_SS_PIN, HIGH); #endif } @@ -153,12 +165,9 @@ static SPISettings spiConfig; } spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0); - #if ENABLED(CUSTOM_SPI_PINS) - SPI.setMISO(MISO_PIN); - SPI.setMOSI(MOSI_PIN); - SPI.setSCLK(SCK_PIN); - SPI.setSSEL(SS_PIN); - #endif + SPI.setMISO(SD_MISO_PIN); + SPI.setMOSI(SD_MOSI_PIN); + SPI.setSCLK(SD_SCK_PIN); SPI.begin(); } @@ -184,7 +193,7 @@ static SPISettings spiConfig; * * @details Uses DMA */ - void spiRead(uint8_t* buf, uint16_t nbyte) { + void spiRead(uint8_t *buf, uint16_t nbyte) { if (nbyte == 0) return; memset(buf, 0xFF, nbyte); SPI.transfer(buf, nbyte); @@ -209,7 +218,7 @@ static SPISettings spiConfig; * * @details Use DMA */ - void spiSendBlock(uint8_t token, const uint8_t* buf) { + void spiSendBlock(uint8_t token, const uint8_t *buf) { uint8_t rxBuf[512]; SPI.transfer(token); SPI.transfer((uint8_t*)buf, &rxBuf, 512); @@ -217,4 +226,4 @@ static SPISettings spiConfig; #endif // SOFTWARE_SPI -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/MarlinSPI.cpp b/Marlin/src/HAL/STM32/MarlinSPI.cpp new file mode 100644 index 000000000000..e1be50820f65 --- /dev/null +++ b/Marlin/src/HAL/STM32/MarlinSPI.cpp @@ -0,0 +1,170 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../platforms.h" + +#if defined(HAL_STM32) && !defined(STM32H7xx) + +#include "MarlinSPI.h" + +static void spi_init(spi_t *obj, uint32_t speed, spi_mode_e mode, uint8_t msb, uint32_t dataSize) { + spi_init(obj, speed, mode, msb); + // spi_init set 8bit always + // TODO: copy the code from spi_init and handle data size, to avoid double init always!! + if (dataSize != SPI_DATASIZE_8BIT) { + obj->handle.Init.DataSize = dataSize; + HAL_SPI_Init(&obj->handle); + __HAL_SPI_ENABLE(&obj->handle); + } +} + +void MarlinSPI::setClockDivider(uint8_t _div) { + _speed = spi_getClkFreq(&_spi);// / _div; + _clockDivider = _div; +} + +void MarlinSPI::begin(void) { + //TODO: only call spi_init if any parameter changed!! + spi_init(&_spi, _speed, _dataMode, _bitOrder, _dataSize); +} + +void MarlinSPI::setupDma(SPI_HandleTypeDef &_spiHandle, DMA_HandleTypeDef &_dmaHandle, uint32_t direction, bool minc) { + _dmaHandle.Init.Direction = direction; + _dmaHandle.Init.PeriphInc = DMA_PINC_DISABLE; + _dmaHandle.Init.Mode = DMA_NORMAL; + _dmaHandle.Init.Priority = DMA_PRIORITY_LOW; + _dmaHandle.Init.MemInc = minc ? DMA_MINC_ENABLE : DMA_MINC_DISABLE; + + if (_dataSize == DATA_SIZE_8BIT) { + _dmaHandle.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE; + _dmaHandle.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE; + } + else { + _dmaHandle.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD; + _dmaHandle.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD; + } + #ifdef STM32F4xx + _dmaHandle.Init.FIFOMode = DMA_FIFOMODE_DISABLE; + #endif + + // start DMA hardware + // TODO: check if hardware is already enabled + #ifdef SPI1_BASE + if (_spiHandle.Instance == SPI1) { + #ifdef STM32F1xx + __HAL_RCC_DMA1_CLK_ENABLE(); + _dmaHandle.Instance = (direction == DMA_MEMORY_TO_PERIPH) ? DMA1_Channel3 : DMA1_Channel2; + #elif defined(STM32F4xx) + __HAL_RCC_DMA2_CLK_ENABLE(); + _dmaHandle.Init.Channel = DMA_CHANNEL_3; + _dmaHandle.Instance = (direction == DMA_MEMORY_TO_PERIPH) ? DMA2_Stream3 : DMA2_Stream0; + #endif + } + #endif + #ifdef SPI2_BASE + if (_spiHandle.Instance == SPI2) { + #ifdef STM32F1xx + __HAL_RCC_DMA1_CLK_ENABLE(); + _dmaHandle.Instance = (direction == DMA_MEMORY_TO_PERIPH) ? DMA1_Channel5 : DMA1_Channel4; + #elif defined(STM32F4xx) + __HAL_RCC_DMA1_CLK_ENABLE(); + _dmaHandle.Init.Channel = DMA_CHANNEL_0; + _dmaHandle.Instance = (direction == DMA_MEMORY_TO_PERIPH) ? DMA1_Stream4 : DMA1_Stream3; + #endif + } + #endif + #ifdef SPI3_BASE + if (_spiHandle.Instance == SPI3) { + #ifdef STM32F1xx + __HAL_RCC_DMA2_CLK_ENABLE(); + _dmaHandle.Instance = (direction == DMA_MEMORY_TO_PERIPH) ? DMA2_Channel2 : DMA2_Channel1; + #elif defined(STM32F4xx) + __HAL_RCC_DMA1_CLK_ENABLE(); + _dmaHandle.Init.Channel = DMA_CHANNEL_0; + _dmaHandle.Instance = (direction == DMA_MEMORY_TO_PERIPH) ? DMA1_Stream5 : DMA1_Stream2; + #endif + } + #endif + + HAL_DMA_Init(&_dmaHandle); +} + +byte MarlinSPI::transfer(uint8_t _data) { + uint8_t rxData = 0xFF; + HAL_SPI_TransmitReceive(&_spi.handle, &_data, &rxData, 1, HAL_MAX_DELAY); + return rxData; +} + +uint8_t MarlinSPI::dmaTransfer(const void *transmitBuf, void *receiveBuf, uint16_t length) { + const uint8_t ff = 0xFF; + + //if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) //only enable if disabled + __HAL_SPI_ENABLE(&_spi.handle); + + if (receiveBuf) { + setupDma(_spi.handle, _dmaRx, DMA_PERIPH_TO_MEMORY, true); + HAL_DMA_Start(&_dmaRx, (uint32_t)&(_spi.handle.Instance->DR), (uint32_t)receiveBuf, length); + SET_BIT(_spi.handle.Instance->CR2, SPI_CR2_RXDMAEN); /* Enable Rx DMA Request */ + } + + // check for 2 lines transfer + bool mincTransmit = true; + if (transmitBuf == nullptr && _spi.handle.Init.Direction == SPI_DIRECTION_2LINES && _spi.handle.Init.Mode == SPI_MODE_MASTER) { + transmitBuf = &ff; + mincTransmit = false; + } + + if (transmitBuf) { + setupDma(_spi.handle, _dmaTx, DMA_MEMORY_TO_PERIPH, mincTransmit); + HAL_DMA_Start(&_dmaTx, (uint32_t)transmitBuf, (uint32_t)&(_spi.handle.Instance->DR), length); + SET_BIT(_spi.handle.Instance->CR2, SPI_CR2_TXDMAEN); /* Enable Tx DMA Request */ + } + + if (transmitBuf) { + HAL_DMA_PollForTransfer(&_dmaTx, HAL_DMA_FULL_TRANSFER, HAL_MAX_DELAY); + HAL_DMA_Abort(&_dmaTx); + HAL_DMA_DeInit(&_dmaTx); + } + + // while ((_spi.handle.Instance->SR & SPI_FLAG_RXNE) != SPI_FLAG_RXNE) {} + + if (receiveBuf) { + HAL_DMA_PollForTransfer(&_dmaRx, HAL_DMA_FULL_TRANSFER, HAL_MAX_DELAY); + HAL_DMA_Abort(&_dmaRx); + HAL_DMA_DeInit(&_dmaRx); + } + + return 1; +} + +uint8_t MarlinSPI::dmaSend(const void * transmitBuf, uint16_t length, bool minc) { + setupDma(_spi.handle, _dmaTx, DMA_MEMORY_TO_PERIPH, minc); + HAL_DMA_Start(&_dmaTx, (uint32_t)transmitBuf, (uint32_t)&(_spi.handle.Instance->DR), length); + __HAL_SPI_ENABLE(&_spi.handle); + SET_BIT(_spi.handle.Instance->CR2, SPI_CR2_TXDMAEN); /* Enable Tx DMA Request */ + HAL_DMA_PollForTransfer(&_dmaTx, HAL_DMA_FULL_TRANSFER, HAL_MAX_DELAY); + HAL_DMA_Abort(&_dmaTx); + // DeInit objects + HAL_DMA_DeInit(&_dmaTx); + return 1; +} + +#endif // HAL_STM32 && !STM32H7xx diff --git a/Marlin/src/HAL/STM32/MarlinSPI.h b/Marlin/src/HAL/STM32/MarlinSPI.h new file mode 100644 index 000000000000..fbd3585ff447 --- /dev/null +++ b/Marlin/src/HAL/STM32/MarlinSPI.h @@ -0,0 +1,107 @@ +/** + * 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 + +#include "HAL.h" +#include + +extern "C" { + #include +} + +/** + * Marlin currently requires 3 SPI classes: + * + * SPIClass: + * This class is normally provided by frameworks and has a semi-default interface. + * This is needed because some libraries reference it globally. + * + * SPISettings: + * Container for SPI configs for SPIClass. As above, libraries may reference it globally. + * + * These two classes are often provided by frameworks so we cannot extend them to add + * useful methods for Marlin. + * + * MarlinSPI: + * Provides the default SPIClass interface plus some Marlin goodies such as a simplified + * interface for SPI DMA transfer. + * + */ + +#define DATA_SIZE_8BIT SPI_DATASIZE_8BIT +#define DATA_SIZE_16BIT SPI_DATASIZE_16BIT + +class MarlinSPI { +public: + MarlinSPI() : MarlinSPI(NC, NC, NC, NC) {} + + MarlinSPI(pin_t mosi, pin_t miso, pin_t sclk, pin_t ssel = (pin_t)NC) : _mosiPin(mosi), _misoPin(miso), _sckPin(sclk), _ssPin(ssel) { + _spi.pin_miso = digitalPinToPinName(_misoPin); + _spi.pin_mosi = digitalPinToPinName(_mosiPin); + _spi.pin_sclk = digitalPinToPinName(_sckPin); + _spi.pin_ssel = digitalPinToPinName(_ssPin); + _dataSize = DATA_SIZE_8BIT; + _bitOrder = MSBFIRST; + _dataMode = SPI_MODE_0; + _spi.handle.State = HAL_SPI_STATE_RESET; + setClockDivider(SPI_SPEED_CLOCK_DIV2_MHZ); + } + + void begin(void); + void end(void) {} + + byte transfer(uint8_t _data); + uint8_t dmaTransfer(const void *transmitBuf, void *receiveBuf, uint16_t length); + uint8_t dmaSend(const void * transmitBuf, uint16_t length, bool minc = true); + + /* These methods are deprecated and kept for compatibility. + * Use SPISettings with SPI.beginTransaction() to configure SPI parameters. + */ + void setBitOrder(BitOrder _order) { _bitOrder = _order; } + + void setDataMode(uint8_t _mode) { + switch (_mode) { + case SPI_MODE0: _dataMode = SPI_MODE_0; break; + case SPI_MODE1: _dataMode = SPI_MODE_1; break; + case SPI_MODE2: _dataMode = SPI_MODE_2; break; + case SPI_MODE3: _dataMode = SPI_MODE_3; break; + } + } + + void setClockDivider(uint8_t _div); + +private: + void setupDma(SPI_HandleTypeDef &_spiHandle, DMA_HandleTypeDef &_dmaHandle, uint32_t direction, bool minc = false); + + spi_t _spi; + DMA_HandleTypeDef _dmaTx; + DMA_HandleTypeDef _dmaRx; + BitOrder _bitOrder; + spi_mode_e _dataMode; + uint8_t _clockDivider; + uint32_t _speed; + uint32_t _dataSize; + pin_t _mosiPin; + pin_t _misoPin; + pin_t _sckPin; + pin_t _ssPin; +}; diff --git a/Marlin/src/HAL/STM32/MarlinSerial.cpp b/Marlin/src/HAL/STM32/MarlinSerial.cpp index a146664366df..3caedc72eb26 100644 --- a/Marlin/src/HAL/STM32/MarlinSerial.cpp +++ b/Marlin/src/HAL/STM32/MarlinSerial.cpp @@ -16,8 +16,9 @@ * along with this program. If not, see . * */ +#include "../platforms.h" -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) +#ifdef HAL_STM32 #include "../../inc/MarlinConfig.h" #include "MarlinSerial.h" @@ -29,28 +30,47 @@ #ifndef USART4 #define USART4 UART4 #endif - #ifndef USART5 #define USART5 UART5 #endif #define DECLARE_SERIAL_PORT(ser_num) \ void _rx_complete_irq_ ## ser_num (serial_t * obj); \ - MarlinSerial MSerial ## ser_num (USART ## ser_num, &_rx_complete_irq_ ## ser_num); \ + MSerialT MSerial ## ser_num (true, USART ## ser_num, &_rx_complete_irq_ ## ser_num); \ void _rx_complete_irq_ ## ser_num (serial_t * obj) { MSerial ## ser_num ._rx_complete_irq(obj); } -#define DECLARE_SERIAL_PORT_EXP(ser_num) DECLARE_SERIAL_PORT(ser_num) - -#if defined(SERIAL_PORT) && SERIAL_PORT >= 0 - DECLARE_SERIAL_PORT_EXP(SERIAL_PORT) +#if USING_HW_SERIAL1 + DECLARE_SERIAL_PORT(1) #endif - -#if defined(SERIAL_PORT_2) && SERIAL_PORT_2 >= 0 - DECLARE_SERIAL_PORT_EXP(SERIAL_PORT_2) +#if USING_HW_SERIAL2 + DECLARE_SERIAL_PORT(2) #endif - -#if defined(LCD_SERIAL_PORT) && LCD_SERIAL_PORT >= 0 - DECLARE_SERIAL_PORT_EXP(LCD_SERIAL_PORT) +#if USING_HW_SERIAL3 + DECLARE_SERIAL_PORT(3) +#endif +#if USING_HW_SERIAL4 + DECLARE_SERIAL_PORT(4) +#endif +#if USING_HW_SERIAL5 + DECLARE_SERIAL_PORT(5) +#endif +#if USING_HW_SERIAL6 + DECLARE_SERIAL_PORT(6) +#endif +#if USING_HW_SERIAL7 + DECLARE_SERIAL_PORT(7) +#endif +#if USING_HW_SERIAL8 + DECLARE_SERIAL_PORT(8) +#endif +#if USING_HW_SERIAL9 + DECLARE_SERIAL_PORT(9) +#endif +#if USING_HW_SERIAL10 + DECLARE_SERIAL_PORT(10) +#endif +#if USING_HW_SERIALLP1 + DECLARE_SERIAL_PORT(LP1) #endif void MarlinSerial::begin(unsigned long baud, uint8_t config) { @@ -78,9 +98,9 @@ void MarlinSerial::_rx_complete_irq(serial_t *obj) { } #if ENABLED(EMERGENCY_PARSER) - emergency_parser.update(emergency_state, c); + emergency_parser.update(static_cast(this)->emergency_state, c); #endif } } -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/MarlinSerial.h b/Marlin/src/HAL/STM32/MarlinSerial.h index 3611cc78d7ce..ab5c4260af2d 100644 --- a/Marlin/src/HAL/STM32/MarlinSerial.h +++ b/Marlin/src/HAL/STM32/MarlinSerial.h @@ -24,41 +24,33 @@ #include "../../feature/e_parser.h" #endif +#include "../../core/serial_hook.h" + typedef void (*usart_rx_callback_t)(serial_t * obj); -class MarlinSerial : public HardwareSerial { -public: - MarlinSerial(void* peripheral, usart_rx_callback_t rx_callback) : +struct MarlinSerial : public HardwareSerial { + MarlinSerial(void *peripheral, usart_rx_callback_t rx_callback) : HardwareSerial(peripheral), _rx_callback(rx_callback) - #if ENABLED(EMERGENCY_PARSER) - , emergency_state(EmergencyParser::State::EP_RESET) - #endif { } - #if ENABLED(EMERGENCY_PARSER) - static inline bool emergency_parser_enabled() { return true; } - #endif - void begin(unsigned long baud, uint8_t config); inline void begin(unsigned long baud) { begin(baud, SERIAL_8N1); } - void _rx_complete_irq(serial_t* obj); + void _rx_complete_irq(serial_t *obj); protected: usart_rx_callback_t _rx_callback; - #if ENABLED(EMERGENCY_PARSER) - EmergencyParser::State emergency_state; - #endif }; -extern MarlinSerial MSerial1; -extern MarlinSerial MSerial2; -extern MarlinSerial MSerial3; -extern MarlinSerial MSerial4; -extern MarlinSerial MSerial5; -extern MarlinSerial MSerial6; -extern MarlinSerial MSerial7; -extern MarlinSerial MSerial8; -extern MarlinSerial MSerial9; -extern MarlinSerial MSerial10; -extern MarlinSerial MSerialLP1; +typedef Serial1Class MSerialT; +extern MSerialT MSerial1; +extern MSerialT MSerial2; +extern MSerialT MSerial3; +extern MSerialT MSerial4; +extern MSerialT MSerial5; +extern MSerialT MSerial6; +extern MSerialT MSerial7; +extern MSerialT MSerial8; +extern MSerialT MSerial9; +extern MSerialT MSerial10; +extern MSerialT MSerialLP1; diff --git a/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp b/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp index 6e73e87c2123..914969f10cd2 100644 --- a/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp +++ b/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp @@ -19,303 +19,307 @@ * along with this program. If not, see . * */ +#include "../platforms.h" + +#ifdef HAL_STM32 #include "../../inc/MarlinConfig.h" -#if ENABLED(SDIO_SUPPORT) && !defined(STM32GENERIC) +#if ENABLED(SDIO_SUPPORT) #include #include -#if NONE(STM32F103xE, STM32F103xG, STM32F4xx, STM32F7xx) - #error "ERROR - Only STM32F103xE, STM32F103xG, STM32F4xx or STM32F7xx CPUs supported" +// use local drivers +#if defined(STM32F103xE) || defined(STM32F103xG) + #include + #include +#elif defined(STM32F4xx) + #include + #include + #include + #include +#elif defined(STM32F7xx) + #include + #include + #include + #include +#else + #error "SDIO only supported with STM32F103xE, STM32F103xG, STM32F4xx, or STM32F7xx." #endif -#ifdef USBD_USE_CDC_COMPOSITE - - // use USB drivers - - extern "C" { int8_t SD_MSC_Read(uint8_t lun, uint8_t *buf, uint32_t blk_addr, uint16_t blk_len); - int8_t SD_MSC_Write(uint8_t lun, uint8_t *buf, uint32_t blk_addr, uint16_t blk_len); - extern SD_HandleTypeDef hsd; - } - - bool SDIO_Init() { - return hsd.State == HAL_SD_STATE_READY; // return pass/fail status - } - - bool SDIO_ReadBlock(uint32_t block, uint8_t *src) { - int8_t status = SD_MSC_Read(0, (uint8_t*)src, block, 1); // read one 512 byte block - return (bool) status; - } +// Fixed +#define SDIO_D0_PIN PC8 +#define SDIO_D1_PIN PC9 +#define SDIO_D2_PIN PC10 +#define SDIO_D3_PIN PC11 +#define SDIO_CK_PIN PC12 +#define SDIO_CMD_PIN PD2 + +SD_HandleTypeDef hsd; // create SDIO structure +// F4 supports one DMA for RX and another for TX, but Marlin will never +// do read and write at same time, so we use the same DMA for both. +DMA_HandleTypeDef hdma_sdio; + +/* + SDIO_INIT_CLK_DIV is 118 + SDIO clock frequency is 48MHz / (TRANSFER_CLOCK_DIV + 2) + SDIO init clock frequency should not exceed 400KHz = 48MHz / (118 + 2) + + Default TRANSFER_CLOCK_DIV is 2 (118 / 40) + Default SDIO clock frequency is 48MHz / (2 + 2) = 12 MHz + This might be too fast for stable SDIO operations + + MKS Robin board seems to have stable SDIO with BusWide 1bit and ClockDiv 8 i.e. 4.8MHz SDIO clock frequency + Additional testing is required as there are clearly some 4bit initialization problems +*/ + +#ifndef USBD_OK + #define USBD_OK 0 +#endif - bool SDIO_WriteBlock(uint32_t block, const uint8_t *src) { - int8_t status = SD_MSC_Write(0, (uint8_t*)src, block, 1); // write one 512 byte block - return (bool) status; - } +// Target Clock, configurable. Default is 18MHz, from STM32F1 +#ifndef SDIO_CLOCK + #define SDIO_CLOCK 18000000 // 18 MHz +#endif -#else // !USBD_USE_CDC_COMPOSITE +// SDIO retries, configurable. Default is 3, from STM32F1 +#ifndef SDIO_READ_RETRIES + #define SDIO_READ_RETRIES 3 +#endif - // use local drivers - #if defined(STM32F103xE) || defined(STM32F103xG) - #include - #include - #elif defined(STM32F4xx) - #include - #include - #include - #include - #elif defined(STM32F7xx) - #include - #include - #include - #include - #else - #error "ERROR - Only STM32F103xE, STM32F103xG, STM32F4xx or STM32F7xx CPUs supported" +// SDIO Max Clock (naming from STM Manual, don't change) +#define SDIOCLK 48000000 + +static uint32_t clock_to_divider(uint32_t clk) { + // limit the SDIO master clock to 8/3 of PCLK2. See STM32 Manuals + // Also limited to no more than 48Mhz (SDIOCLK). + const uint32_t pclk2 = HAL_RCC_GetPCLK2Freq(); + clk = min(clk, (uint32_t)(pclk2 * 8 / 3)); + clk = min(clk, (uint32_t)SDIOCLK); + // Round up divider, so we don't run the card over the speed supported, + // and subtract by 2, because STM32 will add 2, as written in the manual: + // SDIO_CK frequency = SDIOCLK / [CLKDIV + 2] + return pclk2 / clk + (pclk2 % clk != 0) - 2; +} + +void go_to_transfer_speed() { + /* Default SDIO peripheral configuration for SD card initialization */ + hsd.Init.ClockEdge = hsd.Init.ClockEdge; + hsd.Init.ClockBypass = hsd.Init.ClockBypass; + hsd.Init.ClockPowerSave = hsd.Init.ClockPowerSave; + hsd.Init.BusWide = hsd.Init.BusWide; + hsd.Init.HardwareFlowControl = hsd.Init.HardwareFlowControl; + hsd.Init.ClockDiv = clock_to_divider(SDIO_CLOCK); + + /* Initialize SDIO peripheral interface with default configuration */ + SDIO_Init(hsd.Instance, hsd.Init); +} + +void SD_LowLevel_Init(void) { + uint32_t tempreg; + + __HAL_RCC_GPIOC_CLK_ENABLE(); //enable GPIO clocks + __HAL_RCC_GPIOD_CLK_ENABLE(); //enable GPIO clocks + + GPIO_InitTypeDef GPIO_InitStruct; + + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = 1; //GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + + #if DISABLED(STM32F1xx) + GPIO_InitStruct.Alternate = GPIO_AF12_SDIO; #endif - SD_HandleTypeDef hsd; // create SDIO structure - - /* - SDIO_INIT_CLK_DIV is 118 - SDIO clock frequency is 48MHz / (TRANSFER_CLOCK_DIV + 2) - SDIO init clock frequency should not exceed 400KHz = 48MHz / (118 + 2) - - Default TRANSFER_CLOCK_DIV is 2 (118 / 40) - Default SDIO clock frequency is 48MHz / (2 + 2) = 12 MHz - This might be too fast for stable SDIO operations - - MKS Robin board seems to have stable SDIO with BusWide 1bit and ClockDiv 8 i.e. 4.8MHz SDIO clock frequency - Additional testing is required as there are clearly some 4bit initialization problems - - Add -DTRANSFER_CLOCK_DIV=8 to build parameters to improve SDIO stability - */ + GPIO_InitStruct.Pin = GPIO_PIN_8 | GPIO_PIN_12; // D0 & SCK + HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); - #ifndef TRANSFER_CLOCK_DIV - #define TRANSFER_CLOCK_DIV (uint8_t(SDIO_INIT_CLK_DIV) / 40) - #endif - - #ifndef USBD_OK - #define USBD_OK 0 + #if PINS_EXIST(SDIO_D1, SDIO_D2, SDIO_D3) // define D1-D3 only if have a four bit wide SDIO bus + GPIO_InitStruct.Pin = GPIO_PIN_9 | GPIO_PIN_10 | GPIO_PIN_11; // D1-D3 + HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); #endif - void go_to_transfer_speed() { - SD_InitTypeDef Init; - - /* Default SDIO peripheral configuration for SD card initialization */ - Init.ClockEdge = hsd.Init.ClockEdge; - Init.ClockBypass = hsd.Init.ClockBypass; - Init.ClockPowerSave = hsd.Init.ClockPowerSave; - Init.BusWide = hsd.Init.BusWide; - Init.HardwareFlowControl = hsd.Init.HardwareFlowControl; - Init.ClockDiv = TRANSFER_CLOCK_DIV; - - /* Initialize SDIO peripheral interface with default configuration */ - SDIO_Init(hsd.Instance, Init); - } - - void SD_LowLevel_Init(void) { - uint32_t tempreg; + // Configure PD.02 CMD line + GPIO_InitStruct.Pin = GPIO_PIN_2; + HAL_GPIO_Init(GPIOD, &GPIO_InitStruct); + // Setup DMA + #if defined(STM32F1xx) + hdma_sdio.Init.Mode = DMA_NORMAL; + hdma_sdio.Instance = DMA2_Channel4; + HAL_NVIC_EnableIRQ(DMA2_Channel4_5_IRQn); + #elif defined(STM32F4xx) + hdma_sdio.Init.Mode = DMA_PFCTRL; + hdma_sdio.Instance = DMA2_Stream3; + hdma_sdio.Init.Channel = DMA_CHANNEL_4; + hdma_sdio.Init.FIFOMode = DMA_FIFOMODE_ENABLE; + hdma_sdio.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_FULL; + hdma_sdio.Init.MemBurst = DMA_MBURST_INC4; + hdma_sdio.Init.PeriphBurst = DMA_PBURST_INC4; + HAL_NVIC_EnableIRQ(DMA2_Stream3_IRQn); + #endif + HAL_NVIC_EnableIRQ(SDIO_IRQn); + hdma_sdio.Init.PeriphInc = DMA_PINC_DISABLE; + hdma_sdio.Init.MemInc = DMA_MINC_ENABLE; + hdma_sdio.Init.PeriphDataAlignment = DMA_PDATAALIGN_WORD; + hdma_sdio.Init.MemDataAlignment = DMA_MDATAALIGN_WORD; + hdma_sdio.Init.Priority = DMA_PRIORITY_LOW; + __HAL_LINKDMA(&hsd, hdmarx, hdma_sdio); + __HAL_LINKDMA(&hsd, hdmatx, hdma_sdio); + + #if defined(STM32F1xx) + __HAL_RCC_SDIO_CLK_ENABLE(); + __HAL_RCC_DMA2_CLK_ENABLE(); + #else + __HAL_RCC_SDIO_FORCE_RESET(); + delay(2); + __HAL_RCC_SDIO_RELEASE_RESET(); + delay(2); __HAL_RCC_SDIO_CLK_ENABLE(); - __HAL_RCC_GPIOC_CLK_ENABLE(); //enable GPIO clocks - __HAL_RCC_GPIOD_CLK_ENABLE(); //enable GPIO clocks - - GPIO_InitTypeDef GPIO_InitStruct; - - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = 1; //GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; - - #if DISABLED(STM32F1xx) - GPIO_InitStruct.Alternate = GPIO_AF12_SDIO; - #endif - - GPIO_InitStruct.Pin = GPIO_PIN_8 | GPIO_PIN_12; // D0 & SCK - HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); - - #if PINS_EXIST(SDIO_D1, SDIO_D2, SDIO_D3) // define D1-D3 only if have a four bit wide SDIO bus - GPIO_InitStruct.Pin = GPIO_PIN_9 | GPIO_PIN_10 | GPIO_PIN_11; // D1-D3 - HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); - #endif - - // Configure PD.02 CMD line - GPIO_InitStruct.Pin = GPIO_PIN_2; - HAL_GPIO_Init(GPIOD, &GPIO_InitStruct); - - - #if DISABLED(STM32F1xx) - // TODO: use __HAL_RCC_SDIO_RELEASE_RESET() and __HAL_RCC_SDIO_CLK_ENABLE(); - RCC->APB2RSTR &= ~RCC_APB2RSTR_SDIORST_Msk; // take SDIO out of reset - RCC->APB2ENR |= RCC_APB2RSTR_SDIORST_Msk; // enable SDIO clock - // Enable the DMA2 Clock - #endif - - //Initialize the SDIO (with initial <400Khz Clock) - tempreg = 0; //Reset value - tempreg |= SDIO_CLKCR_CLKEN; // Clock enabled - tempreg |= (uint32_t)0x76; // Clock Divider. Clock = 48000 / (118 + 2) = 400Khz - // Keep the rest at 0 => HW_Flow Disabled, Rising Clock Edge, Disable CLK ByPass, Bus Width = 0, Power save Disable - SDIO->CLKCR = tempreg; - // Power up the SDIO - SDIO->POWER = 0x03; - } + __HAL_RCC_DMA2_FORCE_RESET(); + delay(2); + __HAL_RCC_DMA2_RELEASE_RESET(); + delay(2); + __HAL_RCC_DMA2_CLK_ENABLE(); + #endif - void HAL_SD_MspInit(SD_HandleTypeDef *hsd) { // application specific init - UNUSED(hsd); /* Prevent unused argument(s) compilation warning */ - __HAL_RCC_SDIO_CLK_ENABLE(); // turn on SDIO clock + //Initialize the SDIO (with initial <400Khz Clock) + tempreg = 0; //Reset value + tempreg |= SDIO_CLKCR_CLKEN; // Clock enabled + tempreg |= SDIO_INIT_CLK_DIV; // Clock Divider. Clock = 48000 / (118 + 2) = 400Khz + // Keep the rest at 0 => HW_Flow Disabled, Rising Clock Edge, Disable CLK ByPass, Bus Width = 0, Power save Disable + SDIO->CLKCR = tempreg; + + // Power up the SDIO + SDIO_PowerState_ON(SDIO); + hsd.Instance = SDIO; +} + +void HAL_SD_MspInit(SD_HandleTypeDef *hsd) { // application specific init + UNUSED(hsd); // Prevent unused argument(s) compilation warning + __HAL_RCC_SDIO_CLK_ENABLE(); // turn on SDIO clock +} + +bool SDIO_Init() { + uint8_t retryCnt = SDIO_READ_RETRIES; + + bool status; + hsd.Instance = SDIO; + hsd.State = HAL_SD_STATE_RESET; + + SD_LowLevel_Init(); + + uint8_t retry_Cnt = retryCnt; + for (;;) { + TERN_(USE_WATCHDOG, HAL_watchdog_refresh()); + status = (bool) HAL_SD_Init(&hsd); + if (!status) break; + if (!--retry_Cnt) return false; // return failing status if retries are exhausted } - constexpr uint8_t SD_RETRY_COUNT = TERN(SD_CHECK_AND_RETRY, 3, 1); - - bool SDIO_Init() { - //init SDIO and get SD card info + go_to_transfer_speed(); - uint8_t retryCnt = SD_RETRY_COUNT; - - bool status; - hsd.Instance = SDIO; - hsd.State = (HAL_SD_StateTypeDef) 0; // HAL_SD_STATE_RESET - - /* - hsd.Init.ClockEdge = SDIO_CLOCK_EDGE_RISING; - hsd.Init.ClockBypass = SDIO_CLOCK_BYPASS_DISABLE; - hsd.Init.ClockPowerSave = SDIO_CLOCK_POWER_SAVE_DISABLE; - hsd.Init.BusWide = SDIO_BUS_WIDE_1B; - hsd.Init.HardwareFlowControl = SDIO_HARDWARE_FLOW_CONTROL_DISABLE; - hsd.Init.ClockDiv = 8; - */ - - SD_LowLevel_Init(); - - uint8_t retry_Cnt = retryCnt; + #if PINS_EXIST(SDIO_D1, SDIO_D2, SDIO_D3) // go to 4 bit wide mode if pins are defined + retry_Cnt = retryCnt; for (;;) { TERN_(USE_WATCHDOG, HAL_watchdog_refresh()); - status = (bool) HAL_SD_Init(&hsd); - if (!status) break; - if (!--retry_Cnt) return false; // return failing status if retries are exhausted + if (!HAL_SD_ConfigWideBusOperation(&hsd, SDIO_BUS_WIDE_4B)) break; // some cards are only 1 bit wide so a pass here is not required + if (!--retry_Cnt) break; } - - go_to_transfer_speed(); - - #if PINS_EXIST(SDIO_D1, SDIO_D2, SDIO_D3) // go to 4 bit wide mode if pins are defined + if (!retry_Cnt) { // wide bus failed, go back to one bit wide mode + hsd.State = (HAL_SD_StateTypeDef) 0; // HAL_SD_STATE_RESET + SD_LowLevel_Init(); retry_Cnt = retryCnt; for (;;) { TERN_(USE_WATCHDOG, HAL_watchdog_refresh()); - if (!HAL_SD_ConfigWideBusOperation(&hsd, SDIO_BUS_WIDE_4B)) break; // some cards are only 1 bit wide so a pass here is not required - if (!--retry_Cnt) break; - } - if (!retry_Cnt) { // wide bus failed, go back to one bit wide mode - hsd.State = (HAL_SD_StateTypeDef) 0; // HAL_SD_STATE_RESET - SD_LowLevel_Init(); - retry_Cnt = retryCnt; - for (;;) { - TERN_(USE_WATCHDOG, HAL_watchdog_refresh()); - status = (bool) HAL_SD_Init(&hsd); - if (!status) break; - if (!--retry_Cnt) return false; // return failing status if retries are exhausted - } + status = (bool) HAL_SD_Init(&hsd); + if (!status) break; + if (!--retry_Cnt) return false; // return failing status if retries are exhausted } - #endif + go_to_transfer_speed(); + } + #endif - return true; - } - /* - void init_SDIO_pins(void) { - GPIO_InitTypeDef GPIO_InitStruct = {0}; - - // SDIO GPIO Configuration - // PC8 ------> SDIO_D0 - // PC12 ------> SDIO_CK - // PD2 ------> SDIO_CMD - - GPIO_InitStruct.Pin = GPIO_PIN_8; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; - GPIO_InitStruct.Alternate = GPIO_AF12_SDIO; - HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); + return true; +} - GPIO_InitStruct.Pin = GPIO_PIN_12; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; - GPIO_InitStruct.Alternate = GPIO_AF12_SDIO; - HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); +static bool SDIO_ReadWriteBlock_DMA(uint32_t block, const uint8_t *src, uint8_t *dst) { + if (HAL_SD_GetCardState(&hsd) != HAL_SD_CARD_TRANSFER) return false; - GPIO_InitStruct.Pin = GPIO_PIN_2; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; - GPIO_InitStruct.Alternate = GPIO_AF12_SDIO; - HAL_GPIO_Init(GPIOD, &GPIO_InitStruct); + TERN_(USE_WATCHDOG, HAL_watchdog_refresh()); + + HAL_StatusTypeDef ret; + if (src) { + hdma_sdio.Init.Direction = DMA_MEMORY_TO_PERIPH; + HAL_DMA_Init(&hdma_sdio); + ret = HAL_SD_WriteBlocks_DMA(&hsd, (uint8_t *)src, block, 1); + } + else { + hdma_sdio.Init.Direction = DMA_PERIPH_TO_MEMORY; + HAL_DMA_Init(&hdma_sdio); + ret = HAL_SD_ReadBlocks_DMA(&hsd, (uint8_t *)dst, block, 1); } - */ - //bool SDIO_init() { return (bool) (SD_SDIO_Init() ? 1 : 0);} - //bool SDIO_Init_C() { return (bool) (SD_SDIO_Init() ? 1 : 0);} - bool SDIO_ReadBlock(uint32_t block, uint8_t *dst) { - hsd.Instance = SDIO; - uint8_t retryCnt = SD_RETRY_COUNT; + if (ret != HAL_OK) { + HAL_DMA_Abort_IT(&hdma_sdio); + HAL_DMA_DeInit(&hdma_sdio); + return false; + } - bool status; - for (;;) { - TERN_(USE_WATCHDOG, HAL_watchdog_refresh()); - status = (bool) HAL_SD_ReadBlocks(&hsd, (uint8_t*)dst, block, 1, 1000); // read one 512 byte block with 500mS timeout - status |= (bool) HAL_SD_GetCardState(&hsd); // make sure all is OK - if (!status) break; // return passing status - if (!--retryCnt) break; // return failing status if retries are exhausted + millis_t timeout = millis() + 500; + // Wait the transfer + while (hsd.State != HAL_SD_STATE_READY) { + if (ELAPSED(millis(), timeout)) { + HAL_DMA_Abort_IT(&hdma_sdio); + HAL_DMA_DeInit(&hdma_sdio); + return false; } - return status; + } - /* - return (bool) ((status_read | status_card) ? 1 : 0); + while (__HAL_DMA_GET_FLAG(&hdma_sdio, __HAL_DMA_GET_TC_FLAG_INDEX(&hdma_sdio)) != 0 + || __HAL_DMA_GET_FLAG(&hdma_sdio, __HAL_DMA_GET_TE_FLAG_INDEX(&hdma_sdio)) != 0) { /* nada */ } - if (SDIO_GetCardState() != SDIO_CARD_TRANSFER) return false; - if (blockAddress >= SdCard.LogBlockNbr) return false; - if ((0x03 & (uint32_t)data)) return false; // misaligned data + HAL_DMA_Abort_IT(&hdma_sdio); + HAL_DMA_DeInit(&hdma_sdio); - if (SdCard.CardType != CARD_SDHC_SDXC) { blockAddress *= 512U; } + timeout = millis() + 500; + while (HAL_SD_GetCardState(&hsd) != HAL_SD_CARD_TRANSFER) if (ELAPSED(millis(), timeout)) return false; - if (!SDIO_CmdReadSingleBlock(blockAddress)) { - SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS); - dma_disable(SDIO_DMA_DEV, SDIO_DMA_CHANNEL); - return false; - } + return true; +} - while (!SDIO_GET_FLAG(SDIO_STA_DATAEND | SDIO_STA_TRX_ERROR_FLAGS)) {} +bool SDIO_ReadBlock(uint32_t block, uint8_t *dst) { + uint8_t retries = SDIO_READ_RETRIES; + while (retries--) if (SDIO_ReadWriteBlock_DMA(block, nullptr, dst)) return true; + return false; +} - dma_disable(SDIO_DMA_DEV, SDIO_DMA_CHANNEL); +bool SDIO_WriteBlock(uint32_t block, const uint8_t *src) { + uint8_t retries = SDIO_READ_RETRIES; + while (retries--) if (SDIO_ReadWriteBlock_DMA(block, src, nullptr)) return true; + return false; +} - if (SDIO->STA & SDIO_STA_RXDAVL) { - while (SDIO->STA & SDIO_STA_RXDAVL) (void)SDIO->FIFO; - SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS | SDIO_ICR_DATA_FLAGS); - return false; - } +bool SDIO_IsReady() { + return hsd.State == HAL_SD_STATE_READY; +} - if (SDIO_GET_FLAG(SDIO_STA_TRX_ERROR_FLAGS)) { - SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS | SDIO_ICR_DATA_FLAGS); - return false; - } - SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS | SDIO_ICR_DATA_FLAGS); - */ +uint32_t SDIO_GetCardSize() { + return (uint32_t)(hsd.SdCard.BlockNbr) * (hsd.SdCard.BlockSize); +} - return true; - } +#if defined(STM32F1xx) + #define DMA_IRQ_HANDLER DMA2_Channel4_5_IRQHandler +#elif defined(STM32F4xx) + #define DMA_IRQ_HANDLER DMA2_Stream3_IRQHandler +#else + #error "Unknown STM32 architecture." +#endif - bool SDIO_WriteBlock(uint32_t block, const uint8_t *src) { - hsd.Instance = SDIO; - uint8_t retryCnt = SD_RETRY_COUNT; - bool status; - for (;;) { - status = (bool) HAL_SD_WriteBlocks(&hsd, (uint8_t*)src, block, 1, 500); // write one 512 byte block with 500mS timeout - status |= (bool) HAL_SD_GetCardState(&hsd); // make sure all is OK - if (!status) break; // return passing status - if (!--retryCnt) break; // return failing status if retries are exhausted - } - return status; - } +extern "C" void SDIO_IRQHandler(void) { HAL_SD_IRQHandler(&hsd); } +extern "C" void DMA_IRQ_HANDLER(void) { HAL_DMA_IRQHandler(&hdma_sdio); } -#endif // !USBD_USE_CDC_COMPOSITE #endif // SDIO_SUPPORT +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/Servo.cpp b/Marlin/src/HAL/STM32/Servo.cpp index 1cf117a05694..a00186e0e79e 100644 --- a/Marlin/src/HAL/STM32/Servo.cpp +++ b/Marlin/src/HAL/STM32/Servo.cpp @@ -20,7 +20,9 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) +#include "../platforms.h" + +#ifdef HAL_STM32 #include "../../inc/MarlinConfig.h" @@ -37,7 +39,7 @@ static_assert(COUNT(servoDelay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM // This allows all timer interrupt priorities to be managed from a single location in the HAL. static uint32_t servo_interrupt_priority = NVIC_EncodePriority(NVIC_GetPriorityGrouping(), TIM_IRQ_PRIO, TIM_IRQ_SUBPRIO); -// This must be called after the STM32 Servo class has intialized the timer. +// This must be called after the STM32 Servo class has initialized the timer. // It may only be needed after the first call to attach(), but it is possible // that is is necessary after every detach() call. To be safe this is currently // called after every call to attach(). @@ -107,4 +109,4 @@ void libServo::setInterruptPriority(uint32_t preemptPriority, uint32_t subPriori } #endif // HAS_SERVOS -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/eeprom_bl24cxx.cpp b/Marlin/src/HAL/STM32/eeprom_bl24cxx.cpp new file mode 100644 index 000000000000..5bd4c18577b4 --- /dev/null +++ b/Marlin/src/HAL/STM32/eeprom_bl24cxx.cpp @@ -0,0 +1,84 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../platforms.h" + +#ifdef HAL_STM32 + +/** + * PersistentStore for Arduino-style EEPROM interface + * with simple implementations supplied by Marlin. + */ + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(IIC_BL24CXX_EEPROM) + +#include "../shared/eeprom_if.h" +#include "../shared/eeprom_api.h" + +// +// PersistentStore +// + +#ifndef MARLIN_EEPROM_SIZE + #error "MARLIN_EEPROM_SIZE is required for IIC_BL24CXX_EEPROM." +#endif + +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } + +bool PersistentStore::access_start() { eeprom_init(); return true; } +bool PersistentStore::access_finish() { return true; } + +bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + uint16_t written = 0; + while (size--) { + uint8_t v = *value; + uint8_t * const p = (uint8_t * const)pos; + if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed! + eeprom_write_byte(p, v); + if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes + if (eeprom_read_byte(p) != v) { + SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); + return true; + } + } + crc16(crc, &v, 1); + pos++; + value++; + } + return false; +} + +bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { + do { + uint8_t * const p = (uint8_t * const)pos; + uint8_t c = eeprom_read_byte(p); + if (writing) *value = c; + crc16(crc, &c, 1); + pos++; + value++; + } while (--size); + return false; +} + +#endif // IIC_BL24CXX_EEPROM +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/eeprom_flash.cpp b/Marlin/src/HAL/STM32/eeprom_flash.cpp index 0933b9f4e8cb..e785e5924988 100644 --- a/Marlin/src/HAL/STM32/eeprom_flash.cpp +++ b/Marlin/src/HAL/STM32/eeprom_flash.cpp @@ -20,7 +20,9 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) +#include "../platforms.h" + +#ifdef HAL_STM32 #include "../../inc/MarlinConfig.h" @@ -28,14 +30,9 @@ #include "../shared/eeprom_api.h" -#if HAS_SERVOS - #include "Servo.h" - #define PAUSE_SERVO_OUTPUT() libServo::pause_all_servos() - #define RESUME_SERVO_OUTPUT() libServo::resume_all_servos() -#else - #define PAUSE_SERVO_OUTPUT() - #define RESUME_SERVO_OUTPUT() -#endif +// Better: "utility/stm32_eeprom.h", but only after updating stm32duino to 2.0.0 +// Use EEPROM.h for compatibility, for now. +#include /** * The STM32 HAL supports chips that deal with "pages" and some with "sectors" and some that @@ -57,7 +54,7 @@ #include "stm32_def.h" #define DEBUG_OUT ENABLED(EEPROM_CHITCHAT) - #include "src/core/debug_out.h" + #include "../../core/debug_out.h" #ifndef MARLIN_EEPROM_SIZE #define MARLIN_EEPROM_SIZE 0x1000 // 4KB @@ -70,7 +67,9 @@ #define FLASH_UNIT_SIZE 0x20000 // 128kB #endif - #define FLASH_ADDRESS_START (FLASH_END - ((FLASH_SECTOR_TOTAL - (FLASH_SECTOR)) * (FLASH_UNIT_SIZE)) + 1) + #ifndef FLASH_ADDRESS_START + #define FLASH_ADDRESS_START (FLASH_END - ((FLASH_SECTOR_TOTAL - (FLASH_SECTOR)) * (FLASH_UNIT_SIZE)) + 1) + #endif #define FLASH_ADDRESS_END (FLASH_ADDRESS_START + FLASH_UNIT_SIZE - 1) #define EEPROM_SLOTS ((FLASH_UNIT_SIZE) / (MARLIN_EEPROM_SIZE)) @@ -107,13 +106,15 @@ size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } bool PersistentStore::access_start() { + EEPROM.begin(); // Avoid STM32 EEPROM.h warning (do nothing) + #if ENABLED(FLASH_EEPROM_LEVELING) if (current_slot == -1 || eeprom_data_written) { // This must be the first time since power on that we have accessed the storage, or someone // loaded and called write_data and never called access_finish. // Lets go looking for the slot that holds our configuration. - if (eeprom_data_written) DEBUG_ECHOLN("Dangling EEPROM write_data"); + if (eeprom_data_written) DEBUG_ECHOLNPGM("Dangling EEPROM write_data"); uint32_t address = FLASH_ADDRESS_START; while (address <= FLASH_ADDRESS_END) { uint32_t address_value = (*(__IO uint32_t*)address); @@ -124,7 +125,7 @@ bool PersistentStore::access_start() { address += sizeof(uint32_t); } if (current_slot == -1) { - // We didn't find anything, so we'll just intialize to empty + // We didn't find anything, so we'll just initialize to empty for (int i = 0; i < MARLIN_EEPROM_SIZE; i++) ram_eeprom[i] = EMPTY_UINT8; current_slot = EEPROM_SLOTS; } @@ -172,11 +173,11 @@ bool PersistentStore::access_finish() { current_slot = EEPROM_SLOTS - 1; UNLOCK_FLASH(); - PAUSE_SERVO_OUTPUT(); + TERN_(HAS_PAUSE_SERVO_OUTPUT, PAUSE_SERVO_OUTPUT()); DISABLE_ISRS(); status = HAL_FLASHEx_Erase(&EraseInitStruct, &SectorError); ENABLE_ISRS(); - RESUME_SERVO_OUTPUT(); + TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT()); if (status != HAL_OK) { DEBUG_ECHOLNPAIR("HAL_FLASHEx_Erase=", status); DEBUG_ECHOLNPAIR("GetError=", HAL_FLASH_GetError()); @@ -227,11 +228,11 @@ bool PersistentStore::access_finish() { // Interrupts during this time can have unpredictable results, such as killing Servo // output. Servo output still glitches with interrupts disabled, but recovers after the // erase. - PAUSE_SERVO_OUTPUT(); + TERN_(HAS_PAUSE_SERVO_OUTPUT, PAUSE_SERVO_OUTPUT()); DISABLE_ISRS(); eeprom_buffer_flush(); ENABLE_ISRS(); - RESUME_SERVO_OUTPUT(); + TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT()); eeprom_data_written = false; #endif @@ -261,7 +262,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui return false; } -bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { +bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { do { const uint8_t c = TERN(FLASH_EEPROM_LEVELING, ram_eeprom[pos], eeprom_buffered_read_byte(pos)); if (writing) *value = c; @@ -273,4 +274,4 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t } #endif // FLASH_EEPROM_EMULATION -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/eeprom_if_iic.cpp b/Marlin/src/HAL/STM32/eeprom_if_iic.cpp new file mode 100644 index 000000000000..26b3d9044e1f --- /dev/null +++ b/Marlin/src/HAL/STM32/eeprom_if_iic.cpp @@ -0,0 +1,55 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../platforms.h" + +#ifdef HAL_STM32 + +/** + * Platform-independent Arduino functions for I2C EEPROM. + * Enable USE_SHARED_EEPROM if not supplied by the framework. + */ + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(IIC_BL24CXX_EEPROM) + +#include "../../libs/BL24CXX.h" +#include "../shared/eeprom_if.h" + +void eeprom_init() { BL24CXX::init(); } + +// ------------------------ +// Public functions +// ------------------------ + +void eeprom_write_byte(uint8_t *pos, uint8_t value) { + const unsigned eeprom_address = (unsigned)pos; + return BL24CXX::writeOneByte(eeprom_address, value); +} + +uint8_t eeprom_read_byte(uint8_t *pos) { + const unsigned eeprom_address = (unsigned)pos; + return BL24CXX::readOneByte(eeprom_address); +} + +#endif // IIC_BL24CXX_EEPROM +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/eeprom_sdcard.cpp b/Marlin/src/HAL/STM32/eeprom_sdcard.cpp index 711a83ed5b6a..77563b2ae502 100644 --- a/Marlin/src/HAL/STM32/eeprom_sdcard.cpp +++ b/Marlin/src/HAL/STM32/eeprom_sdcard.cpp @@ -19,13 +19,14 @@ * along with this program. If not, see . * */ +#include "../platforms.h" + +#ifdef HAL_STM32 /** * Implementation of EEPROM settings in SD Card */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) - #include "../../inc/MarlinConfig.h" #if ENABLED(SDCARD_EEPROM_EMULATION) @@ -78,7 +79,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui return false; } -bool PersistentStore::read_data(int &pos, uint8_t* value, const size_t size, uint16_t *crc, const bool writing/*=true*/) { +bool PersistentStore::read_data(int &pos, uint8_t *value, const size_t size, uint16_t *crc, const bool writing/*=true*/) { for (size_t i = 0; i < size; i++) { uint8_t c = HAL_eeprom_data[pos + i]; if (writing) value[i] = c; @@ -89,4 +90,4 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, const size_t size, uin } #endif // SDCARD_EEPROM_EMULATION -#endif // STM32 && !STM32GENERIC +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/eeprom_sram.cpp b/Marlin/src/HAL/STM32/eeprom_sram.cpp index 5f6f26f9c61b..687e7f55c226 100644 --- a/Marlin/src/HAL/STM32/eeprom_sram.cpp +++ b/Marlin/src/HAL/STM32/eeprom_sram.cpp @@ -20,7 +20,9 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) +#include "../platforms.h" + +#ifdef HAL_STM32 #include "../../inc/MarlinConfig.h" @@ -52,7 +54,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui return false; } -bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { +bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { do { // Read from either external EEPROM, program flash or Backup SRAM const uint8_t c = ( *(__IO uint8_t *)(BKPSRAM_BASE + ((uint8_t*)pos)) ); @@ -65,4 +67,4 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t } #endif // SRAM_EEPROM_EMULATION -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/eeprom_wired.cpp b/Marlin/src/HAL/STM32/eeprom_wired.cpp index 8c46e45f0324..cf0468151e5e 100644 --- a/Marlin/src/HAL/STM32/eeprom_wired.cpp +++ b/Marlin/src/HAL/STM32/eeprom_wired.cpp @@ -20,7 +20,9 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) +#include "../platforms.h" + +#ifdef HAL_STM32 #include "../../inc/MarlinConfig.h" @@ -43,29 +45,26 @@ bool PersistentStore::access_start() { eeprom_init(); return true; } bool PersistentStore::access_finish() { return true; } bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + uint16_t written = 0; while (size--) { uint8_t v = *value; - - // EEPROM has only ~100,000 write cycles, - // so only write bytes that have changed! uint8_t * const p = (uint8_t * const)pos; - if (v != eeprom_read_byte(p)) { + if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed! eeprom_write_byte(p, v); + if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes if (eeprom_read_byte(p) != v) { SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); return true; } } - crc16(crc, &v, 1); pos++; value++; - }; - + } return false; } -bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { +bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { do { // Read from either external EEPROM, program flash or Backup SRAM const uint8_t c = eeprom_read_byte((uint8_t*)pos); @@ -78,4 +77,4 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t } #endif // USE_WIRED_EEPROM -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/endstop_interrupts.h b/Marlin/src/HAL/STM32/endstop_interrupts.h index fdff8cc644cd..90870881fe66 100644 --- a/Marlin/src/HAL/STM32/endstop_interrupts.h +++ b/Marlin/src/HAL/STM32/endstop_interrupts.h @@ -46,4 +46,10 @@ void setup_endstop_interrupts() { TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); TERN_(HAS_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)); } diff --git a/Marlin/src/HAL/STM32/fast_pwm.cpp b/Marlin/src/HAL/STM32/fast_pwm.cpp new file mode 100644 index 000000000000..a8fcbe5f82b3 --- /dev/null +++ b/Marlin/src/HAL/STM32/fast_pwm.cpp @@ -0,0 +1,61 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../platforms.h" + +#ifdef HAL_STM32 + +#include "../../inc/MarlinConfigPre.h" + +#if NEEDS_HARDWARE_PWM + +#include "HAL.h" +#include "timers.h" + +void set_pwm_frequency(const pin_t pin, int f_desired) { + if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer + + PinName pin_name = digitalPinToPinName(pin); + TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); // Get HAL timer instance + + LOOP_S_L_N(i, 0, NUM_HARDWARE_TIMERS) // Protect used timers + if (timer_instance[i] && timer_instance[i]->getHandle()->Instance == Instance) + return; + + pwm_start(pin_name, f_desired, 0, RESOLUTION_8B_COMPARE_FORMAT); +} + +void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { + PinName pin_name = digitalPinToPinName(pin); + TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); + uint16_t adj_val = Instance->ARR * v / v_size; + if (invert) adj_val = Instance->ARR - adj_val; + + switch (get_pwm_channel(pin_name)) { + case TIM_CHANNEL_1: LL_TIM_OC_SetCompareCH1(Instance, adj_val); break; + case TIM_CHANNEL_2: LL_TIM_OC_SetCompareCH2(Instance, adj_val); break; + case TIM_CHANNEL_3: LL_TIM_OC_SetCompareCH3(Instance, adj_val); break; + case TIM_CHANNEL_4: LL_TIM_OC_SetCompareCH4(Instance, adj_val); break; + } +} + +#endif // NEEDS_HARDWARE_PWM +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/fastio.cpp b/Marlin/src/HAL/STM32/fastio.cpp index 0d55579d8886..b34555b8c841 100644 --- a/Marlin/src/HAL/STM32/fastio.cpp +++ b/Marlin/src/HAL/STM32/fastio.cpp @@ -20,15 +20,17 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) +#include "../platforms.h" + +#ifdef HAL_STM32 #include "../../inc/MarlinConfig.h" -GPIO_TypeDef* FastIOPortMap[LastPort + 1]; +GPIO_TypeDef* FastIOPortMap[LastPort + 1] = { 0 }; void FastIO_init() { LOOP_L_N(i, NUM_DIGITAL_PINS) FastIOPortMap[STM_PORT(digitalPin[i])] = get_GPIO_Port(STM_PORT(digitalPin[i])); } -#endif +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/fastio.h b/Marlin/src/HAL/STM32/fastio.h index ea28b8f3bfaa..4a489544716f 100644 --- a/Marlin/src/HAL/STM32/fastio.h +++ b/Marlin/src/HAL/STM32/fastio.h @@ -38,6 +38,7 @@ extern GPIO_TypeDef * FastIOPortMap[]; // ------------------------ void FastIO_init(); // Must be called before using fast io macros +#define FASTIO_INIT() FastIO_init() // ------------------------ // Defines @@ -59,7 +60,7 @@ void FastIO_init(); // Must be called before using fast io macros #endif #define _READ(IO) bool(READ_BIT(FastIOPortMap[STM_PORT(digitalPinToPinName(IO))]->IDR, _BV32(STM_PIN(digitalPinToPinName(IO))))) -#define _TOGGLE(IO) (FastIOPortMap[STM_PORT(digitalPinToPinName(IO))]->ODR ^= _BV32(STM_PIN(digitalPinToPinName(IO)))) +#define _TOGGLE(IO) TBI32(FastIOPortMap[STM_PORT(digitalPinToPinName(IO))]->ODR, STM_PIN(digitalPinToPinName(IO))) #define _GET_MODE(IO) #define _SET_MODE(IO,M) pinMode(IO, M) diff --git a/Marlin/src/HAL/STM32/inc/Conditionals_adv.h b/Marlin/src/HAL/STM32/inc/Conditionals_adv.h index 5f1c4b16019d..451c94f25d1f 100644 --- a/Marlin/src/HAL/STM32/inc/Conditionals_adv.h +++ b/Marlin/src/HAL/STM32/inc/Conditionals_adv.h @@ -20,3 +20,16 @@ * */ #pragma once + +#if BOTH(SDSUPPORT, USBD_USE_CDC_MSC) && DISABLED(NO_SD_HOST_DRIVE) + #define HAS_SD_HOST_DRIVE 1 +#endif + +// Fix F_CPU not being a compile-time constant in STSTM32 framework +#ifdef BOARD_F_CPU + #undef F_CPU + #define F_CPU BOARD_F_CPU +#endif + +// The Sensitive Pins array is not optimizable +#define RUNTIME_ONLY_ANALOG_TO_DIGITAL diff --git a/Marlin/src/HAL/STM32/inc/SanityCheck.h b/Marlin/src/HAL/STM32/inc/SanityCheck.h index 30d0750d90e0..12ff2abec7ac 100644 --- a/Marlin/src/HAL/STM32/inc/SanityCheck.h +++ b/Marlin/src/HAL/STM32/inc/SanityCheck.h @@ -28,9 +28,6 @@ // #error "SPINDLE_LASER_PWM_PIN must use SERVO0, SERVO1 or SERVO3 connector" //#endif -#if ENABLED(FAST_PWM_FAN) || SPINDLE_LASER_FREQUENCY - #error "Features requiring Hardware PWM (FAST_PWM_FAN, SPINDLE_LASER_FREQUENCY) are not yet supported on STM32." -#endif #if ENABLED(SDCARD_EEPROM_EMULATION) && DISABLED(SDSUPPORT) #undef SDCARD_EEPROM_EMULATION // Avoid additional error noise @@ -50,7 +47,11 @@ #endif #if ENABLED(SERIAL_STATS_MAX_RX_QUEUED) - #error "SERIAL_STATS_MAX_RX_QUEUED is not supported on this platform." + #error "SERIAL_STATS_MAX_RX_QUEUED is not supported on STM32." #elif ENABLED(SERIAL_STATS_DROPPED_RX) - #error "SERIAL_STATS_DROPPED_RX is not supported on this platform." + #error "SERIAL_STATS_DROPPED_RX is not supported on STM32." +#endif + +#if ANY(TFT_COLOR_UI, TFT_LVGL_UI, TFT_CLASSIC_UI) && NOT_TARGET(STM32H7xx, STM32F4xx, STM32F1xx) + #error "TFT_COLOR_UI, TFT_LVGL_UI and TFT_CLASSIC_UI are currently only supported on STM32H7, STM32F4 and STM32F1 hardware." #endif diff --git a/Marlin/src/HAL/STM32/msc_sd.cpp b/Marlin/src/HAL/STM32/msc_sd.cpp new file mode 100644 index 000000000000..4f85af0d446a --- /dev/null +++ b/Marlin/src/HAL/STM32/msc_sd.cpp @@ -0,0 +1,130 @@ +/** + * Marlin 3D Printer Firmware + * + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2019 BigTreeTech [https://github.com/bigtreetech] + * + * 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. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../platforms.h" + +#ifdef HAL_STM32 + +#include "../../inc/MarlinConfigPre.h" + +#if HAS_SD_HOST_DRIVE + +#include "../shared/Marduino.h" +#include "msc_sd.h" +#include "usbd_core.h" + +#include "../../sd/cardreader.h" + +#include +#include + +#define BLOCK_SIZE 512 +#define PRODUCT_ID 0x29 + +class Sd2CardUSBMscHandler : public USBMscHandler { +public: + DiskIODriver* diskIODriver() { + #if ENABLED(MULTI_VOLUME) + #if SHARED_VOLUME_IS(SD_ONBOARD) + return &card.media_driver_sdcard; + #elif SHARED_VOLUME_IS(USB_FLASH_DRIVE) + return &card.media_driver_usbFlash; + #endif + #else + return card.diskIODriver(); + #endif + } + + bool GetCapacity(uint32_t *pBlockNum, uint16_t *pBlockSize) { + *pBlockNum = diskIODriver()->cardSize(); + *pBlockSize = BLOCK_SIZE; + return true; + } + + bool Write(uint8_t *pBuf, uint32_t blkAddr, uint16_t blkLen) { + auto sd2card = diskIODriver(); + // single block + if (blkLen == 1) { + watchdog_refresh(); + sd2card->writeBlock(blkAddr, pBuf); + return true; + } + + // multi block optimization + sd2card->writeStart(blkAddr, blkLen); + while (blkLen--) { + watchdog_refresh(); + sd2card->writeData(pBuf); + pBuf += BLOCK_SIZE; + } + sd2card->writeStop(); + return true; + } + + bool Read(uint8_t *pBuf, uint32_t blkAddr, uint16_t blkLen) { + auto sd2card = diskIODriver(); + // single block + if (blkLen == 1) { + watchdog_refresh(); + sd2card->readBlock(blkAddr, pBuf); + return true; + } + + // multi block optimization + sd2card->readStart(blkAddr); + while (blkLen--) { + watchdog_refresh(); + sd2card->readData(pBuf); + pBuf += BLOCK_SIZE; + } + sd2card->readStop(); + return true; + } + + bool IsReady() { + return diskIODriver()->isReady(); + } +}; + +Sd2CardUSBMscHandler usbMscHandler; + +/* USB Mass storage Standard Inquiry Data */ +uint8_t Marlin_STORAGE_Inquirydata[] = { /* 36 */ + /* LUN 0 */ + 0x00, + 0x80, + 0x02, + 0x02, + (STANDARD_INQUIRY_DATA_LEN - 5), + 0x00, + 0x00, + 0x00, + 'M', 'A', 'R', 'L', 'I', 'N', ' ', ' ', /* Manufacturer : 8 bytes */ + 'P', 'r', 'o', 'd', 'u', 'c', 't', ' ', /* Product : 16 Bytes */ + ' ', ' ', ' ', ' ', ' ', ' ', ' ', ' ', + '0', '.', '0', '1', /* Version : 4 Bytes */ +}; + +USBMscHandler *pSingleMscHandler = &usbMscHandler; + +void MSC_SD_init() { + USBDevice.end(); + delay(200); + USBDevice.registerMscHandlers(1, &pSingleMscHandler, Marlin_STORAGE_Inquirydata); + USBDevice.begin(); +} + +#endif // HAS_SD_HOST_DRIVE +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/msc_sd.h b/Marlin/src/HAL/STM32/msc_sd.h new file mode 100644 index 000000000000..a8e5349f7cd3 --- /dev/null +++ b/Marlin/src/HAL/STM32/msc_sd.h @@ -0,0 +1,18 @@ +/** + * Marlin 3D Printer Firmware + * + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2019 BigTreeTech [https://github.com/bigtreetech] + * + * 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. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +void MSC_SD_init(); diff --git a/Marlin/src/HAL/STM32/pinsDebug.h b/Marlin/src/HAL/STM32/pinsDebug.h index ec08e3fd753f..048f788e3d08 100644 --- a/Marlin/src/HAL/STM32/pinsDebug.h +++ b/Marlin/src/HAL/STM32/pinsDebug.h @@ -18,17 +18,247 @@ */ #pragma once -#if !(defined(NUM_DIGITAL_PINS) || defined(BOARD_NR_GPIO_PINS)) - #error "M43 not supported for this board" +#include + +#ifndef NUM_DIGITAL_PINS + // Only in ST's Arduino core (STM32duino, STM32Core) + #error "Expected NUM_DIGITAL_PINS not found" #endif -// Strange - STM32F4 comes to HAL_STM32 rather than HAL_STM32F4 for these files -#ifdef STM32F4 - #ifdef NUM_DIGITAL_PINS // Only in ST's Arduino core (STM32duino, STM32Core) - #include "pinsDebug_STM32duino.h" - #elif defined(BOARD_NR_GPIO_PINS) // Only in STM32GENERIC (Maple) - #include "pinsDebug_STM32GENERIC.h" +/** + * Life gets complicated if you want an easy to use 'M43 I' output (in port/pin order) + * because the variants in this platform do not always define all the I/O port/pins + * that a CPU has. + * + * VARIABLES: + * Ard_num - Arduino pin number - defined by the platform. It is used by digitalRead and + * digitalWrite commands and by M42. + * - does not contain port/pin info + * - is not in port/pin order + * - typically a variant will only assign Ard_num to port/pins that are actually used + * Index - M43 counter - only used to get Ard_num + * x - a parameter/argument used to search the pin_array to try to find a signal name + * associated with a Ard_num + * Port_pin - port number and pin number for use with CPU registers and printing reports + * + * Since M43 uses digitalRead and digitalWrite commands, only the Port_pins with an Ard_num + * are accessed and/or displayed. + * + * Three arrays are used. + * + * digitalPin[] is provided by the platform. It consists of the Port_pin numbers in + * Arduino pin number order. + * + * pin_array is a structure generated by the pins/pinsDebug.h header file. It is generated by + * the preprocessor. Only the signals associated with enabled options are in this table. + * It contains: + * - name of the signal + * - the Ard_num assigned by the pins_YOUR_BOARD.h file using the platform defines. + * EXAMPLE: "#define KILL_PIN PB1" results in Ard_num of 57. 57 is then used as the + * argument to digitalPinToPinName(IO) to get the Port_pin number + * - if it is a digital or analog signal. PWMs are considered digital here. + * + * pin_xref is a structure generated by this header file. It is generated by the + * preprocessor. It is in port/pin order. It contains just the port/pin numbers defined by the + * platform for this variant. + * - Ard_num + * - printable version of Port_pin + * + * Routines with an "x" as a parameter/argument are used to search the pin_array to try to + * find a signal name associated with a port/pin. + * + * NOTE - the Arduino pin number is what is used by the M42 command, NOT the port/pin for that + * signal. The Arduino pin number is listed by the M43 I command. + */ + +//////////////////////////////////////////////////////// +// +// make a list of the Arduino pin numbers in the Port/Pin order +// + +#define _PIN_ADD_2(NAME_ALPHA, ARDUINO_NUM) { {NAME_ALPHA}, ARDUINO_NUM }, +#define _PIN_ADD(NAME_ALPHA, ARDUINO_NUM) { NAME_ALPHA, ARDUINO_NUM }, +#define PIN_ADD(NAME) _PIN_ADD(#NAME, NAME) + +typedef struct { + char Port_pin_alpha[5]; + pin_t Ard_num; +} XrefInfo; + +const XrefInfo pin_xref[] PROGMEM = { + #include "pins_Xref.h" +}; + +//////////////////////////////////////////////////////////// + +#define MODE_PIN_INPUT 0 // Input mode (reset state) +#define MODE_PIN_OUTPUT 1 // General purpose output mode +#define MODE_PIN_ALT 2 // Alternate function mode +#define MODE_PIN_ANALOG 3 // Analog mode + +#define PIN_NUM(P) (P & 0x000F) +#define PIN_NUM_ALPHA_LEFT(P) (((P & 0x000F) < 10) ? ('0' + (P & 0x000F)) : '1') +#define PIN_NUM_ALPHA_RIGHT(P) (((P & 0x000F) > 9) ? ('0' + (P & 0x000F) - 10) : 0 ) +#define PORT_NUM(P) ((P >> 4) & 0x0007) +#define PORT_ALPHA(P) ('A' + (P >> 4)) + +/** + * Translation of routines & variables used by pinsDebug.h + */ +#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS +#define VALID_PIN(ANUM) ((ANUM) >= 0 && (ANUM) < NUMBER_PINS_TOTAL) +#define digitalRead_mod(Ard_num) extDigitalRead(Ard_num) // must use Arduino pin numbers when doing reads +#define PRINT_PIN(Q) +#define PRINT_PORT(ANUM) port_print(ANUM) +#define DIGITAL_PIN_TO_ANALOG_PIN(ANUM) -1 // will report analog pin number in the print port routine +#define GET_PIN_MAP_PIN_M43(Index) pin_xref[Index].Ard_num + +// x is a variable used to search pin_array +#define GET_ARRAY_IS_DIGITAL(x) ((bool) pin_array[x].is_digital) +#define GET_ARRAY_PIN(x) ((pin_t) pin_array[x].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 MULTI_NAME_PAD 33 // space needed to be pretty if not first name assigned to a pin + +#ifndef M43_NEVER_TOUCH + #define _M43_NEVER_TOUCH(Index) (Index >= 9 && Index <= 12) // SERIAL/USB pins: PA9(TX) PA10(RX) PA11(USB_DM) PA12(USB_DP) + #ifdef KILL_PIN + #define M43_NEVER_TOUCH(Index) m43_never_touch(Index) + + bool m43_never_touch(const pin_t Index) { + static pin_t M43_kill_index = -1; + if (M43_kill_index < 0) + for (M43_kill_index = 0; M43_kill_index < NUMBER_PINS_TOTAL; M43_kill_index++) + if (KILL_PIN == GET_PIN_MAP_PIN_M43(M43_kill_index)) break; + return _M43_NEVER_TOUCH(Index) || Index == M43_kill_index; // KILL_PIN and SERIAL/USB + } #else - #error "M43 not supported for this board" + #define M43_NEVER_TOUCH(Index) _M43_NEVER_TOUCH(Index) #endif #endif + +uint8_t get_pin_mode(const pin_t Ard_num) { + const PinName dp = digitalPinToPinName(Ard_num); + uint32_t ll_pin = STM_LL_GPIO_PIN(dp); + GPIO_TypeDef *port = get_GPIO_Port(STM_PORT(dp)); + uint32_t mode = LL_GPIO_GetPinMode(port, ll_pin); + switch (mode) { + case LL_GPIO_MODE_ANALOG: return MODE_PIN_ANALOG; + case LL_GPIO_MODE_INPUT: return MODE_PIN_INPUT; + case LL_GPIO_MODE_OUTPUT: return MODE_PIN_OUTPUT; + case LL_GPIO_MODE_ALTERNATE: return MODE_PIN_ALT; + TERN_(STM32F1xx, case LL_GPIO_MODE_FLOATING:) + default: return 0; + } +} + +bool GET_PINMODE(const pin_t Ard_num) { + const uint8_t pin_mode = get_pin_mode(Ard_num); + return pin_mode == MODE_PIN_OUTPUT || pin_mode == MODE_PIN_ALT; // assume all alt definitions are PWM +} + +int8_t digital_pin_to_analog_pin(pin_t Ard_num) { + Ard_num -= NUM_ANALOG_FIRST; + return (Ard_num >= 0 && Ard_num < NUM_ANALOG_INPUTS) ? Ard_num : -1; +} + +bool IS_ANALOG(const pin_t Ard_num) { + return get_pin_mode(Ard_num) == MODE_PIN_ANALOG; +} + +bool is_digital(const pin_t x) { + const uint8_t pin_mode = get_pin_mode(pin_array[x].pin); + return pin_mode == MODE_PIN_INPUT || pin_mode == MODE_PIN_OUTPUT; +} + +void port_print(const pin_t Ard_num) { + char buffer[16]; + pin_t Index; + for (Index = 0; Index < NUMBER_PINS_TOTAL; Index++) + if (Ard_num == GET_PIN_MAP_PIN_M43(Index)) break; + + const char * ppa = pin_xref[Index].Port_pin_alpha; + sprintf_P(buffer, PSTR("%s"), ppa); + SERIAL_ECHO(buffer); + if (ppa[3] == '\0') SERIAL_CHAR(' '); + + // print analog pin number + const int8_t Port_pin = digital_pin_to_analog_pin(Ard_num); + if (Port_pin >= 0) { + sprintf_P(buffer, PSTR(" (A%d) "), Port_pin); + SERIAL_ECHO(buffer); + if (Port_pin < 10) SERIAL_CHAR(' '); + } + else + SERIAL_ECHO_SP(7); + + // Print number to be used with M42 + sprintf_P(buffer, PSTR(" M42 P%d "), Ard_num); + SERIAL_ECHO(buffer); + if (Ard_num < 10) SERIAL_CHAR(' '); + if (Ard_num < 100) SERIAL_CHAR(' '); +} + +bool pwm_status(const pin_t Ard_num) { + return get_pin_mode(Ard_num) == MODE_PIN_ALT; +} + +void pwm_details(const pin_t Ard_num) { + #ifndef STM32F1xx + if (pwm_status(Ard_num)) { + uint32_t alt_all = 0; + const PinName dp = digitalPinToPinName(Ard_num); + pin_t pin_number = uint8_t(PIN_NUM(dp)); + const bool over_7 = pin_number >= 8; + const uint8_t ind = over_7 ? 1 : 0; + switch (PORT_ALPHA(dp)) { // get alt function + case 'A' : alt_all = GPIOA->AFR[ind]; break; + case 'B' : alt_all = GPIOB->AFR[ind]; break; + case 'C' : alt_all = GPIOC->AFR[ind]; break; + case 'D' : alt_all = GPIOD->AFR[ind]; break; + #ifdef PE_0 + case 'E' : alt_all = GPIOE->AFR[ind]; break; + #elif defined (PF_0) + case 'F' : alt_all = GPIOF->AFR[ind]; break; + #elif defined (PG_0) + case 'G' : alt_all = GPIOG->AFR[ind]; break; + #elif defined (PH_0) + case 'H' : alt_all = GPIOH->AFR[ind]; break; + #elif defined (PI_0) + case 'I' : alt_all = GPIOI->AFR[ind]; break; + #elif defined (PJ_0) + case 'J' : alt_all = GPIOJ->AFR[ind]; break; + #elif defined (PK_0) + case 'K' : alt_all = GPIOK->AFR[ind]; break; + #elif defined (PL_0) + case 'L' : alt_all = GPIOL->AFR[ind]; break; + #endif + } + if (over_7) pin_number -= 8; + + uint8_t alt_func = (alt_all >> (4 * pin_number)) & 0x0F; + SERIAL_ECHOPAIR("Alt Function: ", alt_func); + if (alt_func < 10) SERIAL_CHAR(' '); + SERIAL_ECHOPGM(" - "); + switch (alt_func) { + case 0 : SERIAL_ECHOPGM("system (misc. I/O)"); break; + case 1 : SERIAL_ECHOPGM("TIM1/TIM2 (probably PWM)"); break; + case 2 : SERIAL_ECHOPGM("TIM3..5 (probably PWM)"); break; + case 3 : SERIAL_ECHOPGM("TIM8..11 (probably PWM)"); break; + case 4 : SERIAL_ECHOPGM("I2C1..3"); break; + case 5 : SERIAL_ECHOPGM("SPI1/SPI2"); break; + case 6 : SERIAL_ECHOPGM("SPI3"); break; + case 7 : SERIAL_ECHOPGM("USART1..3"); break; + case 8 : SERIAL_ECHOPGM("USART4..6"); break; + case 9 : SERIAL_ECHOPGM("CAN1/CAN2, TIM12..14 (probably PWM)"); break; + case 10 : SERIAL_ECHOPGM("OTG"); break; + case 11 : SERIAL_ECHOPGM("ETH"); break; + case 12 : SERIAL_ECHOPGM("FSMC, SDIO, OTG"); break; + case 13 : SERIAL_ECHOPGM("DCMI"); break; + case 14 : SERIAL_ECHOPGM("unused (shouldn't see this)"); break; + case 15 : SERIAL_ECHOPGM("EVENTOUT"); break; + } + } + #else + // TODO: F1 doesn't support changing pins function, so we need to check the function of the PIN and if it's enabled + #endif +} // pwm_details diff --git a/Marlin/src/HAL/STM32/pinsDebug_STM32GENERIC.h b/Marlin/src/HAL/STM32/pinsDebug_STM32GENERIC.h deleted file mode 100644 index 9069d9f7bd8a..000000000000 --- a/Marlin/src/HAL/STM32/pinsDebug_STM32GENERIC.h +++ /dev/null @@ -1,125 +0,0 @@ -/** - * Marlin 3D Printer Firmware - * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ -#pragma once - -/** - * Support routines for STM32GENERIC (Maple) - */ - -/** - * Translation of routines & variables used by pinsDebug.h - */ - -#ifdef BOARD_NR_GPIO_PINS // Only in STM32GENERIC (Maple) - -#ifdef __STM32F1__ - #include "../STM32F1/fastio.h" -#elif defined(STM32F4) || defined(STM32F7) - #include "../STM32_F4_F7/fastio.h" -#else - #include "fastio.h" -#endif - -extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS]; - -#define NUM_DIGITAL_PINS 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_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 - -// pins that will cause hang/reset/disconnect in M43 Toggle and Watch utilities -#ifndef M43_NEVER_TOUCH - #define M43_NEVER_TOUCH(Q) (Q >= 9 && Q <= 12) // SERIAL/USB pins PA9(TX) PA10(RX) -#endif - -static inline int8_t get_pin_mode(pin_t pin) { - return VALID_PIN(pin) ? _GET_MODE(pin) : -1; -} - -static inline pin_t DIGITAL_PIN_TO_ANALOG_PIN(pin_t pin) { - if (!VALID_PIN(pin)) return -1; - int8_t adc_channel = int8_t(PIN_MAP[pin].adc_channel); - #ifdef NUM_ANALOG_INPUTS - if (adc_channel >= NUM_ANALOG_INPUTS) adc_channel = ADCx; - #endif - return pin_t(adc_channel); -} - -static inline bool IS_ANALOG(pin_t pin) { - if (!VALID_PIN(pin)) return false; - if (PIN_MAP[pin].adc_channel != ADCx) { - #ifdef NUM_ANALOG_INPUTS - if (PIN_MAP[pin].adc_channel >= NUM_ANALOG_INPUTS) return false; - #endif - return _GET_MODE(pin) == GPIO_INPUT_ANALOG && !M43_NEVER_TOUCH(pin); - } - return false; -} - -static inline bool GET_PINMODE(const pin_t pin) { - return VALID_PIN(pin) && !IS_INPUT(pin); -} - -static inline bool GET_ARRAY_IS_DIGITAL(const int16_t array_pin) { - const pin_t pin = GET_ARRAY_PIN(array_pin); - return (!IS_ANALOG(pin) - #ifdef NUM_ANALOG_INPUTS - || PIN_MAP[pin].adc_channel >= NUM_ANALOG_INPUTS - #endif - ); -} - -#include "../../inc/MarlinConfig.h" // Allow pins/pins.h to set density - -static inline 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) - tdev == &timer8 ? '8' : - tdev == &timer5 ? '5' : - #endif - tdev == &timer4 ? '4' : - tdev == &timer3 ? '3' : - tdev == &timer2 ? '2' : - tdev == &timer1 ? '1' : '?' - ); - char buffer[10]; - sprintf_P(buffer, PSTR(" TIM%c CH%c"), num, ('0' + channel)); - SERIAL_ECHO(buffer); - } -} - -static inline void print_port(pin_t pin) { - const char port = 'A' + char(pin >> 4); // pin div 16 - const int16_t gbit = PIN_MAP[pin].gpio_bit; - char buffer[8]; - sprintf_P(buffer, PSTR("P%c%hd "), port, gbit); - if (gbit < 10) SERIAL_CHAR(' '); - SERIAL_ECHO(buffer); -} - -#endif // BOARD_NR_GPIO_PINS diff --git a/Marlin/src/HAL/STM32/pinsDebug_STM32duino.h b/Marlin/src/HAL/STM32/pinsDebug_STM32duino.h deleted file mode 100644 index 71480153a717..000000000000 --- a/Marlin/src/HAL/STM32/pinsDebug_STM32duino.h +++ /dev/null @@ -1,273 +0,0 @@ -/** - * Marlin 3D Printer Firmware - * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ -#pragma once - -#include - -#ifdef NUM_DIGITAL_PINS // Only in ST's Arduino core (STM32duino, STM32Core) - -/** - * Life gets complicated if you want an easy to use 'M43 I' output (in port/pin order) - * because the variants in this platform do not always define all the I/O port/pins - * that a CPU has. - * - * VARIABLES: - * Ard_num - Arduino pin number - defined by the platform. It is used by digitalRead and - * digitalWrite commands and by M42. - * - does not contain port/pin info - * - is not in port/pin order - * - typically a variant will only assign Ard_num to port/pins that are actually used - * Index - M43 counter - only used to get Ard_num - * x - a parameter/argument used to search the pin_array to try to find a signal name - * associated with a Ard_num - * Port_pin - port number and pin number for use with CPU registers and printing reports - * - * Since M43 uses digitalRead and digitalWrite commands, only the Port_pins with an Ard_num - * are accessed and/or displayed. - * - * Three arrays are used. - * - * digitalPin[] is provided by the platform. It consists of the Port_pin numbers in - * Arduino pin number order. - * - * pin_array is a structure generated by the pins/pinsDebug.h header file. It is generated by - * the preprocessor. Only the signals associated with enabled options are in this table. - * It contains: - * - name of the signal - * - the Ard_num assigned by the pins_YOUR_BOARD.h file using the platform defines. - * EXAMPLE: "#define KILL_PIN PB1" results in Ard_num of 57. 57 is then used as the - * argument to digitalPinToPinName(IO) to get the Port_pin number - * - if it is a digital or analog signal. PWMs are considered digital here. - * - * pin_xref is a structure generated by this header file. It is generated by the - * preprocessor. It is in port/pin order. It contains just the port/pin numbers defined by the - * platform for this variant. - * - Ard_num - * - printable version of Port_pin - * - * Routines with an "x" as a parameter/argument are used to search the pin_array to try to - * find a signal name associated with a port/pin. - * - * NOTE - the Arduino pin number is what is used by the M42 command, NOT the port/pin for that - * signal. The Arduino pin number is listed by the M43 I command. - */ - -//////////////////////////////////////////////////////// -// -// make a list of the Arduino pin numbers in the Port/Pin order -// - -#define _PIN_ADD_2(NAME_ALPHA, ARDUINO_NUM) { {NAME_ALPHA}, ARDUINO_NUM }, -#define _PIN_ADD(NAME_ALPHA, ARDUINO_NUM) { NAME_ALPHA, ARDUINO_NUM }, -#define PIN_ADD(NAME) _PIN_ADD(#NAME, NAME) - -typedef struct { - char Port_pin_alpha[5]; - pin_t Ard_num; -} XrefInfo; - -const XrefInfo pin_xref[] PROGMEM = { - #include "pins_Xref.h" -}; - -//////////////////////////////////////////////////////////// - -#define MODE_PIN_INPUT 0 // Input mode (reset state) -#define MODE_PIN_OUTPUT 1 // General purpose output mode -#define MODE_PIN_ALT 2 // Alternate function mode -#define MODE_PIN_ANALOG 3 // Analog mode - -#define PIN_NUM(P) (P & 0x000F) -#define PIN_NUM_ALPHA_LEFT(P) (((P & 0x000F) < 10) ? ('0' + (P & 0x000F)) : '1') -#define PIN_NUM_ALPHA_RIGHT(P) (((P & 0x000F) > 9) ? ('0' + (P & 0x000F) - 10) : 0 ) -#define PORT_NUM(P) ((P >> 4) & 0x0007) -#define PORT_ALPHA(P) ('A' + (P >> 4)) - -/** - * Translation of routines & variables used by pinsDebug.h - */ -#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS -#define VALID_PIN(ANUM) ((ANUM) >= 0 && (ANUM) < NUMBER_PINS_TOTAL) -#define digitalRead_mod(Ard_num) extDigitalRead(Ard_num) // must use Arduino pin numbers when doing reads -#define PRINT_PIN(Q) -#define PRINT_PORT(ANUM) port_print(ANUM) -#define DIGITAL_PIN_TO_ANALOG_PIN(ANUM) -1 // will report analog pin number in the print port routine -#define GET_PIN_MAP_PIN_M43(Index) pin_xref[Index].Ard_num - -// x is a variable used to search pin_array -#define GET_ARRAY_IS_DIGITAL(x) ((bool) pin_array[x].is_digital) -#define GET_ARRAY_PIN(x) ((pin_t) pin_array[x].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 MULTI_NAME_PAD 33 // space needed to be pretty if not first name assigned to a pin - -#ifndef M43_NEVER_TOUCH - #define _M43_NEVER_TOUCH(Index) (Index >= 9 && Index <= 12) // SERIAL/USB pins: PA9(TX) PA10(RX) PA11(USB_DM) PA12(USB_DP) - #ifdef KILL_PIN - #define M43_NEVER_TOUCH(Index) m43_never_touch(Index) - - bool m43_never_touch(const pin_t Index) { - static pin_t M43_kill_index = -1; - if (M43_kill_index < 0) - for (M43_kill_index = 0; M43_kill_index < NUMBER_PINS_TOTAL; M43_kill_index++) - if (KILL_PIN == GET_PIN_MAP_PIN_M43(M43_kill_index)) break; - return _M43_NEVER_TOUCH(Index) || Index == M43_kill_index; // KILL_PIN and SERIAL/USB - } - #else - #define M43_NEVER_TOUCH(Index) _M43_NEVER_TOUCH(Index) - #endif -#endif - -uint8_t get_pin_mode(const pin_t Ard_num) { - uint32_t mode_all = 0; - const PinName dp = digitalPinToPinName(Ard_num); - switch (PORT_ALPHA(dp)) { - case 'A' : mode_all = GPIOA->MODER; break; - case 'B' : mode_all = GPIOB->MODER; break; - case 'C' : mode_all = GPIOC->MODER; break; - case 'D' : mode_all = GPIOD->MODER; break; - #ifdef PE_0 - case 'E' : mode_all = GPIOE->MODER; break; - #elif defined(PF_0) - case 'F' : mode_all = GPIOF->MODER; break; - #elif defined(PG_0) - case 'G' : mode_all = GPIOG->MODER; break; - #elif defined(PH_0) - case 'H' : mode_all = GPIOH->MODER; break; - #elif defined(PI_0) - case 'I' : mode_all = GPIOI->MODER; break; - #elif defined(PJ_0) - case 'J' : mode_all = GPIOJ->MODER; break; - #elif defined(PK_0) - case 'K' : mode_all = GPIOK->MODER; break; - #elif defined(PL_0) - case 'L' : mode_all = GPIOL->MODER; break; - #endif - } - return (mode_all >> (2 * uint8_t(PIN_NUM(dp)))) & 0x03; -} - -bool GET_PINMODE(const pin_t Ard_num) { - const uint8_t pin_mode = get_pin_mode(Ard_num); - return pin_mode == MODE_PIN_OUTPUT || pin_mode == MODE_PIN_ALT; // assume all alt definitions are PWM -} - -int8_t digital_pin_to_analog_pin(pin_t Ard_num) { - Ard_num -= NUM_ANALOG_FIRST; - return (Ard_num >= 0 && Ard_num < NUM_ANALOG_INPUTS) ? Ard_num : -1; -} - -bool IS_ANALOG(const pin_t Ard_num) { - return get_pin_mode(Ard_num) == MODE_PIN_ANALOG; -} - -bool is_digital(const pin_t x) { - const uint8_t pin_mode = get_pin_mode(pin_array[x].pin); - return pin_mode == MODE_PIN_INPUT || pin_mode == MODE_PIN_OUTPUT; -} - -void port_print(const pin_t Ard_num) { - char buffer[16]; - pin_t Index; - for (Index = 0; Index < NUMBER_PINS_TOTAL; Index++) - if (Ard_num == GET_PIN_MAP_PIN_M43(Index)) break; - - const char * ppa = pin_xref[Index].Port_pin_alpha; - sprintf_P(buffer, PSTR("%s"), ppa); - SERIAL_ECHO(buffer); - if (ppa[3] == '\0') SERIAL_CHAR(' '); - - // print analog pin number - const int8_t Port_pin = digital_pin_to_analog_pin(Ard_num); - if (Port_pin >= 0) { - sprintf_P(buffer, PSTR(" (A%d) "), Port_pin); - SERIAL_ECHO(buffer); - if (Port_pin < 10) SERIAL_CHAR(' '); - } - else - SERIAL_ECHO_SP(7); - - // Print number to be used with M42 - sprintf_P(buffer, PSTR(" M42 P%d "), Ard_num); - SERIAL_ECHO(buffer); - if (Ard_num < 10) SERIAL_CHAR(' '); - if (Ard_num < 100) SERIAL_CHAR(' '); -} - -bool pwm_status(const pin_t Ard_num) { - return get_pin_mode(Ard_num) == MODE_PIN_ALT; -} - -void pwm_details(const pin_t Ard_num) { - if (pwm_status(Ard_num)) { - uint32_t alt_all = 0; - const PinName dp = digitalPinToPinName(Ard_num); - pin_t pin_number = uint8_t(PIN_NUM(dp)); - const bool over_7 = pin_number >= 8; - const uint8_t ind = over_7 ? 1 : 0; - switch (PORT_ALPHA(dp)) { // get alt function - case 'A' : alt_all = GPIOA->AFR[ind]; break; - case 'B' : alt_all = GPIOB->AFR[ind]; break; - case 'C' : alt_all = GPIOC->AFR[ind]; break; - case 'D' : alt_all = GPIOD->AFR[ind]; break; - #ifdef PE_0 - case 'E' : alt_all = GPIOE->AFR[ind]; break; - #elif defined (PF_0) - case 'F' : alt_all = GPIOF->AFR[ind]; break; - #elif defined (PG_0) - case 'G' : alt_all = GPIOG->AFR[ind]; break; - #elif defined (PH_0) - case 'H' : alt_all = GPIOH->AFR[ind]; break; - #elif defined (PI_0) - case 'I' : alt_all = GPIOI->AFR[ind]; break; - #elif defined (PJ_0) - case 'J' : alt_all = GPIOJ->AFR[ind]; break; - #elif defined (PK_0) - case 'K' : alt_all = GPIOK->AFR[ind]; break; - #elif defined (PL_0) - case 'L' : alt_all = GPIOL->AFR[ind]; break; - #endif - } - if (over_7) pin_number -= 8; - - uint8_t alt_func = (alt_all >> (4 * pin_number)) & 0x0F; - SERIAL_ECHOPAIR("Alt Function: ", alt_func); - if (alt_func < 10) SERIAL_CHAR(' '); - SERIAL_ECHOPGM(" - "); - switch (alt_func) { - case 0 : SERIAL_ECHOPGM("system (misc. I/O)"); break; - case 1 : SERIAL_ECHOPGM("TIM1/TIM2 (probably PWM)"); break; - case 2 : SERIAL_ECHOPGM("TIM3..5 (probably PWM)"); break; - case 3 : SERIAL_ECHOPGM("TIM8..11 (probably PWM)"); break; - case 4 : SERIAL_ECHOPGM("I2C1..3"); break; - case 5 : SERIAL_ECHOPGM("SPI1/SPI2"); break; - case 6 : SERIAL_ECHOPGM("SPI3"); break; - case 7 : SERIAL_ECHOPGM("USART1..3"); break; - case 8 : SERIAL_ECHOPGM("USART4..6"); break; - case 9 : SERIAL_ECHOPGM("CAN1/CAN2, TIM12..14 (probably PWM)"); break; - case 10 : SERIAL_ECHOPGM("OTG"); break; - case 11 : SERIAL_ECHOPGM("ETH"); break; - case 12 : SERIAL_ECHOPGM("FSMC, SDIO, OTG"); break; - case 13 : SERIAL_ECHOPGM("DCMI"); break; - case 14 : SERIAL_ECHOPGM("unused (shouldn't see this)"); break; - case 15 : SERIAL_ECHOPGM("EVENTOUT"); break; - } - } -} // pwm_details - -#endif // NUM_DIGITAL_PINS diff --git a/Marlin/src/HAL/STM32/spi_pins.h b/Marlin/src/HAL/STM32/spi_pins.h index 176e2a7b2063..e2052c5c7704 100644 --- a/Marlin/src/HAL/STM32/spi_pins.h +++ b/Marlin/src/HAL/STM32/spi_pins.h @@ -21,15 +21,15 @@ /** * Define SPI Pins: SCK, MISO, MOSI, SS */ -#ifndef SCK_PIN - #define SCK_PIN PIN_SPI_SCK +#ifndef SD_SCK_PIN + #define SD_SCK_PIN PIN_SPI_SCK #endif -#ifndef MISO_PIN - #define MISO_PIN PIN_SPI_MISO +#ifndef SD_MISO_PIN + #define SD_MISO_PIN PIN_SPI_MISO #endif -#ifndef MOSI_PIN - #define MOSI_PIN PIN_SPI_MOSI +#ifndef SD_MOSI_PIN + #define SD_MOSI_PIN PIN_SPI_MOSI #endif -#ifndef SS_PIN - #define SS_PIN PIN_SPI_SS +#ifndef SD_SS_PIN + #define SD_SS_PIN PIN_SPI_SS #endif diff --git a/Marlin/src/HAL/STM32/tft/gt911.cpp b/Marlin/src/HAL/STM32/tft/gt911.cpp new file mode 100644 index 000000000000..92e14edb2057 --- /dev/null +++ b/Marlin/src/HAL/STM32/tft/gt911.cpp @@ -0,0 +1,204 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../platforms.h" + +#ifdef HAL_STM32 + +#include "../../../inc/MarlinConfig.h" + +#if ENABLED(TFT_TOUCH_DEVICE_GT911) + +#include "gt911.h" +#include "pinconfig.h" + +SW_IIC::SW_IIC(uint16_t sda, uint16_t scl) { + scl_pin = scl; + sda_pin = sda; +} + +// Software I2C hardware io init +void SW_IIC::init() { + OUT_WRITE(scl_pin, HIGH); + OUT_WRITE(sda_pin, HIGH); +} + +// Software I2C start signal +void SW_IIC::start() { + write_sda(HIGH); // SDA = 1 + write_scl(HIGH); // SCL = 1 + iic_delay(2); + write_sda(LOW); // SDA = 0 + iic_delay(1); + write_scl(LOW); // SCL = 0 // keep SCL low, avoid false stop caused by level jump caused by SDA switching IN/OUT +} + +// Software I2C stop signal +void SW_IIC::stop() { + write_scl(LOW); // SCL = 0 + iic_delay(2); + write_sda(LOW); // SDA = 0 + iic_delay(2); + write_scl(HIGH); // SCL = 1 + iic_delay(2); + write_sda(HIGH); // SDA = 1 +} + +// Software I2C sends ACK or NACK signal +void SW_IIC::send_ack(bool ack) { + write_sda(ack ? LOW : HIGH); // SDA = !ack + iic_delay(2); + write_scl(HIGH); // SCL = 1 + iic_delay(2); + write_scl(LOW); // SCL = 0 +} + +// Software I2C read ACK or NACK signal +bool SW_IIC::read_ack() { + bool error = 0; + set_sda_in(); + + iic_delay(2); + + write_scl(HIGH); // SCL = 1 + error = read_sda(); + + iic_delay(2); + + write_scl(LOW); // SCL = 0 + + set_sda_out(); + return error; +} + +void SW_IIC::send_byte(uint8_t txd) { + LOOP_L_N(i, 8) { + write_sda(txd & 0x80); // write data bit + txd <<= 1; + iic_delay(1); + write_scl(HIGH); // SCL = 1 + iic_delay(2); + write_scl(LOW); // SCL = 0 + iic_delay(1); + } + + read_ack(); // wait ack +} + +uint8_t SW_IIC::read_byte(bool ack) { + uint8_t data = 0; + + set_sda_in(); + LOOP_L_N(i, 8) { + write_scl(HIGH); // SCL = 1 + iic_delay(1); + data <<= 1; + if (read_sda()) data++; + write_scl(LOW); // SCL = 0 + iic_delay(2); + } + set_sda_out(); + + send_ack(ack); + + return data; +} + +GT911_REG_MAP GT911::reg; +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 + 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 + sw_iic.send_byte(w_data[i]); + } + sw_iic.stop(); +} + +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 + uint8_t r = (reg >> (8 * (reg_len - 1 - i))) & 0xFF; + sw_iic.send_byte(r); + } + + sw_iic.start(); + sw_iic.send_byte(gt911_slave_address + 1); // Set read mode + + LOOP_L_N(i, r_len) { + r_data[i] = sw_iic.read_byte(1); // Read data from reg + } + sw_iic.stop(); +} + +void GT911::Init() { + OUT_WRITE(GT911_RST_PIN, LOW); + OUT_WRITE(GT911_INT_PIN, LOW); + delay(20); + WRITE(GT911_RST_PIN, HIGH); + SET_INPUT(GT911_INT_PIN); + + sw_iic.init(); + + uint8_t clear_reg = 0x0000; + write_reg(0x814E, 2, &clear_reg, 2); // Reset to 0 for start +} + +bool GT911::getFirstTouchPoint(int16_t *x, int16_t *y) { + read_reg(0x814E, 2, ®.REG.status, 1); + + if (reg.REG.status & 0x80) { + uint8_t clear_reg = 0x00; + write_reg(0x814E, 2, &clear_reg, 1); // Reset to 0 for start + read_reg(0x8150, 2, reg.map + 2, 8 * (reg.REG.status & 0x0F)); + + // First touch point + *x = ((reg.REG.point[0].xh & 0x0F) << 8) | reg.REG.point[0].xl; + *y = ((reg.REG.point[0].yh & 0x0F) << 8) | reg.REG.point[0].yl; + return true; + } + return false; +} + +bool GT911::getPoint(int16_t *x, int16_t *y) { + static bool touched = 0; + static int16_t read_x = 0, read_y = 0; + static millis_t next_time = 0; + + if (ELAPSED(millis(), next_time)) { + touched = getFirstTouchPoint(&read_x, &read_y); + next_time = millis() + 20; + } + + *x = read_x; + *y = read_y; + return touched; +} + +#endif // TFT_TOUCH_DEVICE_GT911 +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/tft/gt911.h b/Marlin/src/HAL/STM32/tft/gt911.h new file mode 100644 index 000000000000..752a554d98ed --- /dev/null +++ b/Marlin/src/HAL/STM32/tft/gt911.h @@ -0,0 +1,120 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include "../../../inc/MarlinConfig.h" + +#define GT911_SLAVE_ADDRESS 0xBA + +#if !PIN_EXISTS(GT911_RST) + #error "GT911_RST_PIN is not defined." +#elif !PIN_EXISTS(GT911_INT) + #error "GT911_INT_PIN is not defined." +#elif !PIN_EXISTS(GT911_SW_I2C_SCL) + #error "GT911_SW_I2C_SCL_PIN is not defined." +#elif !PIN_EXISTS(GT911_SW_I2C_SDA) + #error "GT911_SW_I2C_SDA_PIN is not defined." +#endif + +class SW_IIC { + private: + uint16_t scl_pin; + uint16_t sda_pin; + void write_scl(bool level) + { + WRITE(scl_pin, level); + } + void write_sda(bool level) + { + WRITE(sda_pin, level); + } + bool read_sda() + { + return READ(sda_pin); + } + void set_sda_out() + { + SET_OUTPUT(sda_pin); + } + void set_sda_in() + { + SET_INPUT_PULLUP(sda_pin); + } + static void iic_delay(uint8_t t) + { + delayMicroseconds(t); + } + + public: + SW_IIC(uint16_t sda, uint16_t scl); + // setSCL/SDA have to be called before begin() + void setSCL(uint16_t scl) + { + scl_pin = scl; + }; + void setSDA(uint16_t sda) + { + sda_pin = sda; + }; + void init(); // Initialize the IO port of IIC + void start(); // Send IIC start signal + void stop(); // Send IIC stop signal + void send_byte(uint8_t txd); // IIC sends a byte + uint8_t read_byte(bool ack); // IIC reads a byte + void send_ack(bool ack); // IIC sends ACK or NACK signal + bool read_ack(); +}; + +typedef struct __attribute__((__packed__)) { + uint8_t xl; + uint8_t xh; + uint8_t yl; + uint8_t yh; + uint8_t sizel; + uint8_t sizeh; + uint8_t reserved; + uint8_t track_id; +} GT911_POINT; + +typedef union __attribute__((__packed__)) { + uint8_t map[42]; + struct { + uint8_t status; // 0x814E + uint8_t track_id; // 0x814F + + GT911_POINT point[5]; // [0]:0x8150 - 0x8157 / [1]:0x8158 - 0x815F / [2]:0x8160 - 0x8167 / [3]:0x8168 - 0x816F / [4]:0x8170 - 0x8177 + } REG; +} GT911_REG_MAP; + +class GT911 { + private: + static const uint8_t gt911_slave_address = GT911_SLAVE_ADDRESS; + static GT911_REG_MAP reg; + static SW_IIC sw_iic; + static void write_reg(uint16_t reg, uint8_t reg_len, uint8_t* w_data, uint8_t w_len); + static void read_reg(uint16_t reg, uint8_t reg_len, uint8_t* r_data, uint8_t r_len); + + public: + static void Init(); + static bool getFirstTouchPoint(int16_t *x, int16_t *y); + static bool getPoint(int16_t *x, int16_t *y); +}; diff --git a/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp b/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp index 3a080d5e271e..dacf533224fc 100644 --- a/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp +++ b/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp @@ -19,6 +19,9 @@ * along with this program. If not, see . * */ +#include "../../platforms.h" + +#ifdef HAL_STM32 #include "../../../inc/MarlinConfig.h" @@ -33,27 +36,18 @@ LCD_CONTROLLER_TypeDef *TFT_FSMC::LCD; void TFT_FSMC::Init() { uint32_t controllerAddress; - - #if PIN_EXISTS(TFT_RESET) - OUT_WRITE(TFT_RESET_PIN, HIGH); - HAL_Delay(100); - #endif - - #if PIN_EXISTS(TFT_BACKLIGHT) - OUT_WRITE(TFT_BACKLIGHT_PIN, HIGH); - #endif - FSMC_NORSRAM_TimingTypeDef Timing, ExtTiming; uint32_t NSBank = (uint32_t)pinmap_peripheral(digitalPinToPinName(TFT_CS_PIN), PinMap_FSMC_CS); + // Perform the SRAM1 memory initialization sequence SRAMx.Instance = FSMC_NORSRAM_DEVICE; SRAMx.Extended = FSMC_NORSRAM_EXTENDED_DEVICE; - /* SRAMx.Init */ + // SRAMx.Init SRAMx.Init.NSBank = NSBank; SRAMx.Init.DataAddressMux = FSMC_DATA_ADDRESS_MUX_DISABLE; SRAMx.Init.MemoryType = FSMC_MEMORY_TYPE_SRAM; - SRAMx.Init.MemoryDataWidth = FSMC_NORSRAM_MEM_BUS_WIDTH_16; + SRAMx.Init.MemoryDataWidth = TERN(TFT_INTERFACE_FSMC_8BIT, FSMC_NORSRAM_MEM_BUS_WIDTH_8, FSMC_NORSRAM_MEM_BUS_WIDTH_16); SRAMx.Init.BurstAccessMode = FSMC_BURST_ACCESS_MODE_DISABLE; SRAMx.Init.WaitSignalPolarity = FSMC_WAIT_SIGNAL_POLARITY_LOW; SRAMx.Init.WrapMode = FSMC_WRAP_MODE_DISABLE; @@ -66,8 +60,8 @@ void TFT_FSMC::Init() { #ifdef STM32F4xx SRAMx.Init.PageSize = FSMC_PAGE_SIZE_NONE; #endif - /* Read Timing - relatively slow to ensure ID information is correctly read from TFT controller */ - /* Can be decreases from 15-15-24 to 4-4-8 with risk of stability loss */ + // Read Timing - relatively slow to ensure ID information is correctly read from TFT controller + // Can be decreases from 15-15-24 to 4-4-8 with risk of stability loss Timing.AddressSetupTime = 15; Timing.AddressHoldTime = 15; Timing.DataSetupTime = 24; @@ -75,8 +69,8 @@ void TFT_FSMC::Init() { Timing.CLKDivision = 16; Timing.DataLatency = 17; Timing.AccessMode = FSMC_ACCESS_MODE_A; - /* Write Timing */ - /* Can be decreases from 8-15-8 to 0-0-1 with risk of stability loss */ + // Write Timing + // Can be decreases from 8-15-8 to 0-0-1 with risk of stability loss ExtTiming.AddressSetupTime = 8; ExtTiming.AddressHoldTime = 15; ExtTiming.DataSetupTime = 8; @@ -130,7 +124,7 @@ void TFT_FSMC::Init() { uint32_t TFT_FSMC::GetID() { uint32_t id; - WriteReg(0x0000); + WriteReg(0); id = LCD->RAM; if (id == 0) @@ -140,41 +134,40 @@ uint32_t TFT_FSMC::GetID() { return id; } - uint32_t TFT_FSMC::ReadID(uint16_t Reg) { - uint32_t id; - WriteReg(Reg); - id = LCD->RAM; // dummy read - id = Reg << 24; - id |= (LCD->RAM & 0x00FF) << 16; - id |= (LCD->RAM & 0x00FF) << 8; - id |= LCD->RAM & 0x00FF; - return id; - } +uint32_t TFT_FSMC::ReadID(tft_data_t Reg) { + uint32_t id; + WriteReg(Reg); + id = LCD->RAM; // dummy read + id = Reg << 24; + id |= (LCD->RAM & 0x00FF) << 16; + id |= (LCD->RAM & 0x00FF) << 8; + id |= LCD->RAM & 0x00FF; + return id; +} bool TFT_FSMC::isBusy() { - if (__IS_DMA_ENABLED(&DMAtx)) + #if defined(STM32F1xx) + volatile bool dmaEnabled = (DMAtx.Instance->CCR & DMA_CCR_EN) != RESET; + #elif defined(STM32F4xx) + volatile bool dmaEnabled = DMAtx.Instance->CR & DMA_SxCR_EN; + #endif + if (dmaEnabled) { if (__HAL_DMA_GET_FLAG(&DMAtx, __HAL_DMA_GET_TC_FLAG_INDEX(&DMAtx)) != 0 || __HAL_DMA_GET_FLAG(&DMAtx, __HAL_DMA_GET_TE_FLAG_INDEX(&DMAtx)) != 0) Abort(); - return __IS_DMA_ENABLED(&DMAtx); + } + else + Abort(); + return dmaEnabled; } void TFT_FSMC::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) { DMAtx.Init.PeriphInc = MemoryIncrease; HAL_DMA_Init(&DMAtx); - - __HAL_DMA_CLEAR_FLAG(&DMAtx, __HAL_DMA_GET_TC_FLAG_INDEX(&DMAtx)); - __HAL_DMA_CLEAR_FLAG(&DMAtx, __HAL_DMA_GET_TE_FLAG_INDEX(&DMAtx)); - - #ifdef STM32F1xx - DMAtx.Instance->CNDTR = Count; - DMAtx.Instance->CPAR = (uint32_t)Data; - DMAtx.Instance->CMAR = (uint32_t)&(LCD->RAM); - #elif defined(STM32F4xx) - DMAtx.Instance->NDTR = Count; - DMAtx.Instance->PAR = (uint32_t)Data; - DMAtx.Instance->M0AR = (uint32_t)&(LCD->RAM); - #endif - __HAL_DMA_ENABLE(&DMAtx); + DataTransferBegin(); + HAL_DMA_Start(&DMAtx, (uint32_t)Data, (uint32_t)&(LCD->RAM), Count); + HAL_DMA_PollForTransfer(&DMAtx, HAL_DMA_FULL_TRANSFER, HAL_MAX_DELAY); + Abort(); } #endif // HAS_FSMC_TFT +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/tft/tft_fsmc.h b/Marlin/src/HAL/STM32/tft/tft_fsmc.h index cbec7613ef4a..2200abaa10e8 100644 --- a/Marlin/src/HAL/STM32/tft/tft_fsmc.h +++ b/Marlin/src/HAL/STM32/tft/tft_fsmc.h @@ -21,34 +21,33 @@ */ #pragma once +#include "../../../inc/MarlinConfig.h" + #ifdef STM32F1xx #include "stm32f1xx_hal.h" #elif defined(STM32F4xx) #include "stm32f4xx_hal.h" #else - #error FSMC TFT is currently only supported on STM32F1 and STM32F4 hardware. + #error "FSMC TFT is currently only supported on STM32F1 and STM32F4 hardware." #endif #ifndef LCD_READ_ID - #define LCD_READ_ID 0x04 // Read display identification information (0xD3 on ILI9341) + #define LCD_READ_ID 0x04 // Read display identification information (0xD3 on ILI9341) #endif #ifndef LCD_READ_ID4 #define LCD_READ_ID4 0xD3 // Read display identification information (0xD3 on ILI9341) #endif -#define DATASIZE_8BIT SPI_DATASIZE_8BIT -#define DATASIZE_16BIT SPI_DATASIZE_16BIT -#define TFT_IO_DRIVER TFT_FSMC +#define DATASIZE_8BIT SPI_DATASIZE_8BIT +#define DATASIZE_16BIT SPI_DATASIZE_16BIT +#define TFT_IO_DRIVER TFT_FSMC -#ifdef STM32F1xx - #define __IS_DMA_ENABLED(__HANDLE__) ((__HANDLE__)->Instance->CCR & DMA_CCR_EN) -#elif defined(STM32F4xx) - #define __IS_DMA_ENABLED(__HANDLE__) ((__HANDLE__)->Instance->CR & DMA_SxCR_EN) -#endif +#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; typedef struct { - __IO uint16_t REG; - __IO uint16_t RAM; + __IO tft_data_t REG; + __IO tft_data_t RAM; } LCD_CONTROLLER_TypeDef; class TFT_FSMC { @@ -58,8 +57,8 @@ class TFT_FSMC { static LCD_CONTROLLER_TypeDef *LCD; - static uint32_t ReadID(uint16_t Reg); - static void Transmit(uint16_t Data) { LCD->RAM = Data; __DSB(); } + static uint32_t ReadID(tft_data_t Reg); + static void Transmit(tft_data_t Data) { LCD->RAM = Data; __DSB(); } static void TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count); public: @@ -68,17 +67,23 @@ class TFT_FSMC { static bool isBusy(); static void Abort() { __HAL_DMA_DISABLE(&DMAtx); } - static void DataTransferBegin(uint16_t DataWidth = DATASIZE_16BIT) {} + static void DataTransferBegin(uint16_t DataWidth = TFT_DATASIZE) {} static void DataTransferEnd() {}; - static void WriteData(uint16_t Data) { Transmit(Data); } - static void WriteReg(uint16_t Reg) { LCD->REG = Reg; __DSB(); } + static void WriteData(uint16_t Data) { Transmit(tft_data_t(Data)); } + static void WriteReg(uint16_t Reg) { LCD->REG = tft_data_t(Reg); __DSB(); } static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_PINC_ENABLE, Data, Count); } static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_PINC_DISABLE, &Data, Count); } + static void WriteMultiple(uint16_t Color, uint32_t Count) { + static uint16_t Data; Data = Color; + while (Count > 0) { + TransmitDMA(DMA_MINC_DISABLE, &Data, Count > 0xFFFF ? 0xFFFF : Count); + Count = Count > 0xFFFF ? Count - 0xFFFF : 0; + } + } }; - #ifdef STM32F1xx #define FSMC_PIN_DATA STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, AFIO_NONE) #elif defined(STM32F4xx) @@ -100,14 +105,16 @@ const PinMap PinMap_FSMC[] = { {PE_8, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D05 {PE_9, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D06 {PE_10, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D07 - {PE_11, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D08 - {PE_12, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D09 - {PE_13, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D10 - {PE_14, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D11 - {PE_15, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D12 - {PD_8, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D13 - {PD_9, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D14 - {PD_10, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D15 + #if DISABLED(TFT_INTERFACE_FSMC_8BIT) + {PE_11, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D08 + {PE_12, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D09 + {PE_13, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D10 + {PE_14, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D11 + {PE_15, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D12 + {PD_8, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D13 + {PD_9, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D14 + {PD_10, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D15 + #endif {PD_4, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_NOE {PD_5, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_NWE {NC, NP, 0} @@ -123,7 +130,11 @@ const PinMap PinMap_FSMC_CS[] = { {NC, NP, 0} }; -#define FSMC_RS(A) (void *)((2 << A) - 2) +#if ENABLED(TFT_INTERFACE_FSMC_8BIT) + #define FSMC_RS(A) (void *)((2 << (A-1)) - 1) +#else + #define FSMC_RS(A) (void *)((2 << A) - 2) +#endif const PinMap PinMap_FSMC_RS[] = { #ifdef PF0 diff --git a/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp b/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp new file mode 100644 index 000000000000..0549dbf10845 --- /dev/null +++ b/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp @@ -0,0 +1,389 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../platforms.h" + +#ifdef HAL_STM32 + +#include "../../../inc/MarlinConfig.h" + +#if HAS_LTDC_TFT + +#include "tft_ltdc.h" +#include "pinconfig.h" + +#define FRAME_BUFFER_ADDRESS 0XC0000000 // SDRAM address + +#define SDRAM_TIMEOUT ((uint32_t)0xFFFF) +#define REFRESH_COUNT ((uint32_t)0x02A5) // SDRAM refresh counter + +#define SDRAM_MODEREG_BURST_LENGTH_1 ((uint16_t)0x0000) +#define SDRAM_MODEREG_BURST_LENGTH_2 ((uint16_t)0x0001) +#define SDRAM_MODEREG_BURST_LENGTH_4 ((uint16_t)0x0002) +#define SDRAM_MODEREG_BURST_LENGTH_8 ((uint16_t)0x0004) +#define SDRAM_MODEREG_BURST_TYPE_SEQUENTIAL ((uint16_t)0x0000) +#define SDRAM_MODEREG_BURST_TYPE_INTERLEAVED ((uint16_t)0x0008) +#define SDRAM_MODEREG_CAS_LATENCY_2 ((uint16_t)0x0020) +#define SDRAM_MODEREG_CAS_LATENCY_3 ((uint16_t)0x0030) +#define SDRAM_MODEREG_OPERATING_MODE_STANDARD ((uint16_t)0x0000) +#define SDRAM_MODEREG_WRITEBURST_MODE_PROGRAMMED ((uint16_t)0x0000) +#define SDRAM_MODEREG_WRITEBURST_MODE_SINGLE ((uint16_t)0x0200) + +void SDRAM_Initialization_Sequence(SDRAM_HandleTypeDef *hsdram, FMC_SDRAM_CommandTypeDef *Command) { + + __IO uint32_t tmpmrd =0; + /* Step 1: Configure a clock configuration enable command */ + Command->CommandMode = FMC_SDRAM_CMD_CLK_ENABLE; + Command->CommandTarget = FMC_SDRAM_CMD_TARGET_BANK1; + Command->AutoRefreshNumber = 1; + Command->ModeRegisterDefinition = 0; + /* Send the command */ + HAL_SDRAM_SendCommand(hsdram, Command, SDRAM_TIMEOUT); + + /* Step 2: Insert 100 us minimum delay */ + /* Inserted delay is equal to 1 ms due to systick time base unit (ms) */ + HAL_Delay(1); + + /* Step 3: Configure a PALL (precharge all) command */ + Command->CommandMode = FMC_SDRAM_CMD_PALL; + Command->CommandTarget = FMC_SDRAM_CMD_TARGET_BANK1; + Command->AutoRefreshNumber = 1; + Command->ModeRegisterDefinition = 0; + /* Send the command */ + HAL_SDRAM_SendCommand(hsdram, Command, SDRAM_TIMEOUT); + + /* Step 4 : Configure a Auto-Refresh command */ + Command->CommandMode = FMC_SDRAM_CMD_AUTOREFRESH_MODE; + Command->CommandTarget = FMC_SDRAM_CMD_TARGET_BANK1; + Command->AutoRefreshNumber = 8; + Command->ModeRegisterDefinition = 0; + /* Send the command */ + HAL_SDRAM_SendCommand(hsdram, Command, SDRAM_TIMEOUT); + + /* Step 5: Program the external memory mode register */ + tmpmrd = (uint32_t)(SDRAM_MODEREG_BURST_LENGTH_1 | + SDRAM_MODEREG_BURST_TYPE_SEQUENTIAL | + SDRAM_MODEREG_CAS_LATENCY_2 | + SDRAM_MODEREG_OPERATING_MODE_STANDARD | + SDRAM_MODEREG_WRITEBURST_MODE_SINGLE); + + Command->CommandMode = FMC_SDRAM_CMD_LOAD_MODE; + Command->CommandTarget = FMC_SDRAM_CMD_TARGET_BANK1; + Command->AutoRefreshNumber = 1; + Command->ModeRegisterDefinition = tmpmrd; + /* Send the command */ + HAL_SDRAM_SendCommand(hsdram, Command, SDRAM_TIMEOUT); + + /* Step 6: Set the refresh rate counter */ + /* Set the device refresh rate */ + HAL_SDRAM_ProgramRefreshRate(hsdram, REFRESH_COUNT); +} + +void SDRAM_Config() { + + __HAL_RCC_SYSCFG_CLK_ENABLE(); + __HAL_RCC_FMC_CLK_ENABLE(); + + SDRAM_HandleTypeDef hsdram; + FMC_SDRAM_TimingTypeDef SDRAM_Timing; + FMC_SDRAM_CommandTypeDef command; + + /* Configure the SDRAM device */ + hsdram.Instance = FMC_SDRAM_DEVICE; + hsdram.Init.SDBank = FMC_SDRAM_BANK1; + hsdram.Init.ColumnBitsNumber = FMC_SDRAM_COLUMN_BITS_NUM_9; + hsdram.Init.RowBitsNumber = FMC_SDRAM_ROW_BITS_NUM_13; + hsdram.Init.MemoryDataWidth = FMC_SDRAM_MEM_BUS_WIDTH_16; + hsdram.Init.InternalBankNumber = FMC_SDRAM_INTERN_BANKS_NUM_4; + hsdram.Init.CASLatency = FMC_SDRAM_CAS_LATENCY_2; + hsdram.Init.WriteProtection = FMC_SDRAM_WRITE_PROTECTION_DISABLE; + hsdram.Init.SDClockPeriod = FMC_SDRAM_CLOCK_PERIOD_2; + hsdram.Init.ReadBurst = FMC_SDRAM_RBURST_ENABLE; + hsdram.Init.ReadPipeDelay = FMC_SDRAM_RPIPE_DELAY_0; + + /* Timing configuration for 100Mhz as SDRAM clock frequency (System clock is up to 200Mhz) */ + SDRAM_Timing.LoadToActiveDelay = 2; + SDRAM_Timing.ExitSelfRefreshDelay = 8; + SDRAM_Timing.SelfRefreshTime = 6; + SDRAM_Timing.RowCycleDelay = 6; + SDRAM_Timing.WriteRecoveryTime = 2; + SDRAM_Timing.RPDelay = 2; + SDRAM_Timing.RCDDelay = 2; + + /* Initialize the SDRAM controller */ + if (HAL_SDRAM_Init(&hsdram, &SDRAM_Timing) != HAL_OK) + { + /* Initialization Error */ + } + + /* Program the SDRAM external device */ + SDRAM_Initialization_Sequence(&hsdram, &command); +} + +void LTDC_Config() { + + __HAL_RCC_LTDC_CLK_ENABLE(); + __HAL_RCC_DMA2D_CLK_ENABLE(); + + RCC_PeriphCLKInitTypeDef PeriphClkInitStruct; + + /* The PLL3R is configured to provide the LTDC PCLK clock */ + /* PLL3_VCO Input = HSE_VALUE / PLL3M = 25Mhz / 5 = 5 Mhz */ + /* PLL3_VCO Output = PLL3_VCO Input * PLL3N = 5Mhz * 160 = 800 Mhz */ + /* PLLLCDCLK = PLL3_VCO Output/PLL3R = 800Mhz / 16 = 50Mhz */ + /* LTDC clock frequency = PLLLCDCLK = 50 Mhz */ + PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_LTDC; + PeriphClkInitStruct.PLL3.PLL3M = 5; + PeriphClkInitStruct.PLL3.PLL3N = 160; + PeriphClkInitStruct.PLL3.PLL3FRACN = 0; + PeriphClkInitStruct.PLL3.PLL3P = 2; + PeriphClkInitStruct.PLL3.PLL3Q = 2; + PeriphClkInitStruct.PLL3.PLL3R = (800 / LTDC_LCD_CLK); + PeriphClkInitStruct.PLL3.PLL3VCOSEL = RCC_PLL3VCOWIDE; + PeriphClkInitStruct.PLL3.PLL3RGE = RCC_PLL3VCIRANGE_2; + HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct); + + LTDC_HandleTypeDef hltdc_F; + LTDC_LayerCfgTypeDef pLayerCfg; + + /* LTDC Initialization -------------------------------------------------------*/ + + /* Polarity configuration */ + /* Initialize the horizontal synchronization polarity as active low */ + hltdc_F.Init.HSPolarity = LTDC_HSPOLARITY_AL; + /* Initialize the vertical synchronization polarity as active low */ + hltdc_F.Init.VSPolarity = LTDC_VSPOLARITY_AL; + /* Initialize the data enable polarity as active low */ + hltdc_F.Init.DEPolarity = LTDC_DEPOLARITY_AL; + /* Initialize the pixel clock polarity as input pixel clock */ + hltdc_F.Init.PCPolarity = LTDC_PCPOLARITY_IPC; + + /* Timing configuration */ + hltdc_F.Init.HorizontalSync = (LTDC_LCD_HSYNC - 1); + hltdc_F.Init.VerticalSync = (LTDC_LCD_VSYNC - 1); + hltdc_F.Init.AccumulatedHBP = (LTDC_LCD_HSYNC + LTDC_LCD_HBP - 1); + hltdc_F.Init.AccumulatedVBP = (LTDC_LCD_VSYNC + LTDC_LCD_VBP - 1); + hltdc_F.Init.AccumulatedActiveH = (TFT_HEIGHT + LTDC_LCD_VSYNC + LTDC_LCD_VBP - 1); + hltdc_F.Init.AccumulatedActiveW = (TFT_WIDTH + LTDC_LCD_HSYNC + LTDC_LCD_HBP - 1); + hltdc_F.Init.TotalHeight = (TFT_HEIGHT + LTDC_LCD_VSYNC + LTDC_LCD_VBP + LTDC_LCD_VFP - 1); + hltdc_F.Init.TotalWidth = (TFT_WIDTH + LTDC_LCD_HSYNC + LTDC_LCD_HBP + LTDC_LCD_HFP - 1); + + /* Configure R,G,B component values for LCD background color : all black background */ + hltdc_F.Init.Backcolor.Blue = 0; + hltdc_F.Init.Backcolor.Green = 0; + hltdc_F.Init.Backcolor.Red = 0; + + hltdc_F.Instance = LTDC; + + /* Layer0 Configuration ------------------------------------------------------*/ + + /* Windowing configuration */ + pLayerCfg.WindowX0 = 0; + pLayerCfg.WindowX1 = TFT_WIDTH; + pLayerCfg.WindowY0 = 0; + pLayerCfg.WindowY1 = TFT_HEIGHT; + + /* Pixel Format configuration*/ + pLayerCfg.PixelFormat = LTDC_PIXEL_FORMAT_RGB565; + + /* Start Address configuration : frame buffer is located at SDRAM memory */ + pLayerCfg.FBStartAddress = (uint32_t)(FRAME_BUFFER_ADDRESS); + + /* Alpha constant (255 == totally opaque) */ + pLayerCfg.Alpha = 255; + + /* Default Color configuration (configure A,R,G,B component values) : no background color */ + pLayerCfg.Alpha0 = 0; /* fully transparent */ + pLayerCfg.Backcolor.Blue = 0; + pLayerCfg.Backcolor.Green = 0; + pLayerCfg.Backcolor.Red = 0; + + /* Configure blending factors */ + pLayerCfg.BlendingFactor1 = LTDC_BLENDING_FACTOR1_CA; + pLayerCfg.BlendingFactor2 = LTDC_BLENDING_FACTOR2_CA; + + /* Configure the number of lines and number of pixels per line */ + pLayerCfg.ImageWidth = TFT_WIDTH; + pLayerCfg.ImageHeight = TFT_HEIGHT; + + /* Configure the LTDC */ + if (HAL_LTDC_Init(&hltdc_F) != HAL_OK) + { + /* Initialization Error */ + } + + /* Configure the Layer*/ + if (HAL_LTDC_ConfigLayer(&hltdc_F, &pLayerCfg, 0) != HAL_OK) + { + /* Initialization Error */ + } +} + +uint16_t TFT_LTDC::x_min = 0; +uint16_t TFT_LTDC::x_max = 0; +uint16_t TFT_LTDC::y_min = 0; +uint16_t TFT_LTDC::y_max = 0; +uint16_t TFT_LTDC::x_cur = 0; +uint16_t TFT_LTDC::y_cur = 0; +uint8_t TFT_LTDC::reg = 0; +volatile uint16_t* TFT_LTDC::framebuffer = (volatile uint16_t* )FRAME_BUFFER_ADDRESS; + +void TFT_LTDC::Init() { + + // SDRAM pins init + for (uint16_t i = 0; PinMap_SDRAM[i].pin != NC; i++) + pinmap_pinout(PinMap_SDRAM[i].pin, PinMap_SDRAM); + + // SDRAM peripheral config + SDRAM_Config(); + + // LTDC pins init + for (uint16_t i = 0; PinMap_LTDC[i].pin != NC; i++) + pinmap_pinout(PinMap_LTDC[i].pin, PinMap_LTDC); + + // LTDC peripheral config + LTDC_Config(); +} + +uint32_t TFT_LTDC::GetID() { + return 0xABAB; +} + +uint32_t TFT_LTDC::ReadID(tft_data_t Reg) { + return 0xABAB; +} + +bool TFT_LTDC::isBusy() { + return false; +} + +uint16_t TFT_LTDC::ReadPoint(uint16_t x, uint16_t y) { + return framebuffer[(TFT_WIDTH * y) + x]; +} + +void TFT_LTDC::DrawPoint(uint16_t x, uint16_t y, uint16_t color) { + framebuffer[(TFT_WIDTH * y) + x] = color; +} + +void TFT_LTDC::DrawRect(uint16_t sx, uint16_t sy, uint16_t ex, uint16_t ey, uint16_t color) { + + if (sx == ex || sy == ey) return; + + uint16_t offline = TFT_WIDTH - (ex - sx); + uint32_t addr = (uint32_t)&framebuffer[(TFT_WIDTH * sy) + sx]; + + CBI(DMA2D->CR, 0); + DMA2D->CR = 3 << 16; + DMA2D->OPFCCR = 0X02; + DMA2D->OOR = offline; + DMA2D->OMAR = addr; + DMA2D->NLR = (ey - sy) | ((ex - sx) << 16); + DMA2D->OCOLR = color; + SBI(DMA2D->CR, 0); + + uint32_t timeout = 0; + while (!TEST(DMA2D->ISR, 1)) { + timeout++; + if (timeout > 0x1FFFFF) break; + } + SBI(DMA2D->IFCR, 1); +} + +void TFT_LTDC::DrawImage(uint16_t sx, uint16_t sy, uint16_t ex, uint16_t ey, uint16_t *colors) { + + if (sx == ex || sy == ey) return; + + uint16_t offline = TFT_WIDTH - (ex - sx); + uint32_t addr = (uint32_t)&framebuffer[(TFT_WIDTH * sy) + sx]; + + CBI(DMA2D->CR, 0); + DMA2D->CR = 0 << 16; + DMA2D->FGPFCCR = 0X02; + DMA2D->FGOR = 0; + DMA2D->OOR = offline; + DMA2D->FGMAR = (uint32_t)colors; + DMA2D->OMAR = addr; + DMA2D->NLR = (ey - sy) | ((ex - sx) << 16); + SBI(DMA2D->CR, 0); + + uint32_t timeout = 0; + while (!TEST(DMA2D->ISR, 1)) { + timeout++; + if (timeout > 0x1FFFFF) break; + } + SBI(DMA2D->IFCR, 1); +} + +void TFT_LTDC::WriteData(uint16_t data) { + switch (reg) { + case 0x01: x_cur = x_min = data; return; + case 0x02: x_max = data; return; + case 0x03: y_cur = y_min = data; return; + case 0x04: y_max = data; return; + } + Transmit(data); +} + +void TFT_LTDC::Transmit(tft_data_t Data) { + DrawPoint(x_cur, y_cur, Data); + x_cur++; + if (x_cur > x_max) { + x_cur = x_min; + y_cur++; + if (y_cur > y_max) y_cur = y_min; + } +} + +void TFT_LTDC::WriteReg(uint16_t Reg) { + reg = Reg; +} + +void TFT_LTDC::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) { + + while (x_cur != x_min && Count) { + Transmit(*Data); + if (MemoryIncrease == DMA_PINC_ENABLE) Data++; + Count--; + } + + uint16_t width = x_max - x_min + 1; + uint16_t height = Count / width; + uint16_t x_end_cnt = Count - (width * height); + + if (height) { + if (MemoryIncrease == DMA_PINC_ENABLE) { + DrawImage(x_min, y_cur, x_min + width, y_cur + height, Data); + Data += width * height; + } else { + DrawRect(x_min, y_cur, x_min + width, y_cur + height, *Data); + } + y_cur += height; + } + + while (x_end_cnt) { + Transmit(*Data); + if (MemoryIncrease == DMA_PINC_ENABLE) Data++; + x_end_cnt--; + } +} + +#endif // HAS_LTDC_TFT +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/tft/tft_ltdc.h b/Marlin/src/HAL/STM32/tft/tft_ltdc.h new file mode 100644 index 000000000000..7b63d6929b31 --- /dev/null +++ b/Marlin/src/HAL/STM32/tft/tft_ltdc.h @@ -0,0 +1,155 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include "../../../inc/MarlinConfig.h" + +#ifdef STM32H7xx + #include "stm32h7xx_hal.h" +#else + #error "LTDC TFT is currently only supported on STM32H7 hardware." +#endif + +#define DATASIZE_8BIT SPI_DATASIZE_8BIT +#define DATASIZE_16BIT SPI_DATASIZE_16BIT +#define TFT_IO_DRIVER TFT_LTDC + +#define TFT_DATASIZE DATASIZE_16BIT +typedef uint16_t tft_data_t; + +class TFT_LTDC { + private: + static volatile uint16_t *framebuffer; + static uint16_t x_min, x_max, y_min, y_max, x_cur, y_cur; + static uint8_t reg; + + static uint32_t ReadID(tft_data_t Reg); + + static uint16_t ReadPoint(uint16_t x, uint16_t y); + static void DrawPoint(uint16_t x, uint16_t y, uint16_t color); + static void DrawRect(uint16_t sx, uint16_t sy, uint16_t ex, uint16_t ey, uint16_t color); + static void DrawImage(uint16_t sx, uint16_t sy, uint16_t ex, uint16_t ey, uint16_t *colors); + static void Transmit(tft_data_t Data); + static void TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count); + + public: + static void Init(); + static uint32_t GetID(); + static bool isBusy(); + static void Abort() { /*__HAL_DMA_DISABLE(&DMAtx);*/ } + + static void DataTransferBegin(uint16_t DataWidth = TFT_DATASIZE) {} + static void DataTransferEnd() {}; + + static void WriteData(uint16_t Data); + static void WriteReg(uint16_t Reg); + + static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_PINC_ENABLE, Data, Count); } + static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_PINC_DISABLE, &Data, Count); } + static void WriteMultiple(uint16_t Color, uint32_t Count) { + static uint16_t Data; Data = Color; + while (Count > 0) { + TransmitDMA(DMA_MINC_DISABLE, &Data, Count > 0xFFFF ? 0xFFFF : Count); + Count = Count > 0xFFFF ? Count - 0xFFFF : 0; + } + } +}; + +const PinMap PinMap_LTDC[] = { + {PF_10, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_DE + {PG_7, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_CLK + {PI_9, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_VSYNC + {PI_10, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_HSYNC + + {PG_6, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_R7 + {PH_12, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_R6 + {PH_11, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_R5 + {PH_10, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_R4 + {PH_9, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_R3 + + {PI_2, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_G7 + {PI_1, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_G6 + {PI_0, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_G5 + {PH_15, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_G4 + {PH_14, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_G3 + {PH_13, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_G2 + + {PI_7, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_B7 + {PI_6, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_B6 + {PI_5, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_B5 + {PI_4, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_B4 + {PG_11, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_B3 + {NC, NP, 0} +}; + +const PinMap PinMap_SDRAM[] = { + {PC_0, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_SDNWE + {PC_2, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_SDNE0 + {PC_3, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_SDCKE0 + {PE_0, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_NBL0 + {PE_1, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_NBL1 + {PF_11, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_SDNRAS + {PG_8, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_SDCLK + {PG_15, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_SDNCAS + {PG_4, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_BA0 + {PG_5, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_BA1 + {PD_14, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D0 + {PD_15, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D1 + {PD_0, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D2 + {PD_1, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D3 + {PE_7, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D4 + {PE_8, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D5 + {PE_9, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D6 + {PE_10, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D7 + {PE_11, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D8 + {PE_12, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D9 + {PE_13, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D10 + {PE_14, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D11 + {PE_15, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D12 + {PD_8, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D13 + {PD_9, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D14 + {PD_10, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D15 + {PF_0, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A0 + {PF_1, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A1 + {PF_2, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A2 + {PF_3, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A3 + {PF_4, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A4 + {PF_5, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A5 + {PF_12, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A6 + {PF_13, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A7 + {PF_14, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A8 + {PF_15, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A9 + {PG_0, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A10 + {PG_1, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A11 + {PG_2, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A12 + {NC, NP, 0} +}; + +const PinMap PinMap_QUADSPI[] = { + {PB_2, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QUADSPI)}, // QUADSPI_CLK + {PB_10, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QUADSPI)}, // QUADSPI_BK1_NCS + {PF_6, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QUADSPI)}, // QUADSPI_BK1_IO3 + {PF_7, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QUADSPI)}, // QUADSPI_BK1_IO2 + {PF_8, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_QUADSPI)}, // QUADSPI_BK1_IO0 + {PF_9, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_QUADSPI)}, // QUADSPI_BK1_IO1 + {NC, NP, 0} +}; diff --git a/Marlin/src/HAL/STM32/tft/tft_spi.cpp b/Marlin/src/HAL/STM32/tft/tft_spi.cpp index d3eb4ba8db6a..29a309f40e7b 100644 --- a/Marlin/src/HAL/STM32/tft/tft_spi.cpp +++ b/Marlin/src/HAL/STM32/tft/tft_spi.cpp @@ -19,6 +19,9 @@ * along with this program. If not, see . * */ +#include "../../platforms.h" + +#ifdef HAL_STM32 #include "../../../inc/MarlinConfig.h" @@ -33,22 +36,13 @@ DMA_HandleTypeDef TFT_SPI::DMAtx; void TFT_SPI::Init() { SPI_TypeDef *spiInstance; - #if PIN_EXISTS(TFT_RESET) - OUT_WRITE(TFT_RESET_PIN, HIGH); - HAL_Delay(100); - #endif - - #if PIN_EXISTS(TFT_BACKLIGHT) - OUT_WRITE(TFT_BACKLIGHT_PIN, HIGH); - #endif - OUT_WRITE(TFT_A0_PIN, HIGH); OUT_WRITE(TFT_CS_PIN, HIGH); if ((spiInstance = (SPI_TypeDef *)pinmap_peripheral(digitalPinToPinName(TFT_SCK_PIN), PinMap_SPI_SCLK)) == NP) return; if (spiInstance != (SPI_TypeDef *)pinmap_peripheral(digitalPinToPinName(TFT_MOSI_PIN), PinMap_SPI_MOSI)) return; - #if PIN_EXISTS(TFT_MISO) && (TFT_MISO_PIN != TFT_MOSI_PIN) + #if PIN_EXISTS(TFT_MISO) && TFT_MISO_PIN != TFT_MOSI_PIN if (spiInstance != (SPI_TypeDef *)pinmap_peripheral(digitalPinToPinName(TFT_MISO_PIN), PinMap_SPI_MISO)) return; #endif @@ -56,12 +50,7 @@ void TFT_SPI::Init() { SPIx.State = HAL_SPI_STATE_RESET; SPIx.Init.NSS = SPI_NSS_SOFT; SPIx.Init.Mode = SPI_MODE_MASTER; - SPIx.Init.Direction = - #if TFT_MISO_PIN == TFT_MOSI_PIN - SPI_DIRECTION_1LINE; - #else - SPI_DIRECTION_2LINES; - #endif + SPIx.Init.Direction = (TFT_MISO_PIN == TFT_MOSI_PIN) ? SPI_DIRECTION_1LINE : SPI_DIRECTION_2LINES; SPIx.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_2; SPIx.Init.CLKPhase = SPI_PHASE_1EDGE; SPIx.Init.CLKPolarity = SPI_POLARITY_LOW; @@ -73,7 +62,7 @@ void TFT_SPI::Init() { pinmap_pinout(digitalPinToPinName(TFT_SCK_PIN), PinMap_SPI_SCLK); pinmap_pinout(digitalPinToPinName(TFT_MOSI_PIN), PinMap_SPI_MOSI); - #if PIN_EXISTS(TFT_MISO) && (TFT_MISO_PIN != TFT_MOSI_PIN) + #if PIN_EXISTS(TFT_MISO) && TFT_MISO_PIN != TFT_MOSI_PIN pinmap_pinout(digitalPinToPinName(TFT_MISO_PIN), PinMap_SPI_MISO); #endif pin_PullConfig(get_GPIO_Port(STM_PORT(digitalPinToPinName(TFT_SCK_PIN))), STM_LL_GPIO_PIN(digitalPinToPinName(TFT_SCK_PIN)), GPIO_PULLDOWN); @@ -81,23 +70,41 @@ void TFT_SPI::Init() { #ifdef SPI1_BASE if (SPIx.Instance == SPI1) { __HAL_RCC_SPI1_CLK_ENABLE(); - __HAL_RCC_DMA1_CLK_ENABLE(); + #ifdef STM32F1xx + __HAL_RCC_DMA1_CLK_ENABLE(); + DMAtx.Instance = DMA1_Channel3; + #elif defined(STM32F4xx) + __HAL_RCC_DMA2_CLK_ENABLE(); + DMAtx.Instance = DMA2_Stream3; + DMAtx.Init.Channel = DMA_CHANNEL_3; + #endif SPIx.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_4; - DMAtx.Instance = DMA1_Channel3; } #endif #ifdef SPI2_BASE if (SPIx.Instance == SPI2) { __HAL_RCC_SPI2_CLK_ENABLE(); - __HAL_RCC_DMA1_CLK_ENABLE(); - DMAtx.Instance = DMA1_Channel5; + #ifdef STM32F1xx + __HAL_RCC_DMA1_CLK_ENABLE(); + DMAtx.Instance = DMA1_Channel5; + #elif defined(STM32F4xx) + __HAL_RCC_DMA1_CLK_ENABLE(); + DMAtx.Instance = DMA1_Stream4; + DMAtx.Init.Channel = DMA_CHANNEL_0; + #endif } #endif #ifdef SPI3_BASE if (SPIx.Instance == SPI3) { __HAL_RCC_SPI3_CLK_ENABLE(); - __HAL_RCC_DMA2_CLK_ENABLE(); - DMAtx.Instance = DMA2_Channel2; + #ifdef STM32F1xx + __HAL_RCC_DMA2_CLK_ENABLE(); + DMAtx.Instance = DMA2_Channel2; + #elif defined(STM32F4xx) + __HAL_RCC_DMA1_CLK_ENABLE(); + DMAtx.Instance = DMA1_Stream5; + DMAtx.Init.Channel = DMA_CHANNEL_0; + #endif } #endif @@ -109,6 +116,9 @@ void TFT_SPI::Init() { DMAtx.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD; DMAtx.Init.Mode = DMA_NORMAL; DMAtx.Init.Priority = DMA_PRIORITY_LOW; + #ifdef STM32F4xx + DMAtx.Init.FIFOMode = DMA_FIFOMODE_DISABLE; + #endif } void TFT_SPI::DataTransferBegin(uint16_t DataSize) { @@ -117,21 +127,28 @@ void TFT_SPI::DataTransferBegin(uint16_t DataSize) { WRITE(TFT_CS_PIN, LOW); } +#ifdef TFT_DEFAULT_DRIVER + #include "../../../lcd/tft_io/tft_ids.h" +#endif + uint32_t TFT_SPI::GetID() { uint32_t id; id = ReadID(LCD_READ_ID); - - if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) + if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) { id = ReadID(LCD_READ_ID4); + #ifdef TFT_DEFAULT_DRIVER + if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) + id = TFT_DEFAULT_DRIVER; + #endif + } return id; } uint32_t TFT_SPI::ReadID(uint16_t Reg) { - #if !PIN_EXISTS(TFT_MISO) - return 0; - #else + uint32_t Data = 0; + #if PIN_EXISTS(TFT_MISO) uint32_t BaudRatePrescaler = SPIx.Init.BaudRatePrescaler; - uint32_t i, Data = 0; + uint32_t i; SPIx.Init.BaudRatePrescaler = SPIx.Instance == SPI1 ? SPI_BAUDRATEPRESCALER_8 : SPI_BAUDRATEPRESCALER_4; DataTransferBegin(DATASIZE_8BIT); @@ -155,27 +172,42 @@ uint32_t TFT_SPI::ReadID(uint16_t Reg) { DataTransferEnd(); SPIx.Init.BaudRatePrescaler = BaudRatePrescaler; - - return Data >> 7; #endif + + return Data >> 7; } bool TFT_SPI::isBusy() { - if (DMAtx.Instance->CCR & DMA_CCR_EN) + #if defined(STM32F1xx) + volatile bool dmaEnabled = (DMAtx.Instance->CCR & DMA_CCR_EN) != RESET; + #elif defined(STM32F4xx) + volatile bool dmaEnabled = DMAtx.Instance->CR & DMA_SxCR_EN; + #endif + if (dmaEnabled) { if (__HAL_DMA_GET_FLAG(&DMAtx, __HAL_DMA_GET_TC_FLAG_INDEX(&DMAtx)) != 0 || __HAL_DMA_GET_FLAG(&DMAtx, __HAL_DMA_GET_TE_FLAG_INDEX(&DMAtx)) != 0) Abort(); - return DMAtx.Instance->CCR & DMA_CCR_EN; + } + else + Abort(); + return dmaEnabled; } void TFT_SPI::Abort() { - __HAL_DMA_DISABLE(&DMAtx); + // Wait for any running spi + while ((SPIx.Instance->SR & SPI_FLAG_TXE) != SPI_FLAG_TXE) {} + while ((SPIx.Instance->SR & SPI_FLAG_BSY) == SPI_FLAG_BSY) {} + // First, abort any running dma + HAL_DMA_Abort(&DMAtx); + // DeInit objects + HAL_DMA_DeInit(&DMAtx); + HAL_SPI_DeInit(&SPIx); + // Deselect CS DataTransferEnd(); } void TFT_SPI::Transmit(uint16_t Data) { - #if TFT_MISO_PIN == TFT_MOSI_PIN + if (TFT_MISO_PIN == TFT_MOSI_PIN) SPI_1LINE_TX(&SPIx); - #endif __HAL_SPI_ENABLE(&SPIx); @@ -184,29 +216,30 @@ void TFT_SPI::Transmit(uint16_t Data) { while ((SPIx.Instance->SR & SPI_FLAG_TXE) != SPI_FLAG_TXE) {} while ((SPIx.Instance->SR & SPI_FLAG_BSY) == SPI_FLAG_BSY) {} - #if TFT_MISO_PIN != TFT_MOSI_PIN - __HAL_SPI_CLEAR_OVRFLAG(&SPIx); /* Clear overrun flag in 2 Lines communication mode because received is not read */ - #endif + if (TFT_MISO_PIN != TFT_MOSI_PIN) + __HAL_SPI_CLEAR_OVRFLAG(&SPIx); // Clear overrun flag in 2 Lines communication mode because received is not read } void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) { + // Wait last dma finish, to start another + while (isBusy()) { /* nada */ } + DMAtx.Init.MemInc = MemoryIncrease; HAL_DMA_Init(&DMAtx); - DataTransferBegin(); - - #if TFT_MISO_PIN == TFT_MOSI_PIN + if (TFT_MISO_PIN == TFT_MOSI_PIN) SPI_1LINE_TX(&SPIx); - #endif - DMAtx.DmaBaseAddress->IFCR = (DMA_ISR_GIF1 << DMAtx.ChannelIndex); - DMAtx.Instance->CNDTR = Count; - DMAtx.Instance->CPAR = (uint32_t)&(SPIx.Instance->DR); - DMAtx.Instance->CMAR = (uint32_t)Data; - __HAL_DMA_ENABLE(&DMAtx); + DataTransferBegin(); + + HAL_DMA_Start(&DMAtx, (uint32_t)Data, (uint32_t)&(SPIx.Instance->DR), Count); __HAL_SPI_ENABLE(&SPIx); - SET_BIT(SPIx.Instance->CR2, SPI_CR2_TXDMAEN); /* Enable Tx DMA Request */ + SET_BIT(SPIx.Instance->CR2, SPI_CR2_TXDMAEN); // Enable Tx DMA Request + + HAL_DMA_PollForTransfer(&DMAtx, HAL_DMA_FULL_TRANSFER, HAL_MAX_DELAY); + Abort(); } #endif // HAS_SPI_TFT +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/tft/tft_spi.h b/Marlin/src/HAL/STM32/tft/tft_spi.h index d477b58c004d..667b5f366b7e 100644 --- a/Marlin/src/HAL/STM32/tft/tft_spi.h +++ b/Marlin/src/HAL/STM32/tft/tft_spi.h @@ -64,4 +64,11 @@ class TFT_SPI { static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_MINC_ENABLE, Data, Count); } static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_MINC_DISABLE, &Data, Count); } + static void WriteMultiple(uint16_t Color, uint32_t Count) { + static uint16_t Data; Data = Color; + while (Count > 0) { + TransmitDMA(DMA_MINC_DISABLE, &Data, Count > 0xFFFF ? 0xFFFF : Count); + Count = Count > 0xFFFF ? Count - 0xFFFF : 0; + } + } }; diff --git a/Marlin/src/HAL/STM32/tft/xpt2046.cpp b/Marlin/src/HAL/STM32/tft/xpt2046.cpp index 921e377a9f4e..912e6c2db761 100644 --- a/Marlin/src/HAL/STM32/tft/xpt2046.cpp +++ b/Marlin/src/HAL/STM32/tft/xpt2046.cpp @@ -1,6 +1,9 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * 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 @@ -16,10 +19,13 @@ * along with this program. If not, see . * */ +#include "../../platforms.h" + +#ifdef HAL_STM32 #include "../../../inc/MarlinConfig.h" -#if HAS_TFT_XPT2046 +#if HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS #include "xpt2046.h" #include "pinconfig.h" @@ -27,7 +33,6 @@ uint16_t delta(uint16_t a, uint16_t b) { return a > b ? a - b : b - a; } SPI_HandleTypeDef XPT2046::SPIx; -DMA_HandleTypeDef XPT2046::DMAtx; void XPT2046::Init() { SPI_TypeDef *spiInstance; @@ -67,43 +72,24 @@ void XPT2046::Init() { if (SPIx.Instance == SPI1) { __HAL_RCC_SPI1_CLK_ENABLE(); SPIx.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_16; - #ifdef STM32F1xx - DMAtx.Instance = DMA1_Channel3; - #elif defined(STM32F4xx) - DMAtx.Instance = DMA2_Stream3; // DMA2_Stream5 - #endif - //SERIAL_ECHO_MSG(" Touch Screen on SPI1"); } #endif #ifdef SPI2_BASE if (SPIx.Instance == SPI2) { __HAL_RCC_SPI2_CLK_ENABLE(); - #ifdef STM32F1xx - DMAtx.Instance = DMA1_Channel5; - #elif defined(STM32F4xx) - DMAtx.Instance = DMA1_Stream4; - #endif - //SERIAL_ECHO_MSG(" Touch Screen on SPI2"); } #endif #ifdef SPI3_BASE if (SPIx.Instance == SPI3) { __HAL_RCC_SPI3_CLK_ENABLE(); - #ifdef STM32F1xx - DMAtx.Instance = DMA2_Channel2; - #elif defined(STM32F4xx) - DMAtx.Instance = DMA1_Stream5; // DMA1_Stream7 - #endif - //SERIAL_ECHO_MSG(" Touch Screen on SPI3"); } #endif } else { - SPIx.Instance = NULL; + SPIx.Instance = nullptr; SET_INPUT(TOUCH_MISO_PIN); SET_OUTPUT(TOUCH_MOSI_PIN); SET_OUTPUT(TOUCH_SCK_PIN); - //SERIAL_ECHO_MSG(" Touch Screen on Software SPI"); } getRawData(XPT2046_Z1); @@ -183,3 +169,4 @@ uint16_t XPT2046::SoftwareIO(uint16_t data) { } #endif // HAS_TFT_XPT2046 +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/tft/xpt2046.h b/Marlin/src/HAL/STM32/tft/xpt2046.h index 7a6d8439c59c..2cff3e29d05b 100644 --- a/Marlin/src/HAL/STM32/tft/xpt2046.h +++ b/Marlin/src/HAL/STM32/tft/xpt2046.h @@ -1,6 +1,9 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * 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 @@ -53,23 +56,15 @@ enum XPTCoordinate : uint8_t { XPT2046_Z2 = 0x40 | XPT2046_CONTROL | XPT2046_DFR_MODE, }; -#if !defined(XPT2046_Z1_THRESHOLD) +#ifndef XPT2046_Z1_THRESHOLD #define XPT2046_Z1_THRESHOLD 10 #endif -#ifdef STM32F1xx - #define __IS_DMA_ENABLED(__HANDLE__) ((__HANDLE__)->Instance->CCR & DMA_CCR_EN) -#elif defined(STM32F4xx) - #define __IS_DMA_ENABLED(__HANDLE__) ((__HANDLE__)->Instance->CR & DMA_SxCR_EN) -#endif - - class XPT2046 { private: static SPI_HandleTypeDef SPIx; - static DMA_HandleTypeDef DMAtx; - static bool isBusy() { return SPIx.Instance ? __IS_DMA_ENABLED(&DMAtx) : false; } + static bool isBusy() { return false; } static uint16_t getRawData(const XPTCoordinate coordinate); static bool isTouched(); diff --git a/Marlin/src/HAL/STM32/timers.cpp b/Marlin/src/HAL/STM32/timers.cpp index c0ba19abe545..9b69323ef543 100644 --- a/Marlin/src/HAL/STM32/timers.cpp +++ b/Marlin/src/HAL/STM32/timers.cpp @@ -19,7 +19,9 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) +#include "../platforms.h" + +#ifdef HAL_STM32 #include "../../inc/MarlinConfig.h" @@ -27,8 +29,6 @@ // Local defines // ------------------------ -#define NUM_HARDWARE_TIMERS 2 - // Default timer priorities. Override by specifying alternate priorities in the board pins file. // The TONE timer is not present here, as it currently cannot be set programmatically. It is set // by defining TIM_IRQ_PRIO in the variant.h or platformio.ini file, which adjusts the default @@ -68,26 +68,23 @@ #endif #ifdef STM32F0xx - #define MCU_TIMER_RATE (F_CPU) // Frequency of timer peripherals #define MCU_STEP_TIMER 16 #define MCU_TEMP_TIMER 17 #elif defined(STM32F1xx) - #define MCU_TIMER_RATE (F_CPU) #define MCU_STEP_TIMER 4 #define MCU_TEMP_TIMER 2 #elif defined(STM32F401xC) || defined(STM32F401xE) - #define MCU_TIMER_RATE (F_CPU / 2) #define MCU_STEP_TIMER 9 #define MCU_TEMP_TIMER 10 -#elif defined(STM32F4xx) || defined(STM32F7xx) - #define MCU_TIMER_RATE (F_CPU / 2) +#elif defined(STM32F4xx) || defined(STM32F7xx) || defined(STM32H7xx) #define MCU_STEP_TIMER 6 // STM32F401 has no TIM6, TIM7, or TIM8 #define MCU_TEMP_TIMER 14 // TIM7 is consumed by Software Serial if used. #endif #ifndef HAL_TIMER_RATE - #define HAL_TIMER_RATE MCU_TIMER_RATE + #define HAL_TIMER_RATE GetStepperTimerClkFreq() #endif + #ifndef STEP_TIMER #define STEP_TIMER MCU_STEP_TIMER #endif @@ -100,21 +97,23 @@ #define STEP_TIMER_DEV _TIMER_DEV(STEP_TIMER) #define TEMP_TIMER_DEV _TIMER_DEV(TEMP_TIMER) -#define __TIMER_IRQ_NAME(X) TIM##X##_IRQn -#define _TIMER_IRQ_NAME(X) __TIMER_IRQ_NAME(X) -#define STEP_TIMER_IRQ_NAME _TIMER_IRQ_NAME(STEP_TIMER) -#define TEMP_TIMER_IRQ_NAME _TIMER_IRQ_NAME(TEMP_TIMER) - // ------------------------ // Private Variables // ------------------------ -HardwareTimer *timer_instance[NUM_HARDWARE_TIMERS] = { NULL }; +HardwareTimer *timer_instance[NUM_HARDWARE_TIMERS] = { nullptr }; // ------------------------ // Public functions // ------------------------ +uint32_t GetStepperTimerClkFreq() { + // Timer input clocks vary between devices, and in some cases between timers on the same device. + // Retrieve at runtime to ensure device compatibility. Cache result to avoid repeated overhead. + static uint32_t clkfreq = timer_instance[STEP_TIMER_NUM]->getTimerClkFreq(); + return clkfreq; +} + // frequency is in Hertz void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { if (!HAL_timer_initialized(timer_num)) { @@ -194,87 +193,132 @@ void SetTimerInterruptPriorities() { TERN_(HAS_SERVOS, libServo::setInterruptPriority(SERVO_TIMER_IRQ_PRIO, 0)); } -// This is a terrible hack to replicate the behavior used in the framework's SoftwareSerial.cpp -// to choose a serial timer. It will select TIM7 on most boards used by Marlin, but this is more -// resiliant to new MCUs which may not have a TIM7. Best practice is to explicitly specify -// TIMER_SERIAL to avoid relying on framework selections which may not be predictable. -#if !defined(TIMER_SERIAL) - #if defined (TIM18_BASE) - #define TIMER_SERIAL TIM18 - #elif defined (TIM7_BASE) - #define TIMER_SERIAL TIM7 - #elif defined (TIM6_BASE) - #define TIMER_SERIAL TIM6 - #elif defined (TIM22_BASE) - #define TIMER_SERIAL TIM22 - #elif defined (TIM21_BASE) - #define TIMER_SERIAL TIM21 - #elif defined (TIM17_BASE) - #define TIMER_SERIAL TIM17 - #elif defined (TIM16_BASE) - #define TIMER_SERIAL TIM16 - #elif defined (TIM15_BASE) - #define TIMER_SERIAL TIM15 - #elif defined (TIM14_BASE) - #define TIMER_SERIAL TIM14 - #elif defined (TIM13_BASE) - #define TIMER_SERIAL TIM13 - #elif defined (TIM11_BASE) - #define TIMER_SERIAL TIM11 - #elif defined (TIM10_BASE) - #define TIMER_SERIAL TIM10 - #elif defined (TIM12_BASE) - #define TIMER_SERIAL TIM12 - #elif defined (TIM19_BASE) - #define TIMER_SERIAL TIM19 - #elif defined (TIM9_BASE) - #define TIMER_SERIAL TIM9 - #elif defined (TIM5_BASE) - #define TIMER_SERIAL TIM5 - #elif defined (TIM4_BASE) - #define TIMER_SERIAL TIM4 - #elif defined (TIM3_BASE) - #define TIMER_SERIAL TIM3 - #elif defined (TIM2_BASE) - #define TIMER_SERIAL TIM2 - #elif defined (TIM20_BASE) - #define TIMER_SERIAL TIM20 - #elif defined (TIM8_BASE) - #define TIMER_SERIAL TIM8 - #elif defined (TIM1_BASE) - #define TIMER_SERIAL TIM1 - #else - #error No suitable timer found for SoftwareSerial, define TIMER_SERIAL in variant.h +// ------------------------ +// Detect timer conflicts +// ------------------------ + +// This list serves two purposes. Firstly, it facilitates build-time mapping between +// variant-defined timer names (such as TIM1) and timer numbers. It also replicates +// the order of timers used in the framework's SoftwareSerial.cpp. The first timer in +// this list will be automatically used by SoftwareSerial if it is not already defined +// in the board's variant or compiler options. +static constexpr struct {uintptr_t base_address; int timer_number;} stm32_timer_map[] = { + #ifdef TIM18_BASE + { uintptr_t(TIM18), 18 }, + #endif + #ifdef TIM7_BASE + { uintptr_t(TIM7), 7 }, + #endif + #ifdef TIM6_BASE + { uintptr_t(TIM6), 6 }, + #endif + #ifdef TIM22_BASE + { uintptr_t(TIM22), 22 }, + #endif + #ifdef TIM21_BASE + { uintptr_t(TIM21), 21 }, + #endif + #ifdef TIM17_BASE + { uintptr_t(TIM17), 17 }, + #endif + #ifdef TIM16_BASE + { uintptr_t(TIM16), 16 }, + #endif + #ifdef TIM15_BASE + { uintptr_t(TIM15), 15 }, + #endif + #ifdef TIM14_BASE + { uintptr_t(TIM14), 14 }, + #endif + #ifdef TIM13_BASE + { uintptr_t(TIM13), 13 }, #endif + #ifdef TIM11_BASE + { uintptr_t(TIM11), 11 }, + #endif + #ifdef TIM10_BASE + { uintptr_t(TIM10), 10 }, + #endif + #ifdef TIM12_BASE + { uintptr_t(TIM12), 12 }, + #endif + #ifdef TIM19_BASE + { uintptr_t(TIM19), 19 }, + #endif + #ifdef TIM9_BASE + { uintptr_t(TIM9), 9 }, + #endif + #ifdef TIM5_BASE + { uintptr_t(TIM5), 5 }, + #endif + #ifdef TIM4_BASE + { uintptr_t(TIM4), 4 }, + #endif + #ifdef TIM3_BASE + { uintptr_t(TIM3), 3 }, + #endif + #ifdef TIM2_BASE + { uintptr_t(TIM2), 2 }, + #endif + #ifdef TIM20_BASE + { uintptr_t(TIM20), 20 }, + #endif + #ifdef TIM8_BASE + { uintptr_t(TIM8), 8 }, + #endif + #ifdef TIM1_BASE + { uintptr_t(TIM1), 1 } + #endif +}; + +// Convert from a timer base address to its integer timer number. +static constexpr int get_timer_num_from_base_address(uintptr_t base_address) { + for (const auto &timer : stm32_timer_map) + if (timer.base_address == base_address) return timer.timer_number; + return 0; +} + +// The platform's SoftwareSerial.cpp will use the first timer from stm32_timer_map. +#if HAS_TMC_SW_SERIAL && !defined(TIMER_SERIAL) + #define TIMER_SERIAL (stm32_timer_map[0].base_address) #endif -// Place all timers used into an array, then recursively check for duplicates during compilation. -// This does not currently account for timers used for PWM, such as for fans. -// Timers are actually pointers. Convert to integers to simplify constexpr logic. -static constexpr uintptr_t timers_in_use[] = { - uintptr_t(TEMP_TIMER_DEV), // Override in pins file - uintptr_t(STEP_TIMER_DEV), // Override in pins file +// 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)}); + +enum TimerPurpose { TP_SERIAL, TP_TONE, TP_SERVO, TP_STEP, TP_TEMP }; + +// List of timers, to enable checking for conflicts. +// Includes the purpose of each timer to ease debugging when evaluating at build-time. +// This cannot yet account for timers used for PWM output, such as for fans. +static constexpr struct { TimerPurpose p; int t; } timers_in_use[] = { #if HAS_TMC_SW_SERIAL - uintptr_t(TIMER_SERIAL), // Set in variant.h, or as a define in platformio.h if not present in variant.h + {TP_SERIAL, get_timer_num_from_base_address(timer_serial[0])}, // Set in variant.h, or as a define in platformio.h if not present in variant.h #endif #if ENABLED(SPEAKER) - uintptr_t(TIMER_TONE), // Set in variant.h, or as a define in platformio.h if not present in variant.h + {TP_TONE, get_timer_num_from_base_address(timer_tone[0])}, // Set in variant.h, or as a define in platformio.h if not present in variant.h #endif #if HAS_SERVOS - uintptr_t(TIMER_SERVO), // Set in variant.h, or as a define in platformio.h if not present in variant.h + {TP_SERVO, get_timer_num_from_base_address(timer_servo[0])}, // Set in variant.h, or as a define in platformio.h if not present in variant.h #endif - }; + {TP_STEP, STEP_TIMER}, + {TP_TEMP, TEMP_TIMER}, +}; -static constexpr bool verify_no_duplicate_timers() { +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)) - if (timers_in_use[i] == timers_in_use[j]) return false; + if (timers_in_use[i].t == timers_in_use[j].t) return false; return true; } -// If this assertion fails at compile time, review the timers_in_use array. If default_envs is -// defined properly in platformio.ini, VS Code can evaluate the array when hovering over it, -// making it easy to identify the conflicting timers. -static_assert(verify_no_duplicate_timers(), "One or more timer conflict detected"); +// If this assertion fails at compile time, review the timers_in_use array. +// If default_envs is defined properly in platformio.ini, VS Code can evaluate the array +// when hovering over it, making it easy to identify the conflicting timers. +static_assert(verify_no_timer_conflicts(), "One or more timer conflict detected. Examine \"timers_in_use\" to help identify conflict."); -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/timers.h b/Marlin/src/HAL/STM32/timers.h index 5515219ead00..7a35e432102d 100644 --- a/Marlin/src/HAL/STM32/timers.h +++ b/Marlin/src/HAL/STM32/timers.h @@ -21,15 +21,12 @@ */ #pragma once -#include #include "../../inc/MarlinConfig.h" // ------------------------ // Defines // ------------------------ -#define FORCE_INLINE __attribute__((always_inline)) inline - // STM32 timers may be 16 or 32 bit. Limiting HAL_TIMER_TYPE_MAX to 16 bits // avoids issues with STM32F0 MCUs, which seem to pause timers if UINT32_MAX // is written to the register. STM32F4 timers do not manifest this issue, @@ -43,6 +40,8 @@ #define hal_timer_t uint32_t #define HAL_TIMER_TYPE_MAX UINT16_MAX +#define NUM_HARDWARE_TIMERS 2 + #ifndef STEP_TIMER_NUM #define STEP_TIMER_NUM 0 // Timer Index for Stepper #endif @@ -57,7 +56,8 @@ // TODO: get rid of manual rate/prescale/ticks/cycles taken for procedures in stepper.cpp #define STEPPER_TIMER_RATE 2000000 // 2 Mhz -#define STEPPER_TIMER_PRESCALE ((HAL_TIMER_RATE)/(STEPPER_TIMER_RATE)) +extern uint32_t GetStepperTimerClkFreq(); +#define STEPPER_TIMER_PRESCALE (GetStepperTimerClkFreq() / (STEPPER_TIMER_RATE)) #define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs #define PULSE_TIMER_RATE STEPPER_TIMER_RATE @@ -102,7 +102,7 @@ void SetTimerInterruptPriorities(); // FORCE_INLINE because these are used in performance-critical situations FORCE_INLINE bool HAL_timer_initialized(const uint8_t timer_num) { - return timer_instance[timer_num] != NULL; + return timer_instance[timer_num] != nullptr; } FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) { return HAL_timer_initialized(timer_num) ? timer_instance[timer_num]->getCount() : 0; diff --git a/Marlin/src/HAL/STM32/usb_host.cpp b/Marlin/src/HAL/STM32/usb_host.cpp new file mode 100644 index 000000000000..d2d1d69a1a8d --- /dev/null +++ b/Marlin/src/HAL/STM32/usb_host.cpp @@ -0,0 +1,118 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../platforms.h" + +#ifdef HAL_STM32 + +#include "../../inc/MarlinConfig.h" + +#if BOTH(USE_OTG_USB_HOST, USBHOST) + +#include "usb_host.h" +#include "../shared/Marduino.h" +#include "usbh_core.h" +#include "usbh_msc.h" + +USBH_HandleTypeDef hUsbHost; +USBHost usb; +BulkStorage bulk(&usb); + +static void USBH_UserProcess(USBH_HandleTypeDef *phost, uint8_t id) { + switch(id) { + case HOST_USER_SELECT_CONFIGURATION: + //SERIAL_ECHOLNPGM("APPLICATION_SELECT_CONFIGURATION"); + break; + case HOST_USER_DISCONNECTION: + //SERIAL_ECHOLNPGM("APPLICATION_DISCONNECT"); + //usb.setUsbTaskState(USB_STATE_RUNNING); + break; + case HOST_USER_CLASS_ACTIVE: + //SERIAL_ECHOLNPGM("APPLICATION_READY"); + usb.setUsbTaskState(USB_STATE_RUNNING); + break; + case HOST_USER_CONNECTION: + break; + default: + break; + } +} + +bool USBHost::start() { + if (USBH_Init(&hUsbHost, USBH_UserProcess, TERN(USE_USB_HS_IN_FS, HOST_HS, HOST_FS)) != USBH_OK) { + SERIAL_ECHOLNPGM("Error: USBH_Init"); + return false; + } + if (USBH_RegisterClass(&hUsbHost, USBH_MSC_CLASS) != USBH_OK) { + SERIAL_ECHOLNPGM("Error: USBH_RegisterClass"); + return false; + } + if (USBH_Start(&hUsbHost) != USBH_OK) { + SERIAL_ECHOLNPGM("Error: USBH_Start"); + return false; + } + return true; +} + +void USBHost::Task() { + USBH_Process(&hUsbHost); +} + +uint8_t USBHost::getUsbTaskState() { + return usb_task_state; +} + +void USBHost::setUsbTaskState(uint8_t state) { + usb_task_state = state; + if (usb_task_state == USB_STATE_RUNNING) { + MSC_LUNTypeDef info; + USBH_MSC_GetLUNInfo(&hUsbHost, usb.lun, &info); + capacity = info.capacity.block_nbr / 2000; + block_size = info.capacity.block_size; + block_count = info.capacity.block_nbr; + // SERIAL_ECHOLNPAIR("info.capacity.block_nbr : %ld\n", info.capacity.block_nbr); + // SERIAL_ECHOLNPAIR("info.capacity.block_size: %d\n", info.capacity.block_size); + // SERIAL_ECHOLNPAIR("capacity : %d MB\n", capacity); + } +}; + +bool BulkStorage::LUNIsGood(uint8_t t) { + return USBH_MSC_IsReady(&hUsbHost) && USBH_MSC_UnitIsReady(&hUsbHost, t); +} + +uint32_t BulkStorage::GetCapacity(uint8_t lun) { + return usb->block_count; +} + +uint16_t BulkStorage::GetSectorSize(uint8_t lun) { + return usb->block_size; +} + +uint8_t BulkStorage::Read(uint8_t lun, uint32_t addr, uint16_t bsize, uint8_t blocks, uint8_t *buf) { + return USBH_MSC_Read(&hUsbHost, lun, addr, buf, blocks) != USBH_OK; +} + +uint8_t BulkStorage::Write(uint8_t lun, uint32_t addr, uint16_t bsize, uint8_t blocks, const uint8_t * buf) { + return USBH_MSC_Write(&hUsbHost, lun, addr, const_cast(buf), blocks) != USBH_OK; +} + +#endif // USE_OTG_USB_HOST && USBHOST +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/usb_host.h b/Marlin/src/HAL/STM32/usb_host.h new file mode 100644 index 000000000000..c0001c0d755b --- /dev/null +++ b/Marlin/src/HAL/STM32/usb_host.h @@ -0,0 +1,60 @@ +/** + * 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 + +#include + +typedef enum { + USB_STATE_INIT, + USB_STATE_ERROR, + USB_STATE_RUNNING, +} usb_state_t; + +class USBHost { +public: + bool start(); + void Task(); + uint8_t getUsbTaskState(); + void setUsbTaskState(uint8_t state); + uint8_t regRd(uint8_t reg) { return 0x0; }; + uint8_t usb_task_state = USB_STATE_INIT; + uint8_t lun = 0; + uint32_t capacity = 0; + uint16_t block_size = 0; + uint32_t block_count = 0; +}; + +class BulkStorage { +public: + BulkStorage(USBHost *usb) : usb(usb) {}; + + bool LUNIsGood(uint8_t t); + uint32_t GetCapacity(uint8_t lun); + uint16_t GetSectorSize(uint8_t lun); + uint8_t Read(uint8_t lun, uint32_t addr, uint16_t bsize, uint8_t blocks, uint8_t *buf); + uint8_t Write(uint8_t lun, uint32_t addr, uint16_t bsize, uint8_t blocks, const uint8_t * buf); + + USBHost *usb; +}; + +extern USBHost usb; +extern BulkStorage bulk; diff --git a/Marlin/src/HAL/STM32/usb_serial.cpp b/Marlin/src/HAL/STM32/usb_serial.cpp index 2dd1bef12c43..959ca4ff4319 100644 --- a/Marlin/src/HAL/STM32/usb_serial.cpp +++ b/Marlin/src/HAL/STM32/usb_serial.cpp @@ -16,12 +16,13 @@ * along with this program. If not, see . * */ +#include "../platforms.h" -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) +#ifdef HAL_STM32 #include "../../inc/MarlinConfigPre.h" -#if ENABLED(EMERGENCY_PARSER) +#if ENABLED(EMERGENCY_PARSER) && USBD_USE_CDC #include "usb_serial.h" #include "../../feature/e_parser.h" @@ -51,5 +52,5 @@ void USB_Hook_init() { USBD_CDC_fops.Receive = USBD_CDC_Receive_hook; } -#endif // EMERGENCY_PARSER -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC +#endif // EMERGENCY_PARSER && USBD_USE_CDC +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/watchdog.cpp b/Marlin/src/HAL/STM32/watchdog.cpp index cc1855314968..72c74a2e3b5b 100644 --- a/Marlin/src/HAL/STM32/watchdog.cpp +++ b/Marlin/src/HAL/STM32/watchdog.cpp @@ -19,29 +19,33 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) +#include "../platforms.h" + +#ifdef HAL_STM32 #include "../../inc/MarlinConfigPre.h" #if ENABLED(USE_WATCHDOG) - #include "../../inc/MarlinConfig.h" +#define WDT_TIMEOUT_US TERN(WATCHDOG_DURATION_8S, 8000000, 4000000) // 4 or 8 second timeout + +#include "../../inc/MarlinConfig.h" - #include "watchdog.h" - #include +#include "watchdog.h" +#include - void watchdog_init() { - #if DISABLED(DISABLE_WATCHDOG_INIT) - IWatchdog.begin(4000000); // 4 sec timeout - #endif - } +void watchdog_init() { + #if DISABLED(DISABLE_WATCHDOG_INIT) + IWatchdog.begin(WDT_TIMEOUT_US); + #endif +} - void HAL_watchdog_refresh() { - IWatchdog.reload(); - #if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED) - TOGGLE(LED_PIN); // heartbeat indicator - #endif - } +void HAL_watchdog_refresh() { + IWatchdog.reload(); + #if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED) + TOGGLE(LED_PIN); // heartbeat indicator + #endif +} #endif // USE_WATCHDOG -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32F1/HAL.cpp b/Marlin/src/HAL/STM32F1/HAL.cpp index cd1efc16591d..73014945a156 100644 --- a/Marlin/src/HAL/STM32F1/HAL.cpp +++ b/Marlin/src/HAL/STM32F1/HAL.cpp @@ -82,8 +82,34 @@ // Public Variables // ------------------------ -#if (defined(SERIAL_USB) && !defined(USE_USB_COMPOSITE)) +#if defined(SERIAL_USB) && !HAS_SD_HOST_DRIVE USBSerial SerialUSB; + DefaultSerial1 MSerial0(true, SerialUSB); + + #if ENABLED(EMERGENCY_PARSER) + #include "../libmaple/usb/stm32f1/usb_reg_map.h" + #include "libmaple/usb_cdcacm.h" + // The original callback is not called (no way to retrieve address). + // That callback detects a special STM32 reset sequence: this functionality is not essential + // as M997 achieves the same. + void my_rx_callback(unsigned int, void*) { + // max length of 16 is enough to contain all emergency commands + uint8 buf[16]; + + //rx is usbSerialPart.endpoints[2] + uint16 len = usb_get_ep_rx_count(USB_CDCACM_RX_ENDP); + uint32 total = usb_cdcacm_data_available(); + + if (len == 0 || total == 0 || !WITHIN(total, len, COUNT(buf))) + return; + + // cannot get character by character due to bug in composite_cdcacm_peek_ex + len = usb_cdcacm_peek(buf, total); + + for (uint32 i = 0; i < len; i++) + emergency_parser.update(MSerial0.emergency_state, buf[i + total - len]); + } + #endif #endif uint16_t HAL_adc_result; @@ -106,6 +132,9 @@ const uint8_t adc_pins[] = { #if HAS_TEMP_CHAMBER TEMP_CHAMBER_PIN, #endif + #if HAS_TEMP_COOLER + TEMP_COOLER_PIN, + #endif #if HAS_TEMP_ADC_1 TEMP_1_PIN, #endif @@ -130,7 +159,7 @@ const uint8_t adc_pins[] = { #if ENABLED(FILAMENT_WIDTH_SENSOR) FILWIDTH_PIN, #endif - #if ENABLED(ADC_KEYPAD) + #if HAS_ADC_BUTTONS ADC_KEYPAD_PIN, #endif #if HAS_JOY_ADC_X @@ -163,6 +192,9 @@ enum TempPinIndex : char { #if HAS_TEMP_CHAMBER TEMP_CHAMBER, #endif + #if HAS_TEMP_COOLER + TEMP_COOLER_PIN, + #endif #if HAS_TEMP_ADC_1 TEMP_1, #endif @@ -187,7 +219,7 @@ enum TempPinIndex : char { #if ENABLED(FILAMENT_WIDTH_SENSOR) FILWIDTH, #endif - #if ENABLED(ADC_KEYPAD) + #if HAS_ADC_BUTTONS ADC_KEY, #endif #if HAS_JOY_ADC_X @@ -221,7 +253,7 @@ static void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) { reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); /* clear bits to change */ reg_value = (reg_value | ((uint32_t)0x5FA << SCB_AIRCR_VECTKEY_Pos) | - (PriorityGroupTmp << 8)); /* Insert write key and priorty group */ + (PriorityGroupTmp << 8)); /* Insert write key & priority group */ SCB->AIRCR = reg_value; } @@ -246,34 +278,37 @@ static void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) { } } #endif +TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); + void HAL_init() { NVIC_SetPriorityGrouping(0x3); #if PIN_EXISTS(LED) OUT_WRITE(LED_PIN, LOW); #endif - #ifdef USE_USB_COMPOSITE + #if HAS_SD_HOST_DRIVE MSC_SD_init(); + #elif BOTH(SERIAL_USB, EMERGENCY_PARSER) + usb_cdcacm_set_hooks(USB_CDCACM_HOOK_RX, my_rx_callback); #endif #if PIN_EXISTS(USB_CONNECT) OUT_WRITE(USB_CONNECT_PIN, !USB_CONNECT_INVERTING); // USB clear connection delay(1000); // Give OS time to notice - OUT_WRITE(USB_CONNECT_PIN, USB_CONNECT_INVERTING); + WRITE(USB_CONNECT_PIN, USB_CONNECT_INVERTING); #endif + TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the minimal serial handler } // HAL idle task void HAL_idletask() { - #ifdef USE_USB_COMPOSITE - #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()) - /* copy from lpc1768 framework, should be fixed later for process HAS_SHARED_MEDIA*/ - #endif + #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()) + /* copy from lpc1768 framework, should be fixed later for process HAS_SD_HOST_DRIVE*/ // process USB mass storage device class loop MarlinMSC.loop(); #endif @@ -356,6 +391,9 @@ void HAL_adc_start_conversion(const uint8_t adc_pin) { #if HAS_TEMP_CHAMBER case TEMP_CHAMBER_PIN: pin_index = TEMP_CHAMBER; break; #endif + #if HAS_TEMP_COOLER + case TEMP_COOLER_PIN: pin_index = TEMP_COOLER; break; + #endif #if HAS_TEMP_ADC_1 case TEMP_1_PIN: pin_index = TEMP_1; break; #endif @@ -389,7 +427,7 @@ void HAL_adc_start_conversion(const uint8_t adc_pin) { #if ENABLED(FILAMENT_WIDTH_SENSOR) case FILWIDTH_PIN: pin_index = FILWIDTH; break; #endif - #if ENABLED(ADC_KEYPAD) + #if HAS_ADC_BUTTONS case ADC_KEYPAD_PIN: pin_index = ADC_KEY; break; #endif #if ENABLED(POWER_MONITOR_CURRENT) @@ -415,6 +453,8 @@ void analogWrite(pin_t pin, int pwm_val8) { analogWrite(uint8_t(pin), pwm_val8); } -void flashFirmware(const int16_t) { nvic_sys_reset(); } +void HAL_reboot() { nvic_sys_reset(); } + +void flashFirmware(const int16_t) { HAL_reboot(); } #endif // __STM32F1__ diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index c10dea0eafd1..b3d8dc9d0b3e 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -36,13 +36,12 @@ #include "fastio.h" #include "watchdog.h" - #include #include #include "../../inc/MarlinConfigPre.h" -#ifdef USE_USB_COMPOSITE +#if HAS_SD_HOST_DRIVE #include "msc_sd.h" #endif @@ -53,7 +52,7 @@ // ------------------------ #ifndef STM32_FLASH_SIZE - #if EITHER(MCU_STM32F103RE, MCU_STM32F103VE) + #if ANY(MCU_STM32F103RE, MCU_STM32F103VE, MCU_STM32F103ZE) #define STM32_FLASH_SIZE 512 #else #define STM32_FLASH_SIZE 256 @@ -61,10 +60,12 @@ #endif #ifdef SERIAL_USB - #ifndef USE_USB_COMPOSITE - #define UsbSerial Serial - #else + typedef ForwardSerial1Class< USBSerial > DefaultSerial1; + extern DefaultSerial1 MSerial0; + #if HAS_SD_HOST_DRIVE #define UsbSerial MarlinCompositeSerial + #else + #define UsbSerial MSerial0 #endif #endif @@ -78,24 +79,44 @@ #endif #if SERIAL_PORT == -1 - #define MYSERIAL0 UsbSerial + #define MYSERIAL1 UsbSerial #elif WITHIN(SERIAL_PORT, 1, NUM_UARTS) - #define MYSERIAL0 MSERIAL(SERIAL_PORT) -#elif NUM_UARTS == 5 - #error "SERIAL_PORT must be -1 or from 1 to 5. Please update your configuration." + #define MYSERIAL1 MSERIAL(SERIAL_PORT) #else - #error "SERIAL_PORT must be -1 or from 1 to 3. Please update your configuration." + #define MYSERIAL1 MSERIAL(1) // dummy port + static_assert(false, "SERIAL_PORT must be from 1 to " STRINGIFY(NUM_UARTS) ". You can also use -1 if the board supports Native USB.") #endif #ifdef SERIAL_PORT_2 #if SERIAL_PORT_2 == -1 - #define MYSERIAL1 UsbSerial + #define MYSERIAL2 UsbSerial #elif WITHIN(SERIAL_PORT_2, 1, NUM_UARTS) - #define MYSERIAL1 MSERIAL(SERIAL_PORT_2) - #elif NUM_UARTS == 5 - #error "SERIAL_PORT_2 must be -1 or from 1 to 5. Please update your configuration." + #define MYSERIAL2 MSERIAL(SERIAL_PORT_2) + #else + #define MYSERIAL2 MSERIAL(1) // dummy port + static_assert(false, "SERIAL_PORT_2 must be from 1 to " STRINGIFY(NUM_UARTS) ". You can also use -1 if the board supports Native USB.") + #endif +#endif + +#ifdef SERIAL_PORT_3 + #if SERIAL_PORT_3 == -1 + #define MYSERIAL3 UsbSerial + #elif WITHIN(SERIAL_PORT_3, 1, NUM_UARTS) + #define MYSERIAL3 MSERIAL(SERIAL_PORT_3) #else - #error "SERIAL_PORT_2 must be -1 or from 1 to 3. Please update your configuration." + #define MYSERIAL3 MSERIAL(1) // dummy port + static_assert(false, "SERIAL_PORT_3 must be from 1 to " STRINGIFY(NUM_UARTS) ". You can also use -1 if the board supports Native USB.") + #endif +#endif + +#ifdef MMU2_SERIAL_PORT + #if MMU2_SERIAL_PORT == -1 + #define MMU2_SERIAL UsbSerial + #elif WITHIN(MMU2_SERIAL_PORT, 1, NUM_UARTS) + #define MMU2_SERIAL MSERIAL(MMU2_SERIAL_PORT) + #else + #define MMU2_SERIAL MSERIAL(1) // dummy port + static_assert(false, "MMU2_SERIAL_PORT must be from 1 to " STRINGIFY(NUM_UARTS) ". You can also use -1 if the board supports Native USB.") #endif #endif @@ -104,10 +125,12 @@ #define LCD_SERIAL UsbSerial #elif WITHIN(LCD_SERIAL_PORT, 1, NUM_UARTS) #define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT) - #elif NUM_UARTS == 5 - #error "LCD_SERIAL_PORT must be -1 or from 1 to 5. Please update your configuration." #else - #error "LCD_SERIAL_PORT must be -1 or from 1 to 3. Please update your configuration." + #define LCD_SERIAL MSERIAL(1) // dummy port + 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() #endif #endif @@ -124,7 +147,7 @@ void HAL_idletask(); #endif #ifndef digitalPinHasPWM - #define digitalPinHasPWM(P) (PIN_MAP[P].timer_device != nullptr) + #define digitalPinHasPWM(P) !!PIN_MAP[P].timer_device #define NO_COMPILE_TIME_PWM #endif @@ -137,14 +160,6 @@ void HAL_idletask(); // On AVR this is in math.h? #define square(x) ((x)*(x)) -#ifndef strncpy_P - #define strncpy_P(dest, src, num) strncpy((dest), (src), (num)) -#endif - -// Fix bug in pgm_read_ptr -#undef pgm_read_ptr -#define pgm_read_ptr(addr) (*(addr)) - #define RST_POWER_ON 1 #define RST_EXTERNAL 2 #define RST_BROWN_OUT 4 @@ -185,7 +200,7 @@ void HAL_clear_reset_source(); // Reset reason uint8_t HAL_get_reset_source(); -inline void HAL_reboot() {} // reboot the board or restart the bootloader +void HAL_reboot(); void _delay_ms(const int delay); @@ -200,17 +215,9 @@ extern "C" { extern "C" char* _sbrk(int incr); -/* -static int freeMemory() { - volatile int top; - top = (int)((char*)&top - reinterpret_cast(_sbrk(0))); - return top; -} -*/ - -static int freeMemory() { +static inline int freeMemory() { volatile char top; - return &top - reinterpret_cast(_sbrk(0)); + return &top - _sbrk(0); } #pragma GCC diagnostic pop @@ -244,3 +251,20 @@ void analogWrite(pin_t pin, int pwm_val8); // PWM only! mul by 257 in maple!? #define PLATFORM_M997_SUPPORT void flashFirmware(const int16_t); + +#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment + +/** + * set_pwm_frequency + * Set the frequency of the timer corresponding to the provided pin + * All Timer PWM pins run at the same frequency + */ +void set_pwm_frequency(const pin_t pin, int f_desired); + +/** + * set_pwm_duty + * Set the PWM duty cycle of the provided pin to the provided value + * Optionally allows inverting the duty cycle [default = false] + * Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255] + */ +void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); diff --git a/Marlin/src/HAL/STM32F1/HAL_MinSerial.cpp b/Marlin/src/HAL/STM32F1/HAL_MinSerial.cpp new file mode 100644 index 000000000000..0fc3d014d484 --- /dev/null +++ b/Marlin/src/HAL/STM32F1/HAL_MinSerial.cpp @@ -0,0 +1,118 @@ +/** + * 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 + * 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 + * 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 __STM32F1__ + +#include "../../inc/MarlinConfigPre.h" + +#if ENABLED(POSTMORTEM_DEBUGGING) + +#include "../shared/HAL_MinSerial.h" +#include "watchdog.h" + +#include +#include +#include + +/* Instruction Synchronization Barrier */ +#define isb() __asm__ __volatile__ ("isb" : : : "memory") + +/* Data Synchronization Barrier */ +#define dsb() __asm__ __volatile__ ("dsb" : : : "memory") + +static void TXBegin() { + #if !WITHIN(SERIAL_PORT, 1, 6) + #warning "Using POSTMORTEM_DEBUGGING requires a physical U(S)ART hardware in case of severe error." + #warning "Disabling the severe error reporting feature currently because the used serial port is not a HW port." + #else + // We use MYSERIAL1 here, so we need to figure out how to get the linked register + struct usart_dev* dev = MYSERIAL1.c_dev(); + + // Or use this if removing libmaple + // int irq = dev->irq_num; + // int nvicUART[] = { NVIC_USART1 /* = 37 */, NVIC_USART2 /* = 38 */, NVIC_USART3 /* = 39 */, NVIC_UART4 /* = 52 */, NVIC_UART5 /* = 53 */ }; + // Disabling irq means setting the bit in the NVIC ICER register located at + // Disable UART interrupt in NVIC + nvic_irq_disable(dev->irq_num); + + // Use this if removing libmaple + //SBI(NVIC_BASE->ICER[1], irq - 32); + + // We NEED memory barriers to ensure Interrupts are actually disabled! + // ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the ) + dsb(); + isb(); + + rcc_clk_disable(dev->clk_id); + rcc_clk_enable(dev->clk_id); + + usart_reg_map *regs = dev->regs; + regs->CR1 = 0; // Reset the USART + regs->CR2 = 0; // 1 stop bit + + // If we don't touch the BRR (baudrate register), we don't need to recompute. Else we would need to call + usart_set_baud_rate(dev, 0, BAUDRATE); + + regs->CR1 = (USART_CR1_TE | USART_CR1_UE); // 8 bits, no parity, 1 stop bit + #endif +} + +// 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) + struct usart_dev* dev = MYSERIAL1.c_dev(); + while (!(dev->regs->SR & USART_SR_TXE)) { + TERN_(USE_WATCHDOG, HAL_watchdog_refresh()); + sw_barrier(); + } + dev->regs->DR = c; + #endif +} + +void install_min_serial() { + HAL_min_serial_init = &TXBegin; + HAL_min_serial_out = &TX; +} + +#if DISABLED(DYNAMIC_VECTORTABLE) && DISABLED(STM32F0xx) // Cortex M0 can't branch to a symbol that's too far, so we have a specific hack for them +extern "C" { + __attribute__((naked)) void JumpHandler_ASM() { + __asm__ __volatile__ ( + "b CommonHandler_ASM\n" + ); + } + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) __exc_hardfault(); + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) __exc_busfault(); + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) __exc_usagefault(); + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) __exc_memmanage(); + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) __exc_nmi(); + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) __stm32reservedexception7(); + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) __stm32reservedexception8(); + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) __stm32reservedexception9(); + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) __stm32reservedexception10(); + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) __stm32reservedexception13(); +} +#endif + +#endif // POSTMORTEM_DEBUGGING +#endif // __STM32F1__ diff --git a/Marlin/src/HAL/STM32F1/HAL_SPI.cpp b/Marlin/src/HAL/STM32F1/HAL_SPI.cpp index 76b1c3e2468b..abb348d743c5 100644 --- a/Marlin/src/HAL/STM32F1/HAL_SPI.cpp +++ b/Marlin/src/HAL/STM32F1/HAL_SPI.cpp @@ -61,8 +61,8 @@ * @details Only configures SS pin since libmaple creates and initialize the SPI object */ void spiBegin() { - #if PIN_EXISTS(SS) - OUT_WRITE(SS_PIN, HIGH); + #if PIN_EXISTS(SD_SS) + OUT_WRITE(SD_SS_PIN, HIGH); #endif } @@ -123,7 +123,7 @@ uint8_t spiRec() { * * @details Uses DMA */ -void spiRead(uint8_t* buf, uint16_t nbyte) { +void spiRead(uint8_t *buf, uint16_t nbyte) { SPI.dmaTransfer(0, const_cast(buf), nbyte); } @@ -146,7 +146,7 @@ void spiSend(uint8_t b) { * * @details Use DMA */ -void spiSendBlock(uint8_t token, const uint8_t* buf) { +void spiSendBlock(uint8_t token, const uint8_t *buf) { SPI.send(token); SPI.dmaSend(const_cast(buf), 512); } @@ -160,7 +160,7 @@ uint8_t spiRec(uint32_t chan) { return SPI.transfer(0xFF); } void spiSend(uint32_t chan, byte b) { SPI.send(b); } // Write buffer to specified SPI channel -void spiSend(uint32_t chan, const uint8_t* buf, size_t n) { +void spiSend(uint32_t chan, const uint8_t *buf, size_t n) { for (size_t p = 0; p < n; p++) spiSend(chan, buf[p]); } diff --git a/Marlin/src/HAL/STM32F1/MarlinSPI.h b/Marlin/src/HAL/STM32F1/MarlinSPI.h new file mode 100644 index 000000000000..fab245f904e3 --- /dev/null +++ b/Marlin/src/HAL/STM32F1/MarlinSPI.h @@ -0,0 +1,45 @@ +/** + * 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 + +#include + +/** + * Marlin currently requires 3 SPI classes: + * + * SPIClass: + * This class is normally provided by frameworks and has a semi-default interface. + * This is needed because some libraries reference it globally. + * + * SPISettings: + * Container for SPI configs for SPIClass. As above, libraries may reference it globally. + * + * These two classes are often provided by frameworks so we cannot extend them to add + * useful methods for Marlin. + * + * MarlinSPI: + * Provides the default SPIClass interface plus some Marlin goodies such as a simplified + * interface for SPI DMA transfer. + * + */ + +using MarlinSPI = SPIClass; diff --git a/Marlin/src/HAL/STM32F1/MarlinSerial.cpp b/Marlin/src/HAL/STM32F1/MarlinSerial.cpp index ebf11cb429fa..6dabcde51ead 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, MarlinSerial &serial) { +static inline __always_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. * @@ -60,7 +60,7 @@ static inline __always_inline void my_usart_irq(ring_buffer *rb, ring_buffer *wb } else if (srflags & USART_SR_ORE) { // overrun and empty data, just do a dummy read to clear ORE - // and prevent a raise condition where a continous interrupt stream (due to ORE set) occurs + // and prevent a raise condition where a continuous interrupt stream (due to ORE set) occurs // (see chapter "Overrun error" ) in STM32 reference manual regs->DR; } @@ -90,20 +90,20 @@ constexpr bool serial_handles_emergency(int port) { ; } -#define DEFINE_HWSERIAL_MARLIN(name, n) \ - MarlinSerial name(USART##n, \ - BOARD_USART##n##_TX_PIN, \ - BOARD_USART##n##_RX_PIN, \ - serial_handles_emergency(n)); \ - extern "C" void __irq_usart##n(void) { \ +#define DEFINE_HWSERIAL_MARLIN(name, n) \ + MSerialT name(serial_handles_emergency(n),\ + USART##n, \ + BOARD_USART##n##_TX_PIN, \ + BOARD_USART##n##_RX_PIN); \ + extern "C" void __irq_usart##n(void) { \ my_usart_irq(USART##n->rb, USART##n->wb, USART##n##_BASE, MSerial##n); \ } #define DEFINE_HWSERIAL_UART_MARLIN(name, n) \ - MarlinSerial name(UART##n, \ + MSerialT name(serial_handles_emergency(n), \ + UART##n, \ BOARD_USART##n##_TX_PIN, \ - BOARD_USART##n##_RX_PIN, \ - serial_handles_emergency(n)); \ + BOARD_USART##n##_RX_PIN); \ extern "C" void __irq_usart##n(void) { \ my_usart_irq(UART##n->rb, UART##n->wb, UART##n##_BASE, MSerial##n); \ } @@ -111,7 +111,9 @@ constexpr bool serial_handles_emergency(int port) { // Instantiate all UARTs even if they are not needed // This avoids a bunch of logic to figure out every serial // port which may be in use on the system. -DEFINE_HWSERIAL_MARLIN(MSerial1, 1); +#if DISABLED(MKS_WIFI_MODULE) + DEFINE_HWSERIAL_MARLIN(MSerial1, 1); +#endif DEFINE_HWSERIAL_MARLIN(MSerial2, 2); DEFINE_HWSERIAL_MARLIN(MSerial3, 3); #if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY) @@ -132,12 +134,12 @@ constexpr bool IsSerialClassAllowed(const HardwareSerial&) { return false; } // If you encounter this error, replace SerialX with MSerialX, for example MSerial3. // Non-TMC ports were already validated in HAL.h, so do not require verbose error messages. -#ifdef MYSERIAL0 - CHECK_CFG_SERIAL(MYSERIAL0); -#endif #ifdef MYSERIAL1 CHECK_CFG_SERIAL(MYSERIAL1); #endif +#ifdef MYSERIAL2 + CHECK_CFG_SERIAL(MYSERIAL2); +#endif #ifdef LCD_SERIAL CHECK_CFG_SERIAL(LCD_SERIAL); #endif @@ -165,6 +167,15 @@ constexpr bool IsSerialClassAllowed(const HardwareSerial&) { return false; } #if AXIS_HAS_HW_SERIAL(Z4) CHECK_AXIS_SERIAL(Z4); #endif +#if AXIS_HAS_HW_SERIAL(I) + CHECK_AXIS_SERIAL(I); +#endif +#if AXIS_HAS_HW_SERIAL(J) + CHECK_AXIS_SERIAL(J); +#endif +#if AXIS_HAS_HW_SERIAL(K) + CHECK_AXIS_SERIAL(K); +#endif #if AXIS_HAS_HW_SERIAL(E0) CHECK_AXIS_SERIAL(E0); #endif diff --git a/Marlin/src/HAL/STM32F1/MarlinSerial.h b/Marlin/src/HAL/STM32F1/MarlinSerial.h index 6aa94b64fff7..dda32fe7a2ef 100644 --- a/Marlin/src/HAL/STM32F1/MarlinSerial.h +++ b/Marlin/src/HAL/STM32F1/MarlinSerial.h @@ -26,28 +26,13 @@ #include #include "../../inc/MarlinConfigPre.h" -#if ENABLED(EMERGENCY_PARSER) - #include "../../feature/e_parser.h" -#endif +#include "../../core/serial_hook.h" // Increase priority of serial interrupts, to reduce overflow errors #define UART_IRQ_PRIO 1 -class MarlinSerial : public HardwareSerial { -public: - #if ENABLED(EMERGENCY_PARSER) - const bool ep_enabled; - EmergencyParser::State emergency_state; - inline bool emergency_parser_enabled() { return ep_enabled; } - #endif - - MarlinSerial(struct usart_dev *usart_device, uint8 tx_pin, uint8 rx_pin, bool TERN_(EMERGENCY_PARSER, ep_capable)) : - HardwareSerial(usart_device, tx_pin, rx_pin) - #if ENABLED(EMERGENCY_PARSER) - , ep_enabled(ep_capable) - , emergency_state(EmergencyParser::State::EP_RESET) - #endif - { } +struct MarlinSerial : public HardwareSerial { + MarlinSerial(struct usart_dev *usart_device, uint8 tx_pin, uint8 rx_pin) : HardwareSerial(usart_device, tx_pin, rx_pin) { } #ifdef UART_IRQ_PRIO // Shadow the parent methods to set IRQ priority after begin() @@ -62,10 +47,12 @@ class MarlinSerial : public HardwareSerial { #endif }; -extern MarlinSerial MSerial1; -extern MarlinSerial MSerial2; -extern MarlinSerial MSerial3; +typedef Serial1Class MSerialT; + +extern MSerialT MSerial1; +extern MSerialT MSerial2; +extern MSerialT MSerial3; #if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY) - extern MarlinSerial MSerial4; - extern MarlinSerial MSerial5; + extern MSerialT MSerial4; + extern MSerialT MSerial5; #endif diff --git a/Marlin/src/HAL/STM32F1/SPI.cpp b/Marlin/src/HAL/STM32F1/SPI.cpp index 0452cf629390..8bfa3d236a7c 100644 --- a/Marlin/src/HAL/STM32F1/SPI.cpp +++ b/Marlin/src/HAL/STM32F1/SPI.cpp @@ -147,6 +147,18 @@ SPIClass::SPIClass(uint32_t spi_num) { _currentSetting->state = SPI_STATE_IDLE; } +SPIClass::SPIClass(int8_t mosi, int8_t miso, int8_t sclk, int8_t ssel) : SPIClass(1) { + #if BOARD_NR_SPI >= 1 + if (mosi == BOARD_SPI1_MOSI_PIN) setModule(1); + #endif + #if BOARD_NR_SPI >= 2 + if (mosi == BOARD_SPI2_MOSI_PIN) setModule(2); + #endif + #if BOARD_NR_SPI >= 3 + if (mosi == BOARD_SPI3_MOSI_PIN) setModule(3); + #endif +} + /** * Set up/tear down */ @@ -351,8 +363,8 @@ uint16_t SPIClass::transfer16(uint16_t data) const { /** * Roger Clark and Victor Perez, 2015 * Performs a DMA SPI transfer with at least a receive buffer. - * If a TX buffer is not provided, FF is sent over and over for the lenght of the transfer. - * On exit TX buffer is not modified, and RX buffer cotains the received data. + * If a TX buffer is not provided, FF is sent over and over for the length of the transfer. + * On exit TX buffer is not modified, and RX buffer contains the received data. * Still in progress. */ void SPIClass::dmaTransferSet(const void *transmitBuf, void *receiveBuf) { @@ -656,7 +668,7 @@ static const spi_pins* dev_to_spi_pins(spi_dev *dev) { #if BOARD_NR_SPI >= 3 case RCC_SPI3: return board_spi_pins + 2; #endif - default: return NULL; + default: return nullptr; } } diff --git a/Marlin/src/HAL/STM32F1/SPI.h b/Marlin/src/HAL/STM32F1/SPI.h index 0d20a46577e7..2467432e0718 100644 --- a/Marlin/src/HAL/STM32F1/SPI.h +++ b/Marlin/src/HAL/STM32F1/SPI.h @@ -138,8 +138,8 @@ class SPISettings { spi_dev *spi_d; dma_channel spiRxDmaChannel, spiTxDmaChannel; dma_dev* spiDmaDev; - void (*receiveCallback)() = NULL; - void (*transmitCallback)() = NULL; + void (*receiveCallback)() = nullptr; + void (*transmitCallback)() = nullptr; friend class SPIClass; }; @@ -163,6 +163,11 @@ class SPIClass { */ SPIClass(uint32_t spiPortNumber); + /** + * Init using pins + */ + SPIClass(int8_t mosi, int8_t miso, int8_t sclk, int8_t ssel=-1); + /** * @brief Equivalent to begin(SPI_1_125MHZ, MSBFIRST, 0). */ diff --git a/Marlin/src/HAL/STM32F1/Servo.cpp b/Marlin/src/HAL/STM32F1/Servo.cpp index e1ee83149374..36f7c6d51273 100644 --- a/Marlin/src/HAL/STM32F1/Servo.cpp +++ b/Marlin/src/HAL/STM32F1/Servo.cpp @@ -45,7 +45,7 @@ uint8_t ServoCount = 0; * * This uses the smallest prescaler that allows an overflow < 2^16. */ -#define MAX_OVERFLOW UINT16_MAX //((1 << 16) - 1) +#define MAX_OVERFLOW UINT16_MAX // _BV(16) - 1 #define CYC_MSEC (1000 * CYCLES_PER_MICROSECOND) #define TAU_MSEC 20 #define TAU_USEC (TAU_MSEC * 1000) diff --git a/Marlin/src/HAL/STM32F1/SoftwareSerial.cpp b/Marlin/src/HAL/STM32F1/SoftwareSerial.cpp deleted file mode 100644 index 993403cf720d..000000000000 --- a/Marlin/src/HAL/STM32F1/SoftwareSerial.cpp +++ /dev/null @@ -1,60 +0,0 @@ -/** - * Marlin 3D Printer Firmware - * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ -#if defined(__STM32F1__) && !defined(HAVE_SW_SERIAL) - -/** - * Empty class for Software Serial implementation (Custom RX/TX pins) - * - * TODO: Optionally use https://github.com/FYSETC/SoftwareSerialM if TMC UART is wanted - */ - -#include "SoftwareSerial.h" - -// Constructor - -SoftwareSerial::SoftwareSerial(int8_t RX_pin, int8_t TX_pin) {} - -// Public - -void SoftwareSerial::begin(const uint32_t baudrate) { -} - -bool SoftwareSerial::available() { - return false; -} - -uint8_t SoftwareSerial::read() { - return 0; -} - -uint16_t SoftwareSerial::write(uint8_t byte) { - return 0; -} - -void SoftwareSerial::flush() {} - -void SoftwareSerial::listen() { - listening = true; -} - -void SoftwareSerial::stopListening() { - listening = false; -} - -#endif // __STM32F1__ diff --git a/Marlin/src/HAL/STM32F1/SoftwareSerial.h b/Marlin/src/HAL/STM32F1/SoftwareSerial.h deleted file mode 100644 index 1c8058665a47..000000000000 --- a/Marlin/src/HAL/STM32F1/SoftwareSerial.h +++ /dev/null @@ -1,44 +0,0 @@ -/** - * Marlin 3D Printer Firmware - * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ -#pragma once - -#include - -#ifndef HAVE_SW_SERIAL - #define SW_SERIAL_PLACEHOLDER 1 -#endif - -class SoftwareSerial { -public: - SoftwareSerial(int8_t RX_pin, int8_t TX_pin); - - void begin(const uint32_t baudrate); - - bool available(); - - uint8_t read(); - uint16_t write(uint8_t byte); - void flush(); - - void listen(); - void stopListening(); - -protected: - bool listening; -}; diff --git a/Marlin/src/HAL/STM32F1/build_flags.py b/Marlin/src/HAL/STM32F1/build_flags.py index 98c871a1d8f9..d0848d1c6438 100755 --- a/Marlin/src/HAL/STM32F1/build_flags.py +++ b/Marlin/src/HAL/STM32F1/build_flags.py @@ -3,7 +3,7 @@ #dynamic build flags for generic compile options if __name__ == "__main__": - args = " ".join([ "-std=gnu11", + args = " ".join([ "-std=gnu++14", "-Os", "-mcpu=cortex-m3", "-mthumb", @@ -11,6 +11,7 @@ "-fsigned-char", "-fno-move-loop-invariants", "-fno-strict-aliasing", + "-fsingle-precision-constant", "--specs=nano.specs", "--specs=nosys.specs", 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 60596054e820..f1cd6b373052 100644 --- a/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp +++ b/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp @@ -22,13 +22,15 @@ #if BOTH(HAS_MARLINUI_U8GLIB, FORCE_SOFT_SPI) -#include +#include +#include "../../shared/HAL_SPI.h" -#undef SPI_SPEED -#define SPI_SPEED 0 // Fastest -//#define SPI_SPEED 2 // Slower +#ifndef LCD_SPI_SPEED + #define LCD_SPI_SPEED SPI_FULL_SPEED // Fastest + //#define LCD_SPI_SPEED SPI_QUARTER_SPEED // Slower +#endif -static uint8_t SPI_speed = SPI_SPEED; +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) { @@ -104,7 +106,7 @@ static uint8_t swSpiInit(const uint8_t spi_speed) { uint8_t u8g_com_HAL_STM32F1_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) { switch (msg) { case U8G_COM_MSG_INIT: - SPI_speed = swSpiInit(SPI_SPEED); + SPI_speed = swSpiInit(LCD_SPI_SPEED); break; case U8G_COM_MSG_STOP: diff --git a/Marlin/src/HAL/STM32F1/eeprom_bl24cxx.cpp b/Marlin/src/HAL/STM32F1/eeprom_bl24cxx.cpp index 658b7cd4a654..4e25bc69da4e 100644 --- a/Marlin/src/HAL/STM32F1/eeprom_bl24cxx.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom_bl24cxx.cpp @@ -19,14 +19,13 @@ * along with this program. If not, see . * */ +#ifdef __STM32F1__ /** * PersistentStore for Arduino-style EEPROM interface * with simple implementations supplied by Marlin. */ -#ifdef __STM32F1__ - #include "../../inc/MarlinConfig.h" #if ENABLED(IIC_BL24CXX_EEPROM) @@ -48,14 +47,13 @@ bool PersistentStore::access_start() { eeprom_init(); return true; } bool PersistentStore::access_finish() { return true; } bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + uint16_t written = 0; while (size--) { uint8_t v = *value; uint8_t * const p = (uint8_t * const)pos; - // EEPROM has only ~100,000 write cycles, - // so only write bytes that have changed! - if (v != eeprom_read_byte(p)) { + if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed! eeprom_write_byte(p, v); - delay(2); + if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes if (eeprom_read_byte(p) != v) { SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); return true; @@ -68,7 +66,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui return false; } -bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { +bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { do { uint8_t * const p = (uint8_t * const)pos; uint8_t c = eeprom_read_byte(p); diff --git a/Marlin/src/HAL/STM32F1/eeprom_flash.cpp b/Marlin/src/HAL/STM32F1/eeprom_flash.cpp index 8db8c8638bb8..e7d9dd29e2c5 100644 --- a/Marlin/src/HAL/STM32F1/eeprom_flash.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom_flash.cpp @@ -48,8 +48,8 @@ static uint8_t ram_eeprom[MARLIN_EEPROM_SIZE] __attribute__((aligned(4))) = {0}; static bool eeprom_dirty = false; bool PersistentStore::access_start() { - const uint32_t* source = reinterpret_cast(EEPROM_PAGE0_BASE); - uint32_t* destination = reinterpret_cast(ram_eeprom); + const uint32_t *source = reinterpret_cast(EEPROM_PAGE0_BASE); + uint32_t *destination = reinterpret_cast(ram_eeprom); static_assert(0 == (MARLIN_EEPROM_SIZE) % 4, "MARLIN_EEPROM_SIZE is corrupted. (Must be a multiple of 4.)"); // Ensure copying as uint32_t is safe constexpr size_t eeprom_size_u32 = (MARLIN_EEPROM_SIZE) / 4; @@ -101,7 +101,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui return false; // return true for any error } -bool PersistentStore::read_data(int &pos, uint8_t* value, const size_t size, uint16_t *crc, const bool writing/*=true*/) { +bool PersistentStore::read_data(int &pos, uint8_t *value, const size_t size, uint16_t *crc, const bool writing/*=true*/) { const uint8_t * const buff = writing ? &value[0] : &ram_eeprom[pos]; if (writing) for (size_t i = 0; i < size; i++) value[i] = ram_eeprom[pos + i]; crc16(crc, buff, size); diff --git a/Marlin/src/HAL/STM32F1/eeprom_if_iic.cpp b/Marlin/src/HAL/STM32F1/eeprom_if_iic.cpp index ccc3fc537f1a..78b7af0b0418 100644 --- a/Marlin/src/HAL/STM32F1/eeprom_if_iic.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom_if_iic.cpp @@ -40,7 +40,7 @@ void eeprom_init() { BL24CXX::init(); } // Public functions // ------------------------ -void eeprom_write_byte(uint8_t *pos, unsigned char value) { +void eeprom_write_byte(uint8_t *pos, uint8_t value) { const unsigned eeprom_address = (unsigned)pos; return BL24CXX::writeOneByte(eeprom_address, value); } diff --git a/Marlin/src/HAL/STM32F1/eeprom_sdcard.cpp b/Marlin/src/HAL/STM32F1/eeprom_sdcard.cpp index 11959191f6dd..d608ccee1441 100644 --- a/Marlin/src/HAL/STM32F1/eeprom_sdcard.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom_sdcard.cpp @@ -79,7 +79,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui return false; } -bool PersistentStore::read_data(int &pos, uint8_t* value, const size_t size, uint16_t *crc, const bool writing/*=true*/) { +bool PersistentStore::read_data(int &pos, uint8_t *value, const size_t size, uint16_t *crc, const bool writing/*=true*/) { for (size_t i = 0; i < size; i++) { uint8_t c = HAL_eeprom_data[pos + i]; if (writing) value[i] = c; diff --git a/Marlin/src/HAL/STM32F1/eeprom_wired.cpp b/Marlin/src/HAL/STM32F1/eeprom_wired.cpp index fffd6ccaf01e..0ad69065cf9c 100644 --- a/Marlin/src/HAL/STM32F1/eeprom_wired.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom_wired.cpp @@ -1,6 +1,5 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * This program is free software: you can redistribute it and/or modify @@ -53,13 +52,13 @@ bool PersistentStore::access_start() { } bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + uint16_t written = 0; while (size--) { uint8_t * const p = (uint8_t * const)pos; uint8_t v = *value; - // EEPROM has only ~100,000 write cycles, - // so only write bytes that have changed! - if (v != eeprom_read_byte(p)) { + if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed! eeprom_write_byte(p, v); + if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes if (eeprom_read_byte(p) != v) { SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); return true; @@ -72,7 +71,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui return false; } -bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { +bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { do { uint8_t c = eeprom_read_byte((uint8_t*)pos); if (writing && value) *value = c; diff --git a/Marlin/src/HAL/STM32F1/endstop_interrupts.h b/Marlin/src/HAL/STM32F1/endstop_interrupts.h index bcb07d991d75..4d7edb9496c1 100644 --- a/Marlin/src/HAL/STM32F1/endstop_interrupts.h +++ b/Marlin/src/HAL/STM32F1/endstop_interrupts.h @@ -71,4 +71,10 @@ void setup_endstop_interrupts() { TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); TERN_(HAS_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)); } diff --git a/Marlin/src/HAL/STM32F1/fast_pwm.cpp b/Marlin/src/HAL/STM32F1/fast_pwm.cpp new file mode 100644 index 000000000000..884d482af5f1 --- /dev/null +++ b/Marlin/src/HAL/STM32F1/fast_pwm.cpp @@ -0,0 +1,68 @@ +/** + * 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 __STM32F1__ + +#include "../../inc/MarlinConfigPre.h" + +#if NEEDS_HARDWARE_PWM + +#include +#include "HAL.h" +#include "timers.h" + +void set_pwm_frequency(const pin_t pin, int f_desired) { + if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer + + timer_dev *timer = PIN_MAP[pin].timer_device; + uint8_t channel = PIN_MAP[pin].timer_channel; + + // Protect used timers + if (timer == get_timer_dev(TEMP_TIMER_NUM)) return; + if (timer == get_timer_dev(STEP_TIMER_NUM)) return; + #if PULSE_TIMER_NUM != STEP_TIMER_NUM + if (timer == get_timer_dev(PULSE_TIMER_NUM)) return; + #endif + + if (!(timer->regs.bas->SR & TIMER_CR1_CEN)) // Ensure the timer is enabled + timer_init(timer); + + timer_set_mode(timer, channel, TIMER_PWM); + uint16_t preload = 255; // Lock 255 PWM resolution for high frequencies + int32_t prescaler = (HAL_TIMER_RATE) / (preload + 1) / f_desired - 1; + if (prescaler > 65535) { // For low frequencies increase prescaler + prescaler = 65535; + preload = (HAL_TIMER_RATE) / (prescaler + 1) / f_desired - 1; + } + if (prescaler < 0) return; // Too high frequency + timer_set_reload(timer, preload); + timer_set_prescaler(timer, prescaler); +} + +void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { + timer_dev *timer = PIN_MAP[pin].timer_device; + uint16_t max_val = timer->regs.bas->ARR * v / v_size; + if (invert) max_val = v_size - max_val; + pwmWrite(pin, max_val); +} + +#endif // NEEDS_HARDWARE_PWM +#endif // __STM32F1__ diff --git a/Marlin/src/HAL/STM32F1/fastio.h b/Marlin/src/HAL/STM32F1/fastio.h index e0e2e03a1c47..e75254d6929e 100644 --- a/Marlin/src/HAL/STM32F1/fastio.h +++ b/Marlin/src/HAL/STM32F1/fastio.h @@ -29,9 +29,9 @@ #include -#define READ(IO) (PIN_MAP[IO].gpio_device->regs->IDR & (1U << PIN_MAP[IO].gpio_bit) ? HIGH : LOW) -#define WRITE(IO,V) (PIN_MAP[IO].gpio_device->regs->BSRR = (1U << PIN_MAP[IO].gpio_bit) << ((V) ? 0 : 16)) -#define TOGGLE(IO) (PIN_MAP[IO].gpio_device->regs->ODR = PIN_MAP[IO].gpio_device->regs->ODR ^ (1U << PIN_MAP[IO].gpio_bit)) +#define READ(IO) (PIN_MAP[IO].gpio_device->regs->IDR & _BV32(PIN_MAP[IO].gpio_bit) ? HIGH : LOW) +#define WRITE(IO,V) (PIN_MAP[IO].gpio_device->regs->BSRR = _BV32(PIN_MAP[IO].gpio_bit) << ((V) ? 0 : 16)) +#define TOGGLE(IO) TBI32(PIN_MAP[IO].gpio_device->regs->ODR, PIN_MAP[IO].gpio_bit) #define _GET_MODE(IO) gpio_get_mode(PIN_MAP[IO].gpio_device, PIN_MAP[IO].gpio_bit) #define _SET_MODE(IO,M) gpio_set_mode(PIN_MAP[IO].gpio_device, PIN_MAP[IO].gpio_bit, M) @@ -51,7 +51,7 @@ #define IS_INPUT(IO) (_GET_MODE(IO) == GPIO_INPUT_FLOATING || _GET_MODE(IO) == GPIO_INPUT_ANALOG || _GET_MODE(IO) == GPIO_INPUT_PU || _GET_MODE(IO) == GPIO_INPUT_PD) #define IS_OUTPUT(IO) (_GET_MODE(IO) == GPIO_OUTPUT_PP || _GET_MODE(IO) == GPIO_OUTPUT_OD) -#define PWM_PIN(IO) (PIN_MAP[IO].timer_device != nullptr) +#define PWM_PIN(IO) !!PIN_MAP[IO].timer_device // digitalRead/Write wrappers #define extDigitalRead(IO) digitalRead(IO) diff --git a/Marlin/src/HAL/STM32F1/inc/Conditionals_LCD.h b/Marlin/src/HAL/STM32F1/inc/Conditionals_LCD.h index f52e6fec2b1e..5f1c4b16019d 100644 --- a/Marlin/src/HAL/STM32F1/inc/Conditionals_LCD.h +++ b/Marlin/src/HAL/STM32F1/inc/Conditionals_LCD.h @@ -20,8 +20,3 @@ * */ #pragma once - -#if ENABLED(USE_USB_COMPOSITE) - //#warning "SD_CHECK_AND_RETRY isn't needed with USE_USB_COMPOSITE." - #undef SD_CHECK_AND_RETRY -#endif diff --git a/Marlin/src/HAL/STM32F1/inc/Conditionals_adv.h b/Marlin/src/HAL/STM32F1/inc/Conditionals_adv.h index 5f1c4b16019d..0fe79247658c 100644 --- a/Marlin/src/HAL/STM32F1/inc/Conditionals_adv.h +++ b/Marlin/src/HAL/STM32F1/inc/Conditionals_adv.h @@ -20,3 +20,11 @@ * */ #pragma once + +#ifdef USE_USB_COMPOSITE + //#warning "SD_CHECK_AND_RETRY isn't needed with USE_USB_COMPOSITE." + #undef SD_CHECK_AND_RETRY + #if DISABLED(NO_SD_HOST_DRIVE) + #define HAS_SD_HOST_DRIVE 1 + #endif +#endif diff --git a/Marlin/src/HAL/STM32F1/inc/SanityCheck.h b/Marlin/src/HAL/STM32F1/inc/SanityCheck.h index 9d5026fbab10..2846155c351d 100644 --- a/Marlin/src/HAL/STM32F1/inc/SanityCheck.h +++ b/Marlin/src/HAL/STM32F1/inc/SanityCheck.h @@ -25,15 +25,6 @@ * Test STM32F1-specific configuration values for errors at compile-time. */ -#if ENABLED(FAST_PWM_FAN) || SPINDLE_LASER_FREQUENCY - #error "Features requiring Hardware PWM (FAST_PWM_FAN, SPINDLE_LASER_FREQUENCY) are not yet supported on STM32F1." -#endif - -#if !defined(HAVE_SW_SERIAL) && HAS_TMC_SW_SERIAL - #warning "With TMC2208/9 consider using SoftwareSerialM with HAVE_SW_SERIAL and appropriate SS_TIMER." - #error "Missing SoftwareSerial implementation." -#endif - #if ENABLED(SDCARD_EEPROM_EMULATION) && DISABLED(SDSUPPORT) #undef SDCARD_EEPROM_EMULATION // Avoid additional error noise #if USE_FALLBACK_EEPROM @@ -43,11 +34,18 @@ #endif #if ENABLED(SERIAL_STATS_MAX_RX_QUEUED) - #error "SERIAL_STATS_MAX_RX_QUEUED is not supported on this platform." + #error "SERIAL_STATS_MAX_RX_QUEUED is not supported on the STM32F1 platform." #elif ENABLED(SERIAL_STATS_DROPPED_RX) - #error "SERIAL_STATS_DROPPED_RX is not supported on this platform." + #error "SERIAL_STATS_DROPPED_RX is not supported on the STM32F1 platform." #endif -#if ENABLED(NEOPIXEL_LED) +#if ENABLED(NEOPIXEL_LED) && DISABLED(MKS_MINI_12864_V3) #error "NEOPIXEL_LED (Adafruit NeoPixel) is not supported for HAL/STM32F1. Comment out this line to proceed at your own risk!" #endif + +// Emergency Parser needs at least one serial with HardwareSerial or USBComposite. +// The USBSerial maple don't allow any hook to implement EMERGENCY_PARSER. +// And copy all USBSerial code to marlin space to support EMERGENCY_PARSER, when we have another options, don't worth it. +#if ENABLED(EMERGENCY_PARSER) && !defined(USE_USB_COMPOSITE) && ((SERIAL_PORT == -1 && !defined(SERIAL_PORT_2)) || (SERIAL_PORT_2 == -1 && !defined(SERIAL_PORT))) + #error "EMERGENCY_PARSER is only supported by HardwareSerial or USBComposite in HAL/STM32F1." +#endif diff --git a/Marlin/src/HAL/STM32F1/msc_sd.cpp b/Marlin/src/HAL/STM32F1/msc_sd.cpp index 4f44f2ee905f..f490c83ed829 100644 --- a/Marlin/src/HAL/STM32F1/msc_sd.cpp +++ b/Marlin/src/HAL/STM32F1/msc_sd.cpp @@ -13,15 +13,20 @@ * along with this program. If not, see . * */ -#if defined(__STM32F1__) && defined(USE_USB_COMPOSITE) +#ifdef __STM32F1__ + +#include "../../inc/MarlinConfigPre.h" + +#if HAS_SD_HOST_DRIVE #include "msc_sd.h" #include "SPI.h" +#include "usb_reg_map.h" #define PRODUCT_ID 0x29 USBMassStorage MarlinMSC; -MarlinUSBCompositeSerial MarlinCompositeSerial; +Serial1Class MarlinCompositeSerial(true); #include "../../inc/MarlinConfig.h" @@ -39,14 +44,28 @@ MarlinUSBCompositeSerial MarlinCompositeSerial; #endif #if ENABLED(EMERGENCY_PARSER) - void (*real_rx_callback)(void); - void my_rx_callback(void) { - real_rx_callback(); - int len = MarlinCompositeSerial.available(); - while (len-- > 0) // >0 because available() may return a negative value - emergency_parser.update(MarlinCompositeSerial.emergency_state, MarlinCompositeSerial.peek()); + // The original callback is not called (no way to retrieve address). + // That callback detects a special STM32 reset sequence: this functionality is not essential + // as M997 achieves the same. + void my_rx_callback(unsigned int, void*) { + // max length of 16 is enough to contain all emergency commands + uint8 buf[16]; + + //rx is usbSerialPart.endpoints[2] + uint16 len = usb_get_ep_rx_count(usbSerialPart.endpoints[2].address); + uint32 total = composite_cdcacm_data_available(); + + if (len == 0 || total == 0 || !WITHIN(total, len, COUNT(buf))) + return; + + // cannot get character by character due to bug in composite_cdcacm_peek_ex + len = composite_cdcacm_peek(buf, total); + + for (uint32 i = 0; i < len; i++) + emergency_parser.update(MarlinCompositeSerial.emergency_state, buf[i+total-len]); } + #endif void MSC_SD_init() { @@ -71,10 +90,9 @@ void MSC_SD_init() { MarlinCompositeSerial.registerComponent(); USBComposite.begin(); #if ENABLED(EMERGENCY_PARSER) - //rx is usbSerialPart.endpoints[2] - real_rx_callback = usbSerialPart.endpoints[2].callback; - usbSerialPart.endpoints[2].callback = my_rx_callback; + composite_cdcacm_set_hooks(USBHID_CDCACM_HOOK_RX, my_rx_callback); #endif } -#endif // __STM32F1__ && USE_USB_COMPOSITE +#endif // HAS_SD_HOST_DRIVE +#endif // __STM32F1__ diff --git a/Marlin/src/HAL/STM32F1/msc_sd.h b/Marlin/src/HAL/STM32F1/msc_sd.h index 1e4e4c44b1b5..f4636bdff702 100644 --- a/Marlin/src/HAL/STM32F1/msc_sd.h +++ b/Marlin/src/HAL/STM32F1/msc_sd.h @@ -18,25 +18,9 @@ #include #include "../../inc/MarlinConfigPre.h" -#if ENABLED(EMERGENCY_PARSER) - #include "../../feature/e_parser.h" -#endif - -class MarlinUSBCompositeSerial : public USBCompositeSerial { -public: - MarlinUSBCompositeSerial() : USBCompositeSerial() - #if ENABLED(EMERGENCY_PARSER) - , emergency_state(EmergencyParser::State::EP_RESET) - #endif - { } - - #if ENABLED(EMERGENCY_PARSER) - EmergencyParser::State emergency_state; - inline bool emergency_parser_enabled() { return true; } - #endif -}; +#include "../../core/serial_hook.h" extern USBMassStorage MarlinMSC; -extern MarlinUSBCompositeSerial MarlinCompositeSerial; +extern Serial1Class MarlinCompositeSerial; void MSC_SD_init(); diff --git a/Marlin/src/HAL/STM32F1/onboard_sd.cpp b/Marlin/src/HAL/STM32F1/onboard_sd.cpp index 9c2b128ddc9a..e26947145d0e 100644 --- a/Marlin/src/HAL/STM32F1/onboard_sd.cpp +++ b/Marlin/src/HAL/STM32F1/onboard_sd.cpp @@ -21,10 +21,11 @@ #include "SPI.h" #include "fastio.h" -#if HAS_SHARED_MEDIA - #ifndef ONBOARD_SPI_DEVICE - #define ONBOARD_SPI_DEVICE SPI_DEVICE - #endif +#ifndef ONBOARD_SPI_DEVICE + #define ONBOARD_SPI_DEVICE SPI_DEVICE +#endif + +#if HAS_SD_HOST_DRIVE #define ONBOARD_SD_SPI SPI #else SPIClass OnboardSPI(ONBOARD_SPI_DEVICE); @@ -37,8 +38,8 @@ #define SPI_CLOCK_MAX SPI_BAUD_PCLK_DIV_2 #endif -#define CS_LOW() WRITE(ONBOARD_SD_CS_PIN, LOW) /* Set OnboardSPI cs low */ -#define CS_HIGH() WRITE(ONBOARD_SD_CS_PIN, HIGH) /* Set OnboardSPI cs high */ +#define CS_LOW() WRITE(ONBOARD_SD_CS_PIN, LOW) // Set OnboardSPI cs low +#define CS_HIGH() WRITE(ONBOARD_SD_CS_PIN, HIGH) // Set OnboardSPI cs high #define FCLK_FAST() ONBOARD_SD_SPI.setClockDivider(SPI_CLOCK_MAX) #define FCLK_SLOW() ONBOARD_SD_SPI.setClockDivider(SPI_BAUD_PCLK_DIV_256) @@ -48,32 +49,32 @@ ---------------------------------------------------------------------------*/ /* MMC/SD command */ -#define CMD0 (0) /* GO_IDLE_STATE */ -#define CMD1 (1) /* SEND_OP_COND (MMC) */ -#define ACMD41 (0x80+41) /* SEND_OP_COND (SDC) */ -#define CMD8 (8) /* SEND_IF_COND */ -#define CMD9 (9) /* SEND_CSD */ -#define CMD10 (10) /* SEND_CID */ -#define CMD12 (12) /* STOP_TRANSMISSION */ -#define ACMD13 (0x80+13) /* SD_STATUS (SDC) */ -#define CMD16 (16) /* SET_BLOCKLEN */ -#define CMD17 (17) /* READ_SINGLE_BLOCK */ -#define CMD18 (18) /* READ_MULTIPLE_BLOCK */ -#define CMD23 (23) /* SET_BLOCK_COUNT (MMC) */ -#define ACMD23 (0x80+23) /* SET_WR_BLK_ERASE_COUNT (SDC) */ -#define CMD24 (24) /* WRITE_BLOCK */ -#define CMD25 (25) /* WRITE_MULTIPLE_BLOCK */ -#define CMD32 (32) /* ERASE_ER_BLK_START */ -#define CMD33 (33) /* ERASE_ER_BLK_END */ -#define CMD38 (38) /* ERASE */ -#define CMD48 (48) /* READ_EXTR_SINGLE */ -#define CMD49 (49) /* WRITE_EXTR_SINGLE */ -#define CMD55 (55) /* APP_CMD */ -#define CMD58 (58) /* READ_OCR */ - -static volatile DSTATUS Stat = STA_NOINIT; /* Physical drive status */ +#define CMD0 (0) // GO_IDLE_STATE +#define CMD1 (1) // SEND_OP_COND (MMC) +#define ACMD41 (0x80+41) // SEND_OP_COND (SDC) +#define CMD8 (8) // SEND_IF_COND +#define CMD9 (9) // SEND_CSD +#define CMD10 (10) // SEND_CID +#define CMD12 (12) // STOP_TRANSMISSION +#define ACMD13 (0x80+13) // SD_STATUS (SDC) +#define CMD16 (16) // SET_BLOCKLEN +#define CMD17 (17) // READ_SINGLE_BLOCK +#define CMD18 (18) // READ_MULTIPLE_BLOCK +#define CMD23 (23) // SET_BLOCK_COUNT (MMC) +#define ACMD23 (0x80+23) // SET_WR_BLK_ERASE_COUNT (SDC) +#define CMD24 (24) // WRITE_BLOCK +#define CMD25 (25) // WRITE_MULTIPLE_BLOCK +#define CMD32 (32) // ERASE_ER_BLK_START +#define CMD33 (33) // ERASE_ER_BLK_END +#define CMD38 (38) // ERASE +#define CMD48 (48) // READ_EXTR_SINGLE +#define CMD49 (49) // WRITE_EXTR_SINGLE +#define CMD55 (55) // APP_CMD +#define CMD58 (58) // READ_OCR + +static volatile DSTATUS Stat = STA_NOINIT; // Physical drive status static volatile UINT timeout; -static BYTE CardType; /* Card type flags */ +static BYTE CardType; // Card type flags /*-----------------------------------------------------------------------*/ /* Send/Receive data to the MMC (Platform dependent) */ @@ -81,7 +82,7 @@ static BYTE CardType; /* Card type flags */ /* Exchange a byte */ static BYTE xchg_spi ( - BYTE dat /* Data to send */ + BYTE dat // Data to send ) { BYTE returnByte = ONBOARD_SD_SPI.transfer(dat); return returnByte; @@ -89,18 +90,18 @@ static BYTE xchg_spi ( /* Receive multiple byte */ static void rcvr_spi_multi ( - BYTE *buff, /* Pointer to data buffer */ - UINT btr /* Number of bytes to receive (16, 64 or 512) */ + BYTE *buff, // Pointer to data buffer + UINT btr // Number of bytes to receive (16, 64 or 512) ) { ONBOARD_SD_SPI.dmaTransfer(0, const_cast(buff), btr); } #if _DISKIO_WRITE - /* Send multiple bytes */ + // Send multiple bytes static void xmit_spi_multi ( - const BYTE *buff, /* Pointer to the data */ - UINT btx /* Number of bytes to send (multiple of 16) */ + const BYTE *buff, // Pointer to the data + UINT btx // Number of bytes to send (multiple of 16) ) { ONBOARD_SD_SPI.dmaSend(const_cast(buff), btx); } @@ -111,16 +112,15 @@ static void rcvr_spi_multi ( /* Wait for card ready */ /*-----------------------------------------------------------------------*/ -static int wait_ready ( /* 1:Ready, 0:Timeout */ - UINT wt /* Timeout [ms] */ +static int wait_ready ( // 1:Ready, 0:Timeout + UINT wt // Timeout [ms] ) { BYTE d; - timeout = millis() + wt; do { d = xchg_spi(0xFF); - /* This loop takes a while. Insert rot_rdq() here for multitask environment. */ - } while (d != 0xFF && (timeout > millis())); /* Wait for card goes ready or timeout */ + // This loop takes a while. Insert rot_rdq() here for multitask environment. + } while (d != 0xFF && (timeout > millis())); // Wait for card goes ready or timeout return (d == 0xFF) ? 1 : 0; } @@ -130,21 +130,21 @@ static int wait_ready ( /* 1:Ready, 0:Timeout */ /*-----------------------------------------------------------------------*/ static void deselect() { - CS_HIGH(); /* CS = H */ - xchg_spi(0xFF); /* Dummy clock (force DO hi-z for multiple slave SPI) */ + CS_HIGH(); // CS = H + xchg_spi(0xFF); // Dummy clock (force DO hi-z for multiple slave SPI) } /*-----------------------------------------------------------------------*/ /* Select card and wait for ready */ /*-----------------------------------------------------------------------*/ -static int select() { /* 1:OK, 0:Timeout */ - CS_LOW(); /* CS = L */ - xchg_spi(0xFF); /* Dummy clock (force DO enabled) */ +static int select() { // 1:OK, 0:Timeout + CS_LOW(); // CS = L + xchg_spi(0xFF); // Dummy clock (force DO enabled) - if (wait_ready(500)) return 1; /* Leading busy check: Wait for card ready */ + if (wait_ready(500)) return 1; // Leading busy check: Wait for card ready - deselect(); /* Timeout */ + deselect(); // Timeout return 0; } @@ -152,16 +152,18 @@ static int select() { /* 1:OK, 0:Timeout */ /* Control SPI module (Platform dependent) */ /*-----------------------------------------------------------------------*/ -static void power_on() { /* Enable SSP module and attach it to I/O pads */ +// Enable SSP module and attach it to I/O pads +static void sd_power_on() { ONBOARD_SD_SPI.setModule(ONBOARD_SPI_DEVICE); ONBOARD_SD_SPI.begin(); ONBOARD_SD_SPI.setBitOrder(MSBFIRST); ONBOARD_SD_SPI.setDataMode(SPI_MODE0); - OUT_WRITE(ONBOARD_SD_CS_PIN, HIGH); /* Set CS# high */ + OUT_WRITE(ONBOARD_SD_CS_PIN, HIGH); // Set CS# high } -static void power_off() { /* Disable SPI function */ - select(); /* Wait for card ready */ +// Disable SPI function +static void sd_power_off() { + select(); // Wait for card ready deselect(); } @@ -169,23 +171,23 @@ static void power_off() { /* Disable SPI function */ /* Receive a data packet from the MMC */ /*-----------------------------------------------------------------------*/ -static int rcvr_datablock ( /* 1:OK, 0:Error */ - BYTE *buff, /* Data buffer */ - UINT btr /* Data block length (byte) */ +static int rcvr_datablock ( // 1:OK, 0:Error + BYTE *buff, // Data buffer + UINT btr // Data block length (byte) ) { BYTE token; timeout = millis() + 200; - do { /* Wait for DataStart token in timeout of 200ms */ + do { // Wait for DataStart token in timeout of 200ms token = xchg_spi(0xFF); - /* This loop will take a while. Insert rot_rdq() here for multitask environment. */ + // This loop will take a while. Insert rot_rdq() here for multitask environment. } while ((token == 0xFF) && (timeout > millis())); - if (token != 0xFE) return 0; /* Function fails if invalid DataStart token or timeout */ + if (token != 0xFE) return 0; // Function fails if invalid DataStart token or timeout - rcvr_spi_multi(buff, btr); /* Store trailing data to the buffer */ - xchg_spi(0xFF); xchg_spi(0xFF); /* Discard CRC */ + rcvr_spi_multi(buff, btr); // Store trailing data to the buffer + xchg_spi(0xFF); xchg_spi(0xFF); // Discard CRC - return 1; /* Function succeeded */ + return 1; // Function succeeded } /*-----------------------------------------------------------------------*/ @@ -194,25 +196,25 @@ static int rcvr_datablock ( /* 1:OK, 0:Error */ #if _DISKIO_WRITE - static int xmit_datablock ( /* 1:OK, 0:Failed */ - const BYTE *buff, /* Ponter to 512 byte data to be sent */ - BYTE token /* Token */ + static int xmit_datablock( // 1:OK, 0:Failed + const BYTE *buff, // Pointer to 512 byte data to be sent + BYTE token // Token ) { BYTE resp; - if (!wait_ready(500)) return 0; /* Leading busy check: Wait for card ready to accept data block */ + if (!wait_ready(500)) return 0; // Leading busy check: Wait for card ready to accept data block - xchg_spi(token); /* Send token */ - if (token == 0xFD) return 1; /* Do not send data if token is StopTran */ + xchg_spi(token); // Send token + if (token == 0xFD) return 1; // Do not send data if token is StopTran - xmit_spi_multi(buff, 512); /* Data */ - xchg_spi(0xFF); xchg_spi(0xFF); /* Dummy CRC */ + xmit_spi_multi(buff, 512); // Data + xchg_spi(0xFF); xchg_spi(0xFF); // Dummy CRC - resp = xchg_spi(0xFF); /* Receive data resp */ + resp = xchg_spi(0xFF); // Receive data resp - return (resp & 0x1F) == 0x05 ? 1 : 0; /* Data was accepted or not */ + return (resp & 0x1F) == 0x05 ? 1 : 0; // Data was accepted or not - /* Busy check is done at next transmission */ + // Busy check is done at next transmission } #endif // _DISKIO_WRITE @@ -221,43 +223,43 @@ static int rcvr_datablock ( /* 1:OK, 0:Error */ /* Send a command packet to the MMC */ /*-----------------------------------------------------------------------*/ -static BYTE send_cmd ( /* Return value: R1 resp (bit7==1:Failed to send) */ - BYTE cmd, /* Command index */ - DWORD arg /* Argument */ +static BYTE send_cmd( // Return value: R1 resp (bit7==1:Failed to send) + BYTE cmd, // Command index + DWORD arg // Argument ) { BYTE n, res; - if (cmd & 0x80) { /* Send a CMD55 prior to ACMD */ + if (cmd & 0x80) { // Send a CMD55 prior to ACMD cmd &= 0x7F; res = send_cmd(CMD55, 0); if (res > 1) return res; } - /* Select the card and wait for ready except to stop multiple block read */ + // Select the card and wait for ready except to stop multiple block read if (cmd != CMD12) { deselect(); if (!select()) return 0xFF; } - /* Send command packet */ - xchg_spi(0x40 | cmd); /* Start + command index */ - xchg_spi((BYTE)(arg >> 24)); /* Argument[31..24] */ - xchg_spi((BYTE)(arg >> 16)); /* Argument[23..16] */ - xchg_spi((BYTE)(arg >> 8)); /* Argument[15..8] */ - xchg_spi((BYTE)arg); /* Argument[7..0] */ - n = 0x01; /* Dummy CRC + Stop */ - if (cmd == CMD0) n = 0x95; /* Valid CRC for CMD0(0) */ - if (cmd == CMD8) n = 0x87; /* Valid CRC for CMD8(0x1AA) */ + // Send command packet + xchg_spi(0x40 | cmd); // Start + command index + xchg_spi((BYTE)(arg >> 24)); // Argument[31..24] + xchg_spi((BYTE)(arg >> 16)); // Argument[23..16] + xchg_spi((BYTE)(arg >> 8)); // Argument[15..8] + xchg_spi((BYTE)arg); // Argument[7..0] + n = 0x01; // Dummy CRC + Stop + if (cmd == CMD0) n = 0x95; // Valid CRC for CMD0(0) + if (cmd == CMD8) n = 0x87; // Valid CRC for CMD8(0x1AA) xchg_spi(n); - /* Receive command resp */ - if (cmd == CMD12) xchg_spi(0xFF); /* Diacard following one byte when CMD12 */ - n = 10; /* Wait for response (10 bytes max) */ + // Receive command response + if (cmd == CMD12) xchg_spi(0xFF); // Discard the following byte when CMD12 + n = 10; // Wait for response (10 bytes max) do res = xchg_spi(0xFF); while ((res & 0x80) && --n); - return res; /* Return received response */ + return res; // Return received response } /*-------------------------------------------------------------------------- @@ -269,49 +271,52 @@ static BYTE send_cmd ( /* Return value: R1 resp (bit7==1:Failed to send) */ /*-----------------------------------------------------------------------*/ DSTATUS disk_initialize ( - BYTE drv /* Physical drive number (0) */ + BYTE drv // Physical drive number (0) ) { BYTE n, cmd, ty, ocr[4]; - if (drv) return STA_NOINIT; /* Supports only drive 0 */ - power_on(); /* Initialize SPI */ + if (drv) return STA_NOINIT; // Supports only drive 0 + sd_power_on(); // Initialize SPI - if (Stat & STA_NODISK) return Stat; /* Is a card existing in the soket? */ + if (Stat & STA_NODISK) return Stat; // Is a card existing in the soket? FCLK_SLOW(); - for (n = 10; n; n--) xchg_spi(0xFF); /* Send 80 dummy clocks */ + for (n = 10; n; n--) xchg_spi(0xFF); // Send 80 dummy clocks ty = 0; - if (send_cmd(CMD0, 0) == 1) { /* Put the card SPI state */ - timeout = millis() + 1000; /* Initialization timeout = 1 sec */ - if (send_cmd(CMD8, 0x1AA) == 1) { /* Is the catd SDv2? */ - for (n = 0; n < 4; n++) ocr[n] = xchg_spi(0xFF); /* Get 32 bit return value of R7 resp */ - if (ocr[2] == 0x01 && ocr[3] == 0xAA) { /* Does the card support 2.7-3.6V? */ - while ((timeout > millis()) && send_cmd(ACMD41, 1UL << 30)) ; /* Wait for end of initialization with ACMD41(HCS) */ - if ((timeout > millis()) && send_cmd(CMD58, 0) == 0) { /* Check CCS bit in the OCR */ + if (send_cmd(CMD0, 0) == 1) { // Put the card SPI state + timeout = millis() + 1000; // Initialization timeout = 1 sec + if (send_cmd(CMD8, 0x1AA) == 1) { // Is the catd SDv2? + for (n = 0; n < 4; n++) ocr[n] = xchg_spi(0xFF); // Get 32 bit return value of R7 resp + if (ocr[2] == 0x01 && ocr[3] == 0xAA) { // Does the card support 2.7-3.6V? + while ((timeout > millis()) && send_cmd(ACMD41, 1UL << 30)); // Wait for end of initialization with ACMD41(HCS) + if ((timeout > millis()) && send_cmd(CMD58, 0) == 0) { // Check CCS bit in the OCR for (n = 0; n < 4; n++) ocr[n] = xchg_spi(0xFF); - ty = (ocr[0] & 0x40) ? CT_SD2 | CT_BLOCK : CT_SD2; /* Check if the card is SDv2 */ + ty = (ocr[0] & 0x40) ? CT_SD2 | CT_BLOCK : CT_SD2; // Check if the card is SDv2 } } - } else { /* Not an SDv2 card */ - if (send_cmd(ACMD41, 0) <= 1) { /* SDv1 or MMCv3? */ - ty = CT_SD1; cmd = ACMD41; /* SDv1 (ACMD41(0)) */ - } else { - ty = CT_MMC; cmd = CMD1; /* MMCv3 (CMD1(0)) */ + } + else { // Not an SDv2 card + if (send_cmd(ACMD41, 0) <= 1) { // SDv1 or MMCv3? + ty = CT_SD1; cmd = ACMD41; // SDv1 (ACMD41(0)) + } + else { + ty = CT_MMC; cmd = CMD1; // MMCv3 (CMD1(0)) } - while ((timeout > millis()) && send_cmd(cmd, 0)) ; /* Wait for the card leaves idle state */ - if (!(timeout > millis()) || send_cmd(CMD16, 512) != 0) /* Set block length: 512 */ + while ((timeout > millis()) && send_cmd(cmd, 0)); // Wait for the card leaves idle state + if (!(timeout > millis()) || send_cmd(CMD16, 512) != 0) // Set block length: 512 ty = 0; } } - CardType = ty; /* Card type */ + CardType = ty; // Card type deselect(); - if (ty) { /* OK */ - FCLK_FAST(); /* Set fast clock */ - Stat &= ~STA_NOINIT; /* Clear STA_NOINIT flag */ - } else { /* Failed */ - power_off(); + if (ty) { // OK + FCLK_FAST(); // Set fast clock + Stat &= ~STA_NOINIT; // Clear STA_NOINIT flag + } + else { // Failed + sd_power_off(); Stat = STA_NOINIT; } @@ -323,10 +328,10 @@ DSTATUS disk_initialize ( /*-----------------------------------------------------------------------*/ DSTATUS disk_status ( - BYTE drv /* Physical drive number (0) */ + BYTE drv // Physical drive number (0) ) { - if (drv) return STA_NOINIT; /* Supports only drive 0 */ - return Stat; /* Return disk status */ + if (drv) return STA_NOINIT; // Supports only drive 0 + return Stat; // Return disk status } /*-----------------------------------------------------------------------*/ @@ -334,28 +339,28 @@ DSTATUS disk_status ( /*-----------------------------------------------------------------------*/ DRESULT disk_read ( - BYTE drv, /* Physical drive number (0) */ - BYTE *buff, /* Pointer to the data buffer to store read data */ - DWORD sector, /* Start sector number (LBA) */ - UINT count /* Number of sectors to read (1..128) */ + BYTE drv, // Physical drive number (0) + BYTE *buff, // Pointer to the data buffer to store read data + DWORD sector, // Start sector number (LBA) + UINT count // Number of sectors to read (1..128) ) { BYTE cmd; - if (drv || !count) return RES_PARERR; /* Check parameter */ - if (Stat & STA_NOINIT) return RES_NOTRDY; /* Check if drive is ready */ - if (!(CardType & CT_BLOCK)) sector *= 512; /* LBA ot BA conversion (byte addressing cards) */ + if (drv || !count) return RES_PARERR; // Check parameter + if (Stat & STA_NOINIT) return RES_NOTRDY; // Check if drive is ready + if (!(CardType & CT_BLOCK)) sector *= 512; // LBA ot BA conversion (byte addressing cards) FCLK_FAST(); - cmd = count > 1 ? CMD18 : CMD17; /* READ_MULTIPLE_BLOCK : READ_SINGLE_BLOCK */ + cmd = count > 1 ? CMD18 : CMD17; // READ_MULTIPLE_BLOCK : READ_SINGLE_BLOCK if (send_cmd(cmd, sector) == 0) { do { if (!rcvr_datablock(buff, 512)) break; buff += 512; } while (--count); - if (cmd == CMD18) send_cmd(CMD12, 0); /* STOP_TRANSMISSION */ + if (cmd == CMD18) send_cmd(CMD12, 0); // STOP_TRANSMISSION } deselect(); - return count ? RES_ERROR : RES_OK; /* Return result */ + return count ? RES_ERROR : RES_OK; // Return result } /*-----------------------------------------------------------------------*/ @@ -365,36 +370,36 @@ DRESULT disk_read ( #if _DISKIO_WRITE DRESULT disk_write( - BYTE drv, /* Physical drive number (0) */ - const BYTE *buff, /* Ponter to the data to write */ - DWORD sector, /* Start sector number (LBA) */ - UINT count /* Number of sectors to write (1..128) */ + BYTE drv, // Physical drive number (0) + const BYTE *buff, // Pointer to the data to write + DWORD sector, // Start sector number (LBA) + UINT count // Number of sectors to write (1..128) ) { - if (drv || !count) return RES_PARERR; /* Check parameter */ - if (Stat & STA_NOINIT) return RES_NOTRDY; /* Check drive status */ - if (Stat & STA_PROTECT) return RES_WRPRT; /* Check write protect */ + if (drv || !count) return RES_PARERR; // Check parameter + if (Stat & STA_NOINIT) return RES_NOTRDY; // Check drive status + if (Stat & STA_PROTECT) return RES_WRPRT; // Check write protect FCLK_FAST(); - if (!(CardType & CT_BLOCK)) sector *= 512; /* LBA ==> BA conversion (byte addressing cards) */ + if (!(CardType & CT_BLOCK)) sector *= 512; // LBA ==> BA conversion (byte addressing cards) - if (count == 1) { /* Single sector write */ - if ((send_cmd(CMD24, sector) == 0) /* WRITE_BLOCK */ + if (count == 1) { // Single sector write + if ((send_cmd(CMD24, sector) == 0) // WRITE_BLOCK && xmit_datablock(buff, 0xFE)) { count = 0; } } - else { /* Multiple sector write */ - if (CardType & CT_SDC) send_cmd(ACMD23, count); /* Predefine number of sectors */ - if (send_cmd(CMD25, sector) == 0) { /* WRITE_MULTIPLE_BLOCK */ + else { // Multiple sector write + if (CardType & CT_SDC) send_cmd(ACMD23, count); // Predefine number of sectors + if (send_cmd(CMD25, sector) == 0) { // WRITE_MULTIPLE_BLOCK do { if (!xmit_datablock(buff, 0xFC)) break; buff += 512; } while (--count); - if (!xmit_datablock(0, 0xFD)) count = 1; /* STOP_TRAN token */ + if (!xmit_datablock(0, 0xFD)) count = 1; // STOP_TRAN token } } deselect(); - return count ? RES_ERROR : RES_OK; /* Return result */ + return count ? RES_ERROR : RES_OK; // Return result } #endif // _DISKIO_WRITE @@ -406,9 +411,9 @@ DRESULT disk_read ( #if _DISKIO_IOCTL DRESULT disk_ioctl ( - BYTE drv, /* Physical drive number (0) */ - BYTE cmd, /* Control command code */ - void *buff /* Pointer to the conrtol data */ + BYTE drv, // Physical drive number (0) + BYTE cmd, // Control command code + void *buff // Pointer to the conrtol data ) { DRESULT res; BYTE n, csd[16], *ptr = (BYTE *)buff; @@ -419,22 +424,23 @@ DRESULT disk_read ( UINT dc; #endif - if (drv) return RES_PARERR; /* Check parameter */ - if (Stat & STA_NOINIT) return RES_NOTRDY; /* Check if drive is ready */ + if (drv) return RES_PARERR; // Check parameter + if (Stat & STA_NOINIT) return RES_NOTRDY; // Check if drive is ready res = RES_ERROR; FCLK_FAST(); switch (cmd) { - case CTRL_SYNC: /* Wait for end of internal write process of the drive */ + case CTRL_SYNC: // Wait for end of internal write process of the drive if (select()) res = RES_OK; break; - case GET_SECTOR_COUNT: /* Get drive capacity in unit of sector (DWORD) */ + case GET_SECTOR_COUNT: // Get drive capacity in unit of sector (DWORD) if ((send_cmd(CMD9, 0) == 0) && rcvr_datablock(csd, 16)) { - if ((csd[0] >> 6) == 1) { /* SDC ver 2.00 */ + if ((csd[0] >> 6) == 1) { // SDC ver 2.00 csize = csd[9] + ((WORD)csd[8] << 8) + ((DWORD)(csd[7] & 63) << 16) + 1; *(DWORD*)buff = csize << 10; - } else { /* SDC ver 1.XX or MMC ver 3 */ + } + else { // SDC ver 1.XX or MMC ver 3 n = (csd[5] & 15) + ((csd[10] & 128) >> 7) + ((csd[9] & 3) << 1) + 2; csize = (csd[8] >> 6) + ((WORD)csd[7] << 2) + ((WORD)(csd[6] & 3) << 10) + 1; *(DWORD*)buff = csize << (n - 9); @@ -443,21 +449,23 @@ DRESULT disk_read ( } break; - case GET_BLOCK_SIZE: /* Get erase block size in unit of sector (DWORD) */ - if (CardType & CT_SD2) { /* SDC ver 2.00 */ - if (send_cmd(ACMD13, 0) == 0) { /* Read SD status */ + case GET_BLOCK_SIZE: // Get erase block size in unit of sector (DWORD) + if (CardType & CT_SD2) { // SDC ver 2.00 + if (send_cmd(ACMD13, 0) == 0) { // Read SD status xchg_spi(0xFF); - if (rcvr_datablock(csd, 16)) { /* Read partial block */ - for (n = 64 - 16; n; n--) xchg_spi(0xFF); /* Purge trailing data */ + if (rcvr_datablock(csd, 16)) { // Read partial block + for (n = 64 - 16; n; n--) xchg_spi(0xFF); // Purge trailing data *(DWORD*)buff = 16UL << (csd[10] >> 4); res = RES_OK; } } - } else { /* SDC ver 1.XX or MMC */ - if ((send_cmd(CMD9, 0) == 0) && rcvr_datablock(csd, 16)) { /* Read CSD */ - if (CardType & CT_SD1) { /* SDC ver 1.XX */ + } + else { // SDC ver 1.XX or MMC + if ((send_cmd(CMD9, 0) == 0) && rcvr_datablock(csd, 16)) { // Read CSD + if (CardType & CT_SD1) { // SDC ver 1.XX *(DWORD*)buff = (((csd[10] & 63) << 1) + ((WORD)(csd[11] & 128) >> 7) + 1) << ((csd[13] >> 6) - 1); - } else { /* MMC */ + } + else { // MMC *(DWORD*)buff = ((WORD)((csd[10] & 124) >> 2) + 1) * (((csd[11] & 3) << 3) + ((csd[11] & 224) >> 5) + 1); } res = RES_OK; @@ -465,47 +473,47 @@ DRESULT disk_read ( } break; - case CTRL_TRIM: /* Erase a block of sectors (used when _USE_TRIM in ffconf.h is 1) */ - if (!(CardType & CT_SDC)) break; /* Check if the card is SDC */ - if (disk_ioctl(drv, MMC_GET_CSD, csd)) break; /* Get CSD */ - if (!(csd[0] >> 6) && !(csd[10] & 0x40)) break; /* Check if sector erase can be applied to the card */ - dp = (DWORD *)buff; st = dp[0]; ed = dp[1]; /* Load sector block */ + case CTRL_TRIM: // Erase a block of sectors (used when _USE_TRIM in ffconf.h is 1) + if (!(CardType & CT_SDC)) break; // Check if the card is SDC + if (disk_ioctl(drv, MMC_GET_CSD, csd)) break; // Get CSD + if (!(csd[0] >> 6) && !(csd[10] & 0x40)) break; // Check if sector erase can be applied to the card + dp = (DWORD *)buff; st = dp[0]; ed = dp[1]; // Load sector block if (!(CardType & CT_BLOCK)) { st *= 512; ed *= 512; } - if (send_cmd(CMD32, st) == 0 && send_cmd(CMD33, ed) == 0 && send_cmd(CMD38, 0) == 0 && wait_ready(30000)) { /* Erase sector block */ - res = RES_OK; /* FatFs does not check result of this command */ + if (send_cmd(CMD32, st) == 0 && send_cmd(CMD33, ed) == 0 && send_cmd(CMD38, 0) == 0 && wait_ready(30000)) { // Erase sector block + res = RES_OK; // FatFs does not check result of this command } break; - /* Following commands are never used by FatFs module */ + // The following commands are never used by FatFs module - case MMC_GET_TYPE: /* Get MMC/SDC type (BYTE) */ + case MMC_GET_TYPE: // Get MMC/SDC type (BYTE) *ptr = CardType; res = RES_OK; break; - case MMC_GET_CSD: /* Read CSD (16 bytes) */ - if (send_cmd(CMD9, 0) == 0 && rcvr_datablock(ptr, 16)) { /* READ_CSD */ + case MMC_GET_CSD: // Read CSD (16 bytes) + if (send_cmd(CMD9, 0) == 0 && rcvr_datablock(ptr, 16)) { res = RES_OK; } break; - case MMC_GET_CID: /* Read CID (16 bytes) */ - if (send_cmd(CMD10, 0) == 0 && rcvr_datablock(ptr, 16)) { /* READ_CID */ + case MMC_GET_CID: // Read CID (16 bytes) + if (send_cmd(CMD10, 0) == 0 && rcvr_datablock(ptr, 16)) { res = RES_OK; } break; - case MMC_GET_OCR: /* Read OCR (4 bytes) */ - if (send_cmd(CMD58, 0) == 0) { /* READ_OCR */ + case MMC_GET_OCR: // Read OCR (4 bytes) + if (send_cmd(CMD58, 0) == 0) { for (n = 4; n; n--) *ptr++ = xchg_spi(0xFF); res = RES_OK; } break; - case MMC_GET_SDSTAT: /* Read SD status (64 bytes) */ - if (send_cmd(ACMD13, 0) == 0) { /* SD_STATUS */ + case MMC_GET_SDSTAT: // Read SD status (64 bytes) + if (send_cmd(ACMD13, 0) == 0) { xchg_spi(0xFF); if (rcvr_datablock(ptr, 64)) res = RES_OK; } diff --git a/Marlin/src/HAL/STM32F1/onboard_sd.h b/Marlin/src/HAL/STM32F1/onboard_sd.h index 1dc7ec5b3bfa..f228d068c9db 100644 --- a/Marlin/src/HAL/STM32F1/onboard_sd.h +++ b/Marlin/src/HAL/STM32F1/onboard_sd.h @@ -7,8 +7,8 @@ #pragma once #define _DISKIO_WRITE 1 /* 1: Enable disk_write function */ -#define _DISKIO_IOCTL 1 /* 1: Enable disk_ioctl fucntion */ -#define _DISKIO_ISDIO 0 /* 1: Enable iSDIO control fucntion */ +#define _DISKIO_IOCTL 1 /* 1: Enable disk_ioctl function */ +#define _DISKIO_ISDIO 0 /* 1: Enable iSDIO control function */ typedef unsigned char BYTE; typedef unsigned short WORD; @@ -48,7 +48,7 @@ DRESULT disk_read(BYTE pdrv, BYTE* buff, DWORD sector, UINT count); DRESULT disk_write(BYTE pdrv, const BYTE* buff, DWORD sector, UINT count); #endif #if _DISKIO_IOCTL - DRESULT disk_ioctl(BYTE pdrv, BYTE cmd, void* buff); + DRESULT disk_ioctl(BYTE pdrv, BYTE cmd, void *buff); #endif /* Disk Status Bits (DSTATUS) */ @@ -56,7 +56,7 @@ DRESULT disk_read(BYTE pdrv, BYTE* buff, DWORD sector, UINT count); #define STA_NODISK 0x02 /* No medium in the drive */ #define STA_PROTECT 0x04 /* Write protected */ -/* Command code for disk_ioctrl fucntion */ +/* Command code for disk_ioctrl function */ /* Generic command (Used by FatFs) */ #define CTRL_SYNC 0 /* Complete pending write process (needed at _FS_READONLY == 0) */ diff --git a/Marlin/src/HAL/STM32F1/pinsDebug.h b/Marlin/src/HAL/STM32F1/pinsDebug.h index 2d63ebd770f0..b018a0fc8c0a 100644 --- a/Marlin/src/HAL/STM32F1/pinsDebug.h +++ b/Marlin/src/HAL/STM32F1/pinsDebug.h @@ -18,10 +18,102 @@ */ #pragma once -#ifdef NUM_DIGITAL_PINS // Only in ST's Arduino core (STM32duino, STM32Core) - #include "../STM32/pinsDebug_STM32duino.h" -#elif defined(BOARD_NR_GPIO_PINS) // Only in STM32GENERIC (Maple) - #include "../STM32/pinsDebug_STM32GENERIC.h" -#else - #error "M43 not supported for this board" +/** + * Support routines for MAPLE_STM32F1 + */ + +/** + * Translation of routines & variables used by pinsDebug.h + */ + +#ifndef BOARD_NR_GPIO_PINS // Only in MAPLE_STM32F1 + #error "Expected BOARD_NR_GPIO_PINS not found" #endif + +#include "fastio.h" + +extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS]; + +#define NUM_DIGITAL_PINS 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_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 + +// pins that will cause hang/reset/disconnect in M43 Toggle and Watch utilities +#ifndef M43_NEVER_TOUCH + #define M43_NEVER_TOUCH(Q) (Q >= 9 && Q <= 12) // SERIAL/USB pins PA9(TX) PA10(RX) +#endif + +static inline int8_t get_pin_mode(pin_t pin) { + return VALID_PIN(pin) ? _GET_MODE(pin) : -1; +} + +static inline pin_t DIGITAL_PIN_TO_ANALOG_PIN(pin_t pin) { + if (!VALID_PIN(pin)) return -1; + int8_t adc_channel = int8_t(PIN_MAP[pin].adc_channel); + #ifdef NUM_ANALOG_INPUTS + if (adc_channel >= NUM_ANALOG_INPUTS) adc_channel = ADCx; + #endif + return pin_t(adc_channel); +} + +static inline bool IS_ANALOG(pin_t pin) { + if (!VALID_PIN(pin)) return false; + if (PIN_MAP[pin].adc_channel != ADCx) { + #ifdef NUM_ANALOG_INPUTS + if (PIN_MAP[pin].adc_channel >= NUM_ANALOG_INPUTS) return false; + #endif + return _GET_MODE(pin) == GPIO_INPUT_ANALOG && !M43_NEVER_TOUCH(pin); + } + return false; +} + +static inline bool GET_PINMODE(const pin_t pin) { + return VALID_PIN(pin) && !IS_INPUT(pin); +} + +static inline bool GET_ARRAY_IS_DIGITAL(const int16_t array_pin) { + const pin_t pin = GET_ARRAY_PIN(array_pin); + return (!IS_ANALOG(pin) + #ifdef NUM_ANALOG_INPUTS + || PIN_MAP[pin].adc_channel >= NUM_ANALOG_INPUTS + #endif + ); +} + +#include "../../inc/MarlinConfig.h" // Allow pins/pins.h to set density + +static inline 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) + tdev == &timer8 ? '8' : + tdev == &timer5 ? '5' : + #endif + tdev == &timer4 ? '4' : + tdev == &timer3 ? '3' : + tdev == &timer2 ? '2' : + tdev == &timer1 ? '1' : '?' + ); + char buffer[10]; + sprintf_P(buffer, PSTR(" TIM%c CH%c"), num, ('0' + channel)); + SERIAL_ECHO(buffer); + } +} + +static inline void print_port(pin_t pin) { + const char port = 'A' + char(pin >> 4); // pin div 16 + const int16_t gbit = PIN_MAP[pin].gpio_bit; + char buffer[8]; + sprintf_P(buffer, PSTR("P%c%hd "), port, gbit); + if (gbit < 10) SERIAL_CHAR(' '); + SERIAL_ECHO(buffer); +} diff --git a/Marlin/src/HAL/STM32F1/sdio.cpp b/Marlin/src/HAL/STM32F1/sdio.cpp index ffa6db1206ae..6e41d2cbf1b4 100644 --- a/Marlin/src/HAL/STM32F1/sdio.cpp +++ b/Marlin/src/HAL/STM32F1/sdio.cpp @@ -184,6 +184,10 @@ bool SDIO_WriteBlock(uint32_t blockAddress, const uint8_t *data) { inline uint32_t SDIO_GetCardState() { return SDIO_CmdSendStatus(SdCard.RelCardAdd << 16U) ? (SDIO_GetResponse(SDIO_RESP1) >> 9U) & 0x0FU : SDIO_CARD_ERROR; } +// No F1 board with SDIO + MSC using Maple, that I aware of... +bool SDIO_IsReady() { return true; } +uint32_t SDIO_GetCardSize() { return 0; } + // ------------------------ // SD Commands and Responses // ------------------------ diff --git a/Marlin/src/HAL/STM32F1/spi_pins.h b/Marlin/src/HAL/STM32F1/spi_pins.h index 8f2b324f6457..7d650ffe373f 100644 --- a/Marlin/src/HAL/STM32F1/spi_pins.h +++ b/Marlin/src/HAL/STM32F1/spi_pins.h @@ -31,28 +31,24 @@ * SPI2 | PB12 PB13 PB14 PB15 | * SPI3 | PA15 PB3 PB4 PB5 | * +-----------------------------+ - * Any pin can be used for Chip Select (SS_PIN) + * Any pin can be used for Chip Select (SD_SS_PIN) * SPI1 is enabled by default */ -#ifndef SCK_PIN - #define SCK_PIN PA5 +#ifndef SD_SCK_PIN + #define SD_SCK_PIN PA5 #endif -#ifndef MISO_PIN - #define MISO_PIN PA6 +#ifndef SD_MISO_PIN + #define SD_MISO_PIN PA6 #endif -#ifndef MOSI_PIN - #define MOSI_PIN PA7 +#ifndef SD_MOSI_PIN + #define SD_MOSI_PIN PA7 #endif -#ifndef SS_PIN - #define SS_PIN PA4 +#ifndef SD_SS_PIN + #define SD_SS_PIN PA4 #endif #undef SDSS -#define SDSS SS_PIN +#define SDSS SD_SS_PIN -#if ENABLED(ENABLE_SPI3) - #define SPI_DEVICE 3 -#elif ENABLED(ENABLE_SPI2) - #define SPI_DEVICE 2 -#else +#ifndef SPI_DEVICE #define SPI_DEVICE 1 #endif diff --git a/Marlin/src/HAL/STM32F1/tft/tft_fsmc.h b/Marlin/src/HAL/STM32F1/tft/tft_fsmc.h index 11eb1ffa8410..d9ee1f4c7767 100644 --- a/Marlin/src/HAL/STM32F1/tft/tft_fsmc.h +++ b/Marlin/src/HAL/STM32F1/tft/tft_fsmc.h @@ -22,7 +22,7 @@ #pragma once #ifndef LCD_READ_ID - #define LCD_READ_ID 0x04 // Read display identification information (0xD3 on ILI9341) + #define LCD_READ_ID 0x04 // Read display identification information (0xD3 on ILI9341) #endif #ifndef LCD_READ_ID4 #define LCD_READ_ID4 0xD3 // Read display identification information (0xD3 on ILI9341) @@ -30,9 +30,9 @@ #include -#define DATASIZE_8BIT DMA_SIZE_8BITS -#define DATASIZE_16BIT DMA_SIZE_16BITS -#define TFT_IO_DRIVER TFT_FSMC +#define DATASIZE_8BIT DMA_SIZE_8BITS +#define DATASIZE_16BIT DMA_SIZE_16BITS +#define TFT_IO_DRIVER TFT_FSMC typedef struct { __IO uint16_t REG; diff --git a/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp b/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp index 1095389946ad..5edf96fe56be 100644 --- a/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp +++ b/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp @@ -90,12 +90,20 @@ void TFT_SPI::DataTransferBegin(uint16_t DataSize) { TFT_CS_L; } +#ifdef TFT_DEFAULT_DRIVER + #include "../../../lcd/tft_io/tft_ids.h" +#endif + uint32_t TFT_SPI::GetID() { uint32_t id; id = ReadID(LCD_READ_ID); - - if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) + if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) { id = ReadID(LCD_READ_ID4); + #ifdef TFT_DEFAULT_DRIVER + if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) + id = TFT_DEFAULT_DRIVER; + #endif + } return id; } diff --git a/Marlin/src/HAL/STM32F1/tft/xpt2046.cpp b/Marlin/src/HAL/STM32F1/tft/xpt2046.cpp index 616d05fead15..ac9ad072aa05 100644 --- a/Marlin/src/HAL/STM32F1/tft/xpt2046.cpp +++ b/Marlin/src/HAL/STM32F1/tft/xpt2046.cpp @@ -1,6 +1,9 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * 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 @@ -19,7 +22,7 @@ #include "../../../inc/MarlinConfig.h" -#if HAS_TFT_XPT2046 || HAS_TOUCH_XPT2046 +#if HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS #include "xpt2046.h" #include diff --git a/Marlin/src/HAL/STM32F1/tft/xpt2046.h b/Marlin/src/HAL/STM32F1/tft/xpt2046.h index 019f75efce12..aba0799e445f 100644 --- a/Marlin/src/HAL/STM32F1/tft/xpt2046.h +++ b/Marlin/src/HAL/STM32F1/tft/xpt2046.h @@ -1,6 +1,9 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * 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 @@ -25,16 +28,16 @@ #endif #ifndef TOUCH_MISO_PIN - #define TOUCH_MISO_PIN MISO_PIN + #define TOUCH_MISO_PIN SD_MISO_PIN #endif #ifndef TOUCH_MOSI_PIN - #define TOUCH_MOSI_PIN MOSI_PIN + #define TOUCH_MOSI_PIN SD_MOSI_PIN #endif #ifndef TOUCH_SCK_PIN - #define TOUCH_SCK_PIN SCK_PIN + #define TOUCH_SCK_PIN SD_SCK_PIN #endif #ifndef TOUCH_CS_PIN - #define TOUCH_CS_PIN CS_PIN + #define TOUCH_CS_PIN SD_SS_PIN #endif #ifndef TOUCH_INT_PIN #define TOUCH_INT_PIN -1 @@ -51,7 +54,7 @@ enum XPTCoordinate : uint8_t { XPT2046_Z2 = 0x40 | XPT2046_CONTROL | XPT2046_DFR_MODE, }; -#if !defined(XPT2046_Z1_THRESHOLD) +#ifndef XPT2046_Z1_THRESHOLD #define XPT2046_Z1_THRESHOLD 10 #endif diff --git a/Marlin/src/HAL/STM32F1/timers.h b/Marlin/src/HAL/STM32F1/timers.h index 6f360f6bfc39..c89d55a134b4 100644 --- a/Marlin/src/HAL/STM32F1/timers.h +++ b/Marlin/src/HAL/STM32F1/timers.h @@ -25,9 +25,10 @@ * HAL for stm32duino.com based on Libmaple and compatible (STM32F1) */ -#include +#include "../../inc/MarlinConfig.h" +#include "HAL.h" + #include -#include "../../core/boards.h" // ------------------------ // Defines @@ -37,7 +38,6 @@ * TODO: Check and confirm what timer we will use for each Temps and stepper driving. * We should probable drive temps with PWM. */ -#define FORCE_INLINE __attribute__((always_inline)) inline typedef uint16_t hal_timer_t; #define HAL_TIMER_TYPE_MAX 0xFFFF @@ -80,7 +80,7 @@ typedef uint16_t hal_timer_t; //#define TEMP_TIMER_NUM 4 // 2->4, Timer 2 for Stepper Current PWM #endif -#if MB(BTT_SKR_MINI_E3_V1_0, BTT_SKR_E3_DIP, BTT_SKR_MINI_E3_V1_2, MKS_ROBIN_LITE) +#if MB(BTT_SKR_MINI_E3_V1_0, BTT_SKR_E3_DIP, BTT_SKR_MINI_E3_V1_2, MKS_ROBIN_LITE, MKS_ROBIN_E3D, MKS_ROBIN_E3) // SKR Mini E3 boards use PA8 as FAN_PIN, so TIMER 1 is used for Fan PWM. #ifdef STM32_HIGH_DENSITY #define SERVO0_TIMER_NUM 8 // tone.cpp uses Timer 4 @@ -129,8 +129,10 @@ timer_dev* get_timer_dev(int number); #define HAL_STEP_TIMER_ISR() extern "C" void stepTC_Handler() #endif -extern "C" void tempTC_Handler(); -extern "C" void stepTC_Handler(); +extern "C" { + void tempTC_Handler(); + void stepTC_Handler(); +} // ------------------------ // Public Variables @@ -164,7 +166,7 @@ FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const ha case STEP_TIMER_NUM: // NOTE: WE have set ARPE = 0, which means the Auto reload register is not preloaded // and there is no need to use any compare, as in the timer mode used, setting ARR to the compare value - // will result in exactly the same effect, ie trigerring an interrupt, and on top, set counter to 0 + // will result in exactly the same effect, ie triggering an interrupt, and on top, set counter to 0 timer_set_reload(STEP_TIMER_DEV, compare); // We reload direct ARR as needed during counting up break; case TEMP_TIMER_NUM: diff --git a/Marlin/src/HAL/STM32F1/watchdog.cpp b/Marlin/src/HAL/STM32F1/watchdog.cpp index ca91a6fe4350..b812a4fa6403 100644 --- a/Marlin/src/HAL/STM32F1/watchdog.cpp +++ b/Marlin/src/HAL/STM32F1/watchdog.cpp @@ -33,6 +33,11 @@ #include #include "watchdog.h" +/** + * The watchdog clock is 40Khz. So for a 4s or 8s interval use a /256 preescaler and 625 or 1250 reload value (counts down to 0). + */ +#define STM32F1_WD_RELOAD TERN(WATCHDOG_DURATION_8S, 1250, 625) // 4 or 8 second timeout + void HAL_watchdog_refresh() { #if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED) TOGGLE(LED_PIN); // heartbeat indicator @@ -49,7 +54,7 @@ void watchdogSetup() { * * @return No return * - * @details The watchdog clock is 40Khz. We need a 4 seconds interval, so use a /256 preescaler and 625 reload value (counts down to 0) + * @details The watchdog clock is 40Khz. So for a 4s or 8s interval use a /256 preescaler and 625 or 1250 reload value (counts down to 0). */ void watchdog_init() { #if DISABLED(DISABLE_WATCHDOG_INIT) diff --git a/Marlin/src/HAL/STM32F1/watchdog.h b/Marlin/src/HAL/STM32F1/watchdog.h index 7185d6977521..68920f8cb692 100644 --- a/Marlin/src/HAL/STM32F1/watchdog.h +++ b/Marlin/src/HAL/STM32F1/watchdog.h @@ -27,18 +27,9 @@ #include -/** - * The watchdog clock is 40Khz. We need a 4 seconds interval, so use a /256 preescaler and - * 625 reload value (counts down to 0) - * use 1250 for 8 seconds - */ -#define STM32F1_WD_RELOAD 625 - -// Arduino STM32F1 core now has watchdog support - -// Initialize watchdog with a 4 second countdown time +// Initialize watchdog with a 4 or 8 second countdown time void watchdog_init(); -// Reset watchdog. MUST be called at least every 4 seconds after the -// first watchdog_init or STM32F1 will reset. +// Reset watchdog. MUST be called every 4 or 8 seconds after the +// first watchdog_init or the STM32F1 will reset. void HAL_watchdog_refresh(); diff --git a/Marlin/src/HAL/STM32_F4_F7/HAL.cpp b/Marlin/src/HAL/STM32_F4_F7/HAL.cpp deleted file mode 100644 index b4629d2afd12..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/HAL.cpp +++ /dev/null @@ -1,95 +0,0 @@ -/** - * 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 - * - * 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 . - * - */ -#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7)) - -#include "HAL.h" - -//#include - -// ------------------------ -// Public Variables -// ------------------------ - -uint16_t HAL_adc_result; - -// ------------------------ -// Public functions -// ------------------------ - -/* VGPV Done with defines -// disable interrupts -void cli() { noInterrupts(); } - -// enable interrupts -void sei() { interrupts(); } -*/ - -void HAL_clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); } - -uint8_t HAL_get_reset_source() { - if (__HAL_RCC_GET_FLAG(RCC_FLAG_IWDGRST) != RESET) return RST_WATCHDOG; - if (__HAL_RCC_GET_FLAG(RCC_FLAG_SFTRST) != RESET) return RST_SOFTWARE; - if (__HAL_RCC_GET_FLAG(RCC_FLAG_PINRST) != RESET) return RST_EXTERNAL; - if (__HAL_RCC_GET_FLAG(RCC_FLAG_PORRST) != RESET) return RST_POWER_ON; - return 0; -} - -void _delay_ms(const int delay_ms) { delay(delay_ms); } - -extern "C" { - extern unsigned int _ebss; // end of bss section -} - -// return free memory between end of heap (or end bss) and whatever is current - -/* -#include -//extern caddr_t _sbrk(int incr); -#ifndef CONFIG_HEAP_END -extern char _lm_heap_end; -#define CONFIG_HEAP_END ((caddr_t)&_lm_heap_end) -#endif - -extern "C" { - static int freeMemory() { - char top = 't'; - return &top - reinterpret_cast(sbrk(0)); - } - int freeMemory() { - int free_memory; - int heap_end = (int)_sbrk(0); - free_memory = ((int)&free_memory) - ((int)heap_end); - return free_memory; - } -} -*/ - -// ------------------------ -// ADC -// ------------------------ - -void HAL_adc_start_conversion(const uint8_t adc_pin) { HAL_adc_result = analogRead(adc_pin); } - -uint16_t HAL_adc_get_result() { return HAL_adc_result; } - -#endif // STM32GENERIC && (STM32F4 || STM32F7) diff --git a/Marlin/src/HAL/STM32_F4_F7/HAL.h b/Marlin/src/HAL/STM32_F4_F7/HAL.h deleted file mode 100644 index 00a65de7926f..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/HAL.h +++ /dev/null @@ -1,199 +0,0 @@ -/** - * 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 - * - * 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 CPU_32_BIT - -#include "../../inc/MarlinConfigPre.h" - -#include "../shared/Marduino.h" -#include "../shared/math_32bit.h" -#include "../shared/HAL_SPI.h" - -#include "fastio.h" -#include "watchdog.h" - -#include - -#if defined(STM32F4) && USBCON - #include -#endif - -// ------------------------ -// Defines -// ------------------------ - -// Serial override -//extern HalSerial usb_serial; - -#define _MSERIAL(X) SerialUART##X -#define MSERIAL(X) _MSERIAL(X) -#define SerialUART0 Serial1 - -#if defined(STM32F4) && SERIAL_PORT == 0 - #error "SERIAL_PORT cannot be 0. (Port 0 does not exist.) Please update your configuration." -#elif SERIAL_PORT == -1 - #define MYSERIAL0 SerialUSB -#elif WITHIN(SERIAL_PORT, 0, 6) - #define MYSERIAL0 MSERIAL(SERIAL_PORT) -#else - #error "SERIAL_PORT must be from -1 to 6. Please update your configuration." -#endif - -#ifdef SERIAL_PORT_2 - #if defined(STM32F4) && SERIAL_PORT_2 == 0 - #error "SERIAL_PORT_2 cannot be 0. (Port 0 does not exist.) Please update your configuration." - #elif SERIAL_PORT_2 == -1 - #define MYSERIAL1 SerialUSB - #elif WITHIN(SERIAL_PORT_2, 0, 6) - #define MYSERIAL1 MSERIAL(SERIAL_PORT_2) - #else - #error "SERIAL_PORT_2 must be from -1 to 6. Please update your configuration." - #endif -#endif - -#ifdef LCD_SERIAL_PORT - #if defined(STM32F4) && LCD_SERIAL_PORT == 0 - #error "LCD_SERIAL_PORT cannot be 0. (Port 0 does not exist.) Please update your configuration." - #elif LCD_SERIAL_PORT == -1 - #define LCD_SERIAL SerialUSB - #elif WITHIN(LCD_SERIAL_PORT, 0, 6) - #define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT) - #else - #error "LCD_SERIAL_PORT must be from -1 to 6. Please update your configuration." - #endif -#endif - -/** - * TODO: review this to return 1 for pins that are not analog input - */ -#ifndef analogInputToDigitalPin - #define analogInputToDigitalPin(p) (p) -#endif - -#define CRITICAL_SECTION_START() uint32_t primask = __get_PRIMASK(); __disable_irq() -#define CRITICAL_SECTION_END() if (!primask) __enable_irq() -#define ISRS_ENABLED() (!__get_PRIMASK()) -#define ENABLE_ISRS() __enable_irq() -#define DISABLE_ISRS() __disable_irq() -#define cli() __disable_irq() -#define sei() __enable_irq() - -// On AVR this is in math.h? -#define square(x) ((x)*(x)) - -#ifndef strncpy_P - #define strncpy_P(dest, src, num) strncpy((dest), (src), (num)) -#endif - -// Fix bug in pgm_read_ptr -#undef pgm_read_ptr -#define pgm_read_ptr(addr) (*(addr)) - -// ------------------------ -// Types -// ------------------------ - -typedef int8_t pin_t; - -#ifdef STM32F4 - #define HAL_SERVO_LIB libServo -#endif - -// ------------------------ -// Public Variables -// ------------------------ - -// Result of last ADC conversion -extern uint16_t HAL_adc_result; - -// ------------------------ -// Public functions -// ------------------------ - -// Memory related -#define __bss_end __bss_end__ - -inline void HAL_init() {} - -// Clear reset reason -void HAL_clear_reset_source(); - -// Reset reason -uint8_t HAL_get_reset_source(); - -inline void HAL_reboot() {} // reboot the board or restart the bootloader - -void _delay_ms(const int delay); - -/* -extern "C" { - int freeMemory(); -} -*/ - -extern "C" char* _sbrk(int incr); - -/* -int freeMemory() { - volatile int top; - top = (int)((char*)&top - reinterpret_cast(_sbrk(0))); - return top; -} -*/ - -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-function" - -static inline int freeMemory() { - volatile char top; - return &top - reinterpret_cast(_sbrk(0)); -} - -#pragma GCC diagnostic pop - -// -// ADC -// - -#define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT) - -inline void HAL_adc_init() {} - -#define HAL_ADC_VREF 3.3 -#define HAL_ADC_RESOLUTION 10 -#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) -#define HAL_READ_ADC() HAL_adc_result -#define HAL_ADC_READY() true - -void HAL_adc_start_conversion(const uint8_t adc_pin); -uint16_t HAL_adc_get_result(); - -#define GET_PIN_MAP_PIN(index) index -#define GET_PIN_MAP_INDEX(pin) pin -#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) - -#ifdef STM32F4 - #define JTAG_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_SW_ONLY) - #define JTAGSWD_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_NONE) -#endif diff --git a/Marlin/src/HAL/STM32_F4_F7/HAL_SPI.cpp b/Marlin/src/HAL/STM32_F4_F7/HAL_SPI.cpp deleted file mode 100644 index ebd0b4cee7d0..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/HAL_SPI.cpp +++ /dev/null @@ -1,164 +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 - * 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 - * 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 . - * - */ -#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7)) - -/** - * Software SPI functions originally from Arduino Sd2Card Library - * Copyright (c) 2009 by William Greiman - */ - -/** - * Adapted to the Marlin STM32F4/7 HAL - */ - -#include "../../inc/MarlinConfig.h" - -#include -#include -#include "../shared/HAL_SPI.h" -#include "spi_pins.h" - -// ------------------------ -// Public Variables -// ------------------------ - -static SPISettings spiConfig; - -// ------------------------ -// Public functions -// ------------------------ - -#if ENABLED(SOFTWARE_SPI) - // ------------------------ - // Software SPI - // ------------------------ - #error "Software SPI not supported for STM32F4/7. Use Hardware SPI." -#else - -// ------------------------ -// Hardware SPI -// ------------------------ - -/** - * VGPV SPI speed start and F_CPU/2, by default 72/2 = 36Mhz - */ - -/** - * @brief Begin SPI port setup - * - * @return Nothing - * - * @details Only configures SS pin since libmaple creates and initialize the SPI object - */ -void spiBegin() { - #if !defined(SS_PIN) || SS_PIN < 0 - #error "SS_PIN not defined!" - #endif - - OUT_WRITE(SS_PIN, HIGH); -} - -/** Configure SPI for specified SPI speed */ -void spiInit(uint8_t spiRate) { - // Use datarates Marlin uses - uint32_t clock; - switch (spiRate) { - case SPI_FULL_SPEED: clock = 20000000; break; // 13.9mhz=20000000 6.75mhz=10000000 3.38mhz=5000000 .833mhz=1000000 - case SPI_HALF_SPEED: clock = 5000000; break; - case SPI_QUARTER_SPEED: clock = 2500000; break; - case SPI_EIGHTH_SPEED: clock = 1250000; break; - case SPI_SPEED_5: clock = 625000; break; - case SPI_SPEED_6: clock = 300000; break; - default: clock = 4000000; // Default from the SPI libarary - } - spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0); - SPI.begin(); -} - -/** - * @brief Receives a single byte from the SPI port. - * - * @return Byte received - * - * @details - */ -uint8_t spiRec() { - SPI.beginTransaction(spiConfig); - uint8_t returnByte = SPI.transfer(0xFF); - SPI.endTransaction(); - return returnByte; -} - -/** - * @brief Receives a number of bytes from the SPI port to a buffer - * - * @param buf Pointer to starting address of buffer to write to. - * @param nbyte Number of bytes to receive. - * @return Nothing - * - * @details Uses DMA - */ -void spiRead(uint8_t* buf, uint16_t nbyte) { - SPI.beginTransaction(spiConfig); - #ifndef STM32GENERIC - SPI.dmaTransfer(0, const_cast(buf), nbyte); - #else - SPI.transfer((uint8_t*)buf, nbyte); - #endif - SPI.endTransaction(); -} - -/** - * @brief Sends a single byte on SPI port - * - * @param b Byte to send - * - * @details - */ -void spiSend(uint8_t b) { - SPI.beginTransaction(spiConfig); - SPI.transfer(b); - SPI.endTransaction(); -} - -/** - * @brief Write token and then write from 512 byte buffer to SPI (for SD card) - * - * @param buf Pointer with buffer start address - * @return Nothing - * - * @details Use DMA - */ -void spiSendBlock(uint8_t token, const uint8_t* buf) { - SPI.beginTransaction(spiConfig); - SPI.transfer(token); - #ifndef STM32GENERIC - SPI.dmaSend(const_cast(buf), 512); - #else - SPI.transfer((uint8_t*)buf, nullptr, 512); - #endif - SPI.endTransaction(); -} - -#endif // SOFTWARE_SPI -#endif // STM32GENERIC && (STM32F4 || STM32F7) diff --git a/Marlin/src/HAL/STM32_F4_F7/README.md b/Marlin/src/HAL/STM32_F4_F7/README.md deleted file mode 100644 index 3b5a9ab02e21..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/README.md +++ /dev/null @@ -1,6 +0,0 @@ -# This HAL is for... - - - STM32F407 MCU with STM32Generic Arduino core by danieleff. - - STM32F765 board "The Borg" with STM32Generic. - -See the `README.md` files in HAL_STM32F4 and HAL_STM32F7 for the specifics of those hals. diff --git a/Marlin/src/HAL/STM32_F4_F7/STM32F4/README.md b/Marlin/src/HAL/STM32_F4_F7/STM32F4/README.md deleted file mode 100644 index 10396e875b88..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/STM32F4/README.md +++ /dev/null @@ -1,12 +0,0 @@ -# This HAL is for the STM32F407 MCU used with STM32Generic Arduino core by danieleff. - -# Arduino core is located at: - -https://github.com/danieleff/STM32GENERIC - -Unzip it into [Arduino]/hardware folder - -# This HAL is in development. - -This HAL is a modified version of Chris Barr's Picoprint STM32F4 HAL. - diff --git a/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.cpp b/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.cpp deleted file mode 100644 index dc41f891318d..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.cpp +++ /dev/null @@ -1,115 +0,0 @@ -/** - * 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 - * - * 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 . - * - */ -#if defined(STM32GENERIC) && defined(STM32F4) - -#include "../../../inc/MarlinConfig.h" - -// ------------------------ -// Local defines -// ------------------------ - -#define NUM_HARDWARE_TIMERS 2 -#define STEP_TIMER_IRQ_ID TIM5_IRQn -#define TEMP_TIMER_IRQ_ID TIM7_IRQn - -// ------------------------ -// Private Variables -// ------------------------ - -stm32_timer_t TimerHandle[NUM_HARDWARE_TIMERS]; - -// ------------------------ -// Public functions -// ------------------------ - -bool timers_initialized[NUM_HARDWARE_TIMERS] = {false}; - -void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { - - if (!timers_initialized[timer_num]) { - constexpr uint32_t step_prescaler = STEPPER_TIMER_PRESCALE - 1, - temp_prescaler = TEMP_TIMER_PRESCALE - 1; - switch (timer_num) { - case STEP_TIMER_NUM: - // STEPPER TIMER TIM5 - use a 32bit timer - __HAL_RCC_TIM5_CLK_ENABLE(); - TimerHandle[timer_num].handle.Instance = TIM5; - TimerHandle[timer_num].handle.Init.Prescaler = step_prescaler; - TimerHandle[timer_num].handle.Init.CounterMode = TIM_COUNTERMODE_UP; - TimerHandle[timer_num].handle.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; - TimerHandle[timer_num].callback = (uint32_t)TC5_Handler; - HAL_NVIC_SetPriority(STEP_TIMER_IRQ_ID, 1, 0); - break; - - case TEMP_TIMER_NUM: - // TEMP TIMER TIM7 - any available 16bit Timer (1 already used for PWM) - __HAL_RCC_TIM7_CLK_ENABLE(); - TimerHandle[timer_num].handle.Instance = TIM7; - TimerHandle[timer_num].handle.Init.Prescaler = temp_prescaler; - TimerHandle[timer_num].handle.Init.CounterMode = TIM_COUNTERMODE_UP; - TimerHandle[timer_num].handle.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; - TimerHandle[timer_num].callback = (uint32_t)TC7_Handler; - HAL_NVIC_SetPriority(TEMP_TIMER_IRQ_ID, 2, 0); - break; - } - timers_initialized[timer_num] = true; - } - - TimerHandle[timer_num].handle.Init.Period = (((HAL_TIMER_RATE) / TimerHandle[timer_num].handle.Init.Prescaler) / frequency) - 1; - if (HAL_TIM_Base_Init(&TimerHandle[timer_num].handle) == HAL_OK) - HAL_TIM_Base_Start_IT(&TimerHandle[timer_num].handle); -} - -extern "C" void TIM5_IRQHandler() { - ((void(*)())TimerHandle[0].callback)(); -} -extern "C" void TIM7_IRQHandler() { - ((void(*)())TimerHandle[1].callback)(); -} - -void HAL_timer_enable_interrupt(const uint8_t timer_num) { - switch (timer_num) { - case STEP_TIMER_NUM: HAL_NVIC_EnableIRQ(STEP_TIMER_IRQ_ID); break; - case TEMP_TIMER_NUM: HAL_NVIC_EnableIRQ(TEMP_TIMER_IRQ_ID); break; - } -} - -void HAL_timer_disable_interrupt(const uint8_t timer_num) { - switch (timer_num) { - case STEP_TIMER_NUM: HAL_NVIC_DisableIRQ(STEP_TIMER_IRQ_ID); break; - case TEMP_TIMER_NUM: HAL_NVIC_DisableIRQ(TEMP_TIMER_IRQ_ID); break; - } - // We NEED memory barriers to ensure Interrupts are actually disabled! - // ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the ) - __DSB(); - __ISB(); -} - -bool HAL_timer_interrupt_enabled(const uint8_t timer_num) { - switch (timer_num) { - case STEP_TIMER_NUM: return NVIC->ISER[(uint32_t)((int32_t)STEP_TIMER_IRQ_ID) >> 5] & (uint32_t)(1 << ((uint32_t)((int32_t)STEP_TIMER_IRQ_ID) & (uint32_t)0x1F)); - case TEMP_TIMER_NUM: return NVIC->ISER[(uint32_t)((int32_t)TEMP_TIMER_IRQ_ID) >> 5] & (uint32_t)(1 << ((uint32_t)((int32_t)TEMP_TIMER_IRQ_ID) & (uint32_t)0x1F)); - } - return false; -} - -#endif // STM32GENERIC && STM32F4 diff --git a/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.h b/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.h deleted file mode 100644 index a4a7ad82cca9..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.h +++ /dev/null @@ -1,134 +0,0 @@ -/** - * 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 - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ -#pragma once - -#include - -// ------------------------ -// Defines -// ------------------------ - -#define FORCE_INLINE __attribute__((always_inline)) inline - -#define hal_timer_t uint32_t // TODO: One is 16-bit, one 32-bit - does this need to be checked? -#define HAL_TIMER_TYPE_MAX 0xFFFF - -#define HAL_TIMER_RATE (HAL_RCC_GetSysClockFreq() / 2) // frequency of timer peripherals - -#ifndef STEP_TIMER_NUM - #define STEP_TIMER_NUM 0 // Timer Index for Stepper -#endif -#ifndef PULSE_TIMER_NUM - #define PULSE_TIMER_NUM STEP_TIMER_NUM -#endif -#ifndef TEMP_TIMER_NUM - #define TEMP_TIMER_NUM 1 // Timer Index for Temperature -#endif - -#define TEMP_TIMER_PRESCALE 1000 // prescaler for setting Temp timer, 72Khz -#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency - -#define STEPPER_TIMER_PRESCALE 54 // was 40,prescaler for setting stepper timer, 2Mhz -#define STEPPER_TIMER_RATE (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) // frequency of stepper timer -#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs - -#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer -#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US - -#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM) -#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM) -#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM) - -#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM) -#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM) - -// TODO change this - -#ifdef STM32GENERIC - #define TC_TIMER_ARGS -#else - #define TC_TIMER_ARGS stimer_t *htim -#endif - -extern void TC5_Handler(TC_TIMER_ARGS); -extern void TC7_Handler(TC_TIMER_ARGS); -#ifndef HAL_STEP_TIMER_ISR - #define HAL_STEP_TIMER_ISR() void TC5_Handler(TC_TIMER_ARGS) -#endif -#ifndef HAL_TEMP_TIMER_ISR - #define HAL_TEMP_TIMER_ISR() void TC7_Handler(TC_TIMER_ARGS) -#endif - -// ------------------------ -// Types -// ------------------------ - -#ifdef STM32GENERIC - typedef struct { - TIM_HandleTypeDef handle; - uint32_t callback; - } tTimerConfig; - typedef tTimerConfig stm32_timer_t; -#else - typedef stimer_t stm32_timer_t; -#endif - -// ------------------------ -// Public Variables -// ------------------------ - -extern stm32_timer_t TimerHandle[]; - -// ------------------------ -// Public functions -// ------------------------ - -void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency); -void HAL_timer_enable_interrupt(const uint8_t timer_num); -void HAL_timer_disable_interrupt(const uint8_t timer_num); -bool HAL_timer_interrupt_enabled(const uint8_t timer_num); - -FORCE_INLINE static uint32_t HAL_timer_get_count(const uint8_t timer_num) { - return __HAL_TIM_GET_COUNTER(&TimerHandle[timer_num].handle); -} - -FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const uint32_t compare) { - __HAL_TIM_SET_AUTORELOAD(&TimerHandle[timer_num].handle, compare); - if (HAL_timer_get_count(timer_num) >= compare) - TimerHandle[timer_num].handle.Instance->EGR |= TIM_EGR_UG; // Generate an immediate update interrupt -} - -FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) { - return __HAL_TIM_GET_AUTORELOAD(&TimerHandle[timer_num].handle); -} - -#ifdef STM32GENERIC - FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { - if (__HAL_TIM_GET_FLAG(&TimerHandle[timer_num].handle, TIM_FLAG_UPDATE) == SET) - __HAL_TIM_CLEAR_FLAG(&TimerHandle[timer_num].handle, TIM_FLAG_UPDATE); - } -#else - #define HAL_timer_isr_prologue(TIMER_NUM) -#endif - -#define HAL_timer_isr_epilogue(TIMER_NUM) diff --git a/Marlin/src/HAL/STM32_F4_F7/STM32F7/README.md b/Marlin/src/HAL/STM32_F4_F7/STM32F7/README.md deleted file mode 100644 index 23155b425e31..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/STM32F7/README.md +++ /dev/null @@ -1,27 +0,0 @@ -# This HAL is for the STM32F765 board "The Borg" used with STM32Generic Arduino core by danieleff. - -# Original core is located at: - -https://github.com/danieleff/STM32GENERIC - -but I haven't committed the changes needed for the Borg there yet, so please use: - -https://github.com/Spawn32/STM32GENERIC - -Unzip it into [Arduino]/hardware folder - - -Download the latest GNU ARM Embedded Toolchain: - -https://developer.arm.com/open-source/gnu-toolchain/gnu-rm/downloads - -(The one in Arduino doesn't support STM32F7). - -Change compiler.path in platform.txt to point to the one you downloaded. - -# This HAL is in development. -# Currently only tested on "The Borg". - -You will also need the latest Arduino 1.9.0-beta or newer. - -This HAL is a modified version of Chris Barr's Picoprint STM32F4 HAL, so shouldn't be to hard to get it to work on a F4. diff --git a/Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.cpp b/Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.cpp deleted file mode 100644 index e67808c3c458..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.cpp +++ /dev/null @@ -1,898 +0,0 @@ -/** - * TMC26XStepper.cpp - - TMC26X Stepper library for Wiring/Arduino - * - * based on the stepper library by Tom Igoe, et. al. - * - * Copyright (c) 2011, Interactive Matter, Marcus Nowotny - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. - */ - -#if defined(STM32GENERIC) && defined(STM32F7) - -#include "../../../inc/MarlinConfigPre.h" - -#if HAS_DRIVER(TMC2660) - -#include -#include -#include "TMC2660.h" - -#include "../../../inc/MarlinConfig.h" -#include "../../../MarlinCore.h" -#include "../../../module/stepper/indirection.h" -#include "../../../module/printcounter.h" -#include "../../../libs/duration_t.h" -#include "../../../libs/hex_print.h" - -//some default values used in initialization -#define DEFAULT_MICROSTEPPING_VALUE 32 - -//TMC26X register definitions -#define DRIVER_CONTROL_REGISTER 0x0UL -#define CHOPPER_CONFIG_REGISTER 0x80000UL -#define COOL_STEP_REGISTER 0xA0000ul -#define STALL_GUARD2_LOAD_MEASURE_REGISTER 0xC0000ul -#define DRIVER_CONFIG_REGISTER 0xE0000ul - -#define REGISTER_BIT_PATTERN 0xFFFFFul - -//definitions for the driver control register -#define MICROSTEPPING_PATTERN 0xFul -#define STEP_INTERPOLATION 0x200UL -#define DOUBLE_EDGE_STEP 0x100UL -#define VSENSE 0x40UL -#define READ_MICROSTEP_POSTION 0x0UL -#define READ_STALL_GUARD_READING 0x10UL -#define READ_STALL_GUARD_AND_COOL_STEP 0x20UL -#define READ_SELECTION_PATTERN 0x30UL - -//definitions for the chopper config register -#define CHOPPER_MODE_STANDARD 0x0UL -#define CHOPPER_MODE_T_OFF_FAST_DECAY 0x4000UL -#define T_OFF_PATTERN 0xFul -#define RANDOM_TOFF_TIME 0x2000UL -#define BLANK_TIMING_PATTERN 0x18000UL -#define BLANK_TIMING_SHIFT 15 -#define HYSTERESIS_DECREMENT_PATTERN 0x1800UL -#define HYSTERESIS_DECREMENT_SHIFT 11 -#define HYSTERESIS_LOW_VALUE_PATTERN 0x780UL -#define HYSTERESIS_LOW_SHIFT 7 -#define HYSTERESIS_START_VALUE_PATTERN 0x78UL -#define HYSTERESIS_START_VALUE_SHIFT 4 -#define T_OFF_TIMING_PATERN 0xFul - -//definitions for cool step register -#define MINIMUM_CURRENT_FOURTH 0x8000UL -#define CURRENT_DOWN_STEP_SPEED_PATTERN 0x6000UL -#define SE_MAX_PATTERN 0xF00ul -#define SE_CURRENT_STEP_WIDTH_PATTERN 0x60UL -#define SE_MIN_PATTERN 0xFul - -//definitions for StallGuard2 current register -#define STALL_GUARD_FILTER_ENABLED 0x10000UL -#define STALL_GUARD_TRESHHOLD_VALUE_PATTERN 0x17F00ul -#define CURRENT_SCALING_PATTERN 0x1Ful -#define STALL_GUARD_CONFIG_PATTERN 0x17F00ul -#define STALL_GUARD_VALUE_PATTERN 0x7F00ul - -//definitions for the input from the TMC2660 -#define STATUS_STALL_GUARD_STATUS 0x1UL -#define STATUS_OVER_TEMPERATURE_SHUTDOWN 0x2UL -#define STATUS_OVER_TEMPERATURE_WARNING 0x4UL -#define STATUS_SHORT_TO_GROUND_A 0x8UL -#define STATUS_SHORT_TO_GROUND_B 0x10UL -#define STATUS_OPEN_LOAD_A 0x20UL -#define STATUS_OPEN_LOAD_B 0x40UL -#define STATUS_STAND_STILL 0x80UL -#define READOUT_VALUE_PATTERN 0xFFC00ul - -#define CPU_32_BIT - -//default values -#define INITIAL_MICROSTEPPING 0x3UL //32th microstepping - -SPIClass SPI_6(SPI6, SPI6_MOSI_PIN, SPI6_MISO_PIN, SPI6_SCK_PIN); - -#define STEPPER_SPI SPI_6 - -//debuging output - -//#define TMC_DEBUG1 - -uint8_t current_scaling = 0; - -/** - * Constructor - * number_of_steps - the steps per rotation - * cs_pin - the SPI client select pin - * dir_pin - the pin where the direction pin is connected - * step_pin - the pin where the step pin is connected - */ -TMC26XStepper::TMC26XStepper(const int16_t in_steps, int16_t cs_pin, int16_t dir_pin, int16_t step_pin, uint16_t current, uint16_t resistor) { - // We are not started yet - started = false; - - // By default cool step is not enabled - cool_step_enabled = false; - - // Save the pins for later use - this->cs_pin = cs_pin; - this->dir_pin = dir_pin; - this->step_pin = step_pin; - - // Store the current sense resistor value for later use - this->resistor = resistor; - - // Initizalize our status values - this->steps_left = 0; - this->direction = 0; - - // Initialize register values - driver_control_register_value = DRIVER_CONTROL_REGISTER | INITIAL_MICROSTEPPING; - chopper_config_register = CHOPPER_CONFIG_REGISTER; - - // Setting the default register values - driver_control_register_value = DRIVER_CONTROL_REGISTER|INITIAL_MICROSTEPPING; - microsteps = _BV(INITIAL_MICROSTEPPING); - chopper_config_register = CHOPPER_CONFIG_REGISTER; - cool_step_register_value = COOL_STEP_REGISTER; - stallguard2_current_register_value = STALL_GUARD2_LOAD_MEASURE_REGISTER; - driver_configuration_register_value = DRIVER_CONFIG_REGISTER | READ_STALL_GUARD_READING; - - // Set the current - setCurrent(current); - // Set to a conservative start value - setConstantOffTimeChopper(7, 54, 13,12,1); - // Set a nice microstepping value - setMicrosteps(DEFAULT_MICROSTEPPING_VALUE); - // Save the number of steps - number_of_steps = in_steps; -} - - -/** - * start & configure the stepper driver - * just must be called. - */ -void TMC26XStepper::start() { - - #ifdef TMC_DEBUG1 - SERIAL_ECHOLNPGM("\n TMC26X stepper library"); - SERIAL_ECHOPAIR("\n CS pin: ", cs_pin); - SERIAL_ECHOPAIR("\n DIR pin: ", dir_pin); - SERIAL_ECHOPAIR("\n STEP pin: ", step_pin); - SERIAL_PRINTF("\n current scaling: %d", current_scaling); - SERIAL_PRINTF("\n Resistor: %d", resistor); - //SERIAL_PRINTF("\n current: %d", current); - SERIAL_ECHOPAIR("\n Microstepping: ", microsteps); - #endif - - //set the pins as output & its initial value - pinMode(step_pin, OUTPUT); - pinMode(dir_pin, OUTPUT); - pinMode(cs_pin, OUTPUT); - extDigitalWrite(step_pin, LOW); - extDigitalWrite(dir_pin, LOW); - extDigitalWrite(cs_pin, HIGH); - - STEPPER_SPI.begin(); - STEPPER_SPI.beginTransaction(SPISettings(4000000, MSBFIRST, SPI_MODE3)); - - //set the initial values - send262(driver_control_register_value); - send262(chopper_config_register); - send262(cool_step_register_value); - send262(stallguard2_current_register_value); - send262(driver_configuration_register_value); - - //save that we are in running mode - started = true; -} - -/** - * Mark the driver as unstarted to be able to start it again - */ -void TMC26XStepper::un_start() { started = false; } - - -/** - * Sets the speed in revs per minute - */ -void TMC26XStepper::setSpeed(uint16_t whatSpeed) { - this->speed = whatSpeed; - this->step_delay = 60UL * sq(1000UL) / ((uint32_t)this->number_of_steps * (uint32_t)whatSpeed * (uint32_t)this->microsteps); - #ifdef TMC_DEBUG0 // crashes - SERIAL_ECHOPAIR("\nStep delay in micros: ", this->step_delay); - #endif - // Update the next step time - this->next_step_time = this->last_step_time + this->step_delay; -} - -uint16_t TMC26XStepper::getSpeed() { return this->speed; } - -/** - * Moves the motor steps_to_move steps. - * Negative indicates the reverse direction. - */ -char TMC26XStepper::step(int16_t steps_to_move) { - if (this->steps_left == 0) { - this->steps_left = ABS(steps_to_move); // how many steps to take - - // determine direction based on whether steps_to_move is + or -: - if (steps_to_move > 0) - this->direction = 1; - else if (steps_to_move < 0) - this->direction = 0; - return 0; - } - return -1; -} - -char TMC26XStepper::move() { - // decrement the number of steps, moving one step each time: - if (this->steps_left > 0) { - uint32_t time = micros(); - // move only if the appropriate delay has passed: - - // rem if (time >= this->next_step_time) { - - if (ABS(time - this->last_step_time) > this->step_delay) { - // increment or decrement the step number, - // depending on direction: - if (this->direction == 1) - extDigitalWrite(step_pin, HIGH); - else { - extDigitalWrite(dir_pin, HIGH); - extDigitalWrite(step_pin, HIGH); - } - // get the timeStamp of when you stepped: - this->last_step_time = time; - this->next_step_time = time + this->step_delay; - // decrement the steps left: - steps_left--; - //disable the step & dir pins - extDigitalWrite(step_pin, LOW); - extDigitalWrite(dir_pin, LOW); - } - return -1; - } - return 0; -} - -char TMC26XStepper::isMoving() { return this->steps_left > 0; } - -uint16_t TMC26XStepper::getStepsLeft() { return this->steps_left; } - -char TMC26XStepper::stop() { - //note to self if the motor is currently moving - char state = isMoving(); - //stop the motor - this->steps_left = 0; - this->direction = 0; - //return if it was moving - return state; -} - -void TMC26XStepper::setCurrent(uint16_t current) { - uint8_t current_scaling = 0; - //calculate the current scaling from the max current setting (in mA) - float mASetting = (float)current, - resistor_value = (float)this->resistor; - // remove vsense flag - this->driver_configuration_register_value &= ~(VSENSE); - // Derived from I = (cs + 1) / 32 * (Vsense / Rsense) - // leading to cs = 32 * R * I / V (with V = 0,31V oder 0,165V and I = 1000 * current) - // with Rsense = 0,15 - // for vsense = 0,310V (VSENSE not set) - // or vsense = 0,165V (VSENSE set) - current_scaling = (byte)((resistor_value * mASetting * 32.0 / (0.31 * sq(1000.0))) - 0.5); //theoretically - 1.0 for better rounding it is 0.5 - - // Check if the current scalingis too low - if (current_scaling < 16) { - // Set the csense bit to get a use half the sense voltage (to support lower motor currents) - this->driver_configuration_register_value |= VSENSE; - // and recalculate the current setting - current_scaling = (byte)((resistor_value * mASetting * 32.0 / (0.165 * sq(1000.0))) - 0.5); //theoretically - 1.0 for better rounding it is 0.5 - #ifdef TMC_DEBUG0 // crashes - SERIAL_ECHOPAIR("\nCS (Vsense=1): ",current_scaling); - #endif - } - #ifdef TMC_DEBUG0 // crashes - else - SERIAL_ECHOPAIR("\nCS: ", current_scaling); - #endif - - // do some sanity checks - NOMORE(current_scaling, 31); - - // delete the old value - stallguard2_current_register_value &= ~(CURRENT_SCALING_PATTERN); - // set the new current scaling - stallguard2_current_register_value |= current_scaling; - // if started we directly send it to the motor - if (started) { - send262(driver_configuration_register_value); - send262(stallguard2_current_register_value); - } -} - -uint16_t TMC26XStepper::getCurrent() { - // Calculate the current according to the datasheet to be on the safe side. - // This is not the fastest but the most accurate and illustrative way. - float result = (float)(stallguard2_current_register_value & CURRENT_SCALING_PATTERN), - resistor_value = (float)this->resistor, - voltage = (driver_configuration_register_value & VSENSE) ? 0.165 : 0.31; - result = (result + 1.0) / 32.0 * voltage / resistor_value * sq(1000.0); - return (uint16_t)result; -} - -void TMC26XStepper::setStallGuardThreshold(char stallguard_threshold, char stallguard_filter_enabled) { - // We just have 5 bits - LIMIT(stallguard_threshold, -64, 63); - - // Add trim down to 7 bits - stallguard_threshold &= 0x7F; - // Delete old StallGuard settings - stallguard2_current_register_value &= ~(STALL_GUARD_CONFIG_PATTERN); - if (stallguard_filter_enabled) - stallguard2_current_register_value |= STALL_GUARD_FILTER_ENABLED; - - // Set the new StallGuard threshold - stallguard2_current_register_value |= (((uint32_t)stallguard_threshold << 8) & STALL_GUARD_CONFIG_PATTERN); - // If started we directly send it to the motor - if (started) send262(stallguard2_current_register_value); -} - -char TMC26XStepper::getStallGuardThreshold() { - uint32_t stallguard_threshold = stallguard2_current_register_value & STALL_GUARD_VALUE_PATTERN; - //shift it down to bit 0 - stallguard_threshold >>= 8; - //convert the value to an int16_t to correctly handle the negative numbers - char result = stallguard_threshold; - //check if it is negative and fill it up with leading 1 for proper negative number representation - //rem if (result & _BV(6)) { - - if (TEST(result, 6)) result |= 0xC0; - return result; -} - -char TMC26XStepper::getStallGuardFilter() { - if (stallguard2_current_register_value & STALL_GUARD_FILTER_ENABLED) - return -1; - return 0; -} - -/** - * Set the number of microsteps per step. - * 0,2,4,8,16,32,64,128,256 is supported - * any value in between will be mapped to the next smaller value - * 0 and 1 set the motor in full step mode - */ -void TMC26XStepper::setMicrosteps(const int16_t in_steps) { - uint16_t setting_pattern; - - if (in_steps >= 256) setting_pattern = 0; - else if (in_steps >= 128) setting_pattern = 1; - else if (in_steps >= 64) setting_pattern = 2; - else if (in_steps >= 32) setting_pattern = 3; - else if (in_steps >= 16) setting_pattern = 4; - else if (in_steps >= 8) setting_pattern = 5; - else if (in_steps >= 4) setting_pattern = 6; - else if (in_steps >= 2) setting_pattern = 7; - else if (in_steps <= 1) setting_pattern = 8; // 1 and 0 lead to full step - - microsteps = _BV(8 - setting_pattern); - - #ifdef TMC_DEBUG0 // crashes - SERIAL_ECHOPAIR("\n Microstepping: ", microsteps); - #endif - - // Delete the old value - this->driver_control_register_value &= 0x000FFFF0UL; - - // Set the new value - this->driver_control_register_value |= setting_pattern; - - // If started we directly send it to the motor - if (started) send262(driver_control_register_value); - - // Recalculate the stepping delay by simply setting the speed again - this->setSpeed(this->speed); -} - -/** - * returns the effective number of microsteps at the moment - */ -int16_t TMC26XStepper::getMicrosteps() { return microsteps; } - -/** - * constant_off_time: The off time setting controls the minimum chopper frequency. - * For most applications an off time within the range of 5μs to 20μs will fit. - * 2...15: off time setting - * - * blank_time: Selects the comparator blank time. This time needs to safely cover the switching event and the - * duration of the ringing on the sense resistor. For - * 0: min. setting 3: max. setting - * - * fast_decay_time_setting: Fast decay time setting. With CHM=1, these bits control the portion of fast decay for each chopper cycle. - * 0: slow decay only - * 1...15: duration of fast decay phase - * - * sine_wave_offset: Sine wave offset. With CHM=1, these bits control the sine wave offset. - * A positive offset corrects for zero crossing error. - * -3..-1: negative offset 0: no offset 1...12: positive offset - * - * use_current_comparator: Selects usage of the current comparator for termination of the fast decay cycle. - * If current comparator is enabled, it terminates the fast decay cycle in case the current - * reaches a higher negative value than the actual positive value. - * 1: enable comparator termination of fast decay cycle - * 0: end by time only - */ -void TMC26XStepper::setConstantOffTimeChopper(char constant_off_time, char blank_time, char fast_decay_time_setting, char sine_wave_offset, uint8_t use_current_comparator) { - // Perform some sanity checks - LIMIT(constant_off_time, 2, 15); - - // Save the constant off time - this->constant_off_time = constant_off_time; - - // Calculate the value acc to the clock cycles - const char blank_value = blank_time >= 54 ? 3 : - blank_time >= 36 ? 2 : - blank_time >= 24 ? 1 : 0; - - LIMIT(fast_decay_time_setting, 0, 15); - LIMIT(sine_wave_offset, -3, 12); - - // Shift the sine_wave_offset - sine_wave_offset += 3; - - // Calculate the register setting - // First of all delete all the values for this - chopper_config_register &= ~(_BV(12) | BLANK_TIMING_PATTERN | HYSTERESIS_DECREMENT_PATTERN | HYSTERESIS_LOW_VALUE_PATTERN | HYSTERESIS_START_VALUE_PATTERN | T_OFF_TIMING_PATERN); - // Set the constant off pattern - chopper_config_register |= CHOPPER_MODE_T_OFF_FAST_DECAY; - // Set the blank timing value - chopper_config_register |= ((uint32_t)blank_value) << BLANK_TIMING_SHIFT; - // Setting the constant off time - chopper_config_register |= constant_off_time; - // Set the fast decay time - // Set msb - chopper_config_register |= (((uint32_t)(fast_decay_time_setting & 0x8)) << HYSTERESIS_DECREMENT_SHIFT); - // Other bits - chopper_config_register |= (((uint32_t)(fast_decay_time_setting & 0x7)) << HYSTERESIS_START_VALUE_SHIFT); - // Set the sine wave offset - chopper_config_register |= (uint32_t)sine_wave_offset << HYSTERESIS_LOW_SHIFT; - // Using the current comparator? - if (!use_current_comparator) - chopper_config_register |= _BV(12); - - // If started we directly send it to the motor - if (started) { - // rem send262(driver_control_register_value); - send262(chopper_config_register); - } -} - -/** - * constant_off_time: The off time setting controls the minimum chopper frequency. - * For most applications an off time within the range of 5μs to 20μs will fit. - * 2...15: off time setting - * - * blank_time: Selects the comparator blank time. This time needs to safely cover the switching event and the - * duration of the ringing on the sense resistor. For - * 0: min. setting 3: max. setting - * - * hysteresis_start: Hysteresis start setting. Please remark, that this value is an offset to the hysteresis end value HEND. - * 1...8 - * - * hysteresis_end: Hysteresis end setting. Sets the hysteresis end value after a number of decrements. Decrement interval time is controlled by HDEC. - * The sum HSTRT+HEND must be <16. At a current setting CS of max. 30 (amplitude reduced to 240), the sum is not limited. - * -3..-1: negative HEND 0: zero HEND 1...12: positive HEND - * - * hysteresis_decrement: Hysteresis decrement setting. This setting determines the slope of the hysteresis during on time and during fast decay time. - * 0: fast decrement 3: very slow decrement - */ - -void TMC26XStepper::setSpreadCycleChopper(char constant_off_time, char blank_time, char hysteresis_start, char hysteresis_end, char hysteresis_decrement) { - // Perform some sanity checks - LIMIT(constant_off_time, 2, 15); - - // Save the constant off time - this->constant_off_time = constant_off_time; - - // Calculate the value acc to the clock cycles - const char blank_value = blank_time >= 54 ? 3 : - blank_time >= 36 ? 2 : - blank_time >= 24 ? 1 : 0; - - LIMIT(hysteresis_start, 1, 8); - hysteresis_start--; - - LIMIT(hysteresis_start, -3, 12); - - // Shift the hysteresis_end - hysteresis_end += 3; - - LIMIT(hysteresis_decrement, 0, 3); - - //first of all delete all the values for this - chopper_config_register &= ~(CHOPPER_MODE_T_OFF_FAST_DECAY | BLANK_TIMING_PATTERN | HYSTERESIS_DECREMENT_PATTERN | HYSTERESIS_LOW_VALUE_PATTERN | HYSTERESIS_START_VALUE_PATTERN | T_OFF_TIMING_PATERN); - - //set the blank timing value - chopper_config_register |= ((uint32_t)blank_value) << BLANK_TIMING_SHIFT; - //setting the constant off time - chopper_config_register |= constant_off_time; - //set the hysteresis_start - chopper_config_register |= ((uint32_t)hysteresis_start) << HYSTERESIS_START_VALUE_SHIFT; - //set the hysteresis end - chopper_config_register |= ((uint32_t)hysteresis_end) << HYSTERESIS_LOW_SHIFT; - //set the hystereis decrement - chopper_config_register |= ((uint32_t)blank_value) << BLANK_TIMING_SHIFT; - //if started we directly send it to the motor - if (started) { - //rem send262(driver_control_register_value); - send262(chopper_config_register); - } -} - -/** - * In a constant off time chopper scheme both coil choppers run freely, i.e. are not synchronized. - * The frequency of each chopper mainly depends on the coil current and the position dependant motor coil inductivity, thus it depends on the microstep position. - * With some motors a slightly audible beat can occur between the chopper frequencies, especially when they are near to each other. This typically occurs at a - * few microstep positions within each quarter wave. This effect normally is not audible when compared to mechanical noise generated by ball bearings, etc. - * Further factors which can cause a similar effect are a poor layout of sense resistor GND connection. - * Hint: A common factor, which can cause motor noise, is a bad PCB layout causing coupling of both sense resistor voltages - * (please refer to sense resistor layout hint in chapter 8.1). - * In order to minimize the effect of a beat between both chopper frequencies, an internal random generator is provided. - * It modulates the slow decay time setting when switched on by the RNDTF bit. The RNDTF feature further spreads the chopper spectrum, - * reducing electromagnetic emission on single frequencies. - */ -void TMC26XStepper::setRandomOffTime(char value) { - if (value) - chopper_config_register |= RANDOM_TOFF_TIME; - else - chopper_config_register &= ~(RANDOM_TOFF_TIME); - //if started we directly send it to the motor - if (started) { - //rem send262(driver_control_register_value); - send262(chopper_config_register); - } -} - -void TMC26XStepper::setCoolStepConfiguration( - uint16_t lower_SG_threshold, - uint16_t SG_hysteresis, - uint8_t current_decrement_step_size, - uint8_t current_increment_step_size, - uint8_t lower_current_limit -) { - // Sanitize the input values - NOMORE(lower_SG_threshold, 480); - // Divide by 32 - lower_SG_threshold >>= 5; - NOMORE(SG_hysteresis, 480); - // Divide by 32 - SG_hysteresis >>= 5; - NOMORE(current_decrement_step_size, 3); - NOMORE(current_increment_step_size, 3); - NOMORE(lower_current_limit, 1); - - // Store the lower level in order to enable/disable the cool step - this->cool_step_lower_threshold=lower_SG_threshold; - // If cool step is not enabled we delete the lower value to keep it disabled - if (!this->cool_step_enabled) lower_SG_threshold = 0; - // The good news is that we can start with a complete new cool step register value - // And simply set the values in the register - cool_step_register_value = ((uint32_t)lower_SG_threshold) - | (((uint32_t)SG_hysteresis) << 8) - | (((uint32_t)current_decrement_step_size) << 5) - | (((uint32_t)current_increment_step_size) << 13) - | (((uint32_t)lower_current_limit) << 15) - | COOL_STEP_REGISTER; // Register signature - - if (started) send262(cool_step_register_value); -} - -void TMC26XStepper::setCoolStepEnabled(boolean enabled) { - // Simply delete the lower limit to disable the cool step - cool_step_register_value &= ~SE_MIN_PATTERN; - // And set it to the proper value if cool step is to be enabled - if (enabled) - cool_step_register_value |= this->cool_step_lower_threshold; - // And save the enabled status - this->cool_step_enabled = enabled; - // Save the register value - if (started) send262(cool_step_register_value); -} - -boolean TMC26XStepper::isCoolStepEnabled() { return this->cool_step_enabled; } - -uint16_t TMC26XStepper::getCoolStepLowerSgThreshold() { - // We return our internally stored value - in order to provide the correct setting even if cool step is not enabled - return this->cool_step_lower_threshold<<5; -} - -uint16_t TMC26XStepper::getCoolStepUpperSgThreshold() { - return uint8_t((cool_step_register_value & SE_MAX_PATTERN) >> 8) << 5; -} - -uint8_t TMC26XStepper::getCoolStepCurrentIncrementSize() { - return uint8_t((cool_step_register_value & CURRENT_DOWN_STEP_SPEED_PATTERN) >> 13); -} - -uint8_t TMC26XStepper::getCoolStepNumberOfSGReadings() { - return uint8_t((cool_step_register_value & SE_CURRENT_STEP_WIDTH_PATTERN) >> 5); -} - -uint8_t TMC26XStepper::getCoolStepLowerCurrentLimit() { - return uint8_t((cool_step_register_value & MINIMUM_CURRENT_FOURTH) >> 15); -} - -void TMC26XStepper::setEnabled(boolean enabled) { - //delete the t_off in the chopper config to get sure - chopper_config_register &= ~(T_OFF_PATTERN); - if (enabled) { - //and set the t_off time - chopper_config_register |= this->constant_off_time; - } - //if not enabled we don't have to do anything since we already delete t_off from the register - if (started) send262(chopper_config_register); -} - -boolean TMC26XStepper::isEnabled() { return !!(chopper_config_register & T_OFF_PATTERN); } - -/** - * reads a value from the TMC26X status register. The value is not obtained directly but can then - * be read by the various status routines. - */ -void TMC26XStepper::readStatus(char read_value) { - uint32_t old_driver_configuration_register_value = driver_configuration_register_value; - //reset the readout configuration - driver_configuration_register_value &= ~(READ_SELECTION_PATTERN); - //this now equals TMC26X_READOUT_POSITION - so we just have to check the other two options - if (read_value == TMC26X_READOUT_STALLGUARD) - driver_configuration_register_value |= READ_STALL_GUARD_READING; - else if (read_value == TMC26X_READOUT_CURRENT) - driver_configuration_register_value |= READ_STALL_GUARD_AND_COOL_STEP; - - //all other cases are ignored to prevent funny values - //check if the readout is configured for the value we are interested in - if (driver_configuration_register_value != old_driver_configuration_register_value) { - //because then we need to write the value twice - one time for configuring, second time to get the value, see below - send262(driver_configuration_register_value); - } - //write the configuration to get the last status - send262(driver_configuration_register_value); -} - -int16_t TMC26XStepper::getMotorPosition() { - //we read it out even if we are not started yet - perhaps it is useful information for somebody - readStatus(TMC26X_READOUT_POSITION); - return getReadoutValue(); -} - -//reads the StallGuard setting from last status -//returns -1 if StallGuard information is not present -int16_t TMC26XStepper::getCurrentStallGuardReading() { - //if we don't yet started there cannot be a StallGuard value - if (!started) return -1; - //not time optimal, but solution optiomal: - //first read out the StallGuard value - readStatus(TMC26X_READOUT_STALLGUARD); - return getReadoutValue(); -} - -uint8_t TMC26XStepper::getCurrentCSReading() { - //if we don't yet started there cannot be a StallGuard value - if (!started) return 0; - //not time optimal, but solution optiomal: - //first read out the StallGuard value - readStatus(TMC26X_READOUT_CURRENT); - return (getReadoutValue() & 0x1F); -} - -uint16_t TMC26XStepper::getCurrentCurrent() { - float result = (float)getCurrentCSReading(), - resistor_value = (float)this->resistor, - voltage = (driver_configuration_register_value & VSENSE)? 0.165 : 0.31; - result = (result + 1.0) / 32.0 * voltage / resistor_value * sq(1000.0); - return (uint16_t)result; -} - -/** - * Return true if the StallGuard threshold has been reached - */ -boolean TMC26XStepper::isStallGuardOverThreshold() { - if (!this->started) return false; - return (driver_status_result & STATUS_STALL_GUARD_STATUS); -} - -/** - * returns if there is any over temperature condition: - * OVER_TEMPERATURE_PREWARING if pre warning level has been reached - * OVER_TEMPERATURE_SHUTDOWN if the temperature is so hot that the driver is shut down - * Any of those levels are not too good. - */ -char TMC26XStepper::getOverTemperature() { - if (!this->started) return 0; - - if (driver_status_result & STATUS_OVER_TEMPERATURE_SHUTDOWN) - return TMC26X_OVERTEMPERATURE_SHUTDOWN; - - if (driver_status_result & STATUS_OVER_TEMPERATURE_WARNING) - return TMC26X_OVERTEMPERATURE_PREWARING; - - return 0; -} - -// Is motor channel A shorted to ground -boolean TMC26XStepper::isShortToGroundA() { - if (!this->started) return false; - return (driver_status_result & STATUS_SHORT_TO_GROUND_A); -} - -// Is motor channel B shorted to ground -boolean TMC26XStepper::isShortToGroundB() { - if (!this->started) return false; - return (driver_status_result & STATUS_SHORT_TO_GROUND_B); -} - -// Is motor channel A connected -boolean TMC26XStepper::isOpenLoadA() { - if (!this->started) return false; - return (driver_status_result & STATUS_OPEN_LOAD_A); -} - -// Is motor channel B connected -boolean TMC26XStepper::isOpenLoadB() { - if (!this->started) return false; - return (driver_status_result & STATUS_OPEN_LOAD_B); -} - -// Is chopper inactive since 2^20 clock cycles - defaults to ~0,08s -boolean TMC26XStepper::isStandStill() { - if (!this->started) return false; - return (driver_status_result & STATUS_STAND_STILL); -} - -//is chopper inactive since 2^20 clock cycles - defaults to ~0,08s -boolean TMC26XStepper::isStallGuardReached() { - if (!this->started) return false; - return (driver_status_result & STATUS_STALL_GUARD_STATUS); -} - -//reads the StallGuard setting from last status -//returns -1 if StallGuard information is not present -int16_t TMC26XStepper::getReadoutValue() { - return (int)(driver_status_result >> 10); -} - -int16_t TMC26XStepper::getResistor() { return this->resistor; } - -boolean TMC26XStepper::isCurrentScalingHalfed() { - return !!(this->driver_configuration_register_value & VSENSE); -} -/** - * version() returns the version of the library: - */ -int16_t TMC26XStepper::version() { return 1; } - -void TMC26XStepper::debugLastStatus() { - #ifdef TMC_DEBUG1 - if (this->started) { - if (this->getOverTemperature()&TMC26X_OVERTEMPERATURE_PREWARING) - SERIAL_ECHOLNPGM("\n WARNING: Overtemperature Prewarning!"); - else if (this->getOverTemperature()&TMC26X_OVERTEMPERATURE_SHUTDOWN) - SERIAL_ECHOLNPGM("\n ERROR: Overtemperature Shutdown!"); - - if (this->isShortToGroundA()) - SERIAL_ECHOLNPGM("\n ERROR: SHORT to ground on channel A!"); - - if (this->isShortToGroundB()) - SERIAL_ECHOLNPGM("\n ERROR: SHORT to ground on channel B!"); - - if (this->isOpenLoadA()) - SERIAL_ECHOLNPGM("\n ERROR: Channel A seems to be unconnected!"); - - if (this->isOpenLoadB()) - SERIAL_ECHOLNPGM("\n ERROR: Channel B seems to be unconnected!"); - - if (this->isStallGuardReached()) - SERIAL_ECHOLNPGM("\n INFO: Stall Guard level reached!"); - - if (this->isStandStill()) - SERIAL_ECHOLNPGM("\n INFO: Motor is standing still."); - - uint32_t readout_config = driver_configuration_register_value & READ_SELECTION_PATTERN; - const int16_t value = getReadoutValue(); - if (readout_config == READ_MICROSTEP_POSTION) { - SERIAL_ECHOPAIR("\n Microstep position phase A: ", value); - } - else if (readout_config == READ_STALL_GUARD_READING) { - SERIAL_ECHOPAIR("\n Stall Guard value:", value); - } - else if (readout_config == READ_STALL_GUARD_AND_COOL_STEP) { - SERIAL_ECHOPAIR("\n Approx Stall Guard: ", value & 0xF); - SERIAL_ECHOPAIR("\n Current level", value & 0x1F0); - } - } - #endif -} - -/** - * send register settings to the stepper driver via SPI - * returns the current status - */ -inline void TMC26XStepper::send262(uint32_t datagram) { - uint32_t i_datagram; - - //preserver the previous spi mode - //uint8_t oldMode = SPCR & SPI_MODE_MASK; - - //if the mode is not correct set it to mode 3 - //if (oldMode != SPI_MODE3) { - // SPI.setDataMode(SPI_MODE3); - //} - - //select the TMC driver - extDigitalWrite(cs_pin, LOW); - - //ensure that only valid bist are set (0-19) - //datagram &=REGISTER_BIT_PATTERN; - - #ifdef TMC_DEBUG1 - //SERIAL_PRINTF("Sending "); - //SERIAL_PRINTF("Sending ", datagram,HEX); - //SERIAL_ECHOPAIR("\n\nSending \n", print_hex_long(datagram)); - SERIAL_PRINTF("\n\nSending %x", datagram); - #endif - - //write/read the values - i_datagram = STEPPER_SPI.transfer((datagram >> 16) & 0xFF); - i_datagram <<= 8; - i_datagram |= STEPPER_SPI.transfer((datagram >> 8) & 0xFF); - i_datagram <<= 8; - i_datagram |= STEPPER_SPI.transfer((datagram) & 0xFF); - i_datagram >>= 4; - - #ifdef TMC_DEBUG1 - //SERIAL_PRINTF("Received "); - //SERIAL_PRINTF("Received ", i_datagram,HEX); - //SERIAL_ECHOPAIR("\n\nReceived \n", i_datagram); - SERIAL_PRINTF("\n\nReceived %x", i_datagram); - debugLastStatus(); - #endif - - //deselect the TMC chip - extDigitalWrite(cs_pin, HIGH); - - //restore the previous SPI mode if neccessary - //if the mode is not correct set it to mode 3 - //if (oldMode != SPI_MODE3) { - // SPI.setDataMode(oldMode); - //} - - //store the datagram as status result - driver_status_result = i_datagram; -} - -#endif // HAS_DRIVER(TMC2660) - -#endif // STM32GENERIC && STM32F7 diff --git a/Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.h b/Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.h deleted file mode 100644 index 208c3bc7e062..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.h +++ /dev/null @@ -1,593 +0,0 @@ -/** - * TMC26XStepper.h - - TMC26X Stepper library for Wiring/Arduino - * - * based on the stepper library by Tom Igoe, et. al. - * - * Copyright (c) 2011, Interactive Matter, Marcus Nowotny - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. - */ -#pragma once - -#include - -//! return value for TMC26XStepper.getOverTemperature() if there is a overtemperature situation in the TMC chip -/*! - * This warning indicates that the TMC chip is too warm. - * It is still working but some parameters may be inferior. - * You should do something against it. - */ -#define TMC26X_OVERTEMPERATURE_PREWARING 1 -//! return value for TMC26XStepper.getOverTemperature() if there is a overtemperature shutdown in the TMC chip -/*! - * This warning indicates that the TMC chip is too warm to operate and has shut down to prevent damage. - * It will stop working until it cools down again. - * If you encouter this situation you must do something against it. Like reducing the current or improving the PCB layout - * and/or heat management. - */ -#define TMC26X_OVERTEMPERATURE_SHUTDOWN 2 - -//which values can be read out -/*! - * Selects to readout the microstep position from the motor. - *\sa readStatus() - */ -#define TMC26X_READOUT_POSITION 0 -/*! - * Selects to read out the StallGuard value of the motor. - *\sa readStatus() - */ -#define TMC26X_READOUT_STALLGUARD 1 -/*! - * Selects to read out the current current setting (acc. to CoolStep) and the upper bits of the StallGuard value from the motor. - *\sa readStatus(), setCurrent() - */ -#define TMC26X_READOUT_CURRENT 3 - -/*! - * Define to set the minimum current for CoolStep operation to 1/2 of the selected CS minium. - *\sa setCoolStepConfiguration() - */ -#define COOL_STEP_HALF_CS_LIMIT 0 -/*! - * Define to set the minimum current for CoolStep operation to 1/4 of the selected CS minium. - *\sa setCoolStepConfiguration() - */ -#define COOL_STEP_QUARTDER_CS_LIMIT 1 - -/*! - * \class TMC26XStepper - * \brief Class representing a TMC26X stepper driver - * - * To use one of these drivers in your code create an object of its class: - * \code - * TMC26XStepper tmc_stepper = TMC26XStepper(200,1,2,3,500); - * \endcode - * see TMC26XStepper(int16_t number_of_steps, int16_t cs_pin, int16_t dir_pin, int16_t step_pin, uint16_t rms_current) - * - * Keep in mind that you need to start the driver with start() in order to configure the TMC26X. - * - * The most important function is move(). It checks if the motor requires a step. It's important to call move() as - * often as possible in loop(). I suggest using a very fast loop routine and always call move() at the beginning or end. - * - * To move you must set a movement speed with setSpeed(). The speed is a positive value, setting the RPM. - * - * To really move the motor you have to call step() to tell the driver to move the motor the given number - * of steps in the given direction. Positive values move the motor in one direction, negative values in the other. - * - * You can check with isMoving() if the motor is still moving or stop it abruptly with stop(). - */ -class TMC26XStepper { - public: - /*! - * \brief Create a new representation of a stepper motor connected to a TMC26X stepper driver - * - * Main constructor. If in doubt use this. All parameters must be provided as described below. - * - * \param number_of_steps Number of steps the motor has per rotation. - * \param cs_pin Arduino pin connected to the Client Select Pin (!CS) of the TMC26X for SPI. - * \param dir_pin Arduino pin connected to the DIR input of the TMC26X. - * \param step_pin Arduino pin connected to the STEP pin of the TMC26X. - * \param rms_current Maximum current to provide to the motor in mA (!). A value of 200 will send up to 200mA to the motor. - * \param resistor Current sense resistor in milli-Ohm, defaults to 0.15 Ohm (or 150 milli-Ohm) as in the TMC260 Arduino Shield. - * - * You must also call TMC26XStepper.start() to configure the stepper driver for use. - * - * By default the Constant Off Time chopper is used. See TMC26XStepper.setConstantOffTimeChopper() for details. - * This should work on most motors (YMMV). You may want to configure and use the Spread Cycle Chopper. See setSpreadCycleChopper(). - * - * By default a microstepping of 1/32 is used to provide a smooth motor run while still giving a good progression per step. - * Change stepping by sending setMicrosteps() a different value. - * \sa start(), setMicrosteps() - */ - TMC26XStepper(const int16_t in_steps, int16_t cs_pin, int16_t dir_pin, int16_t step_pin, uint16_t current, uint16_t resistor=100); //resistor=150 - - /*! - * \brief Configure and start the TMC26X stepper driver. Before this is called the stepper driver is nonfunctional. - * - * Configure the TMC26X stepper driver for the given values via SPI. - * Most member functions are non-functional if the driver has not been started, - * therefore it is best to call this in setup(). - */ - void start(); - - /*! - * \brief Reset the stepper in unconfigured mode. - * - * Allows start to be called again. It doesn't change the internal stepper - * configuration or the desired configuration. It just marks the stepper as - * not-yet-started. The stepper doesn't need to be reconfigured before - * starting again, and is not reset to any factory settings. - * It must be reset intentionally. - * (Hint: Normally you do not need this function) - */ - void un_start(); - - /*! - * \brief Set the rotation speed in RPM. - * \param whatSpeed the desired speed in RPM. - */ - void setSpeed(uint16_t whatSpeed); - - /*! - * \brief Report the currently selected speed in RPM. - * \sa setSpeed() - */ - uint16_t getSpeed(); - - /*! - * \brief Set the number of microsteps in 2^i values (rounded) up to 256 - * - * This method sets the number of microsteps per step in 2^i interval. - * It accepts 1, 2, 4, 16, 32, 64, 128 or 256 as valid microsteps. - * Other values will be rounded down to the next smaller value (e.g., 3 gives a microstepping of 2). - * You can always check the current microstepping with getMicrosteps(). - */ - void setMicrosteps(const int16_t in_steps); - - /*! - * \brief Return the effective current number of microsteps selected. - * - * Always returns the effective number of microsteps. - * This may be different from the micro-steps set in setMicrosteps() since it is rounded to 2^i. - * - * \sa setMicrosteps() - */ - int16_t getMicrosteps(); - - /*! - * \brief Initiate a movement with the given number of steps. Positive values move in one direction, negative in the other. - * - * \param number_of_steps The number of steps to move the motor. - * \return 0 if the motor was not moving and moves now. -1 if the motor is moving and the new steps could not be set. - * - * If the previous movement is incomplete the function returns -1 and doesn't change the steps to move the motor. - * If the motor does not move it returns 0. - * - * The movement direction is determined by the sign of the steps parameter. The motor direction in machine space - * cannot be determined, as it depends on the construction of the motor and how it functions in the drive system. - * - * For safety, verify with isMoving() or even use stop() to stop the motor before giving it new step directions. - * \sa isMoving(), getStepsLeft(), stop() - */ - char step(int16_t number_of_steps); - - /*! - * \brief Central movement method. Must be called as often as possible in the loop function and is very fast. - * - * Check if the motor still has to move and whether the wait-to-step interval has expired, and manages the - * number of steps remaining to fulfill the current move command. - * - * This function is implemented to be as fast as possible, so call it as often as possible in your loop. - * It should be invoked with as frequently and with as much regularity as possible. - * - * This can be called even when the motor is known not to be moving. It will simply return. - * - * The frequency with which this function is called determines the top stepping speed of the motor. - * It is recommended to call this using a hardware timer to ensure regular invocation. - * \sa step() - */ - char move(); - - /*! - * \brief Check whether the last movement command is done. - * \return 0 if the motor stops, -1 if the motor is moving. - * - * Used to determine if the motor is ready for new movements. - *\sa step(), move() - */ - char isMoving(); - - /*! - * \brief Get the number of steps left in the current movement. - * \return The number of steps left in the movement. Always positive. - */ - uint16_t getStepsLeft(); - - /*! - * \brief Stop the motor immediately. - * \return -1 if the motor was moving and is really stoped or 0 if it was not moving at all. - * - * This method directly and abruptly stops the motor and may be used as an emergency stop. - */ - char stop(); - - /*! - * \brief Set and configure the classical Constant Off Timer Chopper - * \param constant_off_time The off time setting controls the minimum chopper frequency. For most applications an off time within the range of 5μs to 20μs will fit. Setting this parameter to zero completely disables all driver transistors and the motor can free-wheel. 0: chopper off, 1:15: off time setting (1 will work with minimum blank time of 24 clocks) - * \param blank_time Comparator blank time. This duration needs to safely cover the duration of the switching event and the ringing on the sense resistor. For most low current drivers, a setting of 1 or 2 is good. For high current applications with large MOSFETs, a setting of 2 or 3 will be required. 0 (min setting) … (3) amx setting - * \param fast_decay_time_setting Fast decay time setting. Controls the portion of fast decay for each chopper cycle. 0: slow decay only, 1…15: duration of fast decay phase - * \param sine_wave_offset Sine wave offset. Controls the sine wave offset. A positive offset corrects for zero crossing error. -3…-1: negative offset, 0: no offset,1…12: positive offset - * \param use_curreent_comparator Selects usage of the current comparator for termination of the fast decay cycle. If current comparator is enabled, it terminates the fast decay cycle in case the current reaches a higher negative value than the actual positive value. (0 disable, -1 enable). - * - * The classic constant off time chopper uses a fixed portion of fast decay following each on phase. - * While the duration of the on time is determined by the chopper comparator, the fast decay time needs - * to be set by the user in a way, that the current decay is enough for the driver to be able to follow - * the falling slope of the sine wave, and on the other hand it should not be too long, in order to minimize - * motor current ripple and power dissipation. This best can be tuned using an oscilloscope or - * trying out motor smoothness at different velocities. A good starting value is a fast decay time setting - * similar to the slow decay time setting. - * After tuning of the fast decay time, the offset should be determined, in order to have a smooth zero transition. - * This is necessary, because the fast decay phase leads to the absolute value of the motor current being lower - * than the target current (see figure 17). If the zero offset is too low, the motor stands still for a short - * moment during current zero crossing, if it is set too high, it makes a larger microstep. - * Typically, a positive offset setting is required for optimum operation. - * - * \sa setSpreadCycleChoper() for other alternatives. - * \sa setRandomOffTime() for spreading the noise over a wider spectrum - */ - void setConstantOffTimeChopper(char constant_off_time, char blank_time, char fast_decay_time_setting, char sine_wave_offset, uint8_t use_current_comparator); - - /*! - * \brief Sets and configures with spread cycle chopper. - * \param constant_off_time The off time setting controls the minimum chopper frequency. For most applications an off time within the range of 5μs to 20μs will fit. Setting this parameter to zero completely disables all driver transistors and the motor can free-wheel. 0: chopper off, 1:15: off time setting (1 will work with minimum blank time of 24 clocks) - * \param blank_time Selects the comparator blank time. This time needs to safely cover the switching event and the duration of the ringing on the sense resistor. For most low current drivers, a setting of 1 or 2 is good. For high current applications with large MOSFETs, a setting of 2 or 3 will be required. 0 (min setting) … (3) amx setting - * \param hysteresis_start Hysteresis start setting. Please remark, that this value is an offset to the hysteresis end value. 1 … 8 - * \param hysteresis_end Hysteresis end setting. Sets the hysteresis end value after a number of decrements. Decrement interval time is controlled by hysteresis_decrement. The sum hysteresis_start + hysteresis_end must be <16. At a current setting CS of max. 30 (amplitude reduced to 240), the sum is not limited. - * \param hysteresis_decrement Hysteresis decrement setting. This setting determines the slope of the hysteresis during on time and during fast decay time. 0 (fast decrement) … 3 (slow decrement). - * - * The spreadCycle chopper scheme (pat.fil.) is a precise and simple to use chopper principle, which automatically determines - * the optimum fast decay portion for the motor. Anyhow, a number of settings can be made in order to optimally fit the driver - * to the motor. - * Each chopper cycle is comprised of an on-phase, a slow decay phase, a fast decay phase and a second slow decay phase. - * The slow decay phases limit the maximum chopper frequency and are important for low motor and driver power dissipation. - * The hysteresis start setting limits the chopper frequency by forcing the driver to introduce a minimum amount of - * current ripple into the motor coils. The motor inductivity determines the ability to follow a changing motor current. - * The duration of the on- and fast decay phase needs to cover at least the blank time, because the current comparator is - * disabled during this time. - * - * \sa setRandomOffTime() for spreading the noise over a wider spectrum - */ - void setSpreadCycleChopper(char constant_off_time, char blank_time, char hysteresis_start, char hysteresis_end, char hysteresis_decrement); - - /*! - * \brief Use random off time for noise reduction (0 for off, -1 for on). - * \param value 0 for off, -1 for on - * - * In a constant off time chopper scheme both coil choppers run freely, i.e. are not synchronized. - * The frequency of each chopper mainly depends on the coil current and the position dependant motor coil inductivity, - * thus it depends on the microstep position. With some motors a slightly audible beat can occur between the chopper - * frequencies, especially when they are near to each other. This typically occurs at a few microstep positions within - * each quarter wave. - * This effect normally is not audible when compared to mechanical noise generated by ball bearings, - * etc. Further factors which can cause a similar effect are a poor layout of sense resistor GND connection. - * In order to minimize the effect of a beat between both chopper frequencies, an internal random generator is provided. - * It modulates the slow decay time setting when switched on. The random off time feature further spreads the chopper spectrum, - * reducing electromagnetic emission on single frequencies. - */ - void setRandomOffTime(char value); - - /*! - * \brief set the maximum motor current in mA (1000 is 1 Amp) - * Keep in mind this is the maximum peak Current. The RMS current will be 1/sqrt(2) smaller. The actual current can also be smaller - * by employing CoolStep. - * \param current the maximum motor current in mA - * \sa getCurrent(), getCurrentCurrent() - */ - void setCurrent(uint16_t current); - - /*! - * \brief readout the motor maximum current in mA (1000 is an Amp) - * This is the maximum current. to get the current current - which may be affected by CoolStep us getCurrentCurrent() - * \return the maximum motor current in milli amps - * \sa getCurrentCurrent() - */ - uint16_t getCurrent(); - - /*! - * \brief set the StallGuard threshold in order to get sensible StallGuard readings. - * \param stallguard_threshold -64 … 63 the StallGuard threshold - * \param stallguard_filter_enabled 0 if the filter is disabled, -1 if it is enabled - * - * The StallGuard threshold is used to optimize the StallGuard reading to sensible values. It should be at 0 at - * the maximum allowable load on the otor (but not before). = is a good starting point (and the default) - * If you get Stall Gaurd readings of 0 without any load or with too little laod increase the value. - * If you get readings of 1023 even with load decrease the setting. - * - * If you switch on the filter the StallGuard reading is only updated each 4th full step to reduce the noise in the - * reading. - * - * \sa getCurrentStallGuardReading() to read out the current value. - */ - void setStallGuardThreshold(char stallguard_threshold, char stallguard_filter_enabled); - - /*! - * \brief reads out the StallGuard threshold - * \return a number between -64 and 63. - */ - char getStallGuardThreshold(); - - /*! - * \brief returns the current setting of the StallGuard filter - * \return 0 if not set, -1 if set - */ - char getStallGuardFilter(); - - /*! - * \brief This method configures the CoolStep smart energy operation. You must have a proper StallGuard configuration for the motor situation (current, voltage, speed) in rder to use this feature. - * \param lower_SG_threshold Sets the lower threshold for stallGuard2TM reading. Below this value, the motor current becomes increased. Allowed values are 0...480 - * \param SG_hysteresis Sets the distance between the lower and the upper threshold for stallGuard2TM reading. Above the upper threshold (which is lower_SG_threshold+SG_hysteresis+1) the motor current becomes decreased. Allowed values are 0...480 - * \param current_decrement_step_size Sets the current decrement steps. If the StallGuard value is above the threshold the current gets decremented by this step size. 0...32 - * \param current_increment_step_size Sets the current increment step. The current becomes incremented for each measured stallGuard2TM value below the lower threshold. 0...8 - * \param lower_current_limit Sets the lower motor current limit for coolStepTM operation by scaling the CS value. Values can be COOL_STEP_HALF_CS_LIMIT, COOL_STEP_QUARTER_CS_LIMIT - * The CoolStep smart energy operation automatically adjust the current sent into the motor according to the current load, - * read out by the StallGuard in order to provide the optimum torque with the minimal current consumption. - * You configure the CoolStep current regulator by defining upper and lower bounds of StallGuard readouts. If the readout is above the - * limit the current gets increased, below the limit the current gets decreased. - * You can specify the upper an lower threshold of the StallGuard readout in order to adjust the current. You can also set the number of - * StallGuard readings neccessary above or below the limit to get a more stable current adjustement. - * The current adjustement itself is configured by the number of steps the current gests in- or decreased and the absolut minimum current - * (1/2 or 1/4th otf the configured current). - * \sa COOL_STEP_HALF_CS_LIMIT, COOL_STEP_QUARTER_CS_LIMIT - */ - void setCoolStepConfiguration(uint16_t lower_SG_threshold, uint16_t SG_hysteresis, uint8_t current_decrement_step_size, - uint8_t current_increment_step_size, uint8_t lower_current_limit); - - /*! - * \brief enables or disables the CoolStep smart energy operation feature. It must be configured before enabling it. - * \param enabled true if CoolStep should be enabled, false if not. - * \sa setCoolStepConfiguration() - */ - void setCoolStepEnabled(boolean enabled); - - - /*! - * \brief check if the CoolStep feature is enabled - * \sa setCoolStepEnabled() - */ - boolean isCoolStepEnabled(); - - /*! - * \brief returns the lower StallGuard threshold for the CoolStep operation - * \sa setCoolStepConfiguration() - */ - uint16_t getCoolStepLowerSgThreshold(); - - /*! - * \brief returns the upper StallGuard threshold for the CoolStep operation - * \sa setCoolStepConfiguration() - */ - uint16_t getCoolStepUpperSgThreshold(); - - /*! - * \brief returns the number of StallGuard readings befor CoolStep adjusts the motor current. - * \sa setCoolStepConfiguration() - */ - uint8_t getCoolStepNumberOfSGReadings(); - - /*! - * \brief returns the increment steps for the current for the CoolStep operation - * \sa setCoolStepConfiguration() - */ - uint8_t getCoolStepCurrentIncrementSize(); - - /*! - * \brief returns the absolut minium current for the CoolStep operation - * \sa setCoolStepConfiguration() - * \sa COOL_STEP_HALF_CS_LIMIT, COOL_STEP_QUARTER_CS_LIMIT - */ - uint8_t getCoolStepLowerCurrentLimit(); - - /*! - * \brief Get the current microstep position for phase A - * \return The current microstep position for phase A 0…255 - * - * Keep in mind that this routine reads and writes a value via SPI - so this may take a bit time. - */ - int16_t getMotorPosition(); - - /*! - * \brief Reads the current StallGuard value. - * \return The current StallGuard value, lesser values indicate higher load, 0 means stall detected. - * Keep in mind that this routine reads and writes a value via SPI - so this may take a bit time. - * \sa setStallGuardThreshold() for tuning the readout to sensible ranges. - */ - int16_t getCurrentStallGuardReading(); - - /*! - * \brief Reads the current current setting value as fraction of the maximum current - * Returns values between 0 and 31, representing 1/32 to 32/32 (=1) - * \sa setCoolStepConfiguration() - */ - uint8_t getCurrentCSReading(); - - - /*! - *\brief a convenience method to determine if the current scaling uses 0.31V or 0.165V as reference. - *\return false if 0.13V is the reference voltage, true if 0.165V is used. - */ - boolean isCurrentScalingHalfed(); - - /*! - * \brief Reads the current current setting value and recalculates the absolute current in mA (1A would be 1000). - * This method calculates the currently used current setting (either by setting or by CoolStep) and reconstructs - * the current in mA by usinge the VSENSE and resistor value. This method uses floating point math - so it - * may not be the fastest. - * \sa getCurrentCSReading(), getResistor(), isCurrentScalingHalfed(), getCurrent() - */ - uint16_t getCurrentCurrent(); - - /*! - * \brief checks if there is a StallGuard warning in the last status - * \return 0 if there was no warning, -1 if there was some warning. - * Keep in mind that this method does not enforce a readout but uses the value of the last status readout. - * You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout. - * - * \sa setStallGuardThreshold() for tuning the readout to sensible ranges. - */ - boolean isStallGuardOverThreshold(); - - /*! - * \brief Return over temperature status of the last status readout - * return 0 is everything is OK, TMC26X_OVERTEMPERATURE_PREWARING if status is reached, TMC26X_OVERTEMPERATURE_SHUTDOWN is the chip is shutdown, -1 if the status is unknown. - * Keep in mind that this method does not enforce a readout but uses the value of the last status readout. - * You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout. - */ - char getOverTemperature(); - - /*! - * \brief Is motor channel A shorted to ground detected in the last status readout. - * \return true is yes, false if not. - * Keep in mind that this method does not enforce a readout but uses the value of the last status readout. - * You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout. - */ - - boolean isShortToGroundA(); - - /*! - * \brief Is motor channel B shorted to ground detected in the last status readout. - * \return true is yes, false if not. - * Keep in mind that this method does not enforce a readout but uses the value of the last status readout. - * You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout. - */ - boolean isShortToGroundB(); - /*! - * \brief iIs motor channel A connected according to the last statu readout. - * \return true is yes, false if not. - * Keep in mind that this method does not enforce a readout but uses the value of the last status readout. - * You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout. - */ - boolean isOpenLoadA(); - - /*! - * \brief iIs motor channel A connected according to the last statu readout. - * \return true is yes, false if not. - * Keep in mind that this method does not enforce a readout but uses the value of the last status readout. - * You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout. - */ - boolean isOpenLoadB(); - - /*! - * \brief Is chopper inactive since 2^20 clock cycles - defaults to ~0,08s - * \return true is yes, false if not. - * Keep in mind that this method does not enforce a readout but uses the value of the last status readout. - * You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout. - */ - boolean isStandStill(); - - /*! - * \brief checks if there is a StallGuard warning in the last status - * \return 0 if there was no warning, -1 if there was some warning. - * Keep in mind that this method does not enforce a readout but uses the value of the last status readout. - * You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout. - * - * \sa isStallGuardOverThreshold() - * TODO why? - * - * \sa setStallGuardThreshold() for tuning the readout to sensible ranges. - */ - boolean isStallGuardReached(); - - /*! - *\brief enables or disables the motor driver bridges. If disabled the motor can run freely. If enabled not. - *\param enabled a boolean value true if the motor should be enabled, false otherwise. - */ - void setEnabled(boolean enabled); - - /*! - *\brief checks if the output bridges are enabled. If the bridges are not enabled the motor can run freely - *\return true if the bridges and by that the motor driver are enabled, false if not. - *\sa setEnabled() - */ - boolean isEnabled(); - - /*! - * \brief Manually read out the status register - * This function sends a byte to the motor driver in order to get the current readout. The parameter read_value - * seletcs which value will get returned. If the read_vlaue changes in respect to the previous readout this method - * automatically send two bytes to the motor: one to set the redout and one to get the actual readout. So this method - * may take time to send and read one or two bits - depending on the previous readout. - * \param read_value selects which value to read out (0..3). You can use the defines TMC26X_READOUT_POSITION, TMC_262_READOUT_STALLGUARD, or TMC_262_READOUT_CURRENT - * \sa TMC26X_READOUT_POSITION, TMC_262_READOUT_STALLGUARD, TMC_262_READOUT_CURRENT - */ - void readStatus(char read_value); - - /*! - * \brief Returns the current sense resistor value in milliohm. - * The default value of ,15 Ohm will return 150. - */ - int16_t getResistor(); - - /*! - * \brief Prints out all the information that can be found in the last status read out - it does not force a status readout. - * The result is printed via Serial - */ - void debugLastStatus(); - - /*! - * \brief library version - * \return the version number as int. - */ - int16_t version(); - - private: - uint16_t steps_left; // The steps the motor has to do to complete the movement - int16_t direction; // Direction of rotation - uint32_t step_delay; // Delay between steps, in ms, based on speed - int16_t number_of_steps; // Total number of steps this motor can take - uint16_t speed; // Store the current speed in order to change the speed after changing microstepping - uint16_t resistor; // Current sense resitor value in milliohm - - uint32_t last_step_time, // Timestamp (ms) of the last step - next_step_time; // Timestamp (ms) of the next step - - // Driver control register copies to easily set & modify the registers - uint32_t driver_control_register_value, - chopper_config_register, - cool_step_register_value, - stallguard2_current_register_value, - driver_configuration_register_value, - driver_status_result; // The driver status result - - // Helper routione to get the top 10 bit of the readout - inline int16_t getReadoutValue(); - - // The pins for the stepper driver - uint8_t cs_pin, step_pin, dir_pin; - - // Status values - boolean started; // If the stepper has been started yet - int16_t microsteps; // The current number of micro steps - char constant_off_time; // We need to remember this value in order to enable and disable the motor - uint8_t cool_step_lower_threshold; // we need to remember the threshold to enable and disable the CoolStep feature - boolean cool_step_enabled; // We need to remember this to configure the coolstep if it si enabled - - // SPI sender - inline void send262(uint32_t datagram); -}; diff --git a/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.cpp b/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.cpp deleted file mode 100644 index f7ded7454dd9..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.cpp +++ /dev/null @@ -1,129 +0,0 @@ -/** - * 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 - * - * 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 . - * - */ -#if defined(STM32GENERIC) && defined(STM32F7) - -#include "../../../inc/MarlinConfig.h" - -// ------------------------ -// Local defines -// ------------------------ - -#define NUM_HARDWARE_TIMERS 2 - -//#define PRESCALER 1 - -// ------------------------ -// Private Variables -// ------------------------ - -tTimerConfig timerConfig[NUM_HARDWARE_TIMERS]; - -// ------------------------ -// Public functions -// ------------------------ - -bool timers_initialized[NUM_HARDWARE_TIMERS] = { false }; - -void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { - - if (!timers_initialized[timer_num]) { - switch (timer_num) { - case STEP_TIMER_NUM: - //STEPPER TIMER TIM5 //use a 32bit timer - __HAL_RCC_TIM5_CLK_ENABLE(); - timerConfig[0].timerdef.Instance = TIM5; - timerConfig[0].timerdef.Init.Prescaler = (STEPPER_TIMER_PRESCALE); - timerConfig[0].timerdef.Init.CounterMode = TIM_COUNTERMODE_UP; - timerConfig[0].timerdef.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; - timerConfig[0].IRQ_Id = TIM5_IRQn; - timerConfig[0].callback = (uint32_t)TC5_Handler; - HAL_NVIC_SetPriority(timerConfig[0].IRQ_Id, 1, 0); - #if PIN_EXISTS(STEPPER_ENABLE) - OUT_WRITE(STEPPER_ENABLE_PIN, HIGH); - #endif - break; - case TEMP_TIMER_NUM: - //TEMP TIMER TIM7 // any available 16bit Timer (1 already used for PWM) - __HAL_RCC_TIM7_CLK_ENABLE(); - timerConfig[1].timerdef.Instance = TIM7; - timerConfig[1].timerdef.Init.Prescaler = (TEMP_TIMER_PRESCALE); - timerConfig[1].timerdef.Init.CounterMode = TIM_COUNTERMODE_UP; - timerConfig[1].timerdef.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; - timerConfig[1].IRQ_Id = TIM7_IRQn; - timerConfig[1].callback = (uint32_t)TC7_Handler; - HAL_NVIC_SetPriority(timerConfig[1].IRQ_Id, 2, 0); - break; - } - timers_initialized[timer_num] = true; - } - - timerConfig[timer_num].timerdef.Init.Period = (((HAL_TIMER_RATE) / timerConfig[timer_num].timerdef.Init.Prescaler) / frequency) - 1; - - if (HAL_TIM_Base_Init(&timerConfig[timer_num].timerdef) == HAL_OK) - HAL_TIM_Base_Start_IT(&timerConfig[timer_num].timerdef); -} - -//forward the interrupt -extern "C" void TIM5_IRQHandler() { - ((void(*)())timerConfig[0].callback)(); -} -extern "C" void TIM7_IRQHandler() { - ((void(*)())timerConfig[1].callback)(); -} - -void HAL_timer_set_compare(const uint8_t timer_num, const uint32_t compare) { - __HAL_TIM_SetAutoreload(&timerConfig[timer_num].timerdef, compare); -} - -void HAL_timer_enable_interrupt(const uint8_t timer_num) { - HAL_NVIC_EnableIRQ(timerConfig[timer_num].IRQ_Id); -} - -void HAL_timer_disable_interrupt(const uint8_t timer_num) { - HAL_NVIC_DisableIRQ(timerConfig[timer_num].IRQ_Id); - - // We NEED memory barriers to ensure Interrupts are actually disabled! - // ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the ) - __DSB(); - __ISB(); -} - -hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) { - return __HAL_TIM_GetAutoreload(&timerConfig[timer_num].timerdef); -} - -uint32_t HAL_timer_get_count(const uint8_t timer_num) { - return __HAL_TIM_GetCounter(&timerConfig[timer_num].timerdef); -} - -void HAL_timer_isr_prologue(const uint8_t timer_num) { - if (__HAL_TIM_GET_FLAG(&timerConfig[timer_num].timerdef, TIM_FLAG_UPDATE) == SET) { - __HAL_TIM_CLEAR_FLAG(&timerConfig[timer_num].timerdef, TIM_FLAG_UPDATE); - } -} - -bool HAL_timer_interrupt_enabled(const uint8_t timer_num) { - const uint32_t IRQ_Id = uint32_t(timerConfig[timer_num].IRQ_Id); - return NVIC->ISER[IRQ_Id >> 5] & _BV32(IRQ_Id & 0x1F); -} - -#endif // STM32GENERIC && STM32F7 diff --git a/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.h b/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.h deleted file mode 100644 index d2f78259d68d..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.h +++ /dev/null @@ -1,107 +0,0 @@ -/** - * 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 - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ -#pragma once - -#include - -// ------------------------ -// Defines -// ------------------------ - -#define FORCE_INLINE __attribute__((always_inline)) inline - -#define hal_timer_t uint32_t // TODO: One is 16-bit, one 32-bit - does this need to be checked? -#define HAL_TIMER_TYPE_MAX 0xFFFF - -#define HAL_TIMER_RATE (HAL_RCC_GetSysClockFreq() / 2) // frequency of timer peripherals - -#ifndef STEP_TIMER_NUM - #define STEP_TIMER_NUM 0 // Timer Index for Stepper -#endif -#ifndef PULSE_TIMER_NUM - #define PULSE_TIMER_NUM STEP_TIMER_NUM -#endif -#ifndef TEMP_TIMER_NUM - #define TEMP_TIMER_NUM 1 // Timer Index for Temperature -#endif - -#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency -#define TEMP_TIMER_PRESCALE 1000 // prescaler for setting Temp timer, 72Khz - -#define STEPPER_TIMER_PRESCALE 54 // was 40,prescaler for setting stepper timer, 2Mhz -#define STEPPER_TIMER_RATE (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) // frequency of stepper timer -#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs - -#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer -#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US - -#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM) -#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM) - -#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM) -#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM) - -#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM) -#define TEMP_ISR_ENABLED() HAL_timer_interrupt_enabled(TEMP_TIMER_NUM) - -// TODO change this - -extern void TC5_Handler(); -extern void TC7_Handler(); -#ifndef HAL_STEP_TIMER_ISR - #define HAL_STEP_TIMER_ISR() void TC5_Handler() -#endif -#ifndef HAL_TEMP_TIMER_ISR - #define HAL_TEMP_TIMER_ISR() void TC7_Handler() -#endif - -// ------------------------ -// Types -// ------------------------ - -typedef struct { - TIM_HandleTypeDef timerdef; - IRQn_Type IRQ_Id; - uint32_t callback; -} tTimerConfig; - -// ------------------------ -// Public Variables -// ------------------------ - -//extern const tTimerConfig timerConfig[]; - -// ------------------------ -// Public functions -// ------------------------ - -void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency); -void HAL_timer_enable_interrupt(const uint8_t timer_num); -void HAL_timer_disable_interrupt(const uint8_t timer_num); -bool HAL_timer_interrupt_enabled(const uint8_t timer_num); - -void HAL_timer_set_compare(const uint8_t timer_num, const uint32_t compare); -hal_timer_t HAL_timer_get_compare(const uint8_t timer_num); -uint32_t HAL_timer_get_count(const uint8_t timer_num); -void HAL_timer_isr_prologue(const uint8_t timer_num); -#define HAL_timer_isr_epilogue(TIMER_NUM) diff --git a/Marlin/src/HAL/STM32_F4_F7/Servo.cpp b/Marlin/src/HAL/STM32_F4_F7/Servo.cpp deleted file mode 100644 index 7185468f50a8..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/Servo.cpp +++ /dev/null @@ -1,51 +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 - * 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 - * 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 . - * - */ -#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7)) - -#include "../../inc/MarlinConfig.h" - -#if HAS_SERVOS - -#include "Servo.h" - -int8_t libServo::attach(const int pin) { - if (servoIndex >= MAX_SERVOS) return -1; - return super::attach(pin); -} - -int8_t libServo::attach(const int pin, const int min, const int max) { - return super::attach(pin, min, max); -} - -void libServo::move(const int value) { - constexpr uint16_t servo_delay[] = SERVO_DELAY; - static_assert(COUNT(servo_delay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long."); - if (attach(0) >= 0) { - write(value); - safe_delay(servo_delay[servoIndex]); - TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach()); - } -} - -#endif // HAS_SERVOS -#endif // STM32GENERIC && (STM32F4 || STM32F7) diff --git a/Marlin/src/HAL/STM32_F4_F7/Servo.h b/Marlin/src/HAL/STM32_F4_F7/Servo.h deleted file mode 100644 index e42cc6084091..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/Servo.h +++ /dev/null @@ -1,41 +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 - * 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 - * 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 - -//#ifdef STM32F7 -// #include <../../libraries/Servo/src/Servo.h> -//#else - #include -//#endif - -// Inherit and expand on the official library -class libServo : public Servo { - public: - int8_t attach(const int pin); - int8_t attach(const int pin, const int min, const int max); - void move(const int value); - private: - typedef Servo super; - uint16_t min_ticks, max_ticks; - uint8_t servoIndex; // index into the channel data for this servo -}; diff --git a/Marlin/src/HAL/STM32_F4_F7/eeprom_emul.cpp b/Marlin/src/HAL/STM32_F4_F7/eeprom_emul.cpp deleted file mode 100644 index e0726c7cd592..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/eeprom_emul.cpp +++ /dev/null @@ -1,535 +0,0 @@ -/** - ****************************************************************************** - * @file eeprom_emul.cpp - * @author MCD Application Team - * @version V1.2.6 - * @date 04-November-2016 - * @brief This file provides all the EEPROM emulation firmware functions. - ****************************************************************************** - * @attention - * - * Copyright © 2016 STMicroelectronics International N.V. - * 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. Redistribution 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 other - * contributors to this software may be used to endorse or promote products - * derived from this software without specific written permission. - * 4. This software, including modifications and/or derivative works of this - * software, must execute solely and exclusively on microcontroller or - * microprocessor devices manufactured by or for STMicroelectronics. - * 5. Redistribution and use of this software other than as permitted under - * this license is void and will automatically terminate your rights under - * this license. - * - * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A - * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY - * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT - * SHALL STMICROELECTRONICS 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. - * - ****************************************************************************** - */ -/** @addtogroup EEPROM_Emulation - * @{ - */ -#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7)) - -#include "../../inc/MarlinConfig.h" - -#if ENABLED(FLASH_EEPROM_EMULATION) - -/* Includes ------------------------------------------------------------------*/ -#include "eeprom_emul.h" - -/* Private variables ---------------------------------------------------------*/ - -/* Global variable used to store variable value in read sequence */ -uint16_t DataVar = 0; - -/* Virtual address defined by the user: 0xFFFF value is prohibited */ -uint16_t VirtAddVarTab[NB_OF_VAR]; - -/* Private function prototypes -----------------------------------------------*/ - -static HAL_StatusTypeDef EE_Format(); -static uint16_t EE_FindValidPage(uint8_t Operation); -static uint16_t EE_VerifyPageFullWriteVariable(uint16_t VirtAddress, uint16_t Data); -static uint16_t EE_PageTransfer(uint16_t VirtAddress, uint16_t Data); -static uint16_t EE_VerifyPageFullyErased(uint32_t Address); - - /** - * @brief Restore the pages to a known good state in case of page's status - * corruption after a power loss. - * @param None. - * @retval - Flash error code: on write Flash error - * - FLASH_COMPLETE: on success - */ - -/* Private functions ---------------------------------------------------------*/ - -uint16_t EE_Initialize() { - /* Get Page0 and Page1 status */ - uint16_t PageStatus0 = (*(__IO uint16_t*)PAGE0_BASE_ADDRESS), - PageStatus1 = (*(__IO uint16_t*)PAGE1_BASE_ADDRESS); - - FLASH_EraseInitTypeDef pEraseInit; - pEraseInit.TypeErase = TYPEERASE_SECTORS; - pEraseInit.Sector = PAGE0_ID; - pEraseInit.NbSectors = 1; - pEraseInit.VoltageRange = VOLTAGE_RANGE; - - HAL_StatusTypeDef FlashStatus; // = HAL_OK - - /* Check for invalid header states and repair if necessary */ - uint32_t SectorError; - switch (PageStatus0) { - case ERASED: - if (PageStatus1 == VALID_PAGE) { /* Page0 erased, Page1 valid */ - /* Erase Page0 */ - if (!EE_VerifyPageFullyErased(PAGE0_BASE_ADDRESS)) { - /* As the last operation, simply return the result */ - return HAL_FLASHEx_Erase(&pEraseInit, &SectorError); - } - } - else if (PageStatus1 == RECEIVE_DATA) { /* Page0 erased, Page1 receive */ - /* Erase Page0 */ - if (!EE_VerifyPageFullyErased(PAGE0_BASE_ADDRESS)) { - HAL_StatusTypeDef fStat = HAL_FLASHEx_Erase(&pEraseInit, &SectorError); - /* If erase operation was failed, a Flash error code is returned */ - if (fStat != HAL_OK) return fStat; - } - /* Mark Page1 as valid */ - /* As the last operation, simply return the result */ - return HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, PAGE1_BASE_ADDRESS, VALID_PAGE); - } - else { /* First EEPROM access (Page0&1 are erased) or invalid state -> format EEPROM */ - /* Erase both Page0 and Page1 and set Page0 as valid page */ - /* As the last operation, simply return the result */ - return EE_Format(); - } - break; - - case RECEIVE_DATA: - if (PageStatus1 == VALID_PAGE) { /* Page0 receive, Page1 valid */ - /* Transfer data from Page1 to Page0 */ - int16_t x = -1; - for (uint16_t VarIdx = 0; VarIdx < NB_OF_VAR; VarIdx++) { - if (( *(__IO uint16_t*)(PAGE0_BASE_ADDRESS + 6)) == VirtAddVarTab[VarIdx]) - x = VarIdx; - if (VarIdx != x) { - /* Read the last variables' updates */ - uint16_t ReadStatus = EE_ReadVariable(VirtAddVarTab[VarIdx], &DataVar); - /* In case variable corresponding to the virtual address was found */ - if (ReadStatus != 0x1) { - /* Transfer the variable to the Page0 */ - uint16_t EepromStatus = EE_VerifyPageFullWriteVariable(VirtAddVarTab[VarIdx], DataVar); - /* If program operation was failed, a Flash error code is returned */ - if (EepromStatus != HAL_OK) return EepromStatus; - } - } - } - /* Mark Page0 as valid */ - FlashStatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, PAGE0_BASE_ADDRESS, VALID_PAGE); - /* If program operation was failed, a Flash error code is returned */ - if (FlashStatus != HAL_OK) return FlashStatus; - pEraseInit.Sector = PAGE1_ID; - pEraseInit.NbSectors = 1; - pEraseInit.VoltageRange = VOLTAGE_RANGE; - /* Erase Page1 */ - if (!EE_VerifyPageFullyErased(PAGE1_BASE_ADDRESS)) { - /* As the last operation, simply return the result */ - return HAL_FLASHEx_Erase(&pEraseInit, &SectorError); - } - } - else if (PageStatus1 == ERASED) { /* Page0 receive, Page1 erased */ - pEraseInit.Sector = PAGE1_ID; - pEraseInit.NbSectors = 1; - pEraseInit.VoltageRange = VOLTAGE_RANGE; - /* Erase Page1 */ - if (!EE_VerifyPageFullyErased(PAGE1_BASE_ADDRESS)) { - HAL_StatusTypeDef fStat = HAL_FLASHEx_Erase(&pEraseInit, &SectorError); - /* If erase operation was failed, a Flash error code is returned */ - if (fStat != HAL_OK) return fStat; - } - /* Mark Page0 as valid */ - /* As the last operation, simply return the result */ - return HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, PAGE0_BASE_ADDRESS, VALID_PAGE); - } - else { /* Invalid state -> format eeprom */ - /* Erase both Page0 and Page1 and set Page0 as valid page */ - /* As the last operation, simply return the result */ - return EE_Format(); - } - break; - - case VALID_PAGE: - if (PageStatus1 == VALID_PAGE) { /* Invalid state -> format eeprom */ - /* Erase both Page0 and Page1 and set Page0 as valid page */ - FlashStatus = EE_Format(); - /* If erase/program operation was failed, a Flash error code is returned */ - if (FlashStatus != HAL_OK) return FlashStatus; - } - else if (PageStatus1 == ERASED) { /* Page0 valid, Page1 erased */ - pEraseInit.Sector = PAGE1_ID; - pEraseInit.NbSectors = 1; - pEraseInit.VoltageRange = VOLTAGE_RANGE; - /* Erase Page1 */ - if (!EE_VerifyPageFullyErased(PAGE1_BASE_ADDRESS)) { - FlashStatus = HAL_FLASHEx_Erase(&pEraseInit, &SectorError); - /* If erase operation was failed, a Flash error code is returned */ - if (FlashStatus != HAL_OK) return FlashStatus; - } - } - else { /* Page0 valid, Page1 receive */ - /* Transfer data from Page0 to Page1 */ - int16_t x = -1; - for (uint16_t VarIdx = 0; VarIdx < NB_OF_VAR; VarIdx++) { - if ((*(__IO uint16_t*)(PAGE1_BASE_ADDRESS + 6)) == VirtAddVarTab[VarIdx]) - x = VarIdx; - - if (VarIdx != x) { - /* Read the last variables' updates */ - uint16_t ReadStatus = EE_ReadVariable(VirtAddVarTab[VarIdx], &DataVar); - /* In case variable corresponding to the virtual address was found */ - if (ReadStatus != 0x1) { - /* Transfer the variable to the Page1 */ - uint16_t EepromStatus = EE_VerifyPageFullWriteVariable(VirtAddVarTab[VarIdx], DataVar); - /* If program operation was failed, a Flash error code is returned */ - if (EepromStatus != HAL_OK) return EepromStatus; - } - } - } - /* Mark Page1 as valid */ - FlashStatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, PAGE1_BASE_ADDRESS, VALID_PAGE); - /* If program operation was failed, a Flash error code is returned */ - if (FlashStatus != HAL_OK) return FlashStatus; - pEraseInit.Sector = PAGE0_ID; - pEraseInit.NbSectors = 1; - pEraseInit.VoltageRange = VOLTAGE_RANGE; - /* Erase Page0 */ - if (!EE_VerifyPageFullyErased(PAGE0_BASE_ADDRESS)) { - /* As the last operation, simply return the result */ - return HAL_FLASHEx_Erase(&pEraseInit, &SectorError); - } - } - break; - - default: /* Any other state -> format eeprom */ - /* Erase both Page0 and Page1 and set Page0 as valid page */ - /* As the last operation, simply return the result */ - return EE_Format(); - } - - return HAL_OK; -} - -/** - * @brief Verify if specified page is fully erased. - * @param Address: page address - * This parameter can be one of the following values: - * @arg PAGE0_BASE_ADDRESS: Page0 base address - * @arg PAGE1_BASE_ADDRESS: Page1 base address - * @retval page fully erased status: - * - 0: if Page not erased - * - 1: if Page erased - */ -uint16_t EE_VerifyPageFullyErased(uint32_t Address) { - uint32_t ReadStatus = 1; - /* Check each active page address starting from end */ - while (Address <= PAGE0_END_ADDRESS) { - /* Get the current location content to be compared with virtual address */ - uint16_t AddressValue = (*(__IO uint16_t*)Address); - /* Compare the read address with the virtual address */ - if (AddressValue != ERASED) { - /* In case variable value is read, reset ReadStatus flag */ - ReadStatus = 0; - break; - } - /* Next address location */ - Address += 4; - } - /* Return ReadStatus value: (0: Page not erased, 1: Sector erased) */ - return ReadStatus; -} - -/** - * @brief Returns the last stored variable data, if found, which correspond to - * the passed virtual address - * @param VirtAddress: Variable virtual address - * @param Data: Global variable contains the read variable value - * @retval Success or error status: - * - 0: if variable was found - * - 1: if the variable was not found - * - NO_VALID_PAGE: if no valid page was found. - */ -uint16_t EE_ReadVariable(uint16_t VirtAddress, uint16_t* Data) { - uint16_t ReadStatus = 1; - - /* Get active Page for read operation */ - uint16_t ValidPage = EE_FindValidPage(READ_FROM_VALID_PAGE); - - /* Check if there is no valid page */ - if (ValidPage == NO_VALID_PAGE) return NO_VALID_PAGE; - - /* Get the valid Page start and end Addresses */ - uint32_t PageStartAddress = uint32_t(EEPROM_START_ADDRESS) + uint32_t(ValidPage * (PAGE_SIZE)), - Address = PageStartAddress + PAGE_SIZE - 2; - - /* Check each active page address starting from end */ - while (Address > PageStartAddress + 2) { - /* Get the current location content to be compared with virtual address */ - uint16_t AddressValue = (*(__IO uint16_t*)Address); - - /* Compare the read address with the virtual address */ - if (AddressValue == VirtAddress) { - /* Get content of Address-2 which is variable value */ - *Data = (*(__IO uint16_t*)(Address - 2)); - /* In case variable value is read, reset ReadStatus flag */ - ReadStatus = 0; - break; - } - else /* Next address location */ - Address -= 4; - } - /* Return ReadStatus value: (0: variable exist, 1: variable doesn't exist) */ - return ReadStatus; -} - -/** - * @brief Writes/upadtes variable data in EEPROM. - * @param VirtAddress: Variable virtual address - * @param Data: 16 bit data to be written - * @retval Success or error status: - * - FLASH_COMPLETE: on success - * - PAGE_FULL: if valid page is full - * - NO_VALID_PAGE: if no valid page was found - * - Flash error code: on write Flash error - */ -uint16_t EE_WriteVariable(uint16_t VirtAddress, uint16_t Data) { - /* Write the variable virtual address and value in the EEPROM */ - uint16_t Status = EE_VerifyPageFullWriteVariable(VirtAddress, Data); - - /* In case the EEPROM active page is full */ - if (Status == PAGE_FULL) /* Perform Page transfer */ - Status = EE_PageTransfer(VirtAddress, Data); - - /* Return last operation status */ - return Status; -} - -/** - * @brief Erases PAGE and PAGE1 and writes VALID_PAGE header to PAGE - * @param None - * @retval Status of the last operation (Flash write or erase) done during - * EEPROM formatting - */ -static HAL_StatusTypeDef EE_Format() { - FLASH_EraseInitTypeDef pEraseInit; - pEraseInit.TypeErase = FLASH_TYPEERASE_SECTORS; - pEraseInit.Sector = PAGE0_ID; - pEraseInit.NbSectors = 1; - pEraseInit.VoltageRange = VOLTAGE_RANGE; - - HAL_StatusTypeDef FlashStatus; // = HAL_OK - - /* Erase Page0 */ - if (!EE_VerifyPageFullyErased(PAGE0_BASE_ADDRESS)) { - uint32_t SectorError; - FlashStatus = HAL_FLASHEx_Erase(&pEraseInit, &SectorError); - /* If erase operation was failed, a Flash error code is returned */ - if (FlashStatus != HAL_OK) return FlashStatus; - } - /* Set Page0 as valid page: Write VALID_PAGE at Page0 base address */ - FlashStatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, PAGE0_BASE_ADDRESS, VALID_PAGE); - /* If program operation was failed, a Flash error code is returned */ - if (FlashStatus != HAL_OK) return FlashStatus; - - pEraseInit.Sector = PAGE1_ID; - /* Erase Page1 */ - if (!EE_VerifyPageFullyErased(PAGE1_BASE_ADDRESS)) { - /* As the last operation, just return the result code */ - uint32_t SectorError; - return HAL_FLASHEx_Erase(&pEraseInit, &SectorError); - } - - return HAL_OK; -} - -/** - * @brief Find valid Page for write or read operation - * @param Operation: operation to achieve on the valid page. - * This parameter can be one of the following values: - * @arg READ_FROM_VALID_PAGE: read operation from valid page - * @arg WRITE_IN_VALID_PAGE: write operation from valid page - * @retval Valid page number (PAGE or PAGE1) or NO_VALID_PAGE in case - * of no valid page was found - */ -static uint16_t EE_FindValidPage(uint8_t Operation) { - /* Get Page0 and Page1 actual status */ - uint16_t PageStatus0 = (*(__IO uint16_t*)PAGE0_BASE_ADDRESS), - PageStatus1 = (*(__IO uint16_t*)PAGE1_BASE_ADDRESS); - - /* Write or read operation */ - switch (Operation) { - case WRITE_IN_VALID_PAGE: /* ---- Write operation ---- */ - if (PageStatus1 == VALID_PAGE) { - /* Page0 receiving data */ - return (PageStatus0 == RECEIVE_DATA) ? PAGE0 : PAGE1; - } - else if (PageStatus0 == VALID_PAGE) { - /* Page1 receiving data */ - return (PageStatus1 == RECEIVE_DATA) ? PAGE1 : PAGE0; - } - else - return NO_VALID_PAGE; /* No valid Page */ - - case READ_FROM_VALID_PAGE: /* ---- Read operation ---- */ - if (PageStatus0 == VALID_PAGE) - return PAGE0; /* Page0 valid */ - else if (PageStatus1 == VALID_PAGE) - return PAGE1; /* Page1 valid */ - else - return NO_VALID_PAGE; /* No valid Page */ - - default: - return PAGE0; /* Page0 valid */ - } -} - -/** - * @brief Verify if active page is full and Writes variable in EEPROM. - * @param VirtAddress: 16 bit virtual address of the variable - * @param Data: 16 bit data to be written as variable value - * @retval Success or error status: - * - FLASH_COMPLETE: on success - * - PAGE_FULL: if valid page is full - * - NO_VALID_PAGE: if no valid page was found - * - Flash error code: on write Flash error - */ -static uint16_t EE_VerifyPageFullWriteVariable(uint16_t VirtAddress, uint16_t Data) { - /* Get valid Page for write operation */ - uint16_t ValidPage = EE_FindValidPage(WRITE_IN_VALID_PAGE); - - /* Check if there is no valid page */ - if (ValidPage == NO_VALID_PAGE) return NO_VALID_PAGE; - - /* Get the valid Page start and end Addresses */ - uint32_t Address = uint32_t(EEPROM_START_ADDRESS) + uint32_t(ValidPage * (PAGE_SIZE)), - PageEndAddress = Address + PAGE_SIZE - 1; - - /* Check each active page address starting from begining */ - while (Address < PageEndAddress) { - /* Verify if Address and Address+2 contents are 0xFFFFFFFF */ - if ((*(__IO uint32_t*)Address) == 0xFFFFFFFF) { - /* Set variable data */ - HAL_StatusTypeDef FlashStatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, Address, Data); - /* If program operation was failed, a Flash error code is returned */ - if (FlashStatus != HAL_OK) return FlashStatus; - /* Set variable virtual address, return status */ - return HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, Address + 2, VirtAddress); - } - else /* Next address location */ - Address += 4; - } - - /* Return PAGE_FULL in case the valid page is full */ - return PAGE_FULL; -} - -/** - * @brief Transfers last updated variables data from the full Page to - * an empty one. - * @param VirtAddress: 16 bit virtual address of the variable - * @param Data: 16 bit data to be written as variable value - * @retval Success or error status: - * - FLASH_COMPLETE: on success - * - PAGE_FULL: if valid page is full - * - NO_VALID_PAGE: if no valid page was found - * - Flash error code: on write Flash error - */ -static uint16_t EE_PageTransfer(uint16_t VirtAddress, uint16_t Data) { - /* Get active Page for read operation */ - uint16_t ValidPage = EE_FindValidPage(READ_FROM_VALID_PAGE); - uint32_t NewPageAddress = EEPROM_START_ADDRESS; - uint16_t OldPageId = 0; - - if (ValidPage == PAGE1) { /* Page1 valid */ - /* New page address where variable will be moved to */ - NewPageAddress = PAGE0_BASE_ADDRESS; - /* Old page ID where variable will be taken from */ - OldPageId = PAGE1_ID; - } - else if (ValidPage == PAGE0) { /* Page0 valid */ - /* New page address where variable will be moved to */ - NewPageAddress = PAGE1_BASE_ADDRESS; - /* Old page ID where variable will be taken from */ - OldPageId = PAGE0_ID; - } - else - return NO_VALID_PAGE; /* No valid Page */ - - /* Set the new Page status to RECEIVE_DATA status */ - HAL_StatusTypeDef FlashStatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, NewPageAddress, RECEIVE_DATA); - /* If program operation was failed, a Flash error code is returned */ - if (FlashStatus != HAL_OK) return FlashStatus; - - /* Write the variable passed as parameter in the new active page */ - uint16_t EepromStatus = EE_VerifyPageFullWriteVariable(VirtAddress, Data); - /* If program operation was failed, a Flash error code is returned */ - if (EepromStatus != HAL_OK) return EepromStatus; - - /* Transfer process: transfer variables from old to the new active page */ - for (uint16_t VarIdx = 0; VarIdx < NB_OF_VAR; VarIdx++) { - if (VirtAddVarTab[VarIdx] != VirtAddress) { /* Check each variable except the one passed as parameter */ - /* Read the other last variable updates */ - uint16_t ReadStatus = EE_ReadVariable(VirtAddVarTab[VarIdx], &DataVar); - /* In case variable corresponding to the virtual address was found */ - if (ReadStatus != 0x1) { - /* Transfer the variable to the new active page */ - EepromStatus = EE_VerifyPageFullWriteVariable(VirtAddVarTab[VarIdx], DataVar); - /* If program operation was failed, a Flash error code is returned */ - if (EepromStatus != HAL_OK) return EepromStatus; - } - } - } - - FLASH_EraseInitTypeDef pEraseInit; - pEraseInit.TypeErase = TYPEERASE_SECTORS; - pEraseInit.Sector = OldPageId; - pEraseInit.NbSectors = 1; - pEraseInit.VoltageRange = VOLTAGE_RANGE; - - /* Erase the old Page: Set old Page status to ERASED status */ - uint32_t SectorError; - FlashStatus = HAL_FLASHEx_Erase(&pEraseInit, &SectorError); - /* If erase operation was failed, a Flash error code is returned */ - if (FlashStatus != HAL_OK) return FlashStatus; - - /* Set new Page status to VALID_PAGE status */ - /* As the last operation, just return the result code */ - return HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, NewPageAddress, VALID_PAGE); -} - -#endif // FLASH_EEPROM_EMULATION -#endif // STM32GENERIC && (STM32F4 || STM32F7) - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Marlin/src/HAL/STM32_F4_F7/eeprom_emul.h b/Marlin/src/HAL/STM32_F4_F7/eeprom_emul.h deleted file mode 100644 index 84c4c6e3d253..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/eeprom_emul.h +++ /dev/null @@ -1,114 +0,0 @@ -/****************************************************************************** - * @file eeprom_emul.h - * @author MCD Application Team - * @version V1.2.6 - * @date 04-November-2016 - * @brief This file contains all the functions prototypes for the EEPROM - * emulation firmware library. - ****************************************************************************** - * @attention - * - * Copyright © 2016 STMicroelectronics International N.V. - * 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. Redistribution 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 other - * contributors to this software may be used to endorse or promote products - * derived from this software without specific written permission. - * 4. This software, including modifications and/or derivative works of this - * software, must execute solely and exclusively on microcontroller or - * microprocessor devices manufactured by or for STMicroelectronics. - * 5. Redistribution and use of this software other than as permitted under - * this license is void and will automatically terminate your rights under - * this license. - * - * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A - * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY - * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT - * SHALL STMICROELECTRONICS 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. - * - ******************************************************************************/ -#pragma once - -// ------------------------ -// Includes -// ------------------------ - -#include "../../inc/MarlinConfig.h" - -/* Exported constants --------------------------------------------------------*/ -/* EEPROM emulation firmware error codes */ -#define EE_OK uint32_t(HAL_OK) -#define EE_ERROR uint32_t(HAL_ERROR) -#define EE_BUSY uint32_t(HAL_BUSY) -#define EE_TIMEOUT uint32_t(HAL_TIMEOUT) - -/* Define the size of the sectors to be used */ -#define PAGE_SIZE uint32_t(0x4000) /* Page size = 16KByte */ - -/* Device voltage range supposed to be [2.7V to 3.6V], the operation will - be done by word */ -#define VOLTAGE_RANGE uint8_t(VOLTAGE_RANGE_3) - -/* EEPROM start address in Flash */ -#ifdef STM32F7 - #define EEPROM_START_ADDRESS uint32_t(0x08100000) /* EEPROM emulation start address: - from sector2 : after 16KByte of used - Flash memory */ -#else - #define EEPROM_START_ADDRESS uint32_t(0x08078000) /* EEPROM emulation start address: - after 480KByte of used Flash memory */ -#endif - -/* Pages 0 and 1 base and end addresses */ -#define PAGE0_BASE_ADDRESS uint32_t(EEPROM_START_ADDRESS + 0x0000) -#define PAGE0_END_ADDRESS uint32_t(EEPROM_START_ADDRESS + PAGE_SIZE - 1) -#define PAGE0_ID FLASH_SECTOR_1 - -#define PAGE1_BASE_ADDRESS uint32_t(EEPROM_START_ADDRESS + 0x4000) -#define PAGE1_END_ADDRESS uint32_t(EEPROM_START_ADDRESS + 2 * (PAGE_SIZE) - 1) -#define PAGE1_ID FLASH_SECTOR_2 - -/* Used Flash pages for EEPROM emulation */ -#define PAGE0 uint16_t(0x0000) -#define PAGE1 uint16_t(0x0001) /* Page nb between PAGE0_BASE_ADDRESS & PAGE1_BASE_ADDRESS*/ - -/* No valid page define */ -#define NO_VALID_PAGE uint16_t(0x00AB) - -/* Page status definitions */ -#define ERASED uint16_t(0xFFFF) /* Page is empty */ -#define RECEIVE_DATA uint16_t(0xEEEE) /* Page is marked to receive data */ -#define VALID_PAGE uint16_t(0x0000) /* Page containing valid data */ - -/* Valid pages in read and write defines */ -#define READ_FROM_VALID_PAGE uint8_t(0x00) -#define WRITE_IN_VALID_PAGE uint8_t(0x01) - -/* Page full define */ -#define PAGE_FULL uint8_t(0x80) - -/* Variables' number */ -#define NB_OF_VAR uint16_t(4096) - -/* Exported functions ------------------------------------------------------- */ -uint16_t EE_Initialize(); -uint16_t EE_ReadVariable(uint16_t VirtAddress, uint16_t* Data); -uint16_t EE_WriteVariable(uint16_t VirtAddress, uint16_t Data); - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Marlin/src/HAL/STM32_F4_F7/eeprom_flash.cpp b/Marlin/src/HAL/STM32_F4_F7/eeprom_flash.cpp deleted file mode 100644 index 00b808fd4824..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/eeprom_flash.cpp +++ /dev/null @@ -1,111 +0,0 @@ -/** - * Marlin 3D Printer Firmware - * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ -#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7)) - -#include "../../inc/MarlinConfig.h" - -#if ENABLED(FLASH_EEPROM_EMULATION) - -#include "../shared/eeprom_api.h" -#include "eeprom_emul.h" - -// FLASH_FLAG_PGSERR (Programming Sequence Error) was renamed to -// FLASH_FLAG_ERSERR (Erasing Sequence Error) in STM32F4/7 - -#ifdef STM32F7 - #define FLASH_FLAG_PGSERR FLASH_FLAG_ERSERR -#else - //#define FLASH_FLAG_PGSERR FLASH_FLAG_ERSERR -#endif - -void ee_write_byte(uint8_t *pos, unsigned char value) { - HAL_FLASH_Unlock(); - __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR |FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR); - - const unsigned eeprom_address = (unsigned)pos; - if (EE_WriteVariable(eeprom_address, uint16_t(value)) != EE_OK) - for (;;) HAL_Delay(1); // Spin forever until watchdog reset - - HAL_FLASH_Lock(); -} - -uint8_t ee_read_byte(uint8_t *pos) { - uint16_t data = 0xFF; - const unsigned eeprom_address = (unsigned)pos; - (void)EE_ReadVariable(eeprom_address, &data); // Data unchanged on error - return uint8_t(data); -} - -#ifndef MARLIN_EEPROM_SIZE - #error "MARLIN_EEPROM_SIZE is required for Flash-based EEPROM." -#endif -size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } - -bool PersistentStore::access_finish() { return true; } - -bool PersistentStore::access_start() { - static bool ee_initialized = false; - if (!ee_initialized) { - HAL_FLASH_Unlock(); - - __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR |FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR); - - /* EEPROM Init */ - if (EE_Initialize() != EE_OK) - for (;;) HAL_Delay(1); // Spin forever until watchdog reset - - HAL_FLASH_Lock(); - ee_initialized = true; - } - return true; -} - -bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { - while (size--) { - uint8_t * const p = (uint8_t * const)pos; - uint8_t v = *value; - // EEPROM has only ~100,000 write cycles, - // so only write bytes that have changed! - if (v != ee_read_byte(p)) { - ee_write_byte(p, v); - if (ee_read_byte(p) != v) { - SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); - return true; - } - } - crc16(crc, &v, 1); - pos++; - value++; - } - return false; -} - -bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { - do { - uint8_t c = ee_read_byte((uint8_t*)pos); - if (writing) *value = c; - crc16(crc, &c, 1); - pos++; - value++; - } while (--size); - return false; -} - -#endif // FLASH_EEPROM_EMULATION -#endif // STM32GENERIC && (STM32F4 || STM32F7) diff --git a/Marlin/src/HAL/STM32_F4_F7/eeprom_wired.cpp b/Marlin/src/HAL/STM32_F4_F7/eeprom_wired.cpp deleted file mode 100644 index c0d82dbd0754..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/eeprom_wired.cpp +++ /dev/null @@ -1,77 +0,0 @@ -/** - * 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 - * - * 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 . - * - */ -#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7)) - -#include "../../inc/MarlinConfig.h" - -#if USE_WIRED_EEPROM - -/** - * PersistentStore for Arduino-style EEPROM interface - * with simple implementations supplied by Marlin. - */ - -#include "../shared/eeprom_if.h" -#include "../shared/eeprom_api.h" - -#ifndef MARLIN_EEPROM_SIZE - #error "MARLIN_EEPROM_SIZE is required for I2C / SPI EEPROM." -#endif -size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } - -bool PersistentStore::access_start() { eeprom_init(); return true; } -bool PersistentStore::access_finish() { return true; } - -bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { - while (size--) { - uint8_t * const p = (uint8_t * const)pos; - uint8_t v = *value; - // EEPROM has only ~100,000 write cycles, - // so only write bytes that have changed! - if (v != eeprom_read_byte(p)) { - eeprom_write_byte(p, v); - if (eeprom_read_byte(p) != v) { - SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); - return true; - } - } - crc16(crc, &v, 1); - pos++; - value++; - } - return false; -} - -bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { - do { - uint8_t c = eeprom_read_byte((uint8_t*)pos); - if (writing) *value = c; - crc16(crc, &c, 1); - pos++; - value++; - } while (--size); - return false; -} - -#endif // USE_WIRED_EEPROM -#endif // STM32GENERIC && (STM32F4 || STM32F7) diff --git a/Marlin/src/HAL/STM32_F4_F7/endstop_interrupts.h b/Marlin/src/HAL/STM32_F4_F7/endstop_interrupts.h deleted file mode 100644 index fdff8cc644cd..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/endstop_interrupts.h +++ /dev/null @@ -1,49 +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 - * 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 - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ -#pragma once - -#include "../../module/endstops.h" - -// One ISR for all EXT-Interrupts -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_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); -} diff --git a/Marlin/src/HAL/STM32_F4_F7/fastio.h b/Marlin/src/HAL/STM32_F4_F7/fastio.h deleted file mode 100644 index f42be5835433..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/fastio.h +++ /dev/null @@ -1,310 +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 - * 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 - * 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 - -/** - * Fast I/O interfaces for STM32F4/7 - * These use GPIO functions instead of Direct Port Manipulation, as on AVR. - */ - -#ifndef PWM - #define PWM OUTPUT -#endif - -#define READ(IO) digitalRead(IO) -#define WRITE(IO,V) digitalWrite(IO,V) - -#define _GET_MODE(IO) -#define _SET_MODE(IO,M) pinMode(IO, M) -#define _SET_OUTPUT(IO) pinMode(IO, OUTPUT) /*!< Output Push Pull Mode & GPIO_NOPULL */ - -#define OUT_WRITE(IO,V) do{ _SET_OUTPUT(IO); WRITE(IO,V); }while(0) - -#define SET_INPUT(IO) _SET_MODE(IO, INPUT) /*!< Input Floating Mode */ -#define SET_INPUT_PULLUP(IO) _SET_MODE(IO, INPUT_PULLUP) /*!< Input with Pull-up activation */ -#define SET_INPUT_PULLDOWN(IO) _SET_MODE(IO, INPUT_PULLDOWN) /*!< Input with Pull-down activation */ -#define SET_OUTPUT(IO) OUT_WRITE(IO, LOW) -#define SET_PWM(IO) _SET_MODE(IO, PWM) - -#define TOGGLE(IO) OUT_WRITE(IO, !READ(IO)) - -#define IS_INPUT(IO) -#define IS_OUTPUT(IO) - -#define PWM_PIN(P) true - -// digitalRead/Write wrappers -#define extDigitalRead(IO) digitalRead(IO) -#define extDigitalWrite(IO,V) digitalWrite(IO,V) - -// -// Pins Definitions -// -#define PORTA 0 -#define PORTB 1 -#define PORTC 2 -#define PORTD 3 -#define PORTE 4 -#define PORTF 5 -#define PORTG 6 - -#define _STM32_PIN(P,PN) ((PORT##P * 16) + PN) - -#undef PA0 -#define PA0 _STM32_PIN(A, 0) -#undef PA1 -#define PA1 _STM32_PIN(A, 1) -#undef PA2 -#define PA2 _STM32_PIN(A, 2) -#undef PA3 -#define PA3 _STM32_PIN(A, 3) -#undef PA4 -#define PA4 _STM32_PIN(A, 4) -#undef PA5 -#define PA5 _STM32_PIN(A, 5) -#undef PA6 -#define PA6 _STM32_PIN(A, 6) -#undef PA7 -#define PA7 _STM32_PIN(A, 7) -#undef PA8 -#define PA8 _STM32_PIN(A, 8) -#undef PA9 -#define PA9 _STM32_PIN(A, 9) -#undef PA10 -#define PA10 _STM32_PIN(A, 10) -#undef PA11 -#define PA11 _STM32_PIN(A, 11) -#undef PA12 -#define PA12 _STM32_PIN(A, 12) -#undef PA13 -#define PA13 _STM32_PIN(A, 13) -#undef PA14 -#define PA14 _STM32_PIN(A, 14) -#undef PA15 -#define PA15 _STM32_PIN(A, 15) - -#undef PB0 -#define PB0 _STM32_PIN(B, 0) -#undef PB1 -#define PB1 _STM32_PIN(B, 1) -#undef PB2 -#define PB2 _STM32_PIN(B, 2) -#undef PB3 -#define PB3 _STM32_PIN(B, 3) -#undef PB4 -#define PB4 _STM32_PIN(B, 4) -#undef PB5 -#define PB5 _STM32_PIN(B, 5) -#undef PB6 -#define PB6 _STM32_PIN(B, 6) -#undef PB7 -#define PB7 _STM32_PIN(B, 7) -#undef PB8 -#define PB8 _STM32_PIN(B, 8) -#undef PB9 -#define PB9 _STM32_PIN(B, 9) -#undef PB10 -#define PB10 _STM32_PIN(B, 10) -#undef PB11 -#define PB11 _STM32_PIN(B, 11) -#undef PB12 -#define PB12 _STM32_PIN(B, 12) -#undef PB13 -#define PB13 _STM32_PIN(B, 13) -#undef PB14 -#define PB14 _STM32_PIN(B, 14) -#undef PB15 -#define PB15 _STM32_PIN(B, 15) - -#undef PC0 -#define PC0 _STM32_PIN(C, 0) -#undef PC1 -#define PC1 _STM32_PIN(C, 1) -#undef PC2 -#define PC2 _STM32_PIN(C, 2) -#undef PC3 -#define PC3 _STM32_PIN(C, 3) -#undef PC4 -#define PC4 _STM32_PIN(C, 4) -#undef PC5 -#define PC5 _STM32_PIN(C, 5) -#undef PC6 -#define PC6 _STM32_PIN(C, 6) -#undef PC7 -#define PC7 _STM32_PIN(C, 7) -#undef PC8 -#define PC8 _STM32_PIN(C, 8) -#undef PC9 -#define PC9 _STM32_PIN(C, 9) -#undef PC10 -#define PC10 _STM32_PIN(C, 10) -#undef PC11 -#define PC11 _STM32_PIN(C, 11) -#undef PC12 -#define PC12 _STM32_PIN(C, 12) -#undef PC13 -#define PC13 _STM32_PIN(C, 13) -#undef PC14 -#define PC14 _STM32_PIN(C, 14) -#undef PC15 -#define PC15 _STM32_PIN(C, 15) - -#undef PD0 -#define PD0 _STM32_PIN(D, 0) -#undef PD1 -#define PD1 _STM32_PIN(D, 1) -#undef PD2 -#define PD2 _STM32_PIN(D, 2) -#undef PD3 -#define PD3 _STM32_PIN(D, 3) -#undef PD4 -#define PD4 _STM32_PIN(D, 4) -#undef PD5 -#define PD5 _STM32_PIN(D, 5) -#undef PD6 -#define PD6 _STM32_PIN(D, 6) -#undef PD7 -#define PD7 _STM32_PIN(D, 7) -#undef PD8 -#define PD8 _STM32_PIN(D, 8) -#undef PD9 -#define PD9 _STM32_PIN(D, 9) -#undef PD10 -#define PD10 _STM32_PIN(D, 10) -#undef PD11 -#define PD11 _STM32_PIN(D, 11) -#undef PD12 -#define PD12 _STM32_PIN(D, 12) -#undef PD13 -#define PD13 _STM32_PIN(D, 13) -#undef PD14 -#define PD14 _STM32_PIN(D, 14) -#undef PD15 -#define PD15 _STM32_PIN(D, 15) - -#undef PE0 -#define PE0 _STM32_PIN(E, 0) -#undef PE1 -#define PE1 _STM32_PIN(E, 1) -#undef PE2 -#define PE2 _STM32_PIN(E, 2) -#undef PE3 -#define PE3 _STM32_PIN(E, 3) -#undef PE4 -#define PE4 _STM32_PIN(E, 4) -#undef PE5 -#define PE5 _STM32_PIN(E, 5) -#undef PE6 -#define PE6 _STM32_PIN(E, 6) -#undef PE7 -#define PE7 _STM32_PIN(E, 7) -#undef PE8 -#define PE8 _STM32_PIN(E, 8) -#undef PE9 -#define PE9 _STM32_PIN(E, 9) -#undef PE10 -#define PE10 _STM32_PIN(E, 10) -#undef PE11 -#define PE11 _STM32_PIN(E, 11) -#undef PE12 -#define PE12 _STM32_PIN(E, 12) -#undef PE13 -#define PE13 _STM32_PIN(E, 13) -#undef PE14 -#define PE14 _STM32_PIN(E, 14) -#undef PE15 -#define PE15 _STM32_PIN(E, 15) - -#ifdef STM32F7 - - #undef PORTF - #define PORTF 5 - #undef PF0 - #define PF0 _STM32_PIN(F, 0) - #undef PF1 - #define PF1 _STM32_PIN(F, 1) - #undef PF2 - #define PF2 _STM32_PIN(F, 2) - #undef PF3 - #define PF3 _STM32_PIN(F, 3) - #undef PF4 - #define PF4 _STM32_PIN(F, 4) - #undef PF5 - #define PF5 _STM32_PIN(F, 5) - #undef PF6 - #define PF6 _STM32_PIN(F, 6) - #undef PF7 - #define PF7 _STM32_PIN(F, 7) - #undef PF8 - #define PF8 _STM32_PIN(F, 8) - #undef PF9 - #define PF9 _STM32_PIN(F, 9) - #undef PF10 - #define PF10 _STM32_PIN(F, 10) - #undef PF11 - #define PF11 _STM32_PIN(F, 11) - #undef PF12 - #define PF12 _STM32_PIN(F, 12) - #undef PF13 - #define PF13 _STM32_PIN(F, 13) - #undef PF14 - #define PF14 _STM32_PIN(F, 14) - #undef PF15 - #define PF15 _STM32_PIN(F, 15) - - #undef PORTG - #define PORTG 6 - #undef PG0 - #define PG0 _STM32_PIN(G, 0) - #undef PG1 - #define PG1 _STM32_PIN(G, 1) - #undef PG2 - #define PG2 _STM32_PIN(G, 2) - #undef PG3 - #define PG3 _STM32_PIN(G, 3) - #undef PG4 - #define PG4 _STM32_PIN(G, 4) - #undef PG5 - #define PG5 _STM32_PIN(G, 5) - #undef PG6 - #define PG6 _STM32_PIN(G, 6) - #undef PG7 - #define PG7 _STM32_PIN(G, 7) - #undef PG8 - #define PG8 _STM32_PIN(G, 8) - #undef PG9 - #define PG9 _STM32_PIN(G, 9) - #undef PG10 - #define PG10 _STM32_PIN(G, 10) - #undef PG11 - #define PG11 _STM32_PIN(G, 11) - #undef PG12 - #define PG12 _STM32_PIN(G, 12) - #undef PG13 - #define PG13 _STM32_PIN(G, 13) - #undef PG14 - #define PG14 _STM32_PIN(G, 14) - #undef PG15 - #define PG15 _STM32_PIN(G, 15) - -#endif // STM32GENERIC && STM32F7 diff --git a/Marlin/src/HAL/STM32_F4_F7/inc/SanityCheck.h b/Marlin/src/HAL/STM32_F4_F7/inc/SanityCheck.h deleted file mode 100644 index 9bb36f3bbbca..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/inc/SanityCheck.h +++ /dev/null @@ -1,41 +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 - -/** - * Test STM32F4/7-specific configuration values for errors at compile-time. - */ -//#if ENABLED(SPINDLE_LASER_PWM) && !(SPINDLE_LASER_PWM_PIN == 4 || SPINDLE_LASER_PWM_PIN == 6 || SPINDLE_LASER_PWM_PIN == 11) -// #error "SPINDLE_LASER_PWM_PIN must use SERVO0, SERVO1 or SERVO3 connector" -//#endif - -#if ENABLED(EMERGENCY_PARSER) - #error "EMERGENCY_PARSER is not yet implemented for STM32F4/7. Disable EMERGENCY_PARSER to continue." -#endif - -#if ENABLED(FAST_PWM_FAN) || SPINDLE_LASER_FREQUENCY - #error "Features requiring Hardware PWM (FAST_PWM_FAN, SPINDLE_LASER_FREQUENCY) are not yet supported on STM32F4/F7." -#endif - -#if HAS_TMC_SW_SERIAL - #error "TMC220x Software Serial is not supported on this platform." -#endif diff --git a/Marlin/src/HAL/STM32_F4_F7/pinsDebug.h b/Marlin/src/HAL/STM32_F4_F7/pinsDebug.h deleted file mode 100644 index 973abb1b0185..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/pinsDebug.h +++ /dev/null @@ -1,27 +0,0 @@ -/** - * Marlin 3D Printer Firmware - * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ -#pragma once - -#ifdef NUM_DIGITAL_PINS // Only in ST's Arduino core (STM32duino, STM32Core) - #include "../STM32/pinsDebug_STM32duino.h" -#elif defined(BOARD_NR_GPIO_PINS) // Only in STM32GENERIC (Maple) - #include "../STM32/pinsDebug_STM32GENERIC.h" -#else - #error "M43 Pins Debugging not supported for this board." -#endif diff --git a/Marlin/src/HAL/STM32_F4_F7/spi_pins.h b/Marlin/src/HAL/STM32_F4_F7/spi_pins.h deleted file mode 100644 index 75a6a2b250f6..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/spi_pins.h +++ /dev/null @@ -1,35 +0,0 @@ -/** - * Marlin 3D Printer Firmware - * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ -#pragma once - -/** - * Define SPI Pins: SCK, MISO, MOSI, SS - */ -#ifndef SCK_PIN - #define SCK_PIN PA5 -#endif -#ifndef MISO_PIN - #define MISO_PIN PA6 -#endif -#ifndef MOSI_PIN - #define MOSI_PIN PA7 -#endif -#ifndef SS_PIN - #define SS_PIN PA8 -#endif diff --git a/Marlin/src/HAL/STM32_F4_F7/timers.h b/Marlin/src/HAL/STM32_F4_F7/timers.h deleted file mode 100644 index 4e8c81783e59..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/timers.h +++ /dev/null @@ -1,28 +0,0 @@ -/** - * 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 - * - * 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 - -#ifdef STM32F4 - #include "STM32F4/timers.h" -#else - #include "STM32F7/timers.h" -#endif diff --git a/Marlin/src/HAL/STM32_F4_F7/watchdog.cpp b/Marlin/src/HAL/STM32_F4_F7/watchdog.cpp deleted file mode 100644 index cb12ec7aac3c..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/watchdog.cpp +++ /dev/null @@ -1,55 +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 . - * - */ -#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7)) - -#include "../../inc/MarlinConfig.h" - -#if ENABLED(USE_WATCHDOG) - - #include "watchdog.h" - - IWDG_HandleTypeDef hiwdg; - - void watchdog_init() { - hiwdg.Instance = IWDG; - hiwdg.Init.Prescaler = IWDG_PRESCALER_32; //32kHz LSI clock and 32x prescalar = 1024Hz IWDG clock - hiwdg.Init.Reload = 4095; //4095 counts = 4 seconds at 1024Hz - if (HAL_IWDG_Init(&hiwdg) != HAL_OK) { - //Error_Handler(); - } - else { - #if PIN_EXISTS(LED) && DISABLED(PINS_DEBUGGING) - TOGGLE(LED_PIN); // heartbeat indicator - #endif - } - } - - void HAL_watchdog_refresh() { - /* Refresh IWDG: reload counter */ - if (HAL_IWDG_Refresh(&hiwdg) != HAL_OK) { - /* Refresh Error */ - //Error_Handler(); - } - } - -#endif // USE_WATCHDOG -#endif // STM32GENERIC && (STM32F4 || STM32F7) diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.cpp b/Marlin/src/HAL/TEENSY31_32/HAL.cpp index 8c3dd8337740..f08cf799e9e8 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL.cpp +++ b/Marlin/src/HAL/TEENSY31_32/HAL.cpp @@ -31,6 +31,15 @@ #include +#define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X) +#define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X) +#if WITHIN(SERIAL_PORT, 0, 3) + IMPLEMENT_SERIAL(SERIAL_PORT); +#else + #error "SERIAL_PORT must be from 0 to 3." +#endif +USBSerialType USBSerial(false, SerialUSB); + uint16_t HAL_adc_result; static const uint8_t pin2sc1a[] = { @@ -69,6 +78,8 @@ uint8_t HAL_get_reset_source() { return 0; } +void HAL_reboot() { _reboot_Teensyduino_(); } + extern "C" { extern char __bss_end; extern char __heap_start; diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.h b/Marlin/src/HAL/TEENSY31_32/HAL.h index 8ab358e9e1e5..8baa7936f5f8 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL.h +++ b/Marlin/src/HAL/TEENSY31_32/HAL.h @@ -34,7 +34,6 @@ #include "fastio.h" #include "watchdog.h" - #include #define ST7920_DELAY_1 DELAY_NS(600) @@ -50,14 +49,27 @@ #define IS_TEENSY32 1 #endif -#define _MSERIAL(X) Serial##X -#define MSERIAL(X) _MSERIAL(X) +#include "../../core/serial_hook.h" + #define Serial0 Serial +#define _DECLARE_SERIAL(X) \ + typedef ForwardSerial1Class DefaultSerial##X; \ + extern DefaultSerial##X MSerial##X +#define DECLARE_SERIAL(X) _DECLARE_SERIAL(X) + +typedef ForwardSerial1Class USBSerialType; +extern USBSerialType USBSerial; + +#define _MSERIAL(X) MSerial##X +#define MSERIAL(X) _MSERIAL(X) #if SERIAL_PORT == -1 - #define MYSERIAL0 SerialUSB + #define MYSERIAL1 USBSerial #elif WITHIN(SERIAL_PORT, 0, 3) - #define MYSERIAL0 MSERIAL(SERIAL_PORT) + DECLARE_SERIAL(SERIAL_PORT); + #define MYSERIAL1 MSERIAL(SERIAL_PORT) +#else + #error "The required SERIAL_PORT must be from 0 to 3, or -1 for Native USB." #endif #define HAL_SERVO_LIB libServo @@ -74,17 +86,6 @@ typedef int8_t pin_t; #define ENABLE_ISRS() __enable_irq() #define DISABLE_ISRS() __disable_irq() -#ifndef strncpy_P - #define strncpy_P(dest, src, num) strncpy((dest), (src), (num)) -#endif - -// Fix bug in pgm_read_ptr -#undef pgm_read_ptr -#define pgm_read_ptr(addr) (*((void**)(addr))) -// Add type-checking to pgm_read_word -#undef pgm_read_word -#define pgm_read_word(addr) (*((uint16_t*)(addr))) - inline void HAL_init() {} // Clear the reset reason @@ -93,16 +94,20 @@ void HAL_clear_reset_source(); // Get the reason for the reset uint8_t HAL_get_reset_source(); -inline void HAL_reboot() {} // reboot the board or restart the bootloader +void HAL_reboot(); FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); } -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-function" -extern "C" { - int freeMemory(); -} -#pragma GCC diagnostic pop +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + +extern "C" int freeMemory(); + +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic pop +#endif // ADC diff --git a/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp index cdb3f4701c03..ff84e91f79d7 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp +++ b/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp @@ -21,11 +21,12 @@ */ #ifdef __MK20DX256__ +#include "../../inc/MarlinConfig.h" #include "HAL.h" + #include #include #include "spi_pins.h" -#include "../../core/macros.h" static SPISettings spiConfig; @@ -35,18 +36,18 @@ static SPISettings spiConfig; // Initialize SPI bus void spiBegin() { - #if !PIN_EXISTS(SS) - #error "SS_PIN not defined!" + #if !PIN_EXISTS(SD_SS) + #error "SD_SS_PIN not defined!" #endif - OUT_WRITE(SS_PIN, HIGH); - SET_OUTPUT(SCK_PIN); - SET_INPUT(MISO_PIN); - SET_OUTPUT(MOSI_PIN); + OUT_WRITE(SD_SS_PIN, HIGH); + SET_OUTPUT(SD_SCK_PIN); + SET_INPUT(SD_MISO_PIN); + SET_OUTPUT(SD_MOSI_PIN); #if 0 && DISABLED(SOFTWARE_SPI) // set SS high - may be chip select for another SPI device #if SET_SPI_SS_HIGH - WRITE(SS_PIN, HIGH); + WRITE(SD_SS_PIN, HIGH); #endif // set a default rate spiInit(SPI_HALF_SPEED); // 1 @@ -64,7 +65,7 @@ void spiInit(uint8_t spiRate) { case SPI_EIGHTH_SPEED: clock = 1250000; break; case SPI_SPEED_5: clock = 625000; break; case SPI_SPEED_6: clock = 312500; break; - default: clock = 4000000; // Default from the SPI libarary + default: clock = 4000000; // Default from the SPI library } spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0); SPI.begin(); @@ -82,7 +83,7 @@ uint8_t spiRec() { } // SPI read data -void spiRead(uint8_t* buf, uint16_t nbyte) { +void spiRead(uint8_t *buf, uint16_t nbyte) { SPI.beginTransaction(spiConfig); SPI.transfer(buf, nbyte); SPI.endTransaction(); @@ -107,7 +108,7 @@ void spiSend(uint8_t b) { } // SPI send block -void spiSendBlock(uint8_t token, const uint8_t* buf) { +void spiSendBlock(uint8_t token, const uint8_t *buf) { SPI.beginTransaction(spiConfig); SPDR = token; for (uint16_t i = 0; i < 512; i += 2) { diff --git a/Marlin/src/HAL/TEENSY31_32/eeprom.cpp b/Marlin/src/HAL/TEENSY31_32/eeprom.cpp index cc5c56f7d550..85febebebc25 100644 --- a/Marlin/src/HAL/TEENSY31_32/eeprom.cpp +++ b/Marlin/src/HAL/TEENSY31_32/eeprom.cpp @@ -18,14 +18,14 @@ */ #ifdef __MK20DX256__ -#include "../../inc/MarlinConfig.h" - -#if USE_WIRED_EEPROM - /** * HAL PersistentStore for Teensy 3.2 (MK20DX256) */ +#include "../../inc/MarlinConfig.h" + +#if USE_WIRED_EEPROM + #include "../shared/eeprom_api.h" #include @@ -38,13 +38,13 @@ bool PersistentStore::access_start() { return true; } bool PersistentStore::access_finish() { return true; } bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + uint16_t written = 0; while (size--) { uint8_t * const p = (uint8_t * const)pos; uint8_t v = *value; - // EEPROM has only ~100,000 write cycles, - // so only write bytes that have changed! - if (v != eeprom_read_byte(p)) { + if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed! eeprom_write_byte(p, v); + if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes if (eeprom_read_byte(p) != v) { SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); return true; @@ -57,7 +57,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui return false; } -bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { +bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { do { uint8_t c = eeprom_read_byte((uint8_t*)pos); if (writing) *value = c; diff --git a/Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h b/Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h index 999ada512761..9c7e2104882e 100644 --- a/Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h +++ b/Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h @@ -64,4 +64,10 @@ void setup_endstop_interrupts() { TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); TERN_(HAS_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)); } diff --git a/Marlin/src/HAL/TEENSY31_32/fastio.h b/Marlin/src/HAL/TEENSY31_32/fastio.h index 9a299de9c763..622799ec8cac 100644 --- a/Marlin/src/HAL/TEENSY31_32/fastio.h +++ b/Marlin/src/HAL/TEENSY31_32/fastio.h @@ -28,7 +28,7 @@ */ #ifndef MASK - #define MASK(PIN) (1 << PIN) + #define MASK(PIN) _BV(PIN) #endif #define GPIO_BITBAND_ADDR(reg, bit) (((uint32_t)&(reg) - 0x40000000) * 32 + (bit) * 4 + 0x42000000) diff --git a/Marlin/src/HAL/TEENSY31_32/inc/SanityCheck.h b/Marlin/src/HAL/TEENSY31_32/inc/SanityCheck.h index 3932ee6a76c1..1efa76b1e9df 100644 --- a/Marlin/src/HAL/TEENSY31_32/inc/SanityCheck.h +++ b/Marlin/src/HAL/TEENSY31_32/inc/SanityCheck.h @@ -34,5 +34,9 @@ #endif #if HAS_TMC_SW_SERIAL - #error "TMC220x Software Serial is not supported on this platform." + #error "TMC220x Software Serial is not supported on Teensy 3.1/3.2." +#endif + +#if ENABLED(POSTMORTEM_DEBUGGING) + #error "POSTMORTEM_DEBUGGING is not yet supported on Teensy 3.1/3.2." #endif diff --git a/Marlin/src/HAL/TEENSY31_32/spi_pins.h b/Marlin/src/HAL/TEENSY31_32/spi_pins.h index 5754fbfeed11..6d0d05f85a5d 100644 --- a/Marlin/src/HAL/TEENSY31_32/spi_pins.h +++ b/Marlin/src/HAL/TEENSY31_32/spi_pins.h @@ -21,7 +21,7 @@ */ #pragma once -#define SCK_PIN 13 -#define MISO_PIN 12 -#define MOSI_PIN 11 -#define SS_PIN 20 //SDSS // A.28, A.29, B.21, C.26, C.29 +#define SD_SCK_PIN 13 +#define SD_MISO_PIN 12 +#define SD_MOSI_PIN 11 +#define SD_SS_PIN 20 // SDSS // A.28, A.29, B.21, C.26, C.29 diff --git a/Marlin/src/HAL/TEENSY31_32/timers.h b/Marlin/src/HAL/TEENSY31_32/timers.h index 135b32883084..61b86735967e 100644 --- a/Marlin/src/HAL/TEENSY31_32/timers.h +++ b/Marlin/src/HAL/TEENSY31_32/timers.h @@ -74,10 +74,10 @@ typedef uint32_t hal_timer_t; #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM) #ifndef HAL_STEP_TIMER_ISR - #define HAL_STEP_TIMER_ISR() extern "C" void ftm0_isr() //void TC3_Handler() + #define HAL_STEP_TIMER_ISR() extern "C" void ftm0_isr() //void TC3_Handler() #endif #ifndef HAL_TEMP_TIMER_ISR - #define HAL_TEMP_TIMER_ISR() extern "C" void ftm1_isr() //void TC4_Handler() + #define HAL_TEMP_TIMER_ISR() extern "C" void ftm1_isr() //void TC4_Handler() #endif void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency); diff --git a/Marlin/src/HAL/TEENSY31_32/watchdog.cpp b/Marlin/src/HAL/TEENSY31_32/watchdog.cpp index 9f7b70d9f961..5e21236129db 100644 --- a/Marlin/src/HAL/TEENSY31_32/watchdog.cpp +++ b/Marlin/src/HAL/TEENSY31_32/watchdog.cpp @@ -27,9 +27,11 @@ #include "watchdog.h" +#define WDT_TIMEOUT_MS TERN(WATCHDOG_DURATION_8S, 8000, 4000) // 4 or 8 second timeout + void watchdog_init() { WDOG_TOVALH = 0; - WDOG_TOVALL = 4000; + WDOG_TOVALL = WDT_TIMEOUT_MS; WDOG_STCTRLH = WDOG_STCTRLH_WDOGEN; } diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.cpp b/Marlin/src/HAL/TEENSY35_36/HAL.cpp index 92907353b833..046c00b56ed5 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL.cpp +++ b/Marlin/src/HAL/TEENSY35_36/HAL.cpp @@ -31,6 +31,14 @@ #include +#define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X) +#define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X) +#if WITHIN(SERIAL_PORT, 0, 3) + IMPLEMENT_SERIAL(SERIAL_PORT); +#endif + +USBSerialType USBSerial(false, SerialUSB); + uint16_t HAL_adc_result, HAL_adc_select; static const uint8_t pin2sc1a[] = { @@ -78,6 +86,8 @@ uint8_t HAL_get_reset_source() { return 0; } +void HAL_reboot() { _reboot_Teensyduino_(); } + extern "C" { extern char __bss_end; extern char __heap_start; diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.h b/Marlin/src/HAL/TEENSY35_36/HAL.h index 2b735d6224f4..26c35223bd48 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL.h +++ b/Marlin/src/HAL/TEENSY35_36/HAL.h @@ -53,14 +53,27 @@ #define IS_TEENSY35 1 #endif -#define _MSERIAL(X) Serial##X -#define MSERIAL(X) _MSERIAL(X) +#include "../../core/serial_hook.h" + #define Serial0 Serial +#define _DECLARE_SERIAL(X) \ + typedef ForwardSerial1Class DefaultSerial##X; \ + extern DefaultSerial##X MSerial##X +#define DECLARE_SERIAL(X) _DECLARE_SERIAL(X) + +typedef ForwardSerial1Class USBSerialType; +extern USBSerialType USBSerial; + +#define _MSERIAL(X) MSerial##X +#define MSERIAL(X) _MSERIAL(X) #if SERIAL_PORT == -1 - #define MYSERIAL0 SerialUSB + #define MYSERIAL1 USBSerial #elif WITHIN(SERIAL_PORT, 0, 3) - #define MYSERIAL0 MSERIAL(SERIAL_PORT) + #define MYSERIAL1 MSERIAL(SERIAL_PORT) + DECLARE_SERIAL(SERIAL_PORT); +#else + #error "SERIAL_PORT must be from 0 to 3, or -1 for Native USB." #endif #define HAL_SERVO_LIB libServo @@ -80,17 +93,6 @@ typedef int8_t pin_t; #undef sq #define sq(x) ((x)*(x)) -#ifndef strncpy_P - #define strncpy_P(dest, src, num) strncpy((dest), (src), (num)) -#endif - -// Fix bug in pgm_read_ptr -#undef pgm_read_ptr -#define pgm_read_ptr(addr) (*((void**)(addr))) -// Add type-checking to pgm_read_word -#undef pgm_read_word -#define pgm_read_word(addr) (*((uint16_t*)(addr))) - inline void HAL_init() {} // Clear reset reason @@ -99,16 +101,20 @@ void HAL_clear_reset_source(); // Reset reason uint8_t HAL_get_reset_source(); -inline void HAL_reboot() {} // reboot the board or restart the bootloader +void HAL_reboot(); FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); } -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-function" -extern "C" { - int freeMemory(); -} -#pragma GCC diagnostic pop +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + +extern "C" int freeMemory(); + +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic pop +#endif // ADC diff --git a/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp index b36900a32195..e63ab1c0e3ed 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp +++ b/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp @@ -26,27 +26,28 @@ #if defined(__MK64FX512__) || defined(__MK66FX1M0__) +#include "../../inc/MarlinConfig.h" #include "HAL.h" + #include #include #include "spi_pins.h" -#include "../../core/macros.h" static SPISettings spiConfig; void spiBegin() { - #if !PIN_EXISTS(SS) - #error "SS_PIN not defined!" + #if !PIN_EXISTS(SD_SS) + #error "SD_SS_PIN not defined!" #endif - OUT_WRITE(SS_PIN, HIGH); - SET_OUTPUT(SCK_PIN); - SET_INPUT(MISO_PIN); - SET_OUTPUT(MOSI_PIN); + OUT_WRITE(SD_SS_PIN, HIGH); + SET_OUTPUT(SD_SCK_PIN); + SET_INPUT(SD_MISO_PIN); + SET_OUTPUT(SD_MOSI_PIN); #if 0 && DISABLED(SOFTWARE_SPI) // set SS high - may be chip select for another SPI device #if SET_SPI_SS_HIGH - WRITE(SS_PIN, HIGH); + WRITE(SD_SS_PIN, HIGH); #endif // set a default rate spiInit(SPI_HALF_SPEED); // 1 @@ -64,7 +65,7 @@ void spiInit(uint8_t spiRate) { case SPI_SPEED_5: clock = 625000; break; case SPI_SPEED_6: clock = 312500; break; default: - clock = 4000000; // Default from the SPI libarary + clock = 4000000; // Default from the SPI library } spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0); SPI.begin(); @@ -80,7 +81,7 @@ uint8_t spiRec() { //return SPDR; } -void spiRead(uint8_t* buf, uint16_t nbyte) { +void spiRead(uint8_t *buf, uint16_t nbyte) { SPI.beginTransaction(spiConfig); SPI.transfer(buf, nbyte); SPI.endTransaction(); @@ -103,7 +104,7 @@ void spiSend(uint8_t b) { //while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } } -void spiSendBlock(uint8_t token, const uint8_t* buf) { +void spiSendBlock(uint8_t token, const uint8_t *buf) { SPI.beginTransaction(spiConfig); SPDR = token; for (uint16_t i = 0; i < 512; i += 2) { diff --git a/Marlin/src/HAL/TEENSY35_36/eeprom.cpp b/Marlin/src/HAL/TEENSY35_36/eeprom.cpp index ccbdc6b11600..b80e93b536a5 100644 --- a/Marlin/src/HAL/TEENSY35_36/eeprom.cpp +++ b/Marlin/src/HAL/TEENSY35_36/eeprom.cpp @@ -42,13 +42,13 @@ bool PersistentStore::access_start() { return true; } bool PersistentStore::access_finish() { return true; } bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + uint16_t written = 0; while (size--) { uint8_t * const p = (uint8_t * const)pos; uint8_t v = *value; - // EEPROM has only ~100,000 write cycles, - // so only write bytes that have changed! - if (v != eeprom_read_byte(p)) { + if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed! eeprom_write_byte(p, v); + if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes if (eeprom_read_byte(p) != v) { SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); return true; @@ -61,7 +61,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui return false; } -bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { +bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { do { uint8_t c = eeprom_read_byte((uint8_t*)pos); if (writing) *value = c; diff --git a/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h b/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h index 87e6a7507abc..a30024888535 100644 --- a/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h +++ b/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h @@ -63,4 +63,10 @@ void setup_endstop_interrupts() { TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); TERN_(HAS_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)); } diff --git a/Marlin/src/HAL/TEENSY35_36/fastio.h b/Marlin/src/HAL/TEENSY35_36/fastio.h index 9a299de9c763..622799ec8cac 100644 --- a/Marlin/src/HAL/TEENSY35_36/fastio.h +++ b/Marlin/src/HAL/TEENSY35_36/fastio.h @@ -28,7 +28,7 @@ */ #ifndef MASK - #define MASK(PIN) (1 << PIN) + #define MASK(PIN) _BV(PIN) #endif #define GPIO_BITBAND_ADDR(reg, bit) (((uint32_t)&(reg) - 0x40000000) * 32 + (bit) * 4 + 0x42000000) diff --git a/Marlin/src/HAL/TEENSY35_36/inc/SanityCheck.h b/Marlin/src/HAL/TEENSY35_36/inc/SanityCheck.h index ee80e42696fa..eef2850550eb 100644 --- a/Marlin/src/HAL/TEENSY35_36/inc/SanityCheck.h +++ b/Marlin/src/HAL/TEENSY35_36/inc/SanityCheck.h @@ -34,5 +34,9 @@ #endif #if HAS_TMC_SW_SERIAL - #error "TMC220x Software Serial is not supported on this platform." + #error "TMC220x Software Serial is not supported on Teensy 3.5/3.6." +#endif + +#if ENABLED(POSTMORTEM_DEBUGGING) + #error "POSTMORTEM_DEBUGGING is not yet supported on Teensy 3.5/3.6." #endif diff --git a/Marlin/src/HAL/TEENSY35_36/spi_pins.h b/Marlin/src/HAL/TEENSY35_36/spi_pins.h index c76344d07546..cfffdc932598 100644 --- a/Marlin/src/HAL/TEENSY35_36/spi_pins.h +++ b/Marlin/src/HAL/TEENSY35_36/spi_pins.h @@ -25,7 +25,7 @@ * HAL SPI Pins for Teensy 3.5 (MK64FX512) and Teensy 3.6 (MK66FX1M0) */ -#define SCK_PIN 13 -#define MISO_PIN 12 -#define MOSI_PIN 11 -#define SS_PIN 20 // SDSS // A.28, A.29, B.21, C.26, C.29 +#define SD_SCK_PIN 13 +#define SD_MISO_PIN 12 +#define SD_MOSI_PIN 11 +#define SD_SS_PIN 20 // SDSS // A.28, A.29, B.21, C.26, C.29 diff --git a/Marlin/src/HAL/TEENSY35_36/timers.h b/Marlin/src/HAL/TEENSY35_36/timers.h index 5c623cd80192..99269ac6571f 100644 --- a/Marlin/src/HAL/TEENSY35_36/timers.h +++ b/Marlin/src/HAL/TEENSY35_36/timers.h @@ -73,10 +73,10 @@ typedef uint32_t hal_timer_t; #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM) #ifndef HAL_STEP_TIMER_ISR - #define HAL_STEP_TIMER_ISR() extern "C" void ftm0_isr() //void TC3_Handler() + #define HAL_STEP_TIMER_ISR() extern "C" void ftm0_isr() //void TC3_Handler() #endif #ifndef HAL_TEMP_TIMER_ISR - #define HAL_TEMP_TIMER_ISR() extern "C" void ftm1_isr() //void TC4_Handler() + #define HAL_TEMP_TIMER_ISR() extern "C" void ftm1_isr() //void TC4_Handler() #endif void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency); diff --git a/Marlin/src/HAL/TEENSY35_36/watchdog.cpp b/Marlin/src/HAL/TEENSY35_36/watchdog.cpp index e735ee79238f..3825e2792869 100644 --- a/Marlin/src/HAL/TEENSY35_36/watchdog.cpp +++ b/Marlin/src/HAL/TEENSY35_36/watchdog.cpp @@ -27,9 +27,11 @@ #include "watchdog.h" +#define WDT_TIMEOUT_MS TERN(WATCHDOG_DURATION_8S, 8000, 4000) // 4 or 8 second timeout + void watchdog_init() { WDOG_TOVALH = 0; - WDOG_TOVALL = 4000; + WDOG_TOVALL = WDT_TIMEOUT_MS; WDOG_STCTRLH = WDOG_STCTRLH_WDOGEN; } diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.cpp b/Marlin/src/HAL/TEENSY40_41/HAL.cpp index 5b1b4272f5ee..ccc8c2659c65 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.cpp +++ b/Marlin/src/HAL/TEENSY40_41/HAL.cpp @@ -26,12 +26,20 @@ #ifdef __IMXRT1062__ +#include "../../inc/MarlinConfig.h" #include "HAL.h" + #include "../shared/Delay.h" #include "timers.h" - #include +#define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X) +#define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X) +#if WITHIN(SERIAL_PORT, 0, 3) + IMPLEMENT_SERIAL(SERIAL_PORT); +#endif +USBSerialType USBSerial(false, SerialUSB); + uint16_t HAL_adc_result, HAL_adc_select; static const uint8_t pin2sc1a[] = { @@ -113,6 +121,8 @@ uint8_t HAL_get_reset_source() { return 0; } +void HAL_reboot() { _reboot_Teensyduino_(); } + #define __bss_end _ebss extern "C" { diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.h b/Marlin/src/HAL/TEENSY40_41/HAL.h index 75c10e93958e..1d00447fe894 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.h +++ b/Marlin/src/HAL/TEENSY40_41/HAL.h @@ -37,6 +37,10 @@ #include #include +#if HAS_ETHERNET + #include "../../feature/ethernet.h" +#endif + //#define ST7920_DELAY_1 DELAY_NS(600) //#define ST7920_DELAY_2 DELAY_NS(750) //#define ST7920_DELAY_3 DELAY_NS(750) @@ -51,25 +55,37 @@ #define IS_TEENSY41 1 #endif -#define _MSERIAL(X) Serial##X -#define MSERIAL(X) _MSERIAL(X) +#include "../../core/serial_hook.h" #define Serial0 Serial +#define _DECLARE_SERIAL(X) \ + typedef ForwardSerial1Class DefaultSerial##X; \ + extern DefaultSerial##X MSerial##X +#define DECLARE_SERIAL(X) _DECLARE_SERIAL(X) + +typedef ForwardSerial1Class USBSerialType; +extern USBSerialType USBSerial; + +#define _MSERIAL(X) MSerial##X +#define MSERIAL(X) _MSERIAL(X) #if SERIAL_PORT == -1 - #define MYSERIAL0 SerialUSB + #define MYSERIAL1 SerialUSB #elif WITHIN(SERIAL_PORT, 0, 8) - #define MYSERIAL0 MSERIAL(SERIAL_PORT) + DECLARE_SERIAL(SERIAL_PORT); + #define MYSERIAL1 MSERIAL(SERIAL_PORT) #else - #error "The required SERIAL_PORT must be from -1 to 8. Please update your configuration." + #error "The required SERIAL_PORT must be from 0 to 8, or -1 for Native USB." #endif #ifdef SERIAL_PORT_2 #if SERIAL_PORT_2 == -1 - #define MYSERIAL1 usbSerial + #define MYSERIAL2 usbSerial + #elif SERIAL_PORT_2 == -2 + #define MYSERIAL2 ethernet.telnetClient #elif WITHIN(SERIAL_PORT_2, 0, 8) - #define MYSERIAL1 MSERIAL(SERIAL_PORT_2) + #define MYSERIAL2 MSERIAL(SERIAL_PORT_2) #else - #error "SERIAL_PORT_2 must be from -1 to 8. Please update your configuration." + #error "SERIAL_PORT_2 must be from 0 to 8, or -1 for Native USB, or -2 for Ethernet." #endif #endif @@ -90,21 +106,10 @@ typedef int8_t pin_t; #undef sq #define sq(x) ((x)*(x)) -#ifndef strncpy_P - #define strncpy_P(dest, src, num) strncpy((dest), (src), (num)) -#endif - // Don't place string constants in PROGMEM #undef PSTR #define PSTR(str) ({static const char *data = (str); &data[0];}) -// Fix bug in pgm_read_ptr -#undef pgm_read_ptr -#define pgm_read_ptr(addr) (*((void**)(addr))) -// Add type-checking to pgm_read_word -#undef pgm_read_word -#define pgm_read_word(addr) (*((uint16_t*)(addr))) - // Enable hooks into idle and setup for HAL #define HAL_IDLETASK 1 FORCE_INLINE void HAL_idletask() {} @@ -116,14 +121,20 @@ void HAL_clear_reset_source(); // Reset reason uint8_t HAL_get_reset_source(); +void HAL_reboot(); + FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); } -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-function" -extern "C" { - uint32_t freeMemory(); -} -#pragma GCC diagnostic pop +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + +extern "C" uint32_t freeMemory(); + +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic pop +#endif // ADC diff --git a/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp index 20b472aa3515..610765ad49c7 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp +++ b/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp @@ -26,11 +26,12 @@ #ifdef __IMXRT1062__ +#include "../../inc/MarlinConfig.h" #include "HAL.h" + #include #include #include "spi_pins.h" -#include "../../core/macros.h" static SPISettings spiConfig; @@ -50,20 +51,20 @@ static SPISettings spiConfig; // ------------------------ void spiBegin() { - #ifndef SS_PIN - #error "SS_PIN is not defined!" + #ifndef SD_SS_PIN + #error "SD_SS_PIN is not defined!" #endif - OUT_WRITE(SS_PIN, HIGH); + OUT_WRITE(SD_SS_PIN, HIGH); - //SET_OUTPUT(SCK_PIN); - //SET_INPUT(MISO_PIN); - //SET_OUTPUT(MOSI_PIN); + //SET_OUTPUT(SD_SCK_PIN); + //SET_INPUT(SD_MISO_PIN); + //SET_OUTPUT(SD_MOSI_PIN); #if 0 && DISABLED(SOFTWARE_SPI) // set SS high - may be chip select for another SPI device #if SET_SPI_SS_HIGH - WRITE(SS_PIN, HIGH); + WRITE(SD_SS_PIN, HIGH); #endif // set a default rate spiInit(SPI_HALF_SPEED); // 1 @@ -81,7 +82,7 @@ void spiInit(uint8_t spiRate) { case SPI_SPEED_5: clock = 625000; break; case SPI_SPEED_6: clock = 312500; break; default: - clock = 4000000; // Default from the SPI libarary + clock = 4000000; // Default from the SPI library } spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0); SPI.begin(); @@ -97,7 +98,7 @@ uint8_t spiRec() { //return SPDR; } -void spiRead(uint8_t* buf, uint16_t nbyte) { +void spiRead(uint8_t *buf, uint16_t nbyte) { SPI.beginTransaction(spiConfig); SPI.transfer(buf, nbyte); SPI.endTransaction(); @@ -120,7 +121,7 @@ void spiSend(uint8_t b) { //while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } } -void spiSendBlock(uint8_t token, const uint8_t* buf) { +void spiSendBlock(uint8_t token, const uint8_t *buf) { SPI.beginTransaction(spiConfig); SPDR = token; for (uint16_t i = 0; i < 512; i += 2) { diff --git a/Marlin/src/HAL/TEENSY40_41/eeprom.cpp b/Marlin/src/HAL/TEENSY40_41/eeprom.cpp index 030a8c38af3f..3cd376edce62 100644 --- a/Marlin/src/HAL/TEENSY40_41/eeprom.cpp +++ b/Marlin/src/HAL/TEENSY40_41/eeprom.cpp @@ -22,14 +22,14 @@ */ #ifdef __IMXRT1062__ -#include "../../inc/MarlinConfig.h" - -#if USE_WIRED_EEPROM - /** * HAL PersistentStore for Teensy 4.0 (IMXRT1062DVL6A) / 4.1 (IMXRT1062DVJ6A) */ +#include "../../inc/MarlinConfig.h" + +#if USE_WIRED_EEPROM + #include "../shared/eeprom_api.h" #include @@ -42,13 +42,13 @@ bool PersistentStore::access_start() { return true; } bool PersistentStore::access_finish() { return true; } bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + uint16_t written = 0; while (size--) { uint8_t * const p = (uint8_t * const)pos; uint8_t v = *value; - // EEPROM has only ~100,000 write cycles, - // so only write bytes that have changed! - if (v != eeprom_read_byte(p)) { + if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed! eeprom_write_byte(p, v); + if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes if (eeprom_read_byte(p) != v) { SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); return true; @@ -61,7 +61,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui return false; } -bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { +bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { do { uint8_t c = eeprom_read_byte((uint8_t*)pos); if (writing) *value = c; diff --git a/Marlin/src/HAL/TEENSY40_41/endstop_interrupts.h b/Marlin/src/HAL/TEENSY40_41/endstop_interrupts.h index a05e911668a7..4c3ddec9f1f1 100644 --- a/Marlin/src/HAL/TEENSY40_41/endstop_interrupts.h +++ b/Marlin/src/HAL/TEENSY40_41/endstop_interrupts.h @@ -63,4 +63,10 @@ void setup_endstop_interrupts() { TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); TERN_(HAS_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)); } diff --git a/Marlin/src/HAL/TEENSY40_41/inc/SanityCheck.h b/Marlin/src/HAL/TEENSY40_41/inc/SanityCheck.h index fbfe7b0fc3d4..3d2668d749bc 100644 --- a/Marlin/src/HAL/TEENSY40_41/inc/SanityCheck.h +++ b/Marlin/src/HAL/TEENSY40_41/inc/SanityCheck.h @@ -34,5 +34,9 @@ #endif #if HAS_TMC_SW_SERIAL - #error "TMC220x Software Serial is not supported on this platform." + #error "TMC220x Software Serial is not supported on Teensy 4.0/4.1." +#endif + +#if ENABLED(POSTMORTEM_DEBUGGING) + #error "POSTMORTEM_DEBUGGING is not yet supported on Teensy 4.0/4.1." #endif diff --git a/Marlin/src/HAL/TEENSY40_41/spi_pins.h b/Marlin/src/HAL/TEENSY40_41/spi_pins.h index d6f8d41bf6ce..ba4a2c700a4b 100644 --- a/Marlin/src/HAL/TEENSY40_41/spi_pins.h +++ b/Marlin/src/HAL/TEENSY40_41/spi_pins.h @@ -25,7 +25,7 @@ * HAL SPI Pins for Teensy 4.0 (IMXRT1062DVL6A) / 4.1 (IMXRT1062DVJ6A) */ -#define SCK_PIN 13 -#define MISO_PIN 12 -#define MOSI_PIN 11 -#define SS_PIN 20 // SDSS // A.28, A.29, B.21, C.26, C.29 +#define SD_SCK_PIN 13 +#define SD_MISO_PIN 12 +#define SD_MOSI_PIN 11 +#define SD_SS_PIN 20 // SDSS // A.28, A.29, B.21, C.26, C.29 diff --git a/Marlin/src/HAL/TEENSY40_41/timers.h b/Marlin/src/HAL/TEENSY40_41/timers.h index 7e4cd080cb88..556333d7f408 100644 --- a/Marlin/src/HAL/TEENSY40_41/timers.h +++ b/Marlin/src/HAL/TEENSY40_41/timers.h @@ -72,14 +72,16 @@ typedef uint32_t hal_timer_t; #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM) #ifndef HAL_STEP_TIMER_ISR - #define HAL_STEP_TIMER_ISR() extern "C" void stepTC_Handler() // GPT1_Handler() + #define HAL_STEP_TIMER_ISR() extern "C" void stepTC_Handler() // GPT1_Handler() #endif #ifndef HAL_TEMP_TIMER_ISR - #define HAL_TEMP_TIMER_ISR() extern "C" void tempTC_Handler() // GPT2_Handler() + #define HAL_TEMP_TIMER_ISR() extern "C" void tempTC_Handler() // GPT2_Handler() #endif -extern "C" void stepTC_Handler(); -extern "C" void tempTC_Handler(); +extern "C" { + void stepTC_Handler(); + void tempTC_Handler(); +} void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency); diff --git a/Marlin/src/HAL/TEENSY40_41/watchdog.cpp b/Marlin/src/HAL/TEENSY40_41/watchdog.cpp index 8b05ddb153eb..dd7c0aa92f09 100644 --- a/Marlin/src/HAL/TEENSY40_41/watchdog.cpp +++ b/Marlin/src/HAL/TEENSY40_41/watchdog.cpp @@ -19,31 +19,27 @@ * along with this program. If not, see . * */ +#ifdef __IMXRT1062__ /** * HAL Watchdog for Teensy 4.0 (IMXRT1062DVL6A) / 4.1 (IMXRT1062DVJ6A) */ -#ifdef __IMXRT1062__ - #include "../../inc/MarlinConfig.h" #if ENABLED(USE_WATCHDOG) #include "watchdog.h" -// 4 seconds timeout -#define WDTO 4 //seconds +#define WDT_TIMEOUT TERN(WATCHDOG_DURATION_8S, 8, 4) // 4 or 8 second timeout -uint8_t timeoutval = (WDTO - 0.5f) / 0.5f; +constexpr uint8_t timeoutval = (WDT_TIMEOUT - 0.5f) / 0.5f; void watchdog_init() { - CCM_CCGR3 |= CCM_CCGR3_WDOG1(3); // enable WDOG1 clocks WDOG1_WMCR = 0; // disable power down PDE WDOG1_WCR |= WDOG_WCR_SRS | WDOG_WCR_WT(timeoutval); WDOG1_WCR |= WDOG_WCR_WDE | WDOG_WCR_WDT | WDOG_WCR_SRE; - } void HAL_watchdog_refresh() { diff --git a/Marlin/src/HAL/platforms.h b/Marlin/src/HAL/platforms.h index ef17d19170cc..28fe28e1094f 100644 --- a/Marlin/src/HAL/platforms.h +++ b/Marlin/src/HAL/platforms.h @@ -37,14 +37,17 @@ #define HAL_PATH(PATH, NAME) XSTR(PATH/LPC1768/NAME) #elif defined(__STM32F1__) || defined(TARGET_STM32F1) #define HAL_PATH(PATH, NAME) XSTR(PATH/STM32F1/NAME) -#elif defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7)) - #define HAL_PATH(PATH, NAME) XSTR(PATH/STM32_F4_F7/NAME) #elif defined(ARDUINO_ARCH_STM32) + #ifndef HAL_STM32 + #define HAL_STM32 + #endif #define HAL_PATH(PATH, NAME) XSTR(PATH/STM32/NAME) #elif defined(ARDUINO_ARCH_ESP32) #define HAL_PATH(PATH, NAME) XSTR(PATH/ESP32/NAME) #elif defined(__PLAT_LINUX__) #define HAL_PATH(PATH, NAME) XSTR(PATH/LINUX/NAME) +#elif defined(__PLAT_NATIVE_SIM__) + #define HAL_PATH(PATH, NAME) XSTR(PATH/NATIVE_SIM/NAME) #elif defined(__SAMD51__) #define HAL_PATH(PATH, NAME) XSTR(PATH/SAMD51/NAME) #else diff --git a/Marlin/src/HAL/shared/Delay.cpp b/Marlin/src/HAL/shared/Delay.cpp new file mode 100644 index 000000000000..129698fd306d --- /dev/null +++ b/Marlin/src/HAL/shared/Delay.cpp @@ -0,0 +1,175 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "Delay.h" + +#include "../../inc/MarlinConfig.h" + +#if defined(__arm__) || defined(__thumb__) + + static uint32_t ASM_CYCLES_PER_ITERATION = 4; // Initial bet which will be adjusted in calibrate_delay_loop + + // Simple assembler loop counting down + void delay_asm(uint32_t cy) { + cy = _MAX(cy / ASM_CYCLES_PER_ITERATION, 1U); // Zero is forbidden here + __asm__ __volatile__( + A(".syntax unified") // is to prevent CM0,CM1 non-unified syntax + L("1") + A("subs %[cnt],#1") + A("bne 1b") + : [cnt]"+r"(cy) // output: +r means input+output + : // input: + : "cc" // clobbers: + ); + } + + // We can't use CMSIS since it's not available on all platform, so fallback to hardcoded register values + #define HW_REG(X) *(volatile uint32_t *)(X) + #define _DWT_CTRL 0xE0001000 + #define _DWT_CYCCNT 0xE0001004 // CYCCNT is 32bits, takes 37s or so to wrap. + #define _DEM_CR 0xE000EDFC + #define _LAR 0xE0001FB0 + + // Use hardware cycle counter instead, it's much safer + void delay_dwt(uint32_t count) { + // Reuse the ASM_CYCLES_PER_ITERATION variable to avoid wasting another useless variable + uint32_t start = HW_REG(_DWT_CYCCNT) - ASM_CYCLES_PER_ITERATION, elapsed; + do { + elapsed = HW_REG(_DWT_CYCCNT) - start; + } while (elapsed < count); + } + + // Pointer to asm function, calling the functions has a ~20 cycles overhead + DelayImpl DelayCycleFnc = delay_asm; + + void calibrate_delay_loop() { + // Check if we have a working DWT implementation in the CPU (see https://developer.arm.com/documentation/ddi0439/b/Data-Watchpoint-and-Trace-Unit/DWT-Programmers-Model) + if (!HW_REG(_DWT_CTRL)) { + // No DWT present, so fallback to plain old ASM nop counting + // Unfortunately, we don't exactly know how many iteration it'll take to decrement a counter in a loop + // It depends on the CPU architecture, the code current position (flash vs SRAM) + // So, instead of wild guessing and making mistake, instead + // compute it once for all + ASM_CYCLES_PER_ITERATION = 1; + // We need to fetch some reference clock before waiting + cli(); + uint32_t start = micros(); + delay_asm(1000); // On a typical CPU running in MHz, waiting 1000 "unknown cycles" means it'll take between 1ms to 6ms, that's perfectly acceptable + uint32_t end = micros(); + sei(); + uint32_t expectedCycles = (end - start) * ((F_CPU) / 1000000UL); // Convert microseconds to cycles + // Finally compute the right scale + ASM_CYCLES_PER_ITERATION = (uint32_t)(expectedCycles / 1000); + + // No DWT present, likely a Cortex M0 so NOP counting is our best bet here + DelayCycleFnc = delay_asm; + } + else { + // Enable DWT counter + // From https://stackoverflow.com/a/41188674/1469714 + HW_REG(_DEM_CR) = HW_REG(_DEM_CR) | 0x01000000; // Enable trace + #if __CORTEX_M == 7 + HW_REG(_LAR) = 0xC5ACCE55; // Unlock access to DWT registers, see https://developer.arm.com/documentation/ihi0029/e/ section B2.3.10 + #endif + HW_REG(_DWT_CYCCNT) = 0; // Clear DWT cycle counter + HW_REG(_DWT_CTRL) = HW_REG(_DWT_CTRL) | 1; // Enable DWT cycle counter + + // Then calibrate the constant offset from the counter + ASM_CYCLES_PER_ITERATION = 0; + uint32_t s = HW_REG(_DWT_CYCCNT); + uint32_t e = HW_REG(_DWT_CYCCNT); // (e - s) contains the number of cycle required to read the cycle counter + delay_dwt(0); + uint32_t f = HW_REG(_DWT_CYCCNT); // (f - e) contains the delay to call the delay function + the time to read the cycle counter + ASM_CYCLES_PER_ITERATION = (f - e) - (e - s); + + // Use safer DWT function + DelayCycleFnc = delay_dwt; + } + } + + #if ENABLED(MARLIN_DEV_MODE) + void dump_delay_accuracy_check() { + auto report_call_time = [](PGM_P const name, PGM_P const unit, const uint32_t cycles, const uint32_t total, const bool do_flush=true) { + SERIAL_ECHOPGM("Calling "); + SERIAL_ECHOPGM_P(name); + SERIAL_ECHOLNPAIR(" for ", cycles); + SERIAL_ECHOPGM_P(unit); + SERIAL_ECHOLNPAIR(" took: ", total); + SERIAL_ECHOPGM_P(unit); + if (do_flush) SERIAL_FLUSHTX(); + }; + + uint32_t s, e; + + SERIAL_ECHOLNPAIR("Computed delay calibration value: ", ASM_CYCLES_PER_ITERATION); + SERIAL_FLUSH(); + // Display the results of the calibration above + constexpr uint32_t testValues[] = { 1, 5, 10, 20, 50, 100, 150, 200, 350, 500, 750, 1000 }; + for (auto i : testValues) { + s = micros(); DELAY_US(i); e = micros(); + report_call_time(PSTR("delay"), PSTR("us"), i, e - s); + } + + if (HW_REG(_DWT_CTRL)) { + for (auto i : testValues) { + s = HW_REG(_DWT_CYCCNT); DELAY_CYCLES(i); e = HW_REG(_DWT_CYCCNT); + report_call_time(PSTR("runtime delay"), PSTR("cycles"), i, e - s); + } + + // Measure the delay to call a real function compared to a function pointer + s = HW_REG(_DWT_CYCCNT); delay_dwt(1); e = HW_REG(_DWT_CYCCNT); + report_call_time(PSTR("delay_dwt"), PSTR("cycles"), 1, e - s); + + static PGMSTR(dcd, "DELAY_CYCLES directly "); + + s = HW_REG(_DWT_CYCCNT); DELAY_CYCLES( 1); e = HW_REG(_DWT_CYCCNT); + report_call_time(dcd, PSTR("cycles"), 1, e - s, false); + + s = HW_REG(_DWT_CYCCNT); DELAY_CYCLES( 5); e = HW_REG(_DWT_CYCCNT); + report_call_time(dcd, PSTR("cycles"), 5, e - s, false); + + s = HW_REG(_DWT_CYCCNT); DELAY_CYCLES(10); e = HW_REG(_DWT_CYCCNT); + report_call_time(dcd, PSTR("cycles"), 10, e - s, false); + + s = HW_REG(_DWT_CYCCNT); DELAY_CYCLES(20); e = HW_REG(_DWT_CYCCNT); + report_call_time(dcd, PSTR("cycles"), 20, e - s, false); + + s = HW_REG(_DWT_CYCCNT); DELAY_CYCLES(50); e = HW_REG(_DWT_CYCCNT); + report_call_time(dcd, PSTR("cycles"), 50, e - s, false); + + s = HW_REG(_DWT_CYCCNT); DELAY_CYCLES(100); e = HW_REG(_DWT_CYCCNT); + report_call_time(dcd, PSTR("cycles"), 100, e - s, false); + + s = HW_REG(_DWT_CYCCNT); DELAY_CYCLES(200); e = HW_REG(_DWT_CYCCNT); + report_call_time(dcd, PSTR("cycles"), 200, e - s, false); + } + } + #endif // MARLIN_DEV_MODE + + +#else + + void calibrate_delay_loop() {} + #if ENABLED(MARLIN_DEV_MODE) + void dump_delay_accuracy_check() { SERIAL_ECHOPGM_P(PSTR("N/A on this platform")); } + #endif + +#endif diff --git a/Marlin/src/HAL/shared/Delay.h b/Marlin/src/HAL/shared/Delay.h index d98e96084850..04df35d88d6a 100644 --- a/Marlin/src/HAL/shared/Delay.h +++ b/Marlin/src/HAL/shared/Delay.h @@ -21,6 +21,8 @@ */ #pragma once +#include "../../inc/MarlinConfigPre.h" + /** * Busy wait delay cycles routines: * @@ -31,131 +33,176 @@ #include "../../core/macros.h" -#if defined(__arm__) || defined(__thumb__) - - #if __CORTEX_M == 7 - - // Cortex-M3 through M7 can use the cycle counter of the DWT unit - // https://www.anthonyvh.com/2017/05/18/cortex_m-cycle_counter/ - - FORCE_INLINE static void enableCycleCounter() { - CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk; +void calibrate_delay_loop(); - #if __CORTEX_M == 7 - DWT->LAR = 0xC5ACCE55; // Unlock DWT on the M7 - #endif +#if defined(__arm__) || defined(__thumb__) - DWT->CYCCNT = 0; - DWT->CTRL |= DWT_CTRL_CYCCNTENA_Msk; - } + // We want to have delay_cycle function with the lowest possible overhead, so we adjust at the function at runtime based on the current CPU best feature + typedef void (*DelayImpl)(uint32_t); + extern DelayImpl DelayCycleFnc; - FORCE_INLINE volatile uint32_t getCycleCount() { return DWT->CYCCNT; } + // I've measured 36 cycles on my system to call the cycle waiting method, but it shouldn't change much to have a bit more margin, it only consume a bit more flash + #define TRIP_POINT_FOR_CALLING_FUNCTION 40 - FORCE_INLINE static void DELAY_CYCLES(const uint32_t x) { - const uint32_t endCycles = getCycleCount() + x; - while (PENDING(getCycleCount(), endCycles)) {} + // A simple recursive template class that output exactly one 'nop' of code per recursion + template struct NopWriter { + FORCE_INLINE static void build() { + __asm__ __volatile__("nop"); + NopWriter::build(); } + }; + // End the loop + template <> struct NopWriter<0> { FORCE_INLINE static void build() {} }; + + namespace Private { + // Split recursing template in 2 different class so we don't reach the maximum template instantiation depth limit + template struct Helper { + FORCE_INLINE static void build() { + DelayCycleFnc(N - 2); // Approximative cost of calling the function (might be off by one or 2 cycles) + } + }; - #else - - // https://blueprints.launchpad.net/gcc-arm-embedded/+spec/delay-cycles - - #define nop() __asm__ __volatile__("nop;\n\t":::) + template struct Helper { + FORCE_INLINE static void build() { + NopWriter::build(); + } + }; - FORCE_INLINE static void __delay_4cycles(uint32_t cy) { // +1 cycle - #if ARCH_PIPELINE_RELOAD_CYCLES < 2 - #define EXTRA_NOP_CYCLES A("nop") - #else - #define EXTRA_NOP_CYCLES "" - #endif + template <> struct Helper { + FORCE_INLINE static void build() {} + }; - __asm__ __volatile__( - A(".syntax unified") // is to prevent CM0,CM1 non-unified syntax - L("1") - A("subs %[cnt],#1") - EXTRA_NOP_CYCLES - A("bne 1b") - : [cnt]"+r"(cy) // output: +r means input+output - : // input: - : "cc" // clobbers: - ); + } + // Select a behavior based on the constexpr'ness of the parameter + // If called with a compile-time parameter, then write as many NOP as required to reach the asked cycle count + // (there is some tripping point here to start looping when it's more profitable than gruntly executing NOPs) + // If not called from a compile-time parameter, fallback to a runtime loop counting version instead + template + struct SmartDelay { + FORCE_INLINE SmartDelay(int) { + if (Cycles == 0) return; + Private::Helper::build(); } + }; + // Runtime version below. There is no way this would run under less than ~TRIP_POINT_FOR_CALLING_FUNCTION cycles + template + struct SmartDelay { + FORCE_INLINE SmartDelay(int v) { DelayCycleFnc(v); } + }; - // Delay in cycles - FORCE_INLINE static void DELAY_CYCLES(uint32_t x) { - - if (__builtin_constant_p(x)) { - #define MAXNOPS 4 - - if (x <= (MAXNOPS)) { - switch (x) { case 4: nop(); case 3: nop(); case 2: nop(); case 1: nop(); } - } - else { // because of +1 cycle inside delay_4cycles - const uint32_t rem = (x - 1) % (MAXNOPS); - switch (rem) { case 3: nop(); case 2: nop(); case 1: nop(); } - if ((x = (x - 1) / (MAXNOPS))) - __delay_4cycles(x); // if need more then 4 nop loop is more optimal - } - #undef MAXNOPS - } - else if ((x >>= 2)) - __delay_4cycles(x); - } - #undef nop + #define DELAY_CYCLES(X) do { SmartDelay _smrtdly_X(X); } while(0) - #endif + // For delay in microseconds, no smart delay selection is required, directly call the delay function + // Teensy compiler is too old and does not accept smart delay compile-time / run-time selection correctly + #define DELAY_US(x) DelayCycleFnc((x) * ((F_CPU) / 1000000UL)) #elif defined(__AVR__) - - #define nop() __asm__ __volatile__("nop;\n\t":::) - - FORCE_INLINE static void __delay_4cycles(uint8_t cy) { - __asm__ __volatile__( - L("1") - A("dec %[cnt]") - A("nop") - A("brne 1b") - : [cnt] "+r"(cy) // output: +r means input+output - : // input: - : "cc" // clobbers: - ); + FORCE_INLINE static void __delay_up_to_3c(uint8_t cycles) { + switch (cycles) { + case 3: + __asm__ __volatile__(A("RJMP .+0") A("NOP")); + break; + case 2: + __asm__ __volatile__(A("RJMP .+0")); + break; + case 1: + __asm__ __volatile__(A("NOP")); + break; + } } // Delay in cycles - FORCE_INLINE static void DELAY_CYCLES(uint16_t x) { - - if (__builtin_constant_p(x)) { - #define MAXNOPS 4 - - if (x <= (MAXNOPS)) { - switch (x) { case 4: nop(); case 3: nop(); case 2: nop(); case 1: nop(); } + FORCE_INLINE static void DELAY_CYCLES(uint16_t cycles) { + if (__builtin_constant_p(cycles)) { + if (cycles <= 3) { + __delay_up_to_3c(cycles); + } + else if (cycles == 4) { + __delay_up_to_3c(2); + __delay_up_to_3c(2); } else { - const uint32_t rem = (x) % (MAXNOPS); - switch (rem) { case 3: nop(); case 2: nop(); case 1: nop(); } - if ((x = (x) / (MAXNOPS))) - __delay_4cycles(x); // if need more then 4 nop loop is more optimal + cycles -= 1 + 4; // Compensate for the first LDI (1) and the first round (4) + __delay_up_to_3c(cycles % 4); + + cycles /= 4; + // The following code burns [1 + 4 * (rounds+1)] cycles + uint16_t dummy; + __asm__ __volatile__( + // "manually" load counter from constants, otherwise the compiler may optimize this part away + A("LDI %A[rounds], %[l]") // 1c + A("LDI %B[rounds], %[h]") // 1c (compensating the non branching BRCC) + L("1") + A("SBIW %[rounds], 1") // 2c + A("BRCC 1b") // 2c when branching, else 1c (end of loop) + : // Outputs ... + [rounds] "=w" (dummy) // Restrict to a wo (=) 16 bit register pair (w) + : // Inputs ... + [l] "M" (cycles%256), // Restrict to 0..255 constant (M) + [h] "M" (cycles/256) // Restrict to 0..255 constant (M) + :// Clobbers ... + "cc" // Indicate we are modifying flags like Carry (cc) + ); } - - #undef MAXNOPS } - else if ((x >>= 2)) - __delay_4cycles(x); + else { + __asm__ __volatile__( + L("1") + A("SBIW %[cycles], 4") // 2c + A("BRCC 1b") // 2c when branching, else 1c (end of loop) + : [cycles] "+w" (cycles) // output: Restrict to a rw (+) 16 bit register pair (w) + : // input: - + : "cc" // clobbers: We are modifying flags like Carry (cc) + ); + } } - #undef nop -#elif defined(__PLAT_LINUX__) || defined(ESP32) + // Delay in microseconds + #define DELAY_US(x) DELAY_CYCLES((x) * ((F_CPU) / 1000000UL)) + +#elif defined(ESP32) || defined(__PLAT_LINUX__) || defined(__PLAT_NATIVE_SIM__) - // specified inside platform + // DELAY_CYCLES specified inside platform + // Delay in microseconds + #define DELAY_US(x) DELAY_CYCLES((x) * ((F_CPU) / 1000000UL)) #else #error "Unsupported MCU architecture" #endif -// Delay in nanoseconds -#define DELAY_NS(x) DELAY_CYCLES( (x) * (F_CPU / 1000000UL) / 1000UL ) +/************************************************************** + * Delay in nanoseconds. Requires the F_CPU macro. + * These macros follow avr-libc delay conventions. + * + * For AVR there are three possible operation modes, due to its + * slower clock speeds and thus coarser delay resolution. For + * example, when F_CPU = 16000000 the resolution is 62.5ns. + * + * Round up (default) + * Round up the delay according to the CPU clock resolution. + * e.g., 100 will give a delay of 2 cycles (125ns). + * + * Round down (DELAY_NS_ROUND_DOWN) + * Round down the delay according to the CPU clock resolution. + * e.g., 100 will be rounded down to 1 cycle (62.5ns). + * + * Nearest (DELAY_NS_ROUND_CLOSEST) + * Round the delay to the nearest number of clock cycles. + * e.g., 165 will be rounded up to 3 cycles (187.5ns) because + * it's closer to the requested delay than 2 cycle (125ns). + */ -// Delay in microseconds -#define DELAY_US(x) DELAY_CYCLES( (x) * (F_CPU / 1000000UL) ) +#ifndef __AVR__ + #undef DELAY_NS_ROUND_DOWN + #undef DELAY_NS_ROUND_CLOSEST +#endif + +#if ENABLED(DELAY_NS_ROUND_DOWN) + #define DELAY_NS(x) DELAY_CYCLES((x) * ((F_CPU) / 1000000UL) / 1000UL) // floor +#elif ENABLED(DELAY_NS_ROUND_CLOSEST) + #define DELAY_NS(x) DELAY_CYCLES(((x) * ((F_CPU) / 1000000UL) + 500) / 1000UL) // round +#else + #define DELAY_NS(x) DELAY_CYCLES(((x) * ((F_CPU) / 1000000UL) + 999) / 1000UL) // "ceil" +#endif diff --git a/Marlin/src/HAL/shared/HAL_MinSerial.cpp b/Marlin/src/HAL/shared/HAL_MinSerial.cpp new file mode 100644 index 000000000000..9dda5fdf8c67 --- /dev/null +++ b/Marlin/src/HAL/shared/HAL_MinSerial.cpp @@ -0,0 +1,33 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "HAL_MinSerial.h" + +#if ENABLED(POSTMORTEM_DEBUGGING) + +void HAL_min_serial_init_default() {} +void HAL_min_serial_out_default(char ch) { SERIAL_CHAR(ch); } +void (*HAL_min_serial_init)() = &HAL_min_serial_init_default; +void (*HAL_min_serial_out)(char) = &HAL_min_serial_out_default; + +bool MinSerial::force_using_default_output = false; + +#endif diff --git a/Marlin/src/HAL/shared/HAL_MinSerial.h b/Marlin/src/HAL/shared/HAL_MinSerial.h new file mode 100644 index 000000000000..3089b8aa0618 --- /dev/null +++ b/Marlin/src/HAL/shared/HAL_MinSerial.h @@ -0,0 +1,79 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include "../../core/serial.h" +#include + +// Serial stuff here +// Inside an exception handler, the CPU state is not safe, we can't expect the handler to resume +// and the software to continue. UART communication can't rely on later callback/interrupt as it might never happen. +// So, you need to provide some method to send one byte to the usual UART with the interrupts disabled +// By default, the method uses SERIAL_CHAR but it's 100% guaranteed to break (couldn't be worse than nothing...)7 +extern void (*HAL_min_serial_init)(); +extern void (*HAL_min_serial_out)(char ch); + +struct MinSerial { + static bool force_using_default_output; + // Serial output + static void TX(char ch) { + if (force_using_default_output) + SERIAL_CHAR(ch); + else + HAL_min_serial_out(ch); + } + // Send String through UART + static void TX(const char *s) { while (*s) TX(*s++); } + // Send a digit through UART + static void TXDigit(uint32_t d) { + if (d < 10) TX((char)(d+'0')); + else if (d < 16) TX((char)(d+'A'-10)); + else TX('?'); + } + + // Send Hex number through UART + static void TXHex(uint32_t v) { + TX("0x"); + for (uint8_t i = 0; i < 8; i++, v <<= 4) + TXDigit((v >> 28) & 0xF); + } + + // Send Decimal number through UART + static void TXDec(uint32_t v) { + if (!v) { + TX('0'); + return; + } + + char nbrs[14]; + char *p = &nbrs[0]; + while (v != 0) { + *p++ = '0' + (v % 10); + v /= 10; + } + do { + p--; + TX(*p); + } while (p != &nbrs[0]); + } + static void init() { if (!force_using_default_output) HAL_min_serial_init(); } +}; diff --git a/Marlin/src/HAL/shared/HAL_SPI.h b/Marlin/src/HAL/shared/HAL_SPI.h index 59af5548064c..6611f9ec4e0f 100644 --- a/Marlin/src/HAL/shared/HAL_SPI.h +++ b/Marlin/src/HAL/shared/HAL_SPI.h @@ -71,10 +71,10 @@ void spiSend(uint8_t b); uint8_t spiRec(); // Read from SPI into buffer -void spiRead(uint8_t* buf, uint16_t nbyte); +void spiRead(uint8_t *buf, uint16_t nbyte); // Write token and then write from 512 byte buffer to SPI (for SD card) -void spiSendBlock(uint8_t token, const uint8_t* buf); +void spiSendBlock(uint8_t token, const uint8_t *buf); // Begin SPI transaction, set clock, bit order, data mode void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode); @@ -87,7 +87,7 @@ void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode); void spiSend(uint32_t chan, byte b); // Write buffer to specified SPI channel -void spiSend(uint32_t chan, const uint8_t* buf, size_t n); +void spiSend(uint32_t chan, const uint8_t *buf, size_t n); // Read single byte from specified SPI channel uint8_t spiRec(uint32_t chan); diff --git a/Marlin/src/HAL/shared/Marduino.h b/Marlin/src/HAL/shared/Marduino.h index 3003f3cc2891..56be8d72118f 100644 --- a/Marlin/src/HAL/shared/Marduino.h +++ b/Marlin/src/HAL/shared/Marduino.h @@ -28,9 +28,9 @@ #undef DISABLED // Redefined by ESP32 #undef M_PI // Redefined by all #undef _BV // Redefined by some -#undef sq // Redefined by teensy3/wiring.h #undef SBI // Redefined by arduino/const_functions.h #undef CBI // Redefined by arduino/const_functions.h +#undef sq // Redefined by teensy3/wiring.h #undef UNUSED // Redefined by stm32f4xx_hal_def.h #include // NOTE: If included earlier then this line is a NOOP @@ -40,18 +40,16 @@ #undef _BV #define _BV(b) (1UL << (b)) - -#undef sq -#define sq(x) ((x)*(x)) - #ifndef SBI - #define SBI(A,B) (A |= (1 << (B))) + #define SBI(A,B) (A |= _BV(B)) #endif - #ifndef CBI - #define CBI(A,B) (A &= ~(1 << (B))) + #define CBI(A,B) (A &= ~_BV(B)) #endif +#undef sq +#define sq(x) ((x)*(x)) + #ifndef __AVR__ #ifndef strchr_P // Some platforms define a macro (DUE, teensy35) inline const char* strchr_P(const char *s, int c) { return strchr(s,c); } @@ -83,3 +81,9 @@ #ifndef UNUSED #define UNUSED(x) ((void)(x)) #endif + +#ifndef FORCE_INLINE + #define FORCE_INLINE inline __attribute__((always_inline)) +#endif + +#include "progmem.h" diff --git a/Marlin/src/HAL/shared/backtrace/backtrace.cpp b/Marlin/src/HAL/shared/backtrace/backtrace.cpp index 6cf5e055e151..ad88de8385ac 100644 --- a/Marlin/src/HAL/shared/backtrace/backtrace.cpp +++ b/Marlin/src/HAL/shared/backtrace/backtrace.cpp @@ -25,30 +25,32 @@ #include "unwinder.h" #include "unwmemaccess.h" -#include "../../../core/serial.h" +#include "../HAL_MinSerial.h" #include // Dump a backtrace entry -static bool UnwReportOut(void* ctx, const UnwReport* bte) { +static bool UnwReportOut(void *ctx, const UnwReport *bte) { int *p = (int*)ctx; (*p)++; - SERIAL_CHAR('#'); SERIAL_PRINT(*p, DEC); SERIAL_ECHOPGM(" : "); - SERIAL_ECHOPGM(bte->name ? bte->name : "unknown"); SERIAL_ECHOPGM("@0x"); SERIAL_PRINT(bte->function, HEX); - SERIAL_CHAR('+'); SERIAL_PRINT(bte->address - bte->function,DEC); - SERIAL_ECHOPGM(" PC:"); SERIAL_PRINT(bte->address,HEX); SERIAL_CHAR('\n'); + const uint32_t a = bte->address, f = bte->function; + MinSerial::TX('#'); MinSerial::TXDec(*p); MinSerial::TX(" : "); + MinSerial::TX(bte->name?:"unknown"); MinSerial::TX('@'); MinSerial::TXHex(f); + MinSerial::TX('+'); MinSerial::TXDec(a - f); + MinSerial::TX(" PC:"); MinSerial::TXHex(a); + MinSerial::TX('\n'); return true; } #ifdef UNW_DEBUG - void UnwPrintf(const char* format, ...) { + void UnwPrintf(const char *format, ...) { char dest[256]; va_list argptr; va_start(argptr, format); vsprintf(dest, format, argptr); va_end(argptr); - TX(&dest[0]); + MinSerial::TX(&dest[0]); } #endif @@ -63,10 +65,10 @@ static const UnwindCallbacks UnwCallbacks = { #endif }; +// Perform a backtrace to the serial port void backtrace() { - UnwindFrame btf; - uint32_t sp = 0, lr = 0, pc = 0; + unsigned long sp = 0, lr = 0, pc = 0; // Capture the values of the registers to perform the traceback __asm__ __volatile__ ( @@ -79,6 +81,12 @@ void backtrace() { :: ); + backtrace_ex(sp, lr, pc); +} + +void backtrace_ex(unsigned long sp, unsigned long lr, unsigned long pc) { + UnwindFrame btf; + // Fill the traceback structure btf.sp = sp; btf.fp = btf.sp; @@ -86,7 +94,7 @@ void backtrace() { btf.pc = pc | 1; // Force Thumb, as CORTEX only support it // Perform a backtrace - SERIAL_ERROR_MSG("Backtrace:"); + MinSerial::TX("Backtrace:"); int ctr = 0; UnwindStart(&btf, &UnwCallbacks, &ctr); } @@ -95,4 +103,4 @@ void backtrace() { void backtrace() {} -#endif +#endif // __arm__ || __thumb__ diff --git a/Marlin/src/HAL/shared/backtrace/backtrace.h b/Marlin/src/HAL/shared/backtrace/backtrace.h index fccadedaa543..5d2ba601a071 100644 --- a/Marlin/src/HAL/shared/backtrace/backtrace.h +++ b/Marlin/src/HAL/shared/backtrace/backtrace.h @@ -23,3 +23,6 @@ // Perform a backtrace to the serial port void backtrace(); + +// Perform a backtrace to the serial port +void backtrace_ex(unsigned long sp, unsigned long lr, unsigned long pc); diff --git a/Marlin/src/HAL/shared/backtrace/unwarm.cpp b/Marlin/src/HAL/shared/backtrace/unwarm.cpp index cdc9c06c615e..adbcca69cc58 100644 --- a/Marlin/src/HAL/shared/backtrace/unwarm.cpp +++ b/Marlin/src/HAL/shared/backtrace/unwarm.cpp @@ -7,7 +7,7 @@ * for free and use it as they wish, with or without modifications, and in * any context, commercially or otherwise. The only limitation is that I * don't guarantee that the software is fit for any purpose or accept any - * liability for it's use or misuse - this software is without warranty. + * liability for its use or misuse - this software is without warranty. *************************************************************************** * File Description: Utility functions and glue for ARM unwinding sub-modules. **************************************************************************/ diff --git a/Marlin/src/HAL/shared/backtrace/unwarm.h b/Marlin/src/HAL/shared/backtrace/unwarm.h index 3128e354cc72..edae90650e29 100644 --- a/Marlin/src/HAL/shared/backtrace/unwarm.h +++ b/Marlin/src/HAL/shared/backtrace/unwarm.h @@ -4,9 +4,9 @@ * This program is PUBLIC DOMAIN. * This means that there is no copyright and anyone is able to take a copy * for free and use it as they wish, with or without modifications, and in - * any context, commerically or otherwise. The only limitation is that I + * any context, commercially or otherwise. The only limitation is that I * don't guarantee that the software is fit for any purpose or accept any - * liablity for it's use or misuse - this software is without warranty. + * liability for its use or misuse - this software is without warranty. *************************************************************************** * File Description: Internal interface between the ARM unwinding sub-modules. **************************************************************************/ diff --git a/Marlin/src/HAL/shared/backtrace/unwarm_arm.cpp b/Marlin/src/HAL/shared/backtrace/unwarm_arm.cpp index 0ec9bd56af7d..decf74e6e9c5 100644 --- a/Marlin/src/HAL/shared/backtrace/unwarm_arm.cpp +++ b/Marlin/src/HAL/shared/backtrace/unwarm_arm.cpp @@ -7,7 +7,7 @@ * for free and use it as they wish, with or without modifications, and in * any context, commercially or otherwise. The only limitation is that I * don't guarantee that the software is fit for any purpose or accept any - * liability for it's use or misuse - this software is without warranty. + * liability for its use or misuse - this software is without warranty. *************************************************************************** * File Description: Abstract interpreter for ARM mode. **************************************************************************/ @@ -43,10 +43,9 @@ static bool isDataProc(uint32_t instr) { } UnwResult UnwStartArm(UnwState * const state) { - bool found = false; uint16_t t = UNW_MAX_INSTR_COUNT; - do { + for (;;) { uint32_t instr; /* Attempt to read the instruction */ @@ -527,7 +526,7 @@ UnwResult UnwStartArm(UnwState * const state) { if (--t == 0) return UNWIND_EXHAUSTED; - } while (!found); + } return UNWIND_UNSUPPORTED; } diff --git a/Marlin/src/HAL/shared/backtrace/unwarm_thumb.cpp b/Marlin/src/HAL/shared/backtrace/unwarm_thumb.cpp index 26ca8b2604e9..0c6a70649d82 100644 --- a/Marlin/src/HAL/shared/backtrace/unwarm_thumb.cpp +++ b/Marlin/src/HAL/shared/backtrace/unwarm_thumb.cpp @@ -7,7 +7,7 @@ * for free and use it as they wish, with or without modifications, and in * any context, commercially or otherwise. The only limitation is that I * don't guarantee that the software is fit for any purpose or accept any - * liability for it's use or misuse - this software is without warranty. + * liability for its use or misuse - this software is without warranty. *************************************************************************** * File Description: Abstract interpretation for Thumb mode. **************************************************************************/ @@ -30,12 +30,11 @@ static int32_t signExtend11(const uint16_t value) { } UnwResult UnwStartThumb(UnwState * const state) { - bool found = false; uint16_t t = UNW_MAX_INSTR_COUNT; uint32_t lastJumpAddr = 0; // Last JUMP address, to try to detect infinite loops bool loopDetected = false; // If a loop was detected - do { + for (;;) { uint16_t instr; /* Attempt to read the instruction */ @@ -1059,7 +1058,7 @@ UnwResult UnwStartThumb(UnwState * const state) { if (--t == 0) return UNWIND_EXHAUSTED; - } while (!found); + } return UNWIND_SUCCESS; } diff --git a/Marlin/src/HAL/shared/backtrace/unwarmbytab.cpp b/Marlin/src/HAL/shared/backtrace/unwarmbytab.cpp index bfc062af2090..f1ee81ed4acb 100644 --- a/Marlin/src/HAL/shared/backtrace/unwarmbytab.cpp +++ b/Marlin/src/HAL/shared/backtrace/unwarmbytab.cpp @@ -128,11 +128,8 @@ static UnwResult UnwTabStateInit(const UnwindCallbacks *cb, UnwTabState *ucb, ui * Execute unwinding instructions */ static UnwResult UnwTabExecuteInstructions(const UnwindCallbacks *cb, UnwTabState *ucb) { - int instruction; - uint32_t mask; - uint32_t reg; - uint32_t vsp; + uint32_t mask, reg, vsp; /* Consume all instruction byte */ while ((instruction = UnwTabGetNextInstruction(cb, ucb)) != -1) { @@ -140,12 +137,12 @@ static UnwResult UnwTabExecuteInstructions(const UnwindCallbacks *cb, UnwTabStat if ((instruction & 0xC0) == 0x00) { // ARM_EXIDX_CMD_DATA_POP /* vsp = vsp + (xxxxxx << 2) + 4 */ ucb->vrs[13] += ((instruction & 0x3F) << 2) + 4; - } else - if ((instruction & 0xC0) == 0x40) { // ARM_EXIDX_CMD_DATA_PUSH + } + else if ((instruction & 0xC0) == 0x40) { // ARM_EXIDX_CMD_DATA_PUSH /* vsp = vsp - (xxxxxx << 2) - 4 */ ucb->vrs[13] -= ((instruction & 0x3F) << 2) - 4; - } else - if ((instruction & 0xF0) == 0x80) { + } + else if ((instruction & 0xF0) == 0x80) { /* pop under mask {r15-r12},{r11-r4} or refuse to unwind */ instruction = instruction << 8 | UnwTabGetNextInstruction(cb, ucb); @@ -171,17 +168,17 @@ static UnwResult UnwTabExecuteInstructions(const UnwindCallbacks *cb, UnwTabStat } /* Patch up the vrs sp if it was in the mask */ - if ((instruction & (1 << (13 - 4))) != 0) + if (instruction & (1 << (13 - 4))) ucb->vrs[13] = vsp; - - } else - if ((instruction & 0xF0) == 0x90 && // ARM_EXIDX_CMD_REG_TO_SP - instruction != 0x9D && - instruction != 0x9F) { + } + else if ((instruction & 0xF0) == 0x90 // ARM_EXIDX_CMD_REG_TO_SP + && instruction != 0x9D + && instruction != 0x9F + ) { /* vsp = r[nnnn] */ ucb->vrs[13] = ucb->vrs[instruction & 0x0F]; - } else - if ((instruction & 0xF0) == 0xA0) { // ARM_EXIDX_CMD_REG_POP + } + else if ((instruction & 0xF0) == 0xA0) { // ARM_EXIDX_CMD_REG_POP /* pop r4-r[4+nnn] or pop r4-r[4+nnn], r14*/ vsp = ucb->vrs[13]; @@ -204,8 +201,8 @@ static UnwResult UnwTabExecuteInstructions(const UnwindCallbacks *cb, UnwTabStat ucb->vrs[13] = vsp; - } else - if (instruction == 0xB0) { // ARM_EXIDX_CMD_FINISH + } + else if (instruction == 0xB0) { // ARM_EXIDX_CMD_FINISH /* finished */ if (ucb->vrs[15] == 0) ucb->vrs[15] = ucb->vrs[14]; @@ -213,8 +210,8 @@ static UnwResult UnwTabExecuteInstructions(const UnwindCallbacks *cb, UnwTabStat /* All done unwinding */ return UNWIND_SUCCESS; - } else - if (instruction == 0xB1) { // ARM_EXIDX_CMD_REG_POP + } + else if (instruction == 0xB1) { // ARM_EXIDX_CMD_REG_POP /* pop register under mask {r3,r2,r1,r0} */ vsp = ucb->vrs[13]; mask = UnwTabGetNextInstruction(cb, ucb); @@ -234,16 +231,15 @@ static UnwResult UnwTabExecuteInstructions(const UnwindCallbacks *cb, UnwTabStat } ucb->vrs[13] = (uint32_t)vsp; - } else - if (instruction == 0xB2) { // ARM_EXIDX_CMD_DATA_POP + } + else if (instruction == 0xB2) { // ARM_EXIDX_CMD_DATA_POP /* vps = vsp + 0x204 + (uleb128 << 2) */ ucb->vrs[13] += 0x204 + (UnwTabGetNextInstruction(cb, ucb) << 2); - - } else - if (instruction == 0xB3 || // ARM_EXIDX_CMD_VFP_POP - instruction == 0xC8 || - instruction == 0xC9) { - + } + else if (instruction == 0xB3 // ARM_EXIDX_CMD_VFP_POP + || instruction == 0xC8 + || instruction == 0xC9 + ) { /* pop VFP double-precision registers */ vsp = ucb->vrs[13]; @@ -266,27 +262,20 @@ static UnwResult UnwTabExecuteInstructions(const UnwindCallbacks *cb, UnwTabStat } ucb->vrs[13] = vsp; - - } else - if ((instruction & 0xF8) == 0xB8 || - (instruction & 0xF8) == 0xD0) { - + } + else if ((instruction & 0xF8) == 0xB8 || (instruction & 0xF8) == 0xD0) { /* Pop VFP double precision registers D[8]-D[8+nnn] */ ucb->vrs[14] = 0x80 | (instruction & 0x07); - - if ((instruction & 0xF8) == 0xD0) { + if ((instruction & 0xF8) == 0xD0) ucb->vrs[14] = 1 << 17; - } - - } else + } + else return UNWIND_UNSUPPORTED_DWARF_INSTR; } - return UNWIND_SUCCESS; } static inline __attribute__((always_inline)) uint32_t read_psp() { - /* Read the current PSP and return its value as a pointer */ uint32_t psp; diff --git a/Marlin/src/HAL/shared/backtrace/unwarmbytab.h b/Marlin/src/HAL/shared/backtrace/unwarmbytab.h index 77a1c82dbddb..53aeca259439 100644 --- a/Marlin/src/HAL/shared/backtrace/unwarmbytab.h +++ b/Marlin/src/HAL/shared/backtrace/unwarmbytab.h @@ -5,9 +5,9 @@ * This program is PUBLIC DOMAIN. * This means that there is no copyright and anyone is able to take a copy * for free and use it as they wish, with or without modifications, and in - * any context, commerically or otherwise. The only limitation is that I + * any context, commercially or otherwise. The only limitation is that I * don't guarantee that the software is fit for any purpose or accept any - * liablity for it's use or misuse - this software is without warranty. + * liability for its use or misuse - this software is without warranty. *************************************************************************** * File Description: Interface to the memory tracking sub-system. **************************************************************************/ diff --git a/Marlin/src/HAL/shared/backtrace/unwarmmem.cpp b/Marlin/src/HAL/shared/backtrace/unwarmmem.cpp index cf9ac414c4e0..24023200e155 100644 --- a/Marlin/src/HAL/shared/backtrace/unwarmmem.cpp +++ b/Marlin/src/HAL/shared/backtrace/unwarmmem.cpp @@ -5,9 +5,9 @@ * This program is PUBLIC DOMAIN. * This means that there is no copyright and anyone is able to take a copy * for free and use it as they wish, with or without modifications, and in - * any context, commerically or otherwise. The only limitation is that I + * any context, commercially or otherwise. The only limitation is that I * don't guarantee that the software is fit for any purpose or accept any - * liablity for it's use or misuse - this software is without warranty. + * liability for its use or misuse - this software is without warranty. *************************************************************************** * File Description: Implementation of the memory tracking sub-system. **************************************************************************/ diff --git a/Marlin/src/HAL/shared/backtrace/unwarmmem.h b/Marlin/src/HAL/shared/backtrace/unwarmmem.h index 588618b34f0a..eb4579a76107 100644 --- a/Marlin/src/HAL/shared/backtrace/unwarmmem.h +++ b/Marlin/src/HAL/shared/backtrace/unwarmmem.h @@ -5,9 +5,9 @@ * This program is PUBLIC DOMAIN. * This means that there is no copyright and anyone is able to take a copy * for free and use it as they wish, with or without modifications, and in - * any context, commerically or otherwise. The only limitation is that I + * any context, commercially or otherwise. The only limitation is that I * don't guarantee that the software is fit for any purpose or accept any - * liablity for it's use or misuse - this software is without warranty. + * liability for its use or misuse - this software is without warranty. *************************************************************************** * File Description: Interface to the memory tracking sub-system. **************************************************************************/ diff --git a/Marlin/src/HAL/shared/backtrace/unwinder.cpp b/Marlin/src/HAL/shared/backtrace/unwinder.cpp index e63af1ed25a8..aedfa2404d65 100644 --- a/Marlin/src/HAL/shared/backtrace/unwinder.cpp +++ b/Marlin/src/HAL/shared/backtrace/unwinder.cpp @@ -7,7 +7,7 @@ * for free and use it as they wish, with or without modifications, and in * any context, commercially or otherwise. The only limitation is that I * don't guarantee that the software is fit for any purpose or accept any - * liability for it's use or misuse - this software is without warranty. + * liability for its use or misuse - this software is without warranty. *************************************************************************** * File Description: Implementation of the interface into the ARM unwinder. **************************************************************************/ @@ -28,7 +28,7 @@ extern "C" const UnwTabEntry __exidx_end[]; // Detect if unwind information is present or not static int HasUnwindTableInfo() { - // > 16 because there are default entries we can't supress + // > 16 because there are default entries we can't suppress return ((char*)(&__exidx_end) - (char*)(&__exidx_start)) > 16 ? 1 : 0; } diff --git a/Marlin/src/HAL/shared/backtrace/unwinder.h b/Marlin/src/HAL/shared/backtrace/unwinder.h index cae137951372..9280e2f36e89 100644 --- a/Marlin/src/HAL/shared/backtrace/unwinder.h +++ b/Marlin/src/HAL/shared/backtrace/unwinder.h @@ -5,9 +5,9 @@ * This program is PUBLIC DOMAIN. * This means that there is no copyright and anyone is able to take a copy * for free and use it as they wish, with or without modifications, and in - * any context, commerically or otherwise. The only limitation is that I + * any context, commercially or otherwise. The only limitation is that I * don't guarantee that the software is fit for any purpose or accept any - * liablity for it's use or misuse - this software is without warranty. + * liability for its use or misuse - this software is without warranty. **************************************************************************/ /** \file * Interface to the ARM stack unwinding module. @@ -114,7 +114,7 @@ typedef struct { * report function maybe called again in future. If false is returned, * unwinding will stop with UnwindStart() returning UNWIND_TRUNCATED. */ -typedef bool (*UnwindReportFunc)(void* data, const UnwReport* bte); +typedef bool (*UnwindReportFunc)(void *data, const UnwReport *bte); /** Structure that holds memory callback function pointers. */ diff --git a/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp b/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp index c93494d485c3..2bde1e208d95 100644 --- a/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp +++ b/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp @@ -7,7 +7,7 @@ * for free and use it as they wish, with or without modifications, and in * any context, commercially or otherwise. The only limitation is that I * don't guarantee that the software is fit for any purpose or accept any - * liability for it's use or misuse - this software is without warranty. + * liability for its use or misuse - this software is without warranty. *************************************************************************** * File Description: Utility functions to access memory **************************************************************************/ @@ -41,27 +41,16 @@ #define START_FLASH_ADDR 0x00000000 #define END_FLASH_ADDR 0x00080000 -#elif 0 - - // For STM32F103CBT6 - // SRAM (0x20000000 - 0x20005000) (20kb) - // FLASH (0x00000000 - 0x00020000) (128kb) - // - #define START_SRAM_ADDR 0x20000000 - #define END_SRAM_ADDR 0x20005000 - #define START_FLASH_ADDR 0x00000000 - #define END_FLASH_ADDR 0x00020000 - #elif defined(__STM32F1__) || defined(STM32F1xx) || defined(STM32F0xx) // For STM32F103ZET6/STM32F103VET6/STM32F0xx // SRAM (0x20000000 - 0x20010000) (64kb) - // FLASH (0x00000000 - 0x00080000) (512kb) + // FLASH (0x08000000 - 0x08080000) (512kb) // #define START_SRAM_ADDR 0x20000000 #define END_SRAM_ADDR 0x20010000 - #define START_FLASH_ADDR 0x00000000 - #define END_FLASH_ADDR 0x00080000 + #define START_FLASH_ADDR 0x08000000 + #define END_FLASH_ADDR 0x08080000 #elif defined(STM32F4) || defined(STM32F4xx) @@ -74,17 +63,6 @@ #define START_FLASH_ADDR 0x08000000 #define END_FLASH_ADDR 0x08080000 -#elif MB(THE_BORG) - - // For STM32F765 in BORG - // SRAM (0x20000000 - 0x20080000) (512kb) - // FLASH (0x08000000 - 0x08100000) (1024kb) - // - #define START_SRAM_ADDR 0x20000000 - #define END_SRAM_ADDR 0x20080000 - #define START_FLASH_ADDR 0x08000000 - #define END_FLASH_ADDR 0x08100000 - #elif MB(REMRAM_V1, NUCLEO_F767ZI) // For STM32F765VI in RemRam v1 @@ -153,20 +131,57 @@ #define START_FLASH_ADDR 0x00000000 #define END_FLASH_ADDR 0x00100000 +#else + // 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_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 + #define HW_REG(X) (*((volatile unsigned long *)(X))) + + static bool validate_addr(uint32_t read_address) { + bool works = true; + uint32_t intDisabled = 0; + // Read current interrupt state + __asm__ __volatile__ ("MRS %[result], PRIMASK\n\t" : [result]"=r"(intDisabled) :: ); // 0 is int enabled, 1 for disabled + + // Clear bus fault indicator first (write 1 to clear) + HW_REG(NVIC_FAULT_STAT) |= NVIC_FAULT_STAT_BFARV; + // Ignore bus fault interrupt + HW_REG(NVIC_CFG_CTRL) |= NVIC_CFG_CTRL_BFHFNMIGN; + // Disable interrupts if not disabled previously + if (!intDisabled) __asm__ __volatile__ ("CPSID f"); + // Probe address + *(volatile uint32_t*)read_address; + // Check if a fault happened + if ((HW_REG(NVIC_FAULT_STAT) & NVIC_FAULT_STAT_BFARV) != 0) + works = false; + // Enable interrupts again if previously disabled + if (!intDisabled) __asm__ __volatile__ ("CPSIE f"); + // Enable fault interrupt flag + HW_REG(NVIC_CFG_CTRL) &= ~NVIC_CFG_CTRL_BFHFNMIGN; + + return works; + } + #endif -static bool validate_addr(uint32_t addr) { +#ifdef START_SRAM_ADDR + static bool validate_addr(uint32_t addr) { - // Address must be in SRAM range - if (addr >= START_SRAM_ADDR && addr < END_SRAM_ADDR) - return true; + // Address must be in SRAM range + if (addr >= START_SRAM_ADDR && addr < END_SRAM_ADDR) + return true; - // Or in FLASH range - if (addr >= START_FLASH_ADDR && addr < END_FLASH_ADDR) - return true; + // Or in FLASH range + if (addr >= START_FLASH_ADDR && addr < END_FLASH_ADDR) + return true; - return false; -} + return false; + } +#endif bool UnwReadW(const uint32_t a, uint32_t *v) { if (!validate_addr(a)) diff --git a/Marlin/src/HAL/shared/backtrace/unwmemaccess.h b/Marlin/src/HAL/shared/backtrace/unwmemaccess.h index fe42bd9485e7..b911e343dc46 100644 --- a/Marlin/src/HAL/shared/backtrace/unwmemaccess.h +++ b/Marlin/src/HAL/shared/backtrace/unwmemaccess.h @@ -5,9 +5,9 @@ * This program is PUBLIC DOMAIN. * This means that there is no copyright and anyone is able to take a copy * for free and use it as they wish, with or without modifications, and in - * any context, commerically or otherwise. The only limitation is that I + * any context, commercially or otherwise. The only limitation is that I * don't guarantee that the software is fit for any purpose or accept any - * liablity for it's use or misuse - this software is without warranty. + * liability for its use or misuse - this software is without warranty. *************************************************************************** * File Description: Utility functions to access memory **************************************************************************/ diff --git a/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp b/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp new file mode 100644 index 000000000000..0f0f7c480727 --- /dev/null +++ b/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp @@ -0,0 +1,379 @@ +/** + * 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 + * 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 + * 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 . + * + */ + +/*************************************************************************** + * ARM CPU Exception handler + ***************************************************************************/ + +#if defined(__arm__) || defined(__thumb__) + + +/* + On ARM CPUs exception handling is quite powerful. + + By default, upon a crash, the CPU enters the handlers that have a higher priority than any other interrupts, + so, in effect, no (real) interrupt can "interrupt" the handler (it's acting like if interrupts were disabled). + + If the handler is not called as re-entrant (that is, if the crash is not happening inside an interrupt or an handler), + then it'll patch the return address to a dumping function (resume_from_fault) and save the crash state. + The CPU will exit the handler and, as such, re-allow the other interrupts, and jump to the dumping function. + In this function, the usual serial port (USB / HW) will be used to dump the crash (no special configuration required). + + The only case where it requires hardware UART is when it's crashing in an interrupt or a crash handler. + In that case, instead of returning to the resume_from_fault function (and thus, re-enabling interrupts), + it jumps to this function directly (so with interrupts disabled), after changing the behavior of the serial output + wrapper to use the HW uart (and in effect, calling MinSerial::init which triggers a warning if you are using + a USB serial port). + + In the case you have a USB serial port, this part will be disabled, and only that part (so that's the reason for + the warning). + This means that you can't have a crash report if the crash happens in an interrupt or an handler if you are using + a USB serial port since it's physically impossible. + You will get a crash report in all other cases. +*/ + +#include "exception_hook.h" +#include "../backtrace/backtrace.h" +#include "../HAL_MinSerial.h" + +#define HW_REG(X) (*((volatile unsigned long *)(X))) + +// Default function use the CPU VTOR register to get the vector table. +// Accessing the CPU VTOR register is done in assembly since it's the only way that's common to all current tool +unsigned long get_vtor() { return HW_REG(0xE000ED08); } // Even if it looks like an error, it is not an error +void * hook_get_hardfault_vector_address(unsigned vtor) { return (void*)(vtor + 0x03); } +void * hook_get_memfault_vector_address(unsigned vtor) { return (void*)(vtor + 0x04); } +void * hook_get_busfault_vector_address(unsigned vtor) { return (void*)(vtor + 0x05); } +void * hook_get_usagefault_vector_address(unsigned vtor) { return (void*)(vtor + 0x06); } +void * hook_get_reserved_vector_address(unsigned vtor) { return (void*)(vtor + 0x07); } + +// Common exception frame for ARM, should work for all ARM CPU +// Described here (modified for convenience): https://interrupt.memfault.com/blog/cortex-m-fault-debug +struct __attribute__((packed)) ContextStateFrame { + uint32_t r0; + uint32_t r1; + uint32_t r2; + uint32_t r3; + uint32_t r12; + uint32_t lr; + uint32_t pc; + uint32_t xpsr; +}; + +struct __attribute__((packed)) ContextSavedFrame { + uint32_t R0; + uint32_t R1; + uint32_t R2; + uint32_t R3; + uint32_t R12; + uint32_t LR; + uint32_t PC; + uint32_t XPSR; + + uint32_t CFSR; + uint32_t HFSR; + uint32_t DFSR; + uint32_t AFSR; + uint32_t MMAR; + uint32_t BFAR; + + uint32_t ESP; + uint32_t ELR; +}; + +#if DISABLED(STM32F0xx) + extern "C" + __attribute__((naked)) void CommonHandler_ASM() { + __asm__ __volatile__ ( + // Bit 2 of LR tells which stack pointer to use (either main or process, only main should be used anyway) + "tst lr, #4\n" + "ite eq\n" + "mrseq r0, msp\n" + "mrsne r0, psp\n" + // Save the LR in use when being interrupted + "mov r1, lr\n" + // Get the exception number from the ICSR register + "ldr r2, =0xE000ED00\n" + "ldr r2, [r2, #4]\n" + "b CommonHandler_C\n" + ); + } +#else // Cortex M0 does not support conditional mov and testing with a constant, so let's have a specific handler for it + extern "C" + __attribute__((naked)) void CommonHandler_ASM() { + __asm__ __volatile__ ( + ".syntax unified\n" + // Save the LR in use when being interrupted + "mov r1, lr\n" + // Get the exception number from the ICSR register + "ldr r2, =0xE000ED00\n" + "ldr r2, [r2, #4]\n" + "movs r0, #4\n" + "tst r1, r0\n" + "beq _MSP\n" + "mrs r0, psp\n" + "b CommonHandler_C\n" + "_MSP:\n" + "mrs r0, msp\n" + "b CommonHandler_C\n" + ); + } + + #if DISABLED(DYNAMIC_VECTORTABLE) // Cortex M0 requires the handler's address to be within 32kB to the actual function to be able to branch to it + extern "C" { + void __attribute__((naked, alias("CommonHandler_ASM"), nothrow)) __exc_hardfault(); + void __attribute__((naked, alias("CommonHandler_ASM"), nothrow)) __exc_busfault(); + void __attribute__((naked, alias("CommonHandler_ASM"), nothrow)) __exc_usagefault(); + void __attribute__((naked, alias("CommonHandler_ASM"), nothrow)) __exc_memmanage(); + void __attribute__((naked, alias("CommonHandler_ASM"), nothrow)) __exc_nmi(); + void __attribute__((naked, alias("CommonHandler_ASM"), nothrow)) __stm32reservedexception7(); + void __attribute__((naked, alias("CommonHandler_ASM"), nothrow)) __stm32reservedexception8(); + void __attribute__((naked, alias("CommonHandler_ASM"), nothrow)) __stm32reservedexception9(); + void __attribute__((naked, alias("CommonHandler_ASM"), nothrow)) __stm32reservedexception10(); + void __attribute__((naked, alias("CommonHandler_ASM"), nothrow)) __stm32reservedexception13(); + } + //TODO When going off from libmaple, you'll need to replace those by the one from STM32/HAL_MinSerial.cpp + #endif +#endif + +// Must be a macro to avoid creating a function frame +#define HALT_IF_DEBUGGING() \ + do { \ + if (HW_REG(0xE000EDF0) & _BV(0)) { \ + __asm("bkpt 1"); \ + } \ +} while (0) + +// Resume from a fault (if possible) so we can still use interrupt based code for serial output +// In that case, we will not jump back to the faulty code, but instead to a dumping code and then a +// basic loop with watchdog calling or manual resetting +static ContextSavedFrame savedFrame; +static uint8_t lastCause; +bool resume_from_fault() { + static const char* causestr[] = { "Thread", "Rsvd", "NMI", "Hard", "Mem", "Bus", "Usage", "7", "8", "9", "10", "SVC", "Dbg", "13", "PendSV", "SysTk", "IRQ" }; + // Reinit the serial link (might only work if implemented in each of your boards) + MinSerial::init(); + + MinSerial::TX("\n\n## Software Fault detected ##\n"); + MinSerial::TX("Cause: "); MinSerial::TX(causestr[min(lastCause, (uint8_t)16)]); MinSerial::TX('\n'); + + MinSerial::TX("R0 : "); MinSerial::TXHex(savedFrame.R0); MinSerial::TX('\n'); + MinSerial::TX("R1 : "); MinSerial::TXHex(savedFrame.R1); MinSerial::TX('\n'); + MinSerial::TX("R2 : "); MinSerial::TXHex(savedFrame.R2); MinSerial::TX('\n'); + MinSerial::TX("R3 : "); MinSerial::TXHex(savedFrame.R3); MinSerial::TX('\n'); + MinSerial::TX("R12 : "); MinSerial::TXHex(savedFrame.R12); MinSerial::TX('\n'); + MinSerial::TX("LR : "); MinSerial::TXHex(savedFrame.LR); MinSerial::TX('\n'); + MinSerial::TX("PC : "); MinSerial::TXHex(savedFrame.PC); MinSerial::TX('\n'); + MinSerial::TX("PSR : "); MinSerial::TXHex(savedFrame.XPSR); MinSerial::TX('\n'); + + // Configurable Fault Status Register + // Consists of MMSR, BFSR and UFSR + MinSerial::TX("CFSR : "); MinSerial::TXHex(savedFrame.CFSR); MinSerial::TX('\n'); + + // Hard Fault Status Register + MinSerial::TX("HFSR : "); MinSerial::TXHex(savedFrame.HFSR); MinSerial::TX('\n'); + + // Debug Fault Status Register + MinSerial::TX("DFSR : "); MinSerial::TXHex(savedFrame.DFSR); MinSerial::TX('\n'); + + // Auxiliary Fault Status Register + MinSerial::TX("AFSR : "); MinSerial::TXHex(savedFrame.AFSR); MinSerial::TX('\n'); + + // Read the Fault Address Registers. These may not contain valid values. + // Check BFARVALID/MMARVALID to see if they are valid values + // MemManage Fault Address Register + MinSerial::TX("MMAR : "); MinSerial::TXHex(savedFrame.MMAR); MinSerial::TX('\n'); + + // Bus Fault Address Register + MinSerial::TX("BFAR : "); MinSerial::TXHex(savedFrame.BFAR); MinSerial::TX('\n'); + + MinSerial::TX("ExcLR: "); MinSerial::TXHex(savedFrame.ELR); MinSerial::TX('\n'); + MinSerial::TX("ExcSP: "); MinSerial::TXHex(savedFrame.ESP); MinSerial::TX('\n'); + + // The stack pointer is pushed by 8 words upon entering an exception, so we need to revert this + backtrace_ex(savedFrame.ESP + 8*4, savedFrame.LR, savedFrame.PC); + + // Call the last resort function here + hook_last_resort_func(); + + const uint32_t start = millis(), end = start + 100; // 100ms should be enough + // We need to wait for the serial buffers to be output but we don't know for how long + // So we'll just need to refresh the watchdog for a while and then stop for the system to reboot + uint32_t last = start; + while (PENDING(last, end)) { + watchdog_refresh(); + while (millis() == last) { /* nada */ } + last = millis(); + MinSerial::TX('.'); + } + + // Reset now by reinstantiating the bootloader's vector table + HW_REG(0xE000ED08) = 0; + // Restart watchdog + #if DISABLED(USE_WATCHDOG) + // No watchdog, let's perform ARMv7 reset instead by writing to AIRCR register with VECTKEY set to SYSRESETREQ + HW_REG(0xE000ED0C) = (HW_REG(0xE000ED0C) & 0x0000FFFF) | 0x05FA0004; + #endif + + while(1) {} // Bad luck, nothing worked +} + +// Make sure the compiler does not optimize the frame argument away +extern "C" +__attribute__((optimize("O0"))) +void CommonHandler_C(ContextStateFrame * frame, unsigned long lr, unsigned long cause) { + + // If you are using it'll stop here + HALT_IF_DEBUGGING(); + + // Save the state to backtrace later on (don't call memcpy here since the stack can be corrupted) + savedFrame.R0 = frame->r0; + savedFrame.R1 = frame->r1; + savedFrame.R2 = frame->r2; + savedFrame.R3 = frame->r3; + savedFrame.R12 = frame->r12; + savedFrame.LR = frame->lr; + savedFrame.PC = frame->pc; + savedFrame.XPSR= frame->xpsr; + lastCause = cause & 0x1FF; + + volatile uint32_t &CFSR = HW_REG(0xE000ED28); + savedFrame.CFSR = CFSR; + savedFrame.HFSR = HW_REG(0xE000ED2C); + savedFrame.DFSR = HW_REG(0xE000ED30); + savedFrame.AFSR = HW_REG(0xE000ED3C); + savedFrame.MMAR = HW_REG(0xE000ED34); + savedFrame.BFAR = HW_REG(0xE000ED38); + savedFrame.ESP = (unsigned long)frame; // Even on return, this should not be overwritten by the CPU + savedFrame.ELR = lr; + + // First check if we can resume from this exception to our own handler safely + // If we can, then we don't need to disable interrupts and the usual serial code + // can be used + + //const uint32_t non_usage_fault_mask = 0x0000FFFF; + //const bool non_usage_fault_occurred = (CFSR & non_usage_fault_mask) != 0; + // the bottom 8 bits of the xpsr hold the exception number of the + // executing exception or 0 if the processor is in Thread mode + const bool faulted_from_exception = ((frame->xpsr & 0xFF) != 0); + 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 + frame->xpsr = _BV(24); // Need to clean the PSR register to thumb II only + MinSerial::force_using_default_output = true; + return; // The CPU will resume in our handler hopefully, and we'll try to use default serial output + } + + // Sorry, we need to emergency code here since the fault is too dangerous to recover from + MinSerial::force_using_default_output = false; + resume_from_fault(); +} + +void hook_cpu_exceptions() { + #if ENABLED(DYNAMIC_VECTORTABLE) + // On ARM 32bits CPU, the vector table is like this: + // 0x0C => Hardfault + // 0x10 => MemFault + // 0x14 => BusFault + // 0x18 => UsageFault + + // Unfortunately, it's usually run from flash, and we can't write to flash here directly to hook our instruction + // We could set an hardware breakpoint, and hook on the fly when it's being called, but this + // is hard to get right and would probably break debugger when attached + + // So instead, we'll allocate a new vector table filled with the previous value except + // for the fault we are interested in. + // Now, comes the issue to figure out what is the current vector table size + // There is nothing telling us what is the vector table as it's per-cpu vendor specific. + // BUT: we are being called at the end of the setup, so we assume the setup is done + // Thus, we can read the current vector table until we find an address that's not in flash, and it would mark the + // end of the vector table (skipping the fist entry obviously) + // The position of the program in flash is expected to be at 0x08xxx xxxx on all known platform for ARM and the + // flash size is available via register 0x1FFFF7E0 on STM32 family, but it's not the case for all ARM boards + // (accessing this register might trigger a fault if it's not implemented). + + // So we'll simply mask the top 8 bits of the first handler as an hint of being in the flash or not -that's poor and will + // probably break if the flash happens to be more than 128MB, but in this case, we are not magician, we need help from outside. + + unsigned long *vecAddr = (unsigned long*)get_vtor(); + SERIAL_ECHOPGM("Vector table addr: "); + SERIAL_PRINTLN(get_vtor(), PrintBase::Hex); + + #ifdef VECTOR_TABLE_SIZE + uint32_t vec_size = VECTOR_TABLE_SIZE; + alignas(128) static unsigned long vectable[VECTOR_TABLE_SIZE] ; + #else + #ifndef IS_IN_FLASH + #define IS_IN_FLASH(X) (((unsigned long)X & 0xFF000000) == 0x08000000) + #endif + + // When searching for the end of the vector table, this acts as a limit not to overcome + #ifndef VECTOR_TABLE_SENTINEL + #define VECTOR_TABLE_SENTINEL 80 + #endif + + // Find the vector table size + uint32_t vec_size = 1; + while (IS_IN_FLASH(vecAddr[vec_size]) && vec_size < VECTOR_TABLE_SENTINEL) + vec_size++; + + // We failed to find a valid vector table size, let's abort hooking up + if (vec_size == VECTOR_TABLE_SENTINEL) return; + // Poor method that's wasting RAM here, but allocating with malloc and alignment would be worst + // 128 bytes alignment is required for writing the VTOR register + alignas(128) static unsigned long vectable[VECTOR_TABLE_SENTINEL]; + + SERIAL_ECHOPGM("Detected vector table size: "); + SERIAL_PRINTLN(vec_size, PrintBase::Hex); + #endif + + uint32_t defaultFaultHandler = vecAddr[(unsigned)7]; + // Copy the current vector table into the new table + for (uint32_t i = 0; i < vec_size; i++) { + vectable[i] = vecAddr[i]; + // Replace all default handler by our own handler + if (vectable[i] == defaultFaultHandler) + vectable[i] = (unsigned long)&CommonHandler_ASM; + } + + // Let's hook now with our functions + vectable[(unsigned long)hook_get_hardfault_vector_address(0)] = (unsigned long)&CommonHandler_ASM; + vectable[(unsigned long)hook_get_memfault_vector_address(0)] = (unsigned long)&CommonHandler_ASM; + vectable[(unsigned long)hook_get_busfault_vector_address(0)] = (unsigned long)&CommonHandler_ASM; + vectable[(unsigned long)hook_get_usagefault_vector_address(0)] = (unsigned long)&CommonHandler_ASM; + + // Finally swap with our own vector table + // This is supposed to be atomic, but let's do that with interrupt disabled + + HW_REG(0xE000ED08) = (unsigned long)vectable | _BV32(29); // 29th bit is for telling the CPU the table is now in SRAM (should be present already) + + SERIAL_ECHOLNPGM("Installed fault handlers"); + #endif +} + +#endif // __arm__ || __thumb__ diff --git a/Marlin/src/HAL/shared/cpu_exception/exception_hook.cpp b/Marlin/src/HAL/shared/cpu_exception/exception_hook.cpp new file mode 100644 index 000000000000..93e80f3e8524 --- /dev/null +++ b/Marlin/src/HAL/shared/cpu_exception/exception_hook.cpp @@ -0,0 +1,28 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "exception_hook.h" + +void * __attribute__((weak)) hook_get_hardfault_vector_address(unsigned) { return 0; } +void * __attribute__((weak)) hook_get_memfault_vector_address(unsigned) { return 0; } +void * __attribute__((weak)) hook_get_busfault_vector_address(unsigned) { return 0; } +void * __attribute__((weak)) hook_get_usagefault_vector_address(unsigned) { return 0; } +void __attribute__((weak)) hook_last_resort_func() {} diff --git a/Marlin/src/HAL/shared/cpu_exception/exception_hook.h b/Marlin/src/HAL/shared/cpu_exception/exception_hook.h new file mode 100644 index 000000000000..70d943470457 --- /dev/null +++ b/Marlin/src/HAL/shared/cpu_exception/exception_hook.h @@ -0,0 +1,54 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/* Here is the expected behavior of a system producing a CPU exception with this hook installed: + 1. Before the system is crashed + 1.1 Upon validation (not done yet in this code, but we could be using DEBUG flags here to allow/disallow hooking) + 1.2 Install the hook by overwriting the vector table exception handler with the hooked function + 2. Upon system crash (for example, by a dereference of a NULL pointer or anything else) + 2.1 The CPU triggers its exception and jump into the vector table for the exception type + 2.2 Instead of finding the default handler, it finds the updated pointer to our hook + 2.3 The CPU jumps into our hook function (likely a naked function to keep all information about crash point intact) + 2.4 The hook (naked) function saves the important registers (stack pointer, program counter, current mode) and jumps to a common exception handler (in C) + 2.5 The common exception handler dumps the registers on the serial link and perform a backtrace around the crashing point + 2.6 Once the backtrace is performed the last resort function is called (platform specific). + On some platform with a LCD screen, this might display the crash information as a QR code or as text for the + user to capture by taking a picture + 2.7 The CPU is reset and/or halted by triggering a debug breakpoint if a debugger is attached */ + +// Hook into CPU exception interrupt table to call the backtracing code upon an exception +// Most platform will simply do nothing here, but those who can will install/overwrite the default exception handler +// with a more performant exception handler +void hook_cpu_exceptions(); + +// Some platform might deal without a hard fault handler, in that case, return 0 in your platform here or skip implementing it +void * __attribute__((weak)) hook_get_hardfault_vector_address(unsigned base_address); +// Some platform might deal without a memory management fault handler, in that case, return 0 in your platform here or skip implementing it +void * __attribute__((weak)) hook_get_memfault_vector_address(unsigned base_address); +// Some platform might deal without a bus fault handler, in that case, return 0 in your platform here or skip implementing it +void * __attribute__((weak)) hook_get_busfault_vector_address(unsigned base_address); +// Some platform might deal without a usage fault handler, in that case, return 0 in your platform here or skip implementing it +void * __attribute__((weak)) hook_get_usagefault_vector_address(unsigned base_address); + +// Last resort function that can be called after the exception handler was called. +void __attribute__((weak)) hook_last_resort_func(); diff --git a/Marlin/src/HAL/shared/eeprom_api.h b/Marlin/src/HAL/shared/eeprom_api.h index 6445f7a4aae4..1f38639930dc 100644 --- a/Marlin/src/HAL/shared/eeprom_api.h +++ b/Marlin/src/HAL/shared/eeprom_api.h @@ -45,11 +45,11 @@ class PersistentStore { // Read one or more bytes of data and update the CRC // Return 'true' on read error - static bool read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing=true); + static bool read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing=true); // Write one or more bytes of data // Return 'true' on write error - static inline bool write_data(const int pos, const uint8_t* value, const size_t size=sizeof(uint8_t)) { + static inline bool write_data(const int pos, const uint8_t *value, const size_t size=sizeof(uint8_t)) { int data_pos = pos; uint16_t crc = 0; return write_data(data_pos, value, size, &crc); @@ -61,7 +61,7 @@ class PersistentStore { // Read one or more bytes of data // Return 'true' on read error - static inline bool read_data(const int pos, uint8_t* value, const size_t size=1) { + static inline bool read_data(const int pos, uint8_t *value, const size_t size=1) { int data_pos = pos; uint16_t crc = 0; return read_data(data_pos, value, size, &crc); diff --git a/Marlin/src/HAL/shared/eeprom_if.h b/Marlin/src/HAL/shared/eeprom_if.h index e44da801dfbf..e496de2a03c6 100644 --- a/Marlin/src/HAL/shared/eeprom_if.h +++ b/Marlin/src/HAL/shared/eeprom_if.h @@ -25,5 +25,5 @@ // EEPROM // void eeprom_init(); -void eeprom_write_byte(uint8_t *pos, unsigned char value); +void eeprom_write_byte(uint8_t *pos, uint8_t value); uint8_t eeprom_read_byte(uint8_t *pos); diff --git a/Marlin/src/HAL/shared/eeprom_if_i2c.cpp b/Marlin/src/HAL/shared/eeprom_if_i2c.cpp index cc22bf7d986f..6b559e234b4c 100644 --- a/Marlin/src/HAL/shared/eeprom_if_i2c.cpp +++ b/Marlin/src/HAL/shared/eeprom_if_i2c.cpp @@ -30,9 +30,21 @@ #if ENABLED(I2C_EEPROM) #include "eeprom_if.h" -#include -void eeprom_init() { Wire.begin(); } +#if ENABLED(SOFT_I2C_EEPROM) + #include + SlowSoftWire Wire = SlowSoftWire(I2C_SDA_PIN, I2C_SCL_PIN, true); +#else + #include +#endif + +void eeprom_init() { + Wire.begin( + #if PINS_EXIST(I2C_SCL, I2C_SDA) && DISABLED(SOFT_I2C_EEPROM) + uint8_t(I2C_SDA_PIN), uint8_t(I2C_SCL_PIN) + #endif + ); +} #if ENABLED(USE_SHARED_EEPROM) @@ -49,12 +61,28 @@ static constexpr uint8_t eeprom_device_address = I2C_ADDRESS(EEPROM_DEVICE_ADDRE // Public functions // ------------------------ -void eeprom_write_byte(uint8_t *pos, unsigned char value) { +#define SMALL_EEPROM (MARLIN_EEPROM_SIZE <= 2048) + +// Combine Address high bits into the device address on <=16Kbit (2K) and >512Kbit (64K) EEPROMs. +// Note: MARLIN_EEPROM_SIZE is specified in bytes, whereas EEPROM model numbers refer to bits. +// e.g., The "16" in BL24C16 indicates a 16Kbit (2KB) size. +static uint8_t _eeprom_calc_device_address(uint8_t * const pos) { + const unsigned eeprom_address = (unsigned)pos; + return (SMALL_EEPROM || MARLIN_EEPROM_SIZE > 65536) + ? uint8_t(eeprom_device_address | ((eeprom_address >> (SMALL_EEPROM ? 8 : 16)) & 0x07)) + : eeprom_device_address; +} + +static void _eeprom_begin(uint8_t * const pos) { const unsigned eeprom_address = (unsigned)pos; + Wire.beginTransmission(_eeprom_calc_device_address(pos)); + if (!SMALL_EEPROM) + Wire.write(uint8_t((eeprom_address >> 8) & 0xFF)); // Address High, if needed + Wire.write(uint8_t(eeprom_address & 0xFF)); // Address Low +} - Wire.beginTransmission(eeprom_device_address); - Wire.write(int(eeprom_address >> 8)); // MSB - Wire.write(int(eeprom_address & 0xFF)); // LSB +void eeprom_write_byte(uint8_t *pos, uint8_t value) { + _eeprom_begin(pos); Wire.write(value); Wire.endTransmission(); @@ -64,13 +92,9 @@ void eeprom_write_byte(uint8_t *pos, unsigned char value) { } uint8_t eeprom_read_byte(uint8_t *pos) { - const unsigned eeprom_address = (unsigned)pos; - - Wire.beginTransmission(eeprom_device_address); - Wire.write(int(eeprom_address >> 8)); // MSB - Wire.write(int(eeprom_address & 0xFF)); // LSB + _eeprom_begin(pos); Wire.endTransmission(); - Wire.requestFrom(eeprom_device_address, (byte)1); + Wire.requestFrom(_eeprom_calc_device_address(pos), (byte)1); return Wire.available() ? Wire.read() : 0xFF; } diff --git a/Marlin/src/HAL/shared/eeprom_if_spi.cpp b/Marlin/src/HAL/shared/eeprom_if_spi.cpp index a341fef9de97..6aa6e0909623 100644 --- a/Marlin/src/HAL/shared/eeprom_if_spi.cpp +++ b/Marlin/src/HAL/shared/eeprom_if_spi.cpp @@ -43,44 +43,41 @@ void eeprom_init() {} #define EEPROM_WRITE_DELAY 7 #endif -uint8_t eeprom_read_byte(uint8_t* pos) { - uint8_t v; - uint8_t eeprom_temp[3]; - - // set read location - // begin transmission from device - eeprom_temp[0] = CMD_READ; - eeprom_temp[1] = ((unsigned)pos>>8) & 0xFF; // addr High - eeprom_temp[2] = (unsigned)pos& 0xFF; // addr Low - WRITE(SPI_EEPROM1_CS, HIGH); - WRITE(SPI_EEPROM1_CS, LOW); +static void _eeprom_begin(uint8_t * const pos, const uint8_t cmd) { + const uint8_t eeprom_temp[3] = { + cmd, + (unsigned(pos) >> 8) & 0xFF, // Address High + unsigned(pos) & 0xFF // Address Low + }; + WRITE(SPI_EEPROM1_CS, HIGH); // Usually free already + WRITE(SPI_EEPROM1_CS, LOW); // Activate the Bus spiSend(SPI_CHAN_EEPROM1, eeprom_temp, 3); + // Leave the Bus in-use +} + +uint8_t eeprom_read_byte(uint8_t *pos) { + _eeprom_begin(pos, CMD_READ); // Set read location and begin transmission + + const uint8_t v = spiRec(SPI_CHAN_EEPROM1); // After READ a value sits on the Bus + + WRITE(SPI_EEPROM1_CS, HIGH); // Done with device - v = spiRec(SPI_CHAN_EEPROM1); - WRITE(SPI_EEPROM1_CS, HIGH); return v; } -void eeprom_write_byte(uint8_t* pos, uint8_t value) { - uint8_t eeprom_temp[3]; - - /*write enable*/ - eeprom_temp[0] = CMD_WREN; - WRITE(SPI_EEPROM1_CS, LOW); - spiSend(SPI_CHAN_EEPROM1, eeprom_temp, 1); - WRITE(SPI_EEPROM1_CS, HIGH); - delay(1); - - /*write addr*/ - eeprom_temp[0] = CMD_WRITE; - eeprom_temp[1] = ((unsigned)pos>>8) & 0xFF; //addr High - eeprom_temp[2] = (unsigned)pos & 0xFF; //addr Low +void eeprom_write_byte(uint8_t *pos, uint8_t value) { + const uint8_t eeprom_temp = CMD_WREN; WRITE(SPI_EEPROM1_CS, LOW); - spiSend(SPI_CHAN_EEPROM1, eeprom_temp, 3); + spiSend(SPI_CHAN_EEPROM1, &eeprom_temp, 1); // Write Enable + + WRITE(SPI_EEPROM1_CS, HIGH); // Done with the Bus + delay(1); // For a small amount of time + + _eeprom_begin(pos, CMD_WRITE); // Set write address and begin transmission - spiSend(SPI_CHAN_EEPROM1, value); - WRITE(SPI_EEPROM1_CS, HIGH); - delay(EEPROM_WRITE_DELAY); // wait for page write to complete + spiSend(SPI_CHAN_EEPROM1, value); // Send the value to be written + WRITE(SPI_EEPROM1_CS, HIGH); // Done with the Bus + delay(EEPROM_WRITE_DELAY); // Give page write time to complete } #endif // USE_SHARED_EEPROM diff --git a/Marlin/src/HAL/shared/progmem.h b/Marlin/src/HAL/shared/progmem.h new file mode 100644 index 000000000000..539d02705e97 --- /dev/null +++ b/Marlin/src/HAL/shared/progmem.h @@ -0,0 +1,189 @@ +/** + * 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 + +#ifndef __AVR__ +#ifndef __PGMSPACE_H_ +// This define should prevent reading the system pgmspace.h if included elsewhere +// This is not normally needed. +#define __PGMSPACE_H_ 1 +#endif + +#ifndef PROGMEM +#define PROGMEM +#endif +#ifndef PGM_P +#define PGM_P const char * +#endif +#ifndef PSTR +#define PSTR(str) (str) +#endif +#ifndef F +#define F(str) (str) +#endif +#ifndef _SFR_BYTE +#define _SFR_BYTE(n) (n) +#endif +#ifndef memchr_P +#define memchr_P(str, c, len) memchr((str), (c), (len)) +#endif +#ifndef memcmp_P +#define memcmp_P(a, b, n) memcmp((a), (b), (n)) +#endif +#ifndef memcpy_P +#define memcpy_P(dest, src, num) memcpy((dest), (src), (num)) +#endif +#ifndef memmem_P +#define memmem_P(a, alen, b, blen) memmem((a), (alen), (b), (blen)) +#endif +#ifndef memrchr_P +#define memrchr_P(str, val, len) memrchr((str), (val), (len)) +#endif +#ifndef strcat_P +#define strcat_P(dest, src) strcat((dest), (src)) +#endif +#ifndef strchr_P +#define strchr_P(str, c) strchr((str), (c)) +#endif +#ifndef strchrnul_P +#define strchrnul_P(str, c) strchrnul((str), (c)) +#endif +#ifndef strcmp_P +#define strcmp_P(a, b) strcmp((a), (b)) +#endif +#ifndef strcpy_P +#define strcpy_P(dest, src) strcpy((dest), (src)) +#endif +#ifndef strcasecmp_P +#define strcasecmp_P(a, b) strcasecmp((a), (b)) +#endif +#ifndef strcasestr_P +#define strcasestr_P(a, b) strcasestr((a), (b)) +#endif +#ifndef strlcat_P +#define strlcat_P(dest, src, len) strlcat((dest), (src), (len)) +#endif +#ifndef strlcpy_P +#define strlcpy_P(dest, src, len) strlcpy((dest), (src), (len)) +#endif +#ifndef strlen_P +#define strlen_P(s) strlen((const char *)(s)) +#endif +#ifndef strnlen_P +#define strnlen_P(str, len) strnlen((str), (len)) +#endif +#ifndef strncmp_P +#define strncmp_P(a, b, n) strncmp((a), (b), (n)) +#endif +#ifndef strncasecmp_P +#define strncasecmp_P(a, b, n) strncasecmp((a), (b), (n)) +#endif +#ifndef strncat_P +#define strncat_P(a, b, n) strncat((a), (b), (n)) +#endif +#ifndef strncpy_P +#define strncpy_P(a, b, n) strncpy((a), (b), (n)) +#endif +#ifndef strpbrk_P +#define strpbrk_P(str, chrs) strpbrk((str), (chrs)) +#endif +#ifndef strrchr_P +#define strrchr_P(str, c) strrchr((str), (c)) +#endif +#ifndef strsep_P +#define strsep_P(strp, delim) strsep((strp), (delim)) +#endif +#ifndef strspn_P +#define strspn_P(str, chrs) strspn((str), (chrs)) +#endif +#ifndef strstr_P +#define strstr_P(a, b) strstr((a), (b)) +#endif +#ifndef sprintf_P +#define sprintf_P(s, ...) sprintf((s), __VA_ARGS__) +#endif +#ifndef vfprintf_P +#define vfprintf_P(s, ...) vfprintf((s), __VA_ARGS__) +#endif +#ifndef printf_P +#define printf_P(...) printf(__VA_ARGS__) +#endif +#ifndef snprintf_P +#define snprintf_P(s, n, ...) snprintf((s), (n), __VA_ARGS__) +#endif +#ifndef vsprintf_P +#define vsprintf_P(s, ...) vsprintf((s),__VA_ARGS__) +#endif +#ifndef vsnprintf_P +#define vsnprintf_P(s, n, ...) vsnprintf((s), (n),__VA_ARGS__) +#endif +#ifndef fprintf_P +#define fprintf_P(s, ...) fprintf((s), __VA_ARGS__) +#endif + +#ifndef pgm_read_byte +#define pgm_read_byte(addr) (*(const unsigned char *)(addr)) +#endif +#ifndef pgm_read_word +#define pgm_read_word(addr) (*(const unsigned short *)(addr)) +#endif +#ifndef pgm_read_dword +#define pgm_read_dword(addr) (*(const unsigned long *)(addr)) +#endif +#ifndef pgm_read_float +#define pgm_read_float(addr) (*(const float *)(addr)) +#endif + +#ifndef pgm_read_byte_near +#define pgm_read_byte_near(addr) pgm_read_byte(addr) +#endif +#ifndef pgm_read_word_near +#define pgm_read_word_near(addr) pgm_read_word(addr) +#endif +#ifndef pgm_read_dword_near +#define pgm_read_dword_near(addr) pgm_read_dword(addr) +#endif +#ifndef pgm_read_float_near +#define pgm_read_float_near(addr) pgm_read_float(addr) +#endif +#ifndef pgm_read_byte_far +#define pgm_read_byte_far(addr) pgm_read_byte(addr) +#endif +#ifndef pgm_read_word_far +#define pgm_read_word_far(addr) pgm_read_word(addr) +#endif +#ifndef pgm_read_dword_far +#define pgm_read_dword_far(addr) pgm_read_dword(addr) +#endif +#ifndef pgm_read_float_far +#define pgm_read_float_far(addr) pgm_read_float(addr) +#endif + +#ifndef pgm_read_pointer +#define pgm_read_pointer +#endif + +// Fix bug in pgm_read_ptr +#undef pgm_read_ptr +#define pgm_read_ptr(addr) (*((void**)(addr))) + +#endif // __AVR__ diff --git a/Marlin/src/HAL/shared/servo.h b/Marlin/src/HAL/shared/servo.h index 6d850da851d2..c2560a853832 100644 --- a/Marlin/src/HAL/shared/servo.h +++ b/Marlin/src/HAL/shared/servo.h @@ -76,8 +76,6 @@ #include "../LPC1768/Servo.h" #elif defined(__STM32F1__) || defined(TARGET_STM32F1) #include "../STM32F1/Servo.h" -#elif defined(STM32GENERIC) && defined(STM32F4) - #include "../STM32_F4_F7/Servo.h" #elif defined(ARDUINO_ARCH_STM32) #include "../STM32/Servo.h" #elif defined(ARDUINO_ARCH_ESP32) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 3a20cf3ee330..acb7e9c39a8a 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -36,6 +36,7 @@ #include "HAL/shared/Delay.h" #include "HAL/shared/esp_wifi.h" +#include "HAL/shared/cpu_exception/exception_hook.h" #ifdef ARDUINO #include @@ -43,6 +44,7 @@ #include #include "core/utility.h" + #include "module/motion.h" #include "module/planner.h" #include "module/endstops.h" @@ -57,24 +59,32 @@ #include "gcode/parser.h" #include "gcode/queue.h" +#include "feature/pause.h" #include "sd/cardreader.h" -#include "lcd/ultralcd.h" -#if HAS_TOUCH_XPT2046 +#include "lcd/marlinui.h" +#if HAS_TOUCH_BUTTONS #include "lcd/touch/touch_buttons.h" #endif #if HAS_TFT_LVGL_UI - #include "lcd/extui/lib/mks_ui/tft_lvgl_configuration.h" - #include "lcd/extui/lib/mks_ui/draw_ui.h" - #include "lcd/extui/lib/mks_ui/mks_hardware_test.h" + #include "lcd/extui/mks_ui/tft_lvgl_configuration.h" + #include "lcd/extui/mks_ui/draw_ui.h" + #include "lcd/extui/mks_ui/mks_hardware.h" #include #endif #if ENABLED(DWIN_CREALITY_LCD) - #include "lcd/dwin/e3v2/dwin.h" - #include "lcd/dwin/dwin_lcd.h" - #include "lcd/dwin/e3v2/rotary_encoder.h" + #include "lcd/e3v2/creality/dwin.h" + #include "lcd/e3v2/creality/rotary_encoder.h" +#endif + +#if ENABLED(EXTENSIBLE_UI) + #include "lcd/extui/ui_api.h" +#endif + +#if HAS_ETHERNET + #include "feature/ethernet.h" #endif #if ENABLED(IIC_BL24CXX_EEPROM) @@ -125,13 +135,12 @@ #include "module/servo.h" #endif -#if ENABLED(HAS_MOTOR_CURRENT_DAC) +#if HAS_MOTOR_CURRENT_DAC #include "feature/dac/stepper_dac.h" #endif #if ENABLED(EXPERIMENTAL_I2CBUS) #include "feature/twibus.h" - TWIBus i2c; #endif #if ENABLED(I2C_POSITION_ENCODERS) @@ -165,8 +174,8 @@ #include "feature/bedlevel/bedlevel.h" #endif -#if BOTH(ADVANCED_PAUSE_FEATURE, PAUSE_PARK_NO_STEPPER_TIMEOUT) - #include "feature/pause.h" +#if ENABLED(GCODE_REPEAT_MARKERS) + #include "feature/repeat.h" #endif #if ENABLED(POWER_LOSS_RECOVERY) @@ -181,7 +190,7 @@ #include "feature/runout.h" #endif -#if HAS_Z_SERVO_PROBE +#if EITHER(PROBE_TARE, HAS_Z_SERVO_PROBE) #include "module/probe.h" #endif @@ -201,16 +210,14 @@ #include "feature/fanmux.h" #endif -#if DO_SWITCH_EXTRUDER || ANY(SWITCHING_NOZZLE, PARKING_EXTRUDER, MAGNETIC_PARKING_EXTRUDER, ELECTROMAGNETIC_SWITCHING_TOOLHEAD, SWITCHING_TOOLHEAD) - #include "module/tool_change.h" -#endif +#include "module/tool_change.h" #if ENABLED(USE_CONTROLLER_FAN) #include "feature/controllerfan.h" #endif -#if ENABLED(PRUSA_MMU2) - #include "feature/mmu2/mmu2.h" +#if HAS_PRUSA_MMU2 + #include "feature/mmu/mmu2.h" #endif #if HAS_L64XX @@ -221,18 +228,15 @@ #include "feature/password/password.h" #endif -PGMSTR(NUL_STR, ""); +#if ENABLED(DGUS_LCD_UI_MKS) + #include "lcd/extui/dgus/DGUSScreenHandler.h" +#endif + +#if HAS_DRIVER_SAFE_POWER_PROTECT + #include "feature/stepper_driver_safety.h" +#endif + PGMSTR(M112_KILL_STR, "M112 Shutdown"); -PGMSTR(G28_STR, "G28"); -PGMSTR(M21_STR, "M21"); -PGMSTR(M23_STR, "M23 %s"); -PGMSTR(M24_STR, "M24"); -PGMSTR(SP_P_STR, " P"); PGMSTR(SP_T_STR, " T"); -PGMSTR(X_STR, "X"); PGMSTR(Y_STR, "Y"); PGMSTR(Z_STR, "Z"); PGMSTR(E_STR, "E"); -PGMSTR(X_LBL, "X:"); PGMSTR(Y_LBL, "Y:"); PGMSTR(Z_LBL, "Z:"); PGMSTR(E_LBL, "E:"); -PGMSTR(SP_A_STR, " A"); PGMSTR(SP_B_STR, " B"); PGMSTR(SP_C_STR, " C"); -PGMSTR(SP_X_STR, " X"); PGMSTR(SP_Y_STR, " Y"); PGMSTR(SP_Z_STR, " Z"); PGMSTR(SP_E_STR, " E"); -PGMSTR(SP_X_LBL, " X:"); PGMSTR(SP_Y_LBL, " Y:"); PGMSTR(SP_Z_LBL, " Z:"); PGMSTR(SP_E_LBL, " E:"); MarlinState marlin_state = MF_INITIALIZING; @@ -244,7 +248,7 @@ bool wait_for_heatup = true; bool wait_for_user; // = false; void wait_for_user_response(millis_t ms/*=0*/, const bool no_sleep/*=false*/) { - TERN(ADVANCED_PAUSE_FEATURE,,UNUSED(no_sleep)); + UNUSED(no_sleep); KEEPALIVE_STATE(PAUSED_FOR_USER); wait_for_user = true; if (ms) ms += millis(); // expire time @@ -255,40 +259,12 @@ bool wait_for_heatup = true; #endif -#if PIN_EXISTS(CHDK) - extern millis_t chdk_timeout; -#endif - -#if ENABLED(I2C_POSITION_ENCODERS) - I2CPositionEncodersMgr I2CPEM; -#endif - /** * *************************************************************************** * ******************************** FUNCTIONS ******************************** * *************************************************************************** */ -void setup_killpin() { - #if HAS_KILL - #if KILL_PIN_STATE - SET_INPUT_PULLDOWN(KILL_PIN); - #else - SET_INPUT_PULLUP(KILL_PIN); - #endif - #endif -} - -void setup_powerhold() { - #if HAS_SUICIDE - OUT_WRITE(SUICIDE_PIN, !SUICIDE_PIN_INVERTING); - #endif - #if ENABLED(PSU_CONTROL) - powersupply_on = ENABLED(PSU_DEFAULT_OFF); - if (ENABLED(PSU_DEFAULT_OFF)) PSU_OFF(); else PSU_ON(); - #endif -} - /** * Stepper Reset (RigidBoard, et.al.) */ @@ -297,18 +273,6 @@ void setup_powerhold() { void enableStepperDrivers() { SET_INPUT(STEPPER_RESET_PIN); } // Set to input, allowing pullups to pull the pin high #endif -#if ENABLED(EXPERIMENTAL_I2CBUS) && I2C_SLAVE_ADDRESS > 0 - - void i2c_on_receive(int bytes) { // just echo all bytes received to serial - i2c.receive(bytes); - } - - void i2c_on_request() { // just send dummy data for now - i2c.reply("Hello World!\n"); - } - -#endif - /** * Sensitive pin test for M42, M226 */ @@ -318,29 +282,28 @@ void setup_powerhold() { #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wnarrowing" +#ifndef RUNTIME_ONLY_ANALOG_TO_DIGITAL + template + constexpr pin_t OnlyPins<_SP_END, D...>::table[sizeof...(D)]; +#endif + bool pin_is_protected(const pin_t pin) { - static const pin_t sensitive_pins[] PROGMEM = SENSITIVE_PINS; - LOOP_L_N(i, COUNT(sensitive_pins)) { - pin_t sensitive_pin; - memcpy_P(&sensitive_pin, &sensitive_pins[i], sizeof(pin_t)); - if (pin == sensitive_pin) return true; + #ifdef RUNTIME_ONLY_ANALOG_TO_DIGITAL + static const pin_t sensitive_pins[] PROGMEM = { SENSITIVE_PINS }; + const size_t pincount = COUNT(sensitive_pins); + #else + static constexpr size_t pincount = OnlyPins::size; + static const pin_t (&sensitive_pins)[pincount] PROGMEM = OnlyPins::table; + #endif + LOOP_L_N(i, pincount) { + 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; } return false; } #pragma GCC diagnostic pop -void protected_pin_err() { - SERIAL_ERROR_MSG(STR_ERR_PROTECTED_PIN); -} - -void quickstop_stepper() { - planner.quick_stop(); - planner.synchronize(); - set_current_from_steppers_for_axis(ALL_AXES); - sync_plan_position(); -} - void enable_e_steppers() { #define _ENA_E(N) ENABLE_AXIS_E##N(); REPEAT(E_STEPPERS, _ENA_E) @@ -351,7 +314,12 @@ void enable_all_steppers() { ENABLE_AXIS_X(); ENABLE_AXIS_Y(); ENABLE_AXIS_Z(); + ENABLE_AXIS_I(); // Marlin 6-axis support by DerAndere (https://github.com/DerAndere1/Marlin/wiki) + ENABLE_AXIS_J(); + ENABLE_AXIS_K(); enable_e_steppers(); + + TERN_(EXTENSIBLE_UI, ExtUI::onSteppersEnabled()); } void disable_e_steppers() { @@ -362,7 +330,7 @@ void disable_e_steppers() { void disable_e_stepper(const uint8_t e) { #define _CASE_DIS_E(N) case N: DISABLE_AXIS_E##N(); break; switch (e) { - REPEAT(EXTRUDERS, _CASE_DIS_E) + REPEAT(E_STEPPERS, _CASE_DIS_E) } } @@ -370,57 +338,23 @@ void disable_all_steppers() { DISABLE_AXIS_X(); DISABLE_AXIS_Y(); DISABLE_AXIS_Z(); + DISABLE_AXIS_I(); + DISABLE_AXIS_J(); + DISABLE_AXIS_K(); disable_e_steppers(); -} - -#if ENABLED(G29_RETRY_AND_RECOVER) - - void event_probe_failure() { - #ifdef ACTION_ON_G29_FAILURE - host_action(PSTR(ACTION_ON_G29_FAILURE)); - #endif - #ifdef G29_FAILURE_COMMANDS - gcode.process_subcommands_now_P(PSTR(G29_FAILURE_COMMANDS)); - #endif - #if ENABLED(G29_HALT_ON_FAILURE) - #ifdef ACTION_ON_CANCEL - host_action_cancel(); - #endif - kill(GET_TEXT(MSG_LCD_PROBING_FAILED)); - #endif - } - - void event_probe_recover() { - TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_INFO, PSTR("G29 Retrying"), DISMISS_STR)); - #ifdef ACTION_ON_G29_RECOVER - host_action(PSTR(ACTION_ON_G29_RECOVER)); - #endif - #ifdef G29_RECOVER_COMMANDS - gcode.process_subcommands_now_P(PSTR(G29_RECOVER_COMMANDS)); - #endif - } - -#endif -#if ENABLED(ADVANCED_PAUSE_FEATURE) - #include "feature/pause.h" -#else - constexpr bool did_pause_print = false; -#endif + TERN_(EXTENSIBLE_UI, ExtUI::onSteppersDisabled()); +} /** - * A Print Job exists when the timer is running or SD printing + * A Print Job exists when the timer is running or SD is printing */ -bool printJobOngoing() { - return print_job_timer.isRunning() || IS_SD_PRINTING(); -} +bool printJobOngoing() { return print_job_timer.isRunning() || IS_SD_PRINTING(); } /** - * Printing is active when the print job timer is running + * Printing is active when a job is underway but not paused */ -bool printingIsActive() { - return !did_pause_print && (print_job_timer.isRunning() || IS_SD_PRINTING()); -} +bool printingIsActive() { return !did_pause_print && printJobOngoing(); } /** * Printing is paused according to SD or host indicators @@ -431,6 +365,7 @@ bool printingIsPaused() { void startOrResumeJob() { if (!printingIsPaused()) { + TERN_(GCODE_REPEAT_MARKERS, repeat.reset()); TERN_(CANCEL_OBJECTS, cancelable.reset()); TERN_(LCD_SHOW_E_TOTAL, e_move_accumulator = 0); #if BOTH(LCD_SET_PROGRESS_MANUALLY, USE_M73_REMAINING_TIME) @@ -443,20 +378,22 @@ void startOrResumeJob() { #if ENABLED(SDSUPPORT) inline void abortSDPrinting() { - card.endFilePrint(TERN_(SD_RESORT, true)); + IF_DISABLED(NO_SD_AUTOSTART, card.autofile_cancel()); + card.abortFilePrintNow(TERN_(SD_RESORT, true)); + queue.clear(); quickstop_stepper(); - print_job_timer.stop(); - #if DISABLED(SD_ABORT_NO_COOLDOWN) - thermalManager.disable_all_heaters(); - #endif - #if !HAS_CUTTER - thermalManager.zero_fan_speeds(); - #else - cutter.kill(); // Full cutter shutdown including ISR control - #endif + + print_job_timer.abort(); + + IF_DISABLED(SD_ABORT_NO_COOLDOWN, thermalManager.disable_all_heaters()); + + TERN(HAS_CUTTER, cutter.kill(), thermalManager.zero_fan_speeds()); // Full cutter shutdown including ISR control + wait_for_heatup = false; + TERN_(POWER_LOSS_RECOVERY, recovery.purge()); + #ifdef EVENT_GCODE_SD_ABORT queue.inject_P(PSTR(EVENT_GCODE_SD_ABORT)); #endif @@ -465,9 +402,10 @@ void startOrResumeJob() { } inline void finishSDPrinting() { - if (queue.enqueue_one_P(PSTR("M1001"))) { - marlin_state = MF_RUNNING; + if (queue.enqueue_one_P(PSTR("M1001"))) { // Keep trying until it gets queued + marlin_state = MF_RUNNING; // Signal to stop trying TERN_(PASSWORD_AFTER_SD_PRINT_END, password.lock_machine()); + TERN_(DGUS_LCD_UI_MKS, ScreenHandler.SDPrintingFinished()); } } @@ -481,31 +419,30 @@ void startOrResumeJob() { * - Check if CHDK_PIN needs to go LOW * - Check for KILL button held down * - Check for HOME button held down + * - Check for CUSTOM USER button held down * - Check if cooling fan needs to be switched on * - Check if an idle but hot extruder needs filament extruded (EXTRUDER_RUNOUT_PREVENT) * - Pulse FET_SAFETY_PIN if it exists */ -inline void manage_inactivity(const bool ignore_stepper_queue=false) { +inline void manage_inactivity(const bool no_stepper_sleep=false) { - if (queue.length < BUFSIZE) queue.get_available_commands(); + queue.get_available_commands(); const millis_t ms = millis(); - // Prevent steppers timing-out in the middle of M600 - // unless PAUSE_PARK_NO_STEPPER_TIMEOUT is disabled - const bool parked_or_ignoring = ignore_stepper_queue || - (BOTH(ADVANCED_PAUSE_FEATURE, PAUSE_PARK_NO_STEPPER_TIMEOUT) && did_pause_print); + // Prevent steppers timing-out + const bool do_reset_timeout = no_stepper_sleep + || TERN0(PAUSE_PARK_NO_STEPPER_TIMEOUT, did_pause_print); // Reset both the M18/M84 activity timeout and the M85 max 'kill' timeout - if (parked_or_ignoring) gcode.reset_stepper_timeout(ms); + if (do_reset_timeout) gcode.reset_stepper_timeout(ms); if (gcode.stepper_max_timed_out(ms)) { - SERIAL_ERROR_START(); - SERIAL_ECHOLNPAIR(STR_KILL_INACTIVE_TIME, parser.command_ptr); + SERIAL_ERROR_MSG(STR_KILL_INACTIVE_TIME, parser.command_ptr); kill(); } - // M18 / M94 : Handle steppers inactive time timeout + // M18 / M84 : Handle steppers inactive time timeout if (gcode.stepper_inactive_time) { static bool already_shutdown_steppers; // = false @@ -514,7 +451,7 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) { // activity timeout and the M85 max 'kill' timeout if (planner.has_blocks_queued()) gcode.reset_stepper_timeout(ms); - else if (!parked_or_ignoring && gcode.stepper_inactive_timeout()) { + else if (!do_reset_timeout && gcode.stepper_inactive_timeout()) { if (!already_shutdown_steppers) { already_shutdown_steppers = true; // L6470 SPI will consume 99% of free time without this @@ -522,6 +459,9 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) { if (ENABLED(DISABLE_INACTIVE_X)) DISABLE_AXIS_X(); if (ENABLED(DISABLE_INACTIVE_Y)) DISABLE_AXIS_Y(); if (ENABLED(DISABLE_INACTIVE_Z)) DISABLE_AXIS_Z(); + if (ENABLED(DISABLE_INACTIVE_I)) DISABLE_AXIS_I(); + if (ENABLED(DISABLE_INACTIVE_J)) DISABLE_AXIS_J(); + if (ENABLED(DISABLE_INACTIVE_K)) DISABLE_AXIS_K(); if (ENABLED(DISABLE_INACTIVE_E)) disable_e_steppers(); TERN_(AUTO_BED_LEVELING_UBL, ubl.steppers_were_disabled()); @@ -531,7 +471,9 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) { already_shutdown_steppers = false; } - #if PIN_EXISTS(CHDK) // Check if pin should be set to LOW (after M240 set it HIGH) + #if ENABLED(PHOTO_GCODE) && PIN_EXISTS(CHDK) + // Check if CHDK should be set to LOW (after M240 set it HIGH) + extern millis_t chdk_timeout; if (chdk_timeout && ELAPSED(ms, chdk_timeout)) { chdk_timeout = 0; WRITE(CHDK_PIN, LOW); @@ -559,28 +501,179 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) { } #endif + #if HAS_FREEZE_PIN + Stepper::frozen = !READ(FREEZE_PIN); + #endif + #if HAS_HOME // Handle a standalone HOME button constexpr millis_t HOME_DEBOUNCE_DELAY = 1000UL; static millis_t next_home_key_ms; // = 0 if (!IS_SD_PRINTING() && !READ(HOME_PIN)) { // HOME_PIN goes LOW when pressed - const millis_t ms = millis(); if (ELAPSED(ms, next_home_key_ms)) { next_home_key_ms = ms + HOME_DEBOUNCE_DELAY; LCD_MESSAGEPGM(MSG_AUTO_HOME); - queue.enqueue_now_P(G28_STR); + queue.inject_P(G28_STR); } } #endif + #if ENABLED(CUSTOM_USER_BUTTONS) + // Handle a custom user button if defined + const bool printer_not_busy = !printingIsActive(); + #define HAS_CUSTOM_USER_BUTTON(N) (PIN_EXISTS(BUTTON##N) && defined(BUTTON##N##_HIT_STATE) && defined(BUTTON##N##_GCODE)) + #define HAS_BETTER_USER_BUTTON(N) HAS_CUSTOM_USER_BUTTON(N) && defined(BUTTON##N##_DESC) + #define _CHECK_CUSTOM_USER_BUTTON(N, CODE) do{ \ + constexpr millis_t CUB_DEBOUNCE_DELAY_##N = 250UL; \ + static millis_t next_cub_ms_##N; \ + if (BUTTON##N##_HIT_STATE == READ(BUTTON##N##_PIN) \ + && (ENABLED(BUTTON##N##_WHEN_PRINTING) || printer_not_busy)) { \ + if (ELAPSED(ms, next_cub_ms_##N)) { \ + next_cub_ms_##N = ms + CUB_DEBOUNCE_DELAY_##N; \ + CODE; \ + queue.inject_P(PSTR(BUTTON##N##_GCODE)); \ + } \ + } \ + }while(0) + + #define CHECK_CUSTOM_USER_BUTTON(N) _CHECK_CUSTOM_USER_BUTTON(N, NOOP) + #define CHECK_BETTER_USER_BUTTON(N) _CHECK_CUSTOM_USER_BUTTON(N, if (strlen(BUTTON##N##_DESC)) LCD_MESSAGEPGM_P(PSTR(BUTTON##N##_DESC))) + + #if HAS_BETTER_USER_BUTTON(1) + CHECK_BETTER_USER_BUTTON(1); + #elif HAS_CUSTOM_USER_BUTTON(1) + CHECK_CUSTOM_USER_BUTTON(1); + #endif + #if HAS_BETTER_USER_BUTTON(2) + CHECK_BETTER_USER_BUTTON(2); + #elif HAS_CUSTOM_USER_BUTTON(2) + CHECK_CUSTOM_USER_BUTTON(2); + #endif + #if HAS_BETTER_USER_BUTTON(3) + CHECK_BETTER_USER_BUTTON(3); + #elif HAS_CUSTOM_USER_BUTTON(3) + CHECK_CUSTOM_USER_BUTTON(3); + #endif + #if HAS_BETTER_USER_BUTTON(4) + CHECK_BETTER_USER_BUTTON(4); + #elif HAS_CUSTOM_USER_BUTTON(4) + CHECK_CUSTOM_USER_BUTTON(4); + #endif + #if HAS_BETTER_USER_BUTTON(5) + CHECK_BETTER_USER_BUTTON(5); + #elif HAS_CUSTOM_USER_BUTTON(5) + CHECK_CUSTOM_USER_BUTTON(5); + #endif + #if HAS_BETTER_USER_BUTTON(6) + CHECK_BETTER_USER_BUTTON(6); + #elif HAS_CUSTOM_USER_BUTTON(6) + CHECK_CUSTOM_USER_BUTTON(6); + #endif + #if HAS_BETTER_USER_BUTTON(7) + CHECK_BETTER_USER_BUTTON(7); + #elif HAS_CUSTOM_USER_BUTTON(7) + CHECK_CUSTOM_USER_BUTTON(7); + #endif + #if HAS_BETTER_USER_BUTTON(8) + CHECK_BETTER_USER_BUTTON(8); + #elif HAS_CUSTOM_USER_BUTTON(8) + CHECK_CUSTOM_USER_BUTTON(8); + #endif + #if HAS_BETTER_USER_BUTTON(9) + CHECK_BETTER_USER_BUTTON(9); + #elif HAS_CUSTOM_USER_BUTTON(9) + CHECK_CUSTOM_USER_BUTTON(9); + #endif + #if HAS_BETTER_USER_BUTTON(10) + CHECK_BETTER_USER_BUTTON(10); + #elif HAS_CUSTOM_USER_BUTTON(10) + CHECK_CUSTOM_USER_BUTTON(10); + #endif + #if HAS_BETTER_USER_BUTTON(11) + CHECK_BETTER_USER_BUTTON(11); + #elif HAS_CUSTOM_USER_BUTTON(11) + CHECK_CUSTOM_USER_BUTTON(11); + #endif + #if HAS_BETTER_USER_BUTTON(12) + CHECK_BETTER_USER_BUTTON(12); + #elif HAS_CUSTOM_USER_BUTTON(12) + CHECK_CUSTOM_USER_BUTTON(12); + #endif + #if HAS_BETTER_USER_BUTTON(13) + CHECK_BETTER_USER_BUTTON(13); + #elif HAS_CUSTOM_USER_BUTTON(13) + CHECK_CUSTOM_USER_BUTTON(13); + #endif + #if HAS_BETTER_USER_BUTTON(14) + CHECK_BETTER_USER_BUTTON(14); + #elif HAS_CUSTOM_USER_BUTTON(14) + CHECK_CUSTOM_USER_BUTTON(14); + #endif + #if HAS_BETTER_USER_BUTTON(15) + CHECK_BETTER_USER_BUTTON(15); + #elif HAS_CUSTOM_USER_BUTTON(15) + CHECK_CUSTOM_USER_BUTTON(15); + #endif + #if HAS_BETTER_USER_BUTTON(16) + CHECK_BETTER_USER_BUTTON(16); + #elif HAS_CUSTOM_USER_BUTTON(16) + CHECK_CUSTOM_USER_BUTTON(16); + #endif + #if HAS_BETTER_USER_BUTTON(17) + CHECK_BETTER_USER_BUTTON(17); + #elif HAS_CUSTOM_USER_BUTTON(17) + CHECK_CUSTOM_USER_BUTTON(17); + #endif + #if HAS_BETTER_USER_BUTTON(18) + CHECK_BETTER_USER_BUTTON(18); + #elif HAS_CUSTOM_USER_BUTTON(18) + CHECK_CUSTOM_USER_BUTTON(18); + #endif + #if HAS_BETTER_USER_BUTTON(19) + CHECK_BETTER_USER_BUTTON(19); + #elif HAS_CUSTOM_USER_BUTTON(19) + CHECK_CUSTOM_USER_BUTTON(19); + #endif + #if HAS_BETTER_USER_BUTTON(20) + CHECK_BETTER_USER_BUTTON(20); + #elif HAS_CUSTOM_USER_BUTTON(20) + CHECK_CUSTOM_USER_BUTTON(20); + #endif + #if HAS_BETTER_USER_BUTTON(21) + CHECK_BETTER_USER_BUTTON(21); + #elif HAS_CUSTOM_USER_BUTTON(21) + CHECK_CUSTOM_USER_BUTTON(21); + #endif + #if HAS_BETTER_USER_BUTTON(22) + CHECK_BETTER_USER_BUTTON(22); + #elif HAS_CUSTOM_USER_BUTTON(22) + CHECK_CUSTOM_USER_BUTTON(22); + #endif + #if HAS_BETTER_USER_BUTTON(23) + CHECK_BETTER_USER_BUTTON(23); + #elif HAS_CUSTOM_USER_BUTTON(23) + CHECK_CUSTOM_USER_BUTTON(23); + #endif + #if HAS_BETTER_USER_BUTTON(24) + CHECK_BETTER_USER_BUTTON(24); + #elif HAS_CUSTOM_USER_BUTTON(24) + CHECK_CUSTOM_USER_BUTTON(24); + #endif + #if HAS_BETTER_USER_BUTTON(25) + CHECK_BETTER_USER_BUTTON(25); + #elif HAS_CUSTOM_USER_BUTTON(25) + CHECK_CUSTOM_USER_BUTTON(25); + #endif + #endif + TERN_(USE_CONTROLLER_FAN, controllerFan.update()); // Check if fan should be turned on to cool stepper drivers down - TERN_(AUTO_POWER_CONTROL, powerManager.check()); + TERN_(AUTO_POWER_CONTROL, powerManager.check(!ui.on_status_screen() || printJobOngoing() || printingIsPaused())); TERN_(HOTEND_IDLE_TIMEOUT, hotend_idle.check()); #if ENABLED(EXTRUDER_RUNOUT_PREVENT) - if (thermalManager.degHotend(active_extruder) > EXTRUDER_RUNOUT_MINTEMP + if (thermalManager.degHotend(active_extruder) > (EXTRUDER_RUNOUT_MINTEMP) && ELAPSED(ms, gcode.previous_move_ms + SEC_TO_MS(EXTRUDER_RUNOUT_SECONDS)) && !planner.has_blocks_queued() ) { @@ -637,11 +730,12 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) { #if ENABLED(DUAL_X_CARRIAGE) // handle delayed move timeout - if (delayed_move_time && ELAPSED(ms, delayed_move_time + 1000UL) && IsRunning()) { + if (delayed_move_time && ELAPSED(ms, delayed_move_time) && IsRunning()) { // travel moves have been received so enact them delayed_move_time = 0xFFFFFFFFUL; // force moves to be done destination = current_position; prepare_line_to_destination(); + planner.synchronize(); } #endif @@ -691,10 +785,14 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) { * - Update the Průša MMU2 * - Handle Joystick jogging */ -void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep/*=false*/)) { +void idle(bool no_stepper_sleep/*=false*/) { + #if ENABLED(MARLIN_DEV_MODE) + static uint16_t idle_depth = 0; + if (++idle_depth > 5) SERIAL_ECHOLNPAIR("idle() call depth: ", idle_depth); + #endif // Core Marlin activities - manage_inactivity(TERN_(ADVANCED_PAUSE_FEATURE, no_stepper_sleep)); + manage_inactivity(no_stepper_sleep); // Manage Heaters (and Watchdog) thermalManager.manage_heater(); @@ -703,34 +801,36 @@ void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep/*=false*/)) { TERN_(MAX7219_DEBUG, max7219.idle_tasks()); // Return if setup() isn't completed - if (marlin_state == MF_INITIALIZING) return; + if (marlin_state == MF_INITIALIZING) goto IDLE_DONE; + + // TODO: Still causing errors + (void)check_tool_sensor_stats(active_extruder, true); // Handle filament runout sensors TERN_(HAS_FILAMENT_SENSOR, runout.run()); // Run HAL idle tasks - #ifdef HAL_IDLETASK - HAL_idletask(); - #endif + TERN_(HAL_IDLETASK, HAL_idletask()); + + // Check network connection + TERN_(HAS_ETHERNET, ethernet.check()); // Handle Power-Loss Recovery #if ENABLED(POWER_LOSS_RECOVERY) && PIN_EXISTS(POWER_LOSS) - if (printJobOngoing()) recovery.outage(); + if (IS_SD_PRINTING()) recovery.outage(); #endif // 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) // Read SGT 4 times per idle loop - if (endstops.tmc_spi_homing_check()) break; + 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 #endif // Handle SD Card insert / remove TERN_(SDSUPPORT, card.manage_media()); // Handle USB Flash Drive insert / remove - TERN_(USB_FLASH_DRIVE_SUPPORT, Sd2Card::idle()); + TERN_(USB_FLASH_DRIVE_SUPPORT, card.diskIODriver()->idle()); // Announce Host Keepalive state (if any) TERN_(HOST_KEEPALIVE_FEATURE, gcode.host_keepalive()); @@ -746,6 +846,7 @@ void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep/*=false*/)) { // Run i2c Position Encoders #if ENABLED(I2C_POSITION_ENCODERS) + { static millis_t i2cpem_next_update_ms; if (planner.has_blocks_queued()) { const millis_t ms = millis(); @@ -754,18 +855,20 @@ void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep/*=false*/)) { i2cpem_next_update_ms = ms + I2CPE_MIN_UPD_TIME_MS; } } + } #endif // Auto-report Temperatures / SD Status #if HAS_AUTO_REPORTING if (!gcode.autoreport_paused) { - TERN_(AUTO_REPORT_TEMPERATURES, thermalManager.auto_report_temperatures()); - TERN_(AUTO_REPORT_SD_STATUS, card.auto_report_sd_status()); + TERN_(AUTO_REPORT_TEMPERATURES, thermalManager.auto_reporter.tick()); + TERN_(AUTO_REPORT_SD_STATUS, card.auto_reporter.tick()); + TERN_(AUTO_REPORT_POSITION, position_auto_reporter.tick()); } #endif // Update the Průša MMU2 - TERN_(PRUSA_MMU2, mmu2.mmu_loop()); + TERN_(HAS_PRUSA_MMU2, mmu2.mmu_loop()); // Handle Joystick jogging TERN_(POLL_JOG, joystick.inject_jog_moves()); @@ -773,9 +876,12 @@ void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep/*=false*/)) { // Direct Stepping TERN_(DIRECT_STEPPING, page_manager.write_responses()); - #if HAS_TFT_LVGL_UI - LV_TASK_HANDLER(); - #endif + // Update the LVGL interface + TERN_(HAS_TFT_LVGL_UI, LV_TASK_HANDLER()); + + IDLE_DONE: + TERN_(MARLIN_DEV_MODE, idle_depth--); + return; } /** @@ -787,18 +893,19 @@ void kill(PGM_P const lcd_error/*=nullptr*/, PGM_P const lcd_component/*=nullptr TERN_(HAS_CUTTER, cutter.kill()); // Full cutter shutdown including ISR control - SERIAL_ERROR_MSG(STR_ERR_KILLED); + // Echo the LCD message to serial for extra context + if (lcd_error) { SERIAL_ECHO_START(); SERIAL_ECHOLNPGM_P(lcd_error); } #if HAS_DISPLAY ui.kill_screen(lcd_error ?: GET_TEXT(MSG_KILLED), lcd_component ?: NUL_STR); #else - UNUSED(lcd_error); - UNUSED(lcd_component); + UNUSED(lcd_error); UNUSED(lcd_component); #endif - #if HAS_TFT_LVGL_UI - lv_draw_error_message(lcd_error); - #endif + TERN_(HAS_TFT_LVGL_UI, lv_draw_error_message(lcd_error)); + + // "Error:Printer halted. kill() called!" + SERIAL_ERROR_MSG(STR_ERR_KILLED); #ifdef ACTION_ON_KILL host_action_kill(); @@ -829,20 +936,22 @@ void minkill(const bool steppers_off/*=false*/) { TERN_(HAS_SUICIDE, suicide()); - #if HAS_KILL + #if EITHER(HAS_KILL, SOFT_RESET_ON_KILL) - // Wait for kill to be released - while (kill_state()) watchdog_refresh(); + // Wait for both KILL and ENC to be released + while (TERN0(HAS_KILL, kill_state()) || TERN0(SOFT_RESET_ON_KILL, ui.button_pressed())) + watchdog_refresh(); - // Wait for kill to be pressed - while (!kill_state()) watchdog_refresh(); + // Wait for either KILL or ENC to be pressed again + while (TERN1(HAS_KILL, !kill_state()) && TERN1(SOFT_RESET_ON_KILL, !ui.button_pressed())) + watchdog_refresh(); - void (*resetFunc)() = 0; // Declare resetFunc() at address 0 - resetFunc(); // Jump to address 0 + // Reboot the board + HAL_reboot(); #else - for (;;) watchdog_refresh(); // Wait for reset + for (;;) watchdog_refresh(); // Wait for RESET button or power-cycle #endif } @@ -853,13 +962,14 @@ void minkill(const bool steppers_off/*=false*/) { */ void stop() { thermalManager.disable_all_heaters(); // 'unpause' taken care of in here + print_job_timer.stop(); - #if ENABLED(PROBING_FANS_OFF) - if (thermalManager.fans_paused) thermalManager.set_fans_paused(false); // put things back the way they were + #if EITHER(PROBING_FANS_OFF, ADVANCED_PAUSE_FANS_PAUSE) + thermalManager.set_fans_paused(false); // Un-pause fans for safety #endif - if (IsRunning()) { + if (!IsStopped()) { SERIAL_ERROR_MSG(STR_ERR_STOPPED); LCD_MESSAGEPGM(MSG_STOPPED); safe_delay(350); // allow enough time for messages to get out before stopping @@ -892,6 +1002,15 @@ inline void tmc_standby_setup() { #if PIN_EXISTS(Z4_STDBY) SET_INPUT_PULLDOWN(Z4_STDBY_PIN); #endif + #if PIN_EXISTS(I_STDBY) + SET_INPUT_PULLDOWN(I_STDBY_PIN); + #endif + #if PIN_EXISTS(J_STDBY) + SET_INPUT_PULLDOWN(J_STDBY_PIN); + #endif + #if PIN_EXISTS(K_STDBY) + SET_INPUT_PULLDOWN(K_STDBY_PIN); + #endif #if PIN_EXISTS(E0_STDBY) SET_INPUT_PULLDOWN(E0_STDBY_PIN); #endif @@ -919,25 +1038,101 @@ inline void tmc_standby_setup() { } /** - * Marlin entry-point: Set up before the program loop - * - Set up the kill pin, filament runout, power hold - * - Start the serial port + * Marlin Firmware entry-point. Abandon Hope All Ye Who Enter Here. + * Setup before the program loop: + * + * - Call any special pre-init set for the board + * - Put TMC drivers into Low Power Standby mode + * - Init the serial ports (so setup can be debugged) + * - Set up the kill and suicide pins + * - Prepare (disable) board JTAG and Debug ports + * - Init serial for a connected MKS TFT with WiFi + * - Install Marlin custom Exception Handlers, if set. + * - Init Marlin's HAL interfaces (for SPI, i2c, etc.) + * - Init some optional hardware and features: + * • MAX Thermocouple pins + * • Duet Smart Effector + * • Filament Runout Sensor + * • TMC220x Stepper Drivers (Serial) + * • PSU control + * • Power-loss Recovery + * • L64XX Stepper Drivers (SPI) + * • Stepper Driver Reset: DISABLE + * • TMC Stepper Drivers (SPI) + * • Run BOARD_INIT if defined + * • ESP WiFi + * - Get the Reset Reason and report it * - Print startup messages and diagnostics - * - Get EEPROM or default settings - * - Initialize managers for: - * • temperature - * • planner - * • watchdog - * • stepper - * • photo pin - * • servos - * • LCD controller - * • Digipot I2C - * • Z probe sled - * • status LEDs - * • Max7219 + * - Calibrate the HAL DELAY for precise timing + * - Init the buzzer, possibly a custom timer + * - Init more optional hardware: + * • Color LED illumination + * • Neopixel illumination + * • Controller Fan + * • Creality DWIN LCD (show boot image) + * • Tare the Probe if possible + * - Mount the (most likely external) SD Card + * - Load settings from EEPROM (or use defaults) + * - Init the Ethernet Port + * - Init Touch Buttons (for emulated DOGLCD) + * - Adjust the (certainly wrong) current position by the home offset + * - Init the Planner::position (steps) based on current (native) position + * - Initialize more managers and peripherals: + * • Temperatures + * • Print Job Timer + * • Endstops and Endstop Interrupts + * • Stepper ISR - Kind of Important! + * • Servos + * • Servo-based Probe + * • Photograph Pin + * • Laser/Spindle tool Power / PWM + * • Coolant Control + * • Bed Probe + * • Stepper Driver Reset: ENABLE + * • Digipot I2C - Stepper driver current control + * • Stepper DAC - Stepper driver current control + * • Solenoid (probe, or for other use) + * • Home Pin + * • Custom User Buttons + * • Red/Blue Status LEDs + * • Case Light + * • Prusa MMU filament changer + * • Fan Multiplexer + * • Mixing Extruder + * • BLTouch Probe + * • I2C Position Encoders + * • Custom I2C Bus handlers + * • Enhanced tools or extruders: + * • Switching Extruder + * • Switching Nozzle + * • Parking Extruder + * • Magnetic Parking Extruder + * • Switching Toolhead + * • Electromagnetic Switching Toolhead + * • Watchdog Timer - Also Kind of Important! + * • Closed Loop Controller + * - Run Startup Commands, if defined + * - Tell host to close Host Prompts + * - Test Trinamic driver connections + * - Init Prusa MMU2 filament changer + * - Init and test BL24Cxx EEPROM + * - Init Creality DWIN encoder, show faux progress bar + * - Reset Status Message / Show Service Messages + * - Init MAX7219 LED Matrix + * - Init Direct Stepping (Klipper-style motion control) + * - Init TFT LVGL UI (with 3D Graphics) + * - Apply Password Lock - Hold for Authentication + * - Open Touch Screen Calibration screen, if not calibrated + * - Set Marlin to RUNNING State */ void setup() { + #ifdef FASTIO_INIT + FASTIO_INIT(); + #endif + + #ifdef BOARD_PREINIT + BOARD_PREINIT(); // Low-level init (before serial init) + #endif tmc_standby_setup(); // TMC Low Power Standby pins must be set early or they're not usable @@ -945,8 +1140,7 @@ void setup() { auto log_current_ms = [&](PGM_P const msg) { SERIAL_ECHO_START(); SERIAL_CHAR('['); SERIAL_ECHO(millis()); SERIAL_ECHOPGM("] "); - serialprintPGM(msg); - SERIAL_EOL(); + SERIAL_ECHOLNPGM_P(msg); }; #define SETUP_LOG(M) log_current_ms(PSTR(M)) #else @@ -954,38 +1148,77 @@ void setup() { #endif #define SETUP_RUN(C) do{ SETUP_LOG(STRINGIFY(C)); C; }while(0) + MYSERIAL1.begin(BAUDRATE); + millis_t serial_connect_timeout = millis() + 1000UL; + while (!MYSERIAL1.connected() && PENDING(millis(), serial_connect_timeout)) { /*nada*/ } + + #if HAS_MULTI_SERIAL && !HAS_ETHERNET + #ifndef BAUDRATE_2 + #define BAUDRATE_2 BAUDRATE + #endif + MYSERIAL2.begin(BAUDRATE_2); + serial_connect_timeout = millis() + 1000UL; + while (!MYSERIAL2.connected() && PENDING(millis(), serial_connect_timeout)) { /*nada*/ } + #ifdef SERIAL_PORT_3 + #ifndef BAUDRATE_3 + #define BAUDRATE_3 BAUDRATE + #endif + MYSERIAL3.begin(BAUDRATE_3); + serial_connect_timeout = millis() + 1000UL; + while (!MYSERIAL3.connected() && PENDING(millis(), serial_connect_timeout)) { /*nada*/ } + #endif + #endif + SERIAL_ECHOLNPGM("start"); + + // Set up these pins early to prevent suicide + #if HAS_KILL + SETUP_LOG("KILL_PIN"); + #if KILL_PIN_STATE + SET_INPUT_PULLDOWN(KILL_PIN); + #else + SET_INPUT_PULLUP(KILL_PIN); + #endif + #endif + + #if HAS_FREEZE_PIN + SETUP_LOG("FREEZE_PIN"); + SET_INPUT_PULLUP(FREEZE_PIN); + #endif + + #if HAS_SUICIDE + SETUP_LOG("SUICIDE_PIN"); + OUT_WRITE(SUICIDE_PIN, !SUICIDE_PIN_INVERTING); + #endif + + #ifdef JTAGSWD_RESET + SETUP_LOG("JTAGSWD_RESET"); + JTAGSWD_RESET(); + #endif + #if EITHER(DISABLE_DEBUG, DISABLE_JTAG) + delay(10); // Disable any hardware debug to free up pins for IO #if ENABLED(DISABLE_DEBUG) && defined(JTAGSWD_DISABLE) + SETUP_LOG("JTAGSWD_DISABLE"); JTAGSWD_DISABLE(); #elif defined(JTAG_DISABLE) + SETUP_LOG("JTAG_DISABLE"); JTAG_DISABLE(); #else #error "DISABLE_(DEBUG|JTAG) is not supported for the selected MCU/Board." #endif #endif - MYSERIAL0.begin(BAUDRATE); - uint32_t serial_connect_timeout = millis() + 1000UL; - while (!MYSERIAL0 && PENDING(millis(), serial_connect_timeout)) { /*nada*/ } - #if HAS_MULTI_SERIAL - MYSERIAL1.begin(BAUDRATE); - serial_connect_timeout = millis() + 1000UL; - while (!MYSERIAL1 && PENDING(millis(), serial_connect_timeout)) { /*nada*/ } - #endif - SERIAL_ECHO_MSG("start"); - - #if BOTH(HAS_TFT_LVGL_UI, USE_WIFI_FUNCTION) - mks_esp_wifi_init(); - WIFISERIAL.begin(WIFI_BAUDRATE); - serial_connect_timeout = millis() + 1000UL; - while (/*!WIFISERIAL && */PENDING(millis(), serial_connect_timeout)) { /*nada*/ } - #endif + TERN_(DYNAMIC_VECTORTABLE, hook_cpu_exceptions()); // If supported, install Marlin exception handlers at runtime SETUP_RUN(HAL_init()); - #if HAS_L64XX - SETUP_RUN(L64xxManager.init()); // Set up SPI, init drivers + // Init and disable SPI thermocouples; this is still needed + #if TEMP_SENSOR_0_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 0) + OUT_WRITE(TEMP_0_CS_PIN, HIGH); // Disable + #endif + #if TEMP_SENSOR_1_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 1) + OUT_WRITE(TEMP_1_CS_PIN, HIGH); #endif #if ENABLED(DUET_SMART_EFFECTOR) && PIN_EXISTS(SMART_EFFECTOR_MOD) @@ -996,17 +1229,23 @@ void setup() { SETUP_RUN(runout.setup()); #endif - #if ENABLED(POWER_LOSS_RECOVERY) - SETUP_RUN(recovery.setup()); + #if HAS_TMC220x + SETUP_RUN(tmc_serial_begin()); #endif - SETUP_RUN(setup_killpin()); + #if ENABLED(PSU_CONTROL) + SETUP_LOG("PSU_CONTROL"); + powersupply_on = ENABLED(PSU_DEFAULT_OFF); + if (ENABLED(PSU_DEFAULT_OFF)) PSU_OFF(); else PSU_ON(); + #endif - #if HAS_TMC220x - SETUP_RUN(tmc_serial_begin()); + #if ENABLED(POWER_LOSS_RECOVERY) + SETUP_RUN(recovery.setup()); #endif - SETUP_RUN(setup_powerhold()); + #if HAS_L64XX + SETUP_RUN(L64xxManager.init()); // Set up SPI, init drivers + #endif #if HAS_STEPPER_RESET SETUP_RUN(disableStepperDrivers()); @@ -1035,9 +1274,7 @@ void setup() { if (mcu & RST_SOFTWARE) SERIAL_ECHOLNPGM(STR_SOFTWARE_RESET); HAL_clear_reset_source(); - serialprintPGM(GET_TEXT(MSG_MARLIN)); - SERIAL_CHAR(' '); - SERIAL_ECHOLNPGM(SHORT_BUILD_VERSION); + SERIAL_ECHOLNPGM("Marlin " SHORT_BUILD_VERSION); SERIAL_EOL(); #if defined(STRING_DISTRIBUTION_DATE) && defined(STRING_CONFIG_H_AUTHOR) SERIAL_ECHO_MSG( @@ -1046,7 +1283,10 @@ void setup() { ); #endif SERIAL_ECHO_MSG("Compiled: " __DATE__); - SERIAL_ECHO_MSG(STR_FREE_MEMORY, freeMemory(), STR_PLANNER_BUFFER_BYTES, (int)sizeof(block_t) * (BLOCK_BUFFER_SIZE)); + SERIAL_ECHO_MSG(STR_FREE_MEMORY, freeMemory(), STR_PLANNER_BUFFER_BYTES, sizeof(block_t) * (BLOCK_BUFFER_SIZE)); + + // Some HAL need precise delay adjustment + calibrate_delay_loop(); // Init buzzer pin(s) #if USE_BEEPER @@ -1070,19 +1310,29 @@ void setup() { // (because EEPROM code calls the UI). #if ENABLED(DWIN_CREALITY_LCD) - delay(800); // Required delay (since boot?) - SERIAL_ECHOPGM("\nDWIN handshake "); - if (DWIN_Handshake()) SERIAL_ECHOLNPGM("ok."); else SERIAL_ECHOLNPGM("error."); - DWIN_Frame_SetDir(1); // Orientation 90° - DWIN_UpdateLCD(); // Show bootscreen (first image) + SETUP_RUN(DWIN_Startup()); #else SETUP_RUN(ui.init()); - #if HAS_WIRED_LCD && ENABLED(SHOW_BOOTSCREEN) + #if BOTH(HAS_WIRED_LCD, SHOW_BOOTSCREEN) SETUP_RUN(ui.show_bootscreen()); + const millis_t bootscreen_ms = millis(); #endif SETUP_RUN(ui.reset_status()); // Load welcome message early. (Retained if no errors exist.) #endif + #if PIN_EXISTS(SAFE_POWER) + #if HAS_DRIVER_SAFE_POWER_PROTECT + SETUP_RUN(stepper_driver_backward_check()); + #else + SETUP_LOG("SAFE_POWER"); + OUT_WRITE(SAFE_POWER_PIN, HIGH); + #endif + #endif + + #if ENABLED(PROBE_TARE) + SETUP_RUN(probe.tare_init()); + #endif + #if BOTH(SDSUPPORT, SDCARD_EEPROM_EMULATION) SETUP_RUN(card.mount()); // Mount media with settings before first_load #endif @@ -1090,7 +1340,11 @@ void setup() { SETUP_RUN(settings.first_load()); // Load data from EEPROM if available (or use defaults) // This also updates variables in the planner, elsewhere - #if HAS_TOUCH_XPT2046 + #if HAS_ETHERNET + SETUP_RUN(ethernet.init()); + #endif + + #if HAS_TOUCH_BUTTONS SETUP_RUN(touch.init()); #endif @@ -1141,7 +1395,7 @@ void setup() { SETUP_RUN(digipot_i2c.init()); #endif - #if ENABLED(HAS_MOTOR_CURRENT_DAC) + #if HAS_MOTOR_CURRENT_DAC SETUP_RUN(stepper_dac.init()); #endif @@ -1153,26 +1407,99 @@ void setup() { SET_INPUT_PULLUP(HOME_PIN); #endif + #if ENABLED(CUSTOM_USER_BUTTONS) + #define INIT_CUSTOM_USER_BUTTON_PIN(N) do{ SET_INPUT(BUTTON##N##_PIN); WRITE(BUTTON##N##_PIN, !BUTTON##N##_HIT_STATE); }while(0) + + #if HAS_CUSTOM_USER_BUTTON(1) + INIT_CUSTOM_USER_BUTTON_PIN(1); + #endif + #if HAS_CUSTOM_USER_BUTTON(2) + INIT_CUSTOM_USER_BUTTON_PIN(2); + #endif + #if HAS_CUSTOM_USER_BUTTON(3) + INIT_CUSTOM_USER_BUTTON_PIN(3); + #endif + #if HAS_CUSTOM_USER_BUTTON(4) + INIT_CUSTOM_USER_BUTTON_PIN(4); + #endif + #if HAS_CUSTOM_USER_BUTTON(5) + INIT_CUSTOM_USER_BUTTON_PIN(5); + #endif + #if HAS_CUSTOM_USER_BUTTON(6) + INIT_CUSTOM_USER_BUTTON_PIN(6); + #endif + #if HAS_CUSTOM_USER_BUTTON(7) + INIT_CUSTOM_USER_BUTTON_PIN(7); + #endif + #if HAS_CUSTOM_USER_BUTTON(8) + INIT_CUSTOM_USER_BUTTON_PIN(8); + #endif + #if HAS_CUSTOM_USER_BUTTON(9) + INIT_CUSTOM_USER_BUTTON_PIN(9); + #endif + #if HAS_CUSTOM_USER_BUTTON(10) + INIT_CUSTOM_USER_BUTTON_PIN(10); + #endif + #if HAS_CUSTOM_USER_BUTTON(11) + INIT_CUSTOM_USER_BUTTON_PIN(11); + #endif + #if HAS_CUSTOM_USER_BUTTON(12) + INIT_CUSTOM_USER_BUTTON_PIN(12); + #endif + #if HAS_CUSTOM_USER_BUTTON(13) + INIT_CUSTOM_USER_BUTTON_PIN(13); + #endif + #if HAS_CUSTOM_USER_BUTTON(14) + INIT_CUSTOM_USER_BUTTON_PIN(14); + #endif + #if HAS_CUSTOM_USER_BUTTON(15) + INIT_CUSTOM_USER_BUTTON_PIN(15); + #endif + #if HAS_CUSTOM_USER_BUTTON(16) + INIT_CUSTOM_USER_BUTTON_PIN(16); + #endif + #if HAS_CUSTOM_USER_BUTTON(17) + INIT_CUSTOM_USER_BUTTON_PIN(17); + #endif + #if HAS_CUSTOM_USER_BUTTON(18) + INIT_CUSTOM_USER_BUTTON_PIN(18); + #endif + #if HAS_CUSTOM_USER_BUTTON(19) + INIT_CUSTOM_USER_BUTTON_PIN(19); + #endif + #if HAS_CUSTOM_USER_BUTTON(20) + INIT_CUSTOM_USER_BUTTON_PIN(20); + #endif + #if HAS_CUSTOM_USER_BUTTON(21) + INIT_CUSTOM_USER_BUTTON_PIN(21); + #endif + #if HAS_CUSTOM_USER_BUTTON(22) + INIT_CUSTOM_USER_BUTTON_PIN(22); + #endif + #if HAS_CUSTOM_USER_BUTTON(23) + INIT_CUSTOM_USER_BUTTON_PIN(23); + #endif + #if HAS_CUSTOM_USER_BUTTON(24) + INIT_CUSTOM_USER_BUTTON_PIN(24); + #endif + #if HAS_CUSTOM_USER_BUTTON(25) + INIT_CUSTOM_USER_BUTTON_PIN(25); + #endif + #endif + #if PIN_EXISTS(STAT_LED_RED) OUT_WRITE(STAT_LED_RED_PIN, LOW); // OFF #endif - #if PIN_EXISTS(STAT_LED_BLUE) OUT_WRITE(STAT_LED_BLUE_PIN, LOW); // OFF #endif #if ENABLED(CASE_LIGHT_ENABLE) - #if DISABLED(CASE_LIGHT_USE_NEOPIXEL) - if (PWM_PIN(CASE_LIGHT_PIN)) SET_PWM(CASE_LIGHT_PIN); else SET_OUTPUT(CASE_LIGHT_PIN); - #endif - SETUP_RUN(caselight.update_brightness()); + SETUP_RUN(caselight.init()); #endif - #if ENABLED(MK2_MULTIPLEXER) - SETUP_LOG("MK2_MULTIPLEXER"); - SET_OUTPUT(E_MUX0_PIN); - SET_OUTPUT(E_MUX1_PIN); - SET_OUTPUT(E_MUX2_PIN); + #if HAS_PRUSA_MMU1 + SETUP_RUN(mmu_init()); #endif #if HAS_FANMUX @@ -1212,19 +1539,13 @@ void setup() { #endif #endif - #if ENABLED(MAGNETIC_PARKING_EXTRUDER) - SETUP_RUN(mpe_settings_init()); - #endif - #if ENABLED(PARKING_EXTRUDER) SETUP_RUN(pe_solenoid_init()); - #endif - - #if ENABLED(SWITCHING_TOOLHEAD) + #elif ENABLED(MAGNETIC_PARKING_EXTRUDER) + SETUP_RUN(mpe_settings_init()); + #elif ENABLED(SWITCHING_TOOLHEAD) SETUP_RUN(swt_init()); - #endif - - #if ENABLED(ELECTROMAGNETIC_SWITCHING_TOOLHEAD) + #elif ENABLED(ELECTROMAGNETIC_SWITCHING_TOOLHEAD) SETUP_RUN(est_init()); #endif @@ -1246,10 +1567,14 @@ void setup() { #endif #if HAS_TRINAMIC_CONFIG && DISABLED(PSU_DEFAULT_OFF) - SETUP_RUN(test_tmc_connection(true, true, true, true)); + SETUP_RUN(test_tmc_connection()); #endif - #if ENABLED(PRUSA_MMU2) + #if HAS_DRIVER_SAFE_POWER_PROTECT + SETUP_RUN(stepper_driver_backward_report()); + #endif + + #if HAS_PRUSA_MMU2 SETUP_RUN(mmu2.init()); #endif @@ -1262,7 +1587,9 @@ void setup() { #if ENABLED(DWIN_CREALITY_LCD) Encoder_Configuration(); HMI_Init(); + HMI_SetLanguageCache(); HMI_StartFrame(true); + DWIN_StatusChanged_P(GET_TEXT(WELCOME_MSG)); #endif #if HAS_SERVICE_INTERVALS && DISABLED(DWIN_CREALITY_LCD) @@ -1284,10 +1611,22 @@ void setup() { SETUP_RUN(tft_lvgl_init()); #endif + #if BOTH(HAS_WIRED_LCD, SHOW_BOOTSCREEN) + const millis_t elapsed = millis() - bootscreen_ms; + #if ENABLED(MARLIN_DEV_MODE) + SERIAL_ECHOLNPAIR("elapsed=", elapsed); + #endif + SETUP_RUN(ui.bootscreen_completion(elapsed)); + #endif + #if ENABLED(PASSWORD_ON_STARTUP) SETUP_RUN(password.lock_machine()); // Will not proceed until correct password provided #endif + #if BOTH(HAS_LCD_MENU, TOUCH_SCREEN_CALIBRATION) && EITHER(TFT_CLASSIC_UI, TFT_COLOR_UI) + ui.check_touch_calibration(); + #endif + marlin_state = MF_RUNNING; SETUP_LOG("setup() completed."); @@ -1311,7 +1650,6 @@ void loop() { idle(); #if ENABLED(SDSUPPORT) - card.checkautostart(); if (card.flag.abort_sd_printing) abortSDPrinting(); if (marlin_state == MF_SD_COMPLETE) finishSDPrinting(); #endif diff --git a/Marlin/src/MarlinCore.h b/Marlin/src/MarlinCore.h index 69afc7f30e88..243811d7fb7e 100644 --- a/Marlin/src/MarlinCore.h +++ b/Marlin/src/MarlinCore.h @@ -34,13 +34,8 @@ void stop(); // Pass true to keep steppers from timing out -void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep=false)); -inline void idle_no_sleep() { idle(TERN_(ADVANCED_PAUSE_FEATURE, true)); } - -#if ENABLED(EXPERIMENTAL_I2CBUS) - #include "feature/twibus.h" - extern TWIBus i2c; -#endif +void idle(bool no_stepper_sleep=false); +inline void idle_no_sleep() { idle(true); } #if ENABLED(G38_PROBE_TARGET) extern uint8_t G38_move; // Flag to tell the ISR that G38 is in progress, and the type @@ -59,24 +54,23 @@ void disable_all_steppers(); void kill(PGM_P const lcd_error=nullptr, PGM_P const lcd_component=nullptr, const bool steppers_off=false); void minkill(const bool steppers_off=false); -void quickstop_stepper(); - // Global State of the firmware enum MarlinState : uint8_t { - MF_INITIALIZING = 0, - MF_RUNNING = _BV(0), - MF_PAUSED = _BV(1), - MF_WAITING = _BV(2), - MF_STOPPED = _BV(3), - MF_SD_COMPLETE = _BV(4), - MF_KILLED = _BV(7) + MF_INITIALIZING = 0, + MF_STOPPED, + MF_KILLED, + MF_RUNNING, + MF_SD_COMPLETE, + MF_PAUSED, + MF_WAITING, }; extern MarlinState marlin_state; -inline bool IsRunning() { return marlin_state == MF_RUNNING; } -inline bool IsStopped() { return marlin_state != MF_RUNNING; } +inline bool IsRunning() { return marlin_state >= MF_RUNNING; } +inline bool IsStopped() { return marlin_state == MF_STOPPED; } bool printingIsActive(); +bool printJobOngoing(); bool printingIsPaused(); void startOrResumeJob(); @@ -92,16 +86,21 @@ extern bool wait_for_heatup; #define PSU_PIN_ON() do{ OUT_WRITE(PS_ON_PIN, PSU_ACTIVE_STATE); powersupply_on = true; }while(0) #define PSU_PIN_OFF() do{ OUT_WRITE(PS_ON_PIN, !PSU_ACTIVE_STATE); powersupply_on = false; }while(0) #if ENABLED(AUTO_POWER_CONTROL) - #define PSU_ON() powerManager.power_on() - #define PSU_OFF() powerManager.power_off() + #define PSU_ON() powerManager.power_on() + #define PSU_OFF() powerManager.power_off() + #define PSU_OFF_SOON() powerManager.power_off_soon() #else - #define PSU_ON() PSU_PIN_ON() - #define PSU_OFF() PSU_PIN_OFF() + #define PSU_ON() PSU_PIN_ON() + #if ENABLED(PS_OFF_SOUND) + #define PSU_OFF() do{ BUZZ(1000, 659); PSU_PIN_OFF(); }while(0) + #else + #define PSU_OFF() PSU_PIN_OFF() + #endif + #define PSU_OFF_SOON PSU_OFF #endif #endif bool pin_is_protected(const pin_t pin); -void protected_pin_err(); #if HAS_SUICIDE inline void suicide() { OUT_WRITE(SUICIDE_PIN, SUICIDE_PIN_INVERTING); } @@ -114,12 +113,4 @@ void protected_pin_err(); inline bool kill_state() { return READ(KILL_PIN) == KILL_PIN_STATE; } #endif -#if ENABLED(G29_RETRY_AND_RECOVER) - void event_probe_recover(); - void event_probe_failure(); -#endif - -extern const char NUL_STR[], M112_KILL_STR[], G28_STR[], M21_STR[], M23_STR[], M24_STR[], - SP_A_STR[], SP_B_STR[], SP_C_STR[], - SP_P_STR[], SP_T_STR[], SP_X_STR[], SP_Y_STR[], SP_Z_STR[], SP_E_STR[], - X_LBL[], Y_LBL[], Z_LBL[], E_LBL[], SP_X_LBL[], SP_Y_LBL[], SP_Z_LBL[], SP_E_LBL[]; +extern const char M112_KILL_STR[]; diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index da7d15ec33d5..2ed585919966 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -68,47 +68,53 @@ #define BOARD_MKS_GEN_13 1112 // MKS GEN v1.3 or 1.4 #define BOARD_MKS_GEN_L 1113 // MKS GEN L #define BOARD_KFB_2 1114 // BigTreeTech or BIQU KFB2.0 -#define BOARD_ZRIB_V20 1115 // zrib V2.0 control board (Chinese knock off RAMPS replica) -#define BOARD_FELIX2 1116 // Felix 2.0+ Electronics Board (RAMPS like) -#define BOARD_RIGIDBOARD 1117 // Invent-A-Part RigidBoard -#define BOARD_RIGIDBOARD_V2 1118 // Invent-A-Part RigidBoard V2 -#define BOARD_SAINSMART_2IN1 1119 // Sainsmart 2-in-1 board -#define BOARD_ULTIMAKER 1120 // Ultimaker -#define BOARD_ULTIMAKER_OLD 1121 // Ultimaker (Older electronics. Pre 1.5.4. This is rare) -#define BOARD_AZTEEG_X3 1122 // Azteeg X3 -#define BOARD_AZTEEG_X3_PRO 1123 // Azteeg X3 Pro -#define BOARD_ULTIMAIN_2 1124 // Ultimainboard 2.x (Uses TEMP_SENSOR 20) -#define BOARD_RUMBA 1125 // Rumba -#define BOARD_RUMBA_RAISE3D 1126 // Raise3D N series Rumba derivative -#define BOARD_RL200 1127 // Rapide Lite 200 (v1, low-cost RUMBA clone with drv) -#define BOARD_FORMBOT_TREX2PLUS 1128 // Formbot T-Rex 2 Plus -#define BOARD_FORMBOT_TREX3 1129 // Formbot T-Rex 3 -#define BOARD_FORMBOT_RAPTOR 1130 // Formbot Raptor -#define BOARD_FORMBOT_RAPTOR2 1131 // Formbot Raptor 2 -#define BOARD_BQ_ZUM_MEGA_3D 1132 // bq ZUM Mega 3D -#define BOARD_MAKEBOARD_MINI 1133 // MakeBoard Mini v2.1.2 is a control board sold by MicroMake -#define BOARD_TRIGORILLA_13 1134 // TriGorilla Anycubic version 1.3-based on RAMPS EFB -#define BOARD_TRIGORILLA_14 1135 // ... Ver 1.4 -#define BOARD_TRIGORILLA_14_11 1136 // ... Rev 1.1 (new servo pin order) -#define BOARD_RAMPS_ENDER_4 1137 // Creality: Ender-4, CR-8 -#define BOARD_RAMPS_CREALITY 1138 // Creality: CR10S, CR20, CR-X -#define BOARD_RAMPS_DAGOMA 1139 // Dagoma F5 -#define BOARD_FYSETC_F6_13 1140 // FYSETC F6 1.3 -#define BOARD_FYSETC_F6_14 1141 // FYSETC F6 1.4 -#define BOARD_DUPLICATOR_I3_PLUS 1142 // Wanhao Duplicator i3 Plus -#define BOARD_VORON 1143 // VORON Design -#define BOARD_TRONXY_V3_1_0 1144 // Tronxy TRONXY-V3-1.0 -#define BOARD_Z_BOLT_X_SERIES 1145 // Z-Bolt X Series -#define BOARD_TT_OSCAR 1146 // TT OSCAR -#define BOARD_OVERLORD 1147 // Overlord/Overlord Pro -#define BOARD_HJC2560C_REV1 1148 // ADIMLab Gantry v1 -#define BOARD_HJC2560C_REV2 1149 // ADIMLab Gantry v2 -#define BOARD_TANGO 1150 // BIQU Tango V1 -#define BOARD_MKS_GEN_L_V2 1151 // MKS GEN L V2 -#define BOARD_MKS_GEN_L_V21 1152 // MKS GEN L V2.1 -#define BOARD_COPYMASTER_3D 1153 // Copymaster 3D -#define BOARD_ORTUR_4 1154 // Ortur 4 -#define BOARD_TENLOG_D3_HERO 1155 // Tenlog D3 Hero IDEX printer +#define BOARD_ZRIB_V20 1115 // zrib V2.0 (Chinese RAMPS replica) +#define BOARD_ZRIB_V52 1116 // zrib V5.2 (Chinese RAMPS replica) +#define BOARD_FELIX2 1117 // Felix 2.0+ Electronics Board (RAMPS like) +#define BOARD_RIGIDBOARD 1118 // Invent-A-Part RigidBoard +#define BOARD_RIGIDBOARD_V2 1119 // Invent-A-Part RigidBoard V2 +#define BOARD_SAINSMART_2IN1 1120 // Sainsmart 2-in-1 board +#define BOARD_ULTIMAKER 1121 // Ultimaker +#define BOARD_ULTIMAKER_OLD 1122 // Ultimaker (Older electronics. Pre 1.5.4. This is rare) +#define BOARD_AZTEEG_X3 1123 // Azteeg X3 +#define BOARD_AZTEEG_X3_PRO 1124 // Azteeg X3 Pro +#define BOARD_ULTIMAIN_2 1125 // Ultimainboard 2.x (Uses TEMP_SENSOR 20) +#define BOARD_RUMBA 1126 // Rumba +#define BOARD_RUMBA_RAISE3D 1127 // Raise3D N series Rumba derivative +#define BOARD_RL200 1128 // Rapide Lite 200 (v1, low-cost RUMBA clone with drv) +#define BOARD_FORMBOT_TREX2PLUS 1129 // Formbot T-Rex 2 Plus +#define BOARD_FORMBOT_TREX3 1130 // Formbot T-Rex 3 +#define BOARD_FORMBOT_RAPTOR 1131 // Formbot Raptor +#define BOARD_FORMBOT_RAPTOR2 1132 // Formbot Raptor 2 +#define BOARD_BQ_ZUM_MEGA_3D 1133 // bq ZUM Mega 3D +#define BOARD_MAKEBOARD_MINI 1134 // MakeBoard Mini v2.1.2 by MicroMake +#define BOARD_TRIGORILLA_13 1135 // TriGorilla Anycubic version 1.3-based on RAMPS EFB +#define BOARD_TRIGORILLA_14 1136 // ... Ver 1.4 +#define BOARD_TRIGORILLA_14_11 1137 // ... Rev 1.1 (new servo pin order) +#define BOARD_RAMPS_ENDER_4 1138 // Creality: Ender-4, CR-8 +#define BOARD_RAMPS_CREALITY 1139 // Creality: CR10S, CR20, CR-X +#define BOARD_DAGOMA_F5 1140 // Dagoma F5 +#define BOARD_FYSETC_F6_13 1141 // FYSETC F6 1.3 +#define BOARD_FYSETC_F6_14 1142 // FYSETC F6 1.4 +#define BOARD_DUPLICATOR_I3_PLUS 1143 // Wanhao Duplicator i3 Plus +#define BOARD_VORON 1144 // VORON Design +#define BOARD_TRONXY_V3_1_0 1145 // Tronxy TRONXY-V3-1.0 +#define BOARD_Z_BOLT_X_SERIES 1146 // Z-Bolt X Series +#define BOARD_TT_OSCAR 1147 // TT OSCAR +#define BOARD_OVERLORD 1148 // Overlord/Overlord Pro +#define BOARD_HJC2560C_REV1 1149 // ADIMLab Gantry v1 +#define BOARD_HJC2560C_REV2 1150 // ADIMLab Gantry v2 +#define BOARD_TANGO 1151 // BIQU Tango V1 +#define BOARD_MKS_GEN_L_V2 1152 // MKS GEN L V2 +#define BOARD_MKS_GEN_L_V21 1153 // MKS GEN L V2.1 +#define BOARD_COPYMASTER_3D 1154 // Copymaster 3D +#define BOARD_ORTUR_4 1155 // Ortur 4 +#define BOARD_TENLOG_D3_HERO 1156 // Tenlog D3 Hero IDEX printer +#define BOARD_RAMPS_S_12_EEFB 1157 // Ramps S 1.2 by Sakul.cz (Power outputs: Hotend0, Hotend1, Fan, Bed) +#define BOARD_RAMPS_S_12_EEEB 1158 // Ramps S 1.2 by Sakul.cz (Power outputs: Hotend0, Hotend1, Hotend2, Bed) +#define BOARD_RAMPS_S_12_EFFB 1159 // Ramps S 1.2 by Sakul.cz (Power outputs: Hotend, Fan0, Fan1, Bed) +#define BOARD_LONGER3D_LK1_PRO 1160 // Longer LK1 PRO / Alfawise U20 Pro (PRO version) +#define BOARD_LONGER3D_LKx_PRO 1161 // Longer LKx PRO / Alfawise Uxx Pro (PRO version) // // RAMBo and derivatives @@ -120,6 +126,7 @@ #define BOARD_EINSY_RAMBO 1203 // Einsy Rambo #define BOARD_EINSY_RETRO 1204 // Einsy Retro #define BOARD_SCOOVO_X9H 1205 // abee Scoovo X9H +#define BOARD_RAMBO_THINKERV2 1206 // ThinkerV2 // // Other ATmega1280, ATmega2560 @@ -139,17 +146,20 @@ #define BOARD_ELEFU_3 1311 // Elefu Ra Board (v3) #define BOARD_LEAPFROG 1312 // Leapfrog #define BOARD_MEGACONTROLLER 1313 // Mega controller -#define BOARD_GT2560_REV_A 1314 // Geeetech GT2560 Rev. A -#define BOARD_GT2560_REV_A_PLUS 1315 // Geeetech GT2560 Rev. A+ (with auto level probe) -#define BOARD_GT2560_V3 1316 // Geeetech GT2560 Rev B for A10(M/D) -#define BOARD_GT2560_V3_MC2 1317 // Geeetech GT2560 Rev B for Mecreator2 -#define BOARD_GT2560_V3_A20 1318 // Geeetech GT2560 Rev B for A20(M/D) -#define BOARD_EINSTART_S 1319 // Einstart retrofit -#define BOARD_WANHAO_ONEPLUS 1320 // Wanhao 0ne+ i3 Mini -#define BOARD_LEAPFROG_XEED2015 1321 // Leapfrog Xeed 2015 -#define BOARD_PICA_REVB 1322 // PICA Shield (original version) -#define BOARD_PICA 1323 // PICA Shield (rev C or later) -#define BOARD_INTAMSYS40 1324 // Intamsys 4.0 (Funmat HT) +#define BOARD_GT2560_REV_A 1314 // Geeetech GT2560 Rev A +#define BOARD_GT2560_REV_A_PLUS 1315 // Geeetech GT2560 Rev A+ (with auto level probe) +#define BOARD_GT2560_REV_B 1316 // Geeetech GT2560 Rev B +#define BOARD_GT2560_V3 1317 // Geeetech GT2560 Rev B for A10(M/D) +#define BOARD_GT2560_V4 1318 // Geeetech GT2560 Rev B for A10(M/D) +#define BOARD_GT2560_V3_MC2 1319 // Geeetech GT2560 Rev B for Mecreator2 +#define BOARD_GT2560_V3_A20 1320 // Geeetech GT2560 Rev B for A20(M/D) +#define BOARD_EINSTART_S 1321 // Einstart retrofit +#define BOARD_WANHAO_ONEPLUS 1322 // Wanhao 0ne+ i3 Mini +#define BOARD_LEAPFROG_XEED2015 1323 // Leapfrog Xeed 2015 +#define BOARD_PICA_REVB 1324 // PICA Shield (original version) +#define BOARD_PICA 1325 // PICA Shield (rev C or later) +#define BOARD_INTAMSYS40 1326 // Intamsys 4.0 (Funmat HT) +#define BOARD_MALYAN_M180 1327 // Malyan M180 Mainboard Version 2 (no display function, direct gcode only) // // ATmega1281, ATmega2561 @@ -167,8 +177,8 @@ #define BOARD_MELZI 1502 // Melzi #define BOARD_MELZI_V2 1503 // Melzi V2 #define BOARD_MELZI_MAKR3D 1504 // Melzi with ATmega1284 (MaKr3d version) -#define BOARD_MELZI_CREALITY 1505 // Melzi Creality3D board (for CR-10 etc) -#define BOARD_MELZI_MALYAN 1506 // Melzi Malyan M150 board +#define BOARD_MELZI_CREALITY 1505 // Melzi Creality3D (for CR-10 etc) +#define BOARD_MELZI_MALYAN 1506 // Melzi Malyan M150 #define BOARD_MELZI_TRONXY 1507 // Tronxy X5S #define BOARD_STB_11 1508 // STB V1.1 #define BOARD_AZTEEG_X1 1509 // Azteeg X1 @@ -183,12 +193,12 @@ #define BOARD_GEN3_PLUS 1601 // Gen3+ #define BOARD_GEN6 1602 // Gen6 #define BOARD_GEN6_DELUXE 1603 // Gen6 deluxe -#define BOARD_GEN7_CUSTOM 1604 // Gen7 custom (Alfons3 Version) "https://github.com/Alfons3/Generation_7_Electronics" +#define BOARD_GEN7_CUSTOM 1604 // Gen7 custom (Alfons3 Version) https://github.com/Alfons3/Generation_7_Electronics #define BOARD_GEN7_12 1605 // Gen7 v1.1, v1.2 #define BOARD_GEN7_13 1606 // Gen7 v1.3 #define BOARD_GEN7_14 1607 // Gen7 v1.4 -#define BOARD_OMCA_A 1608 // Alpha OMCA board -#define BOARD_OMCA 1609 // Final OMCA board +#define BOARD_OMCA_A 1608 // Alpha OMCA +#define BOARD_OMCA 1609 // Final OMCA #define BOARD_SETHI 1610 // Sethi 3D_1 // @@ -219,7 +229,7 @@ #define BOARD_SELENA_COMPACT 2008 // Selena Compact (Power outputs: Hotend0, Hotend1, Bed0, Bed1, Fan0, Fan1) #define BOARD_BIQU_B300_V1_0 2009 // BIQU B300_V1.0 (Power outputs: Hotend0, Fan, Bed, SPI Driver) #define BOARD_MKS_SGEN_L 2010 // MKS-SGen-L (Power outputs: Hotend0, Hotend1, Bed, Fan) -#define BOARD_GMARSH_X6_REV1 2011 // GMARSH X6 board, revision 1 prototype +#define BOARD_GMARSH_X6_REV1 2011 // GMARSH X6, revision 1 prototype #define BOARD_BTT_SKR_V1_1 2012 // BigTreeTech SKR v1.1 (Power outputs: Hotend0, Hotend1, Fan, Bed) #define BOARD_BTT_SKR_V1_3 2013 // BigTreeTech SKR v1.3 (Power outputs: Hotend0, Hotend1, Fan, Bed) #define BOARD_BTT_SKR_V1_4 2014 // BigTreeTech SKR v1.4 (Power outputs: Hotend0, Hotend1, Fan, Bed) @@ -239,6 +249,7 @@ #define BOARD_BTT_SKR_V1_4_TURBO 2508 // BigTreeTech SKR v1.4 TURBO (Power outputs: Hotend0, Hotend1, Fan, Bed) #define BOARD_MKS_SGEN_L_V2 2509 // MKS SGEN_L V2 (Power outputs: Hotend0, Hotend1, Bed, Fan) #define BOARD_BTT_SKR_E3_TURBO 2510 // BigTreeTech SKR E3 Turbo (Power outputs: Hotend0, Hotend1, Bed, Fan0, Fan1) +#define BOARD_FLY_CDY 2511 // FLYmaker FLY CDY (Power outputs: Hotend0, Hotend1, Hotend2, Bed, Fan0, Fan1, Fan2) // // SAM3X8E ARM Cortex M3 @@ -271,6 +282,7 @@ #define BOARD_ARCHIM2 3024 // UltiMachine Archim2 (with TMC2130 drivers) #define BOARD_ALLIGATOR 3025 // Alligator Board R2 #define BOARD_CNCONTROLS_15D 3026 // Cartesio CN Controls V15 on DUE +#define BOARD_KRATOS32 3027 // K.3D Kratos32 (Arduino Due Shield) // // SAM3X8C ARM Cortex M3 @@ -283,11 +295,11 @@ // STM32 ARM Cortex-M3 // -#define BOARD_MALYAN_M200_V2 4000 // STM32F070CB STM32F0 controller +#define BOARD_MALYAN_M200_V2 4000 // STM32F070CB controller #define BOARD_MALYAN_M300 4001 // STM32F070-based delta #define BOARD_STM32F103RE 4002 // STM32F103RE Libmaple-based STM32F1 controller -#define BOARD_MALYAN_M200 4003 // STM32C8T6 Libmaple-based STM32F1 controller -#define BOARD_STM3R_MINI 4004 // STM32F103RE Libmaple-based STM32F1 controller +#define BOARD_MALYAN_M200 4003 // STM32C8T6 Libmaple-based STM32F1 controller +#define BOARD_STM3R_MINI 4004 // STM32F103RE Libmaple-based STM32F1 controller #define BOARD_GTM32_PRO_VB 4005 // STM32F103VET6 controller #define BOARD_GTM32_MINI 4006 // STM32F103VET6 controller #define BOARD_GTM32_MINI_A30 4007 // STM32F103VET6 controller @@ -301,26 +313,42 @@ #define BOARD_MKS_ROBIN_LITE 4015 // MKS Robin Lite/Lite2 (STM32F103RCT6) #define BOARD_MKS_ROBIN_LITE3 4016 // MKS Robin Lite3 (STM32F103RCT6) #define BOARD_MKS_ROBIN_PRO 4017 // MKS Robin Pro (STM32F103ZET6) -#define BOARD_MKS_ROBIN_E3 4018 // MKS Robin E3 (STM32F103RCT6) -#define BOARD_MKS_ROBIN_E3D 4019 // MKS Robin E3D (STM32F103RCT6) -#define BOARD_MKS_ROBIN_E3P 4020 // MKS Robin E3p (STM32F103VET6) -#define BOARD_BTT_SKR_MINI_V1_1 4021 // BigTreeTech SKR Mini v1.1 (STM32F103RC) -#define BOARD_BTT_SKR_MINI_E3_V1_0 4022 // BigTreeTech SKR Mini E3 (STM32F103RC) -#define BOARD_BTT_SKR_MINI_E3_V1_2 4023 // BigTreeTech SKR Mini E3 V1.2 (STM32F103RC) -#define BOARD_BTT_SKR_MINI_E3_V2_0 4024 // BigTreeTech SKR Mini E3 V2.0 (STM32F103RC) -#define BOARD_BTT_SKR_E3_DIP 4025 // BigTreeTech SKR E3 DIP V1.0 (STM32F103RC / STM32F103RE) -#define BOARD_JGAURORA_A5S_A1 4026 // JGAurora A5S A1 (STM32F103ZET6) -#define BOARD_FYSETC_AIO_II 4027 // FYSETC AIO_II -#define BOARD_FYSETC_CHEETAH 4028 // FYSETC Cheetah -#define BOARD_FYSETC_CHEETAH_V12 4029 // FYSETC Cheetah V1.2 -#define BOARD_LONGER3D_LK 4030 // Alfawise U20/U20+/U30 (Longer3D LK1/2) / STM32F103VET6 -#define BOARD_CCROBOT_MEEB_3DP 4031 // ccrobot-online.com MEEB_3DP (STM32F103RC) -#define BOARD_CHITU3D_V5 4032 // Chitu3D TronXY X5SA V5 Board -#define BOARD_CHITU3D_V6 4033 // Chitu3D TronXY X5SA V5 Board -#define BOARD_CREALITY_V4 4034 // Creality v4.x (STM32F103RE) -#define BOARD_CREALITY_V427 4035 // Creality v4.2.7 (STM32F103RE) -#define BOARD_TRIGORILLA_PRO 4036 // Trigorilla Pro (STM32F103ZET6) -#define BOARD_FLY_MINI 4037 // FLY MINI (STM32F103RCT6) +#define BOARD_MKS_ROBIN_E3 4018 // MKS Robin E3 (STM32F103RCT6) +#define BOARD_MKS_ROBIN_E3_V1_1 4019 // MKS Robin E3 V1.1 (STM32F103RCT6) +#define BOARD_MKS_ROBIN_E3D 4020 // MKS Robin E3D (STM32F103RCT6) +#define BOARD_MKS_ROBIN_E3D_V1_1 4021 // MKS Robin E3D V1.1 (STM32F103RCT6) +#define BOARD_MKS_ROBIN_E3P 4022 // MKS Robin E3p (STM32F103VET6) +#define BOARD_BTT_SKR_MINI_V1_1 4023 // BigTreeTech SKR Mini v1.1 (STM32F103RC) +#define BOARD_BTT_SKR_MINI_E3_V1_0 4024 // BigTreeTech SKR Mini E3 (STM32F103RC) +#define BOARD_BTT_SKR_MINI_E3_V1_2 4025 // BigTreeTech SKR Mini E3 V1.2 (STM32F103RC) +#define BOARD_BTT_SKR_MINI_E3_V2_0 4026 // BigTreeTech SKR Mini E3 V2.0 (STM32F103RC / STM32F103RE) +#define BOARD_BTT_SKR_MINI_MZ_V1_0 4027 // BigTreeTech SKR Mini MZ V1.0 (STM32F103RC) +#define BOARD_BTT_SKR_E3_DIP 4028 // BigTreeTech SKR E3 DIP V1.0 (STM32F103RC / STM32F103RE) +#define BOARD_BTT_SKR_CR6 4029 // BigTreeTech SKR CR6 v1.0 (STM32F103RE) +#define BOARD_JGAURORA_A5S_A1 4030 // JGAurora A5S A1 (STM32F103ZET6) +#define BOARD_FYSETC_AIO_II 4031 // FYSETC AIO_II +#define BOARD_FYSETC_CHEETAH 4032 // FYSETC Cheetah +#define BOARD_FYSETC_CHEETAH_V12 4033 // FYSETC Cheetah V1.2 +#define BOARD_LONGER3D_LK 4034 // Alfawise U20/U20+/U30 (Longer3D LK1/2) / STM32F103VET6 +#define BOARD_CCROBOT_MEEB_3DP 4035 // ccrobot-online.com MEEB_3DP (STM32F103RC) +#define BOARD_CHITU3D_V5 4036 // Chitu3D TronXY X5SA V5 Board +#define BOARD_CHITU3D_V6 4037 // Chitu3D TronXY X5SA V6 Board +#define BOARD_CHITU3D_V9 4038 // Chitu3D TronXY X5SA V9 Board +#define BOARD_CREALITY_V4 4039 // Creality v4.x (STM32F103RE) +#define BOARD_CREALITY_V427 4040 // Creality v4.2.7 (STM32F103RE) +#define BOARD_CREALITY_V4210 4041 // Creality v4.2.10 (STM32F103RE) as found in the CR-30 +#define BOARD_CREALITY_V431 4042 // Creality v4.3.1 (STM32F103RE) +#define BOARD_CREALITY_V452 4043 // Creality v4.5.2 (STM32F103RE) +#define BOARD_CREALITY_V453 4044 // Creality v4.5.3 (STM32F103RE) +#define BOARD_TRIGORILLA_PRO 4045 // Trigorilla Pro (STM32F103ZET6) +#define BOARD_FLY_MINI 4046 // FLYmaker FLY MINI (STM32F103RCT6) +#define BOARD_FLSUN_HISPEED 4047 // FLSUN HiSpeedV1 (STM32F103VET6) +#define BOARD_BEAST 4048 // STM32F103RET6 Libmaple-based controller +#define BOARD_MINGDA_MPX_ARM_MINI 4049 // STM32F103ZET6 Mingda MD-16 +#define BOARD_GTM32_PRO_VD 4050 // STM32F103VET6 controller +#define BOARD_ZONESTAR_ZM3E2 4051 // Zonestar ZM3E2 (STM32F103RCT6) +#define BOARD_ZONESTAR_ZM3E4 4052 // Zonestar ZM3E4 V1 (STM32F103VCT6) +#define BOARD_ZONESTAR_ZM3E4V2 4053 // Zonestar ZM3E4 V2 (STM32F103VCT6) // // ARM Cortex-M4F @@ -333,46 +361,57 @@ // STM32 ARM Cortex-M4F // -#define BOARD_BEAST 4200 // STM32F4xxVxT6 Libmaple-based STM32F4 controller -#define BOARD_GENERIC_STM32F4 4201 // STM32 STM32GENERIC-based STM32F4 controller -#define BOARD_ARMED 4202 // Arm'ed STM32F4-based controller -#define BOARD_RUMBA32_V1_0 4203 // RUMBA32 STM32F446VET6 based controller from Aus3D -#define BOARD_RUMBA32_V1_1 4204 // RUMBA32 STM32F446VET6 based controller from Aus3D -#define BOARD_RUMBA32_MKS 4205 // RUMBA32 STM32F446VET6 based controller from Makerbase -#define BOARD_BLACK_STM32F407VE 4206 // BLACK_STM32F407VE -#define BOARD_BLACK_STM32F407ZE 4207 // BLACK_STM32F407ZE -#define BOARD_STEVAL_3DP001V1 4208 // STEVAL-3DP001V1 3D PRINTER BOARD -#define BOARD_BTT_SKR_PRO_V1_1 4209 // BigTreeTech SKR Pro v1.1 (STM32F407ZG) -#define BOARD_BTT_SKR_PRO_V1_2 4210 // BigTreeTech SKR Pro v1.2 (STM32F407ZG) -#define BOARD_BTT_BTT002_V1_0 4211 // BigTreeTech BTT002 v1.0 (STM32F407VG) -#define BOARD_BTT_GTR_V1_0 4212 // BigTreeTech GTR v1.0 (STM32F407IGT) -#define BOARD_LERDGE_K 4213 // Lerdge K (STM32F407ZG) -#define BOARD_LERDGE_S 4214 // Lerdge S (STM32F407VE) -#define BOARD_LERDGE_X 4215 // Lerdge X (STM32F407VE) -#define BOARD_VAKE403D 4216 // VAkE 403D (STM32F446VET6) -#define BOARD_FYSETC_S6 4217 // FYSETC S6 board -#define BOARD_FYSETC_S6_V2_0 4218 // FYSETC S6 v2.0 board -#define BOARD_FLYF407ZG 4219 // FLYF407ZG board (STM32F407ZG) -#define BOARD_MKS_ROBIN2 4220 // MKS_ROBIN2 (STM32F407ZE) +#define BOARD_ARMED 4200 // Arm'ed STM32F4-based controller +#define BOARD_RUMBA32_V1_0 4201 // RUMBA32 STM32F446VET6 based controller from Aus3D +#define BOARD_RUMBA32_V1_1 4202 // RUMBA32 STM32F446VET6 based controller from Aus3D +#define BOARD_RUMBA32_MKS 4203 // RUMBA32 STM32F446VET6 based controller from Makerbase +#define BOARD_BLACK_STM32F407VE 4204 // BLACK_STM32F407VE +#define BOARD_BLACK_STM32F407ZE 4205 // BLACK_STM32F407ZE +#define BOARD_STEVAL_3DP001V1 4206 // STEVAL-3DP001V1 3D PRINTER BOARD +#define BOARD_BTT_SKR_PRO_V1_1 4207 // BigTreeTech SKR Pro v1.1 (STM32F407ZGT6) +#define BOARD_BTT_SKR_PRO_V1_2 4208 // BigTreeTech SKR Pro v1.2 (STM32F407ZGT6) +#define BOARD_BTT_BTT002_V1_0 4209 // BigTreeTech BTT002 v1.0 (STM32F407VGT6) +#define BOARD_BTT_E3_RRF 4210 // BigTreeTech E3 RRF (STM32F407VGT6) +#define BOARD_BTT_SKR_V2_0_REV_A 4211 // BigTreeTech SKR v2.0 Rev A (STM32F407VGT6) +#define BOARD_BTT_SKR_V2_0_REV_B 4212 // BigTreeTech SKR v2.0 Rev B (STM32F407VGT6) +#define BOARD_BTT_GTR_V1_0 4213 // BigTreeTech GTR v1.0 (STM32F407IGT) +#define BOARD_BTT_OCTOPUS_V1_0 4214 // BigTreeTech Octopus v1.0 (STM32F446ZET6) +#define BOARD_BTT_OCTOPUS_V1_1 4215 // BigTreeTech Octopus v1.1 (STM32F446ZET6) +#define BOARD_LERDGE_K 4216 // Lerdge K (STM32F407ZG) +#define BOARD_LERDGE_S 4217 // Lerdge S (STM32F407VE) +#define BOARD_LERDGE_X 4218 // Lerdge X (STM32F407VE) +#define BOARD_VAKE403D 4219 // VAkE 403D (STM32F446VET6) +#define BOARD_FYSETC_S6 4220 // FYSETC S6 (STM32F446VET6) +#define BOARD_FYSETC_S6_V2_0 4221 // FYSETC S6 v2.0 (STM32F446VET6) +#define BOARD_FYSETC_SPIDER 4222 // FYSETC Spider (STM32F446VET6) +#define BOARD_FLYF407ZG 4223 // FLYmaker FLYF407ZG (STM32F407ZG) +#define BOARD_MKS_ROBIN2 4224 // MKS_ROBIN2 (STM32F407ZE) +#define BOARD_MKS_ROBIN_PRO_V2 4225 // MKS Robin Pro V2 (STM32F407VE) +#define BOARD_MKS_ROBIN_NANO_V3 4226 // MKS Robin Nano V3 (STM32F407VG) +#define BOARD_MKS_MONSTER8 4227 // MKS Monster8 (STM32F407VGT6) +#define BOARD_ANET_ET4 4228 // ANET ET4 V1.x (STM32F407VGT6) +#define BOARD_ANET_ET4P 4229 // ANET ET4P V1.x (STM32F407VGT6) +#define BOARD_FYSETC_CHEETAH_V20 4230 // FYSETC Cheetah V2.0 // // ARM Cortex M7 // -#define BOARD_THE_BORG 5000 // THE-BORG (Power outputs: Hotend0, Hotend1, Bed, Fan) -#define BOARD_REMRAM_V1 5001 // RemRam v1 -#define BOARD_TEENSY41 5002 // Teensy 4.1 -#define BOARD_T41U5XBB 5003 // T41U5XBB Teensy 4.1 breakout board -#define BOARD_NUCLEO_F767ZI 5004 // ST NUCLEO-F767ZI Dev Board +#define BOARD_REMRAM_V1 5000 // RemRam v1 +#define BOARD_TEENSY41 5001 // Teensy 4.1 +#define BOARD_T41U5XBB 5002 // T41U5XBB Teensy 4.1 breakout board +#define BOARD_NUCLEO_F767ZI 5003 // ST NUCLEO-F767ZI Dev Board +#define BOARD_BTT_SKR_SE_BX 5004 // BigTreeTech SKR SE BX (STM32H743II) // // Espressif ESP32 WiFi // #define BOARD_ESPRESSIF_ESP32 6000 // Generic ESP32 -#define BOARD_MRR_ESPA 6001 // MRR ESPA board based on ESP32 (native pins only) -#define BOARD_MRR_ESPE 6002 // MRR ESPE board based on ESP32 (with I2S stepper stream) +#define BOARD_MRR_ESPA 6001 // MRR ESPA based on ESP32 (native pins only) +#define BOARD_MRR_ESPE 6002 // MRR ESPE based on ESP32 (with I2S stepper stream) #define BOARD_E4D_BOX 6003 // E4d@BOX +#define BOARD_FYSETC_E4 6004 // FYSETC E4 // // SAMD51 ARM Cortex M4 @@ -394,5 +433,3 @@ #define _MB_1(B) (defined(BOARD_##B) && MOTHERBOARD==BOARD_##B) #define MB(V...) DO(MB,||,V) - -#define IS_MELZI MB(MELZI, MELZI_CREALITY, MELZI_MAKR3D, MELZI_MALYAN, MELZI_TRONXY, MELZI_V2) diff --git a/Marlin/src/core/bug_on.h b/Marlin/src/core/bug_on.h new file mode 100644 index 000000000000..cc745f259b7b --- /dev/null +++ b/Marlin/src/core/bug_on.h @@ -0,0 +1,39 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Copyright (c) 2021 X-Ryl669 [https://blog.cyril.by] + * + * 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 + +// We need SERIAL_ECHOPAIR and macros.h +#include "serial.h" + +#if ENABLED(POSTMORTEM_DEBUGGING) + // Useful macro for stopping the CPU on an unexpected condition + // This is used like SERIAL_ECHOPAIR, that is: a key-value call of the local variables you want + // to dump to the serial port before stopping the CPU. + // \/ Don't replace by SERIAL_ECHOPAIR since ONLY_FILENAME cannot be transformed to a PGM string on Arduino and it breaks building + #define BUG_ON(V...) do { SERIAL_ECHO(ONLY_FILENAME); SERIAL_ECHO(__LINE__); SERIAL_ECHOLNPGM(": "); SERIAL_ECHOLNPAIR(V); SERIAL_FLUSHTX(); *(char*)0 = 42; } while(0) +#elif ENABLED(MARLIN_DEV_MODE) + // Don't stop the CPU here, but at least dump the bug on the serial port + // \/ Don't replace by SERIAL_ECHOPAIR since ONLY_FILENAME cannot be transformed to a PGM string on Arduino and it breaks building + #define BUG_ON(V...) do { SERIAL_ECHO(ONLY_FILENAME); SERIAL_ECHO(__LINE__); SERIAL_ECHOLNPGM(": BUG!"); SERIAL_ECHOLNPAIR(V); SERIAL_FLUSHTX(); } while(0) +#else + // Release mode, let's ignore the bug + #define BUG_ON(V...) NOOP +#endif diff --git a/Marlin/src/core/debug_out.h b/Marlin/src/core/debug_out.h index 6ae1b9d8bb97..a7dc32622d1e 100644 --- a/Marlin/src/core/debug_out.h +++ b/Marlin/src/core/debug_out.h @@ -27,7 +27,7 @@ // #undef DEBUG_SECTION -#undef DEBUG_PRINT_P +#undef DEBUG_ECHOPGM_P #undef DEBUG_ECHO_START #undef DEBUG_ERROR_START #undef DEBUG_CHAR @@ -59,7 +59,7 @@ #include "debug_section.h" #define DEBUG_SECTION(N,S,D) SectionLog N(PSTR(S),D) - #define DEBUG_PRINT_P(P) serialprintPGM(P) + #define DEBUG_ECHOPGM_P(P) SERIAL_ECHOPGM_P(P) #define DEBUG_ECHO_START SERIAL_ECHO_START #define DEBUG_ERROR_START SERIAL_ERROR_START #define DEBUG_CHAR SERIAL_CHAR @@ -89,7 +89,7 @@ #else #define DEBUG_SECTION(...) NOOP - #define DEBUG_PRINT_P(P) NOOP + #define DEBUG_ECHOPGM_P(P) NOOP #define DEBUG_ECHO_START() NOOP #define DEBUG_ERROR_START() NOOP #define DEBUG_CHAR(...) NOOP diff --git a/Marlin/src/core/debug_section.h b/Marlin/src/core/debug_section.h index 7f39bc7424e7..ef1511e6f082 100644 --- a/Marlin/src/core/debug_section.h +++ b/Marlin/src/core/debug_section.h @@ -38,12 +38,12 @@ class SectionLog { bool debug; void echo_msg(PGM_P const pre) { - serialprintPGM(pre); + SERIAL_ECHOPGM_P(pre); if (the_msg) { SERIAL_CHAR(' '); - serialprintPGM(the_msg); + SERIAL_ECHOPGM_P(the_msg); } SERIAL_CHAR(' '); - print_xyz(current_position); + print_pos(current_position); } }; diff --git a/Marlin/src/core/drivers.h b/Marlin/src/core/drivers.h index 3a0e620923ad..0a76410274bb 100644 --- a/Marlin/src/core/drivers.h +++ b/Marlin/src/core/drivers.h @@ -60,6 +60,9 @@ #define AXIS_DRIVER_TYPE_X(T) _AXIS_DRIVER_TYPE(X,T) #define AXIS_DRIVER_TYPE_Y(T) _AXIS_DRIVER_TYPE(Y,T) #define AXIS_DRIVER_TYPE_Z(T) _AXIS_DRIVER_TYPE(Z,T) +#define AXIS_DRIVER_TYPE_I(T) _AXIS_DRIVER_TYPE(I,T) +#define AXIS_DRIVER_TYPE_J(T) _AXIS_DRIVER_TYPE(J,T) +#define AXIS_DRIVER_TYPE_K(T) _AXIS_DRIVER_TYPE(K,T) #define AXIS_DRIVER_TYPE_X2(T) (EITHER(X_DUAL_STEPPER_DRIVERS, DUAL_X_CARRIAGE) && _AXIS_DRIVER_TYPE(X2,T)) #define AXIS_DRIVER_TYPE_Y2(T) (ENABLED(Y_DUAL_STEPPER_DRIVERS) && _AXIS_DRIVER_TYPE(Y2,T)) @@ -83,6 +86,7 @@ #define HAS_E_DRIVER(T) (0 RREPEAT2(E_STEPPERS, _OR_ADTE, T)) #define HAS_DRIVER(T) ( AXIS_DRIVER_TYPE_X(T) || AXIS_DRIVER_TYPE_Y(T) || AXIS_DRIVER_TYPE_Z(T) \ + || AXIS_DRIVER_TYPE_I(T) || AXIS_DRIVER_TYPE_J(T) || AXIS_DRIVER_TYPE_K(T) \ || AXIS_DRIVER_TYPE_X2(T) || AXIS_DRIVER_TYPE_Y2(T) || AXIS_DRIVER_TYPE_Z2(T) \ || AXIS_DRIVER_TYPE_Z3(T) || AXIS_DRIVER_TYPE_Z4(T) || HAS_E_DRIVER(T) ) @@ -153,9 +157,11 @@ #define _OR_EAH(N,T) || AXIS_HAS_##T(E##N) #define E_AXIS_HAS(T) (0 _OR_EAH(0,T) _OR_EAH(1,T) _OR_EAH(2,T) _OR_EAH(3,T) _OR_EAH(4,T) _OR_EAH(5,T) _OR_EAH(6,T) _OR_EAH(7,T)) -#define ANY_AXIS_HAS(T) ( AXIS_HAS_##T(X) || AXIS_HAS_##T(Y) || AXIS_HAS_##T(Z) \ - || AXIS_HAS_##T(X2) || AXIS_HAS_##T(Y2) || AXIS_HAS_##T(Z2) \ - || AXIS_HAS_##T(Z3) || AXIS_HAS_##T(Z4) || E_AXIS_HAS(T) ) +#define ANY_AXIS_HAS(T) ( AXIS_HAS_##T(X) || AXIS_HAS_##T(X2) \ + || AXIS_HAS_##T(Y) || AXIS_HAS_##T(Y2) \ + || AXIS_HAS_##T(Z) || AXIS_HAS_##T(Z2) || AXIS_HAS_##T(Z3) || AXIS_HAS_##T(Z4) \ + || AXIS_HAS_##T(I) || AXIS_HAS_##T(J) || AXIS_HAS_##T(K) \ + || E_AXIS_HAS(T) ) #if ANY_AXIS_HAS(STEALTHCHOP) #define HAS_STEALTHCHOP 1 diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index 60d9aa6b720a..8e97ec66a981 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -68,6 +68,7 @@ // ro Romanian // ru Russian // sk Slovak +// sv Swedish // tr Turkish // uk Ukrainian // vi Vietnamese @@ -91,7 +92,7 @@ #define MACHINE_UUID DEFAULT_MACHINE_UUID #endif -#define MARLIN_WEBSITE_URL "https://marlinfw.org" +#define MARLIN_WEBSITE_URL "marlinfw.org" //#if !defined(STRING_SPLASH_LINE3) && defined(WEBSITE_URL) // #define STRING_SPLASH_LINE3 WEBSITE_URL @@ -129,7 +130,9 @@ #define STR_COUNT_A " Count A:" #define STR_WATCHDOG_FIRED "Watchdog timeout. Reset required." #define STR_ERR_KILLED "Printer halted. kill() called!" +#define STR_FLOWMETER_FAULT "Coolant flow fault. Flowmeter safety is active. Attention required." #define STR_ERR_STOPPED "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)" +#define STR_ERR_SERIAL_MISMATCH "Serial status mismatch" #define STR_BUSY_PROCESSING "busy: processing" #define STR_BUSY_PAUSED_FOR_USER "busy: paused for user" #define STR_BUSY_PAUSED_FOR_INPUT "busy: paused for input" @@ -137,24 +140,7 @@ #define STR_RESEND "Resend: " #define STR_UNKNOWN_COMMAND "Unknown command: \"" #define STR_ACTIVE_EXTRUDER "Active Extruder: " -#define STR_X_MIN "x_min" -#define STR_X_MAX "x_max" -#define STR_X2_MIN "x2_min" -#define STR_X2_MAX "x2_max" -#define STR_Y_MIN "y_min" -#define STR_Y_MAX "y_max" -#define STR_Y2_MIN "y2_min" -#define STR_Y2_MAX "y2_max" -#define STR_Z_MIN "z_min" -#define STR_Z_MAX "z_max" -#define STR_Z2_MIN "z2_min" -#define STR_Z2_MAX "z2_max" -#define STR_Z3_MIN "z3_min" -#define STR_Z3_MAX "z3_max" -#define STR_Z4_MIN "z4_min" -#define STR_Z4_MAX "z4_max" -#define STR_Z_PROBE "z_probe" -#define STR_FILAMENT_RUNOUT_SENSOR "filament" + #define STR_PROBE_OFFSET "Probe Offset" #define STR_SKEW_MIN "min_skew_factor: " #define STR_SKEW_MAX "max_skew_factor: " @@ -219,7 +205,7 @@ // temperature.cpp strings #define STR_PID_AUTOTUNE_START "PID Autotune start" -#define STR_PID_BAD_EXTRUDER_NUM "PID Autotune failed! Bad extruder number" +#define STR_PID_BAD_HEATER_ID "PID Autotune failed! Bad heater id" #define STR_PID_TEMP_TOO_HIGH "PID Autotune failed! Temperature too high" #define STR_PID_TIMEOUT "PID Autotune failed! timeout" #define STR_BIAS " bias: " @@ -244,6 +230,8 @@ #define STR_HEATER_BED "bed" #define STR_HEATER_CHAMBER "chamber" +#define STR_COOLER "cooler" +#define STR_LASER_TEMP "laser temperature" #define STR_STOPPED_HEATER ", system stopped! Heater_ID: " #define STR_REDUNDANCY "Heater switched off. Temperature difference between temp sensors is too high !" @@ -271,17 +259,43 @@ #define STR_REMINDER_SAVE_SETTINGS "Remember to save!" #define STR_PASSWORD_SET "Password is " -// LCD Menu Messages +// +// 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" -#define LANGUAGE_DATA_INCL_(M) STRINGIFY_(fontdata/langdata_##M.h) -#define LANGUAGE_DATA_INCL(M) LANGUAGE_DATA_INCL_(M) +#if HAS_Y_AXIS + #define STR_Y_MIN "y_min" + #define STR_Y_MAX "y_max" + #define STR_Y2_MIN "y2_min" + #define STR_Y2_MAX "y2_max" +#endif -#define LANGUAGE_INCL_(M) STRINGIFY_(../lcd/language/language_##M.h) -#define LANGUAGE_INCL(M) LANGUAGE_INCL_(M) +#if HAS_Z_AXIS + #define STR_Z_MIN "z_min" + #define STR_Z_MAX "z_max" + #define STR_Z2_MIN "z2_min" + #define STR_Z2_MAX "z2_max" + #define STR_Z3_MIN "z3_min" + #define STR_Z3_MAX "z3_max" + #define STR_Z4_MIN "z4_min" + #define STR_Z4_MAX "z4_max" +#endif +#define STR_Z_PROBE "z_probe" +#define STR_PROBE_EN "probe_en" +#define STR_FILAMENT_RUNOUT_SENSOR "filament" + +// General axis names #define STR_X "X" #define STR_Y "Y" #define STR_Z "Z" +#define STR_I AXIS4_STR +#define STR_J AXIS5_STR +#define STR_K AXIS6_STR #define STR_E "E" #if IS_KINEMATIC #define STR_A "A" @@ -301,8 +315,114 @@ #define LCD_STR_A STR_A #define LCD_STR_B STR_B #define LCD_STR_C STR_C +#define LCD_STR_I STR_I +#define LCD_STR_J STR_J +#define LCD_STR_K STR_K #define LCD_STR_E STR_E +// Extra Axis and Endstop Names +#if LINEAR_AXES >= 4 + #if AXIS4_NAME == 'A' + #define AXIS4_STR "A" + #define STR_I_MIN "a_min" + #define STR_I_MAX "a_max" + #elif AXIS4_NAME == 'B' + #define AXIS4_STR "B" + #define STR_I_MIN "b_min" + #define STR_I_MAX "b_max" + #elif AXIS4_NAME == 'C' + #define AXIS4_STR "C" + #define STR_I_MIN "c_min" + #define STR_I_MAX "c_max" + #elif AXIS4_NAME == 'U' + #define AXIS4_STR "U" + #define STR_I_MIN "u_min" + #define STR_I_MAX "u_max" + #elif AXIS4_NAME == 'V' + #define AXIS4_STR "V" + #define STR_I_MIN "v_min" + #define STR_I_MAX "v_max" + #elif AXIS4_NAME == 'W' + #define AXIS4_STR "W" + #define STR_I_MIN "w_min" + #define STR_I_MAX "w_max" + #else + #define AXIS4_STR "A" + #define STR_I_MIN "a_min" + #define STR_I_MAX "a_max" + #endif +#else + #define AXIS4_STR "" +#endif + +#if LINEAR_AXES >= 5 + #if AXIS5_NAME == 'A' + #define AXIS5_STR "A" + #define STR_J_MIN "a_min" + #define STR_J_MAX "a_max" + #elif AXIS5_NAME == 'B' + #define AXIS5_STR "B" + #define STR_J_MIN "b_min" + #define STR_J_MAX "b_max" + #elif AXIS5_NAME == 'C' + #define AXIS5_STR "C" + #define STR_J_MIN "c_min" + #define STR_J_MAX "c_max" + #elif AXIS5_NAME == 'U' + #define AXIS5_STR "U" + #define STR_J_MIN "u_min" + #define STR_J_MAX "u_max" + #elif AXIS5_NAME == 'V' + #define AXIS5_STR "V" + #define STR_J_MIN "v_min" + #define STR_J_MAX "v_max" + #elif AXIS5_NAME == 'W' + #define AXIS5_STR "W" + #define STR_J_MIN "w_min" + #define STR_J_MAX "w_max" + #else + #define AXIS5_STR "B" + #define STR_J_MIN "b_min" + #define STR_J_MAX "b_max" + #endif +#else + #define AXIS5_STR "" +#endif + +#if LINEAR_AXES >= 6 + #if AXIS6_NAME == 'A' + #define AXIS6_STR "A" + #define STR_K_MIN "a_min" + #define STR_K_MAX "a_max" + #elif AXIS6_NAME == 'B' + #define AXIS6_STR "B" + #define STR_K_MIN "b_min" + #define STR_K_MAX "b_max" + #elif AXIS6_NAME == 'C' + #define AXIS6_STR "C" + #define STR_K_MIN "c_min" + #define STR_K_MAX "c_max" + #elif AXIS6_NAME == 'U' + #define AXIS6_STR "U" + #define STR_K_MIN "u_min" + #define STR_K_MAX "u_max" + #elif AXIS6_NAME == 'V' + #define AXIS6_STR "V" + #define STR_K_MIN "v_min" + #define STR_K_MAX "v_max" + #elif AXIS6_NAME == 'W' + #define AXIS6_STR "W" + #define STR_K_MIN "w_min" + #define STR_K_MAX "w_max" + #else + #define AXIS6_STR "C" + #define STR_K_MIN "c_min" + #define STR_K_MAX "c_max" + #endif +#else + #define AXIS6_STR "" +#endif + #if EITHER(HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL) // Custom characters defined in the first 8 characters of the LCD @@ -380,6 +500,18 @@ #define LCD_STR_E6 "E" LCD_STR_N6 #define LCD_STR_E7 "E" LCD_STR_N7 +// Include localized LCD Menu Messages + +#define LANGUAGE_DATA_INCL_(M) STRINGIFY_(fontdata/langdata_##M.h) +#define LANGUAGE_DATA_INCL(M) LANGUAGE_DATA_INCL_(M) + +#define LANGUAGE_INCL_(M) STRINGIFY_(../lcd/language/language_##M.h) +#define LANGUAGE_INCL(M) LANGUAGE_INCL_(M) + +// Use superscripts, if possible. Evaluated at point of use. +#define SUPERSCRIPT_TWO TERN(NOT_EXTENDED_ISO10646_1_5X7, "^2", "²") +#define SUPERSCRIPT_THREE TERN(NOT_EXTENDED_ISO10646_1_5X7, "^3", "³") + #include "multi_language.h" // Allow multiple languages #include "../lcd/language/language_en.h" diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index 21bb32c4cf24..86368bf5e718 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -36,12 +36,21 @@ #define _XMIN_ 100 #define _YMIN_ 200 #define _ZMIN_ 300 +#define _IMIN_ 500 +#define _JMIN_ 600 +#define _KMIN_ 700 #define _XMAX_ 101 #define _YMAX_ 201 #define _ZMAX_ 301 +#define _IMAX_ 501 +#define _JMAX_ 601 +#define _KMAX_ 701 #define _XDIAG_ 102 #define _YDIAG_ 202 #define _ZDIAG_ 302 +#define _IDIAG_ 502 +#define _JDIAG_ 602 +#define _KDIAG_ 702 #define _E0DIAG_ 400 #define _E1DIAG_ 401 #define _E2DIAG_ 402 @@ -53,6 +62,7 @@ #define _FORCE_INLINE_ __attribute__((__always_inline__)) __inline__ #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"))) @@ -60,12 +70,10 @@ #define _O2 __attribute__((optimize("O2"))) #define _O3 __attribute__((optimize("O3"))) +#define IS_CONSTEXPR(...) __builtin_constant_p(__VA_ARGS__) // Only valid solution with C++14. Should use std::is_constant_evaluated() in C++20 instead + #ifndef UNUSED - #if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) - #define UNUSED(X) (void)X - #else - #define UNUSED(x) ((void)(x)) - #endif + #define UNUSED(x) ((void)(x)) #endif // Clock speed factors @@ -88,17 +96,13 @@ #define _BV(n) (1<<(n)) #define TEST(n,b) (!!((n)&_BV(b))) #define SET_BIT_TO(N,B,TF) do{ if (TF) SBI(N,B); else CBI(N,B); }while(0) - #ifndef SBI - #define SBI(A,B) (A |= (1 << (B))) + #define SBI(A,B) (A |= _BV(B)) #endif - #ifndef CBI - #define CBI(A,B) (A &= ~(1 << (B))) + #define CBI(A,B) (A &= ~_BV(B)) #endif - #define TBI(N,B) (N ^= _BV(B)) - #define _BV32(b) (1UL << (b)) #define TEST32(n,b) !!((n)&_BV32(b)) #define SBI32(n,b) (n |= _BV32(b)) @@ -109,6 +113,7 @@ #define RADIANS(d) ((d)*float(M_PI)/180.0f) #define DEGREES(r) ((r)*180.0f/float(M_PI)) #define HYPOT2(x,y) (sq(x)+sq(y)) +#define NORMSQ(x,y,z) (sq(x)+sq(y)+sq(z)) #define CIRCLE_AREA(R) (float(M_PI) * sq(float(R))) #define CIRCLE_CIRC(R) (2 * float(M_PI) * float(R)) @@ -135,27 +140,27 @@ #define NOLESS(v, n) \ do{ \ - __typeof__(n) _n = (n); \ + __typeof__(v) _n = (n); \ if (_n > v) v = _n; \ }while(0) #define NOMORE(v, n) \ do{ \ - __typeof__(n) _n = (n); \ + __typeof__(v) _n = (n); \ if (_n < v) v = _n; \ }while(0) #define LIMIT(v, n1, n2) \ do{ \ - __typeof__(n1) _n1 = (n1); \ - __typeof__(n2) _n2 = (n2); \ + __typeof__(v) _n1 = (n1); \ + __typeof__(v) _n2 = (n2); \ if (_n1 > v) v = _n1; \ else if (_n2 < v) v = _n2; \ }while(0) #endif -// Macros to chain up to 12 conditions +// Macros to chain up to 14 conditions #define _DO_1(W,C,A) (_##W##_1(A)) #define _DO_2(W,C,A,B) (_##W##_1(A) C _##W##_1(B)) #define _DO_3(W,C,A,V...) (_##W##_1(A) C _DO_2(W,C,V)) @@ -168,9 +173,12 @@ #define _DO_10(W,C,A,V...) (_##W##_1(A) C _DO_9(W,C,V)) #define _DO_11(W,C,A,V...) (_##W##_1(A) C _DO_10(W,C,V)) #define _DO_12(W,C,A,V...) (_##W##_1(A) C _DO_11(W,C,V)) +#define _DO_13(W,C,A,V...) (_##W##_1(A) C _DO_12(W,C,V)) +#define _DO_14(W,C,A,V...) (_##W##_1(A) C _DO_13(W,C,V)) +#define _DO_15(W,C,A,V...) (_##W##_1(A) C _DO_14(W,C,V)) #define __DO_N(W,C,N,V...) _DO_##N(W,C,V) #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) +#define DO(W,C,V...) (_DO_N(W,C,NUM_ARGS(V),V)) // Macros to support option testing #define _CAT(a,V...) a##V @@ -186,20 +194,37 @@ #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) -#define TERN(O,A,B) _TERN(_ENA_1(O),B,A) // OPTION converted to '0' or '1' -#define TERN0(O,A) _TERN(_ENA_1(O),0,A) // OPTION converted to A or '0' -#define TERN1(O,A) _TERN(_ENA_1(O),1,A) // OPTION converted to A or '1' -#define TERN_(O,A) _TERN(_ENA_1(O),,A) // OPTION converted to A or '' +#define TERN(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' +#define TERN_(O,A) _TERN(_ENA_1(O),,A) // OPTION ? 'A' : '' #define _TERN(E,V...) __TERN(_CAT(T_,E),V) // Prepend 'T_' to get 'T_0' or 'T_1' #define __TERN(T,V...) ___TERN(_CAT(_NO,T),V) // Prepend '_NO' to get '_NOT_0' or '_NOT_1' #define ___TERN(P,V...) THIRD(P,V) // If first argument has a comma, A. Else B. +#define _OPTARG(A...) , A +#define OPTARG(O,A...) TERN_(O,DEFER4(_OPTARG)(A)) +#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. +// 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 SUM_TERN(O,B,A) ((B) PLUS_TERN0(O,A)) // ((B) (OPTION ? '+ (A)' : '')) +#define DIFF_TERN(O,B,A) ((B) MINUS_TERN0(O,A)) // ((B) (OPTION ? '- (A)' : '')) + +#define IF_ENABLED TERN_ +#define IF_DISABLED(O,A) TERN(O,,A) + #define ANY(V...) !DISABLED(V) #define NONE(V...) DISABLED(V) #define ALL(V...) ENABLED(V) #define BOTH(V1,V2) ALL(V1,V2) #define EITHER(V1,V2) ANY(V1,V2) +#define MANY(V...) (COUNT_ENABLED(V) > 1) // Macros to support pins/buttons exist testing #define PIN_EXISTS(PN) (defined(PN##_PIN) && PN##_PIN >= 0) @@ -213,6 +238,7 @@ #define ANY_BUTTON(V...) DO(BTNEX,||,V) #define WITHIN(N,L,H) ((N) >= (L) && (N) <= (H)) +#define ISEOL(C) ((C) == '\n' || (C) == '\r') #define NUMERIC(a) WITHIN(a, '0', '9') #define DECIMAL(a) (NUMERIC(a) || a == '.') #define HEXCHR(a) (NUMERIC(a) ? (a) - '0' : WITHIN(a, 'a', 'f') ? ((a) - 'a' + 10) : WITHIN(a, 'A', 'F') ? ((a) - 'A' + 10) : -1) @@ -225,6 +251,38 @@ memcpy(&a[0],&b[0],_MIN(sizeof(a),sizeof(b))); \ }while(0) +#define CODE_9( A,B,C,D,E,F,G,H,I,...) A; B; C; D; E; F; G; H; I +#define CODE_8( A,B,C,D,E,F,G,H,...) A; B; C; D; E; F; G; H +#define CODE_7( A,B,C,D,E,F,G,...) A; B; C; D; E; F; G +#define CODE_6( A,B,C,D,E,F,...) A; B; C; D; E; F +#define CODE_5( A,B,C,D,E,...) A; B; C; D; E +#define CODE_4( A,B,C,D,...) A; B; C; D +#define CODE_3( A,B,C,...) A; B; C +#define CODE_2( A,B,...) A; B +#define CODE_1( A,...) A +#define _CODE_N(N,V...) CODE_##N(V) +#define CODE_N(N,V...) _CODE_N(N,V) + +#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 +#define GANG_13(A,B,C,D,E,F,G,H,I,J,K,L,M...) A B C D E F G H I J K L M +#define GANG_12(A,B,C,D,E,F,G,H,I,J,K,L...) A B C D E F G H I J K L +#define GANG_11(A,B,C,D,E,F,G,H,I,J,K,...) A B C D E F G H I J K +#define GANG_10(A,B,C,D,E,F,G,H,I,J,...) A B C D E F G H I J +#define GANG_9( A,B,C,D,E,F,G,H,I,...) A B C D E F G H I +#define GANG_8( A,B,C,D,E,F,G,H,...) A B C D E F G H +#define GANG_7( A,B,C,D,E,F,G,...) A B C D E F G +#define GANG_6( A,B,C,D,E,F,...) A B C D E F +#define GANG_5( A,B,C,D,E,...) A B C D E +#define GANG_4( A,B,C,D,...) A B C D +#define GANG_3( A,B,C,...) A B C +#define GANG_2( A,B,...) A B +#define GANG_1( A,...) A +#define _GANG_N(N,V...) GANG_##N(V) +#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 #define LIST_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 LIST_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 @@ -242,10 +300,13 @@ #define LIST_3( A,B,C,...) A,B,C #define LIST_2( A,B,...) A,B #define LIST_1( A,...) A +#define LIST_0(...) #define _LIST_N(N,V...) LIST_##N(V) #define LIST_N(N,V...) _LIST_N(N,V) +#define LIST_N_1(N,K) _LIST_N(N,K,K,K,K,K,K,K,K,K,K,K,K,K,K,K,K) #define ARRAY_N(N,V...) { _LIST_N(N,V) } +#define ARRAY_N_1(N,K) { LIST_N_1(N,K) } #define _JOIN_1(O) (O) #define JOIN_N(N,C,V...) (DO(JOIN,C,LIST_N(N,V))) @@ -283,13 +344,18 @@ #define RSQRT(x) (1.0f / sqrtf(x)) #define CEIL(x) ceilf(x) #define FLOOR(x) floorf(x) +#define TRUNC(x) truncf(x) #define LROUND(x) lroundf(x) #define FMOD(x, y) fmodf(x, y) #define HYPOT(x,y) SQRT(HYPOT2(x,y)) // Use NUM_ARGS(__VA_ARGS__) to get the number of variadic arguments -#define _NUM_ARGS(_,Z,Y,X,W,V,U,T,S,R,Q,P,O,N,M,L,K,J,I,H,G,F,E,D,C,B,A,OUT,...) OUT -#define NUM_ARGS(V...) _NUM_ARGS(0,V,26,25,24,23,22,21,20,19,18,17,16,15,14,13,12,11,10,9,8,7,6,5,4,3,2,1,0) +#define _NUM_ARGS(_,n,m,l,k,j,i,h,g,f,e,d,c,b,a,Z,Y,X,W,V,U,T,S,R,Q,P,O,N,M,L,K,J,I,H,G,F,E,D,C,B,A,OUT,...) OUT +#define NUM_ARGS(V...) _NUM_ARGS(0,V,40,39,38,37,36,35,34,33,32,31,30,29,28,27,26,25,24,23,22,21,20,19,18,17,16,15,14,13,12,11,10,9,8,7,6,5,4,3,2,1,0) + +// Use TWO_ARGS(__VA_ARGS__) to get whether there are 1, 2, or >2 arguments +#define _TWO_ARGS(_,n,m,l,k,j,i,h,g,f,e,d,c,b,a,Z,Y,X,W,V,U,T,S,R,Q,P,O,N,M,L,K,J,I,H,G,F,E,D,C,B,A,OUT,...) OUT +#define TWO_ARGS(V...) _TWO_ARGS(0,V,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,2,1,0) #ifdef __cplusplus @@ -312,33 +378,108 @@ #endif + // Allow manipulating enumeration value like flags without ugly cast everywhere + #define ENUM_FLAGS(T) \ + 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, 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; } + + // C++11 solution that is standard compliant. is not available on all platform + namespace Private { + template struct enable_if { }; + template struct enable_if { typedef _Tp type; }; + + template struct is_same { enum { value = false }; }; + template struct is_same { enum { value = true }; }; + + template struct first_type_of { typedef T type; }; + template struct first_type_of { typedef T 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) \ + namespace Private { \ + template struct HasMember_ ## Member { \ + template static Yes& test( decltype(&C::Member) ) ; \ + template static No& test(...); \ + enum { value = sizeof(test(0)) == sizeof(Yes) }; }; \ + } + + // Call the method if it exists, but do nothing if it does not. The method is detected at compile time. + // If the method exists, this is inlined and does not cost anything. Else, an "empty" wrapper is created, returning a default value + #define CALL_IF_EXISTS_IMPL(Return, Method, ...) \ + HAS_MEMBER_IMPL(Method) \ + namespace Private { \ + template FORCE_INLINE typename enable_if::value, Return>::type Call_ ## Method(T * t, Args... a) { return static_cast(t->Method(a...)); } \ + _UNUSED static Return Call_ ## Method(...) { return __VA_ARGS__; } \ + } + #define CALL_IF_EXISTS(Return, That, Method, ...) \ + static_cast(Private::Call_ ## Method(That, ##__VA_ARGS__)) + + // Compile-time string manipulation + namespace CompileTimeString { + // Simple compile-time parser to find the position of the end of a string + constexpr const char* findStringEnd(const char *str) { + return *str ? findStringEnd(str + 1) : str; + } + + // Check whether a string contains a specific character + constexpr bool contains(const char *str, const char ch) { + return *str == ch ? true : (*str ? contains(str + 1, ch) : false); + } + // Find the last position of the specific character (should be called with findStringEnd) + constexpr const char* findLastPos(const char *str, const char ch) { + return *str == ch ? (str + 1) : findLastPos(str - 1, ch); + } + // Compile-time evaluation of the last part of a file path + // Typically used to shorten the path to file in compiled strings + // CompileTimeString::baseName(__FILE__) returns "macros.h" and not /path/to/Marlin/src/core/macros.h + constexpr const char* baseName(const char *str) { + return contains(str, '/') ? findLastPos(findStringEnd(str), '/') : str; + } + + // Find the first occurrence of a character in a string (or return the last position in the string) + constexpr const char* findFirst(const char *str, const char ch) { + return *str == ch || *str == 0 ? (str + 1) : findFirst(str + 1, ch); + } + // Compute the string length at compile time + constexpr unsigned stringLen(const char *str) { + return *str == 0 ? 0 : 1 + stringLen(str + 1); + } + } + + #define ONLY_FILENAME CompileTimeString::baseName(__FILE__) + /** Get the templated type name. This does not depends on RTTI, but on the preprocessor, so it should be quite safe to use even on old compilers. + WARNING: DO NOT RENAME THIS FUNCTION (or change the text inside the function to match what the preprocessor will generate) + The name is chosen very short since the binary will store "const char* gtn(T*) [with T = YourTypeHere]" so avoid long function name here */ + template + inline const char* gtn(T*) { + // It works on GCC by instantiating __PRETTY_FUNCTION__ and parsing the result. So the syntax here is very limited to GCC output + constexpr unsigned verboseChatLen = sizeof("const char* gtn(T*) [with T = ") - 1; + static char templateType[sizeof(__PRETTY_FUNCTION__) - verboseChatLen] = {}; + __builtin_memcpy(templateType, __PRETTY_FUNCTION__ + verboseChatLen, sizeof(__PRETTY_FUNCTION__) - verboseChatLen - 2); + return templateType; + } + #else - #define MIN_2(a,b) ((a)<(b)?(a):(b)) - #define MIN_3(a,V...) MIN_2(a,MIN_2(V)) - #define MIN_4(a,V...) MIN_2(a,MIN_3(V)) - #define MIN_5(a,V...) MIN_2(a,MIN_4(V)) - #define MIN_6(a,V...) MIN_2(a,MIN_5(V)) - #define MIN_7(a,V...) MIN_2(a,MIN_6(V)) - #define MIN_8(a,V...) MIN_2(a,MIN_7(V)) - #define MIN_9(a,V...) MIN_2(a,MIN_8(V)) - #define MIN_10(a,V...) MIN_2(a,MIN_9(V)) #define __MIN_N(N,V...) MIN_##N(V) #define _MIN_N(N,V...) __MIN_N(N,V) - #define _MIN(V...) _MIN_N(NUM_ARGS(V), V) + #define _MIN_N_REF() _MIN_N + #define _MIN(V...) EVAL(_MIN_N(TWO_ARGS(V),V)) + #define MIN_2(a,b) ((a)<(b)?(a):(b)) + #define MIN_3(a,V...) MIN_2(a,DEFER2(_MIN_N_REF)()(TWO_ARGS(V),V)) - #define MAX_2(a,b) ((a)>(b)?(a):(b)) - #define MAX_3(a,V...) MAX_2(a,MAX_2(V)) - #define MAX_4(a,V...) MAX_2(a,MAX_3(V)) - #define MAX_5(a,V...) MAX_2(a,MAX_4(V)) - #define MAX_6(a,V...) MAX_2(a,MAX_5(V)) - #define MAX_7(a,V...) MAX_2(a,MAX_6(V)) - #define MAX_8(a,V...) MAX_2(a,MAX_7(V)) - #define MAX_9(a,V...) MAX_2(a,MAX_8(V)) - #define MAX_10(a,V...) MAX_2(a,MAX_9(V)) #define __MAX_N(N,V...) MAX_##N(V) #define _MAX_N(N,V...) __MAX_N(N,V) - #define _MAX(V...) _MAX_N(NUM_ARGS(V), V) + #define _MAX_N_REF() _MAX_N + #define _MAX(V...) EVAL(_MAX_N(TWO_ARGS(V),V)) + #define MAX_2(a,b) ((a)>(b)?(a):(b)) + #define MAX_3(a,V...) MAX_2(a,DEFER2(_MAX_N_REF)()(TWO_ARGS(V),V)) #endif @@ -373,6 +514,9 @@ #define ADD8(N) ADD4(ADD4(N)) #define ADD9(N) ADD4(ADD5(N)) #define ADD10(N) ADD5(ADD5(N)) +#define SUM(A,B) _CAT(ADD,A)(B) +#define DOUBLE_(n) ADD##n(n) +#define DOUBLE(n) DOUBLE_(n) // Macros for subtracting #define DEC_0 0 @@ -481,6 +625,7 @@ // Repeat a macro passing S...N-1. #define REPEAT_S(S,N,OP) EVAL(_REPEAT(S,SUB##S(N),OP)) #define REPEAT(N,OP) REPEAT_S(0,N,OP) +#define REPEAT_1(N,OP) REPEAT_S(1,INCREMENT(N),OP) // Repeat a macro passing 0...N-1 plus additional arguments. #define REPEAT2_S(S,N,OP,V...) EVAL(_REPEAT2(S,SUB##S(N),OP,V)) diff --git a/Marlin/src/core/multi_language.h b/Marlin/src/core/multi_language.h index 5852c439a845..1eaef6930524 100644 --- a/Marlin/src/core/multi_language.h +++ b/Marlin/src/core/multi_language.h @@ -16,10 +16,12 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once +#include "../inc/MarlinConfigPre.h" + typedef const char Language_Str[]; #ifdef LCD_LANGUAGE_5 @@ -40,15 +42,12 @@ typedef const char Language_Str[]; #ifndef LCD_LANGUAGE_2 #define LCD_LANGUAGE_2 LCD_LANGUAGE #endif - #ifndef LCD_LANGUAGE_3 #define LCD_LANGUAGE_3 LCD_LANGUAGE_2 #endif - #ifndef LCD_LANGUAGE_4 #define LCD_LANGUAGE_4 LCD_LANGUAGE_3 #endif - #ifndef LCD_LANGUAGE_5 #define LCD_LANGUAGE_5 LCD_LANGUAGE_4 #endif @@ -57,26 +56,27 @@ typedef const char Language_Str[]; #define GET_LANG(LANG) _GET_LANG(LANG) #if NUM_LANGUAGES > 1 - extern uint8_t lang; + #define HAS_MULTI_LANGUAGE 1 #define GET_TEXT(MSG) ( \ - lang == 0 ? GET_LANG(LCD_LANGUAGE)::MSG : \ - lang == 1 ? GET_LANG(LCD_LANGUAGE_2)::MSG : \ - lang == 2 ? GET_LANG(LCD_LANGUAGE_3)::MSG : \ - lang == 3 ? GET_LANG(LCD_LANGUAGE_4)::MSG : \ - GET_LANG(LCD_LANGUAGE_5)::MSG \ - ) - #define MAX_LANG_CHARSIZE _MAX(GET_LANG(LCD_LANGUAGE)::CHARSIZE, \ - GET_LANG(LCD_LANGUAGE_2)::CHARSIZE, \ - GET_LANG(LCD_LANGUAGE_3)::CHARSIZE, \ - GET_LANG(LCD_LANGUAGE_4)::CHARSIZE, \ - GET_LANG(LCD_LANGUAGE_5)::CHARSIZE) + ui.language == 0 ? GET_LANG(LCD_LANGUAGE )::MSG : \ + ui.language == 1 ? GET_LANG(LCD_LANGUAGE_2)::MSG : \ + ui.language == 2 ? GET_LANG(LCD_LANGUAGE_3)::MSG : \ + ui.language == 3 ? GET_LANG(LCD_LANGUAGE_4)::MSG : \ + GET_LANG(LCD_LANGUAGE_5)::MSG ) + #define MAX_LANG_CHARSIZE _MAX(GET_LANG(LCD_LANGUAGE )::CHARSIZE, \ + GET_LANG(LCD_LANGUAGE_2)::CHARSIZE, \ + GET_LANG(LCD_LANGUAGE_3)::CHARSIZE, \ + GET_LANG(LCD_LANGUAGE_4)::CHARSIZE, \ + GET_LANG(LCD_LANGUAGE_5)::CHARSIZE ) #else #define GET_TEXT(MSG) GET_LANG(LCD_LANGUAGE)::MSG - #define MAX_LANG_CHARSIZE GET_LANG(LCD_LANGUAGE)::CHARSIZE + #define MAX_LANG_CHARSIZE LANG_CHARSIZE #endif #define GET_TEXT_F(MSG) (const __FlashStringHelper*)GET_TEXT(MSG) #define GET_LANGUAGE_NAME(INDEX) GET_LANG(LCD_LANGUAGE_##INDEX)::LANGUAGE +#define LANG_CHARSIZE GET_TEXT(CHARSIZE) +#define USE_WIDE_GLYPH (LANG_CHARSIZE > 2) #define MSG_1_LINE(A) A "\0" "\0" #define MSG_2_LINE(A,B) A "\0" B "\0" diff --git a/Marlin/src/core/serial.cpp b/Marlin/src/core/serial.cpp index 0d22f7bfc067..50cc50ad574a 100644 --- a/Marlin/src/core/serial.cpp +++ b/Marlin/src/core/serial.cpp @@ -23,29 +23,58 @@ #include "serial.h" #include "../inc/MarlinConfig.h" +#if HAS_ETHERNET + #include "../feature/ethernet.h" +#endif + uint8_t marlin_debug_flags = MARLIN_DEBUG_NONE; -static PGMSTR(errormagic, "Error:"); -static PGMSTR(echomagic, "echo:"); +// Commonly-used strings in serial output +PGMSTR(NUL_STR, ""); PGMSTR(SP_P_STR, " P"); PGMSTR(SP_T_STR, " T"); +PGMSTR(X_STR, "X"); PGMSTR(Y_STR, "Y"); PGMSTR(Z_STR, "Z"); PGMSTR(E_STR, "E"); +PGMSTR(X_LBL, "X:"); PGMSTR(Y_LBL, "Y:"); PGMSTR(Z_LBL, "Z:"); PGMSTR(E_LBL, "E:"); +PGMSTR(SP_A_STR, " A"); PGMSTR(SP_B_STR, " B"); PGMSTR(SP_C_STR, " C"); +PGMSTR(SP_X_STR, " X"); PGMSTR(SP_Y_STR, " Y"); PGMSTR(SP_Z_STR, " Z"); PGMSTR(SP_E_STR, " E"); +PGMSTR(SP_X_LBL, " X:"); PGMSTR(SP_Y_LBL, " Y:"); PGMSTR(SP_Z_LBL, " Z:"); PGMSTR(SP_E_LBL, " E:"); +PGMSTR(I_STR, AXIS4_STR); PGMSTR(J_STR, AXIS5_STR); PGMSTR(K_STR, AXIS6_STR); +PGMSTR(I_LBL, AXIS4_STR ":"); PGMSTR(J_LBL, AXIS5_STR ":"); PGMSTR(K_LBL, AXIS6_STR ":"); +PGMSTR(SP_I_STR, " " AXIS4_STR); PGMSTR(SP_J_STR, " " AXIS5_STR); PGMSTR(SP_K_STR, " " AXIS6_STR); +PGMSTR(SP_I_LBL, " " AXIS4_STR ":"); PGMSTR(SP_J_LBL, " " AXIS5_STR ":"); PGMSTR(SP_K_LBL, " " AXIS6_STR ":"); + +// Hook Meatpack if it's enabled on the first leaf +#if ENABLED(MEATPACK_ON_SERIAL_PORT_1) + SerialLeafT1 mpSerial1(false, _SERIAL_LEAF_1); +#endif +#if ENABLED(MEATPACK_ON_SERIAL_PORT_2) + SerialLeafT2 mpSerial2(false, _SERIAL_LEAF_2); +#endif +#if ENABLED(MEATPACK_ON_SERIAL_PORT_3) + SerialLeafT3 mpSerial3(false, _SERIAL_LEAF_3); +#endif +// Step 2: For multiserial, handle the second serial port as well #if HAS_MULTI_SERIAL - int8_t serial_port_index = 0; + #if HAS_ETHERNET + // We need a definition here + SerialLeafT2 msSerial2(ethernet.have_telnet_client, MYSERIAL2, false); + #endif + + #define __S_LEAF(N) ,SERIAL_LEAF_##N + #define _S_LEAF(N) __S_LEAF(N) + + SerialOutputT multiSerial( SERIAL_LEAF_1 REPEAT_S(2, INCREMENT(NUM_SERIAL), _S_LEAF) ); + + #undef __S_LEAF + #undef _S_LEAF + #endif void serialprintPGM(PGM_P str) { while (const char c = pgm_read_byte(str++)) SERIAL_CHAR(c); } -void serial_echo_start() { serialprintPGM(echomagic); } -void serial_error_start() { serialprintPGM(errormagic); } - -void serial_echopair_PGM(PGM_P const s_P, const char *v) { serialprintPGM(s_P); SERIAL_ECHO(v); } -void serial_echopair_PGM(PGM_P const s_P, char v) { serialprintPGM(s_P); SERIAL_CHAR(v); } -void serial_echopair_PGM(PGM_P const s_P, int v) { serialprintPGM(s_P); SERIAL_ECHO(v); } -void serial_echopair_PGM(PGM_P const s_P, long v) { serialprintPGM(s_P); SERIAL_ECHO(v); } -void serial_echopair_PGM(PGM_P const s_P, float v) { serialprintPGM(s_P); SERIAL_DECIMAL(v); } -void serial_echopair_PGM(PGM_P const s_P, double v) { serialprintPGM(s_P); SERIAL_DECIMAL(v); } -void serial_echopair_PGM(PGM_P const s_P, unsigned int v) { serialprintPGM(s_P); SERIAL_ECHO(v); } -void serial_echopair_PGM(PGM_P const s_P, unsigned long v) { serialprintPGM(s_P); SERIAL_ECHO(v); } + +void serial_echo_start() { static PGMSTR(echomagic, "echo:"); serialprintPGM(echomagic); } +void serial_error_start() { static PGMSTR(errormagic, "Error:"); serialprintPGM(errormagic); } void serial_spaces(uint8_t count) { count *= (PROPORTIONAL_FONT_RATIO); while (count--) SERIAL_CHAR(' '); } @@ -65,10 +94,10 @@ void print_bin(uint16_t val) { } } -extern const char SP_X_STR[], SP_Y_STR[], SP_Z_STR[]; - -void print_xyz(const float &x, const float &y, const float &z, PGM_P const prefix/*=nullptr*/, PGM_P const suffix/*=nullptr*/) { +void print_pos(LINEAR_AXIS_ARGS(const_float_t), PGM_P const prefix/*=nullptr*/, PGM_P const suffix/*=nullptr*/) { if (prefix) serialprintPGM(prefix); - SERIAL_ECHOPAIR_P(SP_X_STR, x, SP_Y_STR, y, SP_Z_STR, z); + SERIAL_ECHOPAIR_P( + LIST_N(DOUBLE(LINEAR_AXES), SP_X_STR, x, SP_Y_STR, y, SP_Z_STR, z, SP_I_STR, i, SP_J_STR, j, SP_K_STR, k) + ); if (suffix) serialprintPGM(suffix); else SERIAL_EOL(); } diff --git a/Marlin/src/core/serial.h b/Marlin/src/core/serial.h index fc830736a5a6..dfcf23ddb60f 100644 --- a/Marlin/src/core/serial.h +++ b/Marlin/src/core/serial.h @@ -22,10 +22,28 @@ #pragma once #include "../inc/MarlinConfig.h" +#include "serial_hook.h" -/** - * Define debug bit-masks - */ +#if HAS_MEATPACK + #include "../feature/meatpack.h" +#endif + +// Commonly-used strings in serial output +extern const char NUL_STR[], + SP_X_STR[], SP_Y_STR[], SP_Z_STR[], + SP_A_STR[], SP_B_STR[], SP_C_STR[], SP_E_STR[], + SP_X_LBL[], SP_Y_LBL[], SP_Z_LBL[], SP_E_LBL[], + SP_I_STR[], SP_J_STR[], SP_K_STR[], + SP_I_LBL[], SP_J_LBL[], SP_K_LBL[], + SP_P_STR[], SP_T_STR[], + X_STR[], Y_STR[], Z_STR[], E_STR[], + I_STR[], J_STR[], K_STR[], + X_LBL[], Y_LBL[], Z_LBL[], E_LBL[], + I_LBL[], J_LBL[], K_LBL[]; + +// +// Debugging flags for use by M111 +// enum MarlinDebugFlags : uint8_t { MARLIN_DEBUG_NONE = 0, MARLIN_DEBUG_ECHO = _BV(0), ///< Echo commands in order as they are processed @@ -46,225 +64,205 @@ enum MarlinDebugFlags : uint8_t { extern uint8_t marlin_debug_flags; #define DEBUGGING(F) (marlin_debug_flags & (MARLIN_DEBUG_## F)) -#define SERIAL_BOTH 0x7F -#if HAS_MULTI_SERIAL - extern int8_t serial_port_index; - #define _PORT_REDIRECT(n,p) REMEMBER(n,serial_port_index,p) - #define _PORT_RESTORE(n) RESTORE(n) +// +// Serial redirection +// +// Step 1: Find out what the first serial leaf is +#if HAS_MULTI_SERIAL && defined(SERIAL_CATCHALL) + #define _SERIAL_LEAF_1 MYSERIAL +#else + #define _SERIAL_LEAF_1 MYSERIAL1 +#endif +// Hook Meatpack if it's enabled on the first leaf +#if ENABLED(MEATPACK_ON_SERIAL_PORT_1) + typedef MeatpackSerial SerialLeafT1; + extern SerialLeafT1 mpSerial1; + #define SERIAL_LEAF_1 mpSerial1 +#else + #define SERIAL_LEAF_1 _SERIAL_LEAF_1 +#endif + +// Step 2: For multiserial wrap all serial ports in a single +// interface with the ability to output to multiple serial ports. +#if HAS_MULTI_SERIAL + #define _PORT_REDIRECT(n,p) REMEMBER(n,multiSerial.portMask,p) + #define _PORT_RESTORE(n,p) RESTORE(n) + #define SERIAL_ASSERT(P) if(multiSerial.portMask!=(P)){ debugger(); } + // If we have a catchall, use that directly #ifdef SERIAL_CATCHALL - #define SERIAL_OUT(WHAT, V...) (void)CAT(MYSERIAL,SERIAL_CATCHALL).WHAT(V) + #define _SERIAL_LEAF_2 SERIAL_CATCHALL + #elif HAS_ETHERNET + typedef ConditionalSerial SerialLeafT2; // We need to create an instance here + extern SerialLeafT2 msSerial2; + #define _SERIAL_LEAF_2 msSerial2 #else - #define SERIAL_OUT(WHAT, V...) do{ \ - if (!serial_port_index || serial_port_index == SERIAL_BOTH) (void)MYSERIAL0.WHAT(V); \ - if ( serial_port_index) (void)MYSERIAL1.WHAT(V); \ - }while(0) + #define _SERIAL_LEAF_2 MYSERIAL2 // Don't create a useless instance here, directly use the existing instance #endif - #define SERIAL_ASSERT(P) if(serial_port_index!=(P)){ debugger(); } -#else - #define _PORT_REDIRECT(n,p) NOOP - #define _PORT_RESTORE(n) NOOP - #define SERIAL_OUT(WHAT, V...) (void)MYSERIAL0.WHAT(V) - #define SERIAL_ASSERT(P) NOOP -#endif + // Nothing complicated here + #define _SERIAL_LEAF_3 MYSERIAL3 + + // Hook Meatpack if it's enabled on the second leaf + #if ENABLED(MEATPACK_ON_SERIAL_PORT_2) + typedef MeatpackSerial SerialLeafT2; + extern SerialLeafT2 mpSerial2; + #define SERIAL_LEAF_2 mpSerial2 + #else + #define SERIAL_LEAF_2 _SERIAL_LEAF_2 + #endif + + // Hook Meatpack if it's enabled on the third leaf + #if ENABLED(MEATPACK_ON_SERIAL_PORT_3) + typedef MeatpackSerial SerialLeafT3; + extern SerialLeafT3 mpSerial3; + #define SERIAL_LEAF_3 mpSerial3 + #else + #define SERIAL_LEAF_3 _SERIAL_LEAF_3 + #endif + + #define __S_MULTI(N) decltype(SERIAL_LEAF_##N), + #define _S_MULTI(N) __S_MULTI(N) + + typedef MultiSerial< REPEAT_1(NUM_SERIAL, _S_MULTI) 0> SerialOutputT; + + #undef __S_MULTI + #undef _S_MULTI -#define PORT_REDIRECT(p) _PORT_REDIRECT(1,p) -#define PORT_RESTORE() _PORT_RESTORE(1) - -#define SERIAL_ECHO(x) SERIAL_OUT(print, x) -#define SERIAL_ECHO_F(V...) SERIAL_OUT(print, V) -#define SERIAL_ECHOLN(x) SERIAL_OUT(println, x) -#define SERIAL_PRINT(x,b) SERIAL_OUT(print, x, b) -#define SERIAL_PRINTLN(x,b) SERIAL_OUT(println, x, b) -#define SERIAL_PRINTF(V...) SERIAL_OUT(printf, V) -#define SERIAL_FLUSH() SERIAL_OUT(flush) - -#ifdef ARDUINO_ARCH_STM32 - #define SERIAL_FLUSHTX() SERIAL_OUT(flush) -#elif TX_BUFFER_SIZE > 0 - #define SERIAL_FLUSHTX() SERIAL_OUT(flushTX) + extern SerialOutputT multiSerial; + #define SERIAL_IMPL multiSerial #else - #define SERIAL_FLUSHTX() + #define _PORT_REDIRECT(n,p) NOOP + #define _PORT_RESTORE(n) NOOP + #define SERIAL_ASSERT(P) NOOP + #define SERIAL_IMPL SERIAL_LEAF_1 #endif -// Print up to 10 chars from a list -#define __CHAR_N(N,V...) _CHAR_##N(V) -#define _CHAR_N(N,V...) __CHAR_N(N,V) -#define _CHAR_1(c) SERIAL_OUT(write, c) -#define _CHAR_2(a,b) do{ _CHAR_1(a); _CHAR_1(b); }while(0) -#define _CHAR_3(a,V...) do{ _CHAR_1(a); _CHAR_2(V); }while(0) -#define _CHAR_4(a,V...) do{ _CHAR_1(a); _CHAR_3(V); }while(0) -#define _CHAR_5(a,V...) do{ _CHAR_1(a); _CHAR_4(V); }while(0) -#define _CHAR_6(a,V...) do{ _CHAR_1(a); _CHAR_5(V); }while(0) -#define _CHAR_7(a,V...) do{ _CHAR_1(a); _CHAR_6(V); }while(0) -#define _CHAR_8(a,V...) do{ _CHAR_1(a); _CHAR_7(V); }while(0) -#define _CHAR_9(a,V...) do{ _CHAR_1(a); _CHAR_8(V); }while(0) -#define _CHAR_10(a,V...) do{ _CHAR_1(a); _CHAR_9(V); }while(0) - -#define SERIAL_CHAR(V...) _CHAR_N(NUM_ARGS(V),V) - -// Print up to 12 pairs of values. Odd elements auto-wrapped in PSTR(). -#define __SEP_N(N,V...) _SEP_##N(V) -#define _SEP_N(N,V...) __SEP_N(N,V) -#define _SEP_1(PRE) SERIAL_ECHOPGM(PRE) -#define _SEP_2(PRE,V) serial_echopair_PGM(PSTR(PRE),V) -#define _SEP_3(a,b,c) do{ _SEP_2(a,b); SERIAL_ECHOPGM(c); }while(0) -#define _SEP_4(a,b,V...) do{ _SEP_2(a,b); _SEP_2(V); }while(0) -#define _SEP_5(a,b,V...) do{ _SEP_2(a,b); _SEP_3(V); }while(0) -#define _SEP_6(a,b,V...) do{ _SEP_2(a,b); _SEP_4(V); }while(0) -#define _SEP_7(a,b,V...) do{ _SEP_2(a,b); _SEP_5(V); }while(0) -#define _SEP_8(a,b,V...) do{ _SEP_2(a,b); _SEP_6(V); }while(0) -#define _SEP_9(a,b,V...) do{ _SEP_2(a,b); _SEP_7(V); }while(0) -#define _SEP_10(a,b,V...) do{ _SEP_2(a,b); _SEP_8(V); }while(0) -#define _SEP_11(a,b,V...) do{ _SEP_2(a,b); _SEP_9(V); }while(0) -#define _SEP_12(a,b,V...) do{ _SEP_2(a,b); _SEP_10(V); }while(0) -#define _SEP_13(a,b,V...) do{ _SEP_2(a,b); _SEP_11(V); }while(0) -#define _SEP_14(a,b,V...) do{ _SEP_2(a,b); _SEP_12(V); }while(0) -#define _SEP_15(a,b,V...) do{ _SEP_2(a,b); _SEP_13(V); }while(0) -#define _SEP_16(a,b,V...) do{ _SEP_2(a,b); _SEP_14(V); }while(0) -#define _SEP_17(a,b,V...) do{ _SEP_2(a,b); _SEP_15(V); }while(0) -#define _SEP_18(a,b,V...) do{ _SEP_2(a,b); _SEP_16(V); }while(0) -#define _SEP_19(a,b,V...) do{ _SEP_2(a,b); _SEP_17(V); }while(0) -#define _SEP_20(a,b,V...) do{ _SEP_2(a,b); _SEP_18(V); }while(0) -#define _SEP_21(a,b,V...) do{ _SEP_2(a,b); _SEP_19(V); }while(0) -#define _SEP_22(a,b,V...) do{ _SEP_2(a,b); _SEP_20(V); }while(0) -#define _SEP_23(a,b,V...) do{ _SEP_2(a,b); _SEP_21(V); }while(0) -#define _SEP_24(a,b,V...) do{ _SEP_2(a,b); _SEP_22(V); }while(0) - -#define SERIAL_ECHOPAIR(V...) _SEP_N(NUM_ARGS(V),V) - -// Print up to 12 pairs of values. Odd elements must be PSTR pointers. -#define __SEP_N_P(N,V...) _SEP_##N##_P(V) -#define _SEP_N_P(N,V...) __SEP_N_P(N,V) -#define _SEP_1_P(PRE) serialprintPGM(PRE) -#define _SEP_2_P(PRE,V) serial_echopair_PGM(PRE,V) -#define _SEP_3_P(a,b,c) do{ _SEP_2_P(a,b); serialprintPGM(c); }while(0) -#define _SEP_4_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_2_P(V); }while(0) -#define _SEP_5_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_3_P(V); }while(0) -#define _SEP_6_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_4_P(V); }while(0) -#define _SEP_7_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_5_P(V); }while(0) -#define _SEP_8_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_6_P(V); }while(0) -#define _SEP_9_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_7_P(V); }while(0) -#define _SEP_10_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_8_P(V); }while(0) -#define _SEP_11_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_9_P(V); }while(0) -#define _SEP_12_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_10_P(V); }while(0) -#define _SEP_13_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_11_P(V); }while(0) -#define _SEP_14_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_12_P(V); }while(0) -#define _SEP_15_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_13_P(V); }while(0) -#define _SEP_16_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_14_P(V); }while(0) -#define _SEP_17_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_15_P(V); }while(0) -#define _SEP_18_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_16_P(V); }while(0) -#define _SEP_19_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_17_P(V); }while(0) -#define _SEP_20_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_18_P(V); }while(0) -#define _SEP_21_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_19_P(V); }while(0) -#define _SEP_22_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_20_P(V); }while(0) -#define _SEP_23_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_21_P(V); }while(0) -#define _SEP_24_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_22_P(V); }while(0) - -#define SERIAL_ECHOPAIR_P(V...) _SEP_N_P(NUM_ARGS(V),V) - -// Print up to 12 pairs of values followed by newline -#define __SELP_N(N,V...) _SELP_##N(V) -#define _SELP_N(N,V...) __SELP_N(N,V) -#define _SELP_1(PRE) SERIAL_ECHOLNPGM(PRE) -#define _SELP_2(PRE,V) do{ serial_echopair_PGM(PSTR(PRE),V); SERIAL_EOL(); }while(0) -#define _SELP_3(a,b,c) do{ _SEP_2(a,b); SERIAL_ECHOLNPGM(c); }while(0) -#define _SELP_4(a,b,V...) do{ _SEP_2(a,b); _SELP_2(V); }while(0) -#define _SELP_5(a,b,V...) do{ _SEP_2(a,b); _SELP_3(V); }while(0) -#define _SELP_6(a,b,V...) do{ _SEP_2(a,b); _SELP_4(V); }while(0) -#define _SELP_7(a,b,V...) do{ _SEP_2(a,b); _SELP_5(V); }while(0) -#define _SELP_8(a,b,V...) do{ _SEP_2(a,b); _SELP_6(V); }while(0) -#define _SELP_9(a,b,V...) do{ _SEP_2(a,b); _SELP_7(V); }while(0) -#define _SELP_10(a,b,V...) do{ _SEP_2(a,b); _SELP_8(V); }while(0) -#define _SELP_11(a,b,V...) do{ _SEP_2(a,b); _SELP_9(V); }while(0) -#define _SELP_12(a,b,V...) do{ _SEP_2(a,b); _SELP_10(V); }while(0) -#define _SELP_13(a,b,V...) do{ _SEP_2(a,b); _SELP_11(V); }while(0) -#define _SELP_14(a,b,V...) do{ _SEP_2(a,b); _SELP_12(V); }while(0) -#define _SELP_15(a,b,V...) do{ _SEP_2(a,b); _SELP_13(V); }while(0) -#define _SELP_16(a,b,V...) do{ _SEP_2(a,b); _SELP_14(V); }while(0) -#define _SELP_17(a,b,V...) do{ _SEP_2(a,b); _SELP_15(V); }while(0) -#define _SELP_18(a,b,V...) do{ _SEP_2(a,b); _SELP_16(V); }while(0) -#define _SELP_19(a,b,V...) do{ _SEP_2(a,b); _SELP_17(V); }while(0) -#define _SELP_20(a,b,V...) do{ _SEP_2(a,b); _SELP_18(V); }while(0) -#define _SELP_21(a,b,V...) do{ _SEP_2(a,b); _SELP_19(V); }while(0) -#define _SELP_22(a,b,V...) do{ _SEP_2(a,b); _SELP_20(V); }while(0) -#define _SELP_23(a,b,V...) do{ _SEP_2(a,b); _SELP_21(V); }while(0) -#define _SELP_24(a,b,V...) do{ _SEP_2(a,b); _SELP_22(V); }while(0) -#define _SELP_25(a,b,V...) do{ _SEP_2(a,b); _SELP_23(V); }while(0) -#define _SELP_26(a,b,V...) do{ _SEP_2(a,b); _SELP_24(V); }while(0) -#define _SELP_27(a,b,V...) do{ _SEP_2(a,b); _SELP_25(V); }while(0) -#define _SELP_28(a,b,V...) do{ _SEP_2(a,b); _SELP_26(V); }while(0) -#define _SELP_29(a,b,V...) do{ _SEP_2(a,b); _SELP_27(V); }while(0) -#define _SELP_30(a,b,V...) do{ _SEP_2(a,b); _SELP_28(V); }while(0) // Eat two args, pass the rest up - -#define SERIAL_ECHOLNPAIR(V...) _SELP_N(NUM_ARGS(V),V) - -// Print up to 12 pairs of values followed by newline -#define __SELP_N_P(N,V...) _SELP_##N##_P(V) -#define _SELP_N_P(N,V...) __SELP_N_P(N,V) -#define _SELP_1_P(PRE) serialprintPGM(PRE) -#define _SELP_2_P(PRE,V) do{ serial_echopair_PGM(PRE,V); SERIAL_EOL(); }while(0) -#define _SELP_3_P(a,b,c) do{ _SEP_2_P(a,b); serialprintPGM(c); }while(0) -#define _SELP_4_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_2_P(V); }while(0) -#define _SELP_5_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_3_P(V); }while(0) -#define _SELP_6_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_4_P(V); }while(0) -#define _SELP_7_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_5_P(V); }while(0) -#define _SELP_8_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_6_P(V); }while(0) -#define _SELP_9_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_7_P(V); }while(0) -#define _SELP_10_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_8_P(V); }while(0) -#define _SELP_11_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_9_P(V); }while(0) -#define _SELP_12_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_10_P(V); }while(0) -#define _SELP_13_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_11_P(V); }while(0) -#define _SELP_14_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_12_P(V); }while(0) -#define _SELP_15_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_13_P(V); }while(0) -#define _SELP_16_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_14_P(V); }while(0) -#define _SELP_17_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_15_P(V); }while(0) -#define _SELP_18_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_16_P(V); }while(0) -#define _SELP_19_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_17_P(V); }while(0) -#define _SELP_20_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_18_P(V); }while(0) -#define _SELP_21_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_19_P(V); }while(0) -#define _SELP_22_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_20_P(V); }while(0) -#define _SELP_23_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_21_P(V); }while(0) -#define _SELP_24_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_22_P(V); }while(0) -#define _SELP_25_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_23_P(V); }while(0) -#define _SELP_26_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_24_P(V); }while(0) -#define _SELP_27_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_25_P(V); }while(0) -#define _SELP_28_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_26_P(V); }while(0) -#define _SELP_29_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_27_P(V); }while(0) -#define _SELP_30_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_28_P(V); }while(0) // Eat two args, pass the rest up - -#define SERIAL_ECHOLNPAIR_P(V...) _SELP_N_P(NUM_ARGS(V),V) - -// Print up to 20 comma-separated pairs of values -#define __SLST_N(N,V...) _SLST_##N(V) -#define _SLST_N(N,V...) __SLST_N(N,V) -#define _SLST_1(a) SERIAL_ECHO(a) -#define _SLST_2(a,b) do{ SERIAL_ECHO(a); SERIAL_ECHOPAIR(", ",b); }while(0) -#define _SLST_3(a,b,c) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_1(c); }while(0) -#define _SLST_4(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_2(V); }while(0) -#define _SLST_5(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_3(V); }while(0) -#define _SLST_6(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_4(V); }while(0) -#define _SLST_7(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_5(V); }while(0) -#define _SLST_8(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_6(V); }while(0) -#define _SLST_9(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_7(V); }while(0) -#define _SLST_10(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_8(V); }while(0) -#define _SLST_11(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_9(V); }while(0) -#define _SLST_12(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_10(V); }while(0) -#define _SLST_13(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_11(V); }while(0) -#define _SLST_14(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_12(V); }while(0) -#define _SLST_15(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_13(V); }while(0) -#define _SLST_16(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_14(V); }while(0) -#define _SLST_17(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_15(V); }while(0) -#define _SLST_18(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_16(V); }while(0) -#define _SLST_19(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_17(V); }while(0) -#define _SLST_20(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_18(V); }while(0) // Eat two args, pass the rest up - -#define SERIAL_ECHOLIST(pre,V...) do{ SERIAL_ECHOPGM(pre); _SLST_N(NUM_ARGS(V),V); }while(0) -#define SERIAL_ECHOLIST_N(N,V...) _SLST_N(N,LIST_N(N,V)) +#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) + +// +// SERIAL_CHAR - Print one or more individual chars +// +inline void SERIAL_CHAR(char a) { SERIAL_IMPL.write(a); } +template +void SERIAL_CHAR(char a, Args ... args) { SERIAL_IMPL.write(a); SERIAL_CHAR(args ...); } + +/** + * SERIAL_ECHO - Print a single string or value. + * Any numeric parameter (including char) is printed as a base-10 number. + * A string pointer or literal will be output as a string. + * + * NOTE: Use SERIAL_CHAR to print char as a single character. + */ +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)) + +// SERIAL_ECHO_F prints a floating point value with optional precision +inline void SERIAL_ECHO_F(EnsureDouble x, int digit=2) { SERIAL_IMPL.print(x, digit); } + +template +void SERIAL_ECHOLN(T x) { SERIAL_IMPL.println(x); } + +// SERIAL_PRINT works like SERIAL_ECHO but allow to specify the encoding base of the number printed +template +void SERIAL_PRINT(T x, U y) { SERIAL_IMPL.print(x, y); } + +template +void SERIAL_PRINTLN(T x, PrintBase y) { SERIAL_IMPL.println(x, y); } + +// Flush the serial port +inline void SERIAL_FLUSH() { SERIAL_IMPL.flush(); } +inline void SERIAL_FLUSHTX() { SERIAL_IMPL.flushTX(); } + +// Print a single PROGMEM string to serial +void serialprintPGM(PGM_P str); + +// +// SERIAL_ECHOPAIR... macros are used to output string-value pairs. +// + +// Print up to 20 pairs of values. Odd elements must be literal strings. +#define __SEP_N(N,V...) _SEP_##N(V) +#define _SEP_N(N,V...) __SEP_N(N,V) +#define _SEP_N_REF() _SEP_N +#define _SEP_1(s) SERIAL_ECHOPGM(s); +#define _SEP_2(s,v) serial_echopair_PGM(PSTR(s),v); +#define _SEP_3(s,v,V...) _SEP_2(s,v); DEFER2(_SEP_N_REF)()(TWO_ARGS(V),V); +#define SERIAL_ECHOPAIR(V...) do{ EVAL(_SEP_N(TWO_ARGS(V),V)); }while(0) + +// Print up to 20 pairs of values followed by newline. Odd elements must be literal strings. +#define __SELP_N(N,V...) _SELP_##N(V) +#define _SELP_N(N,V...) __SELP_N(N,V) +#define _SELP_N_REF() _SELP_N +#define _SELP_1(s) SERIAL_ECHOLNPGM(s); +#define _SELP_2(s,v) serial_echopair_PGM(PSTR(s),v); SERIAL_EOL(); +#define _SELP_3(s,v,V...) _SEP_2(s,v); DEFER2(_SELP_N_REF)()(TWO_ARGS(V),V); +#define SERIAL_ECHOLNPAIR(V...) do{ EVAL(_SELP_N(TWO_ARGS(V),V)); }while(0) + +// Print up to 20 pairs of values. Odd elements must be PSTR pointers. +#define __SEP_N_P(N,V...) _SEP_##N##_P(V) +#define _SEP_N_P(N,V...) __SEP_N_P(N,V) +#define _SEP_N_P_REF() _SEP_N_P +#define _SEP_1_P(s) serialprintPGM(s); +#define _SEP_2_P(s,v) serial_echopair_PGM(s,v); +#define _SEP_3_P(s,v,V...) _SEP_2_P(s,v); DEFER2(_SEP_N_P_REF)()(TWO_ARGS(V),V); +#define SERIAL_ECHOPAIR_P(V...) do{ EVAL(_SEP_N_P(TWO_ARGS(V),V)); }while(0) + +// Print up to 20 pairs of values followed by newline. Odd elements must be PSTR pointers. +#define __SELP_N_P(N,V...) _SELP_##N##_P(V) +#define _SELP_N_P(N,V...) __SELP_N_P(N,V) +#define _SELP_N_P_REF() _SELP_N_P +#define _SELP_1_P(s) { serialprintPGM(s); SERIAL_EOL(); } +#define _SELP_2_P(s,v) { serial_echopair_PGM(s,v); SERIAL_EOL(); } +#define _SELP_3_P(s,v,V...) { _SEP_2_P(s,v); DEFER2(_SELP_N_P_REF)()(TWO_ARGS(V),V); } +#define SERIAL_ECHOLNPAIR_P(V...) do{ EVAL(_SELP_N_P(TWO_ARGS(V),V)); }while(0) + +#ifdef AllowDifferentTypeInList + + inline void SERIAL_ECHOLIST_IMPL() {} + template + void SERIAL_ECHOLIST_IMPL(T && t) { SERIAL_IMPL.print(t); } + + template + void SERIAL_ECHOLIST_IMPL(T && t, Args && ... args) { + SERIAL_IMPL.print(t); + serialprintPGM(PSTR(", ")); + SERIAL_ECHOLIST_IMPL(args...); + } + + template + void SERIAL_ECHOLIST(PGM_P const str, Args && ... args) { + SERIAL_IMPL.print(str); + SERIAL_ECHOLIST_IMPL(args...); + } + +#else // Optimization if the listed type are all the same (seems to be the case in the codebase so use that instead) + + template + void SERIAL_ECHOLIST(PGM_P const str, Args && ... args) { + serialprintPGM(str); + typename Private::first_type_of::type values[] = { args... }; + constexpr size_t argsSize = sizeof...(args); + for (size_t i = 0; i < argsSize; i++) { + if (i) serialprintPGM(PSTR(", ")); + SERIAL_IMPL.print(values[i]); + } + } + +#endif #define SERIAL_ECHOPGM_P(P) (serialprintPGM(P)) -#define SERIAL_ECHOLNPGM_P(P) (serialprintPGM(P "\n")) +#define SERIAL_ECHOLNPGM_P(P) do{ serialprintPGM(P); SERIAL_EOL(); }while(0) #define SERIAL_ECHOPGM(S) (serialprintPGM(PSTR(S))) #define SERIAL_ECHOLNPGM(S) (serialprintPGM(PSTR(S "\n"))) @@ -295,19 +293,19 @@ extern uint8_t marlin_debug_flags; // // Functions for serial printing from PROGMEM. (Saves loads of SRAM.) // -void serial_echopair_PGM(PGM_P const s_P, const char *v); -void serial_echopair_PGM(PGM_P const s_P, char v); -void serial_echopair_PGM(PGM_P const s_P, int v); -void serial_echopair_PGM(PGM_P const s_P, long v); -void serial_echopair_PGM(PGM_P const s_P, float v); -void serial_echopair_PGM(PGM_P const s_P, double v); -void serial_echopair_PGM(PGM_P const s_P, unsigned int v); -void serial_echopair_PGM(PGM_P const s_P, unsigned long v); -inline void serial_echopair_PGM(PGM_P const s_P, uint8_t v) { serial_echopair_PGM(s_P, (int)v); } +inline void serial_echopair_PGM(PGM_P const s_P, serial_char_t v) { serialprintPGM(s_P); SERIAL_CHAR(v.c); } + +inline void serial_echopair_PGM(PGM_P const s_P, float v) { serialprintPGM(s_P); SERIAL_DECIMAL(v); } +inline void serial_echopair_PGM(PGM_P const s_P, double v) { serialprintPGM(s_P); SERIAL_DECIMAL(v); } +inline void serial_echopair_PGM(PGM_P const s_P, const char *v) { serialprintPGM(s_P); SERIAL_ECHO(v); } + +// Default implementation for types without a specialization. Handles integers. +template +void serial_echopair_PGM(PGM_P const s_P, T v) { serialprintPGM(s_P); SERIAL_ECHO(v); } + inline void serial_echopair_PGM(PGM_P const s_P, bool v) { serial_echopair_PGM(s_P, (int)v); } -inline void serial_echopair_PGM(PGM_P const s_P, void *v) { serial_echopair_PGM(s_P, (unsigned long)v); } +inline void serial_echopair_PGM(PGM_P const s_P, void *v) { serial_echopair_PGM(s_P, (uintptr_t)v); } -void serialprintPGM(PGM_P str); void serial_echo_start(); void serial_error_start(); void serial_ternary(const bool onoff, PGM_P const pre, PGM_P const on, PGM_P const off, PGM_P const post=nullptr); @@ -317,11 +315,11 @@ void serialprint_truefalse(const bool tf); void serial_spaces(uint8_t count); void print_bin(const uint16_t val); -void print_xyz(const float &x, const float &y, const float &z, PGM_P const prefix=nullptr, PGM_P const suffix=nullptr); +void print_pos(LINEAR_AXIS_ARGS(const_float_t), PGM_P const prefix=nullptr, PGM_P const suffix=nullptr); -inline void print_xyz(const xyz_pos_t &xyz, PGM_P const prefix=nullptr, PGM_P const suffix=nullptr) { - print_xyz(xyz.x, xyz.y, xyz.z, prefix, suffix); +inline void print_pos(const xyz_pos_t &xyz, PGM_P const prefix=nullptr, PGM_P const suffix=nullptr) { + print_pos(LINEAR_AXIS_ELEM(xyz), prefix, suffix); } -#define SERIAL_POS(SUFFIX,VAR) do { print_xyz(VAR, PSTR(" " STRINGIFY(VAR) "="), PSTR(" : " SUFFIX "\n")); }while(0) -#define SERIAL_XYZ(PREFIX,V...) do { print_xyz(V, PSTR(PREFIX), nullptr); }while(0) +#define SERIAL_POS(SUFFIX,VAR) do { print_pos(VAR, PSTR(" " STRINGIFY(VAR) "="), PSTR(" : " SUFFIX "\n")); }while(0) +#define SERIAL_XYZ(PREFIX,V...) do { print_pos(V, PSTR(PREFIX), nullptr); }while(0) diff --git a/Marlin/src/core/serial_base.h b/Marlin/src/core/serial_base.h new file mode 100644 index 000000000000..a5abd67d8727 --- /dev/null +++ b/Marlin/src/core/serial_base.h @@ -0,0 +1,258 @@ +/** + * 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 + +#include "../inc/MarlinConfigPre.h" + +#if ENABLED(EMERGENCY_PARSER) + #include "../feature/e_parser.h" +#endif + +// Used in multiple places +// You can build it but not manipulate it. +// There are only few places where it's required to access the underlying member: GCodeQueue, SerialMask and MultiSerial +struct serial_index_t { + // A signed index, where -1 is a special case meaning no action (neither output or input) + int8_t index; + + // Check if the index is within the range [a ... b] + constexpr inline bool within(const int8_t a, const int8_t b) const { return WITHIN(index, a, b); } + constexpr inline bool valid() const { return WITHIN(index, 0, 7); } // At most, 8 bits + + // Construction is either from an index + constexpr serial_index_t(const int8_t index) : index(index) {} + + // Default to "no index" + constexpr serial_index_t() : index(-1) {} +}; + +// In order to catch usage errors in code, we make the base to encode number explicit +// If given a number (and not this enum), the compiler will reject the overload, falling back to the (double, digit) version +// We don't want hidden conversion of the first parameter to double, so it has to be as hard to do for the compiler as creating this enum +enum class PrintBase { + Dec = 10, + Hex = 16, + Oct = 8, + Bin = 2 +}; + +// A simple feature list enumeration +enum class SerialFeature { + None = 0x00, + MeatPack = 0x01, //!< Enabled when Meatpack is present + BinaryFileTransfer = 0x02, //!< Enabled for BinaryFile transfer support (in the future) + Virtual = 0x04, //!< Enabled for virtual serial port (like Telnet / Websocket / ...) + Hookable = 0x08, //!< Enabled if the serial class supports a setHook method +}; +ENUM_FLAGS(SerialFeature); + +// flushTX is not implemented in all HAL, so use SFINAE to call the method where it is. +CALL_IF_EXISTS_IMPL(void, flushTX); +CALL_IF_EXISTS_IMPL(bool, connected, true); +CALL_IF_EXISTS_IMPL(SerialFeature, features, SerialFeature::None); + +// A simple forward struct to prevent the compiler from selecting print(double, int) as a default overload +// for any type other than double/float. For double/float, a conversion exists so the call will be invisible. +struct EnsureDouble { + double a; + 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) + EnsureDouble(double a) : a(a) {} + EnsureDouble(float a) : a(a) {} +}; + +// Using Curiously-Recurring Template Pattern here to avoid virtual table cost when compiling. +// Since the real serial class is known at compile time, this results in the compiler writing +// a completely efficient code. +template +struct SerialBase { + #if ENABLED(EMERGENCY_PARSER) + const bool ep_enabled; + EmergencyParser::State emergency_state; + inline bool emergency_parser_enabled() { return ep_enabled; } + SerialBase(bool ep_capable) : ep_enabled(ep_capable), emergency_state(EmergencyParser::State::EP_RESET) {} + #else + SerialBase(const bool) {} + #endif + + #define SerialChild static_cast(this) + + // Static dispatch methods below: + // The most important method here is where it all ends to: + void write(uint8_t c) { SerialChild->write(c); } + + // Called when the parser finished processing an instruction, usually build to nothing + void msgDone() const { SerialChild->msgDone(); } + + // Called on initialization + void begin(const long baudRate) { SerialChild->begin(baudRate); } + + // Called on destruction + void end() { SerialChild->end(); } + + /** Check for available data from the port + @param index The port index, usually 0 */ + int available(serial_index_t index=0) const { return SerialChild->available(index); } + + /** Read a value from the port + @param index The port index, usually 0 */ + int read(serial_index_t index=0) { return SerialChild->read(index); } + + /** Combine the features of this serial instance and return it + @param index The port index, usually 0 */ + SerialFeature features(serial_index_t index=0) const { return static_cast(this)->features(index); } + + // Check if the serial port has a feature + bool has_feature(serial_index_t index, SerialFeature flag) const { return (features(index) & flag) != SerialFeature::None; } + + // Check if the serial port is connected (usually bypassed) + bool connected() const { return SerialChild->connected(); } + + // Redirect flush + void flush() { SerialChild->flush(); } + + // Not all implementation have a flushTX, so let's call them only if the child has the implementation + void flushTX() { CALL_IF_EXISTS(void, SerialChild, flushTX); } + + // Glue code here + void write(const char *str) { while (*str) write(*str++); } + void write(const uint8_t *buffer, size_t size) { while (size--) write(*buffer++); } + void print(char *str) { write(str); } + void print(const char *str) { write(str); } + // No default argument to avoid ambiguity + + // Define print for every fundamental integer type, to ensure that all redirect properly + // to the correct underlying implementation. + + // Prints are performed with a single size, to avoid needing multiple print functions. + // The fixed integer size used for prints will be the larger of long or a pointer. + #if __LONG_WIDTH__ >= __INTPTR_WIDTH__ + typedef long int_fixed_print_t; + typedef unsigned long uint_fixed_print_t; + #else + typedef intptr_t int_fixed_print_t; + typedef uintptr_t uint_fixed_print_t; + + FORCE_INLINE void print(intptr_t c, PrintBase base) { printNumber_signed(c, base); } + FORCE_INLINE void print(uintptr_t c, PrintBase base) { printNumber_unsigned(c, base); } + #endif + + FORCE_INLINE void print(char c, PrintBase base) { printNumber_signed(c, base); } + FORCE_INLINE void print(short c, PrintBase base) { printNumber_signed(c, base); } + FORCE_INLINE void print(int c, PrintBase base) { printNumber_signed(c, base); } + FORCE_INLINE void print(long c, PrintBase base) { printNumber_signed(c, base); } + FORCE_INLINE void print(unsigned char c, PrintBase base) { printNumber_unsigned(c, base); } + FORCE_INLINE void print(unsigned short c, PrintBase base) { printNumber_unsigned(c, base); } + 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 + + // Default implementation for anything without a specialization + // This handles integers since they are the most common + template + void print(T c) { print(c, PrintBase::Dec); } + + void print(float 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(); } + void println(float c, int digits) { print(c, digits); println(); } + void println(double c, int digits) { print(c, digits); println(); } + void println() { write('\r'); write('\n'); } + + // Default implementations for types without a specialization. Handles integers. + template + void println(T c, PrintBase base) { print(c, base); println(); } + + template + void println(T c) { println(c, PrintBase::Dec); } + + // Forward the call to the former's method + void println(float c) { println(c, 2); } + void println(double c) { println(c, 2); } + + // Print a number with the given base + NO_INLINE void printNumber_unsigned(uint_fixed_print_t n, PrintBase base) { + if (n) { + unsigned char buf[8 * sizeof(long)]; // Enough space for base 2 + int8_t i = 0; + while (n) { + buf[i++] = n % (uint_fixed_print_t)base; + n /= (uint_fixed_print_t)base; + } + while (i--) write((char)(buf[i] + (buf[i] < 10 ? '0' : 'A' - 10))); + } + else write('0'); + } + + NO_INLINE void printNumber_signed(int_fixed_print_t n, PrintBase base) { + if (base == PrintBase::Dec && n < 0) { + n = -n; // This works because all platforms Marlin's builds on are using 2-complement encoding for negative number + // On such CPU, changing the sign of a number is done by inverting the bits and adding one, so if n = 0x80000000 = -2147483648 then + // -n = 0x7FFFFFFF + 1 => 0x80000000 = 2147483648 (if interpreted as unsigned) or -2147483648 if interpreted as signed. + // On non 2-complement CPU, there would be no possible representation for 2147483648. + write('-'); + } + printNumber_unsigned((uint_fixed_print_t)n , base); + } + + // Print a decimal number + NO_INLINE void printFloat(double number, uint8_t digits) { + // Handle negative numbers + if (number < 0.0) { + write('-'); + number = -number; + } + + // Round correctly so that print(1.999, 2) prints as "2.00" + double rounding = 0.5; + LOOP_L_N(i, digits) rounding *= 0.1; + number += rounding; + + // Extract the integer part of the number and print it + unsigned long int_part = (unsigned long)number; + double remainder = number - (double)int_part; + printNumber_unsigned(int_part, PrintBase::Dec); + + // Print the decimal point, but only if there are digits beyond + if (digits) { + write('.'); + // Extract digits from the remainder one at a time + while (digits--) { + remainder *= 10.0; + unsigned long toPrint = (unsigned long)remainder; + printNumber_unsigned(toPrint, PrintBase::Dec); + remainder -= toPrint; + } + } + } +}; + +// All serial instances will be built by chaining the features required +// for the function in the form of a template type definition. diff --git a/Marlin/src/core/serial_hook.h b/Marlin/src/core/serial_hook.h new file mode 100644 index 000000000000..2019b389e497 --- /dev/null +++ b/Marlin/src/core/serial_hook.h @@ -0,0 +1,306 @@ +/** + * 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 + +#include "serial_base.h" + +// A mask containing a bitmap of the serial port to act upon +// This is written to ensure a serial index is never used as a serial mask +class SerialMask { + uint8_t mask; + + // This constructor is private to ensure you can't convert an index to a mask + // The compiler will stop here if you are mixing index and mask in your code. + // If you need to, you'll have to use the explicit static "from" method here + SerialMask(const serial_index_t); + +public: + inline constexpr bool enabled(const SerialMask PortMask) const { return mask & PortMask.mask; } + inline constexpr SerialMask combine(const SerialMask other) const { return SerialMask(mask | other.mask); } + inline constexpr SerialMask operator<< (const int offset) const { return SerialMask(mask << offset); } + static inline SerialMask from(const serial_index_t index) { + if (index.valid()) return SerialMask(_BV(index.index)); + return SerialMask(0); // A invalid index mean no output + } + + constexpr SerialMask(const uint8_t mask) : mask(mask) {} + constexpr SerialMask(const SerialMask & other) : mask(other.mask) {} // Can't use = default here since not all framework support this + + static constexpr uint8_t All = 0xFF; +}; + +// The most basic serial class: it dispatch to the base serial class with no hook whatsoever. This will compile to nothing but the base serial class +template +struct BaseSerial : public SerialBase< BaseSerial >, public SerialT { + typedef SerialBase< BaseSerial > BaseClassT; + + // It's required to implement a write method here to help compiler disambiguate what method to call + using SerialT::write; + using SerialT::flush; + + void msgDone() {} + + // We don't care about indices here, since if one can call us, it's the right index anyway + int available(serial_index_t) { return (int)SerialT::available(); } + int read(serial_index_t) { return (int)SerialT::read(); } + bool connected() { return CALL_IF_EXISTS(bool, static_cast(this), connected);; } + void flushTX() { CALL_IF_EXISTS(void, static_cast(this), flushTX); } + + SerialFeature features(serial_index_t index) const { return CALL_IF_EXISTS(SerialFeature, static_cast(this), features, index); } + + // Two implementations of the same method exist in both base classes so indicate the right one + using SerialT::available; + using SerialT::read; + using SerialT::begin; + using SerialT::end; + + using BaseClassT::print; + using BaseClassT::println; + + BaseSerial(const bool e) : BaseClassT(e) {} + + // Forward constructor + template + BaseSerial(const bool e, Args... args) : BaseClassT(e), SerialT(args...) {} +}; + +// A serial with a condition checked at runtime for its output +// A bit less efficient than static dispatching but since it's only used for ethernet's serial output right now, it's ok. +template +struct ConditionalSerial : public SerialBase< ConditionalSerial > { + typedef SerialBase< ConditionalSerial > BaseClassT; + + bool & condition; + SerialT & out; + NO_INLINE size_t write(uint8_t c) { if (condition) return out.write(c); return 0; } + void flush() { if (condition) out.flush(); } + void begin(long br) { out.begin(br); } + void end() { out.end(); } + + void msgDone() {} + bool connected() { return CALL_IF_EXISTS(bool, &out, connected); } + void flushTX() { CALL_IF_EXISTS(void, &out, flushTX); } + + int available(serial_index_t) { return (int)out.available(); } + int read(serial_index_t) { return (int)out.read(); } + int available() { return (int)out.available(); } + int read() { return (int)out.read(); } + SerialFeature features(serial_index_t index) const { return CALL_IF_EXISTS(SerialFeature, &out, features, index); } + + ConditionalSerial(bool & conditionVariable, SerialT & out, const bool e) : BaseClassT(e), condition(conditionVariable), out(out) {} +}; + +// A simple forward class that taking a reference to an existing serial instance (likely created in their respective framework) +template +struct ForwardSerial : public SerialBase< ForwardSerial > { + typedef SerialBase< ForwardSerial > BaseClassT; + + SerialT & out; + NO_INLINE size_t write(uint8_t c) { return out.write(c); } + void flush() { out.flush(); } + void begin(long br) { out.begin(br); } + void end() { out.end(); } + + void msgDone() {} + // Existing instances implement Arduino's operator bool, so use that if it's available + bool connected() { return Private::HasMember_connected::value ? CALL_IF_EXISTS(bool, &out, connected) : (bool)out; } + void flushTX() { CALL_IF_EXISTS(void, &out, flushTX); } + + int available(serial_index_t) { return (int)out.available(); } + int read(serial_index_t) { return (int)out.read(); } + int available() { return (int)out.available(); } + int read() { return (int)out.read(); } + SerialFeature features(serial_index_t index) const { return CALL_IF_EXISTS(SerialFeature, &out, features, index); } + + ForwardSerial(const bool e, SerialT & out) : BaseClassT(e), out(out) {} +}; + +// A class that can be hooked and unhooked at runtime, useful to capture the output of the serial interface +template +struct RuntimeSerial : public SerialBase< RuntimeSerial >, public SerialT { + typedef SerialBase< RuntimeSerial > BaseClassT; + typedef void (*WriteHook)(void * userPointer, uint8_t c); + typedef void (*EndOfMessageHook)(void * userPointer); + + WriteHook writeHook; + EndOfMessageHook eofHook; + void * userPointer; + + NO_INLINE size_t write(uint8_t c) { + if (writeHook) writeHook(userPointer, c); + return SerialT::write(c); + } + + NO_INLINE void msgDone() { + if (eofHook) eofHook(userPointer); + } + + int available(serial_index_t) { return (int)SerialT::available(); } + int read(serial_index_t) { return (int)SerialT::read(); } + using SerialT::available; + using SerialT::read; + using SerialT::flush; + using SerialT::begin; + using SerialT::end; + + using BaseClassT::print; + using BaseClassT::println; + + // Underlying implementation might use Arduino's bool operator + bool connected() { + return Private::HasMember_connected::value + ? CALL_IF_EXISTS(bool, static_cast(this), connected) + : static_cast(this)->operator bool(); + } + + void flushTX() { CALL_IF_EXISTS(void, static_cast(this), flushTX); } + + // 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) { + // 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; + this->writeHook = writeHook; + this->eofHook = eofHook; + // Order is important here because of asynchronous access here + // When unsetting a hook, the user pointer must be unset last so that any pending writeHook is still using the old pointer + if (!userPointer) this->userPointer = 0; + } + + RuntimeSerial(const bool e) : BaseClassT(e), writeHook(0), eofHook(0), userPointer(0) {} + + // Forward constructor + template + RuntimeSerial(const bool e, Args... args) : BaseClassT(e), SerialT(args...), writeHook(0), eofHook(0), userPointer(0) {} +}; + +#define _S_CLASS(N) class Serial##N##T, +#define _S_NAME(N) Serial##N##T, + +template < REPEAT(NUM_SERIAL, _S_CLASS) const uint8_t offset=0, const uint8_t step=1 > +struct MultiSerial : public SerialBase< MultiSerial< REPEAT(NUM_SERIAL, _S_NAME) offset, step > > { + typedef SerialBase< MultiSerial< REPEAT(NUM_SERIAL, _S_NAME) offset, step > > BaseClassT; + + #undef _S_CLASS + #undef _S_NAME + + SerialMask portMask; + + #define _S_DECLARE(N) Serial##N##T & serial##N; + REPEAT(NUM_SERIAL, _S_DECLARE); + #undef _S_DECLARE + + static constexpr uint8_t Usage = _BV(step) - 1; // A bit mask containing 'step' bits + + #define _OUT_PORT(N) (Usage << (offset + (step * N))), + static constexpr uint8_t output[] = { REPEAT(NUM_SERIAL, _OUT_PORT) }; + #undef _OUT_PORT + + #define _OUT_MASK(N) | output[N] + static constexpr uint8_t ALL = 0 REPEAT(NUM_SERIAL, _OUT_MASK); + #undef _OUT_MASK + + NO_INLINE void write(uint8_t c) { + #define _S_WRITE(N) if (portMask.enabled(output[N])) serial##N.write(c); + REPEAT(NUM_SERIAL, _S_WRITE); + #undef _S_WRITE + } + NO_INLINE void msgDone() { + #define _S_DONE(N) if (portMask.enabled(output[N])) serial##N.msgDone(); + REPEAT(NUM_SERIAL, _S_DONE); + #undef _S_DONE + } + int available(serial_index_t index) { + uint8_t pos = offset; + #define _S_AVAILABLE(N) if (index.within(pos, pos + step - 1)) return serial##N.available(index); else pos += step; + REPEAT(NUM_SERIAL, _S_AVAILABLE); + #undef _S_AVAILABLE + return false; + } + int read(serial_index_t index) { + uint8_t pos = offset; + #define _S_READ(N) if (index.within(pos, pos + step - 1)) return serial##N.read(index); else pos += step; + REPEAT(NUM_SERIAL, _S_READ); + #undef _S_READ + return -1; + } + void begin(const long br) { + #define _S_BEGIN(N) if (portMask.enabled(output[N])) serial##N.begin(br); + REPEAT(NUM_SERIAL, _S_BEGIN); + #undef _S_BEGIN + } + void end() { + #define _S_END(N) if (portMask.enabled(output[N])) serial##N.end(); + REPEAT(NUM_SERIAL, _S_END); + #undef _S_END + } + bool connected() { + bool ret = true; + #define _S_CONNECTED(N) if (portMask.enabled(output[N]) && !CALL_IF_EXISTS(bool, &serial##N, connected)) ret = false; + REPEAT(NUM_SERIAL, _S_CONNECTED); + #undef _S_CONNECTED + return ret; + } + + using BaseClassT::available; + using BaseClassT::read; + + // Redirect flush + NO_INLINE void flush() { + #define _S_FLUSH(N) if (portMask.enabled(output[N])) serial##N.flush(); + REPEAT(NUM_SERIAL, _S_FLUSH); + #undef _S_FLUSH + } + NO_INLINE void flushTX() { + #define _S_FLUSHTX(N) if (portMask.enabled(output[N])) CALL_IF_EXISTS(void, &serial0, flushTX); + REPEAT(NUM_SERIAL, _S_FLUSHTX); + #undef _S_FLUSHTX + } + + // Forward feature queries + SerialFeature features(serial_index_t index) const { + uint8_t pos = offset; + #define _S_FEATURES(N) if (index.within(pos, pos + step - 1)) return serial##N.features(index); else pos += step; + REPEAT(NUM_SERIAL, _S_FEATURES); + #undef _S_FEATURES + return SerialFeature::None; + } + + #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) + : BaseClassT(e), portMask(mask) REPEAT(NUM_SERIAL, _S_INIT) {} + +}; + +// Build the actual serial object depending on current configuration +#define Serial1Class TERN(SERIAL_RUNTIME_HOOK, RuntimeSerial, BaseSerial) +#define ForwardSerial1Class TERN(SERIAL_RUNTIME_HOOK, RuntimeSerial, ForwardSerial) +#ifdef HAS_MULTI_SERIAL + #define Serial2Class ConditionalSerial + #if NUM_SERIAL >= 3 + #define Serial3Class ConditionalSerial + #endif +#endif diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h index a5b78caabbe4..833167a7a196 100644 --- a/Marlin/src/core/types.h +++ b/Marlin/src/core/types.h @@ -29,6 +29,42 @@ class __FlashStringHelper; typedef const __FlashStringHelper *progmem_str; +// +// Conditional type assignment magic. For example... +// +// typename IF<(MYOPT==12), int, float>::type myvar; +// +template +struct IF { typedef R type; }; +template +struct IF { typedef L type; }; + +#define LINEAR_AXIS_GANG(V...) GANG_N(LINEAR_AXES, V) +#define LINEAR_AXIS_CODE(V...) CODE_N(LINEAR_AXES, V) +#define LINEAR_AXIS_LIST(V...) LIST_N(LINEAR_AXES, V) +#define LINEAR_AXIS_ARRAY(V...) { LINEAR_AXIS_LIST(V) } +#define LINEAR_AXIS_ARGS(T...) LINEAR_AXIS_LIST(T x, T y, T z, T i, T j, T k) +#define LINEAR_AXIS_ELEM(O) LINEAR_AXIS_LIST(O.x, O.y, O.z, O.i, O.j, O.k) +#define LINEAR_AXIS_DEFS(T,V) LINEAR_AXIS_LIST(T x=V, T y=V, T z=V, T i=V, T j=V, T k=V) + +#define LOGICAL_AXIS_GANG(E,V...) LINEAR_AXIS_GANG(V) GANG_ITEM_E(E) +#define LOGICAL_AXIS_CODE(E,V...) LINEAR_AXIS_CODE(V) CODE_ITEM_E(E) +#define LOGICAL_AXIS_LIST(E,V...) LINEAR_AXIS_LIST(V) LIST_ITEM_E(E) +#define LOGICAL_AXIS_ARRAY(E,V...) { LOGICAL_AXIS_LIST(E,V) } +#define LOGICAL_AXIS_ARGS(T...) LOGICAL_AXIS_LIST(T e, T x, T y, T z, T i, T j, T k) +#define LOGICAL_AXIS_ELEM(O) LOGICAL_AXIS_LIST(O.e, O.x, O.y, O.z, O.i, O.j, O.k) +#define LOGICAL_AXIS_DECL(T,V) LOGICAL_AXIS_LIST(T e=V, T x=V, T y=V, T z=V, T i=V, T j=V, T k=V) + +#if HAS_EXTRUDERS + #define LIST_ITEM_E(N) , N + #define CODE_ITEM_E(N) ; N + #define GANG_ITEM_E(N) N +#else + #define LIST_ITEM_E(N) + #define CODE_ITEM_E(N) + #define GANG_ITEM_E(N) +#endif + // // Enumerated axis indices // @@ -37,52 +73,84 @@ typedef const __FlashStringHelper *progmem_str; // - X_HEAD, Y_HEAD, and Z_HEAD should be used for Steppers on Core kinematics // enum AxisEnum : uint8_t { - X_AXIS = 0, A_AXIS = 0, - Y_AXIS = 1, B_AXIS = 1, - Z_AXIS = 2, C_AXIS = 2, - E_AXIS = 3, - X_HEAD = 4, Y_HEAD = 5, Z_HEAD = 6, - E0_AXIS = 3, - E1_AXIS, E2_AXIS, E3_AXIS, E4_AXIS, E5_AXIS, E6_AXIS, E7_AXIS, - ALL_AXES = 0xFE, NO_AXIS = 0xFF + + // Linear axes may be controlled directly or indirectly + LINEAR_AXIS_LIST(X_AXIS, Y_AXIS, Z_AXIS, I_AXIS, J_AXIS, K_AXIS) + + // Extruder axes may be considered distinctly + #define _EN_ITEM(N) , E##N##_AXIS + REPEAT(EXTRUDERS, _EN_ITEM) + #undef _EN_ITEM + + // Core also keeps toolhead directions + #if EITHER(IS_CORE, MARKFORGED_XY) + , X_HEAD, Y_HEAD, Z_HEAD + #endif + + // Distinct axes, including all E and Core + , NUM_AXIS_ENUMS + + // Most of the time we refer only to the single E_AXIS + #if HAS_EXTRUDERS + , E_AXIS = E0_AXIS + #endif + + // A, B, and C are for DELTA, SCARA, etc. + , A_AXIS = X_AXIS + #if LINEAR_AXES >= 2 + , B_AXIS = Y_AXIS + #endif + #if LINEAR_AXES >= 3 + , C_AXIS = Z_AXIS + #endif + + // To refer to all or none + , ALL_AXES_ENUM = 0xFE, NO_AXIS_ENUM = 0xFF }; +typedef IF<(NUM_AXIS_ENUMS > 8), uint16_t, uint8_t>::type axis_bits_t; + // -// Loop over XYZE axes +// Loop over axes // -#define LOOP_XYZ(VAR) LOOP_S_LE_N(VAR, X_AXIS, Z_AXIS) -#define LOOP_XYZE(VAR) LOOP_S_LE_N(VAR, X_AXIS, E_AXIS) -#define LOOP_XYZE_N(VAR) LOOP_S_L_N(VAR, X_AXIS, XYZE_N) #define LOOP_ABC(VAR) LOOP_S_LE_N(VAR, A_AXIS, C_AXIS) -#define LOOP_ABCE(VAR) LOOP_S_LE_N(VAR, A_AXIS, E_AXIS) -#define LOOP_ABCE_N(VAR) LOOP_S_L_N(VAR, A_AXIS, XYZE_N) +#define LOOP_LINEAR_AXES(VAR) LOOP_S_L_N(VAR, X_AXIS, LINEAR_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) // -// Conditional type assignment magic. For example... +// feedRate_t is just a humble float // -// typename IF<(MYOPT==12), int, float>::type myvar; +typedef float feedRate_t; + // -template -struct IF { typedef R type; }; -template -struct IF { typedef L type; }; +// celsius_t is the native unit of temperature. Signed to handle a disconnected thermistor value (-14). +// For more resolition (e.g., for a chocolate printer) this may later be changed to Celsius x 100 +// +typedef int16_t celsius_t; +typedef float celsius_float_t; // -// feedRate_t is just a humble float +// On AVR pointers are only 2 bytes so use 'const float &' for 'const float' // -typedef float feedRate_t; +#ifdef __AVR__ + typedef const float & const_float_t; +#else + typedef const float const_float_t; +#endif +typedef const_float_t const_feedRate_t; +typedef const_float_t const_celsius_float_t; // Conversion macros -#define MMM_TO_MMS(MM_M) feedRate_t(float(MM_M) / 60.0f) -#define MMS_TO_MMM(MM_S) (float(MM_S) * 60.0f) -#define MMS_SCALED(V) ((V) * 0.01f * feedrate_percentage) +#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) // // Coordinates structures for XY, XYZ, XYZE... // // Helpers -#define _RECIP(N) ((N) ? 1.0f / float(N) : 0.0f) +#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) << v)) #define _RS(N) (N = (T)(uint32_t(N) >> v)) @@ -170,7 +238,7 @@ void toNative(xyz_pos_t &raw); void toNative(xyze_pos_t &raw); // -// XY coordinates, counters, etc. +// Paired XY coordinates, counters, flags, etc. // template struct XYval { @@ -179,18 +247,34 @@ struct XYval { struct { T a, b; }; T pos[2]; }; + + // Set all to 0 + FI void reset() { x = y = 0; } + + // Setters taking struct types and arrays FI void set(const T px) { x = px; } - FI void set(const T px, const T py) { x = px; y = py; } - FI void set(const T (&arr)[XY]) { x = arr[0]; y = arr[1]; } - FI void set(const T (&arr)[XYZ]) { x = arr[0]; y = arr[1]; } - FI void set(const T (&arr)[XYZE]) { x = arr[0]; y = arr[1]; } - #if XYZE_N > XYZE - FI void set(const T (&arr)[XYZE_N]) { x = arr[0]; y = arr[1]; } + #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]; } #endif - FI void reset() { x = y = 0; } + #if LINEAR_AXES > XY + FI void set(const T (&arr)[LINEAR_AXES]) { x = arr[0]; y = arr[1]; } + #endif + #if LOGICAL_AXES > LINEAR_AXES + 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]; } + #endif + #endif + + // Length reduced to one dimension FI T magnitude() const { return (T)sqrtf(x*x + y*y); } + // Pointer to the data as a simple array FI operator T* () { return pos; } + // If any element is true then it's true FI operator bool() { return 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) }; } @@ -199,20 +283,30 @@ struct XYval { 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 { float(x), float(y) }; } - FI XYval asFloat() const { return { float(x), float(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) }; } + + // 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; } + + // 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 T& operator[](const int i) { return pos[i]; } - FI const T& operator[](const int i) const { return pos[i]; } + + // 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]; } + + // 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; } + + // 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; } @@ -249,6 +343,10 @@ struct XYval { FI XYval operator>>(const int &v) { XYval ls = *this; _RS(ls.x); _RS(ls.y); return ls; } FI XYval operator<<(const int &v) const { XYval ls = *this; _LS(ls.x); _LS(ls.y); return ls; } FI XYval operator<<(const int &v) { 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; } + + // 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; } @@ -262,6 +360,8 @@ struct XYval { FI XYval& operator*=(const int &v) { x *= v; y *= v; return *this; } FI XYval& operator>>=(const int &v) { _RS(x); _RS(y); return *this; } FI XYval& operator<<=(const int &v) { _LS(x); _LS(y); return *this; } + + // Exact comparisons. For floats a "NEAR" operation may be better. FI bool operator==(const XYval &rs) { return x == rs.x && y == rs.y; } FI bool operator==(const XYZval &rs) { return x == rs.x && y == rs.y; } FI bool operator==(const XYZEval &rs) { return x == rs.x && y == rs.y; } @@ -274,224 +374,291 @@ struct XYval { 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 XYval operator-() { XYval o = *this; o.x = -x; o.y = -y; return o; } - FI const XYval operator-() const { XYval o = *this; o.x = -x; o.y = -y; return o; } }; // -// XYZ coordinates, counters, etc. +// Linear Axes coordinates, counters, flags, etc. // template struct XYZval { union { - struct { T x, y, z; }; - struct { T a, b, c; }; - T pos[3]; + struct { T LINEAR_AXIS_ARGS(); }; + struct { T LINEAR_AXIS_LIST(a, b, c, u, v, w); }; + T pos[LINEAR_AXES]; }; + + // Set all to 0 + FI void reset() { LINEAR_AXIS_GANG(x =, y =, z =, i =, j =, k =) 0; } + + // Setters taking struct types and arrays FI void set(const T px) { x = px; } FI void set(const T px, const T py) { x = px; y = py; } - FI void set(const T px, const T py, const T pz) { x = px; y = py; z = pz; } - FI void set(const XYval pxy, const T pz) { x = pxy.x; y = pxy.y; z = pz; } + FI void set(const XYval pxy) { x = pxy.x; y = pxy.y; } + FI void set(const XYval pxy, const T pz) { LINEAR_AXIS_CODE(x = pxy.x, y = pxy.y, z = pz, NOOP, NOOP, NOOP); } FI void set(const T (&arr)[XY]) { x = arr[0]; y = arr[1]; } - FI void set(const T (&arr)[XYZ]) { x = arr[0]; y = arr[1]; z = arr[2]; } - FI void set(const T (&arr)[XYZE]) { x = arr[0]; y = arr[1]; z = arr[2]; } - #if XYZE_N > XYZE - FI void set(const T (&arr)[XYZE_N]) { x = arr[0]; y = arr[1]; z = arr[2]; } + #if HAS_Z_AXIS + FI void set(const T (&arr)[LINEAR_AXES]) { LINEAR_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5]); } + FI void set(LINEAR_AXIS_ARGS(const T)) { LINEAR_AXIS_CODE(a = x, b = y, c = z, u = i, v = j, w = k ); } + #endif + #if LOGICAL_AXES > LINEAR_AXES + FI void set(const T (&arr)[LOGICAL_AXES]) { LINEAR_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5]); } + FI void set(LOGICAL_AXIS_ARGS(const T)) { LINEAR_AXIS_CODE(a = x, b = y, c = z, u = i, v = j, w = k ); } + #if DISTINCT_AXES > LOGICAL_AXES + FI void set(const T (&arr)[DISTINCT_AXES]) { LINEAR_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5]); } + #endif + #endif + #if LINEAR_AXES >= 4 + FI void set(const T px, const T py, const T pz) { x = px; y = py; z = pz; } + #endif + #if LINEAR_AXES >= 5 + FI void set(const T px, const T py, const T pz, const T pi) { x = px; y = py; z = pz; i = pi; } #endif - FI void reset() { x = y = z = 0; } - FI T magnitude() const { return (T)sqrtf(x*x + y*y + z*z); } + #if LINEAR_AXES >= 6 + FI void set(const T px, const T py, const T pz, const T pi, const T pj) { x = px; y = py; z = pz; i = pi; j = pj; } + #endif + + // Length reduced to one dimension + FI T magnitude() const { return (T)sqrtf(LINEAR_AXIS_GANG(x*x, + y*y, + z*z, + i*i, + j*j, + k*k)); } + // Pointer to the data as a simple array FI operator T* () { return pos; } - FI operator bool() { return z || x || y; } + // If any element is true then it's true + FI operator bool() { return LINEAR_AXIS_GANG(x, || y, || z, || i, || j, || k); } + + // Explicit copy and copies with conversion FI XYZval copy() const { XYZval o = *this; return o; } - FI XYZval ABS() const { return { T(_ABS(x)), T(_ABS(y)), T(_ABS(z)) }; } - FI XYZval asInt() { return { int16_t(x), int16_t(y), int16_t(z) }; } - FI XYZval asInt() const { return { int16_t(x), int16_t(y), int16_t(z) }; } - FI XYZval asLong() { return { int32_t(x), int32_t(y), int32_t(z) }; } - FI XYZval asLong() const { return { int32_t(x), int32_t(y), int32_t(z) }; } - FI XYZval ROUNDL() { return { int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)) }; } - FI XYZval ROUNDL() const { return { int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)) }; } - FI XYZval asFloat() { return { float(x), float(y), float(z) }; } - FI XYZval asFloat() const { return { float(x), float(y), float(z) }; } - FI XYZval reciprocal() const { return { _RECIP(x), _RECIP(y), _RECIP(z) }; } + FI XYZval ABS() const { return LINEAR_AXIS_ARRAY(T(_ABS(x)), T(_ABS(y)), T(_ABS(z)), T(_ABS(i)), T(_ABS(j)), T(_ABS(k))); } + FI XYZval asInt() { return LINEAR_AXIS_ARRAY(int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k)); } + FI XYZval asInt() const { return LINEAR_AXIS_ARRAY(int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k)); } + FI XYZval asLong() { return LINEAR_AXIS_ARRAY(int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k)); } + FI XYZval asLong() const { return LINEAR_AXIS_ARRAY(int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k)); } + FI XYZval ROUNDL() { return LINEAR_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))); } + FI XYZval ROUNDL() const { return LINEAR_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))); } + FI XYZval asFloat() { return LINEAR_AXIS_ARRAY(static_cast(x), static_cast(y), static_cast(z), static_cast(i), static_cast(j), static_cast(k)); } + FI XYZval asFloat() const { return LINEAR_AXIS_ARRAY(static_cast(x), static_cast(y), static_cast(z), static_cast(i), static_cast(j), static_cast(k)); } + FI XYZval reciprocal() const { return LINEAR_AXIS_ARRAY(_RECIP(x), _RECIP(y), _RECIP(z), _RECIP(i), _RECIP(j), _RECIP(k)); } + + // 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; } + + // 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 XYZEval() const { return { x, y, z }; } - FI T& operator[](const int i) { return pos[i]; } - FI const T& operator[](const int i) const { return pos[i]; } - FI XYZval& operator= (const T v) { set(v, v, v ); return *this; } + + // Cast to a type with more fields by making a new object + FI operator XYZEval() const { return LINEAR_AXIS_ARRAY(x, y, z, i, j, k); } + + // 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]; } + + // Assignment operator overrides do the expected thing + FI XYZval& operator= (const T v) { set(ARRAY_N_1(LINEAR_AXES, v)); return *this; } FI XYZval& operator= (const XYval &rs) { set(rs.x, rs.y ); return *this; } - FI XYZval& operator= (const XYZEval &rs) { set(rs.x, rs.y, rs.z); return *this; } - FI XYZval operator+ (const XYval &rs) const { XYZval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } - FI XYZval operator+ (const XYval &rs) { XYZval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } - FI XYZval operator- (const XYval &rs) const { XYZval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } - FI XYZval operator- (const XYval &rs) { XYZval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } - FI XYZval operator* (const XYval &rs) const { XYZval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } - FI XYZval operator* (const XYval &rs) { XYZval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } - FI XYZval operator/ (const XYval &rs) const { XYZval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } - FI XYZval operator/ (const XYval &rs) { XYZval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } - FI XYZval operator+ (const XYZval &rs) const { XYZval ls = *this; ls.x += rs.x; ls.y += rs.y; ls.z += rs.z; return ls; } - FI XYZval operator+ (const XYZval &rs) { XYZval ls = *this; ls.x += rs.x; ls.y += rs.y; ls.z += rs.z; return ls; } - FI XYZval operator- (const XYZval &rs) const { XYZval ls = *this; ls.x -= rs.x; ls.y -= rs.y; ls.z -= rs.z; return ls; } - FI XYZval operator- (const XYZval &rs) { XYZval ls = *this; ls.x -= rs.x; ls.y -= rs.y; ls.z -= rs.z; return ls; } - FI XYZval operator* (const XYZval &rs) const { XYZval ls = *this; ls.x *= rs.x; ls.y *= rs.y; ls.z *= rs.z; return ls; } - FI XYZval operator* (const XYZval &rs) { XYZval ls = *this; ls.x *= rs.x; ls.y *= rs.y; ls.z *= rs.z; return ls; } - FI XYZval operator/ (const XYZval &rs) const { XYZval ls = *this; ls.x /= rs.x; ls.y /= rs.y; ls.z /= rs.z; return ls; } - FI XYZval operator/ (const XYZval &rs) { XYZval ls = *this; ls.x /= rs.x; ls.y /= rs.y; ls.z /= rs.z; return ls; } - FI XYZval operator+ (const XYZEval &rs) const { XYZval ls = *this; ls.x += rs.x; ls.y += rs.y; ls.z += rs.z; return ls; } - FI XYZval operator+ (const XYZEval &rs) { XYZval ls = *this; ls.x += rs.x; ls.y += rs.y; ls.z += rs.z; return ls; } - FI XYZval operator- (const XYZEval &rs) const { XYZval ls = *this; ls.x -= rs.x; ls.y -= rs.y; ls.z -= rs.z; return ls; } - FI XYZval operator- (const XYZEval &rs) { XYZval ls = *this; ls.x -= rs.x; ls.y -= rs.y; ls.z -= rs.z; return ls; } - FI XYZval operator* (const XYZEval &rs) const { XYZval ls = *this; ls.x *= rs.x; ls.y *= rs.y; ls.z *= rs.z; return ls; } - FI XYZval operator* (const XYZEval &rs) { XYZval ls = *this; ls.x *= rs.x; ls.y *= rs.y; ls.z *= rs.z; return ls; } - FI XYZval operator/ (const XYZEval &rs) const { XYZval ls = *this; ls.x /= rs.x; ls.y /= rs.y; ls.z /= rs.z; return ls; } - FI XYZval operator/ (const XYZEval &rs) { XYZval ls = *this; ls.x /= rs.x; ls.y /= rs.y; ls.z /= rs.z; return ls; } - FI XYZval operator* (const float &v) const { XYZval ls = *this; ls.x *= v; ls.y *= v; ls.z *= v; return ls; } - FI XYZval operator* (const float &v) { XYZval ls = *this; ls.x *= v; ls.y *= v; ls.z *= v; return ls; } - FI XYZval operator* (const int &v) const { XYZval ls = *this; ls.x *= v; ls.y *= v; ls.z *= v; return ls; } - FI XYZval operator* (const int &v) { XYZval ls = *this; ls.x *= v; ls.y *= v; ls.z *= v; return ls; } - FI XYZval operator/ (const float &v) const { XYZval ls = *this; ls.x /= v; ls.y /= v; ls.z /= v; return ls; } - FI XYZval operator/ (const float &v) { XYZval ls = *this; ls.x /= v; ls.y /= v; ls.z /= v; return ls; } - FI XYZval operator/ (const int &v) const { XYZval ls = *this; ls.x /= v; ls.y /= v; ls.z /= v; return ls; } - FI XYZval operator/ (const int &v) { XYZval ls = *this; ls.x /= v; ls.y /= v; ls.z /= v; return ls; } - FI XYZval operator>>(const int &v) const { XYZval ls = *this; _RS(ls.x); _RS(ls.y); _RS(ls.z); return ls; } - FI XYZval operator>>(const int &v) { XYZval ls = *this; _RS(ls.x); _RS(ls.y); _RS(ls.z); return ls; } - FI XYZval operator<<(const int &v) const { XYZval ls = *this; _LS(ls.x); _LS(ls.y); _LS(ls.z); return ls; } - FI XYZval operator<<(const int &v) { XYZval ls = *this; _LS(ls.x); _LS(ls.y); _LS(ls.z); return ls; } - FI XYZval& operator+=(const XYval &rs) { x += rs.x; y += rs.y; return *this; } - FI XYZval& operator-=(const XYval &rs) { x -= rs.x; y -= rs.y; return *this; } - FI XYZval& operator*=(const XYval &rs) { x *= rs.x; y *= rs.y; return *this; } - FI XYZval& operator/=(const XYval &rs) { x /= rs.x; y /= rs.y; return *this; } - FI XYZval& operator+=(const XYZval &rs) { x += rs.x; y += rs.y; z += rs.z; return *this; } - FI XYZval& operator-=(const XYZval &rs) { x -= rs.x; y -= rs.y; z -= rs.z; return *this; } - FI XYZval& operator*=(const XYZval &rs) { x *= rs.x; y *= rs.y; z *= rs.z; return *this; } - FI XYZval& operator/=(const XYZval &rs) { x /= rs.x; y /= rs.y; z /= rs.z; return *this; } - FI XYZval& operator+=(const XYZEval &rs) { x += rs.x; y += rs.y; z += rs.z; return *this; } - FI XYZval& operator-=(const XYZEval &rs) { x -= rs.x; y -= rs.y; z -= rs.z; return *this; } - FI XYZval& operator*=(const XYZEval &rs) { x *= rs.x; y *= rs.y; z *= rs.z; return *this; } - FI XYZval& operator/=(const XYZEval &rs) { x /= rs.x; y /= rs.y; z /= rs.z; return *this; } - FI XYZval& operator*=(const float &v) { x *= v; y *= v; z *= v; return *this; } - FI XYZval& operator*=(const int &v) { x *= v; y *= v; z *= v; return *this; } - FI XYZval& operator>>=(const int &v) { _RS(x); _RS(y); _RS(z); return *this; } - FI XYZval& operator<<=(const int &v) { _LS(x); _LS(y); _LS(z); return *this; } - FI bool operator==(const XYZEval &rs) { return x == rs.x && y == rs.y && z == rs.z; } + FI XYZval& operator= (const XYZEval &rs) { set(LINEAR_AXIS_ELEM(rs)); return *this; } + + // Override other operators to get intuitive behaviors + FI XYZval operator+ (const XYval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, NOOP , NOOP , NOOP , NOOP ); return ls; } + FI XYZval operator+ (const XYval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, NOOP , NOOP , NOOP , NOOP ); return ls; } + FI XYZval operator- (const XYval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, NOOP , NOOP , NOOP , NOOP ); return ls; } + FI XYZval operator- (const XYval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, NOOP , NOOP , NOOP , NOOP ); return ls; } + FI XYZval operator* (const XYval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, NOOP , NOOP , NOOP , NOOP ); return ls; } + FI XYZval operator* (const XYval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, NOOP , NOOP , NOOP , NOOP ); return ls; } + FI XYZval operator/ (const XYval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, NOOP , NOOP , NOOP , NOOP ); return ls; } + FI XYZval operator/ (const XYval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, NOOP , NOOP , NOOP , NOOP ); return ls; } + FI XYZval operator+ (const XYZval &rs) const { XYZval ls = *this; LINEAR_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); return ls; } + FI XYZval operator+ (const XYZval &rs) { XYZval ls = *this; LINEAR_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); return ls; } + FI XYZval operator- (const XYZval &rs) const { XYZval ls = *this; LINEAR_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); return ls; } + FI XYZval operator- (const XYZval &rs) { XYZval ls = *this; LINEAR_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); return ls; } + FI XYZval operator* (const XYZval &rs) const { XYZval ls = *this; LINEAR_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); return ls; } + FI XYZval operator* (const XYZval &rs) { XYZval ls = *this; LINEAR_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); return ls; } + FI XYZval operator/ (const XYZval &rs) const { XYZval ls = *this; LINEAR_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); return ls; } + FI XYZval operator/ (const XYZval &rs) { XYZval ls = *this; LINEAR_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); return ls; } + FI XYZval operator+ (const XYZEval &rs) const { XYZval ls = *this; LINEAR_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); return ls; } + FI XYZval operator+ (const XYZEval &rs) { XYZval ls = *this; LINEAR_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); return ls; } + FI XYZval operator- (const XYZEval &rs) const { XYZval ls = *this; LINEAR_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); return ls; } + FI XYZval operator- (const XYZEval &rs) { XYZval ls = *this; LINEAR_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); return ls; } + FI XYZval operator* (const XYZEval &rs) const { XYZval ls = *this; LINEAR_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); return ls; } + FI XYZval operator* (const XYZEval &rs) { XYZval ls = *this; LINEAR_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); return ls; } + FI XYZval operator/ (const XYZEval &rs) const { XYZval ls = *this; LINEAR_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); return ls; } + FI XYZval operator/ (const XYZEval &rs) { XYZval ls = *this; LINEAR_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); return ls; } + FI XYZval operator* (const float &v) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v ); return ls; } + FI XYZval operator* (const float &v) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v ); return ls; } + FI XYZval operator* (const int &v) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v ); return ls; } + FI XYZval operator* (const int &v) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v ); return ls; } + FI XYZval operator/ (const float &v) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v ); return ls; } + FI XYZval operator/ (const float &v) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v ); return ls; } + FI XYZval operator/ (const int &v) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v ); return ls; } + FI XYZval operator/ (const int &v) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v ); return ls; } + FI XYZval operator>>(const int &v) const { XYZval ls = *this; LINEAR_AXIS_CODE(_RS(ls.x), _RS(ls.y), _RS(ls.z), _RS(ls.i), _RS(ls.j), _RS(ls.k) ); return ls; } + FI XYZval operator>>(const int &v) { XYZval ls = *this; LINEAR_AXIS_CODE(_RS(ls.x), _RS(ls.y), _RS(ls.z), _RS(ls.i), _RS(ls.j), _RS(ls.k) ); return ls; } + FI XYZval operator<<(const int &v) const { XYZval ls = *this; LINEAR_AXIS_CODE(_LS(ls.x), _LS(ls.y), _LS(ls.z), _LS(ls.i), _LS(ls.j), _LS(ls.k) ); return ls; } + FI XYZval operator<<(const int &v) { XYZval ls = *this; LINEAR_AXIS_CODE(_LS(ls.x), _LS(ls.y), _LS(ls.z), _LS(ls.i), _LS(ls.j), _LS(ls.k) ); return ls; } + FI const XYZval operator-() const { XYZval o = *this; LINEAR_AXIS_CODE(o.x = -x, o.y = -y, o.z = -z, o.i = -i, o.j = -j, o.k = -k); return o; } + FI XYZval operator-() { XYZval o = *this; LINEAR_AXIS_CODE(o.x = -x, o.y = -y, o.z = -z, o.i = -i, o.j = -j, o.k = -k); return o; } + + // Modifier operators + FI XYZval& operator+=(const XYval &rs) { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, NOOP, NOOP, NOOP, NOOP ); return *this; } + FI XYZval& operator-=(const XYval &rs) { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, NOOP, NOOP, NOOP, NOOP ); return *this; } + FI XYZval& operator*=(const XYval &rs) { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, NOOP, NOOP, NOOP, NOOP ); return *this; } + FI XYZval& operator/=(const XYval &rs) { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, NOOP, NOOP, NOOP, NOOP ); return *this; } + FI XYZval& operator+=(const XYZval &rs) { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k); return *this; } + FI XYZval& operator-=(const XYZval &rs) { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k); return *this; } + FI XYZval& operator*=(const XYZval &rs) { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k); return *this; } + FI XYZval& operator/=(const XYZval &rs) { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k); return *this; } + FI XYZval& operator+=(const XYZEval &rs) { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k); return *this; } + FI XYZval& operator-=(const XYZEval &rs) { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k); return *this; } + FI XYZval& operator*=(const XYZEval &rs) { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k); return *this; } + FI XYZval& operator/=(const XYZEval &rs) { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k); return *this; } + FI XYZval& operator*=(const float &v) { LINEAR_AXIS_CODE(x *= v, y *= v, z *= v, i *= v, j *= v, k *= v); return *this; } + FI XYZval& operator*=(const int &v) { LINEAR_AXIS_CODE(x *= v, y *= v, z *= v, i *= v, j *= v, k *= v); return *this; } + FI XYZval& operator>>=(const int &v) { LINEAR_AXIS_CODE(_RS(x), _RS(y), _RS(z), _RS(i), _RS(j), _RS(k)); return *this; } + FI XYZval& operator<<=(const int &v) { LINEAR_AXIS_CODE(_LS(x), _LS(y), _LS(z), _LS(i), _LS(j), _LS(k)); return *this; } + + // Exact comparisons. For floats a "NEAR" operation may be better. + FI bool operator==(const XYZEval &rs) { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k); } + FI bool operator==(const XYZEval &rs) const { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k); } FI bool operator!=(const XYZEval &rs) { return !operator==(rs); } - FI bool operator==(const XYZEval &rs) const { return x == rs.x && y == rs.y && z == rs.z; } FI bool operator!=(const XYZEval &rs) const { return !operator==(rs); } - FI XYZval operator-() { XYZval o = *this; o.x = -x; o.y = -y; o.z = -z; return o; } - FI const XYZval operator-() const { XYZval o = *this; o.x = -x; o.y = -y; o.z = -z; return o; } }; // -// XYZE coordinates, counters, etc. +// Logical Axes coordinates, counters, etc. // template struct XYZEval { union { - struct{ T x, y, z, e; }; - struct{ T a, b, c; }; - T pos[4]; + struct { T LOGICAL_AXIS_ARGS(); }; + struct { T LOGICAL_AXIS_LIST(_e, a, b, c, u, v, w); }; + T pos[LOGICAL_AXES]; }; - FI void reset() { x = y = z = e = 0; } - FI T magnitude() const { return (T)sqrtf(x*x + y*y + z*z + e*e); } - FI operator T* () { return pos; } - FI operator bool() { return e || z || x || y; } - FI void set(const T px) { x = px; } - FI void set(const T px, const T py) { x = px; y = py; } - FI void set(const T px, const T py, const T pz) { x = px; y = py; z = pz; } - FI void set(const T px, const T py, const T pz, const T pe) { x = px; y = py; z = pz; e = pe; } - FI void set(const XYval pxy) { x = pxy.x; y = pxy.y; } - FI void set(const XYval pxy, const T pz) { x = pxy.x; y = pxy.y; z = pz; } - FI void set(const XYZval pxyz) { x = pxyz.x; y = pxyz.y; z = pxyz.z; } - FI void set(const XYval pxy, const T pz, const T pe) { x = pxy.x; y = pxy.y; z = pz; e = pe; } - FI void set(const XYval pxy, const XYval pze) { x = pxy.x; y = pxy.y; z = pze.z; e = pze.e; } - FI void set(const XYZval pxyz, const T pe) { x = pxyz.x; y = pxyz.y; z = pxyz.z; e = pe; } - FI void set(const T (&arr)[XY]) { x = arr[0]; y = arr[1]; } - FI void set(const T (&arr)[XYZ]) { x = arr[0]; y = arr[1]; z = arr[2]; } - FI void set(const T (&arr)[XYZE]) { x = arr[0]; y = arr[1]; z = arr[2]; e = arr[3]; } - #if XYZE_N > XYZE - FI void set(const T (&arr)[XYZE_N]) { x = arr[0]; y = arr[1]; z = arr[2]; e = arr[3]; } + // Reset all to 0 + FI void reset() { LOGICAL_AXIS_GANG(e =, x =, y =, z =, i =, j =, k =) 0; } + + // Setters taking struct types and arrays + FI void set(const T px) { x = px; } + FI void set(const T px, const T py) { x = px; y = py; } + FI void set(const XYval pxy) { x = pxy.x; y = pxy.y; } + FI void set(const XYZval pxyz) { set(LINEAR_AXIS_ELEM(pxyz)); } + #if HAS_Z_AXIS + FI void set(LINEAR_AXIS_ARGS(const T)) { LINEAR_AXIS_CODE(a = x, b = y, c = z, u = i, v = j, w = k); } + #endif + #if LOGICAL_AXES > LINEAR_AXES + FI void set(const XYval pxy, const T pe) { set(pxy); e = pe; } + FI void set(const XYZval pxyz, const T pe) { set(pxyz); e = pe; } + FI void set(LOGICAL_AXIS_ARGS(const T)) { LOGICAL_AXIS_CODE(_e = e, a = x, b = y, c = z, u = i, v = j, w = k); } + #endif + #if LINEAR_AXES >= 4 + FI void set(const T px, const T py, const T pz) { x = px; y = py; z = pz; } #endif - FI XYZEval copy() const { return *this; } - FI XYZEval ABS() const { return { T(_ABS(x)), T(_ABS(y)), T(_ABS(z)), T(_ABS(e)) }; } - FI XYZEval asInt() { return { int16_t(x), int16_t(y), int16_t(z), int16_t(e) }; } - FI XYZEval asInt() const { return { int16_t(x), int16_t(y), int16_t(z), int16_t(e) }; } - FI XYZEval asLong() { return { int32_t(x), int32_t(y), int32_t(z), int32_t(e) }; } - FI XYZEval asLong() const { return { int32_t(x), int32_t(y), int32_t(z), int32_t(e) }; } - FI XYZEval ROUNDL() { return { int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(e)) }; } - FI XYZEval ROUNDL() const { return { int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(e)) }; } - FI XYZEval asFloat() { return { float(x), float(y), float(z), float(e) }; } - FI XYZEval asFloat() const { return { float(x), float(y), float(z), float(e) }; } - FI XYZEval reciprocal() const { return { _RECIP(x), _RECIP(y), _RECIP(z), _RECIP(e) }; } - FI XYZEval asLogical() const { XYZEval o = asFloat(); toLogical(o); return o; } - FI XYZEval asNative() const { XYZEval o = asFloat(); toNative(o); return o; } - FI operator XYval&() { return *(XYval*)this; } - FI operator const XYval&() const { return *(const XYval*)this; } - FI operator XYZval&() { return *(XYZval*)this; } - FI operator const XYZval&() const { return *(const XYZval*)this; } - FI T& operator[](const int i) { return pos[i]; } - FI const T& operator[](const int i) const { return pos[i]; } - FI XYZEval& operator= (const T v) { set(v, v, v, v); return *this; } - FI XYZEval& operator= (const XYval &rs) { set(rs.x, rs.y); return *this; } - FI XYZEval& operator= (const XYZval &rs) { set(rs.x, rs.y, rs.z); return *this; } - 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 { XYZEval ls = *this; ls.x += rs.x; ls.y += rs.y; ls.z += rs.z; return ls; } - FI XYZEval operator+ (const XYZval &rs) { XYZEval ls = *this; ls.x += rs.x; ls.y += rs.y; ls.z += rs.z; return ls; } - FI XYZEval operator- (const XYZval &rs) const { XYZEval ls = *this; ls.x -= rs.x; ls.y -= rs.y; ls.z -= rs.z; return ls; } - FI XYZEval operator- (const XYZval &rs) { XYZEval ls = *this; ls.x -= rs.x; ls.y -= rs.y; ls.z -= rs.z; return ls; } - FI XYZEval operator* (const XYZval &rs) const { XYZEval ls = *this; ls.x *= rs.x; ls.y *= rs.y; ls.z *= rs.z; return ls; } - FI XYZEval operator* (const XYZval &rs) { XYZEval ls = *this; ls.x *= rs.x; ls.y *= rs.y; ls.z *= rs.z; return ls; } - FI XYZEval operator/ (const XYZval &rs) const { XYZEval ls = *this; ls.x /= rs.x; ls.y /= rs.y; ls.z /= rs.z; return ls; } - FI XYZEval operator/ (const XYZval &rs) { XYZEval ls = *this; ls.x /= rs.x; ls.y /= rs.y; ls.z /= rs.z; return ls; } - FI XYZEval operator+ (const XYZEval &rs) const { XYZEval ls = *this; ls.x += rs.x; ls.y += rs.y; ls.z += rs.z; ls.e += rs.e; return ls; } - FI XYZEval operator+ (const XYZEval &rs) { XYZEval ls = *this; ls.x += rs.x; ls.y += rs.y; ls.z += rs.z; ls.e += rs.e; return ls; } - FI XYZEval operator- (const XYZEval &rs) const { XYZEval ls = *this; ls.x -= rs.x; ls.y -= rs.y; ls.z -= rs.z; ls.e -= rs.e; return ls; } - FI XYZEval operator- (const XYZEval &rs) { XYZEval ls = *this; ls.x -= rs.x; ls.y -= rs.y; ls.z -= rs.z; ls.e -= rs.e; return ls; } - FI XYZEval operator* (const XYZEval &rs) const { XYZEval ls = *this; ls.x *= rs.x; ls.y *= rs.y; ls.z *= rs.z; ls.e *= rs.e; return ls; } - FI XYZEval operator* (const XYZEval &rs) { XYZEval ls = *this; ls.x *= rs.x; ls.y *= rs.y; ls.z *= rs.z; ls.e *= rs.e; return ls; } - FI XYZEval operator/ (const XYZEval &rs) const { XYZEval ls = *this; ls.x /= rs.x; ls.y /= rs.y; ls.z /= rs.z; ls.e /= rs.e; return ls; } - FI XYZEval operator/ (const XYZEval &rs) { XYZEval ls = *this; ls.x /= rs.x; ls.y /= rs.y; ls.z /= rs.z; ls.e /= rs.e; return ls; } - FI XYZEval operator* (const float &v) const { XYZEval ls = *this; ls.x *= v; ls.y *= v; ls.z *= v; ls.e *= v; return ls; } - FI XYZEval operator* (const float &v) { XYZEval ls = *this; ls.x *= v; ls.y *= v; ls.z *= v; ls.e *= v; return ls; } - FI XYZEval operator* (const int &v) const { XYZEval ls = *this; ls.x *= v; ls.y *= v; ls.z *= v; ls.e *= v; return ls; } - FI XYZEval operator* (const int &v) { XYZEval ls = *this; ls.x *= v; ls.y *= v; ls.z *= v; ls.e *= v; return ls; } - FI XYZEval operator/ (const float &v) const { XYZEval ls = *this; ls.x /= v; ls.y /= v; ls.z /= v; ls.e /= v; return ls; } - FI XYZEval operator/ (const float &v) { XYZEval ls = *this; ls.x /= v; ls.y /= v; ls.z /= v; ls.e /= v; return ls; } - FI XYZEval operator/ (const int &v) const { XYZEval ls = *this; ls.x /= v; ls.y /= v; ls.z /= v; ls.e /= v; return ls; } - FI XYZEval operator/ (const int &v) { XYZEval ls = *this; ls.x /= v; ls.y /= v; ls.z /= v; ls.e /= v; return ls; } - FI XYZEval operator>>(const int &v) const { XYZEval ls = *this; _RS(ls.x); _RS(ls.y); _RS(ls.z); _RS(ls.e); return ls; } - FI XYZEval operator>>(const int &v) { XYZEval ls = *this; _RS(ls.x); _RS(ls.y); _RS(ls.z); _RS(ls.e); return ls; } - FI XYZEval operator<<(const int &v) const { XYZEval ls = *this; _LS(ls.x); _LS(ls.y); _LS(ls.z); _LS(ls.e); return ls; } - FI XYZEval operator<<(const int &v) { XYZEval ls = *this; _LS(ls.x); _LS(ls.y); _LS(ls.z); _LS(ls.e); return ls; } - FI XYZEval& operator+=(const XYval &rs) { x += rs.x; y += rs.y; return *this; } - FI XYZEval& operator-=(const XYval &rs) { x -= rs.x; y -= rs.y; return *this; } - FI XYZEval& operator*=(const XYval &rs) { x *= rs.x; y *= rs.y; return *this; } - FI XYZEval& operator/=(const XYval &rs) { x /= rs.x; y /= rs.y; return *this; } - FI XYZEval& operator+=(const XYZval &rs) { x += rs.x; y += rs.y; z += rs.z; return *this; } - FI XYZEval& operator-=(const XYZval &rs) { x -= rs.x; y -= rs.y; z -= rs.z; return *this; } - FI XYZEval& operator*=(const XYZval &rs) { x *= rs.x; y *= rs.y; z *= rs.z; return *this; } - FI XYZEval& operator/=(const XYZval &rs) { x /= rs.x; y /= rs.y; z /= rs.z; return *this; } - FI XYZEval& operator+=(const XYZEval &rs) { x += rs.x; y += rs.y; z += rs.z; e += rs.e; return *this; } - FI XYZEval& operator-=(const XYZEval &rs) { x -= rs.x; y -= rs.y; z -= rs.z; e -= rs.e; return *this; } - FI XYZEval& operator*=(const XYZEval &rs) { x *= rs.x; y *= rs.y; z *= rs.z; e *= rs.e; return *this; } - FI XYZEval& operator/=(const XYZEval &rs) { x /= rs.x; y /= rs.y; z /= rs.z; e /= rs.e; return *this; } - FI XYZEval& operator*=(const T &v) { x *= v; y *= v; z *= v; e *= v; return *this; } - FI XYZEval& operator>>=(const int &v) { _RS(x); _RS(y); _RS(z); _RS(e); return *this; } - FI XYZEval& operator<<=(const int &v) { _LS(x); _LS(y); _LS(z); _LS(e); return *this; } - FI bool operator==(const XYZval &rs) { return x == rs.x && y == rs.y && z == rs.z; } - FI bool operator!=(const XYZval &rs) { return !operator==(rs); } - FI bool operator==(const XYZval &rs) const { return x == rs.x && y == rs.y && z == rs.z; } - FI bool operator!=(const XYZval &rs) const { return !operator==(rs); } - FI XYZEval operator-() { return { -x, -y, -z, -e }; } - FI const XYZEval operator-() const { return { -x, -y, -z, -e }; } + #if LINEAR_AXES >= 5 + FI void set(const T px, const T py, const T pz, const T pi) { x = px; y = py; z = pz; i = pi; } + #endif + #if LINEAR_AXES >= 6 + FI void set(const T px, const T py, const T pz, const T pi, const T pj) { x = px; y = py; z = pz; i = pi; j = pj; } + #endif + + // 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)); } + // Pointer to the data as a simple array + 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); } + + // Explicit copy and copies with conversion + FI XYZEval copy() const { XYZEval o = *this; return o; } + 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))); } + 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)); } + 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)); } + 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)); } + 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)); } + 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))); } + 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))); } + 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)); } + 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)); } + FI XYZEval reciprocal() const { return LOGICAL_AXIS_ARRAY(_RECIP(e), _RECIP(x), _RECIP(y), _RECIP(z), _RECIP(i), _RECIP(j), _RECIP(k)); } + + // 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; } + + // 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 XYZval&() { return *(XYZval*)this; } + 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]; } + + // Assignment operator overrides do the expected thing + FI XYZEval& operator= (const T v) { set(LIST_N_1(LINEAR_AXES, v)); return *this; } + FI XYZEval& operator= (const XYval &rs) { set(rs.x, rs.y); return *this; } + FI XYZEval& operator= (const XYZval &rs) { set(LINEAR_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; LINEAR_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); return ls; } + FI XYZEval operator+ (const XYZval &rs) { XYZval ls = *this; LINEAR_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); return ls; } + FI XYZEval operator- (const XYZval &rs) const { XYZval ls = *this; LINEAR_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); return ls; } + FI XYZEval operator- (const XYZval &rs) { XYZval ls = *this; LINEAR_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); return ls; } + FI XYZEval operator* (const XYZval &rs) const { XYZval ls = *this; LINEAR_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); return ls; } + FI XYZEval operator* (const XYZval &rs) { XYZval ls = *this; LINEAR_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); return ls; } + FI XYZEval operator/ (const XYZval &rs) const { XYZval ls = *this; LINEAR_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); return ls; } + FI XYZEval operator/ (const XYZval &rs) { XYZval ls = *this; LINEAR_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); 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); 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); 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); 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); 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); 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); 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); 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); return ls; } + FI XYZEval operator* (const float &v) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v ); return ls; } + FI XYZEval operator* (const float &v) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v ); return ls; } + FI XYZEval operator* (const int &v) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v ); return ls; } + FI XYZEval operator* (const int &v) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v ); return ls; } + FI XYZEval operator/ (const float &v) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v ); return ls; } + FI XYZEval operator/ (const float &v) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v ); return ls; } + FI XYZEval operator/ (const int &v) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v ); return ls; } + FI XYZEval operator/ (const int &v) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v ); return ls; } + FI XYZEval operator>>(const int &v) 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) ); return ls; } + FI XYZEval operator>>(const int &v) { 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) ); return ls; } + FI XYZEval operator<<(const int &v) 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) ); return ls; } + FI XYZEval operator<<(const int &v) { 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) ); return ls; } + FI const XYZEval operator-() const { return LOGICAL_AXIS_ARRAY(-e, -x, -y, -z, -i, -j, -k); } + FI XYZEval operator-() { return LOGICAL_AXIS_ARRAY(-e, -x, -y, -z, -i, -j, -k); } + + // Modifier operators + FI XYZEval& operator+=(const XYval &rs) { x += rs.x; y += rs.y; return *this; } + FI XYZEval& operator-=(const XYval &rs) { x -= rs.x; y -= rs.y; return *this; } + FI XYZEval& operator*=(const XYval &rs) { x *= rs.x; y *= rs.y; return *this; } + FI XYZEval& operator/=(const XYval &rs) { x /= rs.x; y /= rs.y; return *this; } + FI XYZEval& operator+=(const XYZval &rs) { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k); return *this; } + FI XYZEval& operator-=(const XYZval &rs) { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k); return *this; } + FI XYZEval& operator*=(const XYZval &rs) { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k); return *this; } + FI XYZEval& operator/=(const XYZval &rs) { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k); 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); 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); 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); 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); return *this; } + FI XYZEval& operator*=(const T &v) { LOGICAL_AXIS_CODE(e *= v, x *= v, y *= v, z *= v, i *= v, j *= v, k *= v); return *this; } + FI XYZEval& operator>>=(const int &v) { LOGICAL_AXIS_CODE(_RS(e), _RS(x), _RS(y), _RS(z), _RS(i), _RS(j), _RS(k)); return *this; } + FI XYZEval& operator<<=(const int &v) { LOGICAL_AXIS_CODE(_LS(e), _LS(x), _LS(y), _LS(z), _LS(i), _LS(j), _LS(k)); return *this; } + + // Exact comparisons. For floats a "NEAR" operation may be better. + FI bool operator==(const XYZval &rs) { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k); } + FI bool operator==(const XYZval &rs) const { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k); } + FI bool operator!=(const XYZval &rs) { return !operator==(rs); } + FI bool operator!=(const XYZval &rs) const { return !operator==(rs); } }; #undef _RECIP @@ -499,6 +666,3 @@ struct XYZEval { #undef _LS #undef _RS #undef FI - -const xyze_char_t axis_codes { 'X', 'Y', 'Z', 'E' }; -#define XYZ_CHAR(A) ((char)('X' + A)) diff --git a/Marlin/src/core/utility.cpp b/Marlin/src/core/utility.cpp index f99956816778..b810855d5226 100644 --- a/Marlin/src/core/utility.cpp +++ b/Marlin/src/core/utility.cpp @@ -92,9 +92,9 @@ void safe_delay(millis_t ms) { SERIAL_ECHOPGM(" (Aligned With"); if (probe.offset_xy.y > 0) - serialprintPGM(ENABLED(IS_SCARA) ? PSTR("-Distal") : PSTR("-Back")); + SERIAL_ECHOPGM_P(ENABLED(IS_SCARA) ? PSTR("-Distal") : PSTR("-Back")); else if (probe.offset_xy.y < 0) - serialprintPGM(ENABLED(IS_SCARA) ? PSTR("-Proximal") : PSTR("-Front")); + SERIAL_ECHOPGM_P(ENABLED(IS_SCARA) ? PSTR("-Proximal") : PSTR("-Front")); else if (probe.offset_xy.x != 0) SERIAL_ECHOPGM("-Center"); @@ -102,7 +102,7 @@ void safe_delay(millis_t ms) { #endif - serialprintPGM(probe.offset.z < 0 ? PSTR("Below") : probe.offset.z > 0 ? PSTR("Above") : PSTR("Same Z as")); + SERIAL_ECHOPGM_P(probe.offset.z < 0 ? PSTR("Below") : probe.offset.z > 0 ? PSTR("Above") : PSTR("Same Z as")); SERIAL_ECHOLNPGM(" Nozzle)"); #endif @@ -122,10 +122,10 @@ void safe_delay(millis_t ms) { SERIAL_ECHOLNPAIR("Z Fade: ", planner.z_fade_height); #endif #if ABL_PLANAR - SERIAL_ECHOPGM("ABL Adjustment X"); - LOOP_XYZ(a) { + SERIAL_ECHOPGM("ABL Adjustment"); + LOOP_LINEAR_AXES(a) { const float v = planner.get_axis_position_mm(AxisEnum(a)) - current_position[a]; - SERIAL_CHAR(' ', XYZ_CHAR(a)); + SERIAL_CHAR(' ', AXIS_CHAR(a)); if (v > 0) SERIAL_CHAR('+'); SERIAL_DECIMAL(v); } diff --git a/Marlin/src/core/utility.h b/Marlin/src/core/utility.h index 645a4be80735..d248091ce575 100644 --- a/Marlin/src/core/utility.h +++ b/Marlin/src/core/utility.h @@ -25,8 +25,7 @@ #include "../core/types.h" #include "../core/millis_t.h" -// Delay that ensures heaters and watchdog are kept alive -void safe_delay(millis_t ms); +void safe_delay(millis_t ms); // Delay ensuring that temperatures are updated and the watchdog is kept alive. #if ENABLED(SERIAL_OVERRUN_PROTECTION) void serial_delay(const millis_t ms); @@ -34,7 +33,7 @@ void safe_delay(millis_t ms); inline void serial_delay(const millis_t) {} #endif -#if GRID_MAX_POINTS_X && GRID_MAX_POINTS_Y +#if (GRID_MAX_POINTS_X) && (GRID_MAX_POINTS_Y) // 16x16 bit arrays template @@ -77,3 +76,11 @@ class restorer { // Converts from an uint8_t in the range of 0-255 to an uint8_t // in the range 0-100 while avoiding rounding artifacts constexpr uint8_t ui8_to_percent(const uint8_t i) { return (int(i) * 100 + 127) / 255; } + +const xyze_char_t axis_codes LOGICAL_AXIS_ARRAY('E', 'X', 'Y', 'Z', AXIS4_NAME, AXIS5_NAME, AXIS6_NAME); + +#if LINEAR_AXES <= XYZ + #define AXIS_CHAR(A) ((char)('X' + A)) +#else + #define AXIS_CHAR(A) axis_codes[A] +#endif diff --git a/Marlin/src/feature/ammeter.cpp b/Marlin/src/feature/ammeter.cpp new file mode 100644 index 000000000000..71b84f1121a0 --- /dev/null +++ b/Marlin/src/feature/ammeter.cpp @@ -0,0 +1,54 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../inc/MarlinConfig.h" + +#if ENABLED(I2C_AMMETER) + +#include "ammeter.h" + +#ifndef I2C_AMMETER_IMAX + #define I2C_AMMETER_IMAX 0.500 // Calibration range 500 Milliamps +#endif + +INA226 ina; + +Ammeter ammeter; + +float Ammeter::scale; +float Ammeter::current; + +void Ammeter::init() { + ina.begin(); + ina.configure(INA226_AVERAGES_16, INA226_BUS_CONV_TIME_1100US, INA226_SHUNT_CONV_TIME_1100US, INA226_MODE_SHUNT_BUS_CONT); + ina.calibrate(I2C_AMMETER_SHUNT_RESISTOR, I2C_AMMETER_IMAX); +} + +float Ammeter::read() { + scale = 1; + current = ina.readShuntCurrent(); + if (current <= 0.0001f) current = 0; // Clean up least-significant-bit amplification errors + if (current < 0.1f) scale = 1000; + return current * scale; +} + +#endif // I2C_AMMETER diff --git a/Marlin/src/feature/ammeter.h b/Marlin/src/feature/ammeter.h new file mode 100644 index 000000000000..86f09bb9a197 --- /dev/null +++ b/Marlin/src/feature/ammeter.h @@ -0,0 +1,39 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include "../inc/MarlinConfigPre.h" + +#include +#include + +class Ammeter { +private: + static float scale; + +public: + static float current; + static void init(); + static float read(); +}; + +extern Ammeter ammeter; diff --git a/Marlin/src/feature/babystep.cpp b/Marlin/src/feature/babystep.cpp index b07688146110..54ad9588f445 100644 --- a/Marlin/src/feature/babystep.cpp +++ b/Marlin/src/feature/babystep.cpp @@ -50,7 +50,7 @@ void Babystep::step_axis(const AxisEnum axis) { } } -void Babystep::add_mm(const AxisEnum axis, const float &mm) { +void Babystep::add_mm(const AxisEnum axis, const_float_t mm) { add_steps(axis, mm * planner.settings.axis_steps_per_mm[axis]); } diff --git a/Marlin/src/feature/babystep.h b/Marlin/src/feature/babystep.h index f85e5909cad4..f8037678ca16 100644 --- a/Marlin/src/feature/babystep.h +++ b/Marlin/src/feature/babystep.h @@ -61,7 +61,7 @@ class Babystep { #endif static void add_steps(const AxisEnum axis, const int16_t distance); - static void add_mm(const AxisEnum axis, const float &mm); + static void add_mm(const AxisEnum axis, const_float_t mm); static inline bool has_steps() { return steps[BS_AXIS_IND(X_AXIS)] || steps[BS_AXIS_IND(Y_AXIS)] || steps[BS_AXIS_IND(Z_AXIS)]; diff --git a/Marlin/src/feature/backlash.cpp b/Marlin/src/feature/backlash.cpp index 867e9cdd217c..5ab95d157775 100644 --- a/Marlin/src/feature/backlash.cpp +++ b/Marlin/src/feature/backlash.cpp @@ -63,10 +63,24 @@ Backlash backlash; void Backlash::add_correction_steps(const int32_t &da, const int32_t &db, const int32_t &dc, const uint8_t dm, block_t * const block) { static uint8_t last_direction_bits; uint8_t changed_dir = last_direction_bits ^ dm; - // Ignore direction change if no steps are taken in that direction - if (da == 0) CBI(changed_dir, X_AXIS); - if (db == 0) CBI(changed_dir, Y_AXIS); - if (dc == 0) CBI(changed_dir, Z_AXIS); + // Ignore direction change unless steps are taken in that direction + #if DISABLED(CORE_BACKLASH) || ENABLED(MARKFORGED_XY) + if (!da) CBI(changed_dir, X_AXIS); + if (!db) CBI(changed_dir, Y_AXIS); + if (!dc) CBI(changed_dir, Z_AXIS); + #elif CORE_IS_XY + if (!(da + db)) CBI(changed_dir, X_AXIS); + if (!(da - db)) CBI(changed_dir, Y_AXIS); + if (!dc) CBI(changed_dir, Z_AXIS); + #elif CORE_IS_XZ + if (!(da + dc)) CBI(changed_dir, X_AXIS); + if (!(da - dc)) CBI(changed_dir, Z_AXIS); + if (!db) CBI(changed_dir, Y_AXIS); + #elif CORE_IS_YZ + if (!(db + dc)) CBI(changed_dir, Y_AXIS); + if (!(db - dc)) CBI(changed_dir, Z_AXIS); + if (!da) CBI(changed_dir, X_AXIS); + #endif last_direction_bits ^= changed_dir; if (correction == 0) return; @@ -90,7 +104,7 @@ void Backlash::add_correction_steps(const int32_t &da, const int32_t &db, const const float f_corr = float(correction) / 255.0f; - LOOP_XYZ(axis) { + LOOP_LINEAR_AXES(axis) { if (distance_mm[axis]) { const bool reversing = TEST(dm,axis); @@ -105,42 +119,57 @@ void Backlash::add_correction_steps(const int32_t &da, const int32_t &db, const // Take up a portion of the residual_error in this segment, but only when // the current segment travels in the same direction as the correction if (reversing == (error_correction < 0)) { - if (segment_proportion == 0) - segment_proportion = _MIN(1.0f, block->millimeters / smoothing_mm); + if (segment_proportion == 0) segment_proportion = _MIN(1.0f, block->millimeters / smoothing_mm); error_correction = CEIL(segment_proportion * error_correction); } else error_correction = 0; // Don't take up any backlash in this segment, as it would subtract steps } #endif - // Making a correction reduces the residual error and adds block steps + + // This correction reduces the residual error and adds block steps if (error_correction) { block->steps[axis] += ABS(error_correction); - residual_error[axis] -= error_correction; + #if ENABLED(CORE_BACKLASH) + switch (axis) { + case CORE_AXIS_1: + //block->steps[CORE_AXIS_2] += influence_distance_mm[axis] * planner.settings.axis_steps_per_mm[CORE_AXIS_2]; + //SERIAL_ECHOLNPAIR("CORE_AXIS_1 dir change. distance=", distance_mm[axis], " r.err=", residual_error[axis], + // " da=", da, " db=", db, " block->steps[axis]=", block->steps[axis], " err_corr=", error_correction); + break; + case CORE_AXIS_2: + //block->steps[CORE_AXIS_1] += influence_distance_mm[axis] * planner.settings.axis_steps_per_mm[CORE_AXIS_1];; + //SERIAL_ECHOLNPAIR("CORE_AXIS_2 dir change. distance=", distance_mm[axis], " r.err=", residual_error[axis], + // " da=", da, " db=", db, " block->steps[axis]=", block->steps[axis], " err_corr=", error_correction); + break; + case NORMAL_AXIS: break; + } + residual_error[axis] = 0; // No residual_error needed for next CORE block, I think... + #else + residual_error[axis] -= error_correction; + #endif } } } } #if ENABLED(MEASURE_BACKLASH_WHEN_PROBING) - #if HAS_CUSTOM_PROBE_PIN - #define TEST_PROBE_PIN (READ(Z_MIN_PROBE_PIN) != Z_MIN_PROBE_ENDSTOP_INVERTING) - #else - #define TEST_PROBE_PIN (READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING) - #endif + + #include "../module/probe.h" // Measure Z backlash by raising nozzle in increments until probe deactivates void Backlash::measure_with_probe() { if (measured_count.z == 255) return; const float start_height = current_position.z; - while (current_position.z < (start_height + BACKLASH_MEASUREMENT_LIMIT) && TEST_PROBE_PIN) + while (current_position.z < (start_height + BACKLASH_MEASUREMENT_LIMIT) && PROBE_TRIGGERED()) do_blocking_move_to_z(current_position.z + BACKLASH_MEASUREMENT_RESOLUTION, MMM_TO_MMS(BACKLASH_MEASUREMENT_FEEDRATE)); // The backlash from all probe points is averaged, so count the number of measurements measured_mm.z += current_position.z - start_height; measured_count.z++; } + #endif #endif // BACKLASH_COMPENSATION diff --git a/Marlin/src/feature/backlash.h b/Marlin/src/feature/backlash.h index 8d00570f991e..500168b3804e 100644 --- a/Marlin/src/feature/backlash.h +++ b/Marlin/src/feature/backlash.h @@ -35,7 +35,7 @@ class Backlash { static float smoothing_mm; #endif - static inline void set_correction(const float &v) { correction = _MAX(0, _MIN(1.0, v)) * all_on; } + static inline void set_correction(const_float_t v) { correction = _MAX(0, _MIN(1.0, v)) * all_on; } static inline float get_correction() { return float(ui8_to_percent(correction)) / 100.0f; } #else static constexpr uint8_t correction = (BACKLASH_CORRECTION) * 0xFF; @@ -54,17 +54,17 @@ class Backlash { #endif static inline float get_measurement(const AxisEnum a) { + UNUSED(a); // Return the measurement averaged over all readings return TERN(MEASURE_BACKLASH_WHEN_PROBING , measured_count[a] > 0 ? measured_mm[a] / measured_count[a] : 0 , 0 ); - TERN(MEASURE_BACKLASH_WHEN_PROBING,,UNUSED(a)); } static inline bool has_measurement(const AxisEnum a) { + UNUSED(a); return TERN0(MEASURE_BACKLASH_WHEN_PROBING, measured_count[a] > 0); - TERN(MEASURE_BACKLASH_WHEN_PROBING,,UNUSED(a)); } static inline bool has_any_measurement() { diff --git a/Marlin/src/feature/bedlevel/abl/abl.cpp b/Marlin/src/feature/bedlevel/abl/abl.cpp index 39d8815fad98..739065656323 100644 --- a/Marlin/src/feature/bedlevel/abl/abl.cpp +++ b/Marlin/src/feature/bedlevel/abl/abl.cpp @@ -47,11 +47,11 @@ static void extrapolate_one_point(const uint8_t x, const uint8_t y, const int8_t if (DEBUGGING(LEVELING)) { DEBUG_ECHOPGM("Extrapolate ["); if (x < 10) DEBUG_CHAR(' '); - DEBUG_ECHO((int)x); + DEBUG_ECHO(x); DEBUG_CHAR(xdir ? (xdir > 0 ? '+' : '-') : ' '); DEBUG_CHAR(' '); if (y < 10) DEBUG_CHAR(' '); - DEBUG_ECHO((int)y); + DEBUG_ECHO(y); DEBUG_CHAR(ydir ? (ydir > 0 ? '+' : '-') : ' '); DEBUG_ECHOLNPGM("]"); } @@ -85,9 +85,9 @@ static void extrapolate_one_point(const uint8_t x, const uint8_t y, const int8_t //#define EXTRAPOLATE_FROM_EDGE #if ENABLED(EXTRAPOLATE_FROM_EDGE) - #if GRID_MAX_POINTS_X < GRID_MAX_POINTS_Y + #if (GRID_MAX_POINTS_X) < (GRID_MAX_POINTS_Y) #define HALF_IN_X - #elif GRID_MAX_POINTS_Y < GRID_MAX_POINTS_X + #elif (GRID_MAX_POINTS_Y) < (GRID_MAX_POINTS_X) #define HALF_IN_Y #endif #endif @@ -98,23 +98,23 @@ static void extrapolate_one_point(const uint8_t x, const uint8_t y, const int8_t */ void extrapolate_unprobed_bed_level() { #ifdef HALF_IN_X - constexpr uint8_t ctrx2 = 0, xlen = GRID_MAX_POINTS_X - 1; + constexpr uint8_t ctrx2 = 0, xend = GRID_MAX_POINTS_X - 1; #else - constexpr uint8_t ctrx1 = (GRID_MAX_POINTS_X - 1) / 2, // left-of-center - ctrx2 = (GRID_MAX_POINTS_X) / 2, // right-of-center - xlen = ctrx1; + constexpr uint8_t ctrx1 = (GRID_MAX_CELLS_X) / 2, // left-of-center + ctrx2 = (GRID_MAX_POINTS_X) / 2, // right-of-center + xend = ctrx1; #endif #ifdef HALF_IN_Y - constexpr uint8_t ctry2 = 0, ylen = GRID_MAX_POINTS_Y - 1; + constexpr uint8_t ctry2 = 0, yend = GRID_MAX_POINTS_Y - 1; #else - constexpr uint8_t ctry1 = (GRID_MAX_POINTS_Y - 1) / 2, // top-of-center - ctry2 = (GRID_MAX_POINTS_Y) / 2, // bottom-of-center - ylen = ctry1; + constexpr uint8_t ctry1 = (GRID_MAX_CELLS_Y) / 2, // top-of-center + ctry2 = (GRID_MAX_POINTS_Y) / 2, // bottom-of-center + yend = ctry1; #endif - LOOP_LE_N(xo, xlen) - LOOP_LE_N(yo, ylen) { + LOOP_LE_N(xo, xend) + LOOP_LE_N(yo, yend) { uint8_t x2 = ctrx2 + xo, y2 = ctry2 + yo; #ifndef HALF_IN_X const uint8_t x1 = ctrx1 - xo; @@ -143,8 +143,8 @@ void print_bilinear_leveling_grid() { #if ENABLED(ABL_BILINEAR_SUBDIVISION) - #define ABL_GRID_POINTS_VIRT_X (GRID_MAX_POINTS_X - 1) * (BILINEAR_SUBDIVISIONS) + 1 - #define ABL_GRID_POINTS_VIRT_Y (GRID_MAX_POINTS_Y - 1) * (BILINEAR_SUBDIVISIONS) + 1 + #define ABL_GRID_POINTS_VIRT_X GRID_MAX_CELLS_X * (BILINEAR_SUBDIVISIONS) + 1 + #define ABL_GRID_POINTS_VIRT_Y GRID_MAX_CELLS_Y * (BILINEAR_SUBDIVISIONS) + 1 #define ABL_TEMP_POINTS_X (GRID_MAX_POINTS_X + 2) #define ABL_TEMP_POINTS_Y (GRID_MAX_POINTS_Y + 2) float z_values_virt[ABL_GRID_POINTS_VIRT_X][ABL_GRID_POINTS_VIRT_Y]; @@ -161,10 +161,18 @@ void print_bilinear_leveling_grid() { #define LINEAR_EXTRAPOLATION(E, I) ((E) * 2 - (I)) float bed_level_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 + // making this function more complex by extrapolating two points. + return 0.0; + } if (!x || x == ABL_TEMP_POINTS_X - 1) { if (x) { - ep = GRID_MAX_POINTS_X - 1; - ip = GRID_MAX_POINTS_X - 2; + ep = (GRID_MAX_POINTS_X) - 1; + ip = GRID_MAX_CELLS_X - 1; } if (WITHIN(y, 1, ABL_TEMP_POINTS_Y - 2)) return LINEAR_EXTRAPOLATION( @@ -179,8 +187,8 @@ void print_bilinear_leveling_grid() { } if (!y || y == ABL_TEMP_POINTS_Y - 1) { if (y) { - ep = GRID_MAX_POINTS_Y - 1; - ip = GRID_MAX_POINTS_Y - 2; + ep = (GRID_MAX_POINTS_Y) - 1; + ip = GRID_MAX_CELLS_Y - 1; } if (WITHIN(x, 1, ABL_TEMP_POINTS_X - 2)) return LINEAR_EXTRAPOLATION( @@ -205,7 +213,7 @@ void print_bilinear_leveling_grid() { ) * 0.5f; } - static float bed_level_virt_2cmr(const uint8_t x, const uint8_t y, const float &tx, const float &ty) { + static float bed_level_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) { @@ -348,7 +356,7 @@ float bilinear_z_offset(const xy_pos_t &raw) { * Prepare a bilinear-leveled linear move on Cartesian, * splitting the move where it crosses grid borders. */ - void bilinear_line_to_destination(const feedRate_t &scaled_fr_mm_s, uint16_t x_splits, uint16_t y_splits) { + void bilinear_line_to_destination(const_feedRate_t scaled_fr_mm_s, uint16_t x_splits, uint16_t y_splits) { // Get current and destination cells for this line xy_int_t c1 { CELL_INDEX(x, current_position.x), CELL_INDEX(y, current_position.y) }, c2 { CELL_INDEX(x, destination.x), CELL_INDEX(y, destination.y) }; diff --git a/Marlin/src/feature/bedlevel/abl/abl.h b/Marlin/src/feature/bedlevel/abl/abl.h index bbe2411dc346..3d54c55695e8 100644 --- a/Marlin/src/feature/bedlevel/abl/abl.h +++ b/Marlin/src/feature/bedlevel/abl/abl.h @@ -37,7 +37,7 @@ void refresh_bed_level(); #endif #if IS_CARTESIAN && DISABLED(SEGMENT_LEVELED_MOVES) - void bilinear_line_to_destination(const feedRate_t &scaled_fr_mm_s, uint16_t x_splits=0xFFFF, uint16_t y_splits=0xFFFF); + void bilinear_line_to_destination(const_feedRate_t scaled_fr_mm_s, uint16_t x_splits=0xFFFF, uint16_t y_splits=0xFFFF); #endif #define _GET_MESH_X(I) float(bilinear_start.x + (I) * bilinear_grid_spacing.x) diff --git a/Marlin/src/feature/bedlevel/bedlevel.cpp b/Marlin/src/feature/bedlevel/bedlevel.cpp index 3e9225b7f932..8e03632de44d 100644 --- a/Marlin/src/feature/bedlevel/bedlevel.cpp +++ b/Marlin/src/feature/bedlevel/bedlevel.cpp @@ -36,7 +36,7 @@ #endif #if ENABLED(LCD_BED_LEVELING) - #include "../../lcd/ultralcd.h" + #include "../../lcd/marlinui.h" #endif #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) @@ -98,7 +98,7 @@ TemporaryBedLevelingState::TemporaryBedLevelingState(const bool enable) : saved( #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - void set_z_fade_height(const float zfh, const bool do_report/*=true*/) { + void set_z_fade_height(const_float_t zfh, const bool do_report/*=true*/) { if (planner.z_fade_height == zfh) return; @@ -160,7 +160,7 @@ void reset_bed_level() { #ifndef SCAD_MESH_OUTPUT LOOP_L_N(x, sx) { serial_spaces(precision + (x < 10 ? 3 : 2)); - SERIAL_ECHO(int(x)); + SERIAL_ECHO(x); } SERIAL_EOL(); #endif @@ -172,7 +172,7 @@ void reset_bed_level() { SERIAL_ECHOPGM(" ["); // open sub-array #else if (y < 10) SERIAL_CHAR(' '); - SERIAL_ECHO(int(y)); + SERIAL_ECHO(y); #endif LOOP_L_N(x, sx) { SERIAL_CHAR(' '); @@ -196,7 +196,7 @@ void reset_bed_level() { #endif } #ifdef SCAD_MESH_OUTPUT - SERIAL_CHAR(' ', ']'); // close sub-array + SERIAL_ECHOPGM(" ]"); // close sub-array if (y < sy - 1) SERIAL_CHAR(','); #endif SERIAL_EOL(); @@ -213,27 +213,27 @@ void reset_bed_level() { void _manual_goto_xy(const xy_pos_t &pos) { + // Get the resting Z position for after the XY move #ifdef MANUAL_PROBE_START_Z - constexpr float startz = _MAX(0, MANUAL_PROBE_START_Z); - #if MANUAL_PROBE_HEIGHT > 0 - do_blocking_move_to_xy_z(pos, MANUAL_PROBE_HEIGHT); - do_blocking_move_to_z(startz); - #else - do_blocking_move_to_xy_z(pos, startz); - #endif - #elif MANUAL_PROBE_HEIGHT > 0 - const float prev_z = current_position.z; - do_blocking_move_to_xy_z(pos, MANUAL_PROBE_HEIGHT); - do_blocking_move_to_z(prev_z); + constexpr float finalz = _MAX(0, MANUAL_PROBE_START_Z); // If a MANUAL_PROBE_START_Z value is set, always respect it #else - do_blocking_move_to_xy(pos); + #warning "It's recommended to set some MANUAL_PROBE_START_Z value for manual leveling." + #endif + #if Z_CLEARANCE_BETWEEN_MANUAL_PROBES > 0 // A probe/obstacle clearance exists so there is a raise: + #ifndef MANUAL_PROBE_START_Z + const float finalz = current_position.z; // - Use the current Z for starting-Z if no MANUAL_PROBE_START_Z was provided + #endif + do_blocking_move_to_xy_z(pos, Z_CLEARANCE_BETWEEN_MANUAL_PROBES); // - Raise Z, then move to the new XY + do_blocking_move_to_z(finalz); // - Lower down to the starting Z height, ready for adjustment! + #elif defined(MANUAL_PROBE_START_Z) // A starting-Z was provided, but there's no raise: + do_blocking_move_to_xy_z(pos, finalz); // - Move in XY then down to the starting Z height, ready for adjustment! + #else // Zero raise and no starting Z height either: + do_blocking_move_to_xy(pos); // - Move over with no raise, ready for adjustment! #endif - - current_position = pos; TERN_(LCD_BED_LEVELING, ui.wait_for_move = false); } -#endif +#endif // MESH_BED_LEVELING || PROBE_MANUALLY #endif // HAS_LEVELING diff --git a/Marlin/src/feature/bedlevel/bedlevel.h b/Marlin/src/feature/bedlevel/bedlevel.h index 995e9d0dbcef..63f032eee87b 100644 --- a/Marlin/src/feature/bedlevel/bedlevel.h +++ b/Marlin/src/feature/bedlevel/bedlevel.h @@ -23,6 +23,10 @@ #include "../../inc/MarlinConfigPre.h" +#if EITHER(RESTORE_LEVELING_AFTER_G28, ENABLE_LEVELING_AFTER_G28) + #define CAN_SET_LEVELING_AFTER_G28 1 +#endif + #if ENABLED(PROBE_MANUALLY) extern bool g29_in_progress; #else @@ -34,7 +38,7 @@ void set_bed_leveling_enabled(const bool enable=true); void reset_bed_level(); #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - void set_z_fade_height(const float zfh, const bool do_report=true); + void set_z_fade_height(const_float_t zfh, const bool do_report=true); #endif #if EITHER(MESH_BED_LEVELING, PROBE_MANUALLY) diff --git a/Marlin/src/feature/bedlevel/hilbert_curve.cpp b/Marlin/src/feature/bedlevel/hilbert_curve.cpp new file mode 100644 index 000000000000..7474123e3fe1 --- /dev/null +++ b/Marlin/src/feature/bedlevel/hilbert_curve.cpp @@ -0,0 +1,110 @@ +/********************* + * hilbert_curve.cpp * + *********************/ + +/**************************************************************************** + * Written By Marcio Teixeira 2021 - SynDaver Labs, 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 "../../inc/MarlinConfig.h" + +#if ENABLED(UBL_HILBERT_CURVE) + +#include "bedlevel.h" +#include "hilbert_curve.h" + +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 ord = order(_MAX(GRID_MAX_POINTS_X, GRID_MAX_POINTS_Y)); +constexpr uint8_t dim = _BV(ord); + +static inline bool eval_candidate(int8_t x, int8_t y, hilbert_curve::callback_ptr func, void *data) { + // The print bed likely has fewer points than the full Hilbert + // curve, so cull unnecessary points + return x < (GRID_MAX_POINTS_X) && y < (GRID_MAX_POINTS_Y) ? func(x, y, data) : false; +} + +bool hilbert_curve::hilbert(int8_t x, int8_t y, int8_t xi, int8_t xj, int8_t yi, int8_t yj, uint8_t n, hilbert_curve::callback_ptr func, void *data) { + /** + * Hilbert space-filling curve implementation + * + * x and y : coordinates of the bottom left corner + * xi and xj : i and j components of the unit x vector of the frame + * yi and yj : i and j components of the unit y vector of the frame + * + * From: http://www.fundza.com/algorithmic/space_filling/hilbert/basics/index.html + */ + if (n) + return hilbert(x, y, yi/2, yj/2, xi/2, xj/2, n-1, func, data) || + hilbert(x+xi/2, y+xj/2, xi/2, xj/2, yi/2, yj/2, n-1, func, data) || + hilbert(x+xi/2+yi/2, y+xj/2+yj/2, xi/2, xj/2, yi/2, yj/2, n-1, func, data) || + hilbert(x+xi/2+yi, y+xj/2+yj, -yi/2, -yj/2, -xi/2, -xj/2, n-1, func, data); + else + return eval_candidate(to_int(x+(xi+yi)/2), to_int(y+(xj+yj)/2), func, data); +} + +/** + * Calls func(x, y, data) for all points in the Hilbert curve. + * If that function returns true, the search is terminated. + */ +bool hilbert_curve::search(hilbert_curve::callback_ptr func, void *data) { + return hilbert(to_fix(0), to_fix(0),to_fix(dim), to_fix(0), to_fix(0), to_fix(dim), ord, func, data); +} + +/* Helper function for starting the search at a particular point */ + +typedef struct { + uint8_t x, y; + bool found_1st; + hilbert_curve::callback_ptr func; + void *data; +} search_from_t; + +static bool search_from_helper(uint8_t x, uint8_t y, void *data) { + search_from_t *d = (search_from_t *) data; + if (d->x == x && d->y == y) + d->found_1st = true; + return d->found_1st ? d->func(x, y, d->data) : false; +} + +/** + * Same as search, except start at a specific grid intersection point. + */ +bool hilbert_curve::search_from(uint8_t x, uint8_t y, hilbert_curve::callback_ptr func, void *data) { + search_from_t d; + d.x = x; + d.y = y; + d.found_1st = false; + d.func = func; + d.data = data; + // Call twice to allow search to wrap back to the beginning and picked up points prior to the start. + return search(search_from_helper, &d) || search(search_from_helper, &d); +} + +/** + * Like search_from, but takes a bed position and starts from the nearest + * point on the Hilbert curve. + */ +bool hilbert_curve::search_from_closest(const xy_pos_t &pos, hilbert_curve::callback_ptr func, void *data) { + // Find closest grid intersection + const uint8_t grid_x = LROUND(constrain(float(pos.x - (MESH_MIN_X)) / (MESH_X_DIST), 0, (GRID_MAX_POINTS_X) - 1)); + const uint8_t grid_y = LROUND(constrain(float(pos.y - (MESH_MIN_Y)) / (MESH_Y_DIST), 0, (GRID_MAX_POINTS_Y) - 1)); + return search_from(grid_x, grid_y, func, data); +} + +#endif // UBL_HILBERT_CURVE diff --git a/Marlin/src/feature/bedlevel/hilbert_curve.h b/Marlin/src/feature/bedlevel/hilbert_curve.h new file mode 100644 index 000000000000..a5dce8a22d60 --- /dev/null +++ b/Marlin/src/feature/bedlevel/hilbert_curve.h @@ -0,0 +1,32 @@ +/******************* + * hilbert_curve.h * + *******************/ + +/**************************************************************************** + * Written By Marcio Teixeira 2021 - SynDaver Labs, 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 + +class hilbert_curve { + public: + typedef bool (*callback_ptr)(uint8_t x, uint8_t y, void *data); + static bool search(callback_ptr func, void *data); + static bool search_from(uint8_t x, uint8_t y, callback_ptr func, void *data); + static bool search_from_closest(const xy_pos_t &pos, callback_ptr func, void *data); + private: + static bool hilbert(int8_t x, int8_t y, int8_t xi, int8_t xj, int8_t yi, int8_t yj, uint8_t n, callback_ptr func, void *data); +}; diff --git a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp index 1200c2a1b3b8..51cf28f89005 100644 --- a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp +++ b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp @@ -61,18 +61,18 @@ * Prepare a mesh-leveled linear move in a Cartesian setup, * splitting the move where it crosses mesh borders. */ - void mesh_bed_leveling::line_to_destination(const feedRate_t &scaled_fr_mm_s, uint8_t x_splits, uint8_t y_splits) { + void mesh_bed_leveling::line_to_destination(const_feedRate_t scaled_fr_mm_s, uint8_t x_splits, uint8_t y_splits) { // Get current and destination cells for this line xy_int8_t scel = cell_indexes(current_position), ecel = cell_indexes(destination); - NOMORE(scel.x, GRID_MAX_POINTS_X - 2); - NOMORE(scel.y, GRID_MAX_POINTS_Y - 2); - NOMORE(ecel.x, GRID_MAX_POINTS_X - 2); - NOMORE(ecel.y, GRID_MAX_POINTS_Y - 2); + NOMORE(scel.x, GRID_MAX_CELLS_X - 1); + NOMORE(scel.y, GRID_MAX_CELLS_Y - 1); + NOMORE(ecel.x, GRID_MAX_CELLS_X - 1); + NOMORE(ecel.y, GRID_MAX_CELLS_Y - 1); // Start and end in the same cell? No split needed. if (scel == ecel) { - line_to_destination(scaled_fr_mm_s); current_position = destination; + line_to_current_position(scaled_fr_mm_s); return; } @@ -104,8 +104,8 @@ else { // Must already have been split on these border(s) // This should be a rare case. - line_to_destination(scaled_fr_mm_s); current_position = destination; + line_to_current_position(scaled_fr_mm_s); return; } diff --git a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h index ade7a931401a..cc5469577189 100644 --- a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h +++ b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h @@ -32,8 +32,8 @@ enum MeshLevelingState : char { MeshReset // G29 S5 }; -#define MESH_X_DIST (float(MESH_MAX_X - (MESH_MIN_X)) / float(GRID_MAX_POINTS_X - 1)) -#define MESH_Y_DIST (float(MESH_MAX_Y - (MESH_MIN_Y)) / float(GRID_MAX_POINTS_Y - 1)) +#define MESH_X_DIST (float(MESH_MAX_X - (MESH_MIN_X)) / (GRID_MAX_CELLS_X)) +#define MESH_Y_DIST (float(MESH_MAX_Y - (MESH_MIN_Y)) / (GRID_MAX_CELLS_Y)) #define _GET_MESH_X(I) mbl.index_to_xpos[I] #define _GET_MESH_Y(J) mbl.index_to_ypos[J] #define Z_VALUES_ARR mbl.z_values @@ -56,56 +56,54 @@ class mesh_bed_leveling { return false; } - static void set_z(const int8_t px, const int8_t py, const float &z) { z_values[px][py] = z; } + static void set_z(const int8_t px, const int8_t py, const_float_t z) { z_values[px][py] = z; } static inline void zigzag(const int8_t index, int8_t &px, int8_t &py) { px = index % (GRID_MAX_POINTS_X); py = index / (GRID_MAX_POINTS_X); - if (py & 1) px = (GRID_MAX_POINTS_X - 1) - px; // Zig zag + if (py & 1) px = (GRID_MAX_POINTS_X) - 1 - px; // Zig zag } - static void set_zigzag_z(const int8_t index, const float &z) { + static void set_zigzag_z(const int8_t index, const_float_t z) { int8_t px, py; zigzag(index, px, py); set_z(px, py, z); } - static int8_t cell_index_x(const float &x) { + static int8_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_POINTS_X) - 2); + return constrain(cx, 0, GRID_MAX_CELLS_X - 1); } - static int8_t cell_index_y(const float &y) { + static int8_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_POINTS_Y) - 2); + return constrain(cy, 0, GRID_MAX_CELLS_Y - 1); } - static inline xy_int8_t cell_indexes(const float &x, const float &y) { + static inline xy_int8_t cell_indexes(const_float_t x, const_float_t y) { return { cell_index_x(x), cell_index_y(y) }; } static inline xy_int8_t cell_indexes(const xy_pos_t &xy) { return cell_indexes(xy.x, xy.y); } - static int8_t probe_index_x(const float &x) { + 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); - return WITHIN(px, 0, GRID_MAX_POINTS_X - 1) ? px : -1; + return WITHIN(px, 0, (GRID_MAX_POINTS_X) - 1) ? px : -1; } - static int8_t probe_index_y(const float &y) { + static int8_t probe_index_y(const_float_t y) { int8_t py = (y - (MESH_MIN_Y) + 0.5f * (MESH_Y_DIST)) * RECIPROCAL(MESH_Y_DIST); - return WITHIN(py, 0, GRID_MAX_POINTS_Y - 1) ? py : -1; + return WITHIN(py, 0, (GRID_MAX_POINTS_Y) - 1) ? py : -1; } - static inline xy_int8_t probe_indexes(const float &x, const float &y) { + static inline xy_int8_t probe_indexes(const_float_t x, const_float_t y) { return { probe_index_x(x), probe_index_y(y) }; } static inline xy_int8_t probe_indexes(const xy_pos_t &xy) { return probe_indexes(xy.x, xy.y); } - static float calc_z0(const float &a0, const float &a1, const float &z1, const float &a2, const float &z2) { + static float calc_z0(const_float_t a0, const_float_t a1, const_float_t z1, const_float_t a2, const_float_t z2) { const float delta_z = (z2 - z1) / (a2 - a1), delta_a = a0 - a1; return z1 + delta_a * delta_z; } static float get_z(const xy_pos_t &pos - #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - , const float &factor=1.0f - #endif + OPTARG(ENABLE_LEVELING_FADE_HEIGHT, const_float_t factor=1.0f) ) { #if DISABLED(ENABLE_LEVELING_FADE_HEIGHT) constexpr float factor = 1.0f; @@ -114,13 +112,14 @@ class mesh_bed_leveling { const float x1 = index_to_xpos[ind.x], x2 = index_to_xpos[ind.x+1], y1 = index_to_xpos[ind.y], y2 = index_to_xpos[ind.y+1], z1 = calc_z0(pos.x, x1, z_values[ind.x][ind.y ], x2, z_values[ind.x+1][ind.y ]), - z2 = calc_z0(pos.x, x1, z_values[ind.x][ind.y+1], x2, z_values[ind.x+1][ind.y+1]); + z2 = calc_z0(pos.x, x1, z_values[ind.x][ind.y+1], x2, z_values[ind.x+1][ind.y+1]), + zf = calc_z0(pos.y, y1, z1, y2, z2); - return z_offset + calc_z0(pos.y, y1, z1, y2, z2) * factor; + return z_offset + zf * factor; } #if IS_CARTESIAN && DISABLED(SEGMENT_LEVELED_MOVES) - static void line_to_destination(const feedRate_t &scaled_fr_mm_s, uint8_t x_splits=0xFF, uint8_t y_splits=0xFF); + static void line_to_destination(const_feedRate_t scaled_fr_mm_s, uint8_t x_splits=0xFF, uint8_t y_splits=0xFF); #endif }; diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.cpp b/Marlin/src/feature/bedlevel/ubl/ubl.cpp index 087fdf42b2ac..37c8be5bd8f5 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl.cpp @@ -24,213 +24,279 @@ #if ENABLED(AUTO_BED_LEVELING_UBL) - #include "../bedlevel.h" +#include "../bedlevel.h" - unified_bed_leveling ubl; +unified_bed_leveling ubl; - #include "../../../MarlinCore.h" - #include "../../../gcode/gcode.h" +#include "../../../MarlinCore.h" +#include "../../../gcode/gcode.h" - #include "../../../module/settings.h" - #include "../../../module/planner.h" - #include "../../../module/motion.h" - #include "../../../module/probe.h" +#include "../../../module/settings.h" +#include "../../../module/planner.h" +#include "../../../module/motion.h" +#include "../../../module/probe.h" +#include "../../../module/temperature.h" - #if ENABLED(EXTENSIBLE_UI) - #include "../../../lcd/extui/ui_api.h" - #endif +#if ENABLED(EXTENSIBLE_UI) + #include "../../../lcd/extui/ui_api.h" +#endif + +#include "math.h" - #include "math.h" +void unified_bed_leveling::echo_name() { SERIAL_ECHOPGM("Unified Bed Leveling"); } - void unified_bed_leveling::echo_name() { - SERIAL_ECHOPGM("Unified Bed Leveling"); +void unified_bed_leveling::report_current_mesh() { + if (!leveling_is_valid()) return; + SERIAL_ECHO_MSG(" G29 I999"); + GRID_LOOP(x, y) + if (!isnan(z_values[x][y])) { + SERIAL_ECHO_START(); + SERIAL_ECHOPAIR(" M421 I", x, " J", y); + SERIAL_ECHOLNPAIR_F_P(SP_Z_STR, z_values[x][y], 4); + serial_delay(75); // Prevent Printrun from exploding + } +} + +void unified_bed_leveling::report_state() { + echo_name(); + SERIAL_ECHO_TERNARY(planner.leveling_active, " System v" UBL_VERSION " ", "", "in", "active\n"); + serial_delay(50); +} + +int8_t unified_bed_leveling::storage_slot; + +float unified_bed_leveling::z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y]; + +#define _GRIDPOS(A,N) (MESH_MIN_##A + N * (MESH_##A##_DIST)) + +const float +unified_bed_leveling::_mesh_index_to_xpos[GRID_MAX_POINTS_X] PROGMEM = ARRAY_N(GRID_MAX_POINTS_X, + _GRIDPOS(X, 0), _GRIDPOS(X, 1), _GRIDPOS(X, 2), _GRIDPOS(X, 3), + _GRIDPOS(X, 4), _GRIDPOS(X, 5), _GRIDPOS(X, 6), _GRIDPOS(X, 7), + _GRIDPOS(X, 8), _GRIDPOS(X, 9), _GRIDPOS(X, 10), _GRIDPOS(X, 11), + _GRIDPOS(X, 12), _GRIDPOS(X, 13), _GRIDPOS(X, 14), _GRIDPOS(X, 15) +), +unified_bed_leveling::_mesh_index_to_ypos[GRID_MAX_POINTS_Y] PROGMEM = ARRAY_N(GRID_MAX_POINTS_Y, + _GRIDPOS(Y, 0), _GRIDPOS(Y, 1), _GRIDPOS(Y, 2), _GRIDPOS(Y, 3), + _GRIDPOS(Y, 4), _GRIDPOS(Y, 5), _GRIDPOS(Y, 6), _GRIDPOS(Y, 7), + _GRIDPOS(Y, 8), _GRIDPOS(Y, 9), _GRIDPOS(Y, 10), _GRIDPOS(Y, 11), + _GRIDPOS(Y, 12), _GRIDPOS(Y, 13), _GRIDPOS(Y, 14), _GRIDPOS(Y, 15) +); + +volatile int16_t unified_bed_leveling::encoder_diff; + +unified_bed_leveling::unified_bed_leveling() { reset(); } + +void unified_bed_leveling::reset() { + const bool was_enabled = planner.leveling_active; + set_bed_leveling_enabled(false); + storage_slot = -1; + ZERO(z_values); + #if ENABLED(EXTENSIBLE_UI) + GRID_LOOP(x, y) ExtUI::onMeshUpdate(x, y, 0); + #endif + if (was_enabled) report_current_position(); +} + +void unified_bed_leveling::invalidate() { + set_bed_leveling_enabled(false); + set_all_mesh_points_to_value(NAN); +} + +void unified_bed_leveling::set_all_mesh_points_to_value(const_float_t value) { + GRID_LOOP(x, y) { + z_values[x][y] = value; + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, value)); + } +} + +#if ENABLED(OPTIMIZED_MESH_STORAGE) + + constexpr float mesh_store_scaling = 1000; + constexpr int16_t Z_STEPS_NAN = INT16_MAX; + + void unified_bed_leveling::set_store_from_mesh(const bed_mesh_t &in_values, mesh_store_t &stored_values) { + auto z_to_store = [](const_float_t z) { + if (isnan(z)) return Z_STEPS_NAN; + const int32_t z_scaled = TRUNC(z * mesh_store_scaling); + if (z_scaled == Z_STEPS_NAN || !WITHIN(z_scaled, INT16_MIN, INT16_MAX)) + return Z_STEPS_NAN; // If Z is out of range, return our custom 'NaN' + return int16_t(z_scaled); + }; + GRID_LOOP(x, y) stored_values[x][y] = z_to_store(in_values[x][y]); } - void unified_bed_leveling::report_current_mesh() { - if (!leveling_is_valid()) return; - SERIAL_ECHO_MSG(" G29 I999"); - GRID_LOOP(x, y) - if (!isnan(z_values[x][y])) { - SERIAL_ECHO_START(); - SERIAL_ECHOPAIR(" M421 I", int(x), " J", int(y)); - SERIAL_ECHOLNPAIR_F_P(SP_Z_STR, z_values[x][y], 4); - serial_delay(75); // Prevent Printrun from exploding - } + void unified_bed_leveling::set_mesh_from_store(const mesh_store_t &stored_values, bed_mesh_t &out_values) { + auto store_to_z = [](const int16_t z_scaled) { + return z_scaled == Z_STEPS_NAN ? NAN : z_scaled / mesh_store_scaling; + }; + GRID_LOOP(x, y) out_values[x][y] = store_to_z(stored_values[x][y]); } - void unified_bed_leveling::report_state() { - echo_name(); - SERIAL_ECHO_TERNARY(planner.leveling_active, " System v" UBL_VERSION " ", "", "in", "active\n"); - serial_delay(50); +#endif // OPTIMIZED_MESH_STORAGE + +static void serial_echo_xy(const uint8_t sp, const int16_t x, const int16_t y) { + SERIAL_ECHO_SP(sp); + SERIAL_CHAR('('); + if (x < 100) { SERIAL_CHAR(' '); if (x < 10) SERIAL_CHAR(' '); } + SERIAL_ECHO(x); + SERIAL_CHAR(','); + if (y < 100) { SERIAL_CHAR(' '); if (y < 10) SERIAL_CHAR(' '); } + SERIAL_ECHO(y); + SERIAL_CHAR(')'); + serial_delay(5); +} + +static void serial_echo_column_labels(const uint8_t sp) { + SERIAL_ECHO_SP(7); + LOOP_L_N(i, GRID_MAX_POINTS_X) { + if (i < 10) SERIAL_CHAR(' '); + SERIAL_ECHO(i); + SERIAL_ECHO_SP(sp); } + serial_delay(10); +} - int8_t unified_bed_leveling::storage_slot; +/** + * Produce one of these mesh maps: + * 0: Human-readable + * 1: CSV format for spreadsheet import + * 2: TODO: Display on Graphical LCD + * 4: Compact Human-Readable + */ +void unified_bed_leveling::display_map(const uint8_t map_type) { + const bool was = gcode.set_autoreport_paused(true); - float unified_bed_leveling::z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y]; + constexpr uint8_t eachsp = 1 + 6 + 1, // [-3.567] + twixt = eachsp * (GRID_MAX_POINTS_X) - 9 * 2; // Leading 4sp, Coordinates 9sp each - #define _GRIDPOS(A,N) (MESH_MIN_##A + N * (MESH_##A##_DIST)) + const bool human = !(map_type & 0x3), csv = map_type == 1, lcd = map_type == 2, comp = map_type & 0x4; - const float - unified_bed_leveling::_mesh_index_to_xpos[GRID_MAX_POINTS_X] PROGMEM = ARRAY_N(GRID_MAX_POINTS_X, - _GRIDPOS(X, 0), _GRIDPOS(X, 1), _GRIDPOS(X, 2), _GRIDPOS(X, 3), - _GRIDPOS(X, 4), _GRIDPOS(X, 5), _GRIDPOS(X, 6), _GRIDPOS(X, 7), - _GRIDPOS(X, 8), _GRIDPOS(X, 9), _GRIDPOS(X, 10), _GRIDPOS(X, 11), - _GRIDPOS(X, 12), _GRIDPOS(X, 13), _GRIDPOS(X, 14), _GRIDPOS(X, 15) - ), - unified_bed_leveling::_mesh_index_to_ypos[GRID_MAX_POINTS_Y] PROGMEM = ARRAY_N(GRID_MAX_POINTS_Y, - _GRIDPOS(Y, 0), _GRIDPOS(Y, 1), _GRIDPOS(Y, 2), _GRIDPOS(Y, 3), - _GRIDPOS(Y, 4), _GRIDPOS(Y, 5), _GRIDPOS(Y, 6), _GRIDPOS(Y, 7), - _GRIDPOS(Y, 8), _GRIDPOS(Y, 9), _GRIDPOS(Y, 10), _GRIDPOS(Y, 11), - _GRIDPOS(Y, 12), _GRIDPOS(Y, 13), _GRIDPOS(Y, 14), _GRIDPOS(Y, 15) - ); + SERIAL_ECHOPGM("\nBed Topography Report"); + if (human) { + SERIAL_ECHOLNPGM(":\n"); + serial_echo_xy(4, MESH_MIN_X, MESH_MAX_Y); + serial_echo_xy(twixt, MESH_MAX_X, MESH_MAX_Y); + SERIAL_EOL(); + serial_echo_column_labels(eachsp - 2); + } + else { + SERIAL_ECHOPGM(" for "); + SERIAL_ECHOPGM_P(csv ? PSTR("CSV:\n") : PSTR("LCD:\n")); + } - volatile int16_t unified_bed_leveling::encoder_diff; + // Add XY probe offset from extruder because probe.probe_at_point() subtracts them when + // moving to the XY position to be measured. This ensures better agreement between + // the current Z position after G28 and the mesh values. + const xy_int8_t curr = closest_indexes(xy_pos_t(current_position) + probe.offset_xy); - unified_bed_leveling::unified_bed_leveling() { - reset(); - } + if (!lcd) SERIAL_EOL(); + for (int8_t j = (GRID_MAX_POINTS_Y) - 1; j >= 0; j--) { - void unified_bed_leveling::reset() { - const bool was_enabled = planner.leveling_active; - set_bed_leveling_enabled(false); - storage_slot = -1; - ZERO(z_values); - #if ENABLED(EXTENSIBLE_UI) - GRID_LOOP(x, y) ExtUI::onMeshUpdate(x, y, 0); - #endif - if (was_enabled) report_current_position(); - } + // Row Label (J index) + if (human) { + if (j < 10) SERIAL_CHAR(' '); + SERIAL_ECHO(j); + SERIAL_ECHOPGM(" |"); + } - void unified_bed_leveling::invalidate() { - set_bed_leveling_enabled(false); - set_all_mesh_points_to_value(NAN); - } + // Row Values (I indexes) + LOOP_L_N(i, GRID_MAX_POINTS_X) { + + // Opening Brace or Space + const bool is_current = i == curr.x && j == curr.y; + if (human) SERIAL_CHAR(is_current ? '[' : ' '); + + // Z Value at current I, J + const float f = z_values[i][j]; + if (lcd) { + // TODO: Display on Graphical LCD + } + else if (isnan(f)) + SERIAL_ECHOPGM_P(human ? PSTR(" . ") : PSTR("NAN")); + else if (human || csv) { + if (human && f >= 0.0) SERIAL_CHAR(f > 0 ? '+' : ' '); // Display sign also for positive numbers (' ' for 0) + SERIAL_ECHO_F(f, 3); // Positive: 5 digits, Negative: 6 digits + } + if (csv && i < (GRID_MAX_POINTS_X) - 1) SERIAL_CHAR('\t'); - void unified_bed_leveling::set_all_mesh_points_to_value(const float value) { - GRID_LOOP(x, y) { - z_values[x][y] = value; - TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, value)); + // Closing Brace or Space + if (human) SERIAL_CHAR(is_current ? ']' : ' '); + + SERIAL_FLUSHTX(); + idle_no_sleep(); } - } + if (!lcd) SERIAL_EOL(); - static void serial_echo_xy(const uint8_t sp, const int16_t x, const int16_t y) { - SERIAL_ECHO_SP(sp); - SERIAL_CHAR('('); - if (x < 100) { SERIAL_CHAR(' '); if (x < 10) SERIAL_CHAR(' '); } - SERIAL_ECHO(x); - SERIAL_CHAR(','); - if (y < 100) { SERIAL_CHAR(' '); if (y < 10) SERIAL_CHAR(' '); } - SERIAL_ECHO(y); - SERIAL_CHAR(')'); - serial_delay(5); + // A blank line between rows (unless compact) + if (j && human && !comp) SERIAL_ECHOLNPGM(" |"); } - static void serial_echo_column_labels(const uint8_t sp) { - SERIAL_ECHO_SP(7); - for (int8_t i = 0; i < GRID_MAX_POINTS_X; i++) { - if (i < 10) SERIAL_CHAR(' '); - SERIAL_ECHO(i); - SERIAL_ECHO_SP(sp); - } - serial_delay(10); + if (human) { + serial_echo_column_labels(eachsp - 2); + SERIAL_EOL(); + serial_echo_xy(4, MESH_MIN_X, MESH_MIN_Y); + serial_echo_xy(twixt, MESH_MAX_X, MESH_MIN_Y); + SERIAL_EOL(); + SERIAL_EOL(); } - /** - * Produce one of these mesh maps: - * 0: Human-readable - * 1: CSV format for spreadsheet import - * 2: TODO: Display on Graphical LCD - * 4: Compact Human-Readable - */ - void unified_bed_leveling::display_map(const int map_type) { - const bool was = gcode.set_autoreport_paused(true); + gcode.set_autoreport_paused(was); +} - constexpr uint8_t eachsp = 1 + 6 + 1, // [-3.567] - twixt = eachsp * (GRID_MAX_POINTS_X) - 9 * 2; // Leading 4sp, Coordinates 9sp each +bool unified_bed_leveling::sanity_check() { + uint8_t error_flag = 0; - const bool human = !(map_type & 0x3), csv = map_type == 1, lcd = map_type == 2, comp = map_type & 0x4; + if (settings.calc_num_meshes() < 1) { + SERIAL_ECHOLNPGM("?Mesh too big for EEPROM."); + error_flag++; + } - SERIAL_ECHOPGM("\nBed Topography Report"); - if (human) { - SERIAL_ECHOLNPGM(":\n"); - serial_echo_xy(4, MESH_MIN_X, MESH_MAX_Y); - serial_echo_xy(twixt, MESH_MAX_X, MESH_MAX_Y); - SERIAL_EOL(); - serial_echo_column_labels(eachsp - 2); - } - else { - SERIAL_ECHOPGM(" for "); - serialprintPGM(csv ? PSTR("CSV:\n") : PSTR("LCD:\n")); - } + return !!error_flag; +} - // Add XY probe offset from extruder because probe.probe_at_point() subtracts them when - // moving to the XY position to be measured. This ensures better agreement between - // the current Z position after G28 and the mesh values. - const xy_int8_t curr = closest_indexes(xy_pos_t(current_position) + probe.offset_xy); +#if ENABLED(UBL_MESH_WIZARD) - if (!lcd) SERIAL_EOL(); - for (int8_t j = GRID_MAX_POINTS_Y - 1; j >= 0; j--) { + /** + * M1004: UBL Mesh Wizard - One-click mesh creation with or without a probe + */ + void GcodeSuite::M1004() { + + #define ALIGN_GCODE TERN(Z_STEPPER_AUTO_ALIGN, "G34", "") + #define PROBE_GCODE TERN(HAS_BED_PROBE, "G29P1\nG29P3", "G29P4R") - // Row Label (J index) - if (human) { - if (j < 10) SERIAL_CHAR(' '); - SERIAL_ECHO(j); - SERIAL_ECHOPGM(" |"); + #if HAS_HOTEND + if (parser.seenval('H')) { // Handle H# parameter to set Hotend temp + const celsius_t hotend_temp = parser.value_int(); // Marlin never sends itself F or K, always C + thermalManager.setTargetHotend(hotend_temp, 0); + thermalManager.wait_for_hotend(false); } + #endif - // Row Values (I indexes) - LOOP_L_N(i, GRID_MAX_POINTS_X) { - - // Opening Brace or Space - const bool is_current = i == curr.x && j == curr.y; - if (human) SERIAL_CHAR(is_current ? '[' : ' '); - - // Z Value at current I, J - const float f = z_values[i][j]; - if (lcd) { - // TODO: Display on Graphical LCD - } - else if (isnan(f)) - serialprintPGM(human ? PSTR(" . ") : PSTR("NAN")); - else if (human || csv) { - if (human && f >= 0.0) SERIAL_CHAR(f > 0 ? '+' : ' '); // Space for positive ('-' for negative) - SERIAL_ECHO_F(f, 3); // Positive: 5 digits, Negative: 6 digits - } - if (csv && i < GRID_MAX_POINTS_X - 1) SERIAL_CHAR('\t'); - - // Closing Brace or Space - if (human) SERIAL_CHAR(is_current ? ']' : ' '); - - SERIAL_FLUSHTX(); - idle_no_sleep(); + #if HAS_HEATED_BED + if (parser.seenval('B')) { // Handle B# parameter to set Bed temp + const celsius_t bed_temp = parser.value_int(); // Marlin never sends itself F or K, always C + thermalManager.setTargetBed(bed_temp); + thermalManager.wait_for_bed(false); } - if (!lcd) SERIAL_EOL(); + #endif - // A blank line between rows (unless compact) - if (j && human && !comp) SERIAL_ECHOLNPGM(" |"); - } + process_subcommands_now_P(G28_STR); // Home + process_subcommands_now_P(PSTR(ALIGN_GCODE "\n" // Align multi z axis if available + PROBE_GCODE "\n" // Build mesh with available hardware + "G29P3\nG29P3")); // Ensure mesh is complete by running smart fill twice - if (human) { - serial_echo_column_labels(eachsp - 2); - SERIAL_EOL(); - serial_echo_xy(4, MESH_MIN_X, MESH_MIN_Y); - serial_echo_xy(twixt, MESH_MAX_X, MESH_MIN_Y); - SERIAL_EOL(); - SERIAL_EOL(); + if (parser.seenval('S')) { + char umw_gcode[32]; + sprintf_P(umw_gcode, PSTR("G29S%i"), parser.value_int()); + queue.inject(umw_gcode); } - gcode.set_autoreport_paused(was); + process_subcommands_now_P(PSTR("G29A\nG29F10\n" // Set UBL Active & Fade 10 + "M140S0\nM104S0\n" // Turn off heaters + "M500")); // Store settings } - bool unified_bed_leveling::sanity_check() { - uint8_t error_flag = 0; - - if (settings.calc_num_meshes() < 1) { - SERIAL_ECHOLNPGM("?Mesh too big for EEPROM."); - error_flag++; - } - - return !!error_flag; - } +#endif // UBL_MESH_WIZARD #endif // AUTO_BED_LEVELING_UBL diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.h b/Marlin/src/feature/bedlevel/ubl/ubl.h index 9ac9de180638..cf00a282cfdd 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl.h +++ b/Marlin/src/feature/bedlevel/ubl/ubl.h @@ -32,279 +32,279 @@ #define UBL_OK false #define UBL_ERR true -enum MeshPointType : char { INVALID, REAL, SET_IN_BITMAP }; +enum MeshPointType : char { INVALID, REAL, SET_IN_BITMAP, CLOSEST }; // External references struct mesh_index_pair; -#define MESH_X_DIST (float(MESH_MAX_X - (MESH_MIN_X)) / float(GRID_MAX_POINTS_X - 1)) -#define MESH_Y_DIST (float(MESH_MAX_Y - (MESH_MIN_Y)) / float(GRID_MAX_POINTS_Y - 1)) +#define MESH_X_DIST (float(MESH_MAX_X - (MESH_MIN_X)) / (GRID_MAX_CELLS_X)) +#define MESH_Y_DIST (float(MESH_MAX_Y - (MESH_MIN_Y)) / (GRID_MAX_CELLS_Y)) + +#if ENABLED(OPTIMIZED_MESH_STORAGE) + typedef int16_t mesh_store_t[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y]; +#endif + +typedef struct { + bool C_seen; + int8_t KLS_storage_slot; + uint8_t R_repetition, + V_verbosity, + P_phase, + T_map_type; + float B_shim_thickness, + C_constant; + xy_pos_t XY_pos; + xy_bool_t XY_seen; + #if HAS_BED_PROBE + uint8_t J_grid_size; + #endif +} G29_parameters_t; class unified_bed_leveling { - private: - - static int g29_verbose_level, - g29_phase_value, - g29_repetition_cnt, - g29_storage_slot, - g29_map_type; - static bool g29_c_flag; - static float g29_card_thickness, - g29_constant; - static xy_pos_t g29_pos; - static xy_bool_t xy_seen; - - #if HAS_BED_PROBE - static int g29_grid_size; - #endif - - #if ENABLED(NEWPANEL) - static void move_z_with_encoder(const float &multiplier); - static float measure_point_with_encoder(); - static float measure_business_card_thickness(float in_height); - static void manually_probe_remaining_mesh(const xy_pos_t&, const float&, const float&, const bool) _O0; - static void fine_tune_mesh(const xy_pos_t &pos, const bool do_ubl_mesh_map) _O0; - #endif +private: + + static G29_parameters_t param; + + #if IS_NEWPANEL + static void move_z_with_encoder(const_float_t multiplier); + static float measure_point_with_encoder(); + static float measure_business_card_thickness(); + static void manually_probe_remaining_mesh(const xy_pos_t&, const_float_t , const_float_t , const bool) _O0; + static void fine_tune_mesh(const xy_pos_t &pos, const bool do_ubl_mesh_map) _O0; + #endif + + 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 inline bool smart_fill_one(const xy_uint8_t &pos, const xy_uint8_t &dir) { + return smart_fill_one(pos.x, pos.y, dir.x, dir.y); + } + static void smart_fill_mesh(); + + #if ENABLED(UBL_DEVEL_DEBUGGING) + static void g29_what_command(); + static void g29_eeprom_dump(); + static void g29_compare_current_mesh_to_stored_mesh(); + #endif + +public: + + static void echo_name(); + static void report_current_mesh(); + static void report_state(); + static void save_ubl_active_state_and_disable(); + static void restore_ubl_active_state_and_leave(); + static void display_map(const uint8_t) _O0; + static mesh_index_pair find_closest_mesh_point_of_type(const MeshPointType, const xy_pos_t&, const bool=false, MeshFlags *done_flags=nullptr) _O0; + static mesh_index_pair find_furthest_invalid_mesh_point() _O0; + static void reset(); + static void invalidate(); + static void set_all_mesh_points_to_value(const_float_t value); + static void adjust_mesh_to_mean(const bool cflag, const_float_t value); + static bool sanity_check(); + + static void G29() _O0; // O0 for no optimization + static void smart_fill_wlsf(const_float_t ) _O2; // O2 gives smaller code than Os on A2560 + + static int8_t storage_slot; + + static bed_mesh_t z_values; + #if ENABLED(OPTIMIZED_MESH_STORAGE) + static void set_store_from_mesh(const bed_mesh_t &in_values, mesh_store_t &stored_values); + static void set_mesh_from_store(const mesh_store_t &stored_values, bed_mesh_t &out_values); + #endif + static const float _mesh_index_to_xpos[GRID_MAX_POINTS_X], + _mesh_index_to_ypos[GRID_MAX_POINTS_Y]; + + #if HAS_LCD_MENU + static bool lcd_map_control; + static void steppers_were_disabled(); + #else + static inline void steppers_were_disabled() {} + #endif + + static volatile int16_t encoder_diff; // Volatile because buttons may change it at interrupt time + + unified_bed_leveling(); + + FORCE_INLINE static void set_z(const int8_t px, const int8_t py, const_float_t z) { z_values[px][py] = z; } + + static int8_t cell_index_x_raw(const_float_t x) { + return FLOOR((x - (MESH_MIN_X)) * RECIPROCAL(MESH_X_DIST)); + } + + static int8_t cell_index_y_raw(const_float_t y) { + return FLOOR((y - (MESH_MIN_Y)) * RECIPROCAL(MESH_Y_DIST)); + } + + static int8_t 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) { + return WITHIN(cell_index_y_raw(y), 0, GRID_MAX_CELLS_Y - 1); + } + + static int8_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) { + return constrain(cell_index_y_raw(y), 0, GRID_MAX_CELLS_Y - 1); + } + + static inline xy_int8_t cell_indexes(const_float_t x, const_float_t y) { + return { cell_index_x(x), cell_index_y(y) }; + } + static inline xy_int8_t cell_indexes(const xy_pos_t &xy) { return cell_indexes(xy.x, xy.y); } + + static 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); + return WITHIN(px, 0, (GRID_MAX_POINTS_X) - 1) ? px : -1; + } + static int8_t closest_y_index(const_float_t y) { + const int8_t py = (y - (MESH_MIN_Y) + (MESH_Y_DIST) * 0.5) * RECIPROCAL(MESH_Y_DIST); + return WITHIN(py, 0, (GRID_MAX_POINTS_Y) - 1) ? py : -1; + } + static inline xy_int8_t closest_indexes(const xy_pos_t &xy) { + return { closest_x_index(xy.x), closest_y_index(xy.y) }; + } + + /** + * z2 --| + * z0 | | + * | | + (z2-z1) + * z1 | | | + * ---+-------------+--------+-- --| + * a1 a0 a2 + * |<---delta_a---------->| + * + * calc_z0 is the basis for all the Mesh Based correction. It is used to + * find the expected Z Height at a position between two known Z-Height locations. + * + * It is fairly expensive with its 4 floating point additions and 2 floating point + * multiplications. + */ + FORCE_INLINE static float calc_z0(const_float_t a0, const_float_t a1, const_float_t z1, const_float_t a2, const_float_t z2) { + return z1 + (z2 - z1) * (a0 - a1) / (a2 - a1); + } + + #ifdef UBL_Z_RAISE_WHEN_OFF_MESH + #define _UBL_OUTER_Z_RAISE UBL_Z_RAISE_WHEN_OFF_MESH + #else + #define _UBL_OUTER_Z_RAISE NAN + #endif + + /** + * z_correction_for_x_on_horizontal_mesh_line is an optimization for + * the case where the printer is making a vertical line that only crosses horizontal mesh lines. + */ + static inline float z_correction_for_x_on_horizontal_mesh_line(const_float_t rx0, const int x1_i, const int yi) { + if (!WITHIN(x1_i, 0, (GRID_MAX_POINTS_X) - 1) || !WITHIN(yi, 0, (GRID_MAX_POINTS_Y) - 1)) { + + if (DEBUGGING(LEVELING)) { + if (WITHIN(x1_i, 0, (GRID_MAX_POINTS_X) - 1)) DEBUG_ECHOPGM("yi"); else DEBUG_ECHOPGM("x1_i"); + DEBUG_ECHOLNPAIR(" out of bounds in z_correction_for_x_on_horizontal_mesh_line(rx0=", rx0, ",x1_i=", x1_i, ",yi=", yi, ")"); + } - static bool g29_parameter_parsing() _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 &z1, const float &z2, const float &z3); - static void tilt_mesh_based_on_probed_grid(const bool do_ubl_mesh_map); - static bool smart_fill_one(const uint8_t x, const uint8_t y, const int8_t xdir, const int8_t ydir); - static inline bool smart_fill_one(const xy_uint8_t &pos, const xy_uint8_t &dir) { - return smart_fill_one(pos.x, pos.y, dir.x, dir.y); + // The requested location is off the mesh. Return UBL_Z_RAISE_WHEN_OFF_MESH or NAN. + return _UBL_OUTER_Z_RAISE; } - static void smart_fill_mesh(); - #if ENABLED(UBL_DEVEL_DEBUGGING) - static void g29_what_command(); - static void g29_eeprom_dump(); - static void g29_compare_current_mesh_to_stored_mesh(); - #endif - - public: - - static void echo_name(); - static void report_current_mesh(); - static void report_state(); - static void save_ubl_active_state_and_disable(); - static void restore_ubl_active_state_and_leave(); - static void display_map(const int) _O0; - static mesh_index_pair find_closest_mesh_point_of_type(const MeshPointType, const xy_pos_t&, const bool=false, MeshFlags *done_flags=nullptr) _O0; - static mesh_index_pair find_furthest_invalid_mesh_point() _O0; - static void reset(); - static void invalidate(); - static void set_all_mesh_points_to_value(const float value); - static void adjust_mesh_to_mean(const bool cflag, const float value); - static bool sanity_check(); - - static void G29() _O0; // O0 for no optimization - static void smart_fill_wlsf(const float &) _O2; // O2 gives smaller code than Os on A2560 - - static int8_t storage_slot; - - static bed_mesh_t z_values; - static const float _mesh_index_to_xpos[GRID_MAX_POINTS_X], - _mesh_index_to_ypos[GRID_MAX_POINTS_Y]; - - #if HAS_LCD_MENU - static bool lcd_map_control; - static void steppers_were_disabled(); - #else - static inline void steppers_were_disabled() {} - #endif + const float xratio = (rx0 - mesh_index_to_xpos(x1_i)) * RECIPROCAL(MESH_X_DIST), + z1 = z_values[x1_i][yi]; - static volatile int16_t encoder_diff; // Volatile because buttons may changed it at interrupt time - - unified_bed_leveling(); - - FORCE_INLINE static void set_z(const int8_t px, const int8_t py, const float &z) { z_values[px][py] = z; } - - static int8_t cell_index_x(const float &x) { - const int8_t cx = (x - (MESH_MIN_X)) * RECIPROCAL(MESH_X_DIST); - return constrain(cx, 0, (GRID_MAX_POINTS_X) - 1); // -1 is appropriate if we want all movement to the X_MAX - } // position. But with this defined this way, it is possible - // to extrapolate off of this point even further out. Probably - // that is OK because something else should be keeping that from - // happening and should not be worried about at this level. - static int8_t cell_index_y(const float &y) { - const int8_t cy = (y - (MESH_MIN_Y)) * RECIPROCAL(MESH_Y_DIST); - return constrain(cy, 0, (GRID_MAX_POINTS_Y) - 1); // -1 is appropriate if we want all movement to the Y_MAX - } // position. But with this defined this way, it is possible - // to extrapolate off of this point even further out. Probably - // that is OK because something else should be keeping that from - // happening and should not be worried about at this level. - - static inline xy_int8_t cell_indexes(const float &x, const float &y) { - return { cell_index_x(x), cell_index_y(y) }; - } - static inline xy_int8_t cell_indexes(const xy_pos_t &xy) { return cell_indexes(xy.x, xy.y); } + return z1 + xratio * (z_values[_MIN(x1_i, (GRID_MAX_POINTS_X) - 2) + 1][yi] - z1); // Don't allow x1_i+1 to be past the end of the array + // If it is, it is clamped to the last element of the + // z_values[][] array and no correction is applied. + } - static int8_t closest_x_index(const float &x) { - const int8_t px = (x - (MESH_MIN_X) + (MESH_X_DIST) * 0.5) * RECIPROCAL(MESH_X_DIST); - return WITHIN(px, 0, GRID_MAX_POINTS_X - 1) ? px : -1; - } - static int8_t closest_y_index(const float &y) { - const int8_t py = (y - (MESH_MIN_Y) + (MESH_Y_DIST) * 0.5) * RECIPROCAL(MESH_Y_DIST); - return WITHIN(py, 0, GRID_MAX_POINTS_Y - 1) ? py : -1; - } - static inline xy_int8_t closest_indexes(const xy_pos_t &xy) { - return { closest_x_index(xy.x), closest_y_index(xy.y) }; - } - - /** - * z2 --| - * z0 | | - * | | + (z2-z1) - * z1 | | | - * ---+-------------+--------+-- --| - * a1 a0 a2 - * |<---delta_a---------->| - * - * calc_z0 is the basis for all the Mesh Based correction. It is used to - * find the expected Z Height at a position between two known Z-Height locations. - * - * It is fairly expensive with its 4 floating point additions and 2 floating point - * multiplications. - */ - FORCE_INLINE static float calc_z0(const float &a0, const float &a1, const float &z1, const float &a2, const float &z2) { - return z1 + (z2 - z1) * (a0 - a1) / (a2 - a1); - } + // + // See comments above for z_correction_for_x_on_horizontal_mesh_line + // + static inline float z_correction_for_y_on_vertical_mesh_line(const_float_t ry0, const int xi, const int y1_i) { + if (!WITHIN(xi, 0, (GRID_MAX_POINTS_X) - 1) || !WITHIN(y1_i, 0, (GRID_MAX_POINTS_Y) - 1)) { - /** - * z_correction_for_x_on_horizontal_mesh_line is an optimization for - * the case where the printer is making a vertical line that only crosses horizontal mesh lines. - */ - static inline float z_correction_for_x_on_horizontal_mesh_line(const float &rx0, const int x1_i, const int yi) { - if (!WITHIN(x1_i, 0, GRID_MAX_POINTS_X - 1) || !WITHIN(yi, 0, GRID_MAX_POINTS_Y - 1)) { - - if (DEBUGGING(LEVELING)) { - if (WITHIN(x1_i, 0, GRID_MAX_POINTS_X - 1)) DEBUG_ECHOPGM("yi"); else DEBUG_ECHOPGM("x1_i"); - DEBUG_ECHOLNPAIR(" out of bounds in z_correction_for_x_on_horizontal_mesh_line(rx0=", rx0, ",x1_i=", x1_i, ",yi=", yi, ")"); - } - - // The requested location is off the mesh. Return UBL_Z_RAISE_WHEN_OFF_MESH or NAN. - return ( - #ifdef UBL_Z_RAISE_WHEN_OFF_MESH - UBL_Z_RAISE_WHEN_OFF_MESH - #else - NAN - #endif - ); + if (DEBUGGING(LEVELING)) { + if (WITHIN(xi, 0, (GRID_MAX_POINTS_X) - 1)) DEBUG_ECHOPGM("y1_i"); else DEBUG_ECHOPGM("xi"); + DEBUG_ECHOLNPAIR(" out of bounds in z_correction_for_y_on_vertical_mesh_line(ry0=", ry0, ", xi=", xi, ", y1_i=", y1_i, ")"); } - const float xratio = (rx0 - mesh_index_to_xpos(x1_i)) * RECIPROCAL(MESH_X_DIST), - z1 = z_values[x1_i][yi]; - - return z1 + xratio * (z_values[_MIN(x1_i, GRID_MAX_POINTS_X - 2) + 1][yi] - z1); // Don't allow x1_i+1 to be past the end of the array - // If it is, it is clamped to the last element of the - // z_values[][] array and no correction is applied. + // The requested location is off the mesh. Return UBL_Z_RAISE_WHEN_OFF_MESH or NAN. + return _UBL_OUTER_Z_RAISE; } - // - // See comments above for z_correction_for_x_on_horizontal_mesh_line - // - static inline float z_correction_for_y_on_vertical_mesh_line(const float &ry0, const int xi, const int y1_i) { - if (!WITHIN(xi, 0, GRID_MAX_POINTS_X - 1) || !WITHIN(y1_i, 0, GRID_MAX_POINTS_Y - 1)) { - - if (DEBUGGING(LEVELING)) { - if (WITHIN(xi, 0, GRID_MAX_POINTS_X - 1)) DEBUG_ECHOPGM("y1_i"); else DEBUG_ECHOPGM("xi"); - DEBUG_ECHOLNPAIR(" out of bounds in z_correction_for_y_on_vertical_mesh_line(ry0=", ry0, ", xi=", xi, ", y1_i=", y1_i, ")"); - } - - // The requested location is off the mesh. Return UBL_Z_RAISE_WHEN_OFF_MESH or NAN. - return ( - #ifdef UBL_Z_RAISE_WHEN_OFF_MESH - UBL_Z_RAISE_WHEN_OFF_MESH - #else - NAN - #endif - ); - } + const float yratio = (ry0 - mesh_index_to_ypos(y1_i)) * RECIPROCAL(MESH_Y_DIST), + z1 = z_values[xi][y1_i]; - const float yratio = (ry0 - mesh_index_to_ypos(y1_i)) * RECIPROCAL(MESH_Y_DIST), - z1 = z_values[xi][y1_i]; + return z1 + yratio * (z_values[xi][_MIN(y1_i, (GRID_MAX_POINTS_Y) - 2) + 1] - z1); // Don't allow y1_i+1 to be past the end of the array + // If it is, it is clamped to the last element of the + // z_values[][] array and no correction is applied. + } - return z1 + yratio * (z_values[xi][_MIN(y1_i, GRID_MAX_POINTS_Y - 2) + 1] - z1); // Don't allow y1_i+1 to be past the end of the array - // If it is, it is clamped to the last element of the - // z_values[][] array and no correction is applied. - } + /** + * This is the generic Z-Correction. It works anywhere within a Mesh Cell. It first + * does a linear interpolation along both of the bounding X-Mesh-Lines to find the + * Z-Height at both ends. Then it does a linear interpolation of these heights based + * on the Y position within the cell. + */ + static float get_z_correction(const_float_t rx0, const_float_t ry0) { + const int8_t cx = cell_index_x(rx0), cy = cell_index_y(ry0); // return values are clamped /** - * This is the generic Z-Correction. It works anywhere within a Mesh Cell. It first - * does a linear interpolation along both of the bounding X-Mesh-Lines to find the - * Z-Height at both ends. Then it does a linear interpolation of these heights based - * on the Y position within the cell. + * Check if the requested location is off the mesh. If so, and + * UBL_Z_RAISE_WHEN_OFF_MESH is specified, that value is returned. */ - static float get_z_correction(const float &rx0, const float &ry0) { - const int8_t cx = cell_index_x(rx0), cy = cell_index_y(ry0); // return values are clamped - - /** - * Check if the requested location is off the mesh. If so, and - * UBL_Z_RAISE_WHEN_OFF_MESH is specified, that value is returned. - */ - #ifdef UBL_Z_RAISE_WHEN_OFF_MESH - if (!WITHIN(rx0, MESH_MIN_X, MESH_MAX_X) || !WITHIN(ry0, MESH_MIN_Y, MESH_MAX_Y)) - return UBL_Z_RAISE_WHEN_OFF_MESH; - #endif - - const float z1 = calc_z0(rx0, - mesh_index_to_xpos(cx), z_values[cx][cy], - mesh_index_to_xpos(cx + 1), z_values[_MIN(cx, GRID_MAX_POINTS_X - 2) + 1][cy]); - - const float z2 = calc_z0(rx0, - mesh_index_to_xpos(cx), z_values[cx][_MIN(cy, GRID_MAX_POINTS_Y - 2) + 1], - mesh_index_to_xpos(cx + 1), z_values[_MIN(cx, GRID_MAX_POINTS_X - 2) + 1][_MIN(cy, GRID_MAX_POINTS_Y - 2) + 1]); - - float z0 = calc_z0(ry0, - mesh_index_to_ypos(cy), z1, - mesh_index_to_ypos(cy + 1), z2); - - if (DEBUGGING(MESH_ADJUST)) { - DEBUG_ECHOPAIR(" raw get_z_correction(", rx0); - DEBUG_CHAR(','); DEBUG_ECHO(ry0); - DEBUG_ECHOPAIR_F(") = ", z0, 6); - DEBUG_ECHOLNPAIR_F(" >>>---> ", z0, 6); - } + #ifdef UBL_Z_RAISE_WHEN_OFF_MESH + if (!WITHIN(rx0, MESH_MIN_X, MESH_MAX_X) || !WITHIN(ry0, MESH_MIN_Y, MESH_MAX_Y)) + return UBL_Z_RAISE_WHEN_OFF_MESH; + #endif - if (isnan(z0)) { // if part of the Mesh is undefined, it will show up as NAN - z0 = 0.0; // in ubl.z_values[][] and propagate through the - // calculations. If our correction is NAN, we throw it out - // because part of the Mesh is undefined and we don't have the - // information we need to complete the height correction. - - if (DEBUGGING(MESH_ADJUST)) { - DEBUG_ECHOPAIR("??? Yikes! NAN in get_z_correction(", rx0); - DEBUG_CHAR(','); - DEBUG_ECHO(ry0); - DEBUG_CHAR(')'); - DEBUG_EOL(); - } - } - return z0; - } - static inline float get_z_correction(const xy_pos_t &pos) { return get_z_correction(pos.x, pos.y); } + const uint8_t mx = _MIN(cx, (GRID_MAX_POINTS_X) - 2) + 1, my = _MIN(cy, (GRID_MAX_POINTS_Y) - 2) + 1; + const float z1 = calc_z0(rx0, mesh_index_to_xpos(cx), z_values[cx][cy], mesh_index_to_xpos(cx + 1), z_values[mx][cy]); + const float z2 = calc_z0(rx0, mesh_index_to_xpos(cx), z_values[cx][my], mesh_index_to_xpos(cx + 1), z_values[mx][my]); + float z0 = calc_z0(ry0, mesh_index_to_ypos(cy), z1, mesh_index_to_ypos(cy + 1), z2); - static inline float mesh_index_to_xpos(const uint8_t i) { - return i < GRID_MAX_POINTS_X ? pgm_read_float(&_mesh_index_to_xpos[i]) : MESH_MIN_X + i * (MESH_X_DIST); - } - static inline float mesh_index_to_ypos(const uint8_t i) { - return i < GRID_MAX_POINTS_Y ? pgm_read_float(&_mesh_index_to_ypos[i]) : MESH_MIN_Y + i * (MESH_Y_DIST); - } + if (isnan(z0)) { // if part of the Mesh is undefined, it will show up as NAN + z0 = 0.0; // in ubl.z_values[][] and propagate through the + // calculations. If our correction is NAN, we throw it out + // because part of the Mesh is undefined and we don't have the + // information we need to complete the height correction. - #if UBL_SEGMENTED - static bool line_to_destination_segmented(const feedRate_t &scaled_fr_mm_s); - #else - static void line_to_destination_cartesian(const feedRate_t &scaled_fr_mm_s, const uint8_t e); - #endif + if (DEBUGGING(MESH_ADJUST)) DEBUG_ECHOLNPAIR("??? Yikes! NAN in "); + } - static inline bool mesh_is_valid() { - GRID_LOOP(x, y) if (isnan(z_values[x][y])) return false; - return true; + if (DEBUGGING(MESH_ADJUST)) { + DEBUG_ECHOPAIR("get_z_correction(", rx0, ", ", ry0); + DEBUG_ECHOLNPAIR_F(") => ", z0, 6); } + return z0; + } + static inline float get_z_correction(const xy_pos_t &pos) { return get_z_correction(pos.x, pos.y); } + + static inline float mesh_index_to_xpos(const uint8_t i) { + return i < (GRID_MAX_POINTS_X) ? pgm_read_float(&_mesh_index_to_xpos[i]) : MESH_MIN_X + i * (MESH_X_DIST); + } + static inline float mesh_index_to_ypos(const uint8_t i) { + return i < (GRID_MAX_POINTS_Y) ? pgm_read_float(&_mesh_index_to_ypos[i]) : MESH_MIN_Y + i * (MESH_Y_DIST); + } + + #if UBL_SEGMENTED + static bool line_to_destination_segmented(const_feedRate_t scaled_fr_mm_s); + #else + static void line_to_destination_cartesian(const_feedRate_t scaled_fr_mm_s, const uint8_t e); + #endif + + static inline bool mesh_is_valid() { + GRID_LOOP(x, y) if (isnan(z_values[x][y])) return false; + return true; + } + }; // class unified_bed_leveling extern unified_bed_leveling ubl; diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index e41af9f3cd23..f8e446cf81be 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -24,1227 +24,1298 @@ #if ENABLED(AUTO_BED_LEVELING_UBL) - #include "../bedlevel.h" - - #include "../../../MarlinCore.h" - #include "../../../HAL/shared/eeprom_api.h" - #include "../../../libs/hex_print.h" - #include "../../../module/settings.h" - #include "../../../lcd/ultralcd.h" - #include "../../../module/stepper.h" - #include "../../../module/planner.h" - #include "../../../module/motion.h" - #include "../../../module/probe.h" - #include "../../../gcode/gcode.h" - #include "../../../libs/least_squares_fit.h" +#include "../bedlevel.h" - #if HAS_MULTI_HOTEND - #include "../../../module/tool_change.h" - #endif +#include "../../../MarlinCore.h" +#include "../../../HAL/shared/eeprom_api.h" +#include "../../../libs/hex_print.h" +#include "../../../module/settings.h" +#include "../../../lcd/marlinui.h" +#include "../../../module/stepper.h" +#include "../../../module/planner.h" +#include "../../../module/motion.h" +#include "../../../module/probe.h" +#include "../../../gcode/gcode.h" +#include "../../../libs/least_squares_fit.h" - #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) - #include "../../../core/debug_out.h" +#if HAS_MULTI_HOTEND + #include "../../../module/tool_change.h" +#endif - #if ENABLED(EXTENSIBLE_UI) - #include "../../../lcd/extui/ui_api.h" - #endif +#define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) +#include "../../../core/debug_out.h" - #include +#if ENABLED(EXTENSIBLE_UI) + #include "../../../lcd/extui/ui_api.h" +#endif - #define UBL_G29_P31 +#if ENABLED(UBL_HILBERT_CURVE) + #include "../hilbert_curve.h" +#endif - #if HAS_LCD_MENU +#include - bool unified_bed_leveling::lcd_map_control = false; +#define UBL_G29_P31 - void unified_bed_leveling::steppers_were_disabled() { - if (lcd_map_control) { - lcd_map_control = false; - ui.defer_status_screen(false); - } +#if HAS_LCD_MENU + + bool unified_bed_leveling::lcd_map_control = false; + + void unified_bed_leveling::steppers_were_disabled() { + if (lcd_map_control) { + lcd_map_control = false; + ui.defer_status_screen(false); } + } - void ubl_map_screen(); + void ubl_map_screen(); - #endif +#endif - #define SIZE_OF_LITTLE_RAISE 1 - #define BIG_RAISE_NOT_NEEDED 0 +#define SIZE_OF_LITTLE_RAISE 1 +#define BIG_RAISE_NOT_NEEDED 0 + +/** + * G29: Unified Bed Leveling by Roxy + * + * Parameters understood by this leveling system: + * + * A Activate Activate the Unified Bed Leveling system. + * + * B # Business Use the 'Business Card' mode of the Manual Probe subsystem with P2. + * Note: A non-compressible Spark Gap feeler gauge is recommended over a business card. + * In this mode of G29 P2, a business or index card is used as a shim that the nozzle can + * grab onto as it is lowered. In principle, the nozzle-bed distance is the same when the + * same resistance is felt in the shim. You can omit the numerical value on first invocation + * of G29 P2 B to measure shim thickness. Subsequent use of 'B' will apply the previously- + * measured thickness by default. + * + * C Continue G29 P1 C continues the generation of a partially-constructed Mesh without invalidating + * previous measurements. + * + * C G29 P2 C tells the Manual Probe subsystem to not use the current nozzle + * location in its search for the closest unmeasured Mesh Point. Instead, attempt to + * start at one end of the uprobed points and Continue sequentially. + * + * G29 P3 C specifies the Constant for the fill. Otherwise, uses a "reasonable" value. + * + * C Current G29 Z C uses the Current location (instead of bed center or nearest edge). + * + * D Disable Disable the Unified Bed Leveling system. + * + * E Stow_probe Stow the probe after each sampled point. + * + * F # Fade Fade the amount of Mesh Based Compensation over a specified height. At the + * specified height, no correction is applied and natural printer kenimatics take over. If no + * number is specified for the command, 10mm is assumed to be reasonable. + * + * H # Height With P2, 'H' specifies the Height to raise the nozzle after each manual probe of the bed. + * If omitted, the nozzle will raise by Z_CLEARANCE_BETWEEN_PROBES. + * + * H # Offset With P4, 'H' specifies the Offset above the mesh height to place the nozzle. + * If omitted, Z_CLEARANCE_BETWEEN_PROBES will be used. + * + * I # Invalidate Invalidate the specified number of Mesh Points near the given 'X' 'Y'. If X or Y are omitted, + * the nozzle location is used. If no 'I' value is given, only the point nearest to the location + * is invalidated. Use 'T' to produce a map afterward. This command is useful to invalidate a + * portion of the Mesh so it can be adjusted using other UBL tools. When attempting to invalidate + * an isolated bad mesh point, the 'T' option shows the nozzle position in the Mesh with (#). You + * can move the nozzle around and use this feature to select the center of the area (or cell) to + * invalidate. + * + * J # Grid Perform a Grid Based Leveling of the current Mesh using a grid with n points on a side. + * Not specifying a grid size will invoke the 3-Point leveling function. + * + * L Load Load Mesh from the previously activated location in the EEPROM. + * + * L # Load Load Mesh from the specified location in the EEPROM. Set this location as activated + * for subsequent Load and Store operations. + * + * The P or Phase commands are used for the bulk of the work to setup a Mesh. In general, your Mesh will + * start off being initialized with a G29 P0 or a G29 P1. Further refinement of the Mesh happens with + * each additional Phase that processes it. + * + * P0 Phase 0 Zero Mesh Data and turn off the Mesh Compensation System. This reverts the + * 3D Printer to the same state it was in before the Unified Bed Leveling Compensation + * was turned on. Setting the entire Mesh to Zero is a special case that allows + * a subsequent G or T leveling operation for backward compatibility. + * + * P1 Phase 1 Invalidate entire Mesh and continue with automatic generation of the Mesh data using + * the Z-Probe. Usually the probe can't reach all areas that the nozzle can reach. For delta + * printers only the areas where the probe and nozzle can both reach will be automatically probed. + * + * Unreachable points will be handled in Phase 2 and Phase 3. + * + * Use 'C' to leave the previous mesh intact and automatically probe needed points. This allows you + * to invalidate parts of the Mesh but still use Automatic Probing. + * + * The 'X' and 'Y' parameters prioritize where to try and measure points. If omitted, the current + * probe position is used. + * + * Use 'T' (Topology) to generate a report of mesh generation. + * + * P1 will suspend Mesh generation if the controller button is held down. Note that you may need + * to press and hold the switch for several seconds if moves are underway. + * + * P2 Phase 2 Probe unreachable points. + * + * Use 'H' to set the height between Mesh points. If omitted, Z_CLEARANCE_BETWEEN_PROBES is used. + * Smaller values will be quicker. Move the nozzle down till it barely touches the bed. Make sure the + * nozzle is clean and unobstructed. Use caution and move slowly. This can damage your printer! + * (Uses SIZE_OF_LITTLE_RAISE mm if the nozzle is moving less than BIG_RAISE_NOT_NEEDED mm.) + * + * The 'H' value can be negative if the Mesh dips in a large area. Press and hold the + * controller button to terminate the current Phase 2 command. You can then re-issue "G29 P 2" + * with an 'H' parameter more suitable for the area you're manually probing. Note that the command + * tries to start in a corner of the bed where movement will be predictable. Override the distance + * calculation location with the X and Y parameters. You can print a Mesh Map (G29 T) to see where + * the mesh is invalidated and where the nozzle needs to move to complete the command. Use 'C' to + * indicate that the search should be based on the current position. + * + * The 'B' parameter for this command is described above. It places the manual probe subsystem into + * Business Card mode where the thickness of a business card is measured and then used to accurately + * set the nozzle height in all manual probing for the duration of the command. A Business card can + * be used, but you'll get better results with a flexible Shim that doesn't compress. This makes it + * easier to produce similar amounts of force and get more accurate measurements. Google if you're + * not sure how to use a shim. + * + * The 'T' (Map) parameter helps track Mesh building progress. + * + * NOTE: P2 requires an LCD controller! + * + * P3 Phase 3 Fill the unpopulated regions of the Mesh with a fixed value. There are two different paths to + * go down: + * + * - If a 'C' constant is specified, the closest invalid mesh points to the nozzle will be filled, + * and a repeat count can then also be specified with 'R'. + * + * - Leaving out 'C' invokes Smart Fill, which scans the mesh from the edges inward looking for + * invalid mesh points. Adjacent points are used to determine the bed slope. If the bed is sloped + * upward from the invalid point, it takes the value of the nearest point. If sloped downward, it's + * replaced by a value that puts all three points in a line. This version of G29 P3 is a quick, easy + * and (usually) safe way to populate unprobed mesh regions before continuing to G26 Mesh Validation + * Pattern. Note that this populates the mesh with unverified values. Pay attention and use caution. + * + * P4 Phase 4 Fine tune the Mesh. The Delta Mesh Compensation System assumes the existence of + * an LCD Panel. It is possible to fine tune the mesh without an LCD Panel using + * G42 and M421. See the UBL documentation for further details. + * + * Phase 4 is meant to be used with G26 Mesh Validation to fine tune the mesh by direct editing + * of Mesh Points. Raise and lower points to fine tune the mesh until it gives consistently reliable + * adhesion. + * + * P4 moves to the closest Mesh Point (and/or the given X Y), raises the nozzle above the mesh height + * by the given 'H' offset (or default 0), and waits while the controller is used to adjust the nozzle + * height. On click the displayed height is saved in the mesh. + * + * Start Phase 4 at a specific location with X and Y. Adjust a specific number of Mesh Points with + * the 'R' (Repeat) parameter. (If 'R' is left out, the whole matrix is assumed.) This command can be + * terminated early (e.g., after editing the area of interest) by pressing and holding the encoder button. + * + * The general form is G29 P4 [R points] [X position] [Y position] + * + * The H [offset] parameter is useful if a shim is used to fine-tune the mesh. For a 0.4mm shim the + * command would be G29 P4 H0.4. The nozzle is moved to the shim height, you adjust height to the shim, + * and on click the height minus the shim thickness will be saved in the mesh. + * + * !!Use with caution, as a very poor mesh could cause the nozzle to crash into the bed!! + * + * NOTE: P4 is not available unless you have LCD support enabled! + * + * P5 Phase 5 Find Mean Mesh Height and Standard Deviation. Typically, it is easier to use and + * work with the Mesh if it is Mean Adjusted. You can specify a C parameter to + * Correct the Mesh to a 0.00 Mean Height. Adding a C parameter will automatically + * execute a G29 P6 C . + * + * P6 Phase 6 Shift Mesh height. The entire Mesh's height is adjusted by the height specified + * with the C parameter. Being able to adjust the height of a Mesh is useful tool. It + * can be used to compensate for poorly calibrated Z-Probes and other errors. Ideally, + * you should have the Mesh adjusted for a Mean Height of 0.00 and the Z-Probe measuring + * 0.000 at the Z Home location. + * + * Q Test Load specified Test Pattern to assist in checking correct operation of system. This + * command is not anticipated to be of much value to the typical user. It is intended + * for developers to help them verify correct operation of the Unified Bed Leveling System. + * + * R # Repeat Repeat this command the specified number of times. If no number is specified the + * command will be repeated GRID_MAX_POINTS_X * GRID_MAX_POINTS_Y times. + * + * S Store Store the current Mesh in the Activated area of the EEPROM. It will also store the + * current state of the Unified Bed Leveling system in the EEPROM. + * + * S # Store Store the current Mesh at the specified location in EEPROM. Activate this location + * for subsequent Load and Store operations. Valid storage slot numbers begin at 0 and + * extend to a limit related to the available EEPROM storage. + * + * S -1 Store Print the current Mesh as G-code that can be used to restore the mesh anytime. + * + * T Topology Display the Mesh Map Topology. + * 'T' can be used alone (e.g., G29 T) or in combination with most of the other commands. + * This option works with all Phase commands (e.g., G29 P4 R 5 T X 50 Y100 C -.1 O) + * This parameter can also specify a Map Type. T0 (the default) is user-readable. T1 + * is suitable to paste into a spreadsheet for a 3D graph of the mesh. + * + * U Unlevel Perform a probe of the outer perimeter to assist in physically leveling unlevel beds. + * Only used for G29 P1 T U. This speeds up the probing of the edge of the bed. Useful + * when the entire bed doesn't need to be probed because it will be adjusted. + * + * V # Verbosity Set the verbosity level (0-4) for extra details. (Default 0) + * + * X # X Location for this command + * + * Y # Y Location for this command + * + * With UBL_DEVEL_DEBUGGING: + * + * K # Kompare Kompare current Mesh with stored Mesh #, replacing current Mesh with the result. + * This command literally performs a diff between two Meshes. + * + * Q-1 Dump EEPROM Dump the UBL contents stored in EEPROM as HEX format. Useful for developers to help + * verify correct operation of the UBL. + * + * W What? Display valuable UBL data. + * + * + * Release Notes: + * You MUST do M502, M500 to initialize the storage. Failure to do this will cause all + * kinds of problems. Enabling EEPROM Storage is required. + * + * When you do a G28 and G29 P1 to automatically build your first mesh, you are going to notice that + * UBL probes points increasingly further from the starting location. (The starting location defaults + * to the center of the bed.) In contrast, ABL and MBL follow a zigzag pattern. The spiral pattern is + * especially better for Delta printers, since it populates the center of the mesh first, allowing for + * a quicker test print to verify settings. You don't need to populate the entire mesh to use it. + * After all, you don't want to spend a lot of time generating a mesh only to realize the resolution + * or probe offsets are incorrect. Mesh-generation gathers points starting closest to the nozzle unless + * an (X,Y) coordinate pair is given. + * + * Unified Bed Leveling uses a lot of EEPROM storage to hold its data, and it takes some effort to get + * the mesh just right. To prevent this valuable data from being destroyed as the EEPROM structure + * evolves, UBL stores all mesh data at the end of EEPROM. + * + * UBL is founded on Edward Patel's Mesh Bed Leveling code. A big 'Thanks!' to him and the creators of + * 3-Point and Grid Based leveling. Combining their contributions we now have the functionality and + * features of all three systems combined. + */ - int unified_bed_leveling::g29_verbose_level, - unified_bed_leveling::g29_phase_value, - unified_bed_leveling::g29_repetition_cnt, - unified_bed_leveling::g29_storage_slot = 0, - unified_bed_leveling::g29_map_type; - bool unified_bed_leveling::g29_c_flag; - float unified_bed_leveling::g29_card_thickness = 0, - unified_bed_leveling::g29_constant = 0; - xy_bool_t unified_bed_leveling::xy_seen; - xy_pos_t unified_bed_leveling::g29_pos; +G29_parameters_t unified_bed_leveling::param; - #if HAS_BED_PROBE - int unified_bed_leveling::g29_grid_size; - #endif +void unified_bed_leveling::G29() { - /** - * G29: Unified Bed Leveling by Roxy - * - * Parameters understood by this leveling system: - * - * A Activate Activate the Unified Bed Leveling system. - * - * B # Business Use the 'Business Card' mode of the Manual Probe subsystem with P2. - * Note: A non-compressible Spark Gap feeler gauge is recommended over a business card. - * In this mode of G29 P2, a business or index card is used as a shim that the nozzle can - * grab onto as it is lowered. In principle, the nozzle-bed distance is the same when the - * same resistance is felt in the shim. You can omit the numerical value on first invocation - * of G29 P2 B to measure shim thickness. Subsequent use of 'B' will apply the previously- - * measured thickness by default. - * - * C Continue G29 P1 C continues the generation of a partially-constructed Mesh without invalidating - * previous measurements. - * - * C G29 P2 C tells the Manual Probe subsystem to not use the current nozzle - * location in its search for the closest unmeasured Mesh Point. Instead, attempt to - * start at one end of the uprobed points and Continue sequentially. - * - * G29 P3 C specifies the Constant for the fill. Otherwise, uses a "reasonable" value. - * - * C Current G29 Z C uses the Current location (instead of bed center or nearest edge). - * - * D Disable Disable the Unified Bed Leveling system. - * - * E Stow_probe Stow the probe after each sampled point. - * - * F # Fade Fade the amount of Mesh Based Compensation over a specified height. At the - * specified height, no correction is applied and natural printer kenimatics take over. If no - * number is specified for the command, 10mm is assumed to be reasonable. - * - * H # Height With P2, 'H' specifies the Height to raise the nozzle after each manual probe of the bed. - * If omitted, the nozzle will raise by Z_CLEARANCE_BETWEEN_PROBES. - * - * H # Offset With P4, 'H' specifies the Offset above the mesh height to place the nozzle. - * If omitted, Z_CLEARANCE_BETWEEN_PROBES will be used. - * - * I # Invalidate Invalidate the specified number of Mesh Points near the given 'X' 'Y'. If X or Y are omitted, - * the nozzle location is used. If no 'I' value is given, only the point nearest to the location - * is invalidated. Use 'T' to produce a map afterward. This command is useful to invalidate a - * portion of the Mesh so it can be adjusted using other UBL tools. When attempting to invalidate - * an isolated bad mesh point, the 'T' option shows the nozzle position in the Mesh with (#). You - * can move the nozzle around and use this feature to select the center of the area (or cell) to - * invalidate. - * - * J # Grid Perform a Grid Based Leveling of the current Mesh using a grid with n points on a side. - * Not specifying a grid size will invoke the 3-Point leveling function. - * - * L Load Load Mesh from the previously activated location in the EEPROM. - * - * L # Load Load Mesh from the specified location in the EEPROM. Set this location as activated - * for subsequent Load and Store operations. - * - * The P or Phase commands are used for the bulk of the work to setup a Mesh. In general, your Mesh will - * start off being initialized with a G29 P0 or a G29 P1. Further refinement of the Mesh happens with - * each additional Phase that processes it. - * - * P0 Phase 0 Zero Mesh Data and turn off the Mesh Compensation System. This reverts the - * 3D Printer to the same state it was in before the Unified Bed Leveling Compensation - * was turned on. Setting the entire Mesh to Zero is a special case that allows - * a subsequent G or T leveling operation for backward compatibility. - * - * P1 Phase 1 Invalidate entire Mesh and continue with automatic generation of the Mesh data using - * the Z-Probe. Usually the probe can't reach all areas that the nozzle can reach. For delta - * printers only the areas where the probe and nozzle can both reach will be automatically probed. - * - * Unreachable points will be handled in Phase 2 and Phase 3. - * - * Use 'C' to leave the previous mesh intact and automatically probe needed points. This allows you - * to invalidate parts of the Mesh but still use Automatic Probing. - * - * The 'X' and 'Y' parameters prioritize where to try and measure points. If omitted, the current - * probe position is used. - * - * Use 'T' (Topology) to generate a report of mesh generation. - * - * P1 will suspend Mesh generation if the controller button is held down. Note that you may need - * to press and hold the switch for several seconds if moves are underway. - * - * P2 Phase 2 Probe unreachable points. - * - * Use 'H' to set the height between Mesh points. If omitted, Z_CLEARANCE_BETWEEN_PROBES is used. - * Smaller values will be quicker. Move the nozzle down till it barely touches the bed. Make sure the - * nozzle is clean and unobstructed. Use caution and move slowly. This can damage your printer! - * (Uses SIZE_OF_LITTLE_RAISE mm if the nozzle is moving less than BIG_RAISE_NOT_NEEDED mm.) - * - * The 'H' value can be negative if the Mesh dips in a large area. Press and hold the - * controller button to terminate the current Phase 2 command. You can then re-issue "G29 P 2" - * with an 'H' parameter more suitable for the area you're manually probing. Note that the command - * tries to start in a corner of the bed where movement will be predictable. Override the distance - * calculation location with the X and Y parameters. You can print a Mesh Map (G29 T) to see where - * the mesh is invalidated and where the nozzle needs to move to complete the command. Use 'C' to - * indicate that the search should be based on the current position. - * - * The 'B' parameter for this command is described above. It places the manual probe subsystem into - * Business Card mode where the thickness of a business card is measured and then used to accurately - * set the nozzle height in all manual probing for the duration of the command. A Business card can - * be used, but you'll get better results with a flexible Shim that doesn't compress. This makes it - * easier to produce similar amounts of force and get more accurate measurements. Google if you're - * not sure how to use a shim. - * - * The 'T' (Map) parameter helps track Mesh building progress. - * - * NOTE: P2 requires an LCD controller! - * - * P3 Phase 3 Fill the unpopulated regions of the Mesh with a fixed value. There are two different paths to - * go down: - * - * - If a 'C' constant is specified, the closest invalid mesh points to the nozzle will be filled, - * and a repeat count can then also be specified with 'R'. - * - * - Leaving out 'C' invokes Smart Fill, which scans the mesh from the edges inward looking for - * invalid mesh points. Adjacent points are used to determine the bed slope. If the bed is sloped - * upward from the invalid point, it takes the value of the nearest point. If sloped downward, it's - * replaced by a value that puts all three points in a line. This version of G29 P3 is a quick, easy - * and (usually) safe way to populate unprobed mesh regions before continuing to G26 Mesh Validation - * Pattern. Note that this populates the mesh with unverified values. Pay attention and use caution. - * - * P4 Phase 4 Fine tune the Mesh. The Delta Mesh Compensation System assumes the existence of - * an LCD Panel. It is possible to fine tune the mesh without an LCD Panel using - * G42 and M421. See the UBL documentation for further details. - * - * Phase 4 is meant to be used with G26 Mesh Validation to fine tune the mesh by direct editing - * of Mesh Points. Raise and lower points to fine tune the mesh until it gives consistently reliable - * adhesion. - * - * P4 moves to the closest Mesh Point (and/or the given X Y), raises the nozzle above the mesh height - * by the given 'H' offset (or default 0), and waits while the controller is used to adjust the nozzle - * height. On click the displayed height is saved in the mesh. - * - * Start Phase 4 at a specific location with X and Y. Adjust a specific number of Mesh Points with - * the 'R' (Repeat) parameter. (If 'R' is left out, the whole matrix is assumed.) This command can be - * terminated early (e.g., after editing the area of interest) by pressing and holding the encoder button. - * - * The general form is G29 P4 [R points] [X position] [Y position] - * - * The H [offset] parameter is useful if a shim is used to fine-tune the mesh. For a 0.4mm shim the - * command would be G29 P4 H0.4. The nozzle is moved to the shim height, you adjust height to the shim, - * and on click the height minus the shim thickness will be saved in the mesh. - * - * !!Use with caution, as a very poor mesh could cause the nozzle to crash into the bed!! - * - * NOTE: P4 is not available unless you have LCD support enabled! - * - * P5 Phase 5 Find Mean Mesh Height and Standard Deviation. Typically, it is easier to use and - * work with the Mesh if it is Mean Adjusted. You can specify a C parameter to - * Correct the Mesh to a 0.00 Mean Height. Adding a C parameter will automatically - * execute a G29 P6 C . - * - * P6 Phase 6 Shift Mesh height. The entire Mesh's height is adjusted by the height specified - * with the C parameter. Being able to adjust the height of a Mesh is useful tool. It - * can be used to compensate for poorly calibrated Z-Probes and other errors. Ideally, - * you should have the Mesh adjusted for a Mean Height of 0.00 and the Z-Probe measuring - * 0.000 at the Z Home location. - * - * Q Test Load specified Test Pattern to assist in checking correct operation of system. This - * command is not anticipated to be of much value to the typical user. It is intended - * for developers to help them verify correct operation of the Unified Bed Leveling System. - * - * R # Repeat Repeat this command the specified number of times. If no number is specified the - * command will be repeated GRID_MAX_POINTS_X * GRID_MAX_POINTS_Y times. - * - * S Store Store the current Mesh in the Activated area of the EEPROM. It will also store the - * current state of the Unified Bed Leveling system in the EEPROM. - * - * S # Store Store the current Mesh at the specified location in EEPROM. Activate this location - * for subsequent Load and Store operations. Valid storage slot numbers begin at 0 and - * extend to a limit related to the available EEPROM storage. - * - * S -1 Store Print the current Mesh as G-code that can be used to restore the mesh anytime. - * - * T Topology Display the Mesh Map Topology. - * 'T' can be used alone (e.g., G29 T) or in combination with most of the other commands. - * This option works with all Phase commands (e.g., G29 P4 R 5 T X 50 Y100 C -.1 O) - * This parameter can also specify a Map Type. T0 (the default) is user-readable. T1 - * is suitable to paste into a spreadsheet for a 3D graph of the mesh. - * - * U Unlevel Perform a probe of the outer perimeter to assist in physically leveling unlevel beds. - * Only used for G29 P1 T U. This speeds up the probing of the edge of the bed. Useful - * when the entire bed doesn't need to be probed because it will be adjusted. - * - * V # Verbosity Set the verbosity level (0-4) for extra details. (Default 0) - * - * X # X Location for this command - * - * Y # Y Location for this command - * - * With UBL_DEVEL_DEBUGGING: - * - * K # Kompare Kompare current Mesh with stored Mesh #, replacing current Mesh with the result. - * This command literally performs a diff between two Meshes. - * - * Q-1 Dump EEPROM Dump the UBL contents stored in EEPROM as HEX format. Useful for developers to help - * verify correct operation of the UBL. - * - * W What? Display valuable UBL data. - * - * - * Release Notes: - * You MUST do M502, M500 to initialize the storage. Failure to do this will cause all - * kinds of problems. Enabling EEPROM Storage is required. - * - * When you do a G28 and G29 P1 to automatically build your first mesh, you are going to notice that - * UBL probes points increasingly further from the starting location. (The starting location defaults - * to the center of the bed.) In contrast, ABL and MBL follow a zigzag pattern. The spiral pattern is - * especially better for Delta printers, since it populates the center of the mesh first, allowing for - * a quicker test print to verify settings. You don't need to populate the entire mesh to use it. - * After all, you don't want to spend a lot of time generating a mesh only to realize the resolution - * or probe offsets are incorrect. Mesh-generation gathers points starting closest to the nozzle unless - * an (X,Y) coordinate pair is given. - * - * Unified Bed Leveling uses a lot of EEPROM storage to hold its data, and it takes some effort to get - * the mesh just right. To prevent this valuable data from being destroyed as the EEPROM structure - * evolves, UBL stores all mesh data at the end of EEPROM. - * - * UBL is founded on Edward Patel's Mesh Bed Leveling code. A big 'Thanks!' to him and the creators of - * 3-Point and Grid Based leveling. Combining their contributions we now have the functionality and - * features of all three systems combined. - */ + bool probe_deployed = false; + if (G29_parse_parameters()) return; // Abort on parameter error - void unified_bed_leveling::G29() { + const uint8_t p_val = parser.byteval('P'); + const bool may_move = p_val == 1 || p_val == 2 || p_val == 4 || parser.seen_test('J'); + #if HAS_MULTI_HOTEND + const uint8_t old_tool_index = active_extruder; + #endif - bool probe_deployed = false; - if (g29_parameter_parsing()) return; // Abort on parameter error + // Check for commands that require the printer to be homed + if (may_move) { + planner.synchronize(); + // Send 'N' to force homing before G29 (internal only) + if (axes_should_home() || parser.seen_test('N')) gcode.home_all_axes(); + TERN_(HAS_MULTI_HOTEND, if (active_extruder) tool_change(0)); + } - const int8_t p_val = parser.intval('P', -1); - const bool may_move = p_val == 1 || p_val == 2 || p_val == 4 || parser.seen('J'); - TERN_(HAS_MULTI_HOTEND, const uint8_t old_tool_index = active_extruder); + // Invalidate one or more nearby mesh points, possibly all. + if (parser.seen('I')) { + uint8_t count = parser.has_value() ? parser.value_byte() : 1; + bool invalidate_all = count >= GRID_MAX_POINTS; + if (!invalidate_all) { + while (count--) { + if ((count & 0x0F) == 0x0F) idle(); + const mesh_index_pair closest = find_closest_mesh_point_of_type(REAL, param.XY_pos); + // No more REAL mesh points to invalidate? Assume the user meant + // to invalidate the ENTIRE mesh, which can't be done with + // find_closest_mesh_point (which only returns REAL points). + if (closest.pos.x < 0) { invalidate_all = true; break; } + z_values[closest.pos.x][closest.pos.y] = NAN; + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(closest.pos, 0.0f)); + } + } + if (invalidate_all) { + invalidate(); + SERIAL_ECHOPGM("Entire Mesh"); + } + else + SERIAL_ECHOPGM("Locations"); + SERIAL_ECHOLNPGM(" invalidated.\n"); + } - // Check for commands that require the printer to be homed - if (may_move) { - planner.synchronize(); - if (axes_should_home()) gcode.home_all_axes(); - TERN_(HAS_MULTI_HOTEND, if (active_extruder) tool_change(0)); + if (parser.seen('Q')) { + const int16_t test_pattern = parser.has_value() ? parser.value_int() : -99; + if (!WITHIN(test_pattern, -1, 2)) { + SERIAL_ECHOLNPGM("Invalid test_pattern value. (-1 to 2)\n"); + return; } + SERIAL_ECHOLNPGM("Loading test_pattern values.\n"); + switch (test_pattern) { - // Invalidate Mesh Points. This command is a little bit asymmetrical because - // it directly specifies the repetition count and does not use the 'R' parameter. - if (parser.seen('I')) { - uint8_t cnt = 0; - g29_repetition_cnt = parser.has_value() ? parser.value_int() : 1; - if (g29_repetition_cnt >= GRID_MAX_POINTS) { - set_all_mesh_points_to_value(NAN); - } - else { - while (g29_repetition_cnt--) { - if (cnt > 20) { cnt = 0; idle(); } - const mesh_index_pair closest = find_closest_mesh_point_of_type(REAL, g29_pos); - const xy_int8_t &cpos = closest.pos; - if (cpos.x < 0) { - // No more REAL mesh points to invalidate, so we ASSUME the user - // meant to invalidate the ENTIRE mesh, which cannot be done with - // find_closest_mesh_point loop which only returns REAL points. - set_all_mesh_points_to_value(NAN); - SERIAL_ECHOLNPGM("Entire Mesh invalidated.\n"); - break; // No more invalid Mesh Points to populate - } - z_values[cpos.x][cpos.y] = NAN; - TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(cpos, 0.0f)); - cnt++; + case -1: TERN_(UBL_DEVEL_DEBUGGING, g29_eeprom_dump()); break; + + case 0: + GRID_LOOP(x, y) { // Create a bowl shape similar to a poorly-calibrated Delta + const float p1 = 0.5f * (GRID_MAX_POINTS_X) - x, + p2 = 0.5f * (GRID_MAX_POINTS_Y) - y; + z_values[x][y] += 2.0f * HYPOT(p1, p2); + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, z_values[x][y])); } - } - SERIAL_ECHOLNPGM("Locations invalidated.\n"); - } + break; - if (parser.seen('Q')) { - const int test_pattern = parser.has_value() ? parser.value_int() : -99; - if (!WITHIN(test_pattern, -1, 2)) { - SERIAL_ECHOLNPGM("Invalid test_pattern value. (-1 to 2)\n"); - return; - } - SERIAL_ECHOLNPGM("Loading test_pattern values.\n"); - switch (test_pattern) { + case 1: + LOOP_L_N(x, GRID_MAX_POINTS_X) { // Create a diagonal line several Mesh cells thick that is raised + z_values[x][x] += 9.999f; + z_values[x][x + (x < (GRID_MAX_POINTS_Y) - 1) ? 1 : -1] += 9.999f; // We want the altered line several mesh points thick + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onMeshUpdate(x, x, z_values[x][x]); + ExtUI::onMeshUpdate(x, (x + (x < (GRID_MAX_POINTS_Y) - 1) ? 1 : -1), z_values[x][x + (x < (GRID_MAX_POINTS_Y) - 1) ? 1 : -1]); + #endif - #if ENABLED(UBL_DEVEL_DEBUGGING) - case -1: - g29_eeprom_dump(); - break; - #endif + } + break; - case 0: - GRID_LOOP(x, y) { // Create a bowl shape similar to a poorly-calibrated Delta - const float p1 = 0.5f * (GRID_MAX_POINTS_X) - x, - p2 = 0.5f * (GRID_MAX_POINTS_Y) - y; - z_values[x][y] += 2.0f * HYPOT(p1, p2); + case 2: + // Allow the user to specify the height because 10mm is a little extreme in some cases. + for (uint8_t x = (GRID_MAX_POINTS_X) / 3; x < 2 * (GRID_MAX_POINTS_X) / 3; x++) // Create a rectangular raised area in + for (uint8_t y = (GRID_MAX_POINTS_Y) / 3; y < 2 * (GRID_MAX_POINTS_Y) / 3; y++) { // the center of the bed + z_values[x][y] += parser.seen_test('C') ? param.C_constant : 9.99f; TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, z_values[x][y])); } - break; - - case 1: - LOOP_L_N(x, GRID_MAX_POINTS_X) { // Create a diagonal line several Mesh cells thick that is raised - z_values[x][x] += 9.999f; - z_values[x][x + (x < (GRID_MAX_POINTS_Y) - 1) ? 1 : -1] += 9.999f; // We want the altered line several mesh points thick - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(x, x, z_values[x][x]); - ExtUI::onMeshUpdate(x, (x + (x < (GRID_MAX_POINTS_Y) - 1) ? 1 : -1), z_values[x][x + (x < (GRID_MAX_POINTS_Y) - 1) ? 1 : -1]); - #endif + break; + } + } - } - break; - - case 2: - // Allow the user to specify the height because 10mm is a little extreme in some cases. - for (uint8_t x = (GRID_MAX_POINTS_X) / 3; x < 2 * (GRID_MAX_POINTS_X) / 3; x++) // Create a rectangular raised area in - for (uint8_t y = (GRID_MAX_POINTS_Y) / 3; y < 2 * (GRID_MAX_POINTS_Y) / 3; y++) { // the center of the bed - z_values[x][y] += parser.seen('C') ? g29_constant : 9.99f; - TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, z_values[x][y])); - } - break; - } + #if HAS_BED_PROBE + + if (parser.seen_test('J')) { + save_ubl_active_state_and_disable(); + tilt_mesh_based_on_probed_grid(param.J_grid_size == 0); // Zero size does 3-Point + restore_ubl_active_state_and_leave(); + #if ENABLED(UBL_G29_J_RECENTER) + do_blocking_move_to_xy(0.5f * ((MESH_MIN_X) + (MESH_MAX_X)), 0.5f * ((MESH_MIN_Y) + (MESH_MAX_Y))); + #endif + report_current_position(); + probe_deployed = true; } - #if HAS_BED_PROBE + #endif // HAS_BED_PROBE - if (parser.seen('J')) { - save_ubl_active_state_and_disable(); - tilt_mesh_based_on_probed_grid(g29_grid_size == 0); // Zero size does 3-Point - restore_ubl_active_state_and_leave(); - #if ENABLED(UBL_G29_J_RECENTER) - do_blocking_move_to_xy(0.5f * ((MESH_MIN_X) + (MESH_MAX_X)), 0.5f * ((MESH_MIN_Y) + (MESH_MAX_Y))); - #endif - report_current_position(); - probe_deployed = true; - } + if (parser.seen_test('P')) { + if (WITHIN(param.P_phase, 0, 1) && storage_slot == -1) { + storage_slot = 0; + SERIAL_ECHOLNPGM("Default storage slot 0 selected."); + } - #endif // HAS_BED_PROBE + switch (param.P_phase) { + case 0: + // + // Zero Mesh Data + // + reset(); + SERIAL_ECHOLNPGM("Mesh zeroed."); + break; - if (parser.seen('P')) { - if (WITHIN(g29_phase_value, 0, 1) && storage_slot == -1) { - storage_slot = 0; - SERIAL_ECHOLNPGM("Default storage slot 0 selected."); - } + #if HAS_BED_PROBE - switch (g29_phase_value) { - case 0: + case 1: { // - // Zero Mesh Data + // Invalidate Entire Mesh and Automatically Probe Mesh in areas that can be reached by the probe // - reset(); - SERIAL_ECHOLNPGM("Mesh zeroed."); - break; - - #if HAS_BED_PROBE - - case 1: { - // - // Invalidate Entire Mesh and Automatically Probe Mesh in areas that can be reached by the probe - // - if (!parser.seen('C')) { - invalidate(); - SERIAL_ECHOLNPGM("Mesh invalidated. Probing mesh."); - } - if (g29_verbose_level > 1) { - SERIAL_ECHOPAIR("Probing around (", g29_pos.x); - SERIAL_CHAR(','); - SERIAL_DECIMAL(g29_pos.y); - SERIAL_ECHOLNPGM(").\n"); - } - const xy_pos_t near_probe_xy = g29_pos + probe.offset_xy; - probe_entire_mesh(near_probe_xy, parser.seen('T'), parser.seen('E'), parser.seen('U')); + if (!parser.seen_test('C')) { + invalidate(); + SERIAL_ECHOLNPGM("Mesh invalidated. Probing mesh."); + } + if (param.V_verbosity > 1) { + SERIAL_ECHOPAIR("Probing around (", param.XY_pos.x); + SERIAL_CHAR(','); + SERIAL_DECIMAL(param.XY_pos.y); + SERIAL_ECHOLNPGM(").\n"); + } + probe_entire_mesh(param.XY_pos, parser.seen_test('T'), parser.seen_test('E'), parser.seen_test('U')); - report_current_position(); - probe_deployed = true; - } break; - - #endif // HAS_BED_PROBE - - case 2: { - #if HAS_LCD_MENU - // - // Manually Probe Mesh in areas that can't be reached by the probe - // - SERIAL_ECHOLNPGM("Manually probing unreachable points."); - do_z_clearance(Z_CLEARANCE_BETWEEN_PROBES); - - if (parser.seen('C') && !xy_seen) { - - /** - * Use a good default location for the path. - * The flipped > and < operators in these comparisons is intentional. - * It should cause the probed points to follow a nice path on Cartesian printers. - * It may make sense to have Delta printers default to the center of the bed. - * Until that is decided, this can be forced with the X and Y parameters. - */ - g29_pos.set( - #if IS_KINEMATIC - X_HOME_POS, Y_HOME_POS - #else - probe.offset_xy.x > 0 ? X_BED_SIZE : 0, - probe.offset_xy.y < 0 ? Y_BED_SIZE : 0 - #endif - ); - } + report_current_position(); + probe_deployed = true; + } break; - if (parser.seen('B')) { - g29_card_thickness = parser.has_value() ? parser.value_float() : measure_business_card_thickness(float(Z_CLEARANCE_BETWEEN_PROBES)); - if (ABS(g29_card_thickness) > 1.5f) { - SERIAL_ECHOLNPGM("?Error in Business Card measurement."); - return; - } - probe_deployed = true; - } + #endif // HAS_BED_PROBE - if (!position_is_reachable(g29_pos)) { - SERIAL_ECHOLNPGM("XY outside printable radius."); + case 2: { + #if HAS_LCD_MENU + // + // Manually Probe Mesh in areas that can't be reached by the probe + // + SERIAL_ECHOLNPGM("Manually probing unreachable points."); + do_z_clearance(Z_CLEARANCE_BETWEEN_PROBES); + + if (parser.seen_test('C') && !param.XY_seen) { + + /** + * Use a good default location for the path. + * The flipped > and < operators in these comparisons is intentional. + * It should cause the probed points to follow a nice path on Cartesian printers. + * It may make sense to have Delta printers default to the center of the bed. + * Until that is decided, this can be forced with the X and Y parameters. + */ + param.XY_pos.set( + #if IS_KINEMATIC + X_HOME_POS, Y_HOME_POS + #else + probe.offset_xy.x > 0 ? X_BED_SIZE : 0, + probe.offset_xy.y < 0 ? Y_BED_SIZE : 0 + #endif + ); + } + + if (parser.seen('B')) { + param.B_shim_thickness = parser.has_value() ? parser.value_float() : measure_business_card_thickness(); + if (ABS(param.B_shim_thickness) > 1.5f) { + SERIAL_ECHOLNPGM("?Error in Business Card measurement."); return; } + probe_deployed = true; + } - const float height = parser.floatval('H', Z_CLEARANCE_BETWEEN_PROBES); - manually_probe_remaining_mesh(g29_pos, height, g29_card_thickness, parser.seen('T')); + if (!position_is_reachable(param.XY_pos)) { + SERIAL_ECHOLNPGM("XY outside printable radius."); + return; + } - SERIAL_ECHOLNPGM("G29 P2 finished."); + const float height = parser.floatval('H', Z_CLEARANCE_BETWEEN_PROBES); + manually_probe_remaining_mesh(param.XY_pos, height, param.B_shim_thickness, parser.seen_test('T')); - report_current_position(); + SERIAL_ECHOLNPGM("G29 P2 finished."); - #else + report_current_position(); - SERIAL_ECHOLNPGM("?P2 is only available when an LCD is present."); - return; + #else - #endif - } break; + SERIAL_ECHOLNPGM("?P2 is only available when an LCD is present."); + return; - case 3: { - /** - * Populate invalid mesh areas. Proceed with caution. - * Two choices are available: - * - Specify a constant with the 'C' parameter. - * - Allow 'G29 P3' to choose a 'reasonable' constant. - */ - - if (g29_c_flag) { - if (g29_repetition_cnt >= GRID_MAX_POINTS) { - set_all_mesh_points_to_value(g29_constant); - } - else { - while (g29_repetition_cnt--) { // this only populates reachable mesh points near - const mesh_index_pair closest = find_closest_mesh_point_of_type(INVALID, g29_pos); - const xy_int8_t &cpos = closest.pos; - if (cpos.x < 0) { - // No more REAL INVALID mesh points to populate, so we ASSUME - // user meant to populate ALL INVALID mesh points to value - GRID_LOOP(x, y) if (isnan(z_values[x][y])) z_values[x][y] = g29_constant; - break; // No more invalid Mesh Points to populate - } - else { - z_values[cpos.x][cpos.y] = g29_constant; - TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(cpos, g29_constant)); - } - } - } + #endif + } break; + + case 3: { + /** + * Populate invalid mesh areas. Proceed with caution. + * Two choices are available: + * - Specify a constant with the 'C' parameter. + * - Allow 'G29 P3' to choose a 'reasonable' constant. + */ + + if (param.C_seen) { + if (param.R_repetition >= GRID_MAX_POINTS) { + set_all_mesh_points_to_value(param.C_constant); } else { - const float cvf = parser.value_float(); - switch ((int)truncf(cvf * 10.0f) - 30) { // 3.1 -> 1 - #if ENABLED(UBL_G29_P31) - case 1: { - - // P3.1 use least squares fit to fill missing mesh values - // P3.10 zero weighting for distance, all grid points equal, best fit tilted plane - // P3.11 10X weighting for nearest grid points versus farthest grid points - // P3.12 100X distance weighting - // P3.13 1000X distance weighting, approaches simple average of nearest points - - const float weight_power = (cvf - 3.10f) * 100.0f, // 3.12345 -> 2.345 - weight_factor = weight_power ? POW(10.0f, weight_power) : 0; - smart_fill_wlsf(weight_factor); - } - break; - #endif - case 0: // P3 or P3.0 - default: // and anything P3.x that's not P3.1 - smart_fill_mesh(); // Do a 'Smart' fill using nearby known values - break; + while (param.R_repetition--) { // this only populates reachable mesh points near + const mesh_index_pair closest = find_closest_mesh_point_of_type(INVALID, param.XY_pos); + const xy_int8_t &cpos = closest.pos; + if (cpos.x < 0) { + // No more REAL INVALID mesh points to populate, so we ASSUME + // user meant to populate ALL INVALID mesh points to value + GRID_LOOP(x, y) if (isnan(z_values[x][y])) z_values[x][y] = param.C_constant; + break; // No more invalid Mesh Points to populate + } + else { + z_values[cpos.x][cpos.y] = param.C_constant; + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(cpos, param.C_constant)); + } } } - break; } - - case 4: // Fine Tune (i.e., Edit) the Mesh - #if HAS_LCD_MENU - fine_tune_mesh(g29_pos, parser.seen('T')); - #else - SERIAL_ECHOLNPGM("?P4 is only available when an LCD is present."); - return; - #endif - break; - - case 5: adjust_mesh_to_mean(g29_c_flag, g29_constant); break; - - case 6: shift_mesh_height(); break; + else { + const float cvf = parser.value_float(); + switch ((int)TRUNC(cvf * 10.0f) - 30) { // 3.1 -> 1 + #if ENABLED(UBL_G29_P31) + case 1: { + + // P3.1 use least squares fit to fill missing mesh values + // P3.10 zero weighting for distance, all grid points equal, best fit tilted plane + // P3.11 10X weighting for nearest grid points versus farthest grid points + // P3.12 100X distance weighting + // P3.13 1000X distance weighting, approaches simple average of nearest points + + const float weight_power = (cvf - 3.10f) * 100.0f, // 3.12345 -> 2.345 + weight_factor = weight_power ? POW(10.0f, weight_power) : 0; + smart_fill_wlsf(weight_factor); + } + break; + #endif + case 0: // P3 or P3.0 + default: // and anything P3.x that's not P3.1 + smart_fill_mesh(); // Do a 'Smart' fill using nearby known values + break; + } + } + break; } - } - #if ENABLED(UBL_DEVEL_DEBUGGING) - - // - // Much of the 'What?' command can be eliminated. But until we are fully debugged, it is - // good to have the extra information. Soon... we prune this to just a few items - // - if (parser.seen('W')) g29_what_command(); + case 4: // Fine Tune (i.e., Edit) the Mesh + #if HAS_LCD_MENU + fine_tune_mesh(param.XY_pos, parser.seen_test('T')); + #else + SERIAL_ECHOLNPGM("?P4 is only available when an LCD is present."); + return; + #endif + break; - // - // When we are fully debugged, this may go away. But there are some valid - // use cases for the users. So we can wait and see what to do with it. - // + case 5: adjust_mesh_to_mean(param.C_seen, param.C_constant); break; - if (parser.seen('K')) // Kompare Current Mesh Data to Specified Stored Mesh - g29_compare_current_mesh_to_stored_mesh(); + case 6: shift_mesh_height(); break; + } + } - #endif // UBL_DEVEL_DEBUGGING + #if ENABLED(UBL_DEVEL_DEBUGGING) + // + // Much of the 'What?' command can be eliminated. But until we are fully debugged, it is + // good to have the extra information. Soon... we prune this to just a few items + // + if (parser.seen_test('W')) g29_what_command(); // - // Load a Mesh from the EEPROM + // When we are fully debugged, this may go away. But there are some valid + // use cases for the users. So we can wait and see what to do with it. // - if (parser.seen('L')) { // Load Current Mesh Data - g29_storage_slot = parser.has_value() ? parser.value_int() : storage_slot; + if (parser.seen('K')) // Kompare Current Mesh Data to Specified Stored Mesh + g29_compare_current_mesh_to_stored_mesh(); - int16_t a = settings.calc_num_meshes(); + #endif // UBL_DEVEL_DEBUGGING - if (!a) { - SERIAL_ECHOLNPGM("?EEPROM storage not available."); - return; - } - if (!WITHIN(g29_storage_slot, 0, a - 1)) { - SERIAL_ECHOLNPAIR("?Invalid storage slot.\n?Use 0 to ", a - 1); - return; - } + // + // Load a Mesh from the EEPROM + // - settings.load_mesh(g29_storage_slot); - storage_slot = g29_storage_slot; + if (parser.seen('L')) { // Load Current Mesh Data + param.KLS_storage_slot = parser.has_value() ? (int8_t)parser.value_int() : storage_slot; - SERIAL_ECHOLNPGM("Done."); + int16_t a = settings.calc_num_meshes(); + + if (!a) { + SERIAL_ECHOLNPGM("?EEPROM storage not available."); + return; } - // - // Store a Mesh in the EEPROM - // + if (!WITHIN(param.KLS_storage_slot, 0, a - 1)) { + SERIAL_ECHOLNPAIR("?Invalid storage slot.\n?Use 0 to ", a - 1); + return; + } - if (parser.seen('S')) { // Store (or Save) Current Mesh Data - g29_storage_slot = parser.has_value() ? parser.value_int() : storage_slot; + settings.load_mesh(param.KLS_storage_slot); + storage_slot = param.KLS_storage_slot; - if (g29_storage_slot == -1) // Special case, the user wants to 'Export' the mesh to the - return report_current_mesh(); // host program to be saved on the user's computer + SERIAL_ECHOLNPGM("Done."); + } - int16_t a = settings.calc_num_meshes(); + // + // Store a Mesh in the EEPROM + // - if (!a) { - SERIAL_ECHOLNPGM("?EEPROM storage not available."); - goto LEAVE; - } + if (parser.seen('S')) { // Store (or Save) Current Mesh Data + param.KLS_storage_slot = parser.has_value() ? (int8_t)parser.value_int() : storage_slot; - if (!WITHIN(g29_storage_slot, 0, a - 1)) { - SERIAL_ECHOLNPAIR("?Invalid storage slot.\n?Use 0 to ", a - 1); - goto LEAVE; - } + if (param.KLS_storage_slot == -1) // Special case: 'Export' the mesh to the + return report_current_mesh(); // host so it can be saved in a file. - settings.store_mesh(g29_storage_slot); - storage_slot = g29_storage_slot; + int16_t a = settings.calc_num_meshes(); - SERIAL_ECHOLNPGM("Done."); + if (!a) { + SERIAL_ECHOLNPGM("?EEPROM storage not available."); + goto LEAVE; } - if (parser.seen('T')) - display_map(g29_map_type); + if (!WITHIN(param.KLS_storage_slot, 0, a - 1)) { + SERIAL_ECHOLNPAIR("?Invalid storage slot.\n?Use 0 to ", a - 1); + goto LEAVE; + } - LEAVE: + settings.store_mesh(param.KLS_storage_slot); + storage_slot = param.KLS_storage_slot; - #if HAS_LCD_MENU - ui.reset_alert_level(); - ui.quick_feedback(); - ui.reset_status(); - ui.release(); - #endif + SERIAL_ECHOLNPGM("Done."); + } - #ifdef Z_PROBE_END_SCRIPT - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Z Probe End Script: ", Z_PROBE_END_SCRIPT); - if (probe_deployed) { - planner.synchronize(); - gcode.process_subcommands_now_P(PSTR(Z_PROBE_END_SCRIPT)); - } - #else - UNUSED(probe_deployed); - #endif + if (parser.seen_test('T')) + display_map(param.T_map_type); - TERN_(HAS_MULTI_HOTEND, tool_change(old_tool_index)); - return; - } + LEAVE: - void unified_bed_leveling::adjust_mesh_to_mean(const bool cflag, const float value) { - float sum = 0; - int n = 0; - GRID_LOOP(x, y) - if (!isnan(z_values[x][y])) { - sum += z_values[x][y]; - n++; - } + #if HAS_LCD_MENU + ui.reset_alert_level(); + ui.quick_feedback(); + ui.reset_status(); + ui.release(); + #endif - const float mean = sum / n; + #ifdef Z_PROBE_END_SCRIPT + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Z Probe End Script: ", Z_PROBE_END_SCRIPT); + if (probe_deployed) { + planner.synchronize(); + gcode.process_subcommands_now_P(PSTR(Z_PROBE_END_SCRIPT)); + } + #else + UNUSED(probe_deployed); + #endif - // - // Sum the squares of difference from mean - // - float sum_of_diff_squared = 0; - GRID_LOOP(x, y) - if (!isnan(z_values[x][y])) - sum_of_diff_squared += sq(z_values[x][y] - mean); + TERN_(HAS_MULTI_HOTEND, tool_change(old_tool_index)); + return; +} - SERIAL_ECHOLNPAIR("# of samples: ", n); - SERIAL_ECHOLNPAIR_F("Mean Mesh Height: ", mean, 6); +/** + * M420 C + * G29 P5 C : Adjust Mesh To Mean (and subtract the given offset). + * Find the mean average and shift the mesh to center on that value. + */ +void unified_bed_leveling::adjust_mesh_to_mean(const bool cflag, const_float_t offset) { + float sum = 0; + uint8_t n = 0; + GRID_LOOP(x, y) + if (!isnan(z_values[x][y])) { + sum += z_values[x][y]; + n++; + } - const float sigma = SQRT(sum_of_diff_squared / (n + 1)); - SERIAL_ECHOLNPAIR_F("Standard Deviation: ", sigma, 6); + const float mean = sum / n; - if (cflag) - GRID_LOOP(x, y) - if (!isnan(z_values[x][y])) { - z_values[x][y] -= mean + value; - TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, z_values[x][y])); - } - } + // + // Sum the squares of difference from mean + // + float sum_of_diff_squared = 0; + GRID_LOOP(x, y) + if (!isnan(z_values[x][y])) + sum_of_diff_squared += sq(z_values[x][y] - mean); - void unified_bed_leveling::shift_mesh_height() { + SERIAL_ECHOLNPAIR("# of samples: ", n); + SERIAL_ECHOLNPAIR_F("Mean Mesh Height: ", mean, 6); + + const float sigma = SQRT(sum_of_diff_squared / (n + 1)); + SERIAL_ECHOLNPAIR_F("Standard Deviation: ", sigma, 6); + + if (cflag) GRID_LOOP(x, y) if (!isnan(z_values[x][y])) { - z_values[x][y] += g29_constant; + z_values[x][y] -= mean + offset; TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, z_values[x][y])); } - } - - #if HAS_BED_PROBE - /** - * Probe all invalidated locations of the mesh that can be reached by the probe. - * This attempts to fill in locations closest to the nozzle's start location first. - */ - void unified_bed_leveling::probe_entire_mesh(const xy_pos_t &near, const bool do_ubl_mesh_map, const bool stow_probe, const bool do_furthest) { - probe.deploy(); // Deploy before ui.capture() to allow for PAUSE_BEFORE_DEPLOY_STOW - - TERN_(HAS_LCD_MENU, ui.capture()); - - save_ubl_active_state_and_disable(); // No bed level correction so only raw data is obtained - uint8_t count = GRID_MAX_POINTS; +} - mesh_index_pair best; - TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(best.pos, ExtUI::MESH_START)); - do { - if (do_ubl_mesh_map) display_map(g29_map_type); +/** + * G29 P6 C : Shift Mesh Height by a uniform constant. + */ +void unified_bed_leveling::shift_mesh_height() { + GRID_LOOP(x, y) + if (!isnan(z_values[x][y])) { + z_values[x][y] += param.C_constant; + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, z_values[x][y])); + } +} - const int point_num = (GRID_MAX_POINTS) - count + 1; - SERIAL_ECHOLNPAIR("\nProbing mesh point ", point_num, "/", int(GRID_MAX_POINTS), ".\n"); - TERN_(HAS_DISPLAY, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_MESH), point_num, int(GRID_MAX_POINTS))); +#if HAS_BED_PROBE + /** + * G29 P1 T V : Probe Entire Mesh + * Probe all invalidated locations of the mesh that can be reached by the probe. + * This attempts to fill in locations closest to the nozzle's start location first. + */ + void unified_bed_leveling::probe_entire_mesh(const xy_pos_t &nearby, const bool do_ubl_mesh_map, const bool stow_probe, const bool do_furthest) { + probe.deploy(); // Deploy before ui.capture() to allow for PAUSE_BEFORE_DEPLOY_STOW + + TERN_(HAS_LCD_MENU, ui.capture()); + + save_ubl_active_state_and_disable(); // No bed level correction so only raw data is obtained + uint8_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; + SERIAL_ECHOLNPAIR("Probing mesh point ", point_num, "/", GRID_MAX_POINTS, "."); + TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_MESH), point_num, int(GRID_MAX_POINTS))); + + #if HAS_LCD_MENU + if (ui.button_pressed()) { + ui.quick_feedback(false); // Preserve button state for click-and-hold + SERIAL_ECHOLNPGM("\nMesh only partially populated.\n"); + ui.wait_for_release(); + ui.quick_feedback(); + ui.release(); + probe.stow(); // Release UI before stow to allow for PAUSE_BEFORE_DEPLOY_STOW + return restore_ubl_active_state_and_leave(); + } + #endif - #if HAS_LCD_MENU - if (ui.button_pressed()) { - ui.quick_feedback(false); // Preserve button state for click-and-hold - SERIAL_ECHOLNPGM("\nMesh only partially populated.\n"); - ui.wait_for_release(); - ui.quick_feedback(); - ui.release(); - probe.stow(); // Release UI before stow to allow for PAUSE_BEFORE_DEPLOY_STOW - return restore_ubl_active_state_and_leave(); - } + best = do_furthest + ? find_furthest_invalid_mesh_point() + : find_closest_mesh_point_of_type(INVALID, nearby, true); + + if (best.pos.x >= 0) { // mesh point found and is reachable by probe + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(best.pos, ExtUI::G29_POINT_START)); + const float measured_z = probe.probe_at_point( + best.meshpos(), + stow_probe ? PROBE_PT_STOW : PROBE_PT_RAISE, param.V_verbosity + ); + z_values[best.pos.x][best.pos.y] = measured_z; + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onMeshUpdate(best.pos, ExtUI::G29_POINT_FINISH); + ExtUI::onMeshUpdate(best.pos, measured_z); #endif + } + SERIAL_FLUSH(); // Prevent host M105 buffer overrun. - best = do_furthest - ? find_furthest_invalid_mesh_point() - : find_closest_mesh_point_of_type(INVALID, near, true); - - if (best.pos.x >= 0) { // mesh point found and is reachable by probe - TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(best.pos, ExtUI::PROBE_START)); - const float measured_z = probe.probe_at_point( - best.meshpos(), - stow_probe ? PROBE_PT_STOW : PROBE_PT_RAISE, g29_verbose_level - ); - z_values[best.pos.x][best.pos.y] = measured_z; - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(best.pos, ExtUI::PROBE_FINISH); - ExtUI::onMeshUpdate(best.pos, measured_z); - #endif - } - SERIAL_FLUSH(); // Prevent host M105 buffer overrun. - - } while (best.pos.x >= 0 && --count); + } while (best.pos.x >= 0 && --count); - TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(best.pos, ExtUI::MESH_FINISH)); + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(best.pos, ExtUI::G29_FINISH)); - // Release UI during stow to allow for PAUSE_BEFORE_DEPLOY_STOW - TERN_(HAS_LCD_MENU, ui.release()); - probe.stow(); - TERN_(HAS_LCD_MENU, ui.capture()); + // Release UI during stow to allow for PAUSE_BEFORE_DEPLOY_STOW + TERN_(HAS_LCD_MENU, ui.release()); + probe.stow(); + TERN_(HAS_LCD_MENU, ui.capture()); - probe.move_z_after_probing(); + probe.move_z_after_probing(); - restore_ubl_active_state_and_leave(); + restore_ubl_active_state_and_leave(); - do_blocking_move_to_xy( - constrain(near.x - probe.offset_xy.x, MESH_MIN_X, MESH_MAX_X), - constrain(near.y - probe.offset_xy.y, MESH_MIN_Y, MESH_MAX_Y) - ); - } + do_blocking_move_to_xy( + constrain(nearby.x - probe.offset_xy.x, MESH_MIN_X, MESH_MAX_X), + constrain(nearby.y - probe.offset_xy.y, MESH_MIN_Y, MESH_MAX_Y) + ); + } - #endif // HAS_BED_PROBE +#endif // HAS_BED_PROBE +void set_message_with_feedback(PGM_P const msg_P) { #if HAS_LCD_MENU - - typedef void (*clickFunc_t)(); - - bool click_and_hold(const clickFunc_t func=nullptr) { - if (ui.button_pressed()) { - ui.quick_feedback(false); // Preserve button state for click-and-hold - const millis_t nxt = millis() + 1500UL; - while (ui.button_pressed()) { // Loop while the encoder is pressed. Uses hardware flag! - idle(); // idle, of course - if (ELAPSED(millis(), nxt)) { // After 1.5 seconds - ui.quick_feedback(); - if (func) (*func)(); - ui.wait_for_release(); - return true; - } + ui.set_status_P(msg_P); + ui.quick_feedback(); + #else + UNUSED(msg_P); + #endif +} + +#if HAS_LCD_MENU + + typedef void (*clickFunc_t)(); + + bool _click_and_hold(const clickFunc_t func=nullptr) { + if (ui.button_pressed()) { + ui.quick_feedback(false); // Preserve button state for click-and-hold + const millis_t nxt = millis() + 1500UL; + while (ui.button_pressed()) { // Loop while the encoder is pressed. Uses hardware flag! + idle(); // idle, of course + if (ELAPSED(millis(), nxt)) { // After 1.5 seconds + ui.quick_feedback(); + if (func) (*func)(); + ui.wait_for_release(); + return true; } } - serial_delay(15); - return false; } + serial_delay(15); + return false; + } - void unified_bed_leveling::move_z_with_encoder(const float &multiplier) { - ui.wait_for_release(); - while (!ui.button_pressed()) { - idle(); - gcode.reset_stepper_timeout(); // Keep steppers powered - if (encoder_diff) { - do_blocking_move_to_z(current_position.z + float(encoder_diff) * multiplier); - encoder_diff = 0; - } + void unified_bed_leveling::move_z_with_encoder(const_float_t multiplier) { + ui.wait_for_release(); + while (!ui.button_pressed()) { + idle(); + gcode.reset_stepper_timeout(); // Keep steppers powered + if (encoder_diff) { + do_blocking_move_to_z(current_position.z + float(encoder_diff) * multiplier); + encoder_diff = 0; } } + } - float unified_bed_leveling::measure_point_with_encoder() { - KEEPALIVE_STATE(PAUSED_FOR_USER); - move_z_with_encoder(0.01f); - return current_position.z; - } + float unified_bed_leveling::measure_point_with_encoder() { + KEEPALIVE_STATE(PAUSED_FOR_USER); + const float z_step = 0.01f; + move_z_with_encoder(z_step); + return current_position.z; + } - static void echo_and_take_a_measurement() { SERIAL_ECHOLNPGM(" and take a measurement."); } + static void echo_and_take_a_measurement() { SERIAL_ECHOLNPGM(" and take a measurement."); } - float unified_bed_leveling::measure_business_card_thickness(float in_height) { - ui.capture(); - save_ubl_active_state_and_disable(); // Disable bed level correction for probing + float unified_bed_leveling::measure_business_card_thickness() { + ui.capture(); + save_ubl_active_state_and_disable(); // Disable bed level correction for probing - do_blocking_move_to(0.5f * (MESH_MAX_X - (MESH_MIN_X)), 0.5f * (MESH_MAX_Y - (MESH_MIN_Y)), in_height); - //, _MIN(planner.settings.max_feedrate_mm_s[X_AXIS], planner.settings.max_feedrate_mm_s[Y_AXIS]) * 0.5f); - planner.synchronize(); + do_blocking_move_to(0.5f * (MESH_MAX_X - (MESH_MIN_X)), 0.5f * (MESH_MAX_Y - (MESH_MIN_Y)), MANUAL_PROBE_START_Z); + //, _MIN(planner.settings.max_feedrate_mm_s[X_AXIS], planner.settings.max_feedrate_mm_s[Y_AXIS]) * 0.5f); + planner.synchronize(); - SERIAL_ECHOPGM("Place shim under nozzle"); - LCD_MESSAGEPGM(MSG_UBL_BC_INSERT); - ui.return_to_status(); - echo_and_take_a_measurement(); + SERIAL_ECHOPGM("Place shim under nozzle"); + LCD_MESSAGEPGM(MSG_UBL_BC_INSERT); + ui.return_to_status(); + echo_and_take_a_measurement(); - const float z1 = measure_point_with_encoder(); - do_blocking_move_to_z(current_position.z + SIZE_OF_LITTLE_RAISE); - planner.synchronize(); + const float z1 = measure_point_with_encoder(); + do_blocking_move_to_z(current_position.z + SIZE_OF_LITTLE_RAISE); + planner.synchronize(); - SERIAL_ECHOPGM("Remove shim"); - LCD_MESSAGEPGM(MSG_UBL_BC_REMOVE); - echo_and_take_a_measurement(); + SERIAL_ECHOPGM("Remove shim"); + LCD_MESSAGEPGM(MSG_UBL_BC_REMOVE); + echo_and_take_a_measurement(); - const float z2 = measure_point_with_encoder(); - do_blocking_move_to_z(current_position.z + Z_CLEARANCE_BETWEEN_PROBES); + const float z2 = measure_point_with_encoder(); + do_blocking_move_to_z(current_position.z + Z_CLEARANCE_BETWEEN_PROBES); - const float thickness = ABS(z1 - z2); + const float thickness = ABS(z1 - z2); - if (g29_verbose_level > 1) { - SERIAL_ECHOPAIR_F("Business Card is ", thickness, 4); - SERIAL_ECHOLNPGM("mm thick."); - } + if (param.V_verbosity > 1) { + SERIAL_ECHOPAIR_F("Business Card is ", thickness, 4); + SERIAL_ECHOLNPGM("mm thick."); + } - restore_ubl_active_state_and_leave(); + restore_ubl_active_state_and_leave(); - return thickness; - } + return thickness; + } - void unified_bed_leveling::manually_probe_remaining_mesh(const xy_pos_t &pos, const float &z_clearance, const float &thick, const bool do_ubl_mesh_map) { - ui.capture(); + /** + * G29 P2 : Manually Probe Remaining Mesh Points. + * Move to INVALID points and + * NOTE: Blocks the G-code queue and captures Marlin UI during use. + */ + void unified_bed_leveling::manually_probe_remaining_mesh(const xy_pos_t &pos, const_float_t z_clearance, const_float_t thick, const bool do_ubl_mesh_map) { + ui.capture(); - save_ubl_active_state_and_disable(); // No bed level correction so only raw data is obtained - do_blocking_move_to_xy_z(current_position, z_clearance); + save_ubl_active_state_and_disable(); // No bed level correction so only raw data is obtained + do_blocking_move_to_xy_z(current_position, z_clearance); - ui.return_to_status(); + ui.return_to_status(); - mesh_index_pair location; - const xy_int8_t &lpos = location.pos; - do { - location = find_closest_mesh_point_of_type(INVALID, pos); - // It doesn't matter if the probe can't reach the NAN location. This is a manual probe. - if (!location.valid()) continue; - - const xyz_pos_t ppos = { - mesh_index_to_xpos(lpos.x), - mesh_index_to_ypos(lpos.y), - Z_CLEARANCE_BETWEEN_PROBES - }; + mesh_index_pair location; + const xy_int8_t &lpos = location.pos; + do { + location = find_closest_mesh_point_of_type(INVALID, pos); + // It doesn't matter if the probe can't reach the NAN location. This is a manual probe. + if (!location.valid()) continue; - if (!position_is_reachable(ppos)) break; // SHOULD NOT OCCUR (find_closest_mesh_point only returns reachable points) + const xyz_pos_t ppos = { + mesh_index_to_xpos(lpos.x), + mesh_index_to_ypos(lpos.y), + z_clearance + }; - LCD_MESSAGEPGM(MSG_UBL_MOVING_TO_NEXT); + if (!position_is_reachable(ppos)) break; // SHOULD NOT OCCUR (find_closest_mesh_point only returns reachable points) - do_blocking_move_to(ppos); - do_z_clearance(z_clearance); + LCD_MESSAGEPGM(MSG_UBL_MOVING_TO_NEXT); - KEEPALIVE_STATE(PAUSED_FOR_USER); - ui.capture(); + do_blocking_move_to(ppos); + do_z_clearance(z_clearance); - if (do_ubl_mesh_map) display_map(g29_map_type); // show user where we're probing + KEEPALIVE_STATE(PAUSED_FOR_USER); + ui.capture(); - serialprintPGM(parser.seen('B') ? GET_TEXT(MSG_UBL_BC_INSERT) : GET_TEXT(MSG_UBL_BC_INSERT2)); + if (do_ubl_mesh_map) display_map(param.T_map_type); // Show user where we're probing - const float z_step = 0.01f; // existing behavior: 0.01mm per click, occasionally step - //const float z_step = planner.steps_to_mm[Z_AXIS]; // approx one step each click + if (parser.seen_test('B')) { + SERIAL_ECHOPGM("Place Shim & Measure"); + LCD_MESSAGEPGM(MSG_UBL_BC_INSERT); + } + else { + SERIAL_ECHOPGM("Measure"); + LCD_MESSAGEPGM(MSG_UBL_BC_INSERT2); + } - move_z_with_encoder(z_step); + const float z_step = 0.01f; // 0.01mm per encoder tick, occasionally step + move_z_with_encoder(z_step); - if (click_and_hold()) { - SERIAL_ECHOLNPGM("\nMesh only partially populated."); - do_z_clearance(Z_CLEARANCE_DEPLOY_PROBE); - return restore_ubl_active_state_and_leave(); - } + if (_click_and_hold([]{ + SERIAL_ECHOLNPGM("\nMesh only partially populated."); + do_z_clearance(Z_CLEARANCE_DEPLOY_PROBE); + })) return restore_ubl_active_state_and_leave(); - z_values[lpos.x][lpos.y] = current_position.z - thick; - TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(location, z_values[lpos.x][lpos.y])); + // Store the Z position minus the shim height + z_values[lpos.x][lpos.y] = current_position.z - thick; - if (g29_verbose_level > 2) - SERIAL_ECHOLNPAIR_F("Mesh Point Measured at: ", z_values[lpos.x][lpos.y], 6); - SERIAL_FLUSH(); // Prevent host M105 buffer overrun. - } while (location.valid()); + // Tell the external UI to update + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(location, z_values[lpos.x][lpos.y])); - if (do_ubl_mesh_map) display_map(g29_map_type); // show user where we're probing + if (param.V_verbosity > 2) + SERIAL_ECHOLNPAIR_F("Mesh Point Measured at: ", z_values[lpos.x][lpos.y], 6); + SERIAL_FLUSH(); // Prevent host M105 buffer overrun. + } while (location.valid()); - restore_ubl_active_state_and_leave(); - do_blocking_move_to_xy_z(pos, Z_CLEARANCE_DEPLOY_PROBE); - } + if (do_ubl_mesh_map) display_map(param.T_map_type); // show user where we're probing - inline void set_message_with_feedback(PGM_P const msg_P) { - ui.set_status_P(msg_P); - ui.quick_feedback(); - } + restore_ubl_active_state_and_leave(); + do_blocking_move_to_xy_z(pos, Z_CLEARANCE_DEPLOY_PROBE); + } - void abort_fine_tune() { - ui.return_to_status(); - do_z_clearance(Z_CLEARANCE_BETWEEN_PROBES); - set_message_with_feedback(GET_TEXT(MSG_EDITING_STOPPED)); + /** + * G29 P4 : Mesh Fine-Tuning. Go to point(s) and adjust values with the LCD. + * NOTE: Blocks the G-code queue and captures Marlin UI during use. + */ + void unified_bed_leveling::fine_tune_mesh(const xy_pos_t &pos, const bool do_ubl_mesh_map) { + if (!parser.seen_test('R')) // fine_tune_mesh() is special. If no repetition count flag is specified + param.R_repetition = 1; // do exactly one mesh location. Otherwise use what the parser decided. + + #if ENABLED(UBL_MESH_EDIT_MOVES_Z) + const float h_offset = parser.seenval('H') ? parser.value_linear_units() : MANUAL_PROBE_START_Z; + if (!WITHIN(h_offset, 0, 10)) { + SERIAL_ECHOLNPGM("Offset out of bounds. (0 to 10mm)\n"); + return; + } + #endif + + mesh_index_pair location; + + if (!position_is_reachable(pos)) { + SERIAL_ECHOLNPGM("(X,Y) outside printable radius."); + return; } - void unified_bed_leveling::fine_tune_mesh(const xy_pos_t &pos, const bool do_ubl_mesh_map) { - if (!parser.seen('R')) // fine_tune_mesh() is special. If no repetition count flag is specified - g29_repetition_cnt = 1; // do exactly one mesh location. Otherwise use what the parser decided. + save_ubl_active_state_and_disable(); - #if ENABLED(UBL_MESH_EDIT_MOVES_Z) - const float h_offset = parser.seenval('H') ? parser.value_linear_units() : 0; - if (!WITHIN(h_offset, 0, 10)) { - SERIAL_ECHOLNPGM("Offset out of bounds. (0 to 10mm)\n"); - return; - } - #endif + LCD_MESSAGEPGM(MSG_UBL_FINE_TUNE_MESH); + ui.capture(); // Take over control of the LCD encoder - mesh_index_pair location; + do_blocking_move_to_xy_z(pos, Z_CLEARANCE_BETWEEN_PROBES); // Move to the given XY with probe clearance - if (!position_is_reachable(pos)) { - SERIAL_ECHOLNPGM("(X,Y) outside printable radius."); - return; - } + MeshFlags done_flags{0}; + const xy_int8_t &lpos = location.pos; - save_ubl_active_state_and_disable(); + #if IS_TFTGLCD_PANEL + ui.ubl_mesh_edit_start(0); // Change current screen before calling ui.ubl_plot + safe_delay(50); + #endif - LCD_MESSAGEPGM(MSG_UBL_FINE_TUNE_MESH); - ui.capture(); // Take over control of the LCD encoder + do { + location = find_closest_mesh_point_of_type(SET_IN_BITMAP, pos, false, &done_flags); - do_blocking_move_to_xy_z(pos, Z_CLEARANCE_BETWEEN_PROBES); // Move to the given XY with probe clearance + if (lpos.x < 0) break; // Stop when there are no more reachable points - TERN_(UBL_MESH_EDIT_MOVES_Z, do_blocking_move_to_z(h_offset)); // Move Z to the given 'H' offset + done_flags.mark(lpos); // Mark this location as 'adjusted' so a new + // location is used on the next loop + const xyz_pos_t raw = { + mesh_index_to_xpos(lpos.x), + mesh_index_to_ypos(lpos.y), + Z_CLEARANCE_BETWEEN_PROBES + }; - MeshFlags done_flags{0}; - const xy_int8_t &lpos = location.pos; - do { - location = find_closest_mesh_point_of_type(SET_IN_BITMAP, pos, false, &done_flags); + if (!position_is_reachable(raw)) break; // SHOULD NOT OCCUR (find_closest_mesh_point_of_type only returns reachable) - if (lpos.x < 0) break; // Stop when there are no more reachable points + do_blocking_move_to(raw); // Move the nozzle to the edit point with probe clearance - done_flags.mark(lpos); // Mark this location as 'adjusted' so a new - // location is used on the next loop - const xyz_pos_t raw = { - mesh_index_to_xpos(lpos.x), - mesh_index_to_ypos(lpos.y), - Z_CLEARANCE_BETWEEN_PROBES - }; + TERN_(UBL_MESH_EDIT_MOVES_Z, do_blocking_move_to_z(h_offset)); // Move Z to the given 'H' offset before editing - if (!position_is_reachable(raw)) break; // SHOULD NOT OCCUR (find_closest_mesh_point_of_type only returns reachable) + KEEPALIVE_STATE(PAUSED_FOR_USER); - do_blocking_move_to(raw); // Move the nozzle to the edit point with probe clearance + if (do_ubl_mesh_map) display_map(param.T_map_type); // Display the current point - TERN_(UBL_MESH_EDIT_MOVES_Z, do_blocking_move_to_z(h_offset)); // Move Z to the given 'H' offset before editing + #if IS_TFTGLCD_PANEL + ui.ubl_plot(lpos.x, lpos.y); // update plot screen + #endif - KEEPALIVE_STATE(PAUSED_FOR_USER); + ui.refresh(); - if (do_ubl_mesh_map) display_map(g29_map_type); // Display the current point + float new_z = z_values[lpos.x][lpos.y]; + if (isnan(new_z)) new_z = 0; // Invalid points begin at 0 + new_z = FLOOR(new_z * 1000) * 0.001f; // Chop off digits after the 1000ths place - #if IS_TFTGLCD_PANEL - ui.ubl_plot(lpos.x, lpos.y); // update plot screen - #endif + ui.ubl_mesh_edit_start(new_z); - ui.refresh(); + SET_SOFT_ENDSTOP_LOOSE(true); - float new_z = z_values[lpos.x][lpos.y]; - if (isnan(new_z)) new_z = 0; // Invalid points begin at 0 - new_z = FLOOR(new_z * 1000) * 0.001f; // Chop off digits after the 1000ths place + do { + idle_no_sleep(); + new_z = ui.ubl_mesh_value(); + TERN_(UBL_MESH_EDIT_MOVES_Z, do_blocking_move_to_z(h_offset + new_z)); // Move the nozzle as the point is edited + SERIAL_FLUSH(); // Prevent host M105 buffer overrun. + } while (!ui.button_pressed()); - lcd_mesh_edit_setup(new_z); + SET_SOFT_ENDSTOP_LOOSE(false); - SET_SOFT_ENDSTOP_LOOSE(true); + if (!lcd_map_control) ui.return_to_status(); // Just editing a single point? Return to status - do { - idle(); - new_z = lcd_mesh_edit(); - TERN_(UBL_MESH_EDIT_MOVES_Z, do_blocking_move_to_z(h_offset + new_z)); // Move the nozzle as the point is edited - SERIAL_FLUSH(); // Prevent host M105 buffer overrun. - } while (!ui.button_pressed()); + // Button held down? Abort editing + if (_click_and_hold([]{ + ui.return_to_status(); + do_z_clearance(Z_CLEARANCE_BETWEEN_PROBES); + set_message_with_feedback(GET_TEXT(MSG_EDITING_STOPPED)); + })) break; - SET_SOFT_ENDSTOP_LOOSE(false); + // TODO: Disable leveling here so the Z value becomes the 'native' Z value. - if (!lcd_map_control) ui.return_to_status(); // Just editing a single point? Return to status + z_values[lpos.x][lpos.y] = new_z; // Save the updated Z value - if (click_and_hold(abort_fine_tune)) break; // Button held down? Abort editing + // TODO: Re-enable leveling here so Z is correctly based on the updated mesh. - z_values[lpos.x][lpos.y] = new_z; // Save the updated Z value - TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(location, new_z)); + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(location, new_z)); - serial_delay(20); // No switch noise - ui.refresh(); + serial_delay(20); // No switch noise + ui.refresh(); - } while (lpos.x >= 0 && --g29_repetition_cnt > 0); + } while (lpos.x >= 0 && --param.R_repetition > 0); - if (do_ubl_mesh_map) display_map(g29_map_type); - restore_ubl_active_state_and_leave(); + if (do_ubl_mesh_map) display_map(param.T_map_type); + restore_ubl_active_state_and_leave(); - do_blocking_move_to_xy_z(pos, Z_CLEARANCE_BETWEEN_PROBES); + do_blocking_move_to_xy_z(pos, Z_CLEARANCE_BETWEEN_PROBES); - LCD_MESSAGEPGM(MSG_UBL_DONE_EDITING_MESH); - SERIAL_ECHOLNPGM("Done Editing Mesh"); + LCD_MESSAGEPGM(MSG_UBL_DONE_EDITING_MESH); + SERIAL_ECHOLNPGM("Done Editing Mesh"); - if (lcd_map_control) - ui.goto_screen(ubl_map_screen); - else - ui.return_to_status(); - } + if (lcd_map_control) + ui.goto_screen(ubl_map_screen); + else + ui.return_to_status(); + } - #endif // HAS_LCD_MENU +#endif // HAS_LCD_MENU - bool unified_bed_leveling::g29_parameter_parsing() { - bool err_flag = false; +/** + * Parse and validate most G29 parameters, store for use by G29 functions. + */ +bool unified_bed_leveling::G29_parse_parameters() { + bool err_flag = false; - TERN_(HAS_LCD_MENU, set_message_with_feedback(GET_TEXT(MSG_UBL_DOING_G29))); + set_message_with_feedback(GET_TEXT(MSG_UBL_DOING_G29)); - g29_constant = 0; - g29_repetition_cnt = 0; + param.C_constant = 0; + param.R_repetition = 0; - if (parser.seen('R')) { - g29_repetition_cnt = parser.has_value() ? parser.value_int() : GRID_MAX_POINTS; - NOMORE(g29_repetition_cnt, GRID_MAX_POINTS); - if (g29_repetition_cnt < 1) { - SERIAL_ECHOLNPGM("?(R)epetition count invalid (1+).\n"); - return UBL_ERR; - } + if (parser.seen('R')) { + param.R_repetition = parser.has_value() ? parser.value_byte() : GRID_MAX_POINTS; + NOMORE(param.R_repetition, GRID_MAX_POINTS); + if (param.R_repetition < 1) { + SERIAL_ECHOLNPGM("?(R)epetition count invalid (1+).\n"); + return UBL_ERR; } + } - g29_verbose_level = parser.seen('V') ? parser.value_int() : 0; - if (!WITHIN(g29_verbose_level, 0, 4)) { - SERIAL_ECHOLNPGM("?(V)erbose level implausible (0-4).\n"); - err_flag = true; - } + param.V_verbosity = parser.byteval('V'); + if (!WITHIN(param.V_verbosity, 0, 4)) { + SERIAL_ECHOLNPGM("?(V)erbose level implausible (0-4).\n"); + err_flag = true; + } - if (parser.seen('P')) { - const int pv = parser.value_int(); - #if !HAS_BED_PROBE - if (pv == 1) { - SERIAL_ECHOLNPGM("G29 P1 requires a probe.\n"); + if (parser.seen('P')) { + const uint8_t pv = parser.value_byte(); + #if !HAS_BED_PROBE + if (pv == 1) { + SERIAL_ECHOLNPGM("G29 P1 requires a probe.\n"); + err_flag = true; + } + else + #endif + { + param.P_phase = pv; + if (!WITHIN(param.P_phase, 0, 6)) { + SERIAL_ECHOLNPGM("?(P)hase value invalid (0-6).\n"); err_flag = true; } - else - #endif - { - g29_phase_value = pv; - if (!WITHIN(g29_phase_value, 0, 6)) { - SERIAL_ECHOLNPGM("?(P)hase value invalid (0-6).\n"); - err_flag = true; - } - } - } + } + } - if (parser.seen('J')) { - #if HAS_BED_PROBE - g29_grid_size = parser.has_value() ? parser.value_int() : 0; - if (g29_grid_size && !WITHIN(g29_grid_size, 2, 9)) { - SERIAL_ECHOLNPGM("?Invalid grid size (J) specified (2-9).\n"); - err_flag = true; - } - #else - SERIAL_ECHOLNPGM("G29 J action requires a probe.\n"); + if (parser.seen('J')) { + #if HAS_BED_PROBE + param.J_grid_size = parser.value_byte(); + if (param.J_grid_size && !WITHIN(param.J_grid_size, 2, 9)) { + SERIAL_ECHOLNPGM("?Invalid grid size (J) specified (2-9).\n"); err_flag = true; - #endif - } + } + #else + SERIAL_ECHOLNPGM("G29 J action requires a probe.\n"); + err_flag = true; + #endif + } - xy_seen.x = parser.seenval('X'); - float sx = xy_seen.x ? parser.value_float() : current_position.x; - xy_seen.y = parser.seenval('Y'); - float sy = xy_seen.y ? parser.value_float() : current_position.y; + param.XY_seen.x = parser.seenval('X'); + float sx = param.XY_seen.x ? parser.value_float() : current_position.x; + param.XY_seen.y = parser.seenval('Y'); + float sy = param.XY_seen.y ? parser.value_float() : current_position.y; - if (xy_seen.x != xy_seen.y) { - SERIAL_ECHOLNPGM("Both X & Y locations must be specified.\n"); - err_flag = true; - } + if (param.XY_seen.x != param.XY_seen.y) { + SERIAL_ECHOLNPGM("Both X & Y locations must be specified.\n"); + err_flag = true; + } - // If X or Y are not valid, use center of the bed values - if (!WITHIN(sx, X_MIN_BED, X_MAX_BED)) sx = X_CENTER; - if (!WITHIN(sy, Y_MIN_BED, Y_MAX_BED)) sy = Y_CENTER; + // If X or Y are not valid, use center of the bed values + // (for UBL_HILBERT_CURVE default to lower-left corner instead) + if (!COORDINATE_OKAY(sx, X_MIN_BED, X_MAX_BED)) sx = TERN(UBL_HILBERT_CURVE, 0, X_CENTER); + if (!COORDINATE_OKAY(sy, Y_MIN_BED, Y_MAX_BED)) sy = TERN(UBL_HILBERT_CURVE, 0, Y_CENTER); - if (err_flag) return UBL_ERR; + if (err_flag) return UBL_ERR; - g29_pos.set(sx, sy); + param.XY_pos.set(sx, sy); - /** - * Activate or deactivate UBL - * Note: UBL's G29 restores the state set here when done. - * Leveling is being enabled here with old data, possibly - * none. Error handling should disable for safety... - */ - if (parser.seen('A')) { - if (parser.seen('D')) { - SERIAL_ECHOLNPGM("?Can't activate and deactivate at the same time.\n"); - return UBL_ERR; - } - set_bed_leveling_enabled(true); - report_state(); - } - else if (parser.seen('D')) { - set_bed_leveling_enabled(false); - report_state(); + /** + * Activate or deactivate UBL + * Note: UBL's G29 restores the state set here when done. + * Leveling is being enabled here with old data, possibly + * none. Error handling should disable for safety... + */ + if (parser.seen_test('A')) { + if (parser.seen_test('D')) { + SERIAL_ECHOLNPGM("?Can't activate and deactivate at the same time.\n"); + return UBL_ERR; } + set_bed_leveling_enabled(true); + report_state(); + } + else if (parser.seen_test('D')) { + set_bed_leveling_enabled(false); + report_state(); + } - // Set global 'C' flag and its value - if ((g29_c_flag = parser.seen('C'))) - g29_constant = parser.value_float(); + // Set global 'C' flag and its value + if ((param.C_seen = parser.seen('C'))) + param.C_constant = parser.value_float(); - #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - if (parser.seenval('F')) { - const float fh = parser.value_float(); - if (!WITHIN(fh, 0, 100)) { - SERIAL_ECHOLNPGM("?(F)ade height for Bed Level Correction not plausible.\n"); - return UBL_ERR; - } - set_z_fade_height(fh); + #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) + if (parser.seenval('F')) { + const float fh = parser.value_float(); + if (!WITHIN(fh, 0, 100)) { + SERIAL_ECHOLNPGM("?(F)ade height for Bed Level Correction not plausible.\n"); + return UBL_ERR; } - #endif - - g29_map_type = parser.intval('T'); - if (!WITHIN(g29_map_type, 0, 2)) { - SERIAL_ECHOLNPGM("Invalid map type.\n"); - return UBL_ERR; + set_z_fade_height(fh); } - return UBL_OK; + #endif + + param.T_map_type = parser.byteval('T'); + if (!WITHIN(param.T_map_type, 0, 2)) { + SERIAL_ECHOLNPGM("Invalid map type.\n"); + return UBL_ERR; } + return UBL_OK; +} - static uint8_t ubl_state_at_invocation = 0; +static uint8_t ubl_state_at_invocation = 0; +#if ENABLED(UBL_DEVEL_DEBUGGING) + static uint8_t ubl_state_recursion_chk = 0; +#endif + +void unified_bed_leveling::save_ubl_active_state_and_disable() { #if ENABLED(UBL_DEVEL_DEBUGGING) - static uint8_t ubl_state_recursion_chk = 0; + ubl_state_recursion_chk++; + if (ubl_state_recursion_chk != 1) { + SERIAL_ECHOLNPGM("save_ubl_active_state_and_disabled() called multiple times in a row."); + set_message_with_feedback(GET_TEXT(MSG_UBL_SAVE_ERROR)); + return; + } #endif + ubl_state_at_invocation = planner.leveling_active; + set_bed_leveling_enabled(false); +} - void unified_bed_leveling::save_ubl_active_state_and_disable() { - #if ENABLED(UBL_DEVEL_DEBUGGING) - ubl_state_recursion_chk++; - if (ubl_state_recursion_chk != 1) { - SERIAL_ECHOLNPGM("save_ubl_active_state_and_disabled() called multiple times in a row."); - TERN_(HAS_LCD_MENU, set_message_with_feedback(GET_TEXT(MSG_UBL_SAVE_ERROR))); - return; - } - #endif - ubl_state_at_invocation = planner.leveling_active; - set_bed_leveling_enabled(false); - } - - void unified_bed_leveling::restore_ubl_active_state_and_leave() { - TERN_(HAS_LCD_MENU, ui.release()); - #if ENABLED(UBL_DEVEL_DEBUGGING) - if (--ubl_state_recursion_chk) { - SERIAL_ECHOLNPGM("restore_ubl_active_state_and_leave() called too many times."); - TERN_(HAS_LCD_MENU, set_message_with_feedback(GET_TEXT(MSG_UBL_RESTORE_ERROR))); - return; - } - #endif - set_bed_leveling_enabled(ubl_state_at_invocation); - } +void unified_bed_leveling::restore_ubl_active_state_and_leave() { + TERN_(HAS_LCD_MENU, ui.release()); + #if ENABLED(UBL_DEVEL_DEBUGGING) + if (--ubl_state_recursion_chk) { + SERIAL_ECHOLNPGM("restore_ubl_active_state_and_leave() called too many times."); + set_message_with_feedback(GET_TEXT(MSG_UBL_RESTORE_ERROR)); + return; + } + #endif + set_bed_leveling_enabled(ubl_state_at_invocation); +} - mesh_index_pair unified_bed_leveling::find_furthest_invalid_mesh_point() { +mesh_index_pair unified_bed_leveling::find_furthest_invalid_mesh_point() { - bool found_a_NAN = false, found_a_real = false; + bool found_a_NAN = false, found_a_real = false; - mesh_index_pair farthest { -1, -1, -99999.99 }; + mesh_index_pair farthest { -1, -1, -99999.99 }; - GRID_LOOP(i, j) { - if (!isnan(z_values[i][j])) continue; // Skip valid mesh points + GRID_LOOP(i, j) { + if (!isnan(z_values[i][j])) continue; // Skip valid mesh points - // Skip unreachable points - if (!probe.can_reach(mesh_index_to_xpos(i), mesh_index_to_ypos(j))) - continue; + // Skip unreachable points + if (!probe.can_reach(mesh_index_to_xpos(i), mesh_index_to_ypos(j))) + continue; - found_a_NAN = true; + found_a_NAN = true; - xy_int8_t near { -1, -1 }; - float d1, d2 = 99999.9f; - GRID_LOOP(k, l) { - if (isnan(z_values[k][l])) continue; + xy_int8_t nearby { -1, -1 }; + float d1, d2 = 99999.9f; + GRID_LOOP(k, l) { + if (isnan(z_values[k][l])) continue; - found_a_real = true; + found_a_real = true; - // Add in a random weighting factor that scrambles the probing of the - // last half of the mesh (when every unprobed mesh point is one index - // from a probed location). + // Add in a random weighting factor that scrambles the probing of the + // last half of the mesh (when every unprobed mesh point is one index + // from a probed location). - d1 = HYPOT(i - k, j - l) + (1.0f / ((millis() % 47) + 13)); + d1 = HYPOT(i - k, j - l) + (1.0f / ((millis() % 47) + 13)); - if (d1 < d2) { // Invalid mesh point (i,j) is closer to the defined point (k,l) - d2 = d1; - near.set(i, j); - } + if (d1 < d2) { // Invalid mesh point (i,j) is closer to the defined point (k,l) + d2 = d1; + nearby.set(i, j); } + } - // - // At this point d2 should have the near defined mesh point to invalid mesh point (i,j) - // + // + // At this point d2 should have the near defined mesh point to invalid mesh point (i,j) + // - if (found_a_real && near.x >= 0 && d2 > farthest.distance) { - farthest.pos = near; // Found an invalid location farther from the defined mesh point - farthest.distance = d2; - } - } // GRID_LOOP + if (found_a_real && nearby.x >= 0 && d2 > farthest.distance) { + farthest.pos = nearby; // Found an invalid location farther from the defined mesh point + farthest.distance = d2; + } + } // GRID_LOOP - if (!found_a_real && found_a_NAN) { // if the mesh is totally unpopulated, start the probing - farthest.pos.set((GRID_MAX_POINTS_X) / 2, (GRID_MAX_POINTS_Y) / 2); - farthest.distance = 1; + if (!found_a_real && found_a_NAN) { // if the mesh is totally unpopulated, start the probing + farthest.pos.set((GRID_MAX_POINTS_X) / 2, (GRID_MAX_POINTS_Y) / 2); + farthest.distance = 1; + } + return farthest; +} + +#if ENABLED(UBL_HILBERT_CURVE) + + typedef struct { + MeshPointType type; + MeshFlags *done_flags; + bool probe_relative; + mesh_index_pair closest; + } find_closest_t; + + static bool test_func(uint8_t i, uint8_t j, void *data) { + find_closest_t *d = (find_closest_t*)data; + if ( d->type == CLOSEST || d->type == (isnan(ubl.z_values[i][j]) ? INVALID : REAL) + || (d->type == SET_IN_BITMAP && !d->done_flags->marked(i, j)) + ) { + // Found a Mesh Point of the specified type! + const xy_pos_t mpos = { ubl.mesh_index_to_xpos(i), ubl.mesh_index_to_ypos(j) }; + + // If using the probe as the reference there are some unreachable locations. + // Also for round beds, there are grid points outside the bed the nozzle can't reach. + // Prune them from the list and ignore them till the next Phase (manual nozzle probing). + + if (!(d->probe_relative ? probe.can_reach(mpos) : position_is_reachable(mpos))) + return false; + d->closest.pos.set(i, j); + return true; } - return farthest; + return false; } - mesh_index_pair unified_bed_leveling::find_closest_mesh_point_of_type(const MeshPointType type, const xy_pos_t &pos, const bool probe_relative/*=false*/, MeshFlags *done_flags/*=nullptr*/) { +#endif + +mesh_index_pair unified_bed_leveling::find_closest_mesh_point_of_type(const MeshPointType type, const xy_pos_t &pos, const bool probe_relative/*=false*/, MeshFlags *done_flags/*=nullptr*/) { + + #if ENABLED(UBL_HILBERT_CURVE) + + find_closest_t d; + d.type = type; + d.done_flags = done_flags; + d.probe_relative = probe_relative; + d.closest.invalidate(); + hilbert_curve::search_from_closest(pos, test_func, &d); + return d.closest; + + #else + mesh_index_pair closest; closest.invalidate(); closest.distance = -99999.9f; @@ -1255,7 +1326,7 @@ float best_so_far = 99999.99f; GRID_LOOP(i, j) { - if ( (type == (isnan(z_values[i][j]) ? INVALID : REAL)) + if ( type == CLOSEST || type == (isnan(z_values[i][j]) ? INVALID : REAL) || (type == SET_IN_BITMAP && !done_flags->marked(i, j)) ) { // Found a Mesh Point of the specified type! @@ -1284,495 +1355,497 @@ } // GRID_LOOP return closest; - } - /** - * 'Smart Fill': Scan from the outward edges of the mesh towards the center. - * If an invalid location is found, use the next two points (if valid) to - * calculate a 'reasonable' value for the unprobed mesh point. - */ + #endif +} - bool unified_bed_leveling::smart_fill_one(const uint8_t x, const uint8_t y, const int8_t xdir, const int8_t ydir) { - const float v = z_values[x][y]; - if (isnan(v)) { // A NAN... - const int8_t dx = x + xdir, dy = y + ydir; - const float v1 = z_values[dx][dy]; - if (!isnan(v1)) { // ...next to a pair of real values? - const float v2 = z_values[dx + xdir][dy + ydir]; - if (!isnan(v2)) { - z_values[x][y] = v1 < v2 ? v1 : v1 + v1 - v2; - TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, z_values[x][y])); - return true; - } +/** + * 'Smart Fill': Scan from the outward edges of the mesh towards the center. + * If an invalid location is found, use the next two points (if valid) to + * calculate a 'reasonable' value for the unprobed mesh point. + */ + +bool unified_bed_leveling::smart_fill_one(const uint8_t x, const uint8_t y, const int8_t xdir, const int8_t ydir) { + const float v = z_values[x][y]; + if (isnan(v)) { // A NAN... + const int8_t dx = x + xdir, dy = y + ydir; + const float v1 = z_values[dx][dy]; + if (!isnan(v1)) { // ...next to a pair of real values? + const float v2 = z_values[dx + xdir][dy + ydir]; + if (!isnan(v2)) { + z_values[x][y] = v1 < v2 ? v1 : v1 + v1 - v2; + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, z_values[x][y])); + return true; } } - return false; } - - typedef struct { uint8_t sx, ex, sy, ey; bool yfirst; } smart_fill_info; - - void unified_bed_leveling::smart_fill_mesh() { - static const smart_fill_info - info0 PROGMEM = { 0, GRID_MAX_POINTS_X, 0, GRID_MAX_POINTS_Y - 2, false }, // Bottom of the mesh looking up - info1 PROGMEM = { 0, GRID_MAX_POINTS_X, GRID_MAX_POINTS_Y - 1, 0, false }, // Top of the mesh looking down - info2 PROGMEM = { 0, GRID_MAX_POINTS_X - 2, 0, GRID_MAX_POINTS_Y, true }, // Left side of the mesh looking right - 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)) { - 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); - if (pgm_read_byte(&f->yfirst)) { - const int8_t dir = ex > sx ? 1 : -1; - for (uint8_t y = sy; y != ey; ++y) - for (uint8_t x = sx; x != ex; x += dir) - if (smart_fill_one(x, y, dir, 0)) break; - } - else { - const int8_t dir = ey > sy ? 1 : -1; - for (uint8_t x = sx; x != ex; ++x) - for (uint8_t y = sy; y != ey; y += dir) - if (smart_fill_one(x, y, 0, dir)) break; - } + return false; +} + +typedef struct { uint8_t sx, ex, sy, ey; bool yfirst; } smart_fill_info; + +void unified_bed_leveling::smart_fill_mesh() { + static const smart_fill_info + info0 PROGMEM = { 0, GRID_MAX_POINTS_X, 0, GRID_MAX_POINTS_Y - 2, false }, // Bottom of the mesh looking up + info1 PROGMEM = { 0, GRID_MAX_POINTS_X, GRID_MAX_POINTS_Y - 1, 0, false }, // Top of the mesh looking down + info2 PROGMEM = { 0, GRID_MAX_POINTS_X - 2, 0, GRID_MAX_POINTS_Y, true }, // Left side of the mesh looking right + 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)) { + 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); + if (pgm_read_byte(&f->yfirst)) { + const int8_t dir = ex > sx ? 1 : -1; + for (uint8_t y = sy; y != ey; ++y) + for (uint8_t x = sx; x != ex; x += dir) + if (smart_fill_one(x, y, dir, 0)) break; + } + else { + const int8_t dir = ey > sy ? 1 : -1; + for (uint8_t x = sx; x != ex; ++x) + for (uint8_t y = sy; y != ey; y += dir) + if (smart_fill_one(x, y, 0, dir)) break; } } +} - #if HAS_BED_PROBE +#if HAS_BED_PROBE - //#define VALIDATE_MESH_TILT + //#define VALIDATE_MESH_TILT - #include "../../../libs/vector_3.h" + #include "../../../libs/vector_3.h" - void unified_bed_leveling::tilt_mesh_based_on_probed_grid(const bool do_3_pt_leveling) { - const float x_min = probe.min_x(), x_max = probe.max_x(), - y_min = probe.min_y(), y_max = probe.max_y(), - dx = (x_max - x_min) / (g29_grid_size - 1), - dy = (y_max - y_min) / (g29_grid_size - 1); + void unified_bed_leveling::tilt_mesh_based_on_probed_grid(const bool do_3_pt_leveling) { + const float x_min = probe.min_x(), x_max = probe.max_x(), + y_min = probe.min_y(), y_max = probe.max_y(), + dx = (x_max - x_min) / (param.J_grid_size - 1), + dy = (y_max - y_min) / (param.J_grid_size - 1); - xy_float_t points[3]; - probe.get_three_points(points); + xy_float_t points[3]; + probe.get_three_points(points); - float measured_z; - bool abort_flag = false; + float measured_z; + bool abort_flag = false; - #ifdef VALIDATE_MESH_TILT - float z1, z2, z3; // Needed for algorithm validation below - #endif + #ifdef VALIDATE_MESH_TILT + float z1, z2, z3; // Needed for algorithm validation below + #endif + + struct linear_fit_data lsf_results; + incremental_LSF_reset(&lsf_results); - struct linear_fit_data lsf_results; - incremental_LSF_reset(&lsf_results); + if (do_3_pt_leveling) { + SERIAL_ECHOLNPGM("Tilting mesh (1/3)"); + TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " 1/3"), GET_TEXT(MSG_LCD_TILTING_MESH))); - if (do_3_pt_leveling) { - SERIAL_ECHOLNPGM("Tilting mesh (1/3)"); - TERN_(HAS_DISPLAY, ui.status_printf_P(0, PSTR(S_FMT " 1/3"), GET_TEXT(MSG_LCD_TILTING_MESH))); + measured_z = probe.probe_at_point(points[0], PROBE_PT_RAISE, param.V_verbosity); + if (isnan(measured_z)) + abort_flag = true; + else { + measured_z -= get_z_correction(points[0]); + #ifdef VALIDATE_MESH_TILT + z1 = measured_z; + #endif + if (param.V_verbosity > 3) { + serial_spaces(16); + SERIAL_ECHOLNPAIR("Corrected_Z=", measured_z); + } + incremental_LSF(&lsf_results, points[0], measured_z); + } + + if (!abort_flag) { + SERIAL_ECHOLNPGM("Tilting mesh (2/3)"); + TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " 2/3"), GET_TEXT(MSG_LCD_TILTING_MESH))); - measured_z = probe.probe_at_point(points[0], PROBE_PT_RAISE, g29_verbose_level); + measured_z = probe.probe_at_point(points[1], PROBE_PT_RAISE, param.V_verbosity); + #ifdef VALIDATE_MESH_TILT + z2 = measured_z; + #endif if (isnan(measured_z)) abort_flag = true; else { - measured_z -= get_z_correction(points[0]); - #ifdef VALIDATE_MESH_TILT - z1 = measured_z; - #endif - if (g29_verbose_level > 3) { + measured_z -= get_z_correction(points[1]); + if (param.V_verbosity > 3) { serial_spaces(16); SERIAL_ECHOLNPAIR("Corrected_Z=", measured_z); } - incremental_LSF(&lsf_results, points[0], measured_z); - } - - if (!abort_flag) { - SERIAL_ECHOLNPGM("Tilting mesh (2/3)"); - TERN_(HAS_DISPLAY, ui.status_printf_P(0, PSTR(S_FMT " 2/3"), GET_TEXT(MSG_LCD_TILTING_MESH))); - - measured_z = probe.probe_at_point(points[1], PROBE_PT_RAISE, g29_verbose_level); - #ifdef VALIDATE_MESH_TILT - z2 = measured_z; - #endif - if (isnan(measured_z)) - abort_flag = true; - else { - measured_z -= get_z_correction(points[1]); - if (g29_verbose_level > 3) { - serial_spaces(16); - SERIAL_ECHOLNPAIR("Corrected_Z=", measured_z); - } - incremental_LSF(&lsf_results, points[1], measured_z); - } + incremental_LSF(&lsf_results, points[1], measured_z); } + } - if (!abort_flag) { - SERIAL_ECHOLNPGM("Tilting mesh (3/3)"); - TERN_(HAS_DISPLAY, ui.status_printf_P(0, PSTR(S_FMT " 3/3"), GET_TEXT(MSG_LCD_TILTING_MESH))); + if (!abort_flag) { + SERIAL_ECHOLNPGM("Tilting mesh (3/3)"); + TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " 3/3"), GET_TEXT(MSG_LCD_TILTING_MESH))); - measured_z = probe.probe_at_point(points[2], PROBE_PT_STOW, g29_verbose_level); - #ifdef VALIDATE_MESH_TILT - z3 = measured_z; - #endif - if (isnan(measured_z)) - abort_flag = true; - else { - measured_z -= get_z_correction(points[2]); - if (g29_verbose_level > 3) { - serial_spaces(16); - SERIAL_ECHOLNPAIR("Corrected_Z=", measured_z); - } - incremental_LSF(&lsf_results, points[2], measured_z); + measured_z = probe.probe_at_point(points[2], PROBE_PT_STOW, param.V_verbosity); + #ifdef VALIDATE_MESH_TILT + z3 = measured_z; + #endif + if (isnan(measured_z)) + abort_flag = true; + else { + measured_z -= get_z_correction(points[2]); + if (param.V_verbosity > 3) { + serial_spaces(16); + SERIAL_ECHOLNPAIR("Corrected_Z=", measured_z); } + incremental_LSF(&lsf_results, points[2], measured_z); } + } - probe.stow(); - probe.move_z_after_probing(); + probe.stow(); + probe.move_z_after_probing(); - if (abort_flag) { - SERIAL_ECHOLNPGM("?Error probing point. Aborting operation."); - return; - } + if (abort_flag) { + SERIAL_ECHOLNPGM("?Error probing point. Aborting operation."); + return; } - else { // !do_3_pt_leveling - - bool zig_zag = false; - - const uint16_t total_points = sq(g29_grid_size); - uint16_t point_num = 1; - - xy_pos_t rpos; - LOOP_L_N(ix, g29_grid_size) { - rpos.x = x_min + ix * dx; - LOOP_L_N(iy, g29_grid_size) { - rpos.y = y_min + dy * (zig_zag ? g29_grid_size - 1 - iy : iy); - - if (!abort_flag) { - SERIAL_ECHOLNPAIR("Tilting mesh point ", point_num, "/", total_points, "\n"); - TERN_(HAS_DISPLAY, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_LCD_TILTING_MESH), point_num, total_points)); - - measured_z = probe.probe_at_point(rpos, parser.seen('E') ? PROBE_PT_STOW : PROBE_PT_RAISE, g29_verbose_level); // TODO: Needs error handling - - abort_flag = isnan(measured_z); - - #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) { - const xy_pos_t lpos = rpos.asLogical(); - DEBUG_CHAR('('); - DEBUG_ECHO_F(rpos.x, 7); - DEBUG_CHAR(','); - DEBUG_ECHO_F(rpos.y, 7); - DEBUG_ECHOPAIR_F(") logical: (", lpos.x, 7); - DEBUG_CHAR(','); - DEBUG_ECHO_F(lpos.y, 7); - DEBUG_ECHOPAIR_F(") measured: ", measured_z, 7); - DEBUG_ECHOPAIR_F(" correction: ", get_z_correction(rpos), 7); - } - #endif + } + else { // !do_3_pt_leveling + + bool zig_zag = false; + + const uint16_t total_points = sq(param.J_grid_size); + uint16_t point_num = 1; + + xy_pos_t rpos; + LOOP_L_N(ix, param.J_grid_size) { + rpos.x = x_min + ix * dx; + LOOP_L_N(iy, param.J_grid_size) { + rpos.y = y_min + dy * (zig_zag ? param.J_grid_size - 1 - iy : iy); + + if (!abort_flag) { + SERIAL_ECHOLNPAIR("Tilting mesh point ", point_num, "/", total_points, "\n"); + TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_LCD_TILTING_MESH), point_num, total_points)); + + measured_z = probe.probe_at_point(rpos, parser.seen_test('E') ? PROBE_PT_STOW : PROBE_PT_RAISE, param.V_verbosity); // TODO: Needs error handling + + abort_flag = isnan(measured_z); + + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (DEBUGGING(LEVELING)) { + const xy_pos_t lpos = rpos.asLogical(); + DEBUG_CHAR('('); + DEBUG_ECHO_F(rpos.x, 7); + DEBUG_CHAR(','); + DEBUG_ECHO_F(rpos.y, 7); + DEBUG_ECHOPAIR_F(") logical: (", lpos.x, 7); + DEBUG_CHAR(','); + DEBUG_ECHO_F(lpos.y, 7); + DEBUG_ECHOPAIR_F(") measured: ", measured_z, 7); + DEBUG_ECHOPAIR_F(" correction: ", get_z_correction(rpos), 7); + } + #endif - measured_z -= get_z_correction(rpos) /* + probe.offset.z */ ; + measured_z -= get_z_correction(rpos) /* + probe.offset.z */ ; - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR_F(" final >>>---> ", measured_z, 7); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR_F(" final >>>---> ", measured_z, 7); - if (g29_verbose_level > 3) { - serial_spaces(16); - SERIAL_ECHOLNPAIR("Corrected_Z=", measured_z); - } - incremental_LSF(&lsf_results, rpos, measured_z); + if (param.V_verbosity > 3) { + serial_spaces(16); + SERIAL_ECHOLNPAIR("Corrected_Z=", measured_z); } - - point_num++; + incremental_LSF(&lsf_results, rpos, measured_z); } - zig_zag ^= true; + point_num++; } - } - probe.stow(); - probe.move_z_after_probing(); - if (abort_flag || finish_incremental_LSF(&lsf_results)) { - SERIAL_ECHOPGM("Could not complete LSF!"); - return; + zig_zag ^= true; } + } + probe.stow(); + probe.move_z_after_probing(); - vector_3 normal = vector_3(lsf_results.A, lsf_results.B, 1).get_normal(); + if (abort_flag || finish_incremental_LSF(&lsf_results)) { + SERIAL_ECHOPGM("Could not complete LSF!"); + return; + } - if (g29_verbose_level > 2) { - SERIAL_ECHOPAIR_F("bed plane normal = [", normal.x, 7); - SERIAL_CHAR(','); - SERIAL_ECHO_F(normal.y, 7); - SERIAL_CHAR(','); - SERIAL_ECHO_F(normal.z, 7); - SERIAL_ECHOLNPGM("]"); - } + vector_3 normal = vector_3(lsf_results.A, lsf_results.B, 1).get_normal(); - matrix_3x3 rotation = matrix_3x3::create_look_at(vector_3(lsf_results.A, lsf_results.B, 1)); - - GRID_LOOP(i, j) { - float mx = mesh_index_to_xpos(i), - my = mesh_index_to_ypos(j), - mz = z_values[i][j]; - - if (DEBUGGING(LEVELING)) { - DEBUG_ECHOPAIR_F("before rotation = [", mx, 7); - DEBUG_CHAR(','); - DEBUG_ECHO_F(my, 7); - DEBUG_CHAR(','); - DEBUG_ECHO_F(mz, 7); - DEBUG_ECHOPGM("] ---> "); - DEBUG_DELAY(20); - } + if (param.V_verbosity > 2) { + SERIAL_ECHOPAIR_F("bed plane normal = [", normal.x, 7); + SERIAL_CHAR(','); + SERIAL_ECHO_F(normal.y, 7); + SERIAL_CHAR(','); + SERIAL_ECHO_F(normal.z, 7); + SERIAL_ECHOLNPGM("]"); + } - apply_rotation_xyz(rotation, mx, my, mz); + matrix_3x3 rotation = matrix_3x3::create_look_at(vector_3(lsf_results.A, lsf_results.B, 1)); - if (DEBUGGING(LEVELING)) { - DEBUG_ECHOPAIR_F("after rotation = [", mx, 7); - DEBUG_CHAR(','); - DEBUG_ECHO_F(my, 7); - DEBUG_CHAR(','); - DEBUG_ECHO_F(mz, 7); - DEBUG_ECHOLNPGM("]"); - DEBUG_DELAY(20); - } + GRID_LOOP(i, j) { + float mx = mesh_index_to_xpos(i), + my = mesh_index_to_ypos(j), + mz = z_values[i][j]; - z_values[i][j] = mz - lsf_results.D; - TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(i, j, z_values[i][j])); + if (DEBUGGING(LEVELING)) { + DEBUG_ECHOPAIR_F("before rotation = [", mx, 7); + DEBUG_CHAR(','); + DEBUG_ECHO_F(my, 7); + DEBUG_CHAR(','); + DEBUG_ECHO_F(mz, 7); + DEBUG_ECHOPGM("] ---> "); + DEBUG_DELAY(20); } - if (DEBUGGING(LEVELING)) { - rotation.debug(PSTR("rotation matrix:\n")); - DEBUG_ECHOPAIR_F("LSF Results A=", lsf_results.A, 7); - DEBUG_ECHOPAIR_F(" B=", lsf_results.B, 7); - DEBUG_ECHOLNPAIR_F(" D=", lsf_results.D, 7); - DEBUG_DELAY(55); + rotation.apply_rotation_xyz(mx, my, mz); - DEBUG_ECHOPAIR_F("bed plane normal = [", normal.x, 7); + if (DEBUGGING(LEVELING)) { + DEBUG_ECHOPAIR_F("after rotation = [", mx, 7); DEBUG_CHAR(','); - DEBUG_ECHO_F(normal.y, 7); + DEBUG_ECHO_F(my, 7); DEBUG_CHAR(','); - DEBUG_ECHO_F(normal.z, 7); + DEBUG_ECHO_F(mz, 7); DEBUG_ECHOLNPGM("]"); - DEBUG_EOL(); - - /** - * Use the code below to check the validity of the mesh tilting algorithm. - * 3-Point Mesh Tilt uses the same algorithm as grid-based tilting, but only - * three points are used in the calculation. This guarantees that each probed point - * has an exact match when get_z_correction() for that location is calculated. - * The Z error between the probed point locations and the get_z_correction() - * numbers for those locations should be 0. - */ - #ifdef VALIDATE_MESH_TILT - auto d_from = []{ DEBUG_ECHOPGM("D from "); }; - auto normed = [&](const xy_pos_t &pos, const float &zadd) { - return normal.x * pos.x + normal.y * pos.y + zadd; - }; - auto debug_pt = [](PGM_P const pre, const xy_pos_t &pos, const float &zadd) { - d_from(); serialprintPGM(pre); - DEBUG_ECHO_F(normed(pos, zadd), 6); - DEBUG_ECHOLNPAIR_F(" Z error = ", zadd - get_z_correction(pos), 6); - }; - debug_pt(PSTR("1st point: "), probe_pt[0], normal.z * z1); - debug_pt(PSTR("2nd point: "), probe_pt[1], normal.z * z2); - debug_pt(PSTR("3rd point: "), probe_pt[2], normal.z * z3); - d_from(); DEBUG_ECHOPGM("safe home with Z="); - DEBUG_ECHOLNPAIR_F("0 : ", normed(safe_homing_xy, 0), 6); - d_from(); DEBUG_ECHOPGM("safe home with Z="); - DEBUG_ECHOLNPAIR_F("mesh value ", normed(safe_homing_xy, get_z_correction(safe_homing_xy)), 6); - DEBUG_ECHOPAIR(" Z error = (", Z_SAFE_HOMING_X_POINT, ",", Z_SAFE_HOMING_Y_POINT); - DEBUG_ECHOLNPAIR_F(") = ", get_z_correction(safe_homing_xy), 6); - #endif - } // DEBUGGING(LEVELING) + DEBUG_DELAY(20); + } + z_values[i][j] = mz - lsf_results.D; + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(i, j, z_values[i][j])); } - #endif // HAS_BED_PROBE + if (DEBUGGING(LEVELING)) { + rotation.debug(PSTR("rotation matrix:\n")); + DEBUG_ECHOPAIR_F("LSF Results A=", lsf_results.A, 7); + DEBUG_ECHOPAIR_F(" B=", lsf_results.B, 7); + DEBUG_ECHOLNPAIR_F(" D=", lsf_results.D, 7); + DEBUG_DELAY(55); + + DEBUG_ECHOPAIR_F("bed plane normal = [", normal.x, 7); + DEBUG_CHAR(','); + DEBUG_ECHO_F(normal.y, 7); + DEBUG_CHAR(','); + DEBUG_ECHO_F(normal.z, 7); + DEBUG_ECHOLNPGM("]"); + DEBUG_EOL(); + + /** + * Use the code below to check the validity of the mesh tilting algorithm. + * 3-Point Mesh Tilt uses the same algorithm as grid-based tilting, but only + * three points are used in the calculation. This guarantees that each probed point + * has an exact match when get_z_correction() for that location is calculated. + * The Z error between the probed point locations and the get_z_correction() + * numbers for those locations should be 0. + */ + #ifdef VALIDATE_MESH_TILT + auto d_from = []{ DEBUG_ECHOPGM("D from "); }; + auto normed = [&](const xy_pos_t &pos, const_float_t zadd) { + return normal.x * pos.x + normal.y * pos.y + zadd; + }; + auto debug_pt = [](PGM_P const pre, const xy_pos_t &pos, const_float_t zadd) { + d_from(); SERIAL_ECHOPGM_P(pre); + DEBUG_ECHO_F(normed(pos, zadd), 6); + DEBUG_ECHOLNPAIR_F(" Z error = ", zadd - get_z_correction(pos), 6); + }; + debug_pt(PSTR("1st point: "), probe_pt[0], normal.z * z1); + debug_pt(PSTR("2nd point: "), probe_pt[1], normal.z * z2); + debug_pt(PSTR("3rd point: "), probe_pt[2], normal.z * z3); + d_from(); DEBUG_ECHOPGM("safe home with Z="); + DEBUG_ECHOLNPAIR_F("0 : ", normed(safe_homing_xy, 0), 6); + d_from(); DEBUG_ECHOPGM("safe home with Z="); + DEBUG_ECHOLNPAIR_F("mesh value ", normed(safe_homing_xy, get_z_correction(safe_homing_xy)), 6); + DEBUG_ECHOPAIR(" Z error = (", Z_SAFE_HOMING_X_POINT, ",", Z_SAFE_HOMING_Y_POINT); + DEBUG_ECHOLNPAIR_F(") = ", get_z_correction(safe_homing_xy), 6); + #endif + } // DEBUGGING(LEVELING) - #if ENABLED(UBL_G29_P31) - void unified_bed_leveling::smart_fill_wlsf(const float &weight_factor) { - - // For each undefined mesh point, compute a distance-weighted least squares fit - // from all the originally populated mesh points, weighted toward the point - // being extrapolated so that nearby points will have greater influence on - // the point being extrapolated. Then extrapolate the mesh point from WLSF. - - static_assert((GRID_MAX_POINTS_Y) <= 16, "GRID_MAX_POINTS_Y too big"); - uint16_t bitmap[GRID_MAX_POINTS_X] = { 0 }; - struct linear_fit_data lsf_results; - - SERIAL_ECHOPGM("Extrapolating mesh..."); - - const float weight_scaled = weight_factor * _MAX(MESH_X_DIST, MESH_Y_DIST); - - 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) { - ppos.x = mesh_index_to_xpos(ix); - LOOP_L_N(iy, GRID_MAX_POINTS_Y) { - ppos.y = mesh_index_to_ypos(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) { - rpos.x = mesh_index_to_xpos(jx); - LOOP_L_N(jy, GRID_MAX_POINTS_Y) { - if (TEST(bitmap[jx], jy)) { - rpos.y = mesh_index_to_ypos(jy); - const float rz = z_values[jx][jy], - w = 1.0f + weight_scaled / (rpos - ppos).magnitude(); - incremental_WLSF(&lsf_results, rpos, rz, w); - } + } + +#endif // HAS_BED_PROBE + +#if ENABLED(UBL_G29_P31) + void unified_bed_leveling::smart_fill_wlsf(const_float_t weight_factor) { + + // For each undefined mesh point, compute a distance-weighted least squares fit + // from all the originally populated mesh points, weighted toward the point + // being extrapolated so that nearby points will have greater influence on + // the point being extrapolated. Then extrapolate the mesh point from WLSF. + + static_assert((GRID_MAX_POINTS_Y) <= 16, "GRID_MAX_POINTS_Y too big"); + uint16_t bitmap[GRID_MAX_POINTS_X] = { 0 }; + struct linear_fit_data lsf_results; + + SERIAL_ECHOPGM("Extrapolating mesh..."); + + const float weight_scaled = weight_factor * _MAX(MESH_X_DIST, MESH_Y_DIST); + + 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) { + ppos.x = mesh_index_to_xpos(ix); + LOOP_L_N(iy, GRID_MAX_POINTS_Y) { + ppos.y = mesh_index_to_ypos(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) { + rpos.x = mesh_index_to_xpos(jx); + LOOP_L_N(jy, GRID_MAX_POINTS_Y) { + if (TEST(bitmap[jx], jy)) { + rpos.y = mesh_index_to_ypos(jy); + const float rz = z_values[jx][jy], + w = 1.0f + weight_scaled / (rpos - ppos).magnitude(); + incremental_WLSF(&lsf_results, rpos, rz, w); } } - if (finish_incremental_LSF(&lsf_results)) { - SERIAL_ECHOLNPGM("Insufficient data"); - return; - } - const float ez = -lsf_results.D - lsf_results.A * ppos.x - lsf_results.B * ppos.y; - z_values[ix][iy] = ez; - TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ix, iy, z_values[ix][iy])); - idle(); // housekeeping } + if (finish_incremental_LSF(&lsf_results)) { + SERIAL_ECHOLNPGM("Insufficient data"); + return; + } + const float ez = -lsf_results.D - lsf_results.A * ppos.x - lsf_results.B * ppos.y; + z_values[ix][iy] = ez; + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ix, iy, z_values[ix][iy])); + idle(); // housekeeping } } - - SERIAL_ECHOLNPGM("done"); } - #endif // UBL_G29_P31 - #if ENABLED(UBL_DEVEL_DEBUGGING) - /** - * Much of the 'What?' command can be eliminated. But until we are fully debugged, it is - * good to have the extra information. Soon... we prune this to just a few items - */ - void unified_bed_leveling::g29_what_command() { - report_state(); - - if (storage_slot == -1) - SERIAL_ECHOPGM("No Mesh Loaded."); - else - SERIAL_ECHOPAIR("Mesh ", storage_slot, " Loaded."); - SERIAL_EOL(); - serial_delay(50); + SERIAL_ECHOLNPGM("done"); + } +#endif // UBL_G29_P31 - #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - SERIAL_ECHOLNPAIR_F("Fade Height M420 Z", planner.z_fade_height, 4); - #endif +#if ENABLED(UBL_DEVEL_DEBUGGING) + /** + * Much of the 'What?' command can be eliminated. But until we are fully debugged, it is + * good to have the extra information. Soon... we prune this to just a few items + */ + void unified_bed_leveling::g29_what_command() { + report_state(); - adjust_mesh_to_mean(g29_c_flag, g29_constant); + if (storage_slot == -1) + SERIAL_ECHOPGM("No Mesh Loaded."); + else + SERIAL_ECHOPAIR("Mesh ", storage_slot, " Loaded."); + SERIAL_EOL(); + serial_delay(50); - #if HAS_BED_PROBE - SERIAL_ECHOLNPAIR_F("Probe Offset M851 Z", probe.offset.z, 7); - #endif + #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) + SERIAL_ECHOLNPAIR_F("Fade Height M420 Z", planner.z_fade_height, 4); + #endif - SERIAL_ECHOLNPAIR("MESH_MIN_X " STRINGIFY(MESH_MIN_X) "=", MESH_MIN_X); serial_delay(50); - SERIAL_ECHOLNPAIR("MESH_MIN_Y " STRINGIFY(MESH_MIN_Y) "=", MESH_MIN_Y); serial_delay(50); - SERIAL_ECHOLNPAIR("MESH_MAX_X " STRINGIFY(MESH_MAX_X) "=", MESH_MAX_X); serial_delay(50); - SERIAL_ECHOLNPAIR("MESH_MAX_Y " STRINGIFY(MESH_MAX_Y) "=", MESH_MAX_Y); serial_delay(50); - SERIAL_ECHOLNPAIR("GRID_MAX_POINTS_X ", GRID_MAX_POINTS_X); serial_delay(50); - SERIAL_ECHOLNPAIR("GRID_MAX_POINTS_Y ", GRID_MAX_POINTS_Y); serial_delay(50); - SERIAL_ECHOLNPAIR("MESH_X_DIST ", MESH_X_DIST); - SERIAL_ECHOLNPAIR("MESH_Y_DIST ", MESH_Y_DIST); serial_delay(50); - - SERIAL_ECHOPGM("X-Axis Mesh Points at: "); - LOOP_L_N(i, GRID_MAX_POINTS_X) { - SERIAL_ECHO_F(LOGICAL_X_POSITION(mesh_index_to_xpos(i)), 3); - SERIAL_ECHOPGM(" "); - serial_delay(25); - } - SERIAL_EOL(); + adjust_mesh_to_mean(param.C_seen, param.C_constant); - SERIAL_ECHOPGM("Y-Axis Mesh Points at: "); - LOOP_L_N(i, GRID_MAX_POINTS_Y) { - SERIAL_ECHO_F(LOGICAL_Y_POSITION(mesh_index_to_ypos(i)), 3); - SERIAL_ECHOPGM(" "); - serial_delay(25); - } - SERIAL_EOL(); + #if HAS_BED_PROBE + SERIAL_ECHOLNPAIR_F("Probe Offset M851 Z", probe.offset.z, 7); + #endif - #if HAS_KILL - SERIAL_ECHOLNPAIR("Kill pin on :", int(KILL_PIN), " state:", int(kill_state())); - #endif + SERIAL_ECHOLNPAIR("MESH_MIN_X " STRINGIFY(MESH_MIN_X) "=", MESH_MIN_X); serial_delay(50); + SERIAL_ECHOLNPAIR("MESH_MIN_Y " STRINGIFY(MESH_MIN_Y) "=", MESH_MIN_Y); serial_delay(50); + SERIAL_ECHOLNPAIR("MESH_MAX_X " STRINGIFY(MESH_MAX_X) "=", MESH_MAX_X); serial_delay(50); + SERIAL_ECHOLNPAIR("MESH_MAX_Y " STRINGIFY(MESH_MAX_Y) "=", MESH_MAX_Y); serial_delay(50); + SERIAL_ECHOLNPAIR("GRID_MAX_POINTS_X ", GRID_MAX_POINTS_X); serial_delay(50); + SERIAL_ECHOLNPAIR("GRID_MAX_POINTS_Y ", GRID_MAX_POINTS_Y); serial_delay(50); + SERIAL_ECHOLNPAIR("MESH_X_DIST ", MESH_X_DIST); + SERIAL_ECHOLNPAIR("MESH_Y_DIST ", MESH_Y_DIST); serial_delay(50); + + SERIAL_ECHOPGM("X-Axis Mesh Points at: "); + LOOP_L_N(i, GRID_MAX_POINTS_X) { + SERIAL_ECHO_F(LOGICAL_X_POSITION(mesh_index_to_xpos(i)), 3); + SERIAL_ECHOPGM(" "); + serial_delay(25); + } + SERIAL_EOL(); - SERIAL_EOL(); - serial_delay(50); + SERIAL_ECHOPGM("Y-Axis Mesh Points at: "); + LOOP_L_N(i, GRID_MAX_POINTS_Y) { + SERIAL_ECHO_F(LOGICAL_Y_POSITION(mesh_index_to_ypos(i)), 3); + SERIAL_ECHOPGM(" "); + serial_delay(25); + } + SERIAL_EOL(); + + #if HAS_KILL + SERIAL_ECHOLNPAIR("Kill pin on :", KILL_PIN, " state:", kill_state()); + #endif - #if ENABLED(UBL_DEVEL_DEBUGGING) - SERIAL_ECHOLNPAIR("ubl_state_at_invocation :", ubl_state_at_invocation, "\nubl_state_recursion_chk :", ubl_state_recursion_chk); - serial_delay(50); + SERIAL_EOL(); + serial_delay(50); - SERIAL_ECHOLNPAIR("Meshes go from ", hex_address((void*)settings.meshes_start_index()), " to ", hex_address((void*)settings.meshes_end_index())); - serial_delay(50); + #if ENABLED(UBL_DEVEL_DEBUGGING) + SERIAL_ECHOLNPAIR("ubl_state_at_invocation :", ubl_state_at_invocation, "\nubl_state_recursion_chk :", ubl_state_recursion_chk); + serial_delay(50); + + SERIAL_ECHOLNPAIR("Meshes go from ", hex_address((void*)settings.meshes_start_index()), " to ", hex_address((void*)settings.meshes_end_index())); + serial_delay(50); - SERIAL_ECHOLNPAIR("sizeof(ubl) : ", (int)sizeof(ubl)); SERIAL_EOL(); - SERIAL_ECHOLNPAIR("z_value[][] size: ", (int)sizeof(z_values)); SERIAL_EOL(); - serial_delay(25); + SERIAL_ECHOLNPAIR("sizeof(ubl) : ", sizeof(ubl)); SERIAL_EOL(); + SERIAL_ECHOLNPAIR("z_value[][] size: ", sizeof(z_values)); SERIAL_EOL(); + serial_delay(25); - SERIAL_ECHOLNPAIR("EEPROM free for UBL: ", hex_address((void*)(settings.meshes_end_index() - settings.meshes_start_index()))); - serial_delay(50); + SERIAL_ECHOLNPAIR("EEPROM free for UBL: ", hex_address((void*)(settings.meshes_end_index() - settings.meshes_start_index()))); + serial_delay(50); - SERIAL_ECHOLNPAIR("EEPROM can hold ", settings.calc_num_meshes(), " meshes.\n"); - serial_delay(25); - #endif // UBL_DEVEL_DEBUGGING + SERIAL_ECHOLNPAIR("EEPROM can hold ", settings.calc_num_meshes(), " meshes.\n"); + serial_delay(25); + #endif // UBL_DEVEL_DEBUGGING - if (!sanity_check()) { - echo_name(); - SERIAL_ECHOLNPGM(" sanity checks passed."); - } + if (!sanity_check()) { + echo_name(); + SERIAL_ECHOLNPGM(" sanity checks passed."); } + } - /** - * When we are fully debugged, the EEPROM dump command will get deleted also. But - * right now, it is good to have the extra information. Soon... we prune this. - */ - void unified_bed_leveling::g29_eeprom_dump() { - uint8_t cccc; - - SERIAL_ECHO_MSG("EEPROM Dump:"); - persistentStore.access_start(); - for (uint16_t i = 0; i < persistentStore.capacity(); i += 16) { - if (!(i & 0x3)) idle(); - print_hex_word(i); - SERIAL_ECHOPGM(": "); - for (uint16_t j = 0; j < 16; j++) { - persistentStore.read_data(i + j, &cccc, sizeof(uint8_t)); - print_hex_byte(cccc); - SERIAL_CHAR(' '); - } - SERIAL_EOL(); + /** + * When we are fully debugged, the EEPROM dump command will get deleted also. But + * right now, it is good to have the extra information. Soon... we prune this. + */ + void unified_bed_leveling::g29_eeprom_dump() { + uint8_t cccc; + + SERIAL_ECHO_MSG("EEPROM Dump:"); + persistentStore.access_start(); + for (uint16_t i = 0; i < persistentStore.capacity(); i += 16) { + if (!(i & 0x3)) idle(); + print_hex_word(i); + SERIAL_ECHOPGM(": "); + for (uint16_t j = 0; j < 16; j++) { + persistentStore.read_data(i + j, &cccc, sizeof(uint8_t)); + print_hex_byte(cccc); + SERIAL_CHAR(' '); } SERIAL_EOL(); - persistentStore.access_finish(); } + SERIAL_EOL(); + persistentStore.access_finish(); + } - /** - * When we are fully debugged, this may go away. But there are some valid - * use cases for the users. So we can wait and see what to do with it. - */ - void unified_bed_leveling::g29_compare_current_mesh_to_stored_mesh() { - const int16_t a = settings.calc_num_meshes(); + /** + * When we are fully debugged, this may go away. But there are some valid + * use cases for the users. So we can wait and see what to do with it. + */ + void unified_bed_leveling::g29_compare_current_mesh_to_stored_mesh() { + const int16_t a = settings.calc_num_meshes(); - if (!a) { - SERIAL_ECHOLNPGM("?EEPROM storage not available."); - return; - } + if (!a) { + SERIAL_ECHOLNPGM("?EEPROM storage not available."); + return; + } - if (!parser.has_value() || !WITHIN(g29_storage_slot, 0, a - 1)) { - SERIAL_ECHOLNPAIR("?Invalid storage slot.\n?Use 0 to ", a - 1); - return; - } + if (!parser.has_value() || !WITHIN(parser.value_int(), 0, a - 1)) { + SERIAL_ECHOLNPAIR("?Invalid storage slot.\n?Use 0 to ", a - 1); + return; + } - g29_storage_slot = parser.value_int(); + param.KLS_storage_slot = (int8_t)parser.value_int(); - float tmp_z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y]; - settings.load_mesh(g29_storage_slot, &tmp_z_values); + float tmp_z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y]; + settings.load_mesh(param.KLS_storage_slot, &tmp_z_values); - SERIAL_ECHOLNPAIR("Subtracting mesh in slot ", g29_storage_slot, " from current mesh."); + SERIAL_ECHOLNPAIR("Subtracting mesh in slot ", param.KLS_storage_slot, " from current mesh."); - GRID_LOOP(x, y) { - z_values[x][y] -= tmp_z_values[x][y]; - TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, z_values[x][y])); - } + GRID_LOOP(x, y) { + z_values[x][y] -= tmp_z_values[x][y]; + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, z_values[x][y])); } + } - #endif // UBL_DEVEL_DEBUGGING +#endif // UBL_DEVEL_DEBUGGING #endif // AUTO_BED_LEVELING_UBL diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp index 010b5951be5f..20408d8d1e81 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp @@ -37,7 +37,7 @@ #if !UBL_SEGMENTED - void unified_bed_leveling::line_to_destination_cartesian(const feedRate_t &scaled_fr_mm_s, const uint8_t extruder) { + void unified_bed_leveling::line_to_destination_cartesian(const_feedRate_t scaled_fr_mm_s, const uint8_t extruder) { /** * Much of the nozzle movement will be within the same cell. So we will do as little computation * as possible to determine if this is the case. If this move is within the same cell, we will @@ -56,39 +56,32 @@ // A move within the same cell needs no splitting if (istart == iend) { - // For a move off the bed, use a constant Z raise - if (!WITHIN(iend.x, 0, GRID_MAX_POINTS_X - 1) || !WITHIN(iend.y, 0, GRID_MAX_POINTS_Y - 1)) { + FINAL_MOVE: - // Note: There is no Z Correction in this case. We are off the grid and don't know what - // a reasonable correction would be. If the user has specified a UBL_Z_RAISE_WHEN_OFF_MESH - // value, that will be used instead of a calculated (Bi-Linear interpolation) correction. + // When UBL_Z_RAISE_WHEN_OFF_MESH is disabled Z correction is extrapolated from the edge of the mesh + #ifdef UBL_Z_RAISE_WHEN_OFF_MESH + // For a move off the UBL mesh, use a constant Z raise + if (!cell_index_x_valid(end.x) || !cell_index_y_valid(end.y)) { - #ifdef UBL_Z_RAISE_WHEN_OFF_MESH - end.z += UBL_Z_RAISE_WHEN_OFF_MESH; - #endif - planner.buffer_segment(end, scaled_fr_mm_s, extruder); - current_position = destination; - return; - } + // Note: There is no Z Correction in this case. We are off the mesh and don't know what + // a reasonable correction would be, UBL_Z_RAISE_WHEN_OFF_MESH will be used instead of + // a calculated (Bi-Linear interpolation) correction. - FINAL_MOVE: + end.z += UBL_Z_RAISE_WHEN_OFF_MESH; + planner.buffer_segment(end, scaled_fr_mm_s, extruder); + current_position = destination; + return; + } + #endif // The distance is always MESH_X_DIST so multiply by the constant reciprocal. - const float xratio = (end.x - mesh_index_to_xpos(iend.x)) * RECIPROCAL(MESH_X_DIST); - - float z1, z2; - if (iend.x >= GRID_MAX_POINTS_X - 1) - z1 = z2 = 0.0; - else { - z1 = z_values[iend.x ][iend.y ] + xratio * - (z_values[iend.x + 1][iend.y ] - z_values[iend.x][iend.y ]), - z2 = z_values[iend.x ][iend.y + 1] + xratio * - (z_values[iend.x + 1][iend.y + 1] - z_values[iend.x][iend.y + 1]); - } + const float xratio = (end.x - mesh_index_to_xpos(iend.x)) * RECIPROCAL(MESH_X_DIST), + yratio = (end.y - mesh_index_to_ypos(iend.y)) * RECIPROCAL(MESH_Y_DIST), + z1 = z_values[iend.x][iend.y ] + xratio * (z_values[iend.x + 1][iend.y ] - z_values[iend.x][iend.y ]), + z2 = z_values[iend.x][iend.y + 1] + xratio * (z_values[iend.x + 1][iend.y + 1] - z_values[iend.x][iend.y + 1]); // X cell-fraction done. Interpolate the two Z offsets with the Y fraction for the final Z offset. - const float yratio = (end.y - mesh_index_to_ypos(iend.y)) * RECIPROCAL(MESH_Y_DIST), - z0 = iend.y < GRID_MAX_POINTS_Y - 1 ? (z1 + (z2 - z1) * yratio) * planner.fade_scaling_factor_for_z(end.z) : 0.0; + const float z0 = (z1 + (z2 - z1) * yratio) * planner.fade_scaling_factor_for_z(end.z); // Undefined parts of the Mesh in z_values[][] are NAN. // Replace NAN corrections with 0.0 to prevent NAN propagation. @@ -120,20 +113,22 @@ const xy_float_t ad = sign * dist; const bool use_x_dist = ad.x > ad.y; - float on_axis_distance = use_x_dist ? dist.x : dist.y, - e_position = end.e - start.e, - z_position = end.z - start.z; + float on_axis_distance = use_x_dist ? dist.x : dist.y; - const float e_normalized_dist = e_position / on_axis_distance, // Allow divide by zero - z_normalized_dist = z_position / on_axis_distance; + const float z_normalized_dist = (end.z - start.z) / on_axis_distance; // Allow divide by zero + #if HAS_EXTRUDERS + const float e_normalized_dist = (end.e - start.e) / on_axis_distance; + const bool inf_normalized_flag = isinf(e_normalized_dist); + #endif xy_int8_t icell = istart; const float ratio = dist.y / dist.x, // Allow divide by zero c = start.y - ratio * start.x; - const bool inf_normalized_flag = isinf(e_normalized_dist), - inf_ratio_flag = isinf(ratio); + const bool inf_ratio_flag = isinf(ratio); + + xyze_pos_t dest; // Stores XYZE for segmented moves /** * Handle vertical lines that stay within one column. @@ -150,34 +145,36 @@ * For others the next X is the same so this can continue. * Calculate X at the next Y mesh line. */ - const float rx = inf_ratio_flag ? start.x : (next_mesh_line_y - c) / ratio; + dest.x = inf_ratio_flag ? start.x : (next_mesh_line_y - c) / ratio; - float z0 = z_correction_for_x_on_horizontal_mesh_line(rx, icell.x, icell.y) + float z0 = z_correction_for_x_on_horizontal_mesh_line(dest.x, icell.x, icell.y) * planner.fade_scaling_factor_for_z(end.z); // Undefined parts of the Mesh in z_values[][] are NAN. // Replace NAN corrections with 0.0 to prevent NAN propagation. if (isnan(z0)) z0 = 0.0; - const float ry = mesh_index_to_ypos(icell.y); + dest.y = mesh_index_to_ypos(icell.y); /** * Without this check, it's possible to generate a zero length move, as in the case where * the line is heading down, starting exactly on a mesh line boundary. Since this is rare * it might be fine to remove this check and let planner.buffer_segment() filter it out. */ - if (ry != start.y) { + if (dest.y != start.y) { if (!inf_normalized_flag) { // fall-through faster than branch - on_axis_distance = use_x_dist ? rx - start.x : ry - start.y; - e_position = start.e + on_axis_distance * e_normalized_dist; - z_position = start.z + on_axis_distance * z_normalized_dist; + on_axis_distance = use_x_dist ? dest.x - start.x : dest.y - start.y; + TERN_(HAS_EXTRUDERS, dest.e = start.e + on_axis_distance * e_normalized_dist); + dest.z = start.z + on_axis_distance * z_normalized_dist; } else { - e_position = end.e; - z_position = end.z; + TERN_(HAS_EXTRUDERS, dest.e = end.e); + dest.z = end.z; } - planner.buffer_segment(rx, ry, z_position + z0, e_position, scaled_fr_mm_s, extruder); + dest.z += z0; + planner.buffer_segment(dest, scaled_fr_mm_s, extruder); + } //else printf("FIRST MOVE PRUNED "); } @@ -195,12 +192,13 @@ */ if (iadd.y == 0) { // Horizontal line? icell.x += ineg.x; // Heading left? Just go to the left edge of the cell for the first move. + while (icell.x != iend.x + ineg.x) { icell.x += iadd.x; - const float rx = mesh_index_to_xpos(icell.x); - const float ry = ratio * rx + c; // Calculate Y at the next X mesh line + dest.x = mesh_index_to_xpos(icell.x); + dest.y = ratio * dest.x + c; // Calculate Y at the next X mesh line - float z0 = z_correction_for_y_on_vertical_mesh_line(ry, icell.x, icell.y) + float z0 = z_correction_for_y_on_vertical_mesh_line(dest.y, icell.x, icell.y) * planner.fade_scaling_factor_for_z(end.z); // Undefined parts of the Mesh in z_values[][] are NAN. @@ -212,19 +210,20 @@ * the line is heading left, starting exactly on a mesh line boundary. Since this is rare * it might be fine to remove this check and let planner.buffer_segment() filter it out. */ - if (rx != start.x) { + if (dest.x != start.x) { if (!inf_normalized_flag) { - on_axis_distance = use_x_dist ? rx - start.x : ry - start.y; - e_position = start.e + on_axis_distance * e_normalized_dist; // is based on X or Y because this is a horizontal move - z_position = start.z + on_axis_distance * z_normalized_dist; + on_axis_distance = use_x_dist ? dest.x - start.x : dest.y - start.y; + TERN_(HAS_EXTRUDERS, dest.e = start.e + on_axis_distance * e_normalized_dist); // Based on X or Y because the move is horizontal + dest.z = start.z + on_axis_distance * z_normalized_dist; } else { - e_position = end.e; - z_position = end.z; + TERN_(HAS_EXTRUDERS, dest.e = end.e); + dest.z = end.z; } - if (!planner.buffer_segment(rx, ry, z_position + z0, e_position, scaled_fr_mm_s, extruder)) - break; + dest.z += z0; + if (!planner.buffer_segment(dest, scaled_fr_mm_s, extruder)) break; + } //else printf("FIRST MOVE PRUNED "); } @@ -246,57 +245,65 @@ while (cnt) { const float next_mesh_line_x = mesh_index_to_xpos(icell.x + iadd.x), - next_mesh_line_y = mesh_index_to_ypos(icell.y + iadd.y), - ry = ratio * next_mesh_line_x + c, // Calculate Y at the next X mesh line - rx = (next_mesh_line_y - c) / ratio; // Calculate X at the next Y mesh line - // (No need to worry about ratio == 0. - // In that case, it was already detected - // as a vertical line move above.) - - if (neg.x == (rx > next_mesh_line_x)) { // Check if we hit the Y line first + next_mesh_line_y = mesh_index_to_ypos(icell.y + iadd.y); + + dest.y = ratio * next_mesh_line_x + c; // Calculate Y at the next X mesh line + dest.x = (next_mesh_line_y - c) / ratio; // Calculate X at the next Y mesh line + // (No need to worry about ratio == 0. + // In that case, it was already detected + // as a vertical line move above.) + + if (neg.x == (dest.x > next_mesh_line_x)) { // Check if we hit the Y line first // Yes! Crossing a Y Mesh Line next - float z0 = z_correction_for_x_on_horizontal_mesh_line(rx, icell.x - ineg.x, icell.y + iadd.y) + float z0 = z_correction_for_x_on_horizontal_mesh_line(dest.x, icell.x - ineg.x, icell.y + iadd.y) * planner.fade_scaling_factor_for_z(end.z); // Undefined parts of the Mesh in z_values[][] are NAN. // Replace NAN corrections with 0.0 to prevent NAN propagation. if (isnan(z0)) z0 = 0.0; + dest.y = next_mesh_line_y; + if (!inf_normalized_flag) { - on_axis_distance = use_x_dist ? rx - start.x : next_mesh_line_y - start.y; - e_position = start.e + on_axis_distance * e_normalized_dist; - z_position = start.z + on_axis_distance * z_normalized_dist; + on_axis_distance = use_x_dist ? dest.x - start.x : dest.y - start.y; + TERN_(HAS_EXTRUDERS, dest.e = start.e + on_axis_distance * e_normalized_dist); + dest.z = start.z + on_axis_distance * z_normalized_dist; } else { - e_position = end.e; - z_position = end.z; + TERN_(HAS_EXTRUDERS, dest.e = end.e); + dest.z = end.z; } - if (!planner.buffer_segment(rx, next_mesh_line_y, z_position + z0, e_position, scaled_fr_mm_s, extruder)) - break; + + dest.z += z0; + if (!planner.buffer_segment(dest, scaled_fr_mm_s, extruder)) break; + icell.y += iadd.y; cnt.y--; } else { // Yes! Crossing a X Mesh Line next - float z0 = z_correction_for_y_on_vertical_mesh_line(ry, icell.x + iadd.x, icell.y - ineg.y) + float z0 = z_correction_for_y_on_vertical_mesh_line(dest.y, icell.x + iadd.x, icell.y - ineg.y) * planner.fade_scaling_factor_for_z(end.z); // Undefined parts of the Mesh in z_values[][] are NAN. // Replace NAN corrections with 0.0 to prevent NAN propagation. if (isnan(z0)) z0 = 0.0; + dest.x = next_mesh_line_x; + if (!inf_normalized_flag) { - on_axis_distance = use_x_dist ? next_mesh_line_x - start.x : ry - start.y; - e_position = start.e + on_axis_distance * e_normalized_dist; - z_position = start.z + on_axis_distance * z_normalized_dist; + on_axis_distance = use_x_dist ? dest.x - start.x : dest.y - start.y; + TERN_(HAS_EXTRUDERS, dest.e = start.e + on_axis_distance * e_normalized_dist); + dest.z = start.z + on_axis_distance * z_normalized_dist; } else { - e_position = end.e; - z_position = end.z; + TERN_(HAS_EXTRUDERS, dest.e = end.e); + dest.z = end.z; } - if (!planner.buffer_segment(next_mesh_line_x, ry, z_position + z0, e_position, scaled_fr_mm_s, extruder)) - break; + dest.z += z0; + if (!planner.buffer_segment(dest, scaled_fr_mm_s, extruder)) break; + icell.x += iadd.x; cnt.x--; } @@ -330,7 +337,7 @@ * Returns true if did NOT move, false if moved (requires current_position update). */ - bool _O2 unified_bed_leveling::line_to_destination_segmented(const feedRate_t &scaled_fr_mm_s) { + bool _O2 unified_bed_leveling::line_to_destination_segmented(const_feedRate_t scaled_fr_mm_s) { if (!position_is_reachable(destination)) // fail if moving outside reachable boundary return true; // did not move, so current_position still accurate @@ -342,7 +349,7 @@ #if IS_KINEMATIC const float seconds = cart_xy_mm / scaled_fr_mm_s; // Duration of XY move at requested rate - uint16_t segments = LROUND(delta_segments_per_second * seconds), // Preferred number of segments for distance @ feedrate + 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) #else @@ -369,15 +376,11 @@ while (--segments) { raw += diff; planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, segment_xyz_mm - #if ENABLED(SCARA_FEEDRATE_SCALING) - , inv_duration - #endif + OPTARG(SCARA_FEEDRATE_SCALING, inv_duration) ); } planner.buffer_line(destination, scaled_fr_mm_s, active_extruder, segment_xyz_mm - #if ENABLED(SCARA_FEEDRATE_SCALING) - , inv_duration - #endif + OPTARG(SCARA_FEEDRATE_SCALING, inv_duration) ); return false; // Did not set current from destination } @@ -404,8 +407,8 @@ int8_t((raw.x - (MESH_MIN_X)) * RECIPROCAL(MESH_X_DIST)), int8_t((raw.y - (MESH_MIN_Y)) * RECIPROCAL(MESH_Y_DIST)) }; - LIMIT(icell.x, 0, (GRID_MAX_POINTS_X) - 1); - LIMIT(icell.y, 0, (GRID_MAX_POINTS_Y) - 1); + LIMIT(icell.x, 0, GRID_MAX_CELLS_X); + LIMIT(icell.y, 0, GRID_MAX_CELLS_Y); float z_x0y0 = z_values[icell.x ][icell.y ], // z at lower left corner z_x1y0 = z_values[icell.x+1][icell.y ], // z at upper left corner @@ -449,11 +452,9 @@ #endif ; - planner.buffer_line(raw.x, raw.y, raw.z + z_cxcy, raw.e, scaled_fr_mm_s, active_extruder, segment_xyz_mm - #if ENABLED(SCARA_FEEDRATE_SCALING) - , inv_duration - #endif - ); + const float oldz = raw.z; raw.z += z_cxcy; + planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, segment_xyz_mm OPTARG(SCARA_FEEDRATE_SCALING, inv_duration) ); + raw.z = oldz; if (segments == 0) // done with last segment return false; // didn't set current from destination diff --git a/Marlin/src/feature/binary_stream.h b/Marlin/src/feature/binary_stream.h index 32ebcce2f62f..cef8a3c90211 100644 --- a/Marlin/src/feature/binary_stream.h +++ b/Marlin/src/feature/binary_stream.h @@ -24,44 +24,29 @@ #include "../inc/MarlinConfig.h" #define BINARY_STREAM_COMPRESSION - #if ENABLED(BINARY_STREAM_COMPRESSION) #include "../libs/heatshrink/heatshrink_decoder.h" + // STM32 (and others?) require a word-aligned buffer for SD card transfers via DMA + static __attribute__((aligned(sizeof(size_t)))) uint8_t decode_buffer[512] = {}; + static heatshrink_decoder hsd; #endif -inline bool bs_serial_data_available(const uint8_t index) { - switch (index) { - case 0: return MYSERIAL0.available(); - #if HAS_MULTI_SERIAL - case 1: return MYSERIAL1.available(); - #endif - } - return false; +inline bool bs_serial_data_available(const serial_index_t index) { + return SERIAL_IMPL.available(index); } -inline int bs_read_serial(const uint8_t index) { - switch (index) { - case 0: return MYSERIAL0.read(); - #if HAS_MULTI_SERIAL - case 1: return MYSERIAL1.read(); - #endif - } - return -1; +inline int bs_read_serial(const serial_index_t index) { + return SERIAL_IMPL.read(index); } -#if ENABLED(BINARY_STREAM_COMPRESSION) - static heatshrink_decoder hsd; - static uint8_t decode_buffer[512] = {}; -#endif - class SDFileTransferProtocol { private: struct Packet { struct [[gnu::packed]] Open { - static bool validate(char* buffer, size_t length) { + static bool validate(char *buffer, size_t length) { return (length > sizeof(Open) && buffer[length - 1] == '\0'); } - static Open& decode(char* buffer) { + static Open& decode(char *buffer) { data = &buffer[2]; return *reinterpret_cast(buffer); } @@ -74,7 +59,7 @@ class SDFileTransferProtocol { }; }; - static bool file_open(char* filename) { + static bool file_open(char *filename) { if (!dummy_transfer) { card.mount(); card.openFileWrite(filename); @@ -86,7 +71,7 @@ class SDFileTransferProtocol { return true; } - static bool file_write(char* buffer, const size_t length) { + static bool file_write(char *buffer, const size_t length) { #if ENABLED(BINARY_STREAM_COMPRESSION) if (compression) { size_t total_processed = 0, processed_count = 0; @@ -157,15 +142,15 @@ class SDFileTransferProtocol { } } - static void process(uint8_t packet_type, char* buffer, const uint16_t length) { + static void process(uint8_t packet_type, char *buffer, const uint16_t length) { transfer_timeout = millis() + TIMEOUT; switch (static_cast(packet_type)) { case FileTransfer::QUERY: SERIAL_ECHOPAIR("PFT:version:", VERSION_MAJOR, ".", VERSION_MINOR, ".", VERSION_PATCH); #if ENABLED(BINARY_STREAM_COMPRESSION) - SERIAL_ECHOLNPAIR(":compresion:heatshrink,", HEATSHRINK_STATIC_WINDOW_BITS, ",", HEATSHRINK_STATIC_LOOKAHEAD_BITS); + SERIAL_ECHOLNPAIR(":compression:heatshrink,", HEATSHRINK_STATIC_WINDOW_BITS, ",", HEATSHRINK_STATIC_LOOKAHEAD_BITS); #else - SERIAL_ECHOLNPGM(":compresion:none"); + SERIAL_ECHOLNPGM(":compression:none"); #endif break; case FileTransfer::OPEN: @@ -297,7 +282,7 @@ class BinaryStream { millis_t transfer_window = millis() + RX_TIMESLICE; #if ENABLED(SDSUPPORT) - PORT_REDIRECT(card.transfer_port_index); + PORT_REDIRECT(SERIAL_PORTMASK(card.transfer_port_index)); #endif #pragma GCC diagnostic push @@ -364,8 +349,7 @@ class BinaryStream { } } else { - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR("Packet header(", packet.header.sync, "?) corrupt"); + SERIAL_ECHO_MSG("Packet header(", packet.header.sync, "?) corrupt"); stream_state = StreamState::PACKET_RESEND; } } @@ -399,8 +383,7 @@ class BinaryStream { stream_state = StreamState::PACKET_PROCESS; } else { - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR("Packet(", packet.header.sync, ") payload corrupt"); + SERIAL_ECHO_MSG("Packet(", packet.header.sync, ") payload corrupt"); stream_state = StreamState::PACKET_RESEND; } } @@ -418,8 +401,7 @@ class BinaryStream { if (packet_retries < MAX_RETRIES || MAX_RETRIES == 0) { packet_retries++; stream_state = StreamState::PACKET_RESET; - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR("Resend request ", int(packet_retries)); + SERIAL_ECHO_MSG("Resend request ", packet_retries); SERIAL_ECHOLNPAIR("rs", sync); } else diff --git a/Marlin/src/feature/bltouch.cpp b/Marlin/src/feature/bltouch.cpp index d6b1f99c16b9..7fccc52d0584 100644 --- a/Marlin/src/feature/bltouch.cpp +++ b/Marlin/src/feature/bltouch.cpp @@ -31,6 +31,7 @@ BLTouch bltouch; bool BLTouch::last_written_mode; // Initialized by settings.load, 0 = Open Drain; 1 = 5V Drain #include "../module/servo.h" +#include "../module/probe.h" void stop(); @@ -63,7 +64,7 @@ void BLTouch::init(const bool set_voltage/*=false*/) { #else if (DEBUGGING(LEVELING)) { - DEBUG_ECHOLNPAIR("last_written_mode - ", (int)last_written_mode); + DEBUG_ECHOLNPAIR("last_written_mode - ", last_written_mode); DEBUG_ECHOLNPGM("config mode - " #if ENABLED(BLTOUCH_SET_5V_MODE) "BLTOUCH_SET_5V_MODE" @@ -90,15 +91,7 @@ void BLTouch::clear() { _stow(); // STOW to be ready for meaningful work. Could fail, don't care } -bool BLTouch::triggered() { - return ( - #if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) - READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING - #else - READ(Z_MIN_PROBE_PIN) != Z_MIN_PROBE_ENDSTOP_INVERTING - #endif - ); -} +bool BLTouch::triggered() { return PROBE_TRIGGERED(); } bool BLTouch::deploy_proc() { // Do a DEPLOY @@ -182,7 +175,7 @@ bool BLTouch::status_proc() { _set_SW_mode(); // Incidentally, _set_SW_mode() will also RESET any active alarm const bool tr = triggered(); // If triggered in SW mode, the pin is up, it is STOWED - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("BLTouch is ", (int)tr); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("BLTouch is ", tr); if (tr) _stow(); else _deploy(); // Turn off SW mode, reset any trigger, honor pin state return !tr; @@ -194,7 +187,7 @@ void BLTouch::mode_conv_proc(const bool M5V) { * BLTOUCH V3.0: This will set the mode (twice) and sadly, a STOW is needed at the end, because of the deploy * BLTOUCH V3.1: This will set the mode and store it in the eeprom. The STOW is not needed but does not hurt */ - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("BLTouch Set Mode - ", (int)M5V); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("BLTouch Set Mode - ", M5V); _deploy(); if (M5V) _set_5V_mode(); else _set_OD_mode(); _mode_store(); diff --git a/Marlin/src/feature/bltouch.h b/Marlin/src/feature/bltouch.h index 40685af1b357..9ecccb4256f4 100644 --- a/Marlin/src/feature/bltouch.h +++ b/Marlin/src/feature/bltouch.h @@ -23,19 +23,16 @@ #include "../inc/MarlinConfigPre.h" +#if DISABLED(BLTOUCH_HS_MODE) + #define BLTOUCH_SLOW_MODE 1 +#endif + // BLTouch commands are sent as servo angles typedef unsigned char BLTCommand; -#if ENABLED(CREALITY_TOUCH) - #define STOW_ALARM false - #define BLTOUCH_DEPLOY 170 - #define BLTOUCH_STOW 20 -#else - #define STOW_ALARM true - #define BLTOUCH_DEPLOY 10 - #define BLTOUCH_STOW 90 -#endif - +#define STOW_ALARM true +#define BLTOUCH_DEPLOY 10 +#define BLTOUCH_STOW 90 #define BLTOUCH_SW_MODE 60 #define BLTOUCH_SELFTEST 120 #define BLTOUCH_MODE_STORE 130 @@ -77,33 +74,33 @@ class BLTouch { static bool last_written_mode; // Initialized by settings.load, 0 = Open Drain; 1 = 5V Drain // DEPLOY and STOW are wrapped for error handling - these are used by homing and by probing - FORCE_INLINE static bool deploy() { return deploy_proc(); } - FORCE_INLINE static bool stow() { return stow_proc(); } - FORCE_INLINE static bool status() { return status_proc(); } + static bool deploy() { return deploy_proc(); } + static bool stow() { return stow_proc(); } + static bool status() { return status_proc(); } // Native BLTouch commands ("Underscore"...), used in lcd menus and internally - FORCE_INLINE static void _reset() { command(BLTOUCH_RESET, BLTOUCH_RESET_DELAY); } + static void _reset() { command(BLTOUCH_RESET, BLTOUCH_RESET_DELAY); } - FORCE_INLINE static void _selftest() { command(BLTOUCH_SELFTEST, BLTOUCH_DELAY); } + static void _selftest() { command(BLTOUCH_SELFTEST, BLTOUCH_DELAY); } - FORCE_INLINE static void _set_SW_mode() { command(BLTOUCH_SW_MODE, BLTOUCH_DELAY); } - FORCE_INLINE static void _reset_SW_mode() { if (triggered()) _stow(); else _deploy(); } + static void _set_SW_mode() { command(BLTOUCH_SW_MODE, BLTOUCH_DELAY); } + static void _reset_SW_mode() { if (triggered()) _stow(); else _deploy(); } - FORCE_INLINE static void _set_5V_mode() { command(BLTOUCH_5V_MODE, BLTOUCH_SET5V_DELAY); } - FORCE_INLINE static void _set_OD_mode() { command(BLTOUCH_OD_MODE, BLTOUCH_SETOD_DELAY); } - FORCE_INLINE static void _mode_store() { command(BLTOUCH_MODE_STORE, BLTOUCH_MODE_STORE_DELAY); } + static void _set_5V_mode() { command(BLTOUCH_5V_MODE, BLTOUCH_SET5V_DELAY); } + static void _set_OD_mode() { command(BLTOUCH_OD_MODE, BLTOUCH_SETOD_DELAY); } + static void _mode_store() { command(BLTOUCH_MODE_STORE, BLTOUCH_MODE_STORE_DELAY); } - FORCE_INLINE static void _deploy() { command(BLTOUCH_DEPLOY, BLTOUCH_DEPLOY_DELAY); } - FORCE_INLINE static void _stow() { command(BLTOUCH_STOW, BLTOUCH_STOW_DELAY); } + static void _deploy() { command(BLTOUCH_DEPLOY, BLTOUCH_DEPLOY_DELAY); } + static void _stow() { command(BLTOUCH_STOW, BLTOUCH_STOW_DELAY); } - FORCE_INLINE static void mode_conv_5V() { mode_conv_proc(true); } - FORCE_INLINE static void mode_conv_OD() { mode_conv_proc(false); } + static void mode_conv_5V() { mode_conv_proc(true); } + static void mode_conv_OD() { mode_conv_proc(false); } static bool triggered(); private: - FORCE_INLINE static bool _deploy_query_alarm() { return command(BLTOUCH_DEPLOY, BLTOUCH_DEPLOY_DELAY); } - FORCE_INLINE static bool _stow_query_alarm() { return command(BLTOUCH_STOW, BLTOUCH_STOW_DELAY) == STOW_ALARM; } + static bool _deploy_query_alarm() { return command(BLTOUCH_DEPLOY, BLTOUCH_DEPLOY_DELAY); } + static bool _stow_query_alarm() { return command(BLTOUCH_STOW, BLTOUCH_STOW_DELAY) == STOW_ALARM; } static void clear(); static bool command(const BLTCommand cmd, const millis_t &ms); diff --git a/Marlin/src/feature/cancel_object.cpp b/Marlin/src/feature/cancel_object.cpp index 16f876f13686..ee5716888dc3 100644 --- a/Marlin/src/feature/cancel_object.cpp +++ b/Marlin/src/feature/cancel_object.cpp @@ -25,7 +25,7 @@ #include "cancel_object.h" #include "../gcode/gcode.h" -#include "../lcd/ultralcd.h" +#include "../lcd/marlinui.h" CancelObject cancelable; @@ -43,7 +43,7 @@ void CancelObject::set_active_object(const int8_t obj) { else skipping = false; - #if HAS_DISPLAY + #if BOTH(HAS_STATUS_MESSAGE, CANCEL_OBJECTS_REPORTING) if (active_object >= 0) ui.status_printf_P(0, PSTR(S_FMT " %i"), GET_TEXT(MSG_PRINTING_OBJECT), int(active_object)); else @@ -66,10 +66,8 @@ void CancelObject::uncancel_object(const int8_t obj) { } void CancelObject::report() { - if (active_object >= 0) { - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR("Active Object: ", int(active_object)); - } + if (active_object >= 0) + SERIAL_ECHO_MSG("Active Object: ", active_object); if (canceled) { SERIAL_ECHO_START(); diff --git a/Marlin/src/feature/caselight.cpp b/Marlin/src/feature/caselight.cpp index 8a128bb12def..1baef6d46845 100644 --- a/Marlin/src/feature/caselight.cpp +++ b/Marlin/src/feature/caselight.cpp @@ -28,53 +28,48 @@ CaseLight caselight; -uint8_t CaseLight::brightness = CASE_LIGHT_DEFAULT_BRIGHTNESS; -bool CaseLight::on = CASE_LIGHT_DEFAULT_ON; +#if CASELIGHT_USES_BRIGHTNESS && !defined(CASE_LIGHT_DEFAULT_BRIGHTNESS) + #define CASE_LIGHT_DEFAULT_BRIGHTNESS 0 // For use on PWM pin as non-PWM just sets a default +#endif -#if ENABLED(CASE_LIGHT_USE_NEOPIXEL) - LEDColor CaseLight::color = - #ifdef CASE_LIGHT_NEOPIXEL_COLOR - CASE_LIGHT_NEOPIXEL_COLOR - #else - { 255, 255, 255, 255 } - #endif - ; +#if CASELIGHT_USES_BRIGHTNESS + uint8_t CaseLight::brightness = CASE_LIGHT_DEFAULT_BRIGHTNESS; #endif -#ifndef INVERT_CASE_LIGHT - #define INVERT_CASE_LIGHT false +bool CaseLight::on = CASE_LIGHT_DEFAULT_ON; + +#if CASE_LIGHT_IS_COLOR_LED + #include "leds/leds.h" + constexpr uint8_t init_case_light[] = CASE_LIGHT_DEFAULT_COLOR; + LEDColor CaseLight::color = { init_case_light[0], init_case_light[1], init_case_light[2] OPTARG(HAS_WHITE_LED, init_case_light[3]) }; #endif void CaseLight::update(const bool sflag) { - /** - * The brightness_sav (and sflag) is needed because ARM chips ignore - * a "WRITE(CASE_LIGHT_PIN,x)" command to the pins that are directly - * controlled by the PWM module. In order to turn them off the brightness - * level needs to be set to OFF. Since we can't use the PWM register to - * save the last brightness level we need a variable to save it. - */ - static uint8_t brightness_sav; // Save brightness info for restore on "M355 S1" - - if (on || !sflag) - brightness_sav = brightness; // Save brightness except for M355 S0 - if (sflag && on) - brightness = brightness_sav; // Restore last brightness for M355 S1 - - #if ENABLED(CASE_LIGHT_USE_NEOPIXEL) || DISABLED(CASE_LIGHT_NO_BRIGHTNESS) - const uint8_t i = on ? brightness : 0, n10ct = INVERT_CASE_LIGHT ? 255 - i : i; + #if CASELIGHT_USES_BRIGHTNESS + /** + * The brightness_sav (and sflag) is needed because ARM chips ignore + * a "WRITE(CASE_LIGHT_PIN,x)" command to the pins that are directly + * controlled by the PWM module. In order to turn them off the brightness + * level needs to be set to OFF. Since we can't use the PWM register to + * save the last brightness level we need a variable to save it. + */ + static uint8_t brightness_sav; // Save brightness info for restore on "M355 S1" + + if (on || !sflag) + brightness_sav = brightness; // Save brightness except for M355 S0 + if (sflag && on) + brightness = brightness_sav; // Restore last brightness for M355 S1 + + const uint8_t i = on ? brightness : 0, n10ct = ENABLED(INVERT_CASE_LIGHT) ? 255 - i : i; + UNUSED(n10ct); #endif - #if ENABLED(CASE_LIGHT_USE_NEOPIXEL) + #if CASE_LIGHT_IS_COLOR_LED + leds.set_color(LEDColor(color.r, color.g, color.b OPTARG(HAS_WHITE_LED, color.w), n10ct)); + #else // !CASE_LIGHT_IS_COLOR_LED - leds.set_color( - MakeLEDColor(color.r, color.g, color.b, color.w, n10ct), - false - ); - - #else // !CASE_LIGHT_USE_NEOPIXEL - - #if DISABLED(CASE_LIGHT_NO_BRIGHTNESS) - if (PWM_PIN(CASE_LIGHT_PIN)) + #if CASELIGHT_USES_BRIGHTNESS + if (pin_is_pwm()) analogWrite(pin_t(CASE_LIGHT_PIN), ( #if CASE_LIGHT_MAX_PWM == 255 n10ct @@ -85,11 +80,15 @@ void CaseLight::update(const bool sflag) { else #endif { - const bool s = on ? !INVERT_CASE_LIGHT : INVERT_CASE_LIGHT; + const bool s = on ? TERN(INVERT_CASE_LIGHT, LOW, HIGH) : TERN(INVERT_CASE_LIGHT, HIGH, LOW); WRITE(CASE_LIGHT_PIN, s ? HIGH : LOW); } - #endif // !CASE_LIGHT_USE_NEOPIXEL + #endif // !CASE_LIGHT_IS_COLOR_LED + + #if ENABLED(CASE_LIGHT_USE_RGB_LED) + if (leds.lights_on) leds.update(); else leds.set_off(); + #endif } #endif // CASE_LIGHT_ENABLE diff --git a/Marlin/src/feature/caselight.h b/Marlin/src/feature/caselight.h index 9d1e76da26ba..b2e82f9b838f 100644 --- a/Marlin/src/feature/caselight.h +++ b/Marlin/src/feature/caselight.h @@ -21,24 +21,40 @@ */ #pragma once -#include "../inc/MarlinConfigPre.h" +#include "../inc/MarlinConfig.h" -#if ENABLED(CASE_LIGHT_USE_NEOPIXEL) - #include "leds/leds.h" +#if CASE_LIGHT_IS_COLOR_LED + #include "leds/leds.h" // for LEDColor +#endif + +#if NONE(CASE_LIGHT_NO_BRIGHTNESS, CASE_LIGHT_IS_COLOR_LED) || ENABLED(CASE_LIGHT_USE_NEOPIXEL) + #define CASELIGHT_USES_BRIGHTNESS 1 #endif class CaseLight { public: - static uint8_t brightness; static bool on; + #if ENABLED(CASELIGHT_USES_BRIGHTNESS) + static uint8_t brightness; + #endif + + static bool pin_is_pwm() { return TERN0(NEED_CASE_LIGHT_PIN, PWM_PIN(CASE_LIGHT_PIN)); } + static bool has_brightness() { return TERN0(CASELIGHT_USES_BRIGHTNESS, TERN(CASE_LIGHT_USE_NEOPIXEL, true, pin_is_pwm())); } + + static void init() { + #if NEED_CASE_LIGHT_PIN + if (pin_is_pwm()) SET_PWM(CASE_LIGHT_PIN); else SET_OUTPUT(CASE_LIGHT_PIN); + #endif + update_brightness(); + } static void update(const bool sflag); static inline void update_brightness() { update(false); } - static inline void update_enabled() { update(true); } + static inline void update_enabled() { update(true); } -private: - #if ENABLED(CASE_LIGHT_USE_NEOPIXEL) - static LEDColor color; + #if ENABLED(CASE_LIGHT_IS_COLOR_LED) + private: + static LEDColor color; #endif }; diff --git a/Marlin/src/feature/controllerfan.cpp b/Marlin/src/feature/controllerfan.cpp index fa5a86b0194e..020646775253 100644 --- a/Marlin/src/feature/controllerfan.cpp +++ b/Marlin/src/feature/controllerfan.cpp @@ -34,6 +34,8 @@ uint8_t ControllerFan::speed; #if ENABLED(CONTROLLER_FAN_EDITABLE) controllerFan_settings_t ControllerFan::settings; // {0} + #else + const controllerFan_settings_t &ControllerFan::settings = controllerFan_defaults; #endif void ControllerFan::setup() { diff --git a/Marlin/src/feature/controllerfan.h b/Marlin/src/feature/controllerfan.h index d1d39f21f3f2..55f2d5cfc7aa 100644 --- a/Marlin/src/feature/controllerfan.h +++ b/Marlin/src/feature/controllerfan.h @@ -58,7 +58,7 @@ class ControllerFan { #if ENABLED(CONTROLLER_FAN_EDITABLE) static controllerFan_settings_t settings; #else - static const controllerFan_settings_t constexpr &settings = controllerFan_defaults; + static const controllerFan_settings_t &settings; #endif static inline bool state() { return speed > 0; } static inline void init() { reset(); } diff --git a/Marlin/src/feature/cooler.cpp b/Marlin/src/feature/cooler.cpp new file mode 100644 index 000000000000..e0f99777d19a --- /dev/null +++ b/Marlin/src/feature/cooler.cpp @@ -0,0 +1,48 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../inc/MarlinConfig.h" + +#if EITHER(HAS_COOLER, LASER_COOLANT_FLOW_METER) + +#include "cooler.h" +Cooler cooler; + +#if HAS_COOLER + uint8_t Cooler::mode = 0; + uint16_t Cooler::capacity; + uint16_t Cooler::load; + bool Cooler::enabled = false; +#endif + +#if ENABLED(LASER_COOLANT_FLOW_METER) + bool Cooler::flowmeter = false; + millis_t Cooler::flowmeter_next_ms; // = 0 + volatile uint16_t Cooler::flowpulses; + float Cooler::flowrate; + #if ENABLED(FLOWMETER_SAFETY) + bool Cooler::flowsafety_enabled = true; + bool Cooler::flowfault = false; + #endif +#endif + +#endif // HAS_COOLER || LASER_COOLANT_FLOW_METER diff --git a/Marlin/src/feature/cooler.h b/Marlin/src/feature/cooler.h new file mode 100644 index 000000000000..9891514e23c9 --- /dev/null +++ b/Marlin/src/feature/cooler.h @@ -0,0 +1,109 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include "../inc/MarlinConfigPre.h" + +#ifndef FLOWMETER_PPL + #define FLOWMETER_PPL 5880 // Pulses per liter +#endif +#ifndef FLOWMETER_INTERVAL + #define FLOWMETER_INTERVAL 1000 // milliseconds +#endif + +// Cooling device + +class Cooler { +public: + static uint16_t capacity; // Cooling capacity in watts + static uint16_t load; // Cooling load in watts + + static bool enabled; + static void enable() { enabled = true; } + static void disable() { enabled = false; } + static void toggle() { enabled = !enabled; } + + static uint8_t mode; // 0 = CO2 Liquid cooling, 1 = Laser Diode TEC Heatsink Cooling + static void set_mode(const uint8_t m) { mode = m; } + + #if ENABLED(LASER_COOLANT_FLOW_METER) + static float flowrate; // Flow meter reading in liters-per-minute. + static bool flowmeter; // Flag to monitor the flow + static volatile uint16_t flowpulses; // Flowmeter IRQ pulse count + static millis_t flowmeter_next_ms; // Next time at which to calculate flow + + static void set_flowmeter(const bool sflag) { + if (flowmeter != sflag) { + flowmeter = sflag; + if (sflag) { + flowpulses = 0; + flowmeter_next_ms = millis() + FLOWMETER_INTERVAL; + } + } + } + + // To calculate flow we only need to count pulses + static void flowmeter_ISR() { flowpulses++; } + + // Enable / Disable the flow meter interrupt + static void flowmeter_interrupt_enable() { + attachInterrupt(digitalPinToInterrupt(FLOWMETER_PIN), flowmeter_ISR, RISING); + } + static void flowmeter_interrupt_disable() { + detachInterrupt(digitalPinToInterrupt(FLOWMETER_PIN)); + } + + // Enable / Disable the flow meter interrupt + static void flowmeter_enable() { set_flowmeter(true); flowpulses = 0; flowmeter_interrupt_enable(); } + static void flowmeter_disable() { set_flowmeter(false); flowmeter_interrupt_disable(); flowpulses = 0; } + + // Get the total flow (in liters per minute) since the last reading + static void calc_flowrate() { + // flowrate = (litres) * (seconds) = litres per minute + flowrate = (flowpulses / (float)FLOWMETER_PPL) * ((1000.0f / (float)FLOWMETER_INTERVAL) * 60.0f); + flowpulses = 0; + } + + // Userland task to update the flow meter + static void flowmeter_task(const millis_t ms=millis()) { + if (!flowmeter) // !! The flow meter must always be on !! + flowmeter_enable(); // Init and prime + if (ELAPSED(ms, flowmeter_next_ms)) { + calc_flowrate(); + flowmeter_next_ms = ms + FLOWMETER_INTERVAL; + } + } + + #if ENABLED(FLOWMETER_SAFETY) + static bool flowfault; // Flag that the cooler is in a fault state + static bool flowsafety_enabled; // Flag to disable the cutter if flow rate is too low + static void flowsafety_toggle() { flowsafety_enabled = !flowsafety_enabled; } + static bool check_flow_too_low() { + const bool too_low = flowsafety_enabled && flowrate < (FLOWMETER_MIN_LITERS_PER_MINUTE); + flowfault = too_low; + return too_low; + } + #endif + #endif +}; + +extern Cooler cooler; diff --git a/Marlin/src/feature/dac/dac_dac084s085.cpp b/Marlin/src/feature/dac/dac_dac084s085.cpp index 82d17fa28f07..649aa5561bfa 100644 --- a/Marlin/src/feature/dac/dac_dac084s085.cpp +++ b/Marlin/src/feature/dac/dac_dac084s085.cpp @@ -92,7 +92,7 @@ void dac084s085::cshigh() { WRITE(SPI_EEPROM1_CS, HIGH); WRITE(SPI_EEPROM2_CS, HIGH); WRITE(SPI_FLASH_CS, HIGH); - WRITE(SS_PIN, HIGH); + WRITE(SD_SS_PIN, HIGH); } #endif // MB(ALLIGATOR) diff --git a/Marlin/src/feature/dac/dac_mcp4728.cpp b/Marlin/src/feature/dac/dac_mcp4728.cpp index 81c465cf29e4..6f5a9ee691ac 100644 --- a/Marlin/src/feature/dac/dac_mcp4728.cpp +++ b/Marlin/src/feature/dac/dac_mcp4728.cpp @@ -32,7 +32,7 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(HAS_MOTOR_CURRENT_DAC) +#if HAS_MOTOR_CURRENT_DAC #include "dac_mcp4728.h" @@ -66,14 +66,14 @@ uint8_t MCP4728::analogWrite(const uint8_t channel, const uint16_t value) { } /** - * Write all input resistor values to EEPROM using SequencialWrite method. + * Write all input resistor values to EEPROM using SequentialWrite method. * This will update both input register and EEPROM value * This will also write current Vref, PowerDown, Gain settings to EEPROM */ uint8_t MCP4728::eepromWrite() { Wire.beginTransmission(I2C_ADDRESS(DAC_DEV_ADDRESS)); Wire.write(SEQWRITE); - LOOP_XYZE(i) { + LOOP_LOGICAL_AXES(i) { Wire.write(DAC_STEPPER_VREF << 7 | DAC_STEPPER_GAIN << 4 | highByte(dac_values[i])); Wire.write(lowByte(dac_values[i])); } @@ -81,7 +81,7 @@ uint8_t MCP4728::eepromWrite() { } /** - * Write Voltage reference setting to all input regiters + * Write Voltage reference setting to all input registers */ uint8_t MCP4728::setVref_all(const uint8_t value) { Wire.beginTransmission(I2C_ADDRESS(DAC_DEV_ADDRESS)); @@ -89,7 +89,7 @@ uint8_t MCP4728::setVref_all(const uint8_t value) { return Wire.endTransmission(); } /** - * Write Gain setting to all input regiters + * Write Gain setting to all input registers */ uint8_t MCP4728::setGain_all(const uint8_t value) { Wire.beginTransmission(I2C_ADDRESS(DAC_DEV_ADDRESS)); @@ -123,19 +123,19 @@ uint8_t MCP4728::getDrvPct(const uint8_t channel) { return uint8_t(100.0 * dac_v * Receives all Drive strengths as 0-100 percent values, updates * DAC Values array and calls fastwrite to update the DAC. */ -void MCP4728::setDrvPct(xyze_uint8_t &pct) { - dac_values *= 0.01 * pct * (DAC_STEPPER_MAX); +void MCP4728::setDrvPct(xyze_uint_t &pct) { + dac_values = pct * (DAC_STEPPER_MAX) * 0.01f; fastWrite(); } /** - * FastWrite input register values - All DAC ouput update. refer to DATASHEET 5.6.1 + * FastWrite input register values - All DAC output update. refer to DATASHEET 5.6.1 * DAC Input and PowerDown bits update. * No EEPROM update */ uint8_t MCP4728::fastWrite() { Wire.beginTransmission(I2C_ADDRESS(DAC_DEV_ADDRESS)); - LOOP_XYZE(i) { + LOOP_LOGICAL_AXES(i) { Wire.write(highByte(dac_values[i])); Wire.write(lowByte(dac_values[i])); } diff --git a/Marlin/src/feature/dac/dac_mcp4728.h b/Marlin/src/feature/dac/dac_mcp4728.h index 571716d4834e..3a7d5f10f65c 100644 --- a/Marlin/src/feature/dac/dac_mcp4728.h +++ b/Marlin/src/feature/dac/dac_mcp4728.h @@ -76,7 +76,7 @@ class MCP4728 { static uint8_t fastWrite(); static uint8_t simpleCommand(const byte simpleCommand); static uint8_t getDrvPct(const uint8_t channel); - static void setDrvPct(xyze_uint8_t &pct); + static void setDrvPct(xyze_uint_t &pct); }; extern MCP4728 mcp4728; diff --git a/Marlin/src/feature/dac/stepper_dac.cpp b/Marlin/src/feature/dac/stepper_dac.cpp index 5f10b4ccfbdc..6d03808b8282 100644 --- a/Marlin/src/feature/dac/stepper_dac.cpp +++ b/Marlin/src/feature/dac/stepper_dac.cpp @@ -26,14 +26,14 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(HAS_MOTOR_CURRENT_DAC) +#if HAS_MOTOR_CURRENT_DAC #include "stepper_dac.h" #include "../../MarlinCore.h" // for SP_X_LBL... bool dac_present = false; constexpr xyze_uint8_t dac_order = DAC_STEPPER_ORDER; -xyze_uint8_t dac_channel_pct = DAC_MOTOR_CURRENT_DEFAULT; +xyze_uint_t dac_channel_pct = DAC_MOTOR_CURRENT_DEFAULT; StepperDAC stepper_dac; @@ -51,7 +51,7 @@ int StepperDAC::init() { mcp4728.setVref_all(DAC_STEPPER_VREF); mcp4728.setGain_all(DAC_STEPPER_GAIN); - if (mcp4728.getDrvPct(0) < 1 || mcp4728.getDrvPct(1) < 1 || mcp4728.getDrvPct(2) < 1 || mcp4728.getDrvPct(3) < 1 ) { + if (mcp4728.getDrvPct(0) < 1 || mcp4728.getDrvPct(1) < 1 || mcp4728.getDrvPct(2) < 1 || mcp4728.getDrvPct(3) < 1) { mcp4728.setDrvPct(dac_channel_pct); mcp4728.eepromWrite(); } @@ -72,12 +72,12 @@ void StepperDAC::set_current_percent(const uint8_t channel, float val) { set_current_value(channel, _MIN(val, 100.0f) * (DAC_STEPPER_MAX) / 100.0f); } -static float dac_perc(int8_t n) { return 100.0 * mcp4728.getValue(dac_order[n]) * RECIPROCAL(DAC_STEPPER_MAX); } -static float dac_amps(int8_t n) { return mcp4728.getDrvPct(dac_order[n]) * (DAC_STEPPER_MAX) * 0.125 * RECIPROCAL(DAC_STEPPER_SENSE); } +static float dac_perc(int8_t n) { return mcp4728.getDrvPct(dac_order[n]); } +static float dac_amps(int8_t n) { return mcp4728.getValue(dac_order[n]) * 0.125 * RECIPROCAL(DAC_STEPPER_SENSE * 1000); } uint8_t StepperDAC::get_current_percent(const AxisEnum axis) { return mcp4728.getDrvPct(dac_order[axis]); } void StepperDAC::set_current_percents(xyze_uint8_t &pct) { - LOOP_XYZE(i) dac_channel_pct[i] = pct[dac_order[i]]; + LOOP_LOGICAL_AXES(i) dac_channel_pct[i] = pct[dac_order[i]]; mcp4728.setDrvPct(dac_channel_pct); } @@ -85,10 +85,16 @@ void StepperDAC::print_values() { if (!dac_present) return; SERIAL_ECHO_MSG("Stepper current values in % (Amps):"); SERIAL_ECHO_START(); - SERIAL_ECHOPAIR_P( SP_X_LBL, dac_perc(X_AXIS), PSTR(" ("), dac_amps(X_AXIS), PSTR(")")); - SERIAL_ECHOPAIR_P( SP_Y_LBL, dac_perc(Y_AXIS), PSTR(" ("), dac_amps(Y_AXIS), PSTR(")")); - SERIAL_ECHOPAIR_P( SP_Z_LBL, dac_perc(Z_AXIS), PSTR(" ("), dac_amps(Z_AXIS), PSTR(")")); - SERIAL_ECHOLNPAIR_P(SP_E_LBL, dac_perc(E_AXIS), PSTR(" ("), dac_amps(E_AXIS), PSTR(")")); + SERIAL_ECHOPAIR_P(SP_X_LBL, dac_perc(X_AXIS), PSTR(" ("), dac_amps(X_AXIS), PSTR(")")); + #if HAS_Y_AXIS + SERIAL_ECHOPAIR_P(SP_Y_LBL, dac_perc(Y_AXIS), PSTR(" ("), dac_amps(Y_AXIS), PSTR(")")); + #endif + #if HAS_Z_AXIS + SERIAL_ECHOPAIR_P(SP_Z_LBL, dac_perc(Z_AXIS), PSTR(" ("), dac_amps(Z_AXIS), PSTR(")")); + #endif + #if HAS_EXTRUDERS + SERIAL_ECHOLNPAIR_P(SP_E_LBL, dac_perc(E_AXIS), PSTR(" ("), dac_amps(E_AXIS), PSTR(")")); + #endif } void StepperDAC::commit_eeprom() { diff --git a/Marlin/src/feature/dac/stepper_dac.h b/Marlin/src/feature/dac/stepper_dac.h index 6836335e9806..26a0f2f95cc8 100644 --- a/Marlin/src/feature/dac/stepper_dac.h +++ b/Marlin/src/feature/dac/stepper_dac.h @@ -34,7 +34,7 @@ class StepperDAC { static void set_current_value(const uint8_t channel, uint16_t val); static void print_values(); static void commit_eeprom(); - static uint8_t get_current_percent(AxisEnum axis); + static uint8_t get_current_percent(const AxisEnum axis); static void set_current_percents(xyze_uint8_t &pct); }; diff --git a/Marlin/src/feature/digipot/digipot.h b/Marlin/src/feature/digipot/digipot.h index c53f8093dd52..3fbd1f36625e 100644 --- a/Marlin/src/feature/digipot/digipot.h +++ b/Marlin/src/feature/digipot/digipot.h @@ -30,4 +30,4 @@ class DigipotI2C { static void set_current(const uint8_t channel, const float current); }; -DigipotI2C digipot_i2c; +extern DigipotI2C digipot_i2c; diff --git a/Marlin/src/feature/digipot/digipot_mcp4018.cpp b/Marlin/src/feature/digipot/digipot_mcp4018.cpp index 6260185fc32d..37853ff428bc 100644 --- a/Marlin/src/feature/digipot/digipot_mcp4018.cpp +++ b/Marlin/src/feature/digipot/digipot_mcp4018.cpp @@ -27,7 +27,7 @@ #include "digipot.h" #include -#include // https://github.com/stawel/SlowSoftI2CMaster +#include // https://github.com/felias-fogg/SlowSoftI2CMaster // Settings for the I2C based DIGIPOT (MCP4018) based on WT150 @@ -46,21 +46,21 @@ static byte current_to_wiper(const float current) { } static SlowSoftI2CMaster pots[DIGIPOT_I2C_NUM_CHANNELS] = { - SlowSoftI2CMaster(DIGIPOTS_I2C_SDA_X, DIGIPOTS_I2C_SCL) + SlowSoftI2CMaster(DIGIPOTS_I2C_SDA_X, DIGIPOTS_I2C_SCL, ENABLED(DIGIPOT_ENABLE_I2C_PULLUPS)) #if DIGIPOT_I2C_NUM_CHANNELS > 1 - , SlowSoftI2CMaster(DIGIPOTS_I2C_SDA_Y, DIGIPOTS_I2C_SCL) + , SlowSoftI2CMaster(DIGIPOTS_I2C_SDA_Y, DIGIPOTS_I2C_SCL, ENABLED(DIGIPOT_ENABLE_I2C_PULLUPS)) #if DIGIPOT_I2C_NUM_CHANNELS > 2 - , SlowSoftI2CMaster(DIGIPOTS_I2C_SDA_Z, DIGIPOTS_I2C_SCL) + , SlowSoftI2CMaster(DIGIPOTS_I2C_SDA_Z, DIGIPOTS_I2C_SCL, ENABLED(DIGIPOT_ENABLE_I2C_PULLUPS)) #if DIGIPOT_I2C_NUM_CHANNELS > 3 - , SlowSoftI2CMaster(DIGIPOTS_I2C_SDA_E0, DIGIPOTS_I2C_SCL) + , SlowSoftI2CMaster(DIGIPOTS_I2C_SDA_E0, DIGIPOTS_I2C_SCL, ENABLED(DIGIPOT_ENABLE_I2C_PULLUPS)) #if DIGIPOT_I2C_NUM_CHANNELS > 4 - , SlowSoftI2CMaster(DIGIPOTS_I2C_SDA_E1, DIGIPOTS_I2C_SCL) + , SlowSoftI2CMaster(DIGIPOTS_I2C_SDA_E1, DIGIPOTS_I2C_SCL, ENABLED(DIGIPOT_ENABLE_I2C_PULLUPS)) #if DIGIPOT_I2C_NUM_CHANNELS > 5 - , SlowSoftI2CMaster(DIGIPOTS_I2C_SDA_E2, DIGIPOTS_I2C_SCL) + , SlowSoftI2CMaster(DIGIPOTS_I2C_SDA_E2, DIGIPOTS_I2C_SCL, ENABLED(DIGIPOT_ENABLE_I2C_PULLUPS)) #if DIGIPOT_I2C_NUM_CHANNELS > 6 - , SlowSoftI2CMaster(DIGIPOTS_I2C_SDA_E3, DIGIPOTS_I2C_SCL) + , SlowSoftI2CMaster(DIGIPOTS_I2C_SDA_E3, DIGIPOTS_I2C_SCL, ENABLED(DIGIPOT_ENABLE_I2C_PULLUPS)) #if DIGIPOT_I2C_NUM_CHANNELS > 7 - , SlowSoftI2CMaster(DIGIPOTS_I2C_SDA_E4, DIGIPOTS_I2C_SCL) + , SlowSoftI2CMaster(DIGIPOTS_I2C_SDA_E4, DIGIPOTS_I2C_SCL, ENABLED(DIGIPOT_ENABLE_I2C_PULLUPS)) #endif #endif #endif @@ -99,4 +99,6 @@ void DigipotI2C::init() { set_current(i, pgm_read_float(&digipot_motor_current[i])); } +DigipotI2C digipot_i2c; + #endif // DIGIPOT_MCP4018 diff --git a/Marlin/src/feature/digipot/digipot_mcp4451.cpp b/Marlin/src/feature/digipot/digipot_mcp4451.cpp index 7e6ace49a06a..ba5ecdad050a 100644 --- a/Marlin/src/feature/digipot/digipot_mcp4451.cpp +++ b/Marlin/src/feature/digipot/digipot_mcp4451.cpp @@ -40,6 +40,9 @@ #elif MB(AZTEEG_X5_MINI, AZTEEG_X5_MINI_WIFI) #define DIGIPOT_I2C_FACTOR 113.5f #define DIGIPOT_I2C_MAX_CURRENT 2.0f +#elif MB(AZTEEG_X5_GT) + #define DIGIPOT_I2C_FACTOR 51.0f + #define DIGIPOT_I2C_MAX_CURRENT 3.0f #else #define DIGIPOT_I2C_FACTOR 106.7f #define DIGIPOT_I2C_MAX_CURRENT 2.5f @@ -95,4 +98,6 @@ void DigipotI2C::init() { set_current(i, pgm_read_float(&digipot_motor_current[i])); } +DigipotI2C digipot_i2c; + #endif // DIGIPOT_MCP4451 diff --git a/Marlin/src/feature/direct_stepping.cpp b/Marlin/src/feature/direct_stepping.cpp index 9766d1464053..2698b53dd6f7 100644 --- a/Marlin/src/feature/direct_stepping.cpp +++ b/Marlin/src/feature/direct_stepping.cpp @@ -180,7 +180,7 @@ namespace DirectStepping { if (!page_states_dirty) return; page_states_dirty = false; - SERIAL_ECHO(Cfg::CONTROL_CHAR); + SERIAL_CHAR(Cfg::CONTROL_CHAR); constexpr int state_bits = 2; constexpr int n_bytes = Cfg::NUM_PAGES >> state_bits; volatile uint8_t bits_b[n_bytes] = { 0 }; @@ -192,10 +192,10 @@ namespace DirectStepping { uint8_t crc = 0; for (uint8_t i = 0 ; i < n_bytes ; i++) { crc ^= bits_b[i]; - SERIAL_ECHO(bits_b[i]); + SERIAL_CHAR(bits_b[i]); } - SERIAL_ECHO(crc); + SERIAL_CHAR(crc); SERIAL_EOL(); } diff --git a/Marlin/src/feature/direct_stepping.h b/Marlin/src/feature/direct_stepping.h index cde9d1a0b438..b3007731cdb2 100644 --- a/Marlin/src/feature/direct_stepping.h +++ b/Marlin/src/feature/direct_stepping.h @@ -93,8 +93,8 @@ namespace DirectStepping { static constexpr int DIRECTIONAL = dir ? 1 : 0; static constexpr int SEGMENTS = segments; - static constexpr int NUM_SEGMENTS = 1 << BITS_SEGMENT; - static constexpr int SEGMENT_STEPS = (1 << (BITS_SEGMENT - DIRECTIONAL)) - 1; + static constexpr int NUM_SEGMENTS = _BV(BITS_SEGMENT); + static constexpr int SEGMENT_STEPS = _BV(BITS_SEGMENT - DIRECTIONAL) - 1; static constexpr int TOTAL_STEPS = SEGMENT_STEPS * SEGMENTS; static constexpr int PAGE_SIZE = (NUM_AXES * BITS_SEGMENT * SEGMENTS) / 8; diff --git a/Marlin/src/feature/e_parser.cpp b/Marlin/src/feature/e_parser.cpp index a4c2d0dac92c..d98afcfee71b 100644 --- a/Marlin/src/feature/e_parser.cpp +++ b/Marlin/src/feature/e_parser.cpp @@ -32,6 +32,7 @@ // Static data members bool EmergencyParser::killed_by_M112, // = false + EmergencyParser::quickstop_by_M410, EmergencyParser::enabled; #if ENABLED(HOST_PROMPT_SUPPORT) diff --git a/Marlin/src/feature/e_parser.h b/Marlin/src/feature/e_parser.h index 085cbd4eab0e..3723caa35eea 100644 --- a/Marlin/src/feature/e_parser.h +++ b/Marlin/src/feature/e_parser.h @@ -33,36 +33,46 @@ // External references extern bool wait_for_user, wait_for_heatup; -void quickstop_stepper(); + +#if ENABLED(REALTIME_REPORTING_COMMANDS) + // From motion.h, which cannot be included here + void report_current_position_moving(); + void quickpause_stepper(); + void quickresume_stepper(); +#endif + +void HAL_reboot(); class EmergencyParser { public: - // Currently looking for: M108, M112, M410, M876 - enum State : char { + // Currently looking for: M108, M112, M410, M876 S[0-9], S000, P000, R000 + enum State : uint8_t { EP_RESET, EP_N, EP_M, EP_M1, - EP_M10, - EP_M108, - EP_M11, - EP_M112, - EP_M4, - EP_M41, - EP_M410, + EP_M10, EP_M108, + EP_M11, EP_M112, + EP_M4, EP_M41, EP_M410, #if ENABLED(HOST_PROMPT_SUPPORT) - EP_M8, - EP_M87, - EP_M876, - EP_M876S, - EP_M876SN, + EP_M8, EP_M87, EP_M876, EP_M876S, EP_M876SN, + #endif + #if ENABLED(REALTIME_REPORTING_COMMANDS) + EP_S, EP_S0, EP_S00, EP_GRBL_STATUS, + EP_R, EP_R0, EP_R00, EP_GRBL_RESUME, + EP_P, EP_P0, EP_P00, EP_GRBL_PAUSE, + #endif + #if ENABLED(SOFT_RESET_VIA_SERIAL) + EP_ctrl, + EP_K, EP_KI, EP_KIL, EP_KILL, #endif EP_IGNORE // to '\n' }; static bool killed_by_M112; + static bool quickstop_by_M410; #if ENABLED(HOST_PROMPT_SUPPORT) static uint8_t M876_reason; @@ -71,30 +81,63 @@ class EmergencyParser { EmergencyParser() { enable(); } FORCE_INLINE static void enable() { enabled = true; } - FORCE_INLINE static void disable() { enabled = false; } FORCE_INLINE static void update(State &state, const uint8_t c) { - #define ISEOL(C) ((C) == '\n' || (C) == '\r') switch (state) { case EP_RESET: switch (c) { case ' ': case '\n': case '\r': break; - case 'N': state = EP_N; break; - case 'M': state = EP_M; break; - default: state = EP_IGNORE; + case 'N': state = EP_N; break; + case 'M': state = EP_M; break; + #if ENABLED(REALTIME_REPORTING_COMMANDS) + case 'S': state = EP_S; break; + case 'P': state = EP_P; break; + case 'R': state = EP_R; break; + #endif + #if ENABLED(SOFT_RESET_VIA_SERIAL) + case '^': state = EP_ctrl; break; + case 'K': state = EP_K; break; + #endif + default: state = EP_IGNORE; } break; case EP_N: switch (c) { case '0' ... '9': - case '-': case ' ': break; - case 'M': state = EP_M; break; - default: state = EP_IGNORE; + case '-': case ' ': break; + case 'M': state = EP_M; break; + #if ENABLED(REALTIME_REPORTING_COMMANDS) + case 'S': state = EP_S; break; + case 'P': state = EP_P; break; + case 'R': state = EP_R; break; + #endif + default: state = EP_IGNORE; } break; + #if ENABLED(REALTIME_REPORTING_COMMANDS) + case EP_S: state = (c == '0') ? EP_S0 : EP_IGNORE; break; + case EP_S0: state = (c == '0') ? EP_S00 : EP_IGNORE; break; + case EP_S00: state = (c == '0') ? EP_GRBL_STATUS : EP_IGNORE; break; + + case EP_R: state = (c == '0') ? EP_R0 : EP_IGNORE; break; + case EP_R0: state = (c == '0') ? EP_R00 : EP_IGNORE; break; + case EP_R00: state = (c == '0') ? EP_GRBL_RESUME : EP_IGNORE; break; + + case EP_P: state = (c == '0') ? EP_P0 : EP_IGNORE; break; + case EP_P0: state = (c == '0') ? EP_P00 : EP_IGNORE; break; + case EP_P00: state = (c == '0') ? EP_GRBL_PAUSE : EP_IGNORE; break; + #endif + + #if ENABLED(SOFT_RESET_VIA_SERIAL) + case EP_ctrl: state = (c == 'X') ? EP_KILL : EP_IGNORE; break; + case EP_K: state = (c == 'I') ? EP_KI : EP_IGNORE; break; + case EP_KI: state = (c == 'L') ? EP_KIL : EP_IGNORE; break; + case EP_KIL: state = (c == 'L') ? EP_KILL : EP_IGNORE; break; + #endif + case EP_M: switch (c) { case ' ': break; @@ -115,48 +158,34 @@ class EmergencyParser { } break; - case EP_M10: - state = (c == '8') ? EP_M108 : EP_IGNORE; - break; - - case EP_M11: - state = (c == '2') ? EP_M112 : EP_IGNORE; - break; - - case EP_M4: - state = (c == '1') ? EP_M41 : EP_IGNORE; - break; - - case EP_M41: - state = (c == '0') ? EP_M410 : EP_IGNORE; - break; + case EP_M10: state = (c == '8') ? EP_M108 : EP_IGNORE; break; + case EP_M11: state = (c == '2') ? EP_M112 : EP_IGNORE; break; + case EP_M4: state = (c == '1') ? EP_M41 : EP_IGNORE; break; + case EP_M41: state = (c == '0') ? EP_M410 : EP_IGNORE; break; #if ENABLED(HOST_PROMPT_SUPPORT) - case EP_M8: - state = (c == '7') ? EP_M87 : EP_IGNORE; - break; - case EP_M87: - state = (c == '6') ? EP_M876 : EP_IGNORE; - break; + case EP_M8: state = (c == '7') ? EP_M87 : EP_IGNORE; break; + case EP_M87: state = (c == '6') ? EP_M876 : EP_IGNORE; break; - case EP_M876: - switch (c) { - case ' ': break; - case 'S': state = EP_M876S; break; - default: state = EP_IGNORE; break; - } - break; + case EP_M876: + switch (c) { + case ' ': break; + case 'S': state = EP_M876S; break; + default: state = EP_IGNORE; break; + } + break; + + case EP_M876S: + switch (c) { + case ' ': break; + case '0' ... '9': + state = EP_M876SN; + M876_reason = uint8_t(c - '0'); + break; + } + break; - case EP_M876S: - switch (c) { - case ' ': break; - case '0' ... '9': - state = EP_M876SN; - M876_reason = (uint8_t)(c - '0'); - break; - } - break; #endif case EP_IGNORE: @@ -168,10 +197,18 @@ class EmergencyParser { if (enabled) switch (state) { case EP_M108: wait_for_user = wait_for_heatup = false; break; case EP_M112: killed_by_M112 = true; break; - case EP_M410: quickstop_stepper(); break; + case EP_M410: quickstop_by_M410 = true; break; #if ENABLED(HOST_PROMPT_SUPPORT) case EP_M876SN: host_response_handler(M876_reason); break; #endif + #if ENABLED(REALTIME_REPORTING_COMMANDS) + case EP_GRBL_STATUS: report_current_position_moving(); break; + case EP_GRBL_PAUSE: quickpause_stepper(); break; + case EP_GRBL_RESUME: quickresume_stepper(); break; + #endif + #if ENABLED(SOFT_RESET_VIA_SERIAL) + case EP_KILL: HAL_reboot(); break; + #endif default: break; } state = EP_RESET; diff --git a/Marlin/src/feature/encoder_i2c.cpp b/Marlin/src/feature/encoder_i2c.cpp index 8a3e959e0702..283092e3447f 100644 --- a/Marlin/src/feature/encoder_i2c.cpp +++ b/Marlin/src/feature/encoder_i2c.cpp @@ -34,7 +34,6 @@ #include "encoder_i2c.h" -#include "../module/temperature.h" #include "../module/stepper.h" #include "../gcode/parser.h" @@ -42,13 +41,15 @@ #include +I2CPositionEncodersMgr I2CPEM; + void I2CPositionEncoder::init(const uint8_t address, const AxisEnum axis) { encoderAxis = axis; i2cAddress = address; - initialized++; + initialized = true; - SERIAL_ECHOLNPAIR("Setting up encoder on ", axis_codes[encoderAxis], " axis, addr = ", address); + SERIAL_ECHOLNPAIR("Setting up encoder on ", AS_CHAR(axis_codes[encoderAxis]), " axis, addr = ", address); position = get_position(); } @@ -66,7 +67,7 @@ void I2CPositionEncoder::update() { /* if (trusted) { //commented out as part of the note below trusted = false; - SERIAL_ECHOLMPAIR("Fault detected on ", axis_codes[encoderAxis], " axis encoder. Disengaging error correction until module is trusted again."); + SERIAL_ECHOLNPAIR("Fault detected on ", AS_CHAR(axis_codes[encoderAxis]), " axis encoder. Disengaging error correction until module is trusted again."); } */ return; @@ -85,15 +86,15 @@ void I2CPositionEncoder::update() { * the encoder would be re-enabled. */ - /* + #if 0 // If the magnetic strength has been good for a certain time, start trusting the module again if (millis() - lastErrorTime > I2CPE_TIME_TRUSTED) { trusted = true; - SERIAL_ECHOLNPAIR("Untrusted encoder module on ", axis_codes[encoderAxis], " axis has been fault-free for set duration, reinstating error correction."); + SERIAL_ECHOLNPAIR("Untrusted encoder module on ", AS_CHAR(axis_codes[encoderAxis]), " axis has been fault-free for set duration, reinstating error correction."); - //the encoder likely lost its place when the error occured, so we'll reset and use the printer's + //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 const float pos = planner.get_axis_position_mm(encoderAxis); int32_t positionInTicks = pos * get_ticks_unit(); @@ -111,7 +112,7 @@ void I2CPositionEncoder::update() { SERIAL_ECHOLNPGM(")"); #endif } - */ + #endif return; } @@ -171,7 +172,7 @@ void I2CPositionEncoder::update() { float sumP = 0; LOOP_L_N(i, I2CPE_ERR_PRST_ARRAY_SIZE) sumP += errPrst[i]; const int32_t errorP = int32_t(sumP * RECIPROCAL(I2CPE_ERR_PRST_ARRAY_SIZE)); - SERIAL_ECHO(axis_codes[encoderAxis]); + SERIAL_CHAR(axis_codes[encoderAxis]); SERIAL_ECHOLNPAIR(" : CORRECT ERR ", errorP * planner.steps_to_mm[encoderAxis], "mm"); babystep.add_steps(encoderAxis, -LROUND(errorP)); errPrstIdx = 0; @@ -191,8 +192,8 @@ void I2CPositionEncoder::update() { if (ABS(error) > I2CPE_ERR_CNT_THRESH * planner.settings.axis_steps_per_mm[encoderAxis]) { const millis_t ms = millis(); if (ELAPSED(ms, nextErrorCountTime)) { - SERIAL_ECHO(axis_codes[encoderAxis]); - SERIAL_ECHOLNPAIR(" : LARGE ERR ", int(error), "; diffSum=", diffSum); + SERIAL_CHAR(axis_codes[encoderAxis]); + SERIAL_ECHOLNPAIR(" : LARGE ERR ", error, "; diffSum=", diffSum); errorCount++; nextErrorCountTime = ms + I2CPE_ERR_CNT_DEBOUNCE_MS; } @@ -208,11 +209,10 @@ void I2CPositionEncoder::set_homed() { delay(10); zeroOffset = get_raw_count(); - homed++; - trusted++; + homed = trusted = true; #ifdef I2CPE_DEBUG - SERIAL_ECHO(axis_codes[encoderAxis]); + SERIAL_CHAR(axis_codes[encoderAxis]); SERIAL_ECHOLNPAIR(" axis encoder homed, offset of ", zeroOffset, " ticks."); #endif } @@ -223,7 +223,7 @@ void I2CPositionEncoder::set_unhomed() { homed = trusted = false; #ifdef I2CPE_DEBUG - SERIAL_ECHO(axis_codes[encoderAxis]); + SERIAL_CHAR(axis_codes[encoderAxis]); SERIAL_ECHOLNPGM(" axis encoder unhomed."); #endif } @@ -231,7 +231,7 @@ void I2CPositionEncoder::set_unhomed() { bool I2CPositionEncoder::passes_test(const bool report) { if (report) { if (H != I2CPE_MAG_SIG_GOOD) SERIAL_ECHOPGM("Warning. "); - SERIAL_ECHO(axis_codes[encoderAxis]); + SERIAL_CHAR(axis_codes[encoderAxis]); serial_ternary(H == I2CPE_MAG_SIG_BAD, PSTR(" axis "), PSTR("magnetic strip "), PSTR("encoder ")); switch (H) { case I2CPE_MAG_SIG_GOOD: @@ -252,7 +252,7 @@ float I2CPositionEncoder::get_axis_error_mm(const bool report) { error = ABS(diff) > 10000 ? 0 : diff; // Huge error is a bad reading if (report) { - SERIAL_ECHO(axis_codes[encoderAxis]); + SERIAL_CHAR(axis_codes[encoderAxis]); SERIAL_ECHOLNPAIR(" axis target=", target, "mm; actual=", actual, "mm; err=", error, "mm"); } @@ -262,7 +262,7 @@ float I2CPositionEncoder::get_axis_error_mm(const bool report) { int32_t I2CPositionEncoder::get_axis_error_steps(const bool report) { if (!active) { if (report) { - SERIAL_ECHO(axis_codes[encoderAxis]); + SERIAL_CHAR(axis_codes[encoderAxis]); SERIAL_ECHOLNPGM(" axis encoder not active!"); } return 0; @@ -287,7 +287,7 @@ int32_t I2CPositionEncoder::get_axis_error_steps(const bool report) { errorPrev = error; if (report) { - SERIAL_ECHO(axis_codes[encoderAxis]); + SERIAL_CHAR(axis_codes[encoderAxis]); SERIAL_ECHOLNPAIR(" axis target=", target, "; actual=", encoderCountInStepperTicksScaled, "; err=", error); } @@ -327,17 +327,17 @@ int32_t I2CPositionEncoder::get_raw_count() { } bool I2CPositionEncoder::test_axis() { - //only works on XYZ cartesian machines for the time being + // Only works on XYZ Cartesian machines for the time being if (!(encoderAxis == X_AXIS || encoderAxis == Y_AXIS || encoderAxis == Z_AXIS)) return false; const float startPosition = soft_endstop.min[encoderAxis] + 10, endPosition = soft_endstop.max[encoderAxis] - 10; - const feedRate_t fr_mm_s = FLOOR(MMM_TO_MMS((encoderAxis == Z_AXIS) ? HOMING_FEEDRATE_Z : HOMING_FEEDRATE_XY)); + const feedRate_t fr_mm_s = FLOOR(homing_feedrate(encoderAxis)); ec = false; xyze_pos_t startCoord, endCoord; - LOOP_XYZ(a) { + LOOP_LINEAR_AXES(a) { startCoord[a] = planner.get_axis_position_mm((AxisEnum)a); endCoord[a] = planner.get_axis_position_mm((AxisEnum)a); } @@ -345,9 +345,12 @@ bool I2CPositionEncoder::test_axis() { endCoord[encoderAxis] = endPosition; planner.synchronize(); - startCoord.e = planner.get_axis_position_mm(E_AXIS); - planner.buffer_line(startCoord, fr_mm_s, 0); - planner.synchronize(); + + #if HAS_EXTRUDERS + startCoord.e = planner.get_axis_position_mm(E_AXIS); + planner.buffer_line(startCoord, fr_mm_s, 0); + planner.synchronize(); + #endif // if the module isn't currently trusted, wait until it is (or until it should be if things are working) if (!trusted) { @@ -357,7 +360,7 @@ bool I2CPositionEncoder::test_axis() { } if (trusted) { // if trusted, commence test - endCoord.e = planner.get_axis_position_mm(E_AXIS); + TERN_(HAS_EXTRUDERS, endCoord.e = planner.get_axis_position_mm(E_AXIS)); planner.buffer_line(endCoord, fr_mm_s, 0); planner.synchronize(); } @@ -382,7 +385,7 @@ void I2CPositionEncoder::calibrate_steps_mm(const uint8_t iter) { int32_t startCount, stopCount; - const feedRate_t fr_mm_s = MMM_TO_MMS((encoderAxis == Z_AXIS) ? HOMING_FEEDRATE_Z : HOMING_FEEDRATE_XY); + const feedRate_t fr_mm_s = homing_feedrate(encoderAxis); bool oldec = ec; ec = false; @@ -392,7 +395,7 @@ void I2CPositionEncoder::calibrate_steps_mm(const uint8_t iter) { travelDistance = endDistance - startDistance; xyze_pos_t startCoord, endCoord; - LOOP_XYZ(a) { + LOOP_LINEAR_AXES(a) { startCoord[a] = planner.get_axis_position_mm((AxisEnum)a); endCoord[a] = planner.get_axis_position_mm((AxisEnum)a); } @@ -402,7 +405,7 @@ void I2CPositionEncoder::calibrate_steps_mm(const uint8_t iter) { planner.synchronize(); LOOP_L_N(i, iter) { - startCoord.e = planner.get_axis_position_mm(E_AXIS); + TERN_(HAS_EXTRUDERS, startCoord.e = planner.get_axis_position_mm(E_AXIS)); planner.buffer_line(startCoord, fr_mm_s, 0); planner.synchronize(); @@ -411,7 +414,7 @@ void I2CPositionEncoder::calibrate_steps_mm(const uint8_t iter) { //do_blocking_move_to(endCoord); - endCoord.e = planner.get_axis_position_mm(E_AXIS); + TERN_(HAS_EXTRUDERS, endCoord.e = planner.get_axis_position_mm(E_AXIS)); planner.buffer_line(endCoord, fr_mm_s, 0); planner.synchronize(); @@ -497,9 +500,7 @@ void I2CPositionEncodersMgr::init() { encoders[i].set_active(encoders[i].passes_test(true)); - #if I2CPE_ENC_1_AXIS == E_AXIS - encoders[i].set_homed(); - #endif + TERN_(HAS_EXTRUDERS, if (I2CPE_ENC_1_AXIS == E_AXIS) encoders[i].set_homed()); #endif #if I2CPE_ENCODER_CNT > 1 @@ -528,9 +529,7 @@ void I2CPositionEncodersMgr::init() { encoders[i].set_active(encoders[i].passes_test(true)); - #if I2CPE_ENC_2_AXIS == E_AXIS - encoders[i].set_homed(); - #endif + TERN_(HAS_EXTRUDERS, if (I2CPE_ENC_2_AXIS == E_AXIS) encoders[i].set_homed()); #endif #if I2CPE_ENCODER_CNT > 2 @@ -557,11 +556,9 @@ void I2CPositionEncodersMgr::init() { encoders[i].set_ec_threshold(I2CPE_ENC_3_EC_THRESH); #endif - encoders[i].set_active(encoders[i].passes_test(true)); + encoders[i].set_active(encoders[i].passes_test(true)); - #if I2CPE_ENC_3_AXIS == E_AXIS - encoders[i].set_homed(); - #endif + TERN_(HAS_EXTRUDERS, if (I2CPE_ENC_3_AXIS == E_AXIS) encoders[i].set_homed()); #endif #if I2CPE_ENCODER_CNT > 3 @@ -590,9 +587,7 @@ void I2CPositionEncodersMgr::init() { encoders[i].set_active(encoders[i].passes_test(true)); - #if I2CPE_ENC_4_AXIS == E_AXIS - encoders[i].set_homed(); - #endif + TERN_(HAS_EXTRUDERS, if (I2CPE_ENC_4_AXIS == E_AXIS) encoders[i].set_homed()); #endif #if I2CPE_ENCODER_CNT > 4 @@ -621,9 +616,7 @@ void I2CPositionEncodersMgr::init() { encoders[i].set_active(encoders[i].passes_test(true)); - #if I2CPE_ENC_5_AXIS == E_AXIS - encoders[i].set_homed(); - #endif + TERN_(HAS_EXTRUDERS, if (I2CPE_ENC_5_AXIS == E_AXIS) encoders[i].set_homed()); #endif #if I2CPE_ENCODER_CNT > 5 @@ -652,9 +645,7 @@ void I2CPositionEncodersMgr::init() { encoders[i].set_active(encoders[i].passes_test(true)); - #if I2CPE_ENC_6_AXIS == E_AXIS - encoders[i].set_homed(); - #endif + TERN_(HAS_EXTRUDERS, if (I2CPE_ENC_6_AXIS == E_AXIS) encoders[i].set_homed()); #endif } @@ -666,8 +657,7 @@ void I2CPositionEncodersMgr::report_position(const int8_t idx, const bool units, else { if (noOffset) { const int32_t raw_count = encoders[idx].get_raw_count(); - SERIAL_ECHO(axis_codes[encoders[idx].get_axis()]); - SERIAL_CHAR(' '); + SERIAL_CHAR(axis_codes[encoders[idx].get_axis()], ' '); for (uint8_t j = 31; j > 0; j--) SERIAL_ECHO((bool)(0x00000001 & (raw_count >> j))); @@ -722,7 +712,7 @@ void I2CPositionEncodersMgr::change_module_address(const uint8_t oldaddr, const // and enable it (it will likely have failed initialization on power-up, before the address change). const int8_t idx = idx_from_addr(newaddr); if (idx >= 0 && !encoders[idx].get_active()) { - SERIAL_ECHO(axis_codes[encoders[idx].get_axis()]); + SERIAL_CHAR(axis_codes[encoders[idx].get_axis()]); SERIAL_ECHOLNPGM(" axis encoder was not detected on printer startup. Trying again."); encoders[idx].set_active(encoders[idx].passes_test(true)); } @@ -747,7 +737,7 @@ void I2CPositionEncodersMgr::report_module_firmware(const uint8_t address) { if (Wire.requestFrom(I2C_ADDRESS(address), uint8_t(32))) { char c; while (Wire.available() > 0 && (c = (char)Wire.read()) > 0) - SERIAL_ECHO(c); + SERIAL_CHAR(c); SERIAL_EOL(); } @@ -820,11 +810,11 @@ int8_t I2CPositionEncodersMgr::parse() { void I2CPositionEncodersMgr::M860() { if (parse()) return; - const bool hasU = parser.seen('U'), hasO = parser.seen('O'); + const bool hasU = parser.seen_test('U'), hasO = parser.seen_test('O'); if (I2CPE_idx == 0xFF) { - LOOP_XYZE(i) { - if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) { + LOOP_LOGICAL_AXES(i) { + if (!I2CPE_anyaxis || parser.seen_test(axis_codes[i])) { const uint8_t idx = idx_from_axis(AxisEnum(i)); if ((int8_t)idx >= 0) report_position(idx, hasU, hasO); } @@ -850,7 +840,7 @@ void I2CPositionEncodersMgr::M861() { if (parse()) return; if (I2CPE_idx == 0xFF) { - LOOP_XYZE(i) { + LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) { const uint8_t idx = idx_from_axis(AxisEnum(i)); if ((int8_t)idx >= 0) report_status(idx); @@ -878,7 +868,7 @@ void I2CPositionEncodersMgr::M862() { if (parse()) return; if (I2CPE_idx == 0xFF) { - LOOP_XYZE(i) { + LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) { const uint8_t idx = idx_from_axis(AxisEnum(i)); if ((int8_t)idx >= 0) test_axis(idx); @@ -909,7 +899,7 @@ void I2CPositionEncodersMgr::M863() { const uint8_t iterations = constrain(parser.byteval('P', 1), 1, 10); if (I2CPE_idx == 0xFF) { - LOOP_XYZE(i) { + LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) { const uint8_t idx = idx_from_axis(AxisEnum(i)); if ((int8_t)idx >= 0) calibrate_steps_mm(idx, iterations); @@ -957,10 +947,10 @@ void I2CPositionEncodersMgr::M864() { return; } else { - if (parser.seen('X')) newAddress = I2CPE_PRESET_ADDR_X; - else if (parser.seen('Y')) newAddress = I2CPE_PRESET_ADDR_Y; - else if (parser.seen('Z')) newAddress = I2CPE_PRESET_ADDR_Z; - else if (parser.seen('E')) newAddress = I2CPE_PRESET_ADDR_E; + if (parser.seen_test('X')) newAddress = I2CPE_PRESET_ADDR_X; + else if (parser.seen_test('Y')) newAddress = I2CPE_PRESET_ADDR_Y; + else if (parser.seen_test('Z')) newAddress = I2CPE_PRESET_ADDR_Z; + else if (parser.seen_test('E')) newAddress = I2CPE_PRESET_ADDR_E; else return; } @@ -985,7 +975,7 @@ void I2CPositionEncodersMgr::M865() { if (parse()) return; if (!I2CPE_addr) { - LOOP_XYZE(i) { + LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) { const uint8_t idx = idx_from_axis(AxisEnum(i)); if ((int8_t)idx >= 0) report_module_firmware(encoders[idx].get_address()); @@ -1013,10 +1003,10 @@ void I2CPositionEncodersMgr::M865() { void I2CPositionEncodersMgr::M866() { if (parse()) return; - const bool hasR = parser.seen('R'); + const bool hasR = parser.seen_test('R'); if (I2CPE_idx == 0xFF) { - LOOP_XYZE(i) { + LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) { const uint8_t idx = idx_from_axis(AxisEnum(i)); if ((int8_t)idx >= 0) { @@ -1054,7 +1044,7 @@ void I2CPositionEncodersMgr::M867() { const int8_t onoff = parser.seenval('S') ? parser.value_int() : -1; if (I2CPE_idx == 0xFF) { - LOOP_XYZE(i) { + LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) { const uint8_t idx = idx_from_axis(AxisEnum(i)); if ((int8_t)idx >= 0) { @@ -1090,7 +1080,7 @@ void I2CPositionEncodersMgr::M868() { const float newThreshold = parser.seenval('T') ? parser.value_float() : -9999; if (I2CPE_idx == 0xFF) { - LOOP_XYZE(i) { + LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) { const uint8_t idx = idx_from_axis(AxisEnum(i)); if ((int8_t)idx >= 0) { @@ -1124,7 +1114,7 @@ void I2CPositionEncodersMgr::M869() { if (parse()) return; if (I2CPE_idx == 0xFF) { - LOOP_XYZE(i) { + LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) { const uint8_t idx = idx_from_axis(AxisEnum(i)); if ((int8_t)idx >= 0) report_error(idx); diff --git a/Marlin/src/feature/encoder_i2c.h b/Marlin/src/feature/encoder_i2c.h index 511e560ba0ce..20871af98ccb 100644 --- a/Marlin/src/feature/encoder_i2c.h +++ b/Marlin/src/feature/encoder_i2c.h @@ -188,7 +188,7 @@ class I2CPositionEncoder { FORCE_INLINE void set_ec_method(const byte method) { ecMethod = method; } FORCE_INLINE float get_ec_threshold() { return ecThreshold; } - FORCE_INLINE void set_ec_threshold(const float newThreshold) { ecThreshold = newThreshold; } + FORCE_INLINE void set_ec_threshold(const_float_t newThreshold) { ecThreshold = newThreshold; } FORCE_INLINE int get_encoder_ticks_mm() { switch (type) { @@ -261,32 +261,32 @@ class I2CPositionEncodersMgr { static void report_error_count(const int8_t idx, const AxisEnum axis) { CHECK_IDX(); - SERIAL_ECHOLNPAIR("Error count on ", axis_codes[axis], " axis is ", encoders[idx].get_error_count()); + SERIAL_ECHOLNPAIR("Error count on ", AS_CHAR(axis_codes[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_ECHOLNPAIR("Error count on ", axis_codes[axis], " axis has been reset."); + SERIAL_ECHOLNPAIR("Error count on ", AS_CHAR(axis_codes[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_ECHOPAIR("Error correction on ", axis_codes[axis]); + SERIAL_ECHOPAIR("Error correction on ", AS_CHAR(axis_codes[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_ECHOLNPAIR("Error correct threshold for ", axis_codes[axis], " axis set to ", newThreshold, "mm."); + SERIAL_ECHOLNPAIR("Error correct threshold for ", AS_CHAR(axis_codes[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_ECHOLNPAIR("Error correct threshold for ", axis_codes[axis], " axis is ", threshold, "mm."); + SERIAL_ECHOLNPAIR("Error correct threshold for ", AS_CHAR(axis_codes[axis]), " axis is ", threshold, "mm."); } static int8_t idx_from_axis(const AxisEnum axis) { diff --git a/Marlin/src/feature/ethernet.cpp b/Marlin/src/feature/ethernet.cpp new file mode 100644 index 000000000000..d4a95fa051fd --- /dev/null +++ b/Marlin/src/feature/ethernet.cpp @@ -0,0 +1,175 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../inc/MarlinConfigPre.h" + +#if HAS_ETHERNET + +#include "ethernet.h" +#include "../core/serial.h" + +#define DEBUG_OUT ENABLED(DEBUG_ETHERNET) +#include "../core/debug_out.h" + +bool MarlinEthernet::hardware_enabled, // = false + MarlinEthernet::have_telnet_client; // = false + +IPAddress MarlinEthernet::ip, + MarlinEthernet::myDns, + MarlinEthernet::gateway, + MarlinEthernet::subnet; + +EthernetClient MarlinEthernet::telnetClient; // connected client + +MarlinEthernet ethernet; + +EthernetServer server(23); // telnet server + +enum linkStates { UNLINKED, LINKING, LINKED, CONNECTING, CONNECTED, NO_HARDWARE } linkState; + +#ifdef __IMXRT1062__ + + static void teensyMAC(uint8_t * const mac) { + const uint32_t m1 = HW_OCOTP_MAC1, m2 = HW_OCOTP_MAC0; + mac[0] = m1 >> 8; + mac[1] = m1 >> 0; + mac[2] = m2 >> 24; + mac[3] = m2 >> 16; + mac[4] = m2 >> 8; + mac[5] = m2 >> 0; + } + +#else + + byte mac[] = MAC_ADDRESS; + +#endif + +void ethernet_cable_error() { SERIAL_ERROR_MSG("Ethernet cable is not connected."); } + +void MarlinEthernet::init() { + if (!hardware_enabled) return; + + SERIAL_ECHO_MSG("Starting network..."); + + // Init the Ethernet device + #ifdef __IMXRT1062__ + uint8_t mac[6]; + teensyMAC(mac); + #endif + + if (!ip) { + Ethernet.begin(mac); // use DHCP + } + else { + if (!gateway) { + gateway = ip; + gateway[3] = 1; + myDns = gateway; + subnet = IPAddress(255,255,255,0); + } + if (!myDns) myDns = gateway; + if (!subnet) subnet = IPAddress(255,255,255,0); + Ethernet.begin(mac, ip, myDns, gateway, subnet); + } + + // Check for Ethernet hardware present + if (Ethernet.hardwareStatus() == EthernetNoHardware) { + SERIAL_ERROR_MSG("No Ethernet hardware found."); + linkState = NO_HARDWARE; + return; + } + + linkState = UNLINKED; + + if (Ethernet.linkStatus() == LinkOFF) + ethernet_cable_error(); +} + +void MarlinEthernet::check() { + if (!hardware_enabled) return; + + switch (linkState) { + case NO_HARDWARE: + break; + + case UNLINKED: + if (Ethernet.linkStatus() == LinkOFF) break; + + SERIAL_ECHOLNPGM("Ethernet cable connected"); + server.begin(); + linkState = LINKING; + break; + + case LINKING: + if (!Ethernet.localIP()) break; + + SERIAL_ECHOPGM("Successfully started telnet server with IP "); + MYSERIAL1.println(Ethernet.localIP()); + + linkState = LINKED; + break; + + case LINKED: + if (Ethernet.linkStatus() == LinkOFF) { + ethernet_cable_error(); + linkState = UNLINKED; + break; + } + telnetClient = server.accept(); + if (telnetClient) linkState = CONNECTING; + break; + + case CONNECTING: + telnetClient.println("Marlin " SHORT_BUILD_VERSION); + #if defined(STRING_DISTRIBUTION_DATE) && defined(STRING_CONFIG_H_AUTHOR) + telnetClient.println( + " Last Updated: " STRING_DISTRIBUTION_DATE + " | Author: " STRING_CONFIG_H_AUTHOR + ); + #endif + telnetClient.println("Compiled: " __DATE__); + + SERIAL_ECHOLNPGM("Client connected"); + have_telnet_client = true; + linkState = CONNECTED; + break; + + case CONNECTED: + if (telnetClient && !telnetClient.connected()) { + SERIAL_ECHOLNPGM("Client disconnected"); + telnetClient.stop(); + have_telnet_client = false; + linkState = LINKED; + } + if (Ethernet.linkStatus() == LinkOFF) { + ethernet_cable_error(); + if (telnetClient) telnetClient.stop(); + linkState = UNLINKED; + } + break; + + default: break; + } +} + +#endif // HAS_ETHERNET diff --git a/Marlin/src/feature/ethernet.h b/Marlin/src/feature/ethernet.h new file mode 100644 index 000000000000..70a58efce7e3 --- /dev/null +++ b/Marlin/src/feature/ethernet.h @@ -0,0 +1,39 @@ +/** + * 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 + +#ifdef __IMXRT1062__ + #include +#endif + +// Teensy 4.1 uses internal MAC Address + +class MarlinEthernet { + public: + static bool hardware_enabled, have_telnet_client; + static IPAddress ip, myDns, gateway, subnet; + static EthernetClient telnetClient; + static void init(); + static void check(); +}; + +extern MarlinEthernet ethernet; diff --git a/Marlin/src/feature/fanmux.h b/Marlin/src/feature/fanmux.h index b1b0c67a55e0..efb92cf1989c 100644 --- a/Marlin/src/feature/fanmux.h +++ b/Marlin/src/feature/fanmux.h @@ -25,5 +25,5 @@ * feature/fanmux.h - Cooling Fan Multiplexer support functions */ -extern void fanmux_switch(const uint8_t e); -extern void fanmux_init(); +void fanmux_switch(const uint8_t e); +void fanmux_init(); diff --git a/Marlin/src/feature/filwidth.h b/Marlin/src/feature/filwidth.h index ef3859df719a..e63d3d719ffb 100644 --- a/Marlin/src/feature/filwidth.h +++ b/Marlin/src/feature/filwidth.h @@ -78,7 +78,7 @@ class FilamentWidthSensor { static inline void update_measured_mm() { measured_mm = raw_to_mm(); } // Update ring buffer used to delay filament measurements - static inline void advance_e(const float &e_move) { + static inline void advance_e(const_float_t e_move) { // Increment counters with the E distance e_count += e_move; diff --git a/Marlin/src/feature/fwretract.cpp b/Marlin/src/feature/fwretract.cpp index e5c52562a9ad..41dbf430e829 100644 --- a/Marlin/src/feature/fwretract.cpp +++ b/Marlin/src/feature/fwretract.cpp @@ -36,6 +36,8 @@ FWRetract fwretract; // Single instance - this calls the constructor #include "../module/planner.h" #include "../module/stepper.h" +#include "../gcode/parser.h" + #if ENABLED(RETRACT_SYNC_MIXING) #include "mixing.h" #endif @@ -89,11 +91,7 @@ void FWRetract::reset() { * Note: Auto-retract will apply the set Z hop in addition to any Z hop * included in the G-code. Use M207 Z0 to to prevent double hop. */ -void FWRetract::retract(const bool retracting - #if HAS_MULTI_EXTRUDER - , bool swapping/*=false*/ - #endif -) { +void FWRetract::retract(const bool retracting OPTARG(HAS_MULTI_EXTRUDER, bool swapping/*=false*/)) { // Prevent two retracts or recovers in a row if (retracted[active_extruder] == retracting) return; @@ -109,14 +107,14 @@ void FWRetract::retract(const bool retracting /* // debugging SERIAL_ECHOLNPAIR( - "retracting ", retracting, + "retracting ", AS_DIGIT(retracting), " swapping ", swapping, " active extruder ", active_extruder ); LOOP_L_N(i, EXTRUDERS) { - SERIAL_ECHOLNPAIR("retracted[", i, "] ", retracted[i]); + SERIAL_ECHOLNPAIR("retracted[", i, "] ", AS_DIGIT(retracted[i])); #if HAS_MULTI_EXTRUDER - SERIAL_ECHOLNPAIR("retracted_swap[", i, "] ", retracted_swap[i]); + SERIAL_ECHOLNPAIR("retracted_swap[", i, "] ", AS_DIGIT(retracted_swap[i])); #endif } SERIAL_ECHOLNPAIR("current_position.z ", current_position.z); @@ -139,7 +137,7 @@ void FWRetract::retract(const bool retracting if (retracting) { // Retract by moving from a faux E position back to the current E position current_retract[active_extruder] = base_retract; - prepare_internal_move_to_destination( // set current to destination + prepare_internal_move_to_destination( // set current from destination settings.retract_feedrate_mm_s * TERN1(RETRACT_SYNC_MIXING, (MIXING_STEPPERS)) ); @@ -183,13 +181,13 @@ void FWRetract::retract(const bool retracting #endif /* // debugging - SERIAL_ECHOLNPAIR("retracting ", retracting); - SERIAL_ECHOLNPAIR("swapping ", swapping); + SERIAL_ECHOLNPAIR("retracting ", AS_DIGIT(retracting)); + SERIAL_ECHOLNPAIR("swapping ", AS_DIGIT(swapping)); SERIAL_ECHOLNPAIR("active_extruder ", active_extruder); LOOP_L_N(i, EXTRUDERS) { - SERIAL_ECHOLNPAIR("retracted[", i, "] ", retracted[i]); + SERIAL_ECHOLNPAIR("retracted[", i, "] ", AS_DIGIT(retracted[i])); #if HAS_MULTI_EXTRUDER - SERIAL_ECHOLNPAIR("retracted_swap[", i, "] ", retracted_swap[i]); + SERIAL_ECHOLNPAIR("retracted_swap[", i, "] ", AS_DIGIT(retracted_swap[i])); #endif } SERIAL_ECHOLNPAIR("current_position.z ", current_position.z); @@ -198,4 +196,78 @@ void FWRetract::retract(const bool retracting //*/ } +//extern const char SP_Z_STR[]; + +/** + * M207: Set firmware retraction values + * + * S[+units] retract_length + * W[+units] swap_retract_length (multi-extruder) + * F[units/min] retract_feedrate_mm_s + * Z[units] retract_zraise + */ +void FWRetract::M207() { + if (!parser.seen("FSWZ")) return M207_report(); + if (parser.seenval('S')) settings.retract_length = parser.value_axis_units(E_AXIS); + if (parser.seenval('F')) settings.retract_feedrate_mm_s = MMM_TO_MMS(parser.value_axis_units(E_AXIS)); + if (parser.seenval('Z')) settings.retract_zraise = parser.value_linear_units(); + if (parser.seenval('W')) settings.swap_retract_length = parser.value_axis_units(E_AXIS); +} + +void FWRetract::M207_report(const bool forReplay/*=false*/) { + if (!forReplay) { SERIAL_ECHO_MSG("; Retract: S F Z"); SERIAL_ECHO_START(); } + SERIAL_ECHOLNPAIR_P( + PSTR(" M207 S"), LINEAR_UNIT(settings.retract_length) + , PSTR(" W"), LINEAR_UNIT(settings.swap_retract_length) + , PSTR(" F"), LINEAR_UNIT(MMS_TO_MMM(settings.retract_feedrate_mm_s)) + , SP_Z_STR, LINEAR_UNIT(settings.retract_zraise) + ); +} + +/** + * M208: Set firmware un-retraction values + * + * S[+units] retract_recover_extra (in addition to M207 S*) + * W[+units] swap_retract_recover_extra (multi-extruder) + * F[units/min] retract_recover_feedrate_mm_s + * R[units/min] swap_retract_recover_feedrate_mm_s + */ +void FWRetract::M208() { + if (!parser.seen("FSRW")) return M208_report(); + if (parser.seen('S')) settings.retract_recover_extra = parser.value_axis_units(E_AXIS); + if (parser.seen('F')) settings.retract_recover_feedrate_mm_s = MMM_TO_MMS(parser.value_axis_units(E_AXIS)); + if (parser.seen('R')) settings.swap_retract_recover_feedrate_mm_s = MMM_TO_MMS(parser.value_axis_units(E_AXIS)); + if (parser.seen('W')) settings.swap_retract_recover_extra = parser.value_axis_units(E_AXIS); +} + +void FWRetract::M208_report(const bool forReplay/*=false*/) { + if (!forReplay) { SERIAL_ECHO_MSG("; Recover: S F"); SERIAL_ECHO_START(); } + SERIAL_ECHOLNPAIR( + " M208 S", LINEAR_UNIT(settings.retract_recover_extra) + , " W", LINEAR_UNIT(settings.swap_retract_recover_extra) + , " F", LINEAR_UNIT(MMS_TO_MMM(settings.retract_recover_feedrate_mm_s)) + ); +} + +#if ENABLED(FWRETRACT_AUTORETRACT) + + /** + * M209: Enable automatic retract (M209 S1) + * For slicers that don't support G10/11, reversed extrude-only + * moves will be classified as retraction. + */ + void FWRetract::M209() { + if (!parser.seen('S')) return M209_report(); + if (MIN_AUTORETRACT <= MAX_AUTORETRACT) + enable_autoretract(parser.value_bool()); + } + + void FWRetract::M209_report(const bool forReplay/*=false*/) { + if (!forReplay) { SERIAL_ECHO_MSG("; Auto-Retract: S=0 to disable, 1 to interpret E-only moves as retract/recover"); SERIAL_ECHO_START(); } + SERIAL_ECHOLNPAIR(" M209 S", AS_DIGIT(autoretract_enabled)); + } + +#endif // FWRETRACT_AUTORETRACT + + #endif // FWRETRACT diff --git a/Marlin/src/feature/fwretract.h b/Marlin/src/feature/fwretract.h index 134851965dc4..cd93e9cf39ed 100644 --- a/Marlin/src/feature/fwretract.h +++ b/Marlin/src/feature/fwretract.h @@ -74,11 +74,16 @@ class FWRetract { #endif } - static void retract(const bool retracting - #if HAS_MULTI_EXTRUDER - , bool swapping = false - #endif - ); + static void retract(const bool retracting OPTARG(HAS_MULTI_EXTRUDER, bool swapping = false)); + + static void M207(); + static void M207_report(const bool forReplay=false); + static void M208(); + static void M208_report(const bool forReplay=false); + #if ENABLED(FWRETRACT_AUTORETRACT) + static void M209(); + static void M209_report(const bool forReplay=false); + #endif }; extern FWRetract fwretract; diff --git a/Marlin/src/feature/host_actions.cpp b/Marlin/src/feature/host_actions.cpp index 30126392207d..62e60320f763 100644 --- a/Marlin/src/feature/host_actions.cpp +++ b/Marlin/src/feature/host_actions.cpp @@ -38,9 +38,9 @@ #endif void host_action(PGM_P const pstr, const bool eol) { - PORT_REDIRECT(SERIAL_BOTH); + PORT_REDIRECT(SerialMask::All); SERIAL_ECHOPGM("//action:"); - serialprintPGM(pstr); + SERIAL_ECHOPGM_P(pstr); if (eol) SERIAL_EOL(); } @@ -78,30 +78,29 @@ void host_action(PGM_P const pstr, const bool eol) { PromptReason host_prompt_reason = PROMPT_NOT_DEFINED; void host_action_notify(const char * const message) { - PORT_REDIRECT(SERIAL_BOTH); + PORT_REDIRECT(SerialMask::All); host_action(PSTR("notification "), false); SERIAL_ECHOLN(message); } void host_action_notify_P(PGM_P const message) { - PORT_REDIRECT(SERIAL_BOTH); + PORT_REDIRECT(SerialMask::All); host_action(PSTR("notification "), false); - serialprintPGM(message); - SERIAL_EOL(); + SERIAL_ECHOLNPGM_P(message); } void host_action_prompt(PGM_P const ptype, const bool eol=true) { - PORT_REDIRECT(SERIAL_BOTH); + PORT_REDIRECT(SerialMask::All); host_action(PSTR("prompt_"), false); - serialprintPGM(ptype); + SERIAL_ECHOPGM_P(ptype); if (eol) SERIAL_EOL(); } void host_action_prompt_plus(PGM_P const ptype, PGM_P const pstr, const char extra_char='\0') { host_action_prompt(ptype, false); - PORT_REDIRECT(SERIAL_BOTH); + PORT_REDIRECT(SerialMask::All); SERIAL_CHAR(' '); - serialprintPGM(pstr); + SERIAL_ECHOPGM_P(pstr); if (extra_char != '\0') SERIAL_CHAR(extra_char); SERIAL_EOL(); } @@ -113,12 +112,20 @@ void host_action(PGM_P const pstr, const bool eol) { void host_action_prompt_button(PGM_P const pstr) { host_action_prompt_plus(PSTR("button"), pstr); } void host_action_prompt_end() { host_action_prompt(PSTR("end")); } void host_action_prompt_show() { host_action_prompt(PSTR("show")); } - void host_prompt_do(const PromptReason reason, PGM_P const pstr, PGM_P const btn1/*=nullptr*/, PGM_P const btn2/*=nullptr*/) { - host_action_prompt_begin(reason, pstr); + + void _host_prompt_show(PGM_P const btn1/*=nullptr*/, PGM_P const btn2/*=nullptr*/) { if (btn1) host_action_prompt_button(btn1); if (btn2) host_action_prompt_button(btn2); host_action_prompt_show(); } + void host_prompt_do(const PromptReason reason, PGM_P const pstr, PGM_P const btn1/*=nullptr*/, PGM_P const btn2/*=nullptr*/) { + host_action_prompt_begin(reason, pstr); + _host_prompt_show(btn1, btn2); + } + void host_prompt_do(const PromptReason reason, PGM_P const pstr, const char extra_char, PGM_P const btn1/*=nullptr*/, PGM_P const btn2/*=nullptr*/) { + host_action_prompt_begin(reason, pstr, extra_char); + _host_prompt_show(btn1, btn2); + } void filament_load_host_prompt() { const bool disable_to_continue = TERN0(HAS_FILAMENT_SENSOR, runout.filament_ran_out); @@ -135,28 +142,20 @@ void host_action(PGM_P const pstr, const bool eol) { // - Dismissal of info // void host_response_handler(const uint8_t response) { - #ifdef DEBUG_HOST_ACTIONS - static PGMSTR(m876_prefix, "M876 Handle Re"); - serialprintPGM(m876_prefix); SERIAL_ECHOLNPAIR("ason: ", host_prompt_reason); - serialprintPGM(m876_prefix); SERIAL_ECHOLNPAIR("sponse: ", response); - #endif - PGM_P msg = PSTR("UNKNOWN STATE"); const PromptReason hpr = host_prompt_reason; host_prompt_reason = PROMPT_NOT_DEFINED; // Reset now ahead of logic switch (hpr) { case PROMPT_FILAMENT_RUNOUT: - msg = PSTR("FILAMENT_RUNOUT"); switch (response) { case 0: // "Purge More" button - #if BOTH(HAS_LCD_MENU, ADVANCED_PAUSE_FEATURE) + #if BOTH(M600_PURGE_MORE_RESUMABLE, ADVANCED_PAUSE_FEATURE) pause_menu_response = PAUSE_RESPONSE_EXTRUDE_MORE; // Simulate menu selection (menu exits, doesn't extrude more) #endif - filament_load_host_prompt(); // Initiate another host prompt. (NOTE: The loop in load_filament may also do this!) break; case 1: // "Continue" / "Disable Runout" button - #if BOTH(HAS_LCD_MENU, ADVANCED_PAUSE_FEATURE) + #if BOTH(M600_PURGE_MORE_RESUMABLE, ADVANCED_PAUSE_FEATURE) pause_menu_response = PAUSE_RESPONSE_RESUME_PRINT; // Simulate menu selection #endif #if HAS_FILAMENT_SENSOR @@ -170,23 +169,17 @@ void host_action(PGM_P const pstr, const bool eol) { break; case PROMPT_USER_CONTINUE: TERN_(HAS_RESUME_CONTINUE, wait_for_user = false); - msg = PSTR("FILAMENT_RUNOUT_CONTINUE"); break; case PROMPT_PAUSE_RESUME: - msg = PSTR("LCD_PAUSE_RESUME"); - #if ENABLED(ADVANCED_PAUSE_FEATURE) + #if BOTH(ADVANCED_PAUSE_FEATURE, SDSUPPORT) extern const char M24_STR[]; queue.inject_P(M24_STR); #endif break; case PROMPT_INFO: - msg = PSTR("GCODE_INFO"); break; default: break; } - SERIAL_ECHOPGM("M876 Responding PROMPT_"); - serialprintPGM(msg); - SERIAL_EOL(); } #endif // HOST_PROMPT_SUPPORT diff --git a/Marlin/src/feature/host_actions.h b/Marlin/src/feature/host_actions.h index 09eeed23e215..065b59d755ed 100644 --- a/Marlin/src/feature/host_actions.h +++ b/Marlin/src/feature/host_actions.h @@ -71,6 +71,7 @@ void host_action(PGM_P const pstr, const bool eol=true); void host_action_prompt_end(); void host_action_prompt_show(); void host_prompt_do(const PromptReason reason, PGM_P const pstr, PGM_P const btn1=nullptr, PGM_P const btn2=nullptr); + void host_prompt_do(const PromptReason reason, PGM_P const pstr, const char extra_char, PGM_P const btn1=nullptr, PGM_P const btn2=nullptr); inline void host_prompt_open(const PromptReason reason, PGM_P const pstr, PGM_P const btn1=nullptr, PGM_P const btn2=nullptr) { if (host_prompt_reason == PROMPT_NOT_DEFINED) host_prompt_do(reason, pstr, btn1, btn2); } diff --git a/Marlin/src/feature/hotend_idle.cpp b/Marlin/src/feature/hotend_idle.cpp index 9d5594c2f184..b962743ed045 100644 --- a/Marlin/src/feature/hotend_idle.cpp +++ b/Marlin/src/feature/hotend_idle.cpp @@ -34,7 +34,8 @@ #include "../module/temperature.h" #include "../module/motion.h" -#include "../lcd/ultralcd.h" +#include "../module/planner.h" +#include "../lcd/marlinui.h" extern HotendIdleProtection hotend_idle; @@ -43,7 +44,8 @@ millis_t HotendIdleProtection::next_protect_ms = 0; void HotendIdleProtection::check_hotends(const millis_t &ms) { bool do_prot = false; HOTEND_LOOP() { - if (thermalManager.degHotend(e) >= HOTEND_IDLE_MIN_TRIGGER) { + const bool busy = (TERN0(HAS_RESUME_CONTINUE, wait_for_user) || planner.has_blocks_queued()); + if (thermalManager.degHotend(e) >= (HOTEND_IDLE_MIN_TRIGGER) && !busy) { do_prot = true; break; } } diff --git a/Marlin/src/feature/joystick.cpp b/Marlin/src/feature/joystick.cpp index d9c5ae7c1b1c..d8e6cef3b6d3 100644 --- a/Marlin/src/feature/joystick.cpp +++ b/Marlin/src/feature/joystick.cpp @@ -32,7 +32,6 @@ #include "../inc/MarlinConfig.h" // for pins #include "../module/planner.h" -#include "../module/temperature.h" Joystick joystick; @@ -127,6 +126,11 @@ Joystick joystick; static bool injecting_now; // = false; if (injecting_now) return; + #if ENABLED(NO_MOTION_BEFORE_HOMING) + if (TERN0(HAS_JOY_ADC_X, axis_should_home(X_AXIS)) || TERN0(HAS_JOY_ADC_Y, axis_should_home(Y_AXIS)) || TERN0(HAS_JOY_ADC_Z, axis_should_home(Z_AXIS))) + return; + #endif + static constexpr int QUEUE_DEPTH = 5; // Insert up to this many movements static constexpr float target_lag = 0.25f, // Aim for 1/4 second lag seg_time = target_lag / QUEUE_DEPTH; // 0.05 seconds, short segments inserted every 1/20th of a second @@ -159,13 +163,8 @@ Joystick joystick; // norm_jog values of [-1 .. 1] maps linearly to [-feedrate .. feedrate] xyz_float_t move_dist{0}; float hypot2 = 0; - LOOP_XYZ(i) if (norm_jog[i]) { - move_dist[i] = seg_time * norm_jog[i] * - #if ENABLED(EXTENSIBLE_UI) - manual_feedrate_mm_s[i]; - #else - planner.settings.max_feedrate_mm_s[i]; - #endif + LOOP_LINEAR_AXES(i) if (norm_jog[i]) { + move_dist[i] = seg_time * norm_jog[i] * TERN(EXTENSIBLE_UI, manual_feedrate_mm_s, planner.settings.max_feedrate_mm_s)[i]; hypot2 += sq(move_dist[i]); } diff --git a/Marlin/src/feature/joystick.h b/Marlin/src/feature/joystick.h index 1d25a30cc24d..91bf6bdc00d2 100644 --- a/Marlin/src/feature/joystick.h +++ b/Marlin/src/feature/joystick.h @@ -27,17 +27,24 @@ #include "../inc/MarlinConfigPre.h" #include "../core/types.h" -#include "../core/macros.h" #include "../module/temperature.h" class Joystick { friend class Temperature; private: - TERN_(HAS_JOY_ADC_X, static temp_info_t x); - TERN_(HAS_JOY_ADC_Y, static temp_info_t y); - TERN_(HAS_JOY_ADC_Z, static temp_info_t z); + #if HAS_JOY_ADC_X + static temp_info_t x; + #endif + #if HAS_JOY_ADC_Y + static temp_info_t y; + #endif + #if HAS_JOY_ADC_Z + static temp_info_t z; + #endif public: - TERN_(JOYSTICK_DEBUG, static void report()); + #if ENABLED(JOYSTICK_DEBUG) + static void report(); + #endif static void calculate(xyz_float_t &norm_jog); static void inject_jog_moves(); }; diff --git a/Marlin/src/feature/leds/leds.cpp b/Marlin/src/feature/leds/leds.cpp index ef9099fb2093..328daa626d46 100644 --- a/Marlin/src/feature/leds/leds.cpp +++ b/Marlin/src/feature/leds/leds.cpp @@ -42,14 +42,19 @@ #include "pca9533.h" #endif +#if ENABLED(CASE_LIGHT_USE_RGB_LED) + #include "../../feature/caselight.h" +#endif + #if ENABLED(LED_COLOR_PRESETS) - const LEDColor LEDLights::defaultLEDColor = MakeLEDColor( - LED_USER_PRESET_RED, LED_USER_PRESET_GREEN, LED_USER_PRESET_BLUE, - LED_USER_PRESET_WHITE, LED_USER_PRESET_BRIGHTNESS + const LEDColor LEDLights::defaultLEDColor = LEDColor( + LED_USER_PRESET_RED, LED_USER_PRESET_GREEN, LED_USER_PRESET_BLUE + OPTARG(HAS_WHITE_LED, LED_USER_PRESET_WHITE) + OPTARG(NEOPIXEL_LED, LED_USER_PRESET_BRIGHTNESS) ); #endif -#if EITHER(LED_CONTROL_MENU, PRINTER_EVENT_LEDS) +#if ANY(LED_CONTROL_MENU, PRINTER_EVENT_LEDS, CASE_LIGHT_IS_COLOR_LED) LEDColor LEDLights::color; bool LEDLights::lights_on; #endif @@ -71,34 +76,36 @@ void LEDLights::setup() { } void LEDLights::set_color(const LEDColor &incol - #if ENABLED(NEOPIXEL_LED) - , bool isSequence/*=false*/ - #endif + OPTARG(NEOPIXEL_IS_SEQUENTIAL, bool isSequence/*=false*/) ) { #if ENABLED(NEOPIXEL_LED) const uint32_t neocolor = LEDColorWhite() == incol ? neo.Color(NEO_WHITE) - : neo.Color(incol.r, incol.g, incol.b, incol.w); - static uint16_t nextLed = 0; + : neo.Color(incol.r, incol.g, incol.b OPTARG(HAS_WHITE_LED, incol.w)); + + #if ENABLED(NEOPIXEL_IS_SEQUENTIAL) + static uint16_t nextLed = 0; + #ifdef NEOPIXEL_BKGD_INDEX_FIRST + while (WITHIN(nextLed, NEOPIXEL_BKGD_INDEX_FIRST, NEOPIXEL_BKGD_INDEX_LAST)) { + neo.reset_background_color(); + if (++nextLed >= neo.pixels()) { nextLed = 0; return; } + } + #endif + #endif + + neo.set_brightness(incol.i); - #ifdef NEOPIXEL_BKGD_LED_INDEX - if (NEOPIXEL_BKGD_LED_INDEX == nextLed) { + #if ENABLED(NEOPIXEL_IS_SEQUENTIAL) + if (isSequence) { + neo.set_pixel_color(nextLed, neocolor); + neo.show(); if (++nextLed >= neo.pixels()) nextLed = 0; return; } #endif - neo.set_brightness(incol.i); - - if (isSequence) { - neo.set_pixel_color(nextLed, neocolor); - neo.show(); - if (++nextLed >= neo.pixels()) nextLed = 0; - return; - } - neo.set_color(neocolor); #endif @@ -114,12 +121,13 @@ void LEDLights::set_color(const LEDColor &incol // This variant uses 3-4 separate pins for the RGB(W) components. // If the pins can do PWM then their intensity will be set. - #define UPDATE_RGBW(C,c) do { \ - if (PWM_PIN(RGB_LED_##C##_PIN)) \ - analogWrite(pin_t(RGB_LED_##C##_PIN), incol.c); \ - else \ - WRITE(RGB_LED_##C##_PIN, incol.c ? HIGH : LOW); \ + #define _UPDATE_RGBW(C,c) do { \ + if (PWM_PIN(RGB_LED_##C##_PIN)) \ + analogWrite(pin_t(RGB_LED_##C##_PIN), c); \ + else \ + WRITE(RGB_LED_##C##_PIN, c ? HIGH : LOW); \ }while(0) + #define UPDATE_RGBW(C,c) _UPDATE_RGBW(C, TERN1(CASE_LIGHT_USE_RGB_LED, caselight.on) ? incol.c : 0) UPDATE_RGBW(R,r); UPDATE_RGBW(G,g); UPDATE_RGBW(B,b); #if ENABLED(RGBW_LED) UPDATE_RGBW(W,w); @@ -147,11 +155,13 @@ void LEDLights::set_color(const LEDColor &incol millis_t LEDLights::led_off_time; // = 0 void LEDLights::update_timeout(const bool power_on) { - const millis_t ms = millis(); - if (power_on) - reset_timeout(ms); - else if (ELAPSED(ms, led_off_time)) - set_off(); + if (lights_on) { + const millis_t ms = millis(); + if (power_on) + reset_timeout(ms); + else if (ELAPSED(ms, led_off_time)) + set_off(); + } } #endif @@ -159,9 +169,10 @@ void LEDLights::set_color(const LEDColor &incol #if ENABLED(NEOPIXEL2_SEPARATE) #if ENABLED(NEO2_COLOR_PRESETS) - const LEDColor LEDLights2::defaultLEDColor = MakeLEDColor( - NEO2_USER_PRESET_RED, NEO2_USER_PRESET_GREEN, NEO2_USER_PRESET_BLUE, - NEO2_USER_PRESET_WHITE, NEO2_USER_PRESET_BRIGHTNESS + const LEDColor LEDLights2::defaultLEDColor = LEDColor( + LED_USER_PRESET_RED, LED_USER_PRESET_GREEN, LED_USER_PRESET_BLUE + OPTARG(HAS_WHITE_LED2, LED_USER_PRESET_WHITE) + OPTARG(NEOPIXEL_LED, LED_USER_PRESET_BRIGHTNESS) ); #endif @@ -180,7 +191,7 @@ void LEDLights::set_color(const LEDColor &incol void LEDLights2::set_color(const LEDColor &incol) { const uint32_t neocolor = LEDColorWhite() == incol ? neo2.Color(NEO2_WHITE) - : neo2.Color(incol.r, incol.g, incol.b, incol.w); + : neo2.Color(incol.r, incol.g, incol.b OPTARG(HAS_WHITE_LED2, incol.w)); neo2.set_brightness(incol.i); neo2.set_color(neocolor); diff --git a/Marlin/src/feature/leds/leds.h b/Marlin/src/feature/leds/leds.h index 055ea0df37ad..74964b51a8e4 100644 --- a/Marlin/src/feature/leds/leds.h +++ b/Marlin/src/feature/leds/leds.h @@ -29,60 +29,37 @@ #include -#if ENABLED(NEOPIXEL_LED) - #include "neopixel.h" -#endif - // A white component can be passed -#if EITHER(RGBW_LED, NEOPIXEL_LED) +#if EITHER(RGBW_LED, PCA9632_RGBW) #define HAS_WHITE_LED 1 #endif +#if ENABLED(NEOPIXEL_LED) + #define _NEOPIXEL_INCLUDE_ + #include "neopixel.h" + #undef _NEOPIXEL_INCLUDE_ +#endif + /** * LEDcolor type for use with leds.set_color */ typedef struct LEDColor { uint8_t r, g, b - #if HAS_WHITE_LED - , w - #if ENABLED(NEOPIXEL_LED) - , i - #endif - #endif + OPTARG(HAS_WHITE_LED, w) + OPTARG(NEOPIXEL_LED, i) ; LEDColor() : r(255), g(255), b(255) - #if HAS_WHITE_LED - , w(255) - #if ENABLED(NEOPIXEL_LED) - , i(NEOPIXEL_BRIGHTNESS) - #endif - #endif + OPTARG(HAS_WHITE_LED, w(255)) + OPTARG(NEOPIXEL_LED, i(NEOPIXEL_BRIGHTNESS)) {} - LEDColor(uint8_t r, uint8_t g, uint8_t b - #if HAS_WHITE_LED - , uint8_t w=0 - #if ENABLED(NEOPIXEL_LED) - , uint8_t i=NEOPIXEL_BRIGHTNESS - #endif - #endif - ) : r(r), g(g), b(b) - #if HAS_WHITE_LED - , w(w) - #if ENABLED(NEOPIXEL_LED) - , i(i) - #endif - #endif - {} + LEDColor(uint8_t r, uint8_t g, uint8_t b OPTARG(HAS_WHITE_LED, uint8_t w=0) OPTARG(NEOPIXEL_LED, uint8_t i=NEOPIXEL_BRIGHTNESS)) + : r(r), g(g), b(b) OPTARG(HAS_WHITE_LED, w(w)) OPTARG(NEOPIXEL_LED, i(i)) {} LEDColor(const uint8_t (&rgbw)[4]) : r(rgbw[0]), g(rgbw[1]), b(rgbw[2]) - #if HAS_WHITE_LED - , w(rgbw[3]) - #if ENABLED(NEOPIXEL_LED) - , i(NEOPIXEL_BRIGHTNESS) - #endif - #endif + OPTARG(HAS_WHITE_LED, w(rgbw[3])) + OPTARG(NEOPIXEL_LED, i(NEOPIXEL_BRIGHTNESS)) {} LEDColor& operator=(const uint8_t (&rgbw)[4]) { @@ -109,17 +86,8 @@ typedef struct LEDColor { } LEDColor; /** - * Color helpers and presets + * Color presets */ -#if HAS_WHITE_LED - #if ENABLED(NEOPIXEL_LED) - #define MakeLEDColor(R,G,B,W,I) LEDColor(R, G, B, W, I) - #else - #define MakeLEDColor(R,G,B,W,I) LEDColor(R, G, B, W) - #endif -#else - #define MakeLEDColor(R,G,B,W,I) LEDColor(R, G, B) -#endif #define LEDColorOff() LEDColor( 0, 0, 0) #define LEDColorRed() LEDColor(255, 0, 0) @@ -147,25 +115,15 @@ class LEDLights { static void setup(); // init() static void set_color(const LEDColor &color - #if ENABLED(NEOPIXEL_LED) - , bool isSequence=false - #endif + OPTARG(NEOPIXEL_IS_SEQUENTIAL, bool isSequence=false) ); static inline void set_color(uint8_t r, uint8_t g, uint8_t b - #if HAS_WHITE_LED - , uint8_t w=0 - #endif - #if ENABLED(NEOPIXEL_LED) - , uint8_t i=NEOPIXEL_BRIGHTNESS - , bool isSequence=false - #endif + OPTARG(HAS_WHITE_LED, uint8_t w=0) + OPTARG(NEOPIXEL_LED, uint8_t i=NEOPIXEL_BRIGHTNESS) + OPTARG(NEOPIXEL_IS_SEQUENTIAL, bool isSequence=false) ) { - set_color(MakeLEDColor(r, g, b, w, i) - #if ENABLED(NEOPIXEL_LED) - , isSequence - #endif - ); + set_color(LEDColor(r, g, b OPTARG(HAS_WHITE_LED, w) OPTARG(NEOPIXEL_LED, i)) OPTARG(NEOPIXEL_IS_SEQUENTIAL, isSequence)); } static inline void set_off() { set_color(LEDColorOff()); } @@ -187,13 +145,15 @@ class LEDLights { static inline LEDColor get_color() { return lights_on ? color : LEDColorOff(); } #endif - #if EITHER(LED_CONTROL_MENU, PRINTER_EVENT_LEDS) + #if ANY(LED_CONTROL_MENU, PRINTER_EVENT_LEDS, CASE_LIGHT_IS_COLOR_LED) static LEDColor color; // last non-off color static bool lights_on; // the last set color was "on" #endif #if ENABLED(LED_CONTROL_MENU) static void toggle(); // swap "off" with color + #endif + #if EITHER(LED_CONTROL_MENU, CASE_LIGHT_USE_RGB_LED) static inline void update() { set_color(color); } #endif @@ -203,7 +163,7 @@ class LEDLights { public: static inline void reset_timeout(const millis_t &ms) { led_off_time = ms + LED_BACKLIGHT_TIMEOUT; - if (!lights_on) set_default(); + if (!lights_on) update(); } static void update_timeout(const bool power_on); #endif @@ -221,8 +181,14 @@ extern LEDLights leds; static void set_color(const LEDColor &color); - inline void set_color(uint8_t r, uint8_t g, uint8_t b, uint8_t w=0, uint8_t i=NEOPIXEL2_BRIGHTNESS) { - set_color(MakeLEDColor(r, g, b, w, i)); + static inline void set_color(uint8_t r, uint8_t g, uint8_t b + OPTARG(HAS_WHITE_LED, uint8_t w=0) + OPTARG(NEOPIXEL_LED, uint8_t i=NEOPIXEL_BRIGHTNESS) + ) { + set_color(LEDColor(r, g, b + OPTARG(HAS_WHITE_LED, w) + OPTARG(NEOPIXEL_LED, i) + )); } static inline void set_off() { set_color(LEDColorOff()); } diff --git a/Marlin/src/feature/leds/neopixel.cpp b/Marlin/src/feature/leds/neopixel.cpp index 27bbeb348c5d..2654e9a1df5a 100644 --- a/Marlin/src/feature/leds/neopixel.cpp +++ b/Marlin/src/feature/leds/neopixel.cpp @@ -28,7 +28,7 @@ #if ENABLED(NEOPIXEL_LED) -#include "neopixel.h" +#include "leds.h" #if EITHER(NEOPIXEL_STARTUP_TEST, NEOPIXEL2_STARTUP_TEST) #include "../../core/utility.h" @@ -37,17 +37,21 @@ Marlin_NeoPixel neo; int8_t Marlin_NeoPixel::neoindex; -Adafruit_NeoPixel Marlin_NeoPixel::adaneo1(NEOPIXEL_PIXELS, NEOPIXEL_PIN, NEOPIXEL_TYPE + NEO_KHZ800) - #if CONJOINED_NEOPIXEL - , Marlin_NeoPixel::adaneo2(NEOPIXEL_PIXELS, NEOPIXEL2_PIN, NEOPIXEL2_TYPE + NEO_KHZ800) - #endif -; +Adafruit_NeoPixel Marlin_NeoPixel::adaneo1(NEOPIXEL_PIXELS, NEOPIXEL_PIN, NEOPIXEL_TYPE + NEO_KHZ800); +#if CONJOINED_NEOPIXEL + Adafruit_NeoPixel Marlin_NeoPixel::adaneo2(NEOPIXEL_PIXELS, NEOPIXEL2_PIN, NEOPIXEL2_TYPE + NEO_KHZ800); +#endif -#ifdef NEOPIXEL_BKGD_LED_INDEX +#ifdef NEOPIXEL_BKGD_INDEX_FIRST + + void Marlin_NeoPixel::set_background_color(uint8_t r, uint8_t g, uint8_t b, uint8_t w) { + for (int background_led = NEOPIXEL_BKGD_INDEX_FIRST; background_led <= NEOPIXEL_BKGD_INDEX_LAST; background_led++) + set_pixel_color(background_led, adaneo1.Color(r, g, b, w)); + } - void Marlin_NeoPixel::set_color_background() { - uint8_t background_color[4] = NEOPIXEL_BKGD_COLOR; - set_pixel_color(NEOPIXEL_BKGD_LED_INDEX, adaneo1.Color(background_color[0], background_color[1], background_color[2], background_color[3])); + void Marlin_NeoPixel::reset_background_color() { + constexpr uint8_t background_color[4] = NEOPIXEL_BKGD_COLOR; + set_background_color(background_color[0], background_color[1], background_color[2], background_color[3]); } #endif @@ -59,9 +63,10 @@ void Marlin_NeoPixel::set_color(const uint32_t color) { } else { for (uint16_t i = 0; i < pixels(); ++i) { - #ifdef NEOPIXEL_BKGD_LED_INDEX - if (i == NEOPIXEL_BKGD_LED_INDEX && color != 0x000000) { - set_color_background(); + #ifdef NEOPIXEL_BKGD_INDEX_FIRST + if (i == NEOPIXEL_BKGD_INDEX_FIRST && TERN(NEOPIXEL_BKGD_ALWAYS_ON, true, color != 0x000000)) { + reset_background_color(); + i += NEOPIXEL_BKGD_INDEX_LAST - (NEOPIXEL_BKGD_INDEX_FIRST); continue; } #endif @@ -90,35 +95,22 @@ void Marlin_NeoPixel::init() { safe_delay(500); set_color_startup(adaneo1.Color(0, 0, 255, 0)); // blue safe_delay(500); + #if HAS_WHITE_LED + set_color_startup(adaneo1.Color(0, 0, 0, 255)); // white + safe_delay(500); + #endif #endif - #ifdef NEOPIXEL_BKGD_LED_INDEX - set_color_background(); - #endif - - #if ENABLED(LED_USER_PRESET_STARTUP) - set_color(adaneo1.Color(LED_USER_PRESET_RED, LED_USER_PRESET_GREEN, LED_USER_PRESET_BLUE, LED_USER_PRESET_WHITE)); - #else - set_color(adaneo1.Color(0, 0, 0, 0)); + #ifdef NEOPIXEL_BKGD_INDEX_FIRST + reset_background_color(); #endif -} -#if 0 -bool Marlin_NeoPixel::set_led_color(const uint8_t r, const uint8_t g, const uint8_t b, const uint8_t w, const uint8_t p) { - const uint32_t color = adaneo1.Color(r, g, b, w); - set_brightness(p); - #if DISABLED(NEOPIXEL_IS_SEQUENTIAL) - set_color(color); - return false; - #else - static uint16_t nextLed = 0; - set_pixel_color(nextLed, color); - show(); - if (++nextLed >= pixels()) nextLed = 0; - return true; - #endif + set_color(adaneo1.Color + TERN(LED_USER_PRESET_STARTUP, + (LED_USER_PRESET_RED, LED_USER_PRESET_GREEN, LED_USER_PRESET_BLUE, LED_USER_PRESET_WHITE), + (0, 0, 0, 0)) + ); } -#endif #if ENABLED(NEOPIXEL2_SEPARATE) @@ -158,13 +150,17 @@ bool Marlin_NeoPixel::set_led_color(const uint8_t r, const uint8_t g, const uint safe_delay(500); set_color_startup(adaneo.Color(0, 0, 255, 0)); // blue safe_delay(500); + #if HAS_WHITE_LED2 + set_color_startup(adaneo.Color(0, 0, 0, 255)); // white + safe_delay(500); + #endif #endif - #if ENABLED(NEO2_USER_PRESET_STARTUP) - set_color(adaneo.Color(NEO2_USER_PRESET_RED, NEO2_USER_PRESET_GREEN, NEO2_USER_PRESET_BLUE, NEO2_USER_PRESET_WHITE)); - #else - set_color(adaneo.Color(0, 0, 0, 0)); - #endif + set_color(adaneo.Color + TERN(NEO2_USER_PRESET_STARTUP, + (NEO2_USER_PRESET_RED, NEO2_USER_PRESET_GREEN, NEO2_USER_PRESET_BLUE, NEO2_USER_PRESET_WHITE), + (0, 0, 0, 0)) + ); } #endif // NEOPIXEL2_SEPARATE diff --git a/Marlin/src/feature/leds/neopixel.h b/Marlin/src/feature/leds/neopixel.h index 42046fa5638f..b2c16459f504 100644 --- a/Marlin/src/feature/leds/neopixel.h +++ b/Marlin/src/feature/leds/neopixel.h @@ -25,6 +25,10 @@ * NeoPixel support */ +#ifndef _NEOPIXEL_INCLUDE_ + #error "Always include 'leds.h' and not 'neopixel.h' directly." +#endif + // ------------------------ // Includes // ------------------------ @@ -38,24 +42,24 @@ // Defines // ------------------------ -#if defined(NEOPIXEL2_TYPE) && NEOPIXEL2_TYPE != NEOPIXEL_TYPE && DISABLED(NEOPIXEL2_SEPARATE) - #define MULTIPLE_NEOPIXEL_TYPES 1 -#endif +#define _NEO_IS_RGB(N) (N == NEO_RGB || N == NEO_RBG || N == NEO_GRB || N == NEO_GBR || N == NEO_BRG || N == NEO_BGR) -#if EITHER(MULTIPLE_NEOPIXEL_TYPES, NEOPIXEL2_INSERIES) - #define CONJOINED_NEOPIXEL 1 +#if !_NEO_IS_RGB(NEOPIXEL_TYPE) + #define HAS_WHITE_LED 1 #endif -#if NEOPIXEL_TYPE == NEO_RGB || NEOPIXEL_TYPE == NEO_RBG || NEOPIXEL_TYPE == NEO_GRB || NEOPIXEL_TYPE == NEO_GBR || NEOPIXEL_TYPE == NEO_BRG || NEOPIXEL_TYPE == NEO_BGR - #define NEOPIXEL_IS_RGB 1 +#if HAS_WHITE_LED + #define NEO_WHITE 0, 0, 0, 255 #else - #define NEOPIXEL_IS_RGBW 1 + #define NEO_WHITE 255, 255, 255 #endif -#if NEOPIXEL_IS_RGB - #define NEO_WHITE 255, 255, 255, 0 -#else - #define NEO_WHITE 0, 0, 0, 255 +#if defined(NEOPIXEL2_TYPE) && NEOPIXEL2_TYPE != NEOPIXEL_TYPE && DISABLED(NEOPIXEL2_SEPARATE) + #define MULTIPLE_NEOPIXEL_TYPES 1 +#endif + +#if EITHER(MULTIPLE_NEOPIXEL_TYPES, NEOPIXEL2_INSERIES) + #define CONJOINED_NEOPIXEL 1 #endif // ------------------------ @@ -64,11 +68,10 @@ class Marlin_NeoPixel { private: - static Adafruit_NeoPixel adaneo1 - #if CONJOINED_NEOPIXEL - , adaneo2 - #endif - ; + static Adafruit_NeoPixel adaneo1; + #if CONJOINED_NEOPIXEL + static Adafruit_NeoPixel adaneo2; + #endif public: static int8_t neoindex; @@ -78,8 +81,9 @@ class Marlin_NeoPixel { static void set_color(const uint32_t c); - #ifdef NEOPIXEL_BKGD_LED_INDEX - static void set_color_background(); + #ifdef NEOPIXEL_BKGD_INDEX_FIRST + static void set_background_color(uint8_t r, uint8_t g, uint8_t b, uint8_t w); + static void reset_background_color(); #endif static inline void begin() { @@ -93,9 +97,7 @@ class Marlin_NeoPixel { else adaneo1.setPixelColor(n, c); #else adaneo1.setPixelColor(n, c); - #if MULTIPLE_NEOPIXEL_TYPES - adaneo2.setPixelColor(n, c); - #endif + TERN_(MULTIPLE_NEOPIXEL_TYPES, adaneo2.setPixelColor(n, c)); #endif } @@ -105,27 +107,27 @@ class Marlin_NeoPixel { } static inline void show() { + // Some platforms cannot maintain PWM output when NeoPixel disables interrupts for long durations. + TERN_(HAS_PAUSE_SERVO_OUTPUT, PAUSE_SERVO_OUTPUT()); adaneo1.show(); #if PIN_EXISTS(NEOPIXEL2) #if CONJOINED_NEOPIXEL adaneo2.show(); #else - TERN(NEOPIXEL2_SEPARATE,,adaneo1.setPin(NEOPIXEL2_PIN)); adaneo1.show(); adaneo1.setPin(NEOPIXEL_PIN); #endif #endif + TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT()); } - #if 0 - bool set_led_color(const uint8_t r, const uint8_t g, const uint8_t b, const uint8_t w, const uint8_t p); - #endif - // Accessors - static inline uint16_t pixels() { TERN(NEOPIXEL2_INSERIES, return adaneo1.numPixels() * 2, return adaneo1.numPixels()); } + static inline uint16_t pixels() { return adaneo1.numPixels() * TERN1(NEOPIXEL2_INSERIES, 2); } + static inline uint8_t brightness() { return adaneo1.getBrightness(); } - static inline uint32_t Color(uint8_t r, uint8_t g, uint8_t b, uint8_t w) { - return adaneo1.Color(r, g, b, w); + + static inline uint32_t Color(uint8_t r, uint8_t g, uint8_t b OPTARG(HAS_WHITE_LED, uint8_t w)) { + return adaneo1.Color(r, g, b OPTARG(HAS_WHITE_LED, w)); } }; @@ -134,15 +136,12 @@ extern Marlin_NeoPixel neo; // Neo pixel channel 2 #if ENABLED(NEOPIXEL2_SEPARATE) - #if NEOPIXEL2_TYPE == NEO_RGB || NEOPIXEL2_TYPE == NEO_RBG || NEOPIXEL2_TYPE == NEO_GRB || NEOPIXEL2_TYPE == NEO_GBR || NEOPIXEL2_TYPE == NEO_BRG || NEOPIXEL2_TYPE == NEO_BGR + #if _NEO_IS_RGB(NEOPIXEL2_TYPE) #define NEOPIXEL2_IS_RGB 1 + #define NEO2_WHITE 255, 255, 255 #else #define NEOPIXEL2_IS_RGBW 1 - #endif - - #if NEOPIXEL2_IS_RGB - #define NEO2_WHITE 255, 255, 255, 0 - #else + #define HAS_WHITE_LED2 1 // A white component can be passed for NEOPIXEL2 #define NEO2_WHITE 0, 0, 0, 255 #endif @@ -169,11 +168,13 @@ extern Marlin_NeoPixel neo; // Accessors static inline uint16_t pixels() { return adaneo.numPixels();} static inline uint8_t brightness() { return adaneo.getBrightness(); } - static inline uint32_t Color(uint8_t r, uint8_t g, uint8_t b, uint8_t w) { - return adaneo.Color(r, g, b, w); + static inline uint32_t Color(uint8_t r, uint8_t g, uint8_t b OPTARG(HAS_WHITE_LED2, uint8_t w)) { + return adaneo.Color(r, g, b OPTARG(HAS_WHITE_LED2, w)); } }; extern Marlin_NeoPixel2 neo2; #endif // NEOPIXEL2_SEPARATE + +#undef _NEO_IS_RGB diff --git a/Marlin/src/feature/leds/pca9632.cpp b/Marlin/src/feature/leds/pca9632.cpp index d8af31cb6ce4..abea98800451 100644 --- a/Marlin/src/feature/leds/pca9632.cpp +++ b/Marlin/src/feature/leds/pca9632.cpp @@ -58,7 +58,7 @@ #define PCA9632_AUTOGLO 0xC0 #define PCA9632_AUTOGI 0xE0 -// Red=LED0 Green=LED1 Blue=LED2 +// Red=LED0 Green=LED1 Blue=LED2 White=LED3 #ifndef PCA9632_RED #define PCA9632_RED 0x00 #endif @@ -68,9 +68,12 @@ #ifndef PCA9632_BLU #define PCA9632_BLU 0x04 #endif +#if HAS_WHITE_LED && !defined(PCA9632_WHT) + #define PCA9632_WHT 0x06 +#endif // If any of the color indexes are greater than 0x04 they can't use auto increment -#if !defined(PCA9632_NO_AUTO_INC) && (PCA9632_RED > 0x04 || PCA9632_GRN > 0x04 || PCA9632_BLU > 0x04) +#if !defined(PCA9632_NO_AUTO_INC) && (PCA9632_RED > 0x04 || PCA9632_GRN > 0x04 || PCA9632_BLU > 0x04 || PCA9632_WHT > 0x04) #define PCA9632_NO_AUTO_INC #endif @@ -89,25 +92,26 @@ static void PCA9632_WriteRegister(const byte addr, const byte regadd, const byte Wire.endTransmission(); } -static void PCA9632_WriteAllRegisters(const byte addr, const byte regadd, const byte vr, const byte vg, const byte vb) { +static void PCA9632_WriteAllRegisters(const byte addr, const byte regadd, const byte vr, const byte vg, const byte vb + OPTARG(PCA9632_RGBW, const byte vw) +) { #if DISABLED(PCA9632_NO_AUTO_INC) - uint8_t data[4], len = 4; + uint8_t data[4]; data[0] = PCA9632_AUTO_IND | regadd; data[1 + (PCA9632_RED >> 1)] = vr; data[1 + (PCA9632_GRN >> 1)] = vg; data[1 + (PCA9632_BLU >> 1)] = vb; + Wire.beginTransmission(I2C_ADDRESS(addr)); + Wire.write(data, sizeof(data)); + Wire.endTransmission(); #else - uint8_t data[6], len = 6; - data[0] = regadd + (PCA9632_RED >> 1); - data[1] = vr; - data[2] = regadd + (PCA9632_GRN >> 1); - data[3] = vg; - data[4] = regadd + (PCA9632_BLU >> 1); - data[5] = vb; + PCA9632_WriteRegister(addr, regadd + (PCA9632_RED >> 1), vr); + PCA9632_WriteRegister(addr, regadd + (PCA9632_GRN >> 1), vg); + PCA9632_WriteRegister(addr, regadd + (PCA9632_BLU >> 1), vb); + #if ENABLED(PCA9632_RGBW) + PCA9632_WriteRegister(addr, regadd + (PCA9632_WHT >> 1), vw); + #endif #endif - Wire.beginTransmission(I2C_ADDRESS(addr)); - Wire.write(data, len); - Wire.endTransmission(); } #if 0 @@ -130,9 +134,15 @@ void PCA9632_set_led_color(const LEDColor &color) { const byte LEDOUT = (color.r ? LED_PWM << PCA9632_RED : 0) | (color.g ? LED_PWM << PCA9632_GRN : 0) - | (color.b ? LED_PWM << PCA9632_BLU : 0); - - PCA9632_WriteAllRegisters(PCA9632_ADDRESS,PCA9632_PWM0, color.r, color.g, color.b); + | (color.b ? LED_PWM << PCA9632_BLU : 0) + #if ENABLED(PCA9632_RGBW) + | (color.w ? LED_PWM << PCA9632_WHT : 0) + #endif + ; + + PCA9632_WriteAllRegisters(PCA9632_ADDRESS,PCA9632_PWM0, color.r, color.g, color.b + OPTARG(PCA9632_RGBW, color.w) + ); PCA9632_WriteRegister(PCA9632_ADDRESS,PCA9632_LEDOUT, LEDOUT); } diff --git a/Marlin/src/feature/leds/printer_event_leds.cpp b/Marlin/src/feature/leds/printer_event_leds.cpp index 31c628c2816a..e6407a6320a5 100644 --- a/Marlin/src/feature/leds/printer_event_leds.cpp +++ b/Marlin/src/feature/leds/printer_event_leds.cpp @@ -40,16 +40,15 @@ PrinterEventLEDs printerEventLEDs; uint8_t PrinterEventLEDs::old_intensity = 0; - inline uint8_t pel_intensity(const float &start, const float ¤t, const float &target) { - return (uint8_t)map(constrain(current, start, target), start, target, 0.f, 255.f); + inline uint8_t pel_intensity(const celsius_t start, const celsius_t current, const celsius_t target) { + if (start == target) return 255; + return (uint8_t)map(constrain(current, start, target), start, target, 0, 255); } - inline void pel_set_rgb(const uint8_t r, const uint8_t g, const uint8_t b) { + inline void pel_set_rgb(const uint8_t r, const uint8_t g, const uint8_t b OPTARG(HAS_WHITE_LED, const uint8_t w=0)) { leds.set_color( - MakeLEDColor(r, g, b, 0, neo.brightness()) - #if ENABLED(NEOPIXEL_IS_SEQUENTIAL) - , true - #endif + LEDColor(r, g, b OPTARG(HAS_WHITE_LED, w) OPTARG(NEOPIXEL_LED, neo.brightness())) + OPTARG(NEOPIXEL_IS_SEQUENTIAL, true) ); } @@ -57,7 +56,7 @@ PrinterEventLEDs printerEventLEDs; #if HAS_TEMP_HOTEND - void PrinterEventLEDs::onHotendHeating(const float &start, const float ¤t, const float &target) { + void PrinterEventLEDs::onHotendHeating(const celsius_t start, const celsius_t current, const celsius_t target) { const uint8_t blue = pel_intensity(start, current, target); if (blue != old_intensity) { old_intensity = blue; @@ -69,13 +68,26 @@ PrinterEventLEDs printerEventLEDs; #if HAS_HEATED_BED - void PrinterEventLEDs::onBedHeating(const float &start, const float ¤t, const float &target) { + void PrinterEventLEDs::onBedHeating(const celsius_t start, const celsius_t current, const celsius_t target) { const uint8_t red = pel_intensity(start, current, target); if (red != old_intensity) { old_intensity = red; pel_set_rgb(red, 0, 255); } } + +#endif + +#if HAS_HEATED_CHAMBER + + void PrinterEventLEDs::onChamberHeating(const celsius_t start, const celsius_t current, const celsius_t target) { + const uint8_t green = pel_intensity(start, current, target); + if (green != old_intensity) { + old_intensity = green; + pel_set_rgb(255, green, 255); + } + } + #endif #endif // PRINTER_EVENT_LEDS diff --git a/Marlin/src/feature/leds/printer_event_leds.h b/Marlin/src/feature/leds/printer_event_leds.h index 86ec292aa3da..b2201433d821 100644 --- a/Marlin/src/feature/leds/printer_event_leds.h +++ b/Marlin/src/feature/leds/printer_event_leds.h @@ -36,27 +36,26 @@ class PrinterEventLEDs { static bool leds_off_after_print; #endif - static inline void set_done() { - #if ENABLED(LED_COLOR_PRESETS) - leds.set_default(); - #else - leds.set_off(); - #endif - } + static inline void set_done() { TERN(LED_COLOR_PRESETS, leds.set_default(), leds.set_off()); } public: #if HAS_TEMP_HOTEND static inline LEDColor onHotendHeatingStart() { old_intensity = 0; return leds.get_color(); } - static void onHotendHeating(const float &start, const float ¤t, const float &target); + static void onHotendHeating(const celsius_t start, const celsius_t current, const celsius_t target); #endif #if HAS_HEATED_BED static inline LEDColor onBedHeatingStart() { old_intensity = 127; return leds.get_color(); } - static void onBedHeating(const float &start, const float ¤t, const float &target); + static void onBedHeating(const celsius_t start, const celsius_t current, const celsius_t target); #endif - #if HAS_TEMP_HOTEND || HAS_HEATED_BED - static inline void onHeatingDone() { leds.set_white(); } + #if HAS_HEATED_CHAMBER + static inline LEDColor onChamberHeatingStart() { old_intensity = 127; return leds.get_color(); } + static void onChamberHeating(const celsius_t start, const celsius_t current, const celsius_t target); + #endif + + #if HAS_TEMP_HOTEND || HAS_HEATED_BED || HAS_HEATED_CHAMBER + static inline void onHeatingDone() { leds.set_white(); } static inline void onPidTuningDone(LEDColor c) { leds.set_color(c); } #endif diff --git a/Marlin/src/feature/leds/tempstat.cpp b/Marlin/src/feature/leds/tempstat.cpp index 880258f85245..967b9f4d815d 100644 --- a/Marlin/src/feature/leds/tempstat.cpp +++ b/Marlin/src/feature/leds/tempstat.cpp @@ -36,10 +36,10 @@ void handle_status_leds() { static millis_t next_status_led_update_ms = 0; if (ELAPSED(millis(), next_status_led_update_ms)) { next_status_led_update_ms += 500; // Update every 0.5s - float max_temp = TERN0(HAS_HEATED_BED, _MAX(thermalManager.degTargetBed(), thermalManager.degBed())); + celsius_t max_temp = TERN0(HAS_HEATED_BED, _MAX(thermalManager.degTargetBed(), thermalManager.wholeDegBed())); HOTEND_LOOP() - max_temp = _MAX(max_temp, thermalManager.degHotend(e), thermalManager.degTargetHotend(e)); - const int8_t new_red = (max_temp > 55.0) ? HIGH : (max_temp < 54.0 || old_red < 0) ? LOW : old_red; + max_temp = _MAX(max_temp, thermalManager.wholeDegHotend(e), thermalManager.degTargetHotend(e)); + const int8_t new_red = (max_temp > 55) ? HIGH : (max_temp < 54 || old_red < 0) ? LOW : old_red; if (new_red != old_red) { old_red = new_red; #if PIN_EXISTS(STAT_LED_RED) diff --git a/Marlin/src/feature/max7219.cpp b/Marlin/src/feature/max7219.cpp index ebcb56490d4f..200e6b580d5b 100644 --- a/Marlin/src/feature/max7219.cpp +++ b/Marlin/src/feature/max7219.cpp @@ -127,7 +127,7 @@ uint8_t Max7219::suspended; // = 0; void Max7219::error(const char * const func, const int32_t v1, const int32_t v2/*=-1*/) { #if ENABLED(MAX7219_ERRORS) SERIAL_ECHOPGM("??? Max7219::"); - serialprintPGM(func); + SERIAL_ECHOPGM_P(func); SERIAL_CHAR('('); SERIAL_ECHO(v1); if (v2 > 0) SERIAL_ECHOPAIR(", ", v2); @@ -256,7 +256,7 @@ void Max7219::set(const uint8_t line, const uint8_t bits) { } // Draw a float with a decimal point and optional digits - void Max7219::print(const uint8_t start, const float value, const uint8_t pre_size, const uint8_t post_size, const bool leadzero=false) { + void Max7219::print(const uint8_t start, const_float_t value, const uint8_t pre_size, const uint8_t post_size, const bool leadzero=false) { if (pre_size) print(start, value, pre_size, leadzero, !!post_size); if (post_size) { const int16_t after = ABS(value) * (10 ^ post_size); diff --git a/Marlin/src/feature/max7219.h b/Marlin/src/feature/max7219.h index 8e98c9456c3f..3e5b62db2f75 100644 --- a/Marlin/src/feature/max7219.h +++ b/Marlin/src/feature/max7219.h @@ -100,6 +100,13 @@ class Max7219 { // Update a single native line on just one unit static void refresh_unit_line(const uint8_t line); + #if ENABLED(MAX7219_NUMERIC) + // Draw an integer with optional leading zeros and optional decimal point + void print(const uint8_t start, int16_t value, uint8_t size, const bool leadzero=false, bool dec=false); + // Draw a float with a decimal point and optional digits + void print(const uint8_t start, const_float_t value, const uint8_t pre_size, const uint8_t post_size, const bool leadzero=false); + #endif + // Set a single LED by XY coordinate static void led_set(const uint8_t x, const uint8_t y, const bool on); static void led_on(const uint8_t x, const uint8_t y); diff --git a/Marlin/src/feature/meatpack.cpp b/Marlin/src/feature/meatpack.cpp new file mode 100644 index 000000000000..6803a0de7df4 --- /dev/null +++ b/Marlin/src/feature/meatpack.cpp @@ -0,0 +1,219 @@ +/** + * 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 . + * + */ + +/** + * MeatPack G-code Compression + * + * Algorithm & Implementation: Scott Mudge - mail@scottmudge.com + * Date: Dec. 2020 + * + * Character Frequencies from ~30 MB of comment-stripped gcode: + * '1' -> 4451136 '4' -> 1353273 '\n' -> 1087683 '-' -> 90242 + * '0' -> 4253577 '9' -> 1352147 'G' -> 1075806 'Z' -> 34109 + * ' ' -> 3053297 '3' -> 1262929 'X' -> 975742 'M' -> 11879 + * '.' -> 3035310 '5' -> 1189871 'E' -> 965275 'S' -> 9910 + * '2' -> 1523296 '6' -> 1127900 'Y' -> 965274 + * '8' -> 1366812 '7' -> 1112908 'F' -> 99416 + * + * When space is omitted the letter 'E' is used in its place + */ + +#include "../inc/MarlinConfig.h" + +#if HAS_MEATPACK + +#include "meatpack.h" + +#define MeatPack_ProtocolVersion "PV01" +//#define MP_DEBUG + +#define DEBUG_OUT ENABLED(MP_DEBUG) +#include "../core/debug_out.h" + +// The 15 most-common characters used in G-code, ~90-95% of all G-code uses these characters +// Stored in SRAM for performance. +uint8_t meatPackLookupTable[16] = { + '0', '1', '2', '3', '4', '5', '6', '7', '8', '9', + '.', ' ', '\n', 'G', 'X', + '\0' // Unused. 0b1111 indicates a literal character +}; + +#if ENABLED(MP_DEBUG) + uint8_t chars_decoded = 0; // Log the first 64 bytes after each reset +#endif + +void MeatPack::reset_state() { + state = 0; + cmd_is_next = false; + second_char = 0; + cmd_count = full_char_count = char_out_count = 0; + TERN_(MP_DEBUG, chars_decoded = 0); +} + +/** + * Unpack one or two characters from a packed byte into a buffer. + * Return flags indicating whether any literal bytes follow. + */ +uint8_t MeatPack::unpack_chars(const uint8_t pk, uint8_t* __restrict const chars_out) { + uint8_t out = 0; + + // If lower nybble is 1111, the higher nybble is unused, and next char is full. + if ((pk & kFirstNotPacked) == kFirstNotPacked) + out = kFirstCharIsLiteral; + else { + const uint8_t chr = pk & 0x0F; + chars_out[0] = meatPackLookupTable[chr]; // Set the first char + } + + // Check if upper nybble is 1111... if so, we don't need the second char. + if ((pk & kSecondNotPacked) == kSecondNotPacked) + out |= kSecondCharIsLiteral; + else { + const uint8_t chr = (pk >> 4) & 0x0F; + chars_out[1] = meatPackLookupTable[chr]; // Set the second char + } + + return out; +} + +/** + * Interpret a single (non-command) character + * according to the current MeatPack state. + */ +void MeatPack::handle_rx_char_inner(const uint8_t c) { + if (TEST(state, MPConfig_Bit_Active)) { // Is MeatPack active? + if (!full_char_count) { // No literal characters to fetch? + uint8_t buf[2] = { 0, 0 }; + const uint8_t res = unpack_chars(c, buf); // Decode the byte into one or two characters. + if (res & kFirstCharIsLiteral) { // The 1st character couldn't be packed. + ++full_char_count; // So the next stream byte is a full character. + if (res & kSecondCharIsLiteral) ++full_char_count; // The 2nd character couldn't be packed. Another stream byte is a full character. + else second_char = buf[1]; // Retain the unpacked second character. + } + else { + handle_output_char(buf[0]); // Send the unpacked first character out. + if (buf[0] != '\n') { // After a newline the next char won't be set + if (res & kSecondCharIsLiteral) ++full_char_count; // The 2nd character couldn't be packed. The next stream byte is a full character. + else handle_output_char(buf[1]); // Send the unpacked second character out. + } + } + } + else { + handle_output_char(c); // Pass through the character that couldn't be packed... + if (second_char) { + handle_output_char(second_char); // ...and send an unpacked 2nd character, if set. + second_char = 0; + } + --full_char_count; // One literal character was consumed + } + } + else // Packing not enabled, just copy character to output + handle_output_char(c); +} + +/** + * Buffer a single output character which will be picked up in + * GCodeQueue::get_serial_commands via calls to get_result_char + */ +void MeatPack::handle_output_char(const uint8_t c) { + char_out_buf[char_out_count++] = c; + + #if ENABLED(MP_DEBUG) + if (chars_decoded < 1024) { + ++chars_decoded; + DEBUG_ECHOLNPAIR("RB: ", AS_CHAR(c)); + } + #endif +} + +/** + * Process a MeatPack command byte to update the state. + * Report the new state to serial. + */ +void MeatPack::handle_command(const MeatPack_Command c) { + switch (c) { + case MPCommand_QueryConfig: break; + case MPCommand_EnablePacking: SBI(state, MPConfig_Bit_Active); DEBUG_ECHOLNPGM("[MPDBG] ENA REC"); break; + case MPCommand_DisablePacking: CBI(state, MPConfig_Bit_Active); DEBUG_ECHOLNPGM("[MPDBG] DIS REC"); break; + case MPCommand_ResetAll: reset_state(); DEBUG_ECHOLNPGM("[MPDBG] RESET REC"); break; + case MPCommand_EnableNoSpaces: + SBI(state, MPConfig_Bit_NoSpaces); + meatPackLookupTable[kSpaceCharIdx] = kSpaceCharReplace; DEBUG_ECHOLNPGM("[MPDBG] ENA NSP"); break; + case MPCommand_DisableNoSpaces: + CBI(state, MPConfig_Bit_NoSpaces); + meatPackLookupTable[kSpaceCharIdx] = ' '; DEBUG_ECHOLNPGM("[MPDBG] DIS NSP"); break; + default: DEBUG_ECHOLNPGM("[MPDBG] UNK CMD REC"); + } + report_state(); +} + +void MeatPack::report_state() { + // NOTE: if any configuration vars are added below, the outgoing sync text for host plugin + // should not contain the "PV' substring, as this is used to indicate protocol version + SERIAL_ECHOPGM("[MP] "); + SERIAL_ECHOPGM(MeatPack_ProtocolVersion " "); + serialprint_onoff(TEST(state, MPConfig_Bit_Active)); + SERIAL_ECHOPGM_P(TEST(state, MPConfig_Bit_NoSpaces) ? PSTR(" NSP\n") : PSTR(" ESP\n")); +} + +/** + * Interpret a single character received from serial + * according to the current meatpack state. + */ +void MeatPack::handle_rx_char(const uint8_t c, const serial_index_t serial_ind) { + if (c == kCommandByte) { // A command (0xFF) byte? + if (cmd_count) { // In fact, two in a row? + cmd_is_next = true; // Then a MeatPack command follows + cmd_count = 0; + } + else + ++cmd_count; // cmd_count = 1 // One command byte received so far... + return; + } + + if (cmd_is_next) { // Were two command bytes received? + PORT_REDIRECT(SERIAL_PORTMASK(serial_ind)); + handle_command((MeatPack_Command)c); // Then the byte is a MeatPack command + cmd_is_next = false; + return; + } + + if (cmd_count) { // Only a single 0xFF was received + handle_rx_char_inner(kCommandByte); // A single 0xFF is passed on literally so it can be interpreted as kFirstNotPacked|kSecondNotPacked + cmd_count = 0; + } + + handle_rx_char_inner(c); // Other characters are passed on for MeatPack decoding +} + +uint8_t MeatPack::get_result_char(char * const __restrict out) { + uint8_t res = 0; + if (char_out_count) { + res = char_out_count; + char_out_count = 0; + for (uint8_t i = 0; i < res; ++i) + out[i] = (char)char_out_buf[i]; + } + return res; +} + +#endif // HAS_MEATPACK diff --git a/Marlin/src/feature/meatpack.h b/Marlin/src/feature/meatpack.h new file mode 100644 index 000000000000..a56e65b6cc30 --- /dev/null +++ b/Marlin/src/feature/meatpack.h @@ -0,0 +1,175 @@ +/** + * 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 . + * + */ + +/* + * MeatPack G-code Compression + * + * Algorithm & Implementation: Scott Mudge - mail@scottmudge.com + * Date: Dec. 2020 + * + * Specifically optimized for 3D printing G-Code, this is a zero-cost data compression method + * which packs ~180-190% more data into the same amount of bytes going to the CNC controller. + * As a majority of G-Code can be represented by a restricted alphabet, I performed histogram + * analysis on a wide variety of 3D printing gcode samples, and found ~93% of all gcode could + * be represented by the same 15-character alphabet. + * + * This allowed me to design a system of packing 2 8-bit characters into a single byte, assuming + * they fall within this limited 15-character alphabet. Using a 4-bit lookup table, these 8-bit + * characters can be represented by a 4-bit index. + * + * Combined with some logic to allow commingling of full-width characters outside of this 15- + * character alphabet (at the cost of an extra 8-bits per full-width character), and by stripping + * out unnecessary comments, the end result is gcode which is roughly half the original size. + * + * Why did I do this? I noticed micro-stuttering and other data-bottleneck issues while printing + * objects with high curvature, especially at high speeds. There is also the issue of the limited + * baud rate provided by Prusa's Atmega2560-based boards, over the USB serial connection. So soft- + * ware like OctoPrint would also suffer this same micro-stuttering and poor print quality issue. + * + */ +#pragma once + +#include +#include "../core/serial_hook.h" + +/** + * Commands sent to MeatPack to control its behavior. + * They are sent by first sending 2x MeatPack_CommandByte (0xFF) in sequence, + * followed by one of the command bytes below. + * Provided that 0xFF is an exceedingly rare character that is virtually never + * present in G-code naturally, it is safe to assume 2 in sequence should never + * happen naturally, and so it is used as a signal here. + * + * 0xFF *IS* used in "packed" G-code (used to denote that the next 2 characters are + * full-width), however 2 in a row will never occur, as the next 2 bytes will always + * some non-0xFF character. + */ +enum MeatPack_Command : uint8_t { + MPCommand_None = 0, + MPCommand_EnablePacking = 0xFB, + MPCommand_DisablePacking = 0xFA, + MPCommand_ResetAll = 0xF9, + MPCommand_QueryConfig = 0xF8, + MPCommand_EnableNoSpaces = 0xF7, + MPCommand_DisableNoSpaces = 0xF6 +}; + +enum MeatPack_ConfigStateBits : uint8_t { + MPConfig_Bit_Active = 0, + MPConfig_Bit_NoSpaces = 1 +}; + +class MeatPack { + + // Utility definitions + static const uint8_t kCommandByte = 0b11111111, + kFirstNotPacked = 0b00001111, + kSecondNotPacked = 0b11110000, + kFirstCharIsLiteral = 0b00000001, + kSecondCharIsLiteral = 0b00000010; + + static const uint8_t kSpaceCharIdx = 11; + static const char kSpaceCharReplace = 'E'; + + bool cmd_is_next; // A command is pending + uint8_t state; // Configuration state + uint8_t second_char; // Buffers a character if dealing with out-of-sequence pairs + uint8_t cmd_count, // Counter of command bytes received (need 2) + full_char_count, // Counter for full-width characters to be received + char_out_count; // Stores number of characters to be read out. + uint8_t char_out_buf[2]; // Output buffer for caching up to 2 characters + +public: + // Pass in a character rx'd by SD card or serial. Automatically parses command/ctrl sequences, + // and will control state internally. + void handle_rx_char(const uint8_t c, const serial_index_t serial_ind); + + /** + * After passing in rx'd char using above method, call this to get characters out. + * Can return from 0 to 2 characters at once. + * @param out [in] Output pointer for unpacked/processed data. + * @return Number of characters returned. Range from 0 to 2. + */ + uint8_t get_result_char(char * const __restrict out); + + void reset_state(); + void report_state(); + uint8_t unpack_chars(const uint8_t pk, uint8_t* __restrict const chars_out); + void handle_command(const MeatPack_Command c); + void handle_output_char(const uint8_t c); + void handle_rx_char_inner(const uint8_t c); + + MeatPack() : cmd_is_next(false), state(0), second_char(0), cmd_count(0), full_char_count(0), char_out_count(0) {} +}; + +// Implement the MeatPack serial class so it's transparent to rest of the code +template +struct MeatpackSerial : public SerialBase > { + typedef SerialBase< MeatpackSerial > BaseClassT; + + SerialT & out; + MeatPack meatpack; + + char serialBuffer[2]; + uint8_t charCount; + uint8_t readIndex; + + NO_INLINE void write(uint8_t c) { out.write(c); } + void flush() { out.flush(); } + void begin(long br) { out.begin(br); readIndex = 0; } + void end() { out.end(); } + + void msgDone() { out.msgDone(); } + // Existing instances implement Arduino's operator bool, so use that if it's available + bool connected() { return Private::HasMember_connected::value ? CALL_IF_EXISTS(bool, &out, connected) : (bool)out; } + 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 + + // Don't read in read method, instead do it here, so we can make progress in the read method + const int r = out.read(index); + if (r == -1) return 0; // This is an error from the underlying serial code + meatpack.handle_rx_char((uint8_t)r, index); + charCount = meatpack.get_result_char(serialBuffer); + readIndex = 0; + + return charCount; + } + + int readImpl(const serial_index_t index) { + // Not enough char to make progress? + if (charCount == 0 && available(index) == 0) return -1; + + charCount--; + return serialBuffer[readIndex++]; + } + + int read(serial_index_t index) { return readImpl(index); } + int available() { return available(0); } + int read() { return readImpl(0); } + + MeatpackSerial(const bool e, SerialT & out) : BaseClassT(e), out(out) {} +}; diff --git a/Marlin/src/feature/mixing.cpp b/Marlin/src/feature/mixing.cpp index b002e9808adc..4823ac2c608b 100644 --- a/Marlin/src/feature/mixing.cpp +++ b/Marlin/src/feature/mixing.cpp @@ -135,11 +135,11 @@ void Mixer::refresh_collector(const float proportion/*=1.0*/, const uint8_t t/*= cmax = _MAX(cmax, v); csum += v; } - //SERIAL_ECHOPAIR("Mixer::refresh_collector(", proportion, ", ", int(t), ") cmax=", cmax, " csum=", csum, " color"); + //SERIAL_ECHOPAIR("Mixer::refresh_collector(", proportion, ", ", t, ") cmax=", cmax, " csum=", csum, " color"); const float inv_prop = proportion / csum; MIXER_STEPPER_LOOP(i) { c[i] = color[t][i] * inv_prop; - //SERIAL_ECHOPAIR(" [", int(t), "][", int(i), "] = ", int(color[t][i]), " (", c[i], ") "); + //SERIAL_ECHOPAIR(" [", t, "][", i, "] = ", color[t][i], " (", c[i], ") "); } //SERIAL_EOL(); } @@ -162,7 +162,7 @@ void Mixer::refresh_collector(const float proportion/*=1.0*/, const uint8_t t/*= float Mixer::prev_z; // = 0 - void Mixer::update_gradient_for_z(const float z) { + void Mixer::update_gradient_for_z(const_float_t z) { if (z == prev_z) return; prev_z = z; diff --git a/Marlin/src/feature/mixing.h b/Marlin/src/feature/mixing.h index 7fe7062a7a52..573b61cb68f0 100644 --- a/Marlin/src/feature/mixing.h +++ b/Marlin/src/feature/mixing.h @@ -61,9 +61,6 @@ enum MixTool { #define MAX_VTOOLS TERN(HAS_MIXER_SYNC_CHANNEL, 254, 255) static_assert(NR_MIXING_VIRTUAL_TOOLS <= MAX_VTOOLS, "MIXING_VIRTUAL_TOOLS must be <= " STRINGIFY(MAX_VTOOLS) "!"); -#define MIXER_BLOCK_FIELD mixer_comp_t b_color[MIXING_STEPPERS] -#define MIXER_POPULATE_BLOCK() mixer.populate_block(block->b_color) -#define MIXER_STEPPER_SETUP() mixer.stepper_setup(current_block->b_color) #define MIXER_STEPPER_LOOP(VAR) for (uint_fast8_t VAR = 0; VAR < MIXING_STEPPERS; VAR++) #if ENABLED(GRADIENT_MIX) @@ -73,9 +70,11 @@ static_assert(NR_MIXING_VIRTUAL_TOOLS <= MAX_VTOOLS, "MIXING_VIRTUAL_TOOLS must mixer_comp_t color[MIXING_STEPPERS]; // The current gradient color float start_z, end_z; // Region for gradient int8_t start_vtool, end_vtool; // Start and end virtual tools - mixer_perc_t start_mix[MIXING_STEPPERS], // Start and end mixes from those tools + mixer_perc_t start_mix[MIXING_STEPPERS], // Start and end mixes from those tools end_mix[MIXING_STEPPERS]; - TERN_(GRADIENT_VTOOL, int8_t vtool_index); // Use this virtual tool number as index + #if ENABLED(GRADIENT_VTOOL) + int8_t vtool_index; // Use this virtual tool number as index + #endif } gradient_t; #endif @@ -139,9 +138,9 @@ class Mixer { #ifdef MIXER_NORMALIZER_DEBUG SERIAL_ECHOPGM("Mix [ "); - SERIAL_ECHOLIST_N(MIXING_STEPPERS, int(mix[0]), int(mix[1]), int(mix[2]), int(mix[3]), int(mix[4]), int(mix[5])); + SERIAL_ECHOLIST_N(MIXING_STEPPERS, mix[0], mix[1], mix[2], mix[3], mix[4], mix[5]); SERIAL_ECHOPGM(" ] to Color [ "); - SERIAL_ECHOLIST_N(MIXING_STEPPERS, int(tcolor[0]), int(tcolor[1]), int(tcolor[2]), int(tcolor[3]), int(tcolor[4]), int(tcolor[5])); + SERIAL_ECHOLIST_N(MIXING_STEPPERS, tcolor[0], tcolor[1], tcolor[2], tcolor[3], tcolor[4], tcolor[5]); SERIAL_ECHOLNPGM(" ]"); #endif } @@ -153,10 +152,10 @@ class Mixer { MIXER_STEPPER_LOOP(i) mix[i] = mixer_perc_t(100.0f * color[j][i] / ctot); #ifdef MIXER_NORMALIZER_DEBUG - SERIAL_ECHOPAIR("V-tool ", int(j), " [ "); - SERIAL_ECHOLIST_N(MIXING_STEPPERS, int(color[j][0]), int(color[j][1]), int(color[j][2]), int(color[j][3]), int(color[j][4]), int(color[j][5])); + SERIAL_ECHOPAIR("V-tool ", j, " [ "); + SERIAL_ECHOLIST_N(MIXING_STEPPERS, color[j][0], color[j][1], color[j][2], color[j][3], color[j][4], color[j][5]); SERIAL_ECHOPGM(" ] to Mix [ "); - SERIAL_ECHOLIST_N(MIXING_STEPPERS, int(mix[0]), int(mix[1]), int(mix[2]), int(mix[3]), int(mix[4]), int(mix[5])); + SERIAL_ECHOLIST_N(MIXING_STEPPERS, mix[0], mix[1], mix[2], mix[3], mix[4], mix[5]); SERIAL_ECHOLNPGM(" ]"); #endif } @@ -181,9 +180,9 @@ class Mixer { static float prev_z; // Update the current mix from the gradient for a given Z - static void update_gradient_for_z(const float z); + static void update_gradient_for_z(const_float_t z); static void update_gradient_for_planner_z(); - static inline void gradient_control(const float z) { + static inline void gradient_control(const_float_t z) { if (gradient.enabled) { if (z >= gradient.end_z) T(gradient.end_vtool); @@ -199,9 +198,9 @@ class Mixer { #ifdef MIXER_NORMALIZER_DEBUG SERIAL_ECHOPGM("Gradient [ "); - SERIAL_ECHOLIST_N(MIXING_STEPPERS, int(gradient.color[0]), int(gradient.color[1]), int(gradient.color[2]), int(gradient.color[3]), int(gradient.color[4]), int(gradient.color[5])); + SERIAL_ECHOLIST_N(MIXING_STEPPERS, gradient.color[0], gradient.color[1], gradient.color[2], gradient.color[3], gradient.color[4], gradient.color[5]); SERIAL_ECHOPGM(" ] to Mix [ "); - SERIAL_ECHOLIST_N(MIXING_STEPPERS, int(mix[0]), int(mix[1]), int(mix[2]), int(mix[3]), int(mix[4]), int(mix[5])); + SERIAL_ECHOLIST_N(MIXING_STEPPERS, mix[0], mix[1], mix[2], mix[3], mix[4], mix[5]); SERIAL_ECHOLNPGM(" ]"); #endif } diff --git a/Marlin/src/feature/mmu/mmu.cpp b/Marlin/src/feature/mmu/mmu.cpp new file mode 100644 index 000000000000..718972313844 --- /dev/null +++ b/Marlin/src/feature/mmu/mmu.cpp @@ -0,0 +1,45 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../inc/MarlinConfig.h" + +#if HAS_PRUSA_MMU1 + +#include "../MarlinCore.h" +#include "../module/planner.h" + +void mmu_init() { + SET_OUTPUT(E_MUX0_PIN); + SET_OUTPUT(E_MUX1_PIN); + SET_OUTPUT(E_MUX2_PIN); +} + +void select_multiplexed_stepper(const uint8_t e) { + planner.synchronize(); + disable_e_steppers(); + WRITE(E_MUX0_PIN, TEST(e, 0) ? HIGH : LOW); + WRITE(E_MUX1_PIN, TEST(e, 1) ? HIGH : LOW); + WRITE(E_MUX2_PIN, TEST(e, 2) ? HIGH : LOW); + safe_delay(100); +} + +#endif // HAS_PRUSA_MMU1 diff --git a/Marlin/src/feature/mmu/mmu.h b/Marlin/src/feature/mmu/mmu.h new file mode 100644 index 000000000000..23742d00c61e --- /dev/null +++ b/Marlin/src/feature/mmu/mmu.h @@ -0,0 +1,25 @@ +/** + * 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 + +void mmu_init(); +void select_multiplexed_stepper(const uint8_t e); diff --git a/Marlin/src/feature/mmu/mmu2-serial-protocol.md b/Marlin/src/feature/mmu/mmu2-serial-protocol.md new file mode 100644 index 000000000000..7ff0901742af --- /dev/null +++ b/Marlin/src/feature/mmu/mmu2-serial-protocol.md @@ -0,0 +1,94 @@ +Startup sequence +================ + +When initialized, MMU sends + +- MMU => 'start\n' + +We follow with + +- MMU <= 'S1\n' +- MMU => 'ok*Firmware version*\n' +- MMU <= 'S2\n' +- MMU => 'ok*Build number*\n' + +#if (12V_mode) + +- MMU <= 'M1\n' +- MMU => 'ok\n' + +#endif + +- MMU <= 'P0\n' +- MMU => '*FINDA status*\n' + +Now we are sure MMU is available and ready. If there was a timeout or other communication problem somewhere, printer will be killed. + +- *Firmware version* is an integer value, but we don't care about it +- *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 +========== + +- MMU <= 'T*Filament index*\n' + +MMU sends + +- MMU => 'ok\n' + +as soon as the filament is fed down to the extruder. We follow with + +- MMU <= 'C0\n' + +MMU will feed a few more millimeters of filament for the extruder gears to grab. +When done, the MMU sends + +- MMU => 'ok\n' + +We don't wait for a response here but immediately continue with the next gcode which should +be one or more extruder moves to feed the filament into the hotend. + + +FINDA status +============ + +- MMU <= 'P0\n' +- MMU => '*FINDA status*\n' + +*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 +============= + +- MMU <= 'L*Filament index*\n' + +MMU will feed filament down to the extruder, when done + +- MMU => 'ok\n' + + +Unload filament +============= + +- MMU <= 'U0\n' + +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 new file mode 100644 index 000000000000..1acd26f331c3 --- /dev/null +++ b/Marlin/src/feature/mmu/mmu2.cpp @@ -0,0 +1,1040 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../inc/MarlinConfig.h" + +#if HAS_PRUSA_MMU2 + +#include "mmu2.h" +#include "../../lcd/menu/menu_mmu2.h" + +MMU2 mmu2; + +#include "../../gcode/gcode.h" +#include "../../lcd/marlinui.h" +#include "../../libs/buzzer.h" +#include "../../libs/nozzle.h" +#include "../../module/temperature.h" +#include "../../module/planner.h" +#include "../../module/stepper/indirection.h" +#include "../../MarlinCore.h" + +#if ENABLED(HOST_PROMPT_SUPPORT) + #include "../../feature/host_actions.h" +#endif + +#if ENABLED(EXTENSIBLE_UI) + #include "../../lcd/extui/ui_api.h" +#endif + +#define DEBUG_OUT ENABLED(MMU2_DEBUG) +#include "../../core/debug_out.h" + +#define MMU_TODELAY 100 +#define MMU_TIMEOUT 10 +#define MMU_CMD_TIMEOUT 45000UL // 45s timeout for mmu commands (except P0) +#define MMU_P0_TIMEOUT 3000UL // Timeout for P0 command: 3seconds + +#define MMU2_COMMAND(S) tx_str_P(PSTR(S "\n")) + +#if ENABLED(MMU_EXTRUDER_SENSOR) + uint8_t mmu_idl_sens = 0; + static bool mmu_loading_flag = false; +#endif + +#define MMU_CMD_NONE 0 +#define MMU_CMD_T0 0x10 // up to supported filaments +#define MMU_CMD_L0 0x20 // up to supported filaments +#define MMU_CMD_C0 0x30 +#define MMU_CMD_U0 0x40 +#define MMU_CMD_E0 0x50 // up to supported filaments +#define MMU_CMD_R0 0x60 +#define MMU_CMD_F0 0x70 // up to supported filaments + +#define MMU_REQUIRED_FW_BUILDNR TERN(MMU2_MODE_12V, 132, 126) + +#define MMU2_NO_TOOL 99 +#define MMU_BAUD 115200 + +bool MMU2::_enabled, MMU2::ready, MMU2::mmu_print_saved; +#if HAS_PRUSA_MMU2S + bool MMU2::mmu2s_triggered; +#endif +uint8_t MMU2::cmd, MMU2::cmd_arg, MMU2::last_cmd, MMU2::extruder; +int8_t MMU2::state = 0; +volatile int8_t MMU2::finda = 1; +volatile bool MMU2::finda_runout_valid; +int16_t MMU2::version = -1, MMU2::buildnr = -1; +millis_t MMU2::prev_request, MMU2::prev_P0_request; +char MMU2::rx_buffer[MMU_RX_SIZE], MMU2::tx_buffer[MMU_TX_SIZE]; + +struct E_Step { + float extrude; //!< extrude distance in mm + feedRate_t feedRate; //!< feed rate in mm/s +}; + +static constexpr E_Step + ramming_sequence[] PROGMEM = { MMU2_RAMMING_SEQUENCE } + , load_to_nozzle_sequence[] PROGMEM = { MMU2_LOAD_TO_NOZZLE_SEQUENCE } + #if HAS_PRUSA_MMU2S + , can_load_sequence[] PROGMEM = { MMU2_CAN_LOAD_SEQUENCE } + , can_load_increment_sequence[] PROGMEM = { MMU2_CAN_LOAD_INCREMENT_SEQUENCE } + #endif +; + +MMU2::MMU2() { + rx_buffer[0] = '\0'; +} + +void MMU2::init() { + + set_runout_valid(false); + + #if PIN_EXISTS(MMU2_RST) + WRITE(MMU2_RST_PIN, HIGH); + SET_OUTPUT(MMU2_RST_PIN); + #endif + + MMU2_SERIAL.begin(MMU_BAUD); + extruder = MMU2_NO_TOOL; + + safe_delay(10); + reset(); + rx_buffer[0] = '\0'; + state = -1; +} + +void MMU2::reset() { + DEBUG_ECHOLNPGM("MMU <= reset"); + + #if PIN_EXISTS(MMU2_RST) + WRITE(MMU2_RST_PIN, LOW); + safe_delay(20); + WRITE(MMU2_RST_PIN, HIGH); + #else + MMU2_COMMAND("X0"); // Send soft reset + #endif +} + +uint8_t MMU2::get_current_tool() { + return extruder == MMU2_NO_TOOL ? -1 : extruder; +} + +#if EITHER(HAS_PRUSA_MMU2S, MMU_EXTRUDER_SENSOR) + #define FILAMENT_PRESENT() (READ(FIL_RUNOUT1_PIN) != FIL_RUNOUT1_STATE) +#endif + +void MMU2::mmu_loop() { + + switch (state) { + + case 0: break; + + case -1: + if (rx_start()) { + prev_P0_request = millis(); // Initialize finda sensor timeout + + DEBUG_ECHOLNPGM("MMU => 'start'"); + DEBUG_ECHOLNPGM("MMU <= 'S1'"); + + MMU2_COMMAND("S1"); // Read Version + state = -2; + } + else if (millis() > 30000) { // 30sec after reset disable MMU + SERIAL_ECHOLNPGM("MMU not responding - DISABLED"); + state = 0; + } + break; + + case -2: + if (rx_ok()) { + sscanf(rx_buffer, "%huok\n", &version); + + DEBUG_ECHOLNPAIR("MMU => ", version, "\nMMU <= 'S2'"); + + MMU2_COMMAND("S2"); // Read Build Number + state = -3; + } + break; + + case -3: + if (rx_ok()) { + sscanf(rx_buffer, "%huok\n", &buildnr); + + DEBUG_ECHOLNPAIR("MMU => ", buildnr); + + check_version(); + + #if ENABLED(MMU2_MODE_12V) + DEBUG_ECHOLNPGM("MMU <= 'M1'"); + + MMU2_COMMAND("M1"); // Stealth Mode + state = -5; + + #else + DEBUG_ECHOLNPGM("MMU <= 'P0'"); + + MMU2_COMMAND("P0"); // Read FINDA + state = -4; + #endif + } + break; + + #if ENABLED(MMU2_MODE_12V) + case -5: + // response to M1 + if (rx_ok()) { + DEBUG_ECHOLNPGM("MMU => ok"); + + DEBUG_ECHOLNPGM("MMU <= 'P0'"); + + MMU2_COMMAND("P0"); // Read FINDA + state = -4; + } + break; + #endif + + case -4: + if (rx_ok()) { + sscanf(rx_buffer, "%hhuok\n", &finda); + + DEBUG_ECHOLNPAIR("MMU => ", finda, "\nMMU - ENABLED"); + + _enabled = true; + state = 1; + TERN_(HAS_PRUSA_MMU2S, mmu2s_triggered = false); + } + break; + + case 1: + if (cmd) { + if (WITHIN(cmd, MMU_CMD_T0, MMU_CMD_T0 + EXTRUDERS - 1)) { + // tool change + int filament = cmd - MMU_CMD_T0; + DEBUG_ECHOLNPAIR("MMU <= T", filament); + tx_printf_P(PSTR("T%d\n"), filament); + TERN_(MMU_EXTRUDER_SENSOR, mmu_idl_sens = 1); // enable idler sensor, if any + state = 3; // wait for response + } + else if (WITHIN(cmd, MMU_CMD_L0, MMU_CMD_L0 + EXTRUDERS - 1)) { + // load + int filament = cmd - MMU_CMD_L0; + DEBUG_ECHOLNPAIR("MMU <= L", filament); + tx_printf_P(PSTR("L%d\n"), filament); + state = 3; // wait for response + } + else if (cmd == MMU_CMD_C0) { + // continue loading + DEBUG_ECHOLNPGM("MMU <= 'C0'"); + MMU2_COMMAND("C0"); + state = 3; // wait for response + } + else if (cmd == MMU_CMD_U0) { + // unload current + DEBUG_ECHOLNPGM("MMU <= 'U0'"); + + MMU2_COMMAND("U0"); + state = 3; // wait for response + } + else if (WITHIN(cmd, MMU_CMD_E0, MMU_CMD_E0 + EXTRUDERS - 1)) { + // eject filament + int filament = cmd - MMU_CMD_E0; + DEBUG_ECHOLNPAIR("MMU <= E", filament); + tx_printf_P(PSTR("E%d\n"), filament); + state = 3; // wait for response + } + else if (cmd == MMU_CMD_R0) { + // recover after eject + DEBUG_ECHOLNPGM("MMU <= 'R0'"); + MMU2_COMMAND("R0"); + state = 3; // wait for response + } + else if (WITHIN(cmd, MMU_CMD_F0, MMU_CMD_F0 + EXTRUDERS - 1)) { + // filament type + int filament = cmd - MMU_CMD_F0; + DEBUG_ECHOLNPAIR("MMU <= F", filament, " ", cmd_arg); + tx_printf_P(PSTR("F%d %d\n"), filament, cmd_arg); + state = 3; // wait for response + } + + last_cmd = cmd; + cmd = MMU_CMD_NONE; + } + else if (ELAPSED(millis(), prev_P0_request + 300)) { + MMU2_COMMAND("P0"); // Read FINDA + state = 2; // wait for response + } + + TERN_(HAS_PRUSA_MMU2S, check_filament()); + break; + + case 2: // response to command P0 + if (rx_ok()) { + sscanf(rx_buffer, "%hhuok\n", &finda); + + // This is super annoying. Only activate if necessary + // if (finda_runout_valid) DEBUG_ECHOLNPAIR_F("MMU <= 'P0'\nMMU => ", finda, 6); + + if (!finda && finda_runout_valid) filament_runout(); + if (cmd == MMU_CMD_NONE) ready = true; + state = 1; + } + else if (ELAPSED(millis(), prev_request + MMU_P0_TIMEOUT)) // Resend request after timeout (3s) + state = 1; + + TERN_(HAS_PRUSA_MMU2S, check_filament()); + break; + + case 3: // response to mmu commands + #if ENABLED(MMU_EXTRUDER_SENSOR) + if (mmu_idl_sens) { + if (FILAMENT_PRESENT() && mmu_loading_flag) { + DEBUG_ECHOLNPGM("MMU <= 'A'"); + MMU2_COMMAND("A"); // send 'abort' request + mmu_idl_sens = 0; + DEBUG_ECHOLNPGM("MMU IDLER_SENSOR = 0 - ABORT"); + } + } + #endif + + if (rx_ok()) { + #if HAS_PRUSA_MMU2S + // Respond to C0 MMU command in MMU2S model + const bool keep_trying = !mmu2s_triggered && last_cmd == MMU_CMD_C0; + if (keep_trying) { + // MMU ok received but filament sensor not triggered, retrying... + DEBUG_ECHOLNPGM("MMU => 'ok' (filament not present in gears)"); + DEBUG_ECHOLNPGM("MMU <= 'C0' (keep trying)"); + MMU2_COMMAND("C0"); + } + #else + constexpr bool keep_trying = false; + #endif + + if (!keep_trying) { + DEBUG_ECHOLNPGM("MMU => 'ok'"); + ready = true; + state = 1; + last_cmd = MMU_CMD_NONE; + } + } + else if (ELAPSED(millis(), prev_request + MMU_CMD_TIMEOUT)) { + // resend request after timeout + if (last_cmd) { + DEBUG_ECHOLNPGM("MMU retry"); + cmd = last_cmd; + last_cmd = MMU_CMD_NONE; + } + state = 1; + } + TERN_(HAS_PRUSA_MMU2S, check_filament()); + break; + } +} + +/** + * Check if MMU was started + */ +bool MMU2::rx_start() { + // check for start message + return rx_str_P(PSTR("start\n")); +} + +/** + * Check if the data received ends with the given string. + */ +bool MMU2::rx_str_P(const char *str) { + uint8_t i = strlen(rx_buffer); + + while (MMU2_SERIAL.available()) { + rx_buffer[i++] = MMU2_SERIAL.read(); + + if (i == sizeof(rx_buffer) - 1) { + DEBUG_ECHOLNPGM("rx buffer overrun"); + break; + } + } + rx_buffer[i] = '\0'; + + uint8_t len = strlen_P(str); + + if (i < len) return false; + + str += len; + + while (len--) { + char c0 = pgm_read_byte(str--), c1 = rx_buffer[i--]; + if (c0 == c1) continue; + if (c0 == '\r' && c1 == '\n') continue; // match cr as lf + if (c0 == '\n' && c1 == '\r') continue; // match lf as cr + return false; + } + return true; +} + +/** + * Transfer data to MMU, no argument + */ +void MMU2::tx_str_P(const char *str) { + clear_rx_buffer(); + uint8_t len = strlen_P(str); + LOOP_L_N(i, len) MMU2_SERIAL.write(pgm_read_byte(str++)); + prev_request = millis(); +} + +/** + * Transfer data to MMU, single argument + */ +void MMU2::tx_printf_P(const char *format, int argument = -1) { + clear_rx_buffer(); + uint8_t len = sprintf_P(tx_buffer, format, argument); + LOOP_L_N(i, len) MMU2_SERIAL.write(tx_buffer[i]); + prev_request = millis(); +} + +/** + * Transfer data to MMU, two arguments + */ +void MMU2::tx_printf_P(const char *format, int argument1, int argument2) { + clear_rx_buffer(); + uint8_t len = sprintf_P(tx_buffer, format, argument1, argument2); + LOOP_L_N(i, len) MMU2_SERIAL.write(tx_buffer[i]); + prev_request = millis(); +} + +/** + * Empty the rx buffer + */ +void MMU2::clear_rx_buffer() { + while (MMU2_SERIAL.available()) MMU2_SERIAL.read(); + rx_buffer[0] = '\0'; +} + +/** + * Check if we received 'ok' from MMU + */ +bool MMU2::rx_ok() { + if (rx_str_P(PSTR("ok\n"))) { + prev_P0_request = millis(); + return true; + } + return false; +} + +/** + * Check if MMU has compatible firmware + */ +void MMU2::check_version() { + if (buildnr < MMU_REQUIRED_FW_BUILDNR) { + SERIAL_ERROR_MSG("Invalid MMU2 firmware. Version >= " STRINGIFY(MMU_REQUIRED_FW_BUILDNR) " required."); + kill(GET_TEXT(MSG_KILL_MMU2_FIRMWARE)); + } +} + +static void mmu2_not_responding() { + LCD_MESSAGEPGM(MSG_MMU2_NOT_RESPONDING); + BUZZ(100, 659); + BUZZ(200, 698); + BUZZ(100, 659); + BUZZ(300, 440); + BUZZ(100, 659); +} + +#if HAS_PRUSA_MMU2S + + 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 + if (mmu2s_triggered) break; + command(MMU_CMD_C0); + manage_response(true, true); + check_filament(); + } + const bool success = mmu2s_triggered && can_load(); + if (!success) mmu2_not_responding(); + return success; + } + + /** + * Handle tool change + */ + void MMU2::tool_change(const uint8_t index) { + + if (!_enabled) return; + + set_runout_valid(false); + + if (index != extruder) { + + DISABLE_AXIS_E0(); + ui.status_printf_P(0, GET_TEXT(MSG_MMU2_LOADING_FILAMENT), int(index + 1)); + + command(MMU_CMD_T0 + index); + manage_response(true, true); + + if (load_to_gears()) { + extruder = index; // filament change is finished + active_extruder = 0; + ENABLE_AXIS_E0(); + SERIAL_ECHO_MSG(STR_ACTIVE_EXTRUDER, extruder); + } + ui.reset_status(); + } + + set_runout_valid(true); + } + + /** + * Handle special T?/Tx/Tc commands + * + * T? Gcode to extrude shouldn't have to follow, load to extruder wheels is done automatically + * Tx Same as T?, except nozzle doesn't have to be preheated. Tc must be placed after extruder nozzle is preheated to finish filament load. + * Tc Load to nozzle after filament was prepared by Tx and extruder nozzle is already heated. + */ + void MMU2::tool_change(const char *special) { + if (!_enabled) return; + + set_runout_valid(false); + + switch (*special) { + case '?': { + #if ENABLED(MMU2_MENUS) + const uint8_t index = mmu2_choose_filament(); + while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100); + load_filament_to_nozzle(index); + #else + BUZZ(400, 40); + #endif + } break; + + case 'x': { + #if ENABLED(MMU2_MENUS) + planner.synchronize(); + const uint8_t index = mmu2_choose_filament(); + DISABLE_AXIS_E0(); + command(MMU_CMD_T0 + index); + manage_response(true, true); + + if (load_to_gears()) { + mmu_loop(); + ENABLE_AXIS_E0(); + extruder = index; + active_extruder = 0; + } + #else + BUZZ(400, 40); + #endif + } break; + + case 'c': { + while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100); + load_to_nozzle(); + } break; + } + + set_runout_valid(true); + } + +#elif ENABLED(MMU_EXTRUDER_SENSOR) + + /** + * Handle tool change + */ + void MMU2::tool_change(const uint8_t index) { + if (!_enabled) return; + + set_runout_valid(false); + + if (index != extruder) { + DISABLE_AXIS_E0(); + if (FILAMENT_PRESENT()) { + DEBUG_ECHOLNPGM("Unloading\n"); + mmu_loading_flag = false; + command(MMU_CMD_U0); + manage_response(true, true); + } + ui.status_printf_P(0, GET_TEXT(MSG_MMU2_LOADING_FILAMENT), int(index + 1)); + mmu_loading_flag = true; + command(MMU_CMD_T0 + index); + manage_response(true, true); + mmu_continue_loading(); + command(MMU_CMD_C0); + extruder = index; + active_extruder = 0; + + ENABLE_AXIS_E0(); + SERIAL_ECHO_MSG(STR_ACTIVE_EXTRUDER, extruder); + + ui.reset_status(); + } + + set_runout_valid(true); + } + + /** + * Handle special T?/Tx/Tc commands + * + * T? Gcode to extrude shouldn't have to follow, load to extruder wheels is done automatically + * Tx Same as T?, except nozzle doesn't have to be preheated. Tc must be placed after extruder nozzle is preheated to finish filament load. + * Tc Load to nozzle after filament was prepared by Tx and extruder nozzle is already heated. + */ + void MMU2::tool_change(const char *special) { + if (!_enabled) return; + + set_runout_valid(false); + + switch (*special) { + case '?': { + DEBUG_ECHOLNPGM("case ?\n"); + #if ENABLED(MMU2_MENUS) + uint8_t index = mmu2_choose_filament(); + while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100); + load_filament_to_nozzle(index); + #else + BUZZ(400, 40); + #endif + } break; + + case 'x': { + DEBUG_ECHOLNPGM("case x\n"); + #if ENABLED(MMU2_MENUS) + planner.synchronize(); + uint8_t index = mmu2_choose_filament(); + DISABLE_AXIS_E0(); + command(MMU_CMD_T0 + index); + manage_response(true, true); + mmu_continue_loading(); + command(MMU_CMD_C0); + mmu_loop(); + + ENABLE_AXIS_E0(); + extruder = index; + active_extruder = 0; + #else + BUZZ(400, 40); + #endif + } break; + + case 'c': { + DEBUG_ECHOLNPGM("case c\n"); + while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100); + execute_extruder_sequence((const E_Step *)load_to_nozzle_sequence, COUNT(load_to_nozzle_sequence)); + } break; + } + + set_runout_valid(true); + } + + void MMU2::mmu_continue_loading() { + for (uint8_t i = 0; i < MMU_LOADING_ATTEMPTS_NR; i++) { + DEBUG_ECHOLNPAIR("Additional load attempt #", i); + if (FILAMENT_PRESENT()) break; + command(MMU_CMD_C0); + manage_response(true, true); + } + if (!FILAMENT_PRESENT()) { + DEBUG_ECHOLNPGM("Filament never reached sensor, runout"); + filament_runout(); + } + mmu_idl_sens = 0; + } + +#else // !HAS_PRUSA_MMU2S && !MMU_EXTRUDER_SENSOR + + /** + * Handle tool change + */ + void MMU2::tool_change(const uint8_t index) { + if (!_enabled) return; + + set_runout_valid(false); + + if (index != extruder) { + DISABLE_AXIS_E0(); + ui.status_printf_P(0, GET_TEXT(MSG_MMU2_LOADING_FILAMENT), int(index + 1)); + command(MMU_CMD_T0 + index); + manage_response(true, true); + command(MMU_CMD_C0); + extruder = index; //filament change is finished + active_extruder = 0; + ENABLE_AXIS_E0(); + SERIAL_ECHO_MSG(STR_ACTIVE_EXTRUDER, extruder); + ui.reset_status(); + } + + set_runout_valid(true); + } + + /** + * Handle special T?/Tx/Tc commands + * + * T? Gcode to extrude shouldn't have to follow, load to extruder wheels is done automatically + * Tx Same as T?, except nozzle doesn't have to be preheated. Tc must be placed after extruder nozzle is preheated to finish filament load. + * Tc Load to nozzle after filament was prepared by Tx and extruder nozzle is already heated. + */ + void MMU2::tool_change(const char *special) { + if (!_enabled) return; + + set_runout_valid(false); + + switch (*special) { + case '?': { + DEBUG_ECHOLNPGM("case ?\n"); + #if ENABLED(MMU2_MENUS) + uint8_t index = mmu2_choose_filament(); + while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100); + load_filament_to_nozzle(index); + #else + BUZZ(400, 40); + #endif + } break; + + case 'x': { + DEBUG_ECHOLNPGM("case x\n"); + #if ENABLED(MMU2_MENUS) + planner.synchronize(); + uint8_t index = mmu2_choose_filament(); + DISABLE_AXIS_E0(); + command(MMU_CMD_T0 + index); + manage_response(true, true); + command(MMU_CMD_C0); + mmu_loop(); + + ENABLE_AXIS_E0(); + extruder = index; + active_extruder = 0; + #else + BUZZ(400, 40); + #endif + } break; + + case 'c': { + DEBUG_ECHOLNPGM("case c\n"); + while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100); + execute_extruder_sequence((const E_Step *)load_to_nozzle_sequence, COUNT(load_to_nozzle_sequence)); + } break; + } + + set_runout_valid(true); + } + +#endif // HAS_PRUSA_MMU2S + +/** + * Set next command + */ +void MMU2::command(const uint8_t mmu_cmd) { + if (!_enabled) return; + cmd = mmu_cmd; + ready = false; +} + +/** + * Wait for response from MMU + */ +bool MMU2::get_response() { + while (cmd != MMU_CMD_NONE) idle(); + + while (!ready) { + idle(); + if (state != 3) break; + } + + const bool ret = ready; + ready = false; + + return ret; +} + +/** + * Wait for response and deal with timeout if necessary + */ +void MMU2::manage_response(const bool move_axes, const bool turn_off_nozzle) { + + constexpr xyz_pos_t park_point = NOZZLE_PARK_POINT; + bool response = false; + mmu_print_saved = false; + xyz_pos_t resume_position; + celsius_t resume_hotend_temp = thermalManager.degTargetHotend(active_extruder); + + KEEPALIVE_STATE(PAUSED_FOR_USER); + + while (!response) { + + response = get_response(); // wait for "ok" from mmu + + if (!response) { // No "ok" was received in reserved time frame, user will fix the issue on mmu unit + if (!mmu_print_saved) { // First occurrence. Save current position, park print head, disable nozzle heater. + + planner.synchronize(); + + mmu_print_saved = true; + + SERIAL_ECHOLNPGM("MMU not responding"); + + resume_hotend_temp = thermalManager.degTargetHotend(active_extruder); + resume_position = current_position; + + if (move_axes && all_axes_homed()) + nozzle.park(0, park_point /*= NOZZLE_PARK_POINT*/); + + if (turn_off_nozzle) thermalManager.setTargetHotend(0, active_extruder); + + mmu2_not_responding(); + } + } + else if (mmu_print_saved) { + SERIAL_ECHOLNPGM("MMU starts responding\n"); + + if (turn_off_nozzle && resume_hotend_temp) { + thermalManager.setTargetHotend(resume_hotend_temp, active_extruder); + LCD_MESSAGEPGM(MSG_HEATING); + BUZZ(200, 40); + + while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(1000); + } + + if (move_axes && all_axes_homed()) { + LCD_MESSAGEPGM(MSG_MMU2_RESUMING); + BUZZ(198, 404); BUZZ(4, 0); BUZZ(198, 404); + + // Move XY to starting position, then Z + do_blocking_move_to_xy(resume_position, feedRate_t(NOZZLE_PARK_XY_FEEDRATE)); + + // Move Z_AXIS to saved position + do_blocking_move_to_z(resume_position.z, feedRate_t(NOZZLE_PARK_Z_FEEDRATE)); + } + else { + BUZZ(198, 404); BUZZ(4, 0); BUZZ(198, 404); + LCD_MESSAGEPGM(MSG_MMU2_RESUMING); + } + } + } +} + +void MMU2::set_filament_type(const uint8_t index, const uint8_t filamentType) { + if (!_enabled) return; + + cmd_arg = filamentType; + command(MMU_CMD_F0 + index); + + manage_response(true, true); +} + +void MMU2::filament_runout() { + queue.inject_P(PSTR(MMU2_FILAMENT_RUNOUT_SCRIPT)); + planner.synchronize(); +} + +#if HAS_PRUSA_MMU2S + + void MMU2::check_filament() { + const bool present = FILAMENT_PRESENT(); + if (cmd == MMU_CMD_NONE && last_cmd == MMU_CMD_C0) { + if (present && !mmu2s_triggered) { + DEBUG_ECHOLNPGM("MMU <= 'A'"); + tx_str_P(PSTR("A\n")); + } + // Slowly spin the extruder during C0 + else { + while (planner.movesplanned() < 3) { + current_position.e += 0.25; + line_to_current_position(MMM_TO_MMS(120)); + } + } + } + mmu2s_triggered = present; + } + + bool MMU2::can_load() { + execute_extruder_sequence((const E_Step *)can_load_sequence, COUNT(can_load_sequence)); + + 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) { + 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'); + if (mmu2s_triggered) ++filament_detected_count; + } + + if (filament_detected_count <= steps - (MMU2_CAN_LOAD_DEVIATION) / (MMU2_CAN_LOAD_INCREMENT)) { + DEBUG_ECHOLNPGM(" failed."); + return false; + } + + DEBUG_ECHOLNPGM(" succeeded."); + return true; + } + +#endif + +// Load filament into MMU2 +void MMU2::load_filament(const uint8_t index) { + if (!_enabled) return; + + command(MMU_CMD_L0 + index); + manage_response(false, false); + BUZZ(200, 404); +} + +/** + * Switch material and load to nozzle + */ +bool MMU2::load_filament_to_nozzle(const uint8_t index) { + + if (!_enabled) return false; + + if (thermalManager.tooColdToExtrude(active_extruder)) { + BUZZ(200, 404); + LCD_ALERTMESSAGEPGM(MSG_HOTEND_TOO_COLD); + return false; + } + + DISABLE_AXIS_E0(); + command(MMU_CMD_T0 + index); + manage_response(true, true); + + const bool success = load_to_gears(); + if (success) { + mmu_loop(); + extruder = index; + active_extruder = 0; + load_to_nozzle(); + BUZZ(200, 404); + } + return success; +} + +/** + * Load filament to nozzle of multimaterial printer + * + * This function is used only after T? (user select filament) and M600 (change filament). + * It is not used after T0 .. T4 command (select filament), in such case, gcode is responsible for loading + * filament to nozzle. + */ +void MMU2::load_to_nozzle() { + execute_extruder_sequence((const E_Step *)load_to_nozzle_sequence, COUNT(load_to_nozzle_sequence)); +} + +bool MMU2::eject_filament(const uint8_t index, const bool recover) { + + if (!_enabled) return false; + + if (thermalManager.tooColdToExtrude(active_extruder)) { + BUZZ(200, 404); + LCD_ALERTMESSAGEPGM(MSG_HOTEND_TOO_COLD); + return false; + } + + LCD_MESSAGEPGM(MSG_MMU2_EJECTING_FILAMENT); + + ENABLE_AXIS_E0(); + current_position.e -= MMU2_FILAMENTCHANGE_EJECT_FEED; + line_to_current_position(MMM_TO_MMS(2500)); + planner.synchronize(); + command(MMU_CMD_E0 + index); + manage_response(false, false); + + if (recover) { + LCD_MESSAGEPGM(MSG_MMU2_EJECT_RECOVER); + BUZZ(200, 404); + TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("MMU2 Eject Recover"), CONTINUE_STR)); + TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("MMU2 Eject Recover"))); + wait_for_user_response(); + BUZZ(200, 404); + BUZZ(200, 404); + + command(MMU_CMD_R0); + manage_response(false, false); + } + + ui.reset_status(); + + // no active tool + extruder = MMU2_NO_TOOL; + + set_runout_valid(false); + + BUZZ(200, 404); + + DISABLE_AXIS_E0(); + + return true; +} + +/** + * Unload from hotend and retract to MMU + */ +bool MMU2::unload() { + + if (!_enabled) return false; + + if (thermalManager.tooColdToExtrude(active_extruder)) { + BUZZ(200, 404); + LCD_ALERTMESSAGEPGM(MSG_HOTEND_TOO_COLD); + return false; + } + + // Unload sequence to optimize shape of the tip of the unloaded filament + execute_extruder_sequence((const E_Step *)ramming_sequence, sizeof(ramming_sequence) / sizeof(E_Step)); + + command(MMU_CMD_U0); + manage_response(false, true); + + BUZZ(200, 404); + + // no active tool + extruder = MMU2_NO_TOOL; + + set_runout_valid(false); + + return true; +} + +void MMU2::execute_extruder_sequence(const E_Step * sequence, int steps) { + + planner.synchronize(); + ENABLE_AXIS_E0(); + + const E_Step* step = sequence; + + LOOP_L_N(i, steps) { + const float es = pgm_read_float(&(step->extrude)); + const feedRate_t fr_mm_m = pgm_read_float(&(step->feedRate)); + + DEBUG_ECHO_START(); + DEBUG_ECHOLNPAIR("E step ", es, "/", fr_mm_m); + + current_position.e += es; + line_to_current_position(MMM_TO_MMS(fr_mm_m)); + planner.synchronize(); + + step++; + } + + DISABLE_AXIS_E0(); +} + +#endif // HAS_PRUSA_MMU2 diff --git a/Marlin/src/feature/mmu2/mmu2.h b/Marlin/src/feature/mmu/mmu2.h similarity index 75% rename from Marlin/src/feature/mmu2/mmu2.h rename to Marlin/src/feature/mmu/mmu2.h index 678f65d0720d..95338a518410 100644 --- a/Marlin/src/feature/mmu2/mmu2.h +++ b/Marlin/src/feature/mmu/mmu2.h @@ -43,25 +43,24 @@ class MMU2 { static void init(); static void reset(); + static inline bool enabled() { return _enabled; } static void mmu_loop(); static void tool_change(const uint8_t index); - static void tool_change(const char* special); + static void tool_change(const char *special); static uint8_t get_current_tool(); static void set_filament_type(const uint8_t index, const uint8_t type); - #if BOTH(HAS_LCD_MENU, MMU2_MENUS) - static bool unload(); - static void load_filament(uint8_t); - static void load_all(); - static bool load_filament_to_nozzle(const uint8_t index); - static bool eject_filament(const uint8_t index, const bool recover); - #endif + static bool unload(); + static void load_filament(uint8_t); + static void load_all(); + static bool load_filament_to_nozzle(const uint8_t index); + static bool eject_filament(const uint8_t index, const bool recover); private: - static bool rx_str_P(const char* str); - static void tx_str_P(const char* str); - static void tx_printf_P(const char* format, const int argument); - static void tx_printf_P(const char* format, const int argument1, const int argument2); + static bool rx_str_P(const char *str); + static void tx_str_P(const char *str); + static void tx_printf_P(const char *format, const int argument); + static void tx_printf_P(const char *format, const int argument1, const int argument2); static void clear_rx_buffer(); static bool rx_ok(); @@ -72,15 +71,12 @@ class MMU2 { static bool get_response(); static void manage_response(const bool move_axes, const bool turn_off_nozzle); - #if BOTH(HAS_LCD_MENU, MMU2_MENUS) - static void load_to_nozzle(); - static void filament_ramming(); - static void execute_extruder_sequence(const E_Step * sequence, int steps); - #endif + static void load_to_nozzle(); + static void execute_extruder_sequence(const E_Step * sequence, int steps); static void filament_runout(); - #if ENABLED(PRUSA_MMU2_S_MODE) + #if HAS_PRUSA_MMU2S static bool mmu2s_triggered; static void check_filament(); static bool can_load(); @@ -93,7 +89,7 @@ class MMU2 { static void mmu_continue_loading(); #endif - static bool enabled, ready, mmu_print_saved; + static bool _enabled, ready, mmu_print_saved; static uint8_t cmd, cmd_arg, last_cmd, extruder; static int8_t state; diff --git a/Marlin/src/feature/mmu2/mmu2.cpp b/Marlin/src/feature/mmu2/mmu2.cpp deleted file mode 100644 index 3d635369e438..000000000000 --- a/Marlin/src/feature/mmu2/mmu2.cpp +++ /dev/null @@ -1,1068 +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 . - * - */ - -#include "../../inc/MarlinConfig.h" - -#if ENABLED(PRUSA_MMU2) - -#include "mmu2.h" -#include "../../lcd/menu/menu_mmu2.h" - -MMU2 mmu2; - -#include "../../gcode/gcode.h" -#include "../../lcd/ultralcd.h" -#include "../../libs/buzzer.h" -#include "../../libs/nozzle.h" -#include "../../module/temperature.h" -#include "../../module/planner.h" -#include "../../module/stepper/indirection.h" -#include "../../MarlinCore.h" - -#if ENABLED(HOST_PROMPT_SUPPORT) - #include "../../feature/host_actions.h" -#endif - -#if ENABLED(EXTENSIBLE_UI) - #include "../../lcd/extui/ui_api.h" -#endif - -#define DEBUG_OUT ENABLED(MMU2_DEBUG) -#include "../../core/debug_out.h" - -#define MMU_TODELAY 100 -#define MMU_TIMEOUT 10 -#define MMU_CMD_TIMEOUT 45000UL // 45s timeout for mmu commands (except P0) -#define MMU_P0_TIMEOUT 3000UL // Timeout for P0 command: 3seconds - -#define MMU2_COMMAND(S) tx_str_P(PSTR(S "\n")) - -#if ENABLED(MMU_EXTRUDER_SENSOR) - uint8_t mmu_idl_sens = 0; - static bool mmu_loading_flag = false; -#endif - -#define MMU_CMD_NONE 0 -#define MMU_CMD_T0 0x10 -#define MMU_CMD_T1 0x11 -#define MMU_CMD_T2 0x12 -#define MMU_CMD_T3 0x13 -#define MMU_CMD_T4 0x14 -#define MMU_CMD_L0 0x20 -#define MMU_CMD_L1 0x21 -#define MMU_CMD_L2 0x22 -#define MMU_CMD_L3 0x23 -#define MMU_CMD_L4 0x24 -#define MMU_CMD_C0 0x30 -#define MMU_CMD_U0 0x40 -#define MMU_CMD_E0 0x50 -#define MMU_CMD_E1 0x51 -#define MMU_CMD_E2 0x52 -#define MMU_CMD_E3 0x53 -#define MMU_CMD_E4 0x54 -#define MMU_CMD_R0 0x60 -#define MMU_CMD_F0 0x70 -#define MMU_CMD_F1 0x71 -#define MMU_CMD_F2 0x72 -#define MMU_CMD_F3 0x73 -#define MMU_CMD_F4 0x74 - -#define MMU_REQUIRED_FW_BUILDNR TERN(MMU2_MODE_12V, 132, 126) - -#define MMU2_NO_TOOL 99 -#define MMU_BAUD 115200 - -#define mmuSerial MMU2_SERIAL - -bool MMU2::enabled, MMU2::ready, MMU2::mmu_print_saved; -#if ENABLED(PRUSA_MMU2_S_MODE) - bool MMU2::mmu2s_triggered; -#endif -uint8_t MMU2::cmd, MMU2::cmd_arg, MMU2::last_cmd, MMU2::extruder; -int8_t MMU2::state = 0; -volatile int8_t MMU2::finda = 1; -volatile bool MMU2::finda_runout_valid; -int16_t MMU2::version = -1, MMU2::buildnr = -1; -millis_t MMU2::prev_request, MMU2::prev_P0_request; -char MMU2::rx_buffer[MMU_RX_SIZE], MMU2::tx_buffer[MMU_TX_SIZE]; - -#if BOTH(HAS_LCD_MENU, MMU2_MENUS) - - struct E_Step { - float extrude; //!< extrude distance in mm - feedRate_t feedRate; //!< feed rate in mm/s - }; - - static constexpr E_Step - ramming_sequence[] PROGMEM = { MMU2_RAMMING_SEQUENCE } - , load_to_nozzle_sequence[] PROGMEM = { MMU2_LOAD_TO_NOZZLE_SEQUENCE } - #if ENABLED(PRUSA_MMU2_S_MODE) - , can_load_sequence[] PROGMEM = { MMU2_CAN_LOAD_SEQUENCE } - , can_load_increment_sequence[] PROGMEM = { MMU2_CAN_LOAD_INCREMENT_SEQUENCE } - #endif - ; - -#endif // MMU2_MENUS - -MMU2::MMU2() { - rx_buffer[0] = '\0'; -} - -void MMU2::init() { - - set_runout_valid(false); - - #if PIN_EXISTS(MMU2_RST) - // TODO use macros for this - WRITE(MMU2_RST_PIN, HIGH); - SET_OUTPUT(MMU2_RST_PIN); - #endif - - mmuSerial.begin(MMU_BAUD); - extruder = MMU2_NO_TOOL; - - safe_delay(10); - reset(); - rx_buffer[0] = '\0'; - state = -1; -} - -void MMU2::reset() { - DEBUG_ECHOLNPGM("MMU <= reset"); - - #if PIN_EXISTS(MMU2_RST) - WRITE(MMU2_RST_PIN, LOW); - safe_delay(20); - WRITE(MMU2_RST_PIN, HIGH); - #else - MMU2_COMMAND("X0"); // Send soft reset - #endif -} - -uint8_t MMU2::get_current_tool() { - return extruder == MMU2_NO_TOOL ? -1 : extruder; -} - -#if EITHER(PRUSA_MMU2_S_MODE, MMU_EXTRUDER_SENSOR) - #define FILAMENT_PRESENT() (READ(FIL_RUNOUT_PIN) != FIL_RUNOUT_STATE) -#endif - -void MMU2::mmu_loop() { - - switch (state) { - - case 0: break; - - case -1: - if (rx_start()) { - DEBUG_ECHOLNPGM("MMU => 'start'"); - DEBUG_ECHOLNPGM("MMU <= 'S1'"); - - MMU2_COMMAND("S1"); // Read Version - state = -2; - } - else if (millis() > 3000000) { - SERIAL_ECHOLNPGM("MMU not responding - DISABLED"); - state = 0; - } - break; - - case -2: - if (rx_ok()) { - sscanf(rx_buffer, "%uok\n", &version); - - DEBUG_ECHOLNPAIR("MMU => ", version, "\nMMU <= 'S2'"); - - MMU2_COMMAND("S2"); // Read Build Number - state = -3; - } - break; - - case -3: - if (rx_ok()) { - sscanf(rx_buffer, "%uok\n", &buildnr); - - DEBUG_ECHOLNPAIR("MMU => ", buildnr); - - check_version(); - - #if ENABLED(MMU2_MODE_12V) - DEBUG_ECHOLNPGM("MMU <= 'M1'"); - - MMU2_COMMAND("M1"); // Stealth Mode - state = -5; - - #else - DEBUG_ECHOLNPGM("MMU <= 'P0'"); - - MMU2_COMMAND("P0"); // Read FINDA - state = -4; - #endif - } - break; - - #if ENABLED(MMU2_MODE_12V) - case -5: - // response to M1 - if (rx_ok()) { - DEBUG_ECHOLNPGM("MMU => ok"); - - DEBUG_ECHOLNPGM("MMU <= 'P0'"); - - MMU2_COMMAND("P0"); // Read FINDA - state = -4; - } - break; - #endif - - case -4: - if (rx_ok()) { - sscanf(rx_buffer, "%hhuok\n", &finda); - - DEBUG_ECHOLNPAIR("MMU => ", finda, "\nMMU - ENABLED"); - - enabled = true; - state = 1; - TERN_(PRUSA_MMU2_S_MODE, mmu2s_triggered = false); - } - break; - - case 1: - if (cmd) { - if (WITHIN(cmd, MMU_CMD_T0, MMU_CMD_T4)) { - // tool change - int filament = cmd - MMU_CMD_T0; - DEBUG_ECHOLNPAIR("MMU <= T", filament); - tx_printf_P(PSTR("T%d\n"), filament); - TERN_(MMU_EXTRUDER_SENSOR, mmu_idl_sens = 1); // enable idler sensor, if any - state = 3; // wait for response - } - else if (WITHIN(cmd, MMU_CMD_L0, MMU_CMD_L4)) { - // load - int filament = cmd - MMU_CMD_L0; - DEBUG_ECHOLNPAIR("MMU <= L", filament); - tx_printf_P(PSTR("L%d\n"), filament); - state = 3; // wait for response - } - else if (cmd == MMU_CMD_C0) { - // continue loading - DEBUG_ECHOLNPGM("MMU <= 'C0'"); - MMU2_COMMAND("C0"); - state = 3; // wait for response - } - else if (cmd == MMU_CMD_U0) { - // unload current - DEBUG_ECHOLNPGM("MMU <= 'U0'"); - - MMU2_COMMAND("U0"); - state = 3; // wait for response - } - else if (WITHIN(cmd, MMU_CMD_E0, MMU_CMD_E4)) { - // eject filament - int filament = cmd - MMU_CMD_E0; - DEBUG_ECHOLNPAIR("MMU <= E", filament); - tx_printf_P(PSTR("E%d\n"), filament); - state = 3; // wait for response - } - else if (cmd == MMU_CMD_R0) { - // recover after eject - DEBUG_ECHOLNPGM("MMU <= 'R0'"); - MMU2_COMMAND("R0"); - state = 3; // wait for response - } - else if (WITHIN(cmd, MMU_CMD_F0, MMU_CMD_F4)) { - // filament type - int filament = cmd - MMU_CMD_F0; - DEBUG_ECHOPAIR("MMU <= F", filament, " "); - DEBUG_ECHO_F(cmd_arg, DEC); - DEBUG_EOL(); - tx_printf_P(PSTR("F%d %d\n"), filament, cmd_arg); - state = 3; // wait for response - } - - last_cmd = cmd; - cmd = MMU_CMD_NONE; - } - else if (ELAPSED(millis(), prev_P0_request + 300)) { - MMU2_COMMAND("P0"); // Read FINDA - state = 2; // wait for response - } - - TERN_(PRUSA_MMU2_S_MODE, check_filament()); - break; - - case 2: // response to command P0 - if (rx_ok()) { - sscanf(rx_buffer, "%hhuok\n", &finda); - - // This is super annoying. Only activate if necessary - // if (finda_runout_valid) DEBUG_ECHOLNPAIR_F("MMU <= 'P0'\nMMU => ", finda, 6); - - if (!finda && finda_runout_valid) filament_runout(); - if (cmd == 0) ready = true; - state = 1; - } - else if (ELAPSED(millis(), prev_request + MMU_P0_TIMEOUT)) // Resend request after timeout (3s) - state = 1; - - TERN_(PRUSA_MMU2_S_MODE, check_filament()); - break; - - case 3: // response to mmu commands - #if ENABLED(MMU_EXTRUDER_SENSOR) - if (mmu_idl_sens) { - if (FILAMENT_PRESENT() && mmu_loading_flag) { - DEBUG_ECHOLNPGM("MMU <= 'A'"); - MMU2_COMMAND("A"); // send 'abort' request - mmu_idl_sens = 0; - DEBUG_ECHOLNPGM("MMU IDLER_SENSOR = 0 - ABORT"); - } - } - #endif - - if (rx_ok()) { - // Response to C0 mmu command in PRUSA_MMU2_S_MODE - bool can_reset = true; - #if ENABLED(PRUSA_MMU2_S_MODE) - if (!mmu2s_triggered && last_cmd == MMU_CMD_C0) { - can_reset = false; - // MMU ok received but filament sensor not triggered, retrying... - DEBUG_ECHOLNPGM("MMU => 'ok' (filament not present in gears)"); - DEBUG_ECHOLNPGM("MMU <= 'C0' (keep trying)"); - MMU2_COMMAND("C0"); - } - #endif - if (can_reset) { - DEBUG_ECHOLNPGM("MMU => 'ok'"); - ready = true; - state = 1; - last_cmd = MMU_CMD_NONE; - } - } - else if (ELAPSED(millis(), prev_request + MMU_CMD_TIMEOUT)) { - // resend request after timeout - if (last_cmd) { - DEBUG_ECHOLNPGM("MMU retry"); - cmd = last_cmd; - last_cmd = MMU_CMD_NONE; - } - state = 1; - } - TERN_(PRUSA_MMU2_S_MODE, check_filament()); - break; - } -} - -/** - * Check if MMU was started - */ -bool MMU2::rx_start() { - // check for start message - if (rx_str_P(PSTR("start\n"))) { - prev_P0_request = millis(); - return true; - } - return false; -} - -/** - * Check if the data received ends with the given string. - */ -bool MMU2::rx_str_P(const char* str) { - uint8_t i = strlen(rx_buffer); - - while (mmuSerial.available()) { - rx_buffer[i++] = mmuSerial.read(); - rx_buffer[i] = '\0'; - - if (i == sizeof(rx_buffer) - 1) { - DEBUG_ECHOLNPGM("rx buffer overrun"); - break; - } - } - - uint8_t len = strlen_P(str); - - if (i < len) return false; - - str += len; - - while (len--) { - char c0 = pgm_read_byte(str--), c1 = rx_buffer[i--]; - if (c0 == c1) continue; - if (c0 == '\r' && c1 == '\n') continue; // match cr as lf - if (c0 == '\n' && c1 == '\r') continue; // match lf as cr - return false; - } - return true; -} - -/** - * Transfer data to MMU, no argument - */ -void MMU2::tx_str_P(const char* str) { - clear_rx_buffer(); - uint8_t len = strlen_P(str); - LOOP_L_N(i, len) mmuSerial.write(pgm_read_byte(str++)); - rx_buffer[0] = '\0'; - prev_request = millis(); -} - -/** - * Transfer data to MMU, single argument - */ -void MMU2::tx_printf_P(const char* format, int argument = -1) { - clear_rx_buffer(); - uint8_t len = sprintf_P(tx_buffer, format, argument); - LOOP_L_N(i, len) mmuSerial.write(tx_buffer[i]); - rx_buffer[0] = '\0'; - prev_request = millis(); -} - -/** - * Transfer data to MMU, two arguments - */ -void MMU2::tx_printf_P(const char* format, int argument1, int argument2) { - clear_rx_buffer(); - uint8_t len = sprintf_P(tx_buffer, format, argument1, argument2); - LOOP_L_N(i, len) mmuSerial.write(tx_buffer[i]); - rx_buffer[0] = '\0'; - prev_request = millis(); -} - -/** - * Empty the rx buffer - */ -void MMU2::clear_rx_buffer() { - while (mmuSerial.available()) mmuSerial.read(); - rx_buffer[0] = '\0'; -} - -/** - * Check if we received 'ok' from MMU - */ -bool MMU2::rx_ok() { - if (rx_str_P(PSTR("ok\n"))) { - prev_P0_request = millis(); - return true; - } - return false; -} - -/** - * Check if MMU has compatible firmware - */ -void MMU2::check_version() { - if (buildnr < MMU_REQUIRED_FW_BUILDNR) { - SERIAL_ERROR_MSG("Invalid MMU2 firmware. Version >= " STRINGIFY(MMU_REQUIRED_FW_BUILDNR) " required."); - kill(GET_TEXT(MSG_KILL_MMU2_FIRMWARE)); - } -} - -static void mmu2_not_responding() { - LCD_MESSAGEPGM(MSG_MMU2_NOT_RESPONDING); - BUZZ(100, 659); - BUZZ(200, 698); - BUZZ(100, 659); - BUZZ(300, 440); - BUZZ(100, 659); -} - -#if ENABLED(PRUSA_MMU2_S_MODE) - - 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 - if (mmu2s_triggered) break; - command(MMU_CMD_C0); - manage_response(true, true); - check_filament(); - } - const bool success = mmu2s_triggered && can_load(); - if (!success) mmu2_not_responding(); - return success; - } - - /** - * Handle tool change - */ - void MMU2::tool_change(const uint8_t index) { - - if (!enabled) return; - - set_runout_valid(false); - - if (index != extruder) { - - DISABLE_AXIS_E0(); - ui.status_printf_P(0, GET_TEXT(MSG_MMU2_LOADING_FILAMENT), int(index + 1)); - - command(MMU_CMD_T0 + index); - manage_response(true, true); - - if (load_to_gears()) { - extruder = index; // filament change is finished - active_extruder = 0; - ENABLE_AXIS_E0(); - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR(STR_ACTIVE_EXTRUDER, int(extruder)); - } - ui.reset_status(); - } - - set_runout_valid(true); - } - - /** - * Handle special T?/Tx/Tc commands - * - * T? Gcode to extrude shouldn't have to follow, load to extruder wheels is done automatically - * Tx Same as T?, except nozzle doesn't have to be preheated. Tc must be placed after extruder nozzle is preheated to finish filament load. - * Tc Load to nozzle after filament was prepared by Tx and extruder nozzle is already heated. - */ - void MMU2::tool_change(const char* special) { - - if (!enabled) return; - - #if ENABLED(MMU2_MENUS) - - set_runout_valid(false); - - switch (*special) { - case '?': { - uint8_t index = mmu2_choose_filament(); - while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100); - load_filament_to_nozzle(index); - } break; - - case 'x': { - planner.synchronize(); - uint8_t index = mmu2_choose_filament(); - DISABLE_AXIS_E0(); - command(MMU_CMD_T0 + index); - manage_response(true, true); - - if (load_to_gears()) { - mmu_loop(); - ENABLE_AXIS_E0(); - extruder = index; - active_extruder = 0; - } - } break; - - case 'c': { - while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100); - execute_extruder_sequence((const E_Step *)load_to_nozzle_sequence, COUNT(load_to_nozzle_sequence)); - } break; - } - - set_runout_valid(true); - - #endif // MMU2_MENUS - } - -#elif ENABLED(MMU_EXTRUDER_SENSOR) - - /** - * Handle tool change - */ - void MMU2::tool_change(const uint8_t index) { - if (!enabled) return; - - set_runout_valid(false); - - if (index != extruder) { - DISABLE_AXIS_E0(); - if (FILAMENT_PRESENT()) { - DEBUG_ECHOLNPGM("Unloading\n"); - mmu_loading_flag = false; - command(MMU_CMD_U0); - manage_response(true, true); - } - ui.status_printf_P(0, GET_TEXT(MSG_MMU2_LOADING_FILAMENT), int(index + 1)); - mmu_loading_flag = true; - command(MMU_CMD_T0 + index); - manage_response(true, true); - mmu_continue_loading(); - command(MMU_CMD_C0); - extruder = index; - active_extruder = 0; - - ENABLE_AXIS_E0(); - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR(STR_ACTIVE_EXTRUDER, int(extruder)); - - ui.reset_status(); - } - - set_runout_valid(true); - } - - /** - * Handle special T?/Tx/Tc commands - * - * T? Gcode to extrude shouldn't have to follow, load to extruder wheels is done automatically - * Tx Same as T?, except nozzle doesn't have to be preheated. Tc must be placed after extruder nozzle is preheated to finish filament load. - * Tc Load to nozzle after filament was prepared by Tx and extruder nozzle is already heated. - */ - void MMU2::tool_change(const char* special) { - if (!enabled) return; - - #if ENABLED(MMU2_MENUS) - - set_runout_valid(false); - - switch (*special) { - case '?': { - DEBUG_ECHOLNPGM("case ?\n"); - uint8_t index = mmu2_choose_filament(); - while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100); - load_filament_to_nozzle(index); - } break; - - case 'x': { - DEBUG_ECHOLNPGM("case x\n"); - planner.synchronize(); - uint8_t index = mmu2_choose_filament(); - DISABLE_AXIS_E0(); - command(MMU_CMD_T0 + index); - manage_response(true, true); - mmu_continue_loading(); - command(MMU_CMD_C0); - mmu_loop(); - - ENABLE_AXIS_E0(); - extruder = index; - active_extruder = 0; - } break; - - case 'c': { - DEBUG_ECHOLNPGM("case c\n"); - while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100); - execute_extruder_sequence((const E_Step *)load_to_nozzle_sequence, COUNT(load_to_nozzle_sequence)); - } break; - } - - set_runout_valid(true); - - #endif // MMU2_MENUS - } - - void MMU2::mmu_continue_loading() { - for (uint8_t i = 0; i < MMU_LOADING_ATTEMPTS_NR; i++) { - DEBUG_ECHOLNPAIR("Additional load attempt #", i); - if (FILAMENT_PRESENT()) break; - command(MMU_CMD_C0); - manage_response(true, true); - } - if (!FILAMENT_PRESENT()) { - DEBUG_ECHOLNPGM("Filament never reached sensor, runout"); - filament_runout(); - } - mmu_idl_sens = 0; - } - -#elif DISABLED(MMU_EXTRUDER_SENSOR) && DISABLED(PRUSA_MMU2_S_MODE) - -/** - * Handle tool change - */ -void MMU2::tool_change(const uint8_t index) { - if (!enabled) return; - - set_runout_valid(false); - - if (index != extruder) { - DISABLE_AXIS_E0(); - ui.status_printf_P(0, GET_TEXT(MSG_MMU2_LOADING_FILAMENT), int(index + 1)); - command(MMU_CMD_T0 + index); - manage_response(true, true); - command(MMU_CMD_C0); - extruder = index; //filament change is finished - active_extruder = 0; - ENABLE_AXIS_E0(); - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR(STR_ACTIVE_EXTRUDER, int(extruder)); - ui.reset_status(); - } - - set_runout_valid(true); -} - -/** - * Handle special T?/Tx/Tc commands - * - * T? Gcode to extrude shouldn't have to follow, load to extruder wheels is done automatically - * Tx Same as T?, except nozzle doesn't have to be preheated. Tc must be placed after extruder nozzle is preheated to finish filament load. - * Tc Load to nozzle after filament was prepared by Tx and extruder nozzle is already heated. - */ -void MMU2::tool_change(const char* special) { - if (!enabled) return; - - #if ENABLED(MMU2_MENUS) - - set_runout_valid(false); - - switch (*special) { - case '?': { - DEBUG_ECHOLNPGM("case ?\n"); - uint8_t index = mmu2_choose_filament(); - while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100); - load_filament_to_nozzle(index); - } break; - - case 'x': { - DEBUG_ECHOLNPGM("case x\n"); - planner.synchronize(); - uint8_t index = mmu2_choose_filament(); - DISABLE_AXIS_E0(); - command(MMU_CMD_T0 + index); - manage_response(true, true); - command(MMU_CMD_C0); - mmu_loop(); - - ENABLE_AXIS_E0(); - extruder = index; - active_extruder = 0; - } break; - - case 'c': { - DEBUG_ECHOLNPGM("case c\n"); - while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100); - execute_extruder_sequence((const E_Step *)load_to_nozzle_sequence, COUNT(load_to_nozzle_sequence)); - } break; - } - - set_runout_valid(true); - - #endif - } - -#endif // MMU_EXTRUDER_SENSOR - -/** - * Set next command - */ -void MMU2::command(const uint8_t mmu_cmd) { - if (!enabled) return; - cmd = mmu_cmd; - ready = false; -} - -/** - * Wait for response from MMU - */ -bool MMU2::get_response() { - while (cmd != MMU_CMD_NONE) idle(); - - while (!ready) { - idle(); - if (state != 3) break; - } - - const bool ret = ready; - ready = false; - - return ret; -} - -/** - * Wait for response and deal with timeout if nexcessary - */ -void MMU2::manage_response(const bool move_axes, const bool turn_off_nozzle) { - - constexpr xyz_pos_t park_point = NOZZLE_PARK_POINT; - bool response = false; - mmu_print_saved = false; - xyz_pos_t resume_position; - int16_t resume_hotend_temp = thermalManager.degTargetHotend(active_extruder); - - KEEPALIVE_STATE(PAUSED_FOR_USER); - - while (!response) { - - response = get_response(); // wait for "ok" from mmu - - if (!response) { // No "ok" was received in reserved time frame, user will fix the issue on mmu unit - if (!mmu_print_saved) { // First occurrence. Save current position, park print head, disable nozzle heater. - - planner.synchronize(); - - mmu_print_saved = true; - - SERIAL_ECHOLNPGM("MMU not responding"); - - resume_hotend_temp = thermalManager.degTargetHotend(active_extruder); - resume_position = current_position; - - if (move_axes && all_axes_homed()) - nozzle.park(0, park_point /*= NOZZLE_PARK_POINT*/); - - if (turn_off_nozzle) thermalManager.setTargetHotend(0, active_extruder); - - mmu2_not_responding(); - } - } - else if (mmu_print_saved) { - SERIAL_ECHOLNPGM("MMU starts responding\n"); - - if (turn_off_nozzle && resume_hotend_temp) { - thermalManager.setTargetHotend(resume_hotend_temp, active_extruder); - LCD_MESSAGEPGM(MSG_HEATING); - BUZZ(200, 40); - - while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(1000); - } - - if (move_axes && all_axes_homed()) { - LCD_MESSAGEPGM(MSG_MMU2_RESUMING); - BUZZ(198, 404); BUZZ(4, 0); BUZZ(198, 404); - - // Move XY to starting position, then Z - do_blocking_move_to_xy(resume_position, feedRate_t(NOZZLE_PARK_XY_FEEDRATE)); - - // Move Z_AXIS to saved position - do_blocking_move_to_z(resume_position.z, feedRate_t(NOZZLE_PARK_Z_FEEDRATE)); - } - else { - BUZZ(198, 404); BUZZ(4, 0); BUZZ(198, 404); - LCD_MESSAGEPGM(MSG_MMU2_RESUMING); - } - } - } -} - -void MMU2::set_filament_type(const uint8_t index, const uint8_t filamentType) { - if (!enabled) return; - - cmd_arg = filamentType; - command(MMU_CMD_F0 + index); - - manage_response(true, true); -} - -void MMU2::filament_runout() { - queue.inject_P(PSTR(MMU2_FILAMENT_RUNOUT_SCRIPT)); - planner.synchronize(); -} - -#if ENABLED(PRUSA_MMU2_S_MODE) - - void MMU2::check_filament() { - const bool present = FILAMENT_PRESENT(); - if (cmd == MMU_CMD_NONE && last_cmd == MMU_CMD_C0) { - if (present && !mmu2s_triggered) { - DEBUG_ECHOLNPGM("MMU <= 'A'"); - tx_str_P(PSTR("A\n")); - } - // Slowly spin the extruder during C0 - else { - while (planner.movesplanned() < 3) { - current_position.e += 0.25; - line_to_current_position(MMM_TO_MMS(120)); - } - } - } - mmu2s_triggered = present; - } - - bool MMU2::can_load() { - execute_extruder_sequence((const E_Step *)can_load_sequence, COUNT(can_load_sequence)); - - 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) { - 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'); - if (mmu2s_triggered) ++filament_detected_count; - } - - if (filament_detected_count <= steps - (MMU2_CAN_LOAD_DEVIATION) / (MMU2_CAN_LOAD_INCREMENT)) { - DEBUG_ECHOLNPGM(" failed."); - return false; - } - - DEBUG_ECHOLNPGM(" succeeded."); - return true; - } -#endif - -#if BOTH(HAS_LCD_MENU, MMU2_MENUS) - - // Load filament into MMU2 - void MMU2::load_filament(const uint8_t index) { - if (!enabled) return; - command(MMU_CMD_L0 + index); - manage_response(false, false); - BUZZ(200, 404); - } - - /** - * Switch material and load to nozzle - */ - bool MMU2::load_filament_to_nozzle(const uint8_t index) { - - if (!enabled) return false; - - if (thermalManager.tooColdToExtrude(active_extruder)) { - BUZZ(200, 404); - LCD_ALERTMESSAGEPGM(MSG_HOTEND_TOO_COLD); - return false; - } - - command(MMU_CMD_T0 + index); - manage_response(true, true); - - const bool success = load_to_gears(); - if (success) { - mmu_loop(); - extruder = index; - active_extruder = 0; - load_to_nozzle(); - BUZZ(200, 404); - } - return success; - } - - /** - * Load filament to nozzle of multimaterial printer - * - * This function is used only only after T? (user select filament) and M600 (change filament). - * It is not used after T0 .. T4 command (select filament), in such case, gcode is responsible for loading - * filament to nozzle. - */ - void MMU2::load_to_nozzle() { - if (!enabled) return; - execute_extruder_sequence((const E_Step *)load_to_nozzle_sequence, COUNT(load_to_nozzle_sequence)); - } - - bool MMU2::eject_filament(const uint8_t index, const bool recover) { - - if (!enabled) return false; - - if (thermalManager.tooColdToExtrude(active_extruder)) { - BUZZ(200, 404); - LCD_ALERTMESSAGEPGM(MSG_HOTEND_TOO_COLD); - return false; - } - - LCD_MESSAGEPGM(MSG_MMU2_EJECTING_FILAMENT); - - ENABLE_AXIS_E0(); - current_position.e -= MMU2_FILAMENTCHANGE_EJECT_FEED; - line_to_current_position(2500 / 60); - planner.synchronize(); - command(MMU_CMD_E0 + index); - manage_response(false, false); - - if (recover) { - LCD_MESSAGEPGM(MSG_MMU2_EJECT_RECOVER); - BUZZ(200, 404); - TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("MMU2 Eject Recover"), CONTINUE_STR)); - TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("MMU2 Eject Recover"))); - wait_for_user_response(); - BUZZ(200, 404); - BUZZ(200, 404); - - command(MMU_CMD_R0); - manage_response(false, false); - } - - ui.reset_status(); - - // no active tool - extruder = MMU2_NO_TOOL; - - set_runout_valid(false); - - BUZZ(200, 404); - - DISABLE_AXIS_E0(); - - return true; - } - - /** - * Unload from hotend and retract to MMU - */ - bool MMU2::unload() { - - if (!enabled) return false; - - if (thermalManager.tooColdToExtrude(active_extruder)) { - BUZZ(200, 404); - LCD_ALERTMESSAGEPGM(MSG_HOTEND_TOO_COLD); - return false; - } - - filament_ramming(); - - command(MMU_CMD_U0); - manage_response(false, true); - - BUZZ(200, 404); - - // no active tool - extruder = MMU2_NO_TOOL; - - set_runout_valid(false); - - return true; - } - - /** - * Unload sequence to optimize shape of the tip of the unloaded filament - */ - void MMU2::filament_ramming() { - execute_extruder_sequence((const E_Step *)ramming_sequence, sizeof(ramming_sequence) / sizeof(E_Step)); - } - - void MMU2::execute_extruder_sequence(const E_Step * sequence, int steps) { - - planner.synchronize(); - ENABLE_AXIS_E0(); - - const E_Step* step = sequence; - - LOOP_L_N(i, steps) { - const float es = pgm_read_float(&(step->extrude)); - const feedRate_t fr_mm_m = pgm_read_float(&(step->feedRate)); - - DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("E step ", es, "/", fr_mm_m); - - current_position.e += es; - line_to_current_position(MMM_TO_MMS(fr_mm_m)); - planner.synchronize(); - - step++; - } - - DISABLE_AXIS_E0(); - } - -#endif // HAS_LCD_MENU && MMU2_MENUS - -#endif // PRUSA_MMU2 diff --git a/Marlin/src/feature/mmu2/serial-protocol.md b/Marlin/src/feature/mmu2/serial-protocol.md deleted file mode 100644 index 936830e1dc08..000000000000 --- a/Marlin/src/feature/mmu2/serial-protocol.md +++ /dev/null @@ -1,94 +0,0 @@ -Startup sequence -================ - -When initialized, MMU sends - -- MMU => 'start\n' - -We follow with - -- MMU <= 'S1\n' -- MMU => 'ok*Firmware version*\n' -- MMU <= 'S2\n' -- MMU => 'ok*Build number*\n' - -#if (12V_mode) - -- MMU <= 'M1\n' -- MMU => 'ok\n' - -#endif - -- MMU <= 'P0\n' -- MMU => '*FINDA status*\n' - -Now we are sure MMU is available and ready. If there was a timeout or other communication problem somewhere, printer will be killed. - -- *Firmware version* is an integer value, but we don't care about it -- *Build number* is an integer value and has to be >=126, or =>132 if 12V mode is enabled -- *FINDA status* is 1 if the is filament loaded to the extruder, 0 otherwise - - -*Build number* is checked against the required value, if it does not match, printer is halted. - - - -Toolchange -========== - -- MMU <= 'T*Filament index*\n' - -MMU sends - -- MMU => 'ok\n' - -as soon as the filament is fed down to the extruder. We follow with - -- MMU <= 'C0\n' - -MMU will feed a few more millimeters of filament for the extruder gears to grab. -When done, the MMU sends - -- MMU => 'ok\n' - -We don't wait for a response here but immediately continue with the next gcode which should -be one or more extruder moves to feed the filament into the hotend. - - -FINDA status -============ - -- MMU <= 'P0\n' -- MMU => '*FINDA status*\n' - -*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 -============= - -- MMU <= 'L*Filament index*\n' - -MMU will feed filament down to the extruder, when done - -- MMU => 'ok\n' - - -Unload filament -============= - -- MMU <= 'U0\n' - -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/password/password.cpp b/Marlin/src/feature/password/password.cpp index 90bb647118b5..4e841c243cf0 100644 --- a/Marlin/src/feature/password/password.cpp +++ b/Marlin/src/feature/password/password.cpp @@ -31,7 +31,7 @@ Password password; // public: -bool Password::is_set, Password::is_locked; +bool Password::is_set, Password::is_locked, Password::did_first_run; // = false uint32_t Password::value, Password::value_entry; // @@ -47,11 +47,14 @@ void Password::lock_machine() { // Authentication check // void Password::authentication_check() { - if (value_entry == value) + if (value_entry == value) { is_locked = false; - else + did_first_run = true; + } + else { + is_locked = true; SERIAL_ECHOLNPGM(STR_WRONG_PASSWORD); - + } TERN_(HAS_LCD_MENU, authentication_done()); } diff --git a/Marlin/src/feature/password/password.h b/Marlin/src/feature/password/password.h index 3ed584b29d5e..829d222e20b9 100644 --- a/Marlin/src/feature/password/password.h +++ b/Marlin/src/feature/password/password.h @@ -21,20 +21,20 @@ */ #pragma once -#include "../../lcd/ultralcd.h" +#include "../../lcd/marlinui.h" class Password { public: - static bool is_set, is_locked; + static bool is_set, is_locked, did_first_run; static uint32_t value, value_entry; - Password() { is_locked = false; } + Password() {} static void lock_machine(); + static void authentication_check(); #if HAS_LCD_MENU static void access_menu_password(); - static void authentication_check(); static void authentication_done(); static void media_gatekeeper(); @@ -47,7 +47,7 @@ class Password { static void start_over(); static void digit_entered(); - static void set_password_done(); + static void set_password_done(const bool with_set=true); static void menu_password_report(); static void remove_password(); diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 0ab659402181..94c564a9aaf7 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -55,7 +55,7 @@ #include "../lcd/extui/ui_api.h" #endif -#include "../lcd/ultralcd.h" +#include "../lcd/marlinui.h" #if HAS_BUZZER #include "../libs/buzzer.h" @@ -75,7 +75,7 @@ static xyze_pos_t resume_position; -#if HAS_LCD_MENU +#if M600_PURGE_MORE_RESUMABLE PauseMenuResponse pause_menu_response; PauseMode pause_mode = PAUSE_MODE_PAUSE_PRINT; #endif @@ -130,21 +130,20 @@ fil_change_settings_t fc_settings[EXTRUDERS]; */ static bool ensure_safe_temperature(const bool wait=true, const PauseMode mode=PAUSE_MODE_SAME) { DEBUG_SECTION(est, "ensure_safe_temperature", true); - DEBUG_ECHOLNPAIR("... wait:", int(wait), " mode:", int(mode)); + DEBUG_ECHOLNPAIR("... wait:", wait, " mode:", mode); - if (!DEBUGGING(DRYRUN) && thermalManager.targetTooColdToExtrude(active_extruder)) - thermalManager.setTargetHotend(thermalManager.extrude_min_temp, active_extruder); - - #if HAS_LCD_MENU - lcd_pause_show_message(PAUSE_MESSAGE_HEATING, mode); + #if ENABLED(PREVENT_COLD_EXTRUSION) + if (!DEBUGGING(DRYRUN) && thermalManager.targetTooColdToExtrude(active_extruder)) + thermalManager.setTargetHotend(thermalManager.extrude_min_temp, active_extruder); #endif - UNUSED(mode); - if (wait) - return thermalManager.wait_for_hotend(active_extruder); + ui.pause_show_message(PAUSE_MESSAGE_HEATING, mode); UNUSED(mode); + + if (wait) return thermalManager.wait_for_hotend(active_extruder); - wait_for_heatup = true; // Allow interruption by Emergency Parser M108 - while (wait_for_heatup && ABS(thermalManager.degHotend(active_extruder) - thermalManager.degTargetHotend(active_extruder)) > TEMP_WINDOW) + // Allow interruption by Emergency Parser M108 + wait_for_heatup = TERN1(PREVENT_COLD_EXTRUSION, !thermalManager.allow_cold_extrude); + while (wait_for_heatup && ABS(thermalManager.wholeDegHotend(active_extruder) - thermalManager.degTargetHotend(active_extruder)) > (TEMP_WINDOW)) idle(); wait_for_heatup = false; @@ -171,58 +170,46 @@ static bool ensure_safe_temperature(const bool wait=true, const PauseMode mode=P * * Returns 'true' if load was completed, 'false' for abort */ -bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_length/*=0*/, const float &purge_length/*=0*/, const int8_t max_beep_count/*=0*/, +bool load_filament(const_float_t slow_load_length/*=0*/, const_float_t fast_load_length/*=0*/, const_float_t purge_length/*=0*/, const int8_t max_beep_count/*=0*/, const bool show_lcd/*=false*/, const bool pause_for_user/*=false*/, const PauseMode mode/*=PAUSE_MODE_PAUSE_PRINT*/ DXC_ARGS ) { DEBUG_SECTION(lf, "load_filament", true); - DEBUG_ECHOLNPAIR("... slowlen:", slow_load_length, " fastlen:", fast_load_length, " purgelen:", purge_length, " maxbeep:", int(max_beep_count), " showlcd:", int(show_lcd), " pauseforuser:", int(pause_for_user), " pausemode:", int(mode) DXC_SAY); - - UNUSED(show_lcd); + DEBUG_ECHOLNPAIR("... slowlen:", slow_load_length, " fastlen:", fast_load_length, " purgelen:", purge_length, " maxbeep:", max_beep_count, " showlcd:", show_lcd, " pauseforuser:", pause_for_user, " pausemode:", mode DXC_SAY); if (!ensure_safe_temperature(false, mode)) { - #if HAS_LCD_MENU - if (show_lcd) lcd_pause_show_message(PAUSE_MESSAGE_STATUS, mode); - #endif + if (show_lcd) ui.pause_show_message(PAUSE_MESSAGE_STATUS, mode); return false; } if (pause_for_user) { - #if HAS_LCD_MENU - if (show_lcd) lcd_pause_show_message(PAUSE_MESSAGE_INSERT, mode); - #endif + if (show_lcd) ui.pause_show_message(PAUSE_MESSAGE_INSERT, mode); SERIAL_ECHO_MSG(_PMSG(STR_FILAMENT_CHANGE_INSERT)); first_impatient_beep(max_beep_count); KEEPALIVE_STATE(PAUSED_FOR_USER); + wait_for_user = true; // LCD click or M108 will clear this #if ENABLED(HOST_PROMPT_SUPPORT) - const char tool = '0' - #if NUM_RUNOUT_SENSORS > 1 - + active_extruder - #endif - ; - host_action_prompt_begin(PROMPT_USER_CONTINUE, PSTR("Load Filament T"), tool); - host_action_prompt_button(CONTINUE_STR); - host_action_prompt_show(); + const char tool = '0' + TERN0(MULTI_FILAMENT_SENSOR, active_extruder); + host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Load Filament T"), tool, CONTINUE_STR); #endif + TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("Load Filament"))); + while (wait_for_user) { impatient_beep(max_beep_count); idle_no_sleep(); } } - #if HAS_LCD_MENU - if (show_lcd) lcd_pause_show_message(PAUSE_MESSAGE_LOAD, mode); - #endif + if (show_lcd) ui.pause_show_message(PAUSE_MESSAGE_LOAD, mode); #if ENABLED(DUAL_X_CARRIAGE) const int8_t saved_ext = active_extruder; const bool saved_ext_dup_mode = extruder_duplication_enabled; - active_extruder = DXC_ext; - extruder_duplication_enabled = false; + set_duplication_enabled(false, DXC_ext); #endif // Slow Load filament @@ -243,16 +230,12 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l } #if ENABLED(DUAL_X_CARRIAGE) // Tie the two extruders movement back together. - active_extruder = saved_ext; - extruder_duplication_enabled = saved_ext_dup_mode; - stepper.set_directions(); + set_duplication_enabled(saved_ext_dup_mode, saved_ext); #endif #if ENABLED(ADVANCED_PAUSE_CONTINUOUS_PURGE) - #if HAS_LCD_MENU - if (show_lcd) lcd_pause_show_message(PAUSE_MESSAGE_PURGE); - #endif + if (show_lcd) ui.pause_show_message(PAUSE_MESSAGE_PURGE); TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Filament Purging..."), CONTINUE_STR)); TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("Filament Purging..."))); @@ -266,28 +249,30 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l do { if (purge_length > 0) { // "Wait for filament purge" - #if HAS_LCD_MENU - if (show_lcd) lcd_pause_show_message(PAUSE_MESSAGE_PURGE); - #endif + if (show_lcd) ui.pause_show_message(PAUSE_MESSAGE_PURGE); // Extrude filament to get into hotend unscaled_e_move(purge_length, ADVANCED_PAUSE_PURGE_FEEDRATE); } - TERN_(HOST_PROMPT_SUPPORT, filament_load_host_prompt()); // Initiate another host prompt. (NOTE: host_response_handler may also do this!) + TERN_(HOST_PROMPT_SUPPORT, filament_load_host_prompt()); // Initiate another host prompt. - #if HAS_LCD_MENU + #if M600_PURGE_MORE_RESUMABLE if (show_lcd) { // Show "Purge More" / "Resume" menu and wait for reply KEEPALIVE_STATE(PAUSED_FOR_USER); wait_for_user = false; - lcd_pause_show_message(PAUSE_MESSAGE_OPTION); + #if HAS_LCD_MENU + ui.pause_show_message(PAUSE_MESSAGE_OPTION); // Also sets PAUSE_RESPONSE_WAIT_FOR + #else + pause_menu_response = PAUSE_RESPONSE_WAIT_FOR; + #endif while (pause_menu_response == PAUSE_RESPONSE_WAIT_FOR) idle_no_sleep(); } #endif // Keep looping if "Purge More" was selected - } while (TERN0(HAS_LCD_MENU, show_lcd && pause_menu_response == PAUSE_RESPONSE_EXTRUDE_MORE)); + } while (TERN0(M600_PURGE_MORE_RESUMABLE, show_lcd && pause_menu_response == PAUSE_RESPONSE_EXTRUDE_MORE)); #endif TERN_(HOST_PROMPT_SUPPORT, host_action_prompt_end()); @@ -295,6 +280,18 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l return true; } +/** + * Disabling E steppers for manual filament change should be fine + * as long as users don't spin the E motor ridiculously fast and + * send current back to their board, potentially frying it. + */ +inline void disable_active_extruder() { + #if HAS_E_STEPPER_ENABLE + disable_e_stepper(active_extruder); + safe_delay(100); + #endif +} + /** * Unload filament from the hotend * @@ -305,35 +302,29 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l * * Returns 'true' if unload was completed, 'false' for abort */ -bool unload_filament(const float &unload_length, const bool show_lcd/*=false*/, +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) - , const float &mix_multiplier/*=1.0*/ + , const_float_t mix_multiplier/*=1.0*/ #endif ) { DEBUG_SECTION(uf, "unload_filament", true); - DEBUG_ECHOLNPAIR("... unloadlen:", unload_length, " showlcd:", int(show_lcd), " mode:", int(mode) + DEBUG_ECHOLNPAIR("... unloadlen:", unload_length, " showlcd:", show_lcd, " mode:", mode #if BOTH(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER) , " mixmult:", mix_multiplier #endif ); - UNUSED(show_lcd); - #if !BOTH(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER) - constexpr float mix_multiplier = 1.0; + constexpr float mix_multiplier = 1.0f; #endif if (!ensure_safe_temperature(false, mode)) { - #if HAS_LCD_MENU - if (show_lcd) lcd_pause_show_message(PAUSE_MESSAGE_STATUS); - #endif + if (show_lcd) ui.pause_show_message(PAUSE_MESSAGE_STATUS); return false; } - #if HAS_LCD_MENU - if (show_lcd) lcd_pause_show_message(PAUSE_MESSAGE_UNLOAD, mode); - #endif + if (show_lcd) ui.pause_show_message(PAUSE_MESSAGE_UNLOAD, mode); // Retract filament unscaled_e_move(-(FILAMENT_UNLOAD_PURGE_RETRACT) * mix_multiplier, (PAUSE_PARK_RETRACT_FEEDRATE) * mix_multiplier); @@ -357,11 +348,8 @@ bool unload_filament(const float &unload_length, const bool show_lcd/*=false*/, planner.settings.retract_acceleration = saved_acceleration; #endif - // Disable E steppers for manual change - #if HAS_E_STEPPER_ENABLE - disable_e_stepper(active_extruder); - safe_delay(100); - #endif + // Disable the Extruder for manual change + disable_active_extruder(); return true; } @@ -383,9 +371,9 @@ bool unload_filament(const float &unload_length, const bool show_lcd/*=false*/, */ uint8_t did_pause_print = 0; -bool pause_print(const float &retract, const xyz_pos_t &park_point, const float &unload_length/*=0*/, const bool show_lcd/*=false*/ DXC_ARGS) { +bool pause_print(const_float_t retract, const xyz_pos_t &park_point, const bool show_lcd/*=false*/, const_float_t unload_length/*=0*/ DXC_ARGS) { DEBUG_SECTION(pp, "pause_print", true); - DEBUG_ECHOLNPAIR("... park.x:", park_point.x, " y:", park_point.y, " z:", park_point.z, " unloadlen:", unload_length, " showlcd:", int(show_lcd) DXC_SAY); + DEBUG_ECHOLNPAIR("... park.x:", park_point.x, " y:", park_point.y, " z:", park_point.z, " unloadlen:", unload_length, " showlcd:", show_lcd DXC_SAY); UNUSED(show_lcd); @@ -406,7 +394,8 @@ bool pause_print(const float &retract, const xyz_pos_t &park_point, const float // Pause the print job and timer #if ENABLED(SDSUPPORT) - if (IS_SD_PRINTING()) { + const bool was_sd_printing = IS_SD_PRINTING(); + if (was_sd_printing) { card.pauseSDPrint(); ++did_pause_print; // Indicate SD pause also } @@ -417,6 +406,15 @@ bool pause_print(const float &retract, const xyz_pos_t &park_point, const float // Save current position resume_position = current_position; + // Will the nozzle be parking? + const bool do_park = !axes_should_home(); + + #if ENABLED(POWER_LOSS_RECOVERY) + // Save PLR info in case the power goes out while parked + const float park_raise = do_park ? nozzle.park_mode_0_height(park_point.z) - current_position.z : POWER_LOSS_ZRAISE; + if (was_sd_printing && recovery.enabled) recovery.save(true, park_raise, do_park); + #endif + // Wait for buffered blocks to complete planner.synchronize(); @@ -430,26 +428,26 @@ bool pause_print(const float &retract, const xyz_pos_t &park_point, const float unscaled_e_move(retract, PAUSE_PARK_RETRACT_FEEDRATE); } - // Park the nozzle by moving up by z_lift and then moving to (x_pos, y_pos) - if (!axes_should_home()) - nozzle.park(0, park_point); + // If axes don't need to home then the nozzle can park + if (do_park) nozzle.park(0, park_point); // Park the nozzle by doing a Minimum Z Raise followed by an XY Move #if ENABLED(DUAL_X_CARRIAGE) const int8_t saved_ext = active_extruder; const bool saved_ext_dup_mode = extruder_duplication_enabled; - active_extruder = DXC_ext; - extruder_duplication_enabled = false; + set_duplication_enabled(false, DXC_ext); #endif - if (unload_length) // Unload the filament + // Unload the filament, if specified + if (unload_length) unload_filament(unload_length, show_lcd, PAUSE_MODE_CHANGE_FILAMENT); #if ENABLED(DUAL_X_CARRIAGE) - active_extruder = saved_ext; - extruder_duplication_enabled = saved_ext_dup_mode; - stepper.set_directions(); + set_duplication_enabled(saved_ext_dup_mode, saved_ext); #endif + // Disable the Extruder for manual change + disable_active_extruder(); + return true; } @@ -468,16 +466,16 @@ bool pause_print(const float &retract, const xyz_pos_t &park_point, const float void show_continue_prompt(const bool is_reload) { DEBUG_SECTION(scp, "pause_print", true); - DEBUG_ECHOLNPAIR("... is_reload:", int(is_reload)); + DEBUG_ECHOLNPAIR("... is_reload:", is_reload); - TERN_(HAS_LCD_MENU, lcd_pause_show_message(is_reload ? PAUSE_MESSAGE_INSERT : PAUSE_MESSAGE_WAITING)); + ui.pause_show_message(is_reload ? PAUSE_MESSAGE_INSERT : PAUSE_MESSAGE_WAITING); SERIAL_ECHO_START(); - serialprintPGM(is_reload ? PSTR(_PMSG(STR_FILAMENT_CHANGE_INSERT) "\n") : PSTR(_PMSG(STR_FILAMENT_CHANGE_WAIT) "\n")); + SERIAL_ECHOPGM_P(is_reload ? PSTR(_PMSG(STR_FILAMENT_CHANGE_INSERT) "\n") : PSTR(_PMSG(STR_FILAMENT_CHANGE_WAIT) "\n")); } void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep_count/*=0*/ DXC_ARGS) { DEBUG_SECTION(wfc, "wait_for_confirmation", true); - DEBUG_ECHOLNPAIR("... is_reload:", is_reload, " maxbeep:", int(max_beep_count) DXC_SAY); + DEBUG_ECHOLNPAIR("... is_reload:", is_reload, " maxbeep:", max_beep_count DXC_SAY); bool nozzle_timed_out = false; @@ -493,8 +491,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep #if ENABLED(DUAL_X_CARRIAGE) const int8_t saved_ext = active_extruder; const bool saved_ext_dup_mode = extruder_duplication_enabled; - active_extruder = DXC_ext; - extruder_duplication_enabled = false; + set_duplication_enabled(false, DXC_ext); #endif // Wait for filament insert by user and press button @@ -512,7 +509,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep // Wait for the user to press the button to re-heat the nozzle, then // re-heat the nozzle, re-show the continue prompt, restart idle timers, start over if (nozzle_timed_out) { - TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_HEAT)); + ui.pause_show_message(PAUSE_MESSAGE_HEAT); SERIAL_ECHO_MSG(_PMSG(STR_FILAMENT_CHANGE_HEAT)); TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT(MSG_HEATER_TIMEOUT), GET_TEXT(MSG_REHEAT))); @@ -538,8 +535,8 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep const millis_t nozzle_timeout = SEC_TO_MS(PAUSE_PARK_NOZZLE_TIMEOUT); HOTEND_LOOP() thermalManager.heater_idle[e].start(nozzle_timeout); - TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Reheat Done"), CONTINUE_STR)); - TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("Reheat finished."))); + TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT(MSG_REHEATDONE), CONTINUE_STR)); + TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_REHEATDONE))); wait_for_user = true; nozzle_timed_out = false; @@ -548,9 +545,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep idle_no_sleep(); } #if ENABLED(DUAL_X_CARRIAGE) - active_extruder = saved_ext; - extruder_duplication_enabled = saved_ext_dup_mode; - stepper.set_directions(); + set_duplication_enabled(saved_ext_dup_mode, saved_ext); #endif } @@ -574,9 +569,9 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep * - Send host action for resume, if configured * - Resume the current SD print job, if any */ -void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_length/*=0*/, const float &purge_length/*=ADVANCED_PAUSE_PURGE_LENGTH*/, const int8_t max_beep_count/*=0*/, int16_t targetTemp/*=0*/ DXC_ARGS) { +void resume_print(const_float_t slow_load_length/*=0*/, const_float_t fast_load_length/*=0*/, const_float_t purge_length/*=ADVANCED_PAUSE_PURGE_LENGTH*/, const int8_t max_beep_count/*=0*/, const celsius_t targetTemp/*=0*/ DXC_ARGS) { DEBUG_SECTION(rp, "resume_print", true); - DEBUG_ECHOLNPAIR("... slowlen:", slow_load_length, " fastlen:", fast_load_length, " purgelen:", purge_length, " maxbeep:", int(max_beep_count), " targetTemp:", targetTemp DXC_SAY); + DEBUG_ECHOLNPAIR("... slowlen:", slow_load_length, " fastlen:", fast_load_length, " purgelen:", purge_length, " maxbeep:", max_beep_count, " targetTemp:", targetTemp DXC_SAY); /* SERIAL_ECHOLNPAIR( @@ -596,9 +591,8 @@ void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_le thermalManager.reset_hotend_idle_timer(e); } - if (targetTemp > thermalManager.degTargetHotend(active_extruder)) { + if (targetTemp > thermalManager.degTargetHotend(active_extruder)) thermalManager.setTargetHotend(targetTemp, active_extruder); - } // Load the new filament load_filament(slow_load_length, fast_load_length, purge_length, max_beep_count, true, nozzle_timed_out, PAUSE_MODE_SAME DXC_PASS); @@ -608,7 +602,7 @@ void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_le thermalManager.wait_for_hotend(active_extruder, false); } - TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_RESUME)); + ui.pause_show_message(PAUSE_MESSAGE_RESUME); // Check Temperature before moving hotend ensure_safe_temperature(); @@ -617,11 +611,13 @@ void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_le unscaled_e_move(-(PAUSE_PARK_RETRACT_LENGTH), feedRate_t(PAUSE_PARK_RETRACT_FEEDRATE)); if (!axes_should_home()) { - // Move XY to starting position, then Z - do_blocking_move_to_xy(resume_position, feedRate_t(NOZZLE_PARK_XY_FEEDRATE)); + // Move XY back to saved position + destination.set(resume_position.x, resume_position.y, current_position.z, current_position.e); + prepare_internal_move_to_destination(NOZZLE_PARK_XY_FEEDRATE); - // Move Z_AXIS to saved position - do_blocking_move_to_z(resume_position.z, feedRate_t(NOZZLE_PARK_Z_FEEDRATE)); + // Move Z back to saved position + destination.z = resume_position.z; + prepare_internal_move_to_destination(NOZZLE_PARK_Z_FEEDRATE); } // Unretract @@ -644,10 +640,7 @@ void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_le // Set extruder to saved position planner.set_e_position_mm((destination.e = current_position.e = resume_position.e)); - // Write PLR now to update the z axis value - TERN_(POWER_LOSS_RECOVERY, if (recovery.enabled) recovery.save(true)); - - TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_STATUS)); + ui.pause_show_message(PAUSE_MESSAGE_STATUS); #ifdef ACTION_ON_RESUMED host_action_resumed(); @@ -659,8 +652,16 @@ void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_le TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_INFO, PSTR("Resuming"), DISMISS_STR)); + // Resume the print job timer if it was running + if (print_job_timer.isPaused()) print_job_timer.start(); + #if ENABLED(SDSUPPORT) - if (did_pause_print) { card.startFileprint(); --did_pause_print; } + if (did_pause_print) { + --did_pause_print; + card.startOrResumeFilePrinting(); + // Write PLR now to update the z axis value + TERN_(POWER_LOSS_RECOVERY, if (recovery.enabled) recovery.save(true)); + } #endif #if ENABLED(ADVANCED_PAUSE_FANS_PAUSE) && HAS_FAN @@ -669,10 +670,7 @@ void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_le TERN_(HAS_FILAMENT_SENSOR, runout.reset()); - // Resume the print job timer if it was running - if (print_job_timer.isPaused()) print_job_timer.start(); - - TERN_(HAS_DISPLAY, ui.reset_status()); + TERN_(HAS_STATUS_MESSAGE, ui.reset_status()); TERN_(HAS_LCD_MENU, ui.return_to_status()); } diff --git a/Marlin/src/feature/pause.h b/Marlin/src/feature/pause.h index 016b0ce3f7d9..d2c45e44a5df 100644 --- a/Marlin/src/feature/pause.h +++ b/Marlin/src/feature/pause.h @@ -59,7 +59,7 @@ enum PauseMessage : char { PAUSE_MESSAGE_HEATING }; -#if HAS_LCD_MENU +#if M600_PURGE_MORE_RESUMABLE enum PauseMenuResponse : char { PAUSE_RESPONSE_WAIT_FOR, PAUSE_RESPONSE_EXTRUDE_MORE, @@ -85,19 +85,52 @@ extern uint8_t did_pause_print; #define DXC_SAY #endif -bool pause_print(const float &retract, const xyz_pos_t &park_point, const float &unload_length=0, const bool show_lcd=false DXC_PARAMS); +// Pause the print. If unload_length is set, do a Filament Unload +bool pause_print( + const_float_t retract, // (mm) Retraction length + const xyz_pos_t &park_point, // Parking XY Position and Z Raise + const bool show_lcd=false, // Set LCD status messages? + const_float_t unload_length=0 // (mm) Filament Change Unload Length - 0 to skip + DXC_PARAMS // Dual-X-Carriage extruder index +); -void wait_for_confirmation(const bool is_reload=false, const int8_t max_beep_count=0 DXC_PARAMS); +void wait_for_confirmation( + const bool is_reload=false, // Reload Filament? (otherwise Resume Print) + const int8_t max_beep_count=0 // Beep alert for attention + DXC_PARAMS // Dual-X-Carriage extruder index +); -void resume_print(const float &slow_load_length=0, const float &fast_load_length=0, const float &extrude_length=ADVANCED_PAUSE_PURGE_LENGTH, const int8_t max_beep_count=0, int16_t targetTemp=0 DXC_PARAMS); +void resume_print( + const_float_t slow_load_length=0, // (mm) Slow Load Length for finishing move + const_float_t fast_load_length=0, // (mm) Fast Load Length for initial move + const_float_t extrude_length=ADVANCED_PAUSE_PURGE_LENGTH, // (mm) Purge length + const int8_t max_beep_count=0, // Beep alert for attention + const celsius_t targetTemp=0 // (°C) A target temperature for the hotend + DXC_PARAMS // Dual-X-Carriage extruder index +); -bool load_filament(const float &slow_load_length=0, const float &fast_load_length=0, const float &extrude_length=0, const int8_t max_beep_count=0, const bool show_lcd=false, - const bool pause_for_user=false, const PauseMode mode=PAUSE_MODE_PAUSE_PRINT DXC_PARAMS); +bool load_filament( + const_float_t slow_load_length=0, // (mm) Slow Load Length for finishing move + const_float_t fast_load_length=0, // (mm) Fast Load Length for initial move + const_float_t extrude_length=0, // (mm) Purge length + const int8_t max_beep_count=0, // Beep alert for attention + const bool show_lcd=false, // Set LCD status messages? + const bool pause_for_user=false, // Pause for user before returning? + const PauseMode mode=PAUSE_MODE_PAUSE_PRINT // Pause Mode to apply + DXC_PARAMS // Dual-X-Carriage extruder index +); -bool unload_filament(const float &unload_length, const bool show_lcd=false, const PauseMode mode=PAUSE_MODE_PAUSE_PRINT +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) - , const float &mix_multiplier=1.0 + , const_float_t mix_multiplier=1.0f // Extrusion multiplier (for a Mixing Extruder) #endif ); -#endif // ADVANCED_PAUSE_FEATURE +#else // !ADVANCED_PAUSE_FEATURE + + constexpr uint8_t did_pause_print = 0; + +#endif // !ADVANCED_PAUSE_FEATURE diff --git a/Marlin/src/feature/power.cpp b/Marlin/src/feature/power.cpp index 5be554e5e472..9b173d6ee706 100644 --- a/Marlin/src/feature/power.cpp +++ b/Marlin/src/feature/power.cpp @@ -33,6 +33,14 @@ #include "../module/stepper/indirection.h" #include "../MarlinCore.h" +#if ENABLED(PS_OFF_SOUND) + #include "../libs/buzzer.h" +#endif + +#if defined(PSU_POWERUP_GCODE) || defined(PSU_POWEROFF_GCODE) + #include "../gcode/gcode.h" +#endif + #if BOTH(USE_CONTROLLER_FAN, AUTO_POWER_CONTROLLERFAN) #include "controllerfan.h" #endif @@ -42,6 +50,9 @@ Power powerManager; millis_t Power::lastPowerOn; bool Power::is_power_needed() { + + if (printJobOngoing() || printingIsPaused()) return true; + #if ENABLED(AUTO_POWER_FANS) FANS_LOOP(i) if (thermalManager.fan_speed[i]) return true; #endif @@ -57,6 +68,9 @@ bool Power::is_power_needed() { if (TERN0(AUTO_POWER_CHAMBER_FAN, thermalManager.chamberfan_speed)) return true; + if (TERN0(AUTO_POWER_COOLER_FAN, thermalManager.coolerfan_speed)) + return true; + // If any of the drivers or the bed are enabled... if (X_ENABLE_READ() == X_ENABLE_ON || Y_ENABLE_READ() == Y_ENABLE_ON || Z_ENABLE_READ() == Z_ENABLE_ON #if HAS_X2_ENABLE @@ -74,44 +88,86 @@ bool Power::is_power_needed() { #endif ) return true; - HOTEND_LOOP() if (thermalManager.degTargetHotend(e) > 0 || thermalManager.temp_hotend[e].soft_pwm_amount > 0) return true; + #if HAS_HOTEND + HOTEND_LOOP() if (thermalManager.degTargetHotend(e) > 0 || thermalManager.temp_hotend[e].soft_pwm_amount > 0) return true; + #endif + if (TERN0(HAS_HEATED_BED, thermalManager.degTargetBed() > 0 || thermalManager.temp_bed.soft_pwm_amount > 0)) return true; #if HAS_HOTEND && AUTO_POWER_E_TEMP - HOTEND_LOOP() if (thermalManager.degHotend(e) >= AUTO_POWER_E_TEMP) return true; + HOTEND_LOOP() if (thermalManager.degHotend(e) >= (AUTO_POWER_E_TEMP)) return true; #endif #if HAS_HEATED_CHAMBER && AUTO_POWER_CHAMBER_TEMP - if (thermalManager.degChamber() >= AUTO_POWER_CHAMBER_TEMP) return true; + if (thermalManager.degChamber() >= (AUTO_POWER_CHAMBER_TEMP)) return true; + #endif + + #if HAS_COOLER && AUTO_POWER_COOLER_TEMP + if (thermalManager.degCooler() >= (AUTO_POWER_COOLER_TEMP)) return true; #endif return false; } -void Power::check() { +#ifndef POWER_TIMEOUT + #define POWER_TIMEOUT 0 +#endif + +void Power::check(const bool pause) { + static bool _pause = false; static millis_t nextPowerCheck = 0; - millis_t ms = millis(); - if (ELAPSED(ms, nextPowerCheck)) { - nextPowerCheck = ms + 2500UL; + const millis_t now = millis(); + #if POWER_TIMEOUT > 0 + if (pause != _pause) { + lastPowerOn = now + !now; + _pause = pause; + } + if (pause) return; + #endif + if (ELAPSED(now, nextPowerCheck)) { + nextPowerCheck = now + 2500UL; if (is_power_needed()) power_on(); - else if (!lastPowerOn || ELAPSED(ms, lastPowerOn + SEC_TO_MS(POWER_TIMEOUT))) + else if (!lastPowerOn || (POWER_TIMEOUT > 0 && ELAPSED(now, lastPowerOn + SEC_TO_MS(POWER_TIMEOUT)))) power_off(); } } void Power::power_on() { - lastPowerOn = millis(); + const millis_t now = millis(); + lastPowerOn = now + !now; if (!powersupply_on) { PSU_PIN_ON(); safe_delay(PSU_POWERUP_DELAY); restore_stepper_drivers(); TERN_(HAS_TRINAMIC_CONFIG, safe_delay(PSU_POWERUP_DELAY)); + #ifdef PSU_POWERUP_GCODE + GcodeSuite::process_subcommands_now_P(PSTR(PSU_POWERUP_GCODE)); + #endif } } void Power::power_off() { - if (powersupply_on) PSU_PIN_OFF(); + if (powersupply_on) { + #ifdef PSU_POWEROFF_GCODE + GcodeSuite::process_subcommands_now_P(PSTR(PSU_POWEROFF_GCODE)); + #endif + + #if ENABLED(PS_OFF_SOUND) + BUZZ(1000, 659); + #endif + + PSU_PIN_OFF(); + } +} + +void Power::power_off_soon() { + #if POWER_OFF_DELAY + lastPowerOn = millis() - SEC_TO_MS(POWER_TIMEOUT) + SEC_TO_MS(POWER_OFF_DELAY); + //if (!lastPowerOn) ++lastPowerOn; + #else + power_off(); + #endif } #endif // AUTO_POWER_CONTROL diff --git a/Marlin/src/feature/power.h b/Marlin/src/feature/power.h index 8b988907e6c6..bca5432946fb 100644 --- a/Marlin/src/feature/power.h +++ b/Marlin/src/feature/power.h @@ -29,9 +29,10 @@ class Power { public: - static void check(); + static void check(const bool pause); static void power_on(); static void power_off(); + static void power_off_soon(); private: static millis_t lastPowerOn; static bool is_power_needed(); diff --git a/Marlin/src/feature/power_monitor.cpp b/Marlin/src/feature/power_monitor.cpp index af31d156fc84..1937a54102a8 100644 --- a/Marlin/src/feature/power_monitor.cpp +++ b/Marlin/src/feature/power_monitor.cpp @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * Copyright (C) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. - * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm + * 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 @@ -26,8 +26,11 @@ #include "power_monitor.h" -#include "../lcd/ultralcd.h" -#include "../lcd/lcdprint.h" +#if HAS_LCD_MENU + #include "../lcd/marlinui.h" + #include "../lcd/lcdprint.h" +#endif + #include "../libs/numtostr.h" uint8_t PowerMonitor::flags; // = 0 @@ -54,7 +57,7 @@ PowerMonitor power_monitor; // Single instance - this calls the constructor } #endif - #if HAS_POWER_MONITOR_VREF + #if ENABLED(POWER_MONITOR_VOLTAGE) void PowerMonitor::draw_voltage() { const float volts = getVolts(); lcd_put_u8str(volts < 100 ? ftostr31ns(volts) : ui16tostr4rj((uint16_t)volts)); diff --git a/Marlin/src/feature/power_monitor.h b/Marlin/src/feature/power_monitor.h index a0eaf353f4c7..f6e0b292e30c 100644 --- a/Marlin/src/feature/power_monitor.h +++ b/Marlin/src/feature/power_monitor.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * Copyright (C) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. - * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm + * 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 @@ -23,7 +23,7 @@ #include "../inc/MarlinConfig.h" -#define PM_SAMPLE_RANGE 1024 +#define PM_SAMPLE_RANGE HAL_ADC_RANGE #define PM_K_VALUE 6 #define PM_K_SCALE 6 @@ -35,7 +35,7 @@ struct pm_lpf_t { filter_buf = filter_buf - (filter_buf >> K_VALUE) + (uint32_t(sample) << K_SCALE); } void capture() { - value = filter_buf * (SCALE * (1.0f / (1UL << (PM_K_VALUE + PM_K_SCALE)))) + (POWER_MONITOR_CURRENT_OFFSET); + value = filter_buf * (SCALE * (1.0f / (1UL << (PM_K_VALUE + PM_K_SCALE)))); } void reset(uint16_t reset_value = 0) { filter_buf = uint32_t(reset_value) << (K_VALUE + K_SCALE); @@ -69,19 +69,15 @@ class PowerMonitor { }; #if ENABLED(POWER_MONITOR_CURRENT) - FORCE_INLINE static float getAmps() { return amps.value; } + FORCE_INLINE static float getAmps() { return amps.value + (POWER_MONITOR_CURRENT_OFFSET); } void add_current_sample(const uint16_t value) { amps.add_sample(value); } #endif - #if HAS_POWER_MONITOR_VREF - #if ENABLED(POWER_MONITOR_VOLTAGE) - FORCE_INLINE static float getVolts() { return volts.value; } - #else - FORCE_INLINE static float getVolts() { return POWER_MONITOR_FIXED_VOLTAGE; } // using a specified fixed valtage as the voltage measurement - #endif - #if ENABLED(POWER_MONITOR_VOLTAGE) - void add_voltage_sample(const uint16_t value) { volts.add_sample(value); } - #endif + #if ENABLED(POWER_MONITOR_VOLTAGE) + FORCE_INLINE static float getVolts() { return volts.value + (POWER_MONITOR_VOLTAGE_OFFSET); } + void add_voltage_sample(const uint16_t value) { volts.add_sample(value); } + #else + FORCE_INLINE static float getVolts() { return POWER_MONITOR_FIXED_VOLTAGE; } #endif #if HAS_POWER_MONITOR_WATTS @@ -98,7 +94,7 @@ class PowerMonitor { FORCE_INLINE static void set_current_display(const bool b) { SET_BIT_TO(flags, PM_DISP_BIT_I, b); } FORCE_INLINE static void toggle_current_display() { TBI(flags, PM_DISP_BIT_I); } #endif - #if HAS_POWER_MONITOR_VREF + #if ENABLED(POWER_MONITOR_VOLTAGE) static void draw_voltage(); FORCE_INLINE static bool voltage_display_enabled() { return TEST(flags, PM_DISP_BIT_V); } FORCE_INLINE static void set_voltage_display(const bool b) { SET_BIT_TO(flags, PM_DISP_BIT_V, b); } diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index e4bc605bb55f..a512022320db 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -45,7 +45,7 @@ uint32_t PrintJobRecovery::cmd_sdpos, // = 0 #endif #include "../sd/cardreader.h" -#include "../lcd/ultralcd.h" +#include "../lcd/marlinui.h" #include "../gcode/queue.h" #include "../gcode/gcode.h" #include "../module/motion.h" @@ -66,9 +66,6 @@ PrintJobRecovery recovery; #ifndef POWER_LOSS_PURGE_LEN #define POWER_LOSS_PURGE_LEN 0 #endif -#ifndef POWER_LOSS_ZRAISE - #define POWER_LOSS_ZRAISE 2 // Move on loss with backup power, or on resume without it -#endif #if DISABLED(BACKUP_POWER_SUPPLY) #undef POWER_LOSS_RETRACT_LEN // No retract at outage without backup power @@ -140,14 +137,16 @@ void PrintJobRecovery::load() { * Set info fields that won't change */ void PrintJobRecovery::prepare() { - card.getAbsFilename(info.sd_filename); // SD filename + card.getAbsFilenameInCWD(info.sd_filename); // SD filename cmd_sdpos = 0; } /** * Save the current machine state to the power-loss recovery file */ -void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=0*/) { +void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=POWER_LOSS_ZRAISE*/, const bool raised/*=false*/) { + + // We don't check IS_SD_PRINTING here so a save may occur during a pause #if SAVE_INFO_INTERVAL_MS > 0 static millis_t next_save_ms; // = 0 @@ -180,17 +179,17 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=0*/ // Machine state info.current_position = current_position; + info.feedrate = uint16_t(MMS_TO_MMM(feedrate_mm_s)); info.zraise = zraise; + info.flag.raised = raised; // Was Z raised before power-off? + + TERN_(GCODE_REPEAT_MARKERS, info.stored_repeat = repeat); TERN_(HAS_HOME_OFFSET, info.home_offset = home_offset); TERN_(HAS_POSITION_SHIFT, info.position_shift = position_shift); - info.feedrate = uint16_t(feedrate_mm_s * 60.0f); - - #if HAS_MULTI_EXTRUDER - info.active_extruder = active_extruder; - #endif + TERN_(HAS_MULTI_EXTRUDER, info.active_extruder = active_extruder); #if DISABLED(NO_VOLUMETRICS) - info.volumetric_enabled = parser.volumetric_enabled; + info.flag.volumetric_enabled = parser.volumetric_enabled; #if HAS_MULTI_EXTRUDER for (int8_t e = 0; e < EXTRUDERS; e++) info.filament_size[e] = planner.filament_size[e]; #else @@ -198,18 +197,18 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=0*/ #endif #endif - #if EXTRUDERS - HOTEND_LOOP() info.target_temperature[e] = thermalManager.temp_hotend[e].target; + #if HAS_EXTRUDERS + HOTEND_LOOP() info.target_temperature[e] = thermalManager.degTargetHotend(e); #endif - TERN_(HAS_HEATED_BED, info.target_temperature_bed = thermalManager.temp_bed.target); + TERN_(HAS_HEATED_BED, info.target_temperature_bed = thermalManager.degTargetBed()); #if HAS_FAN COPY(info.fan_speed, thermalManager.fan_speed); #endif #if HAS_LEVELING - info.leveling = planner.leveling_active; + info.flag.leveling = planner.leveling_active; info.fade = TERN0(ENABLE_LEVELING_FADE_HEIGHT, planner.z_fade_height); #endif @@ -220,12 +219,12 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=0*/ info.retract_hop = fwretract.current_hop; #endif - // Relative axis modes - info.axis_relative = gcode.axis_relative; - // Elapsed print job time info.print_job_elapsed = print_job_timer.duration(); + // Relative axis modes + info.axis_relative = gcode.axis_relative; + // Misc. Marlin flags info.flag.dryrun = !!(marlin_debug_flags & MARLIN_DEBUG_DRYRUN); info.flag.allow_cold_extrusion = TERN0(PREVENT_COLD_EXTRUSION, thermalManager.allow_cold_extrude); @@ -238,7 +237,7 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=0*/ #if ENABLED(BACKUP_POWER_SUPPLY) - void PrintJobRecovery::retract_and_lift(const float &zraise) { + void PrintJobRecovery::retract_and_lift(const_float_t zraise) { #if POWER_LOSS_RETRACT_LEN || POWER_LOSS_ZRAISE gcode.set_relative_mode(true); // Use relative coordinates @@ -252,7 +251,7 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=0*/ // Raise the Z axis now if (zraise) { char cmd[20], str_1[16]; - sprintf_P(cmd, PSTR("G0 Z%s"), dtostrf(zraise, 1, 3, str_1)); + sprintf_P(cmd, PSTR("G0Z%s"), dtostrf(zraise, 1, 3, str_1)); gcode.process_subcommands_now(cmd); } #else @@ -288,8 +287,9 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=0*/ constexpr float zraise = 0; #endif - // Save, including the limited Z raise - if (IS_SD_PRINTING()) save(true, zraise); + // Save the current position, distance that Z was (or should be) raised, + // and a flag whether the raise was already done here. + if (IS_SD_PRINTING()) save(true, zraise, ENABLED(BACKUP_POWER_SUPPLY)); // Disable all heaters to reduce power loss thermalManager.disable_all_heaters(); @@ -340,46 +340,108 @@ void PrintJobRecovery::resume() { gcode.process_subcommands_now_P(PSTR("M420 S0 Z0")); #endif - // Reset E, raise Z, home XY... - #if Z_HOME_DIR > 0 + #if HAS_HEATED_BED + const celsius_t bt = info.target_temperature_bed; + if (bt) { + // Restore the bed temperature + sprintf_P(cmd, PSTR("M190S%i"), bt); + gcode.process_subcommands_now(cmd); + } + #endif - // If Z homing goes to max, just reset E and home all - gcode.process_subcommands_now_P(PSTR( - "G92.9 E0\n" - "G28R0" - )); + // Heat hotend enough to soften material + #if HAS_HOTEND + HOTEND_LOOP() { + const celsius_t et = _MAX(info.target_temperature[e], 180); + if (et) { + #if HAS_MULTI_HOTEND + sprintf_P(cmd, PSTR("T%iS"), e); + gcode.process_subcommands_now(cmd); + #endif + sprintf_P(cmd, PSTR("M109S%i"), et); + gcode.process_subcommands_now(cmd); + } + } + #endif - #else // "G92.9 E0 ..." + // Interpret the saved Z according to flags + const float z_print = info.current_position.z, + z_raised = z_print + info.zraise; - // Set Z to 0, raise Z by info.zraise, and Home (XY only for Cartesian) - // with no raise. (Only do simulated homing in Marlin Dev Mode.) + // + // Home the axes that can safely be homed, and + // establish the current position as best we can. + // - sprintf_P(cmd, PSTR("G92.9 E0 " - #if ENABLED(BACKUP_POWER_SUPPLY) - "Z%s" // Z was already raised at outage - #else - "Z0\nG1Z%s" // Set Z=0 and Raise Z now - #endif - ), - dtostrf(info.zraise, 1, 3, str_1) - ); + gcode.process_subcommands_now_P(PSTR("G92.9E0")); // Reset E to 0 + + #if Z_HOME_TO_MAX + + float z_now = z_raised; + + // If Z homing goes to max then just move back to the "raised" position + sprintf_P(cmd, PSTR( + "G28R0\n" // Home all axes (no raise) + "G1Z%sF1200" // Move Z down to (raised) height + ), dtostrf(z_now, 1, 3, str_1)); gcode.process_subcommands_now(cmd); - gcode.process_subcommands_now_P(PSTR( - "G28R0" // No raise during G28 - #if IS_CARTESIAN && DISABLED(POWER_LOSS_RECOVER_ZHOME) - "XY" // Don't home Z on Cartesian unless overridden - #endif - )); + #else + + #if ENABLED(POWER_LOSS_RECOVER_ZHOME) && defined(POWER_LOSS_ZHOME_POS) + #define HOMING_Z_DOWN 1 + #else + #define HOME_XY_ONLY 1 + #endif + + float z_now = info.flag.raised ? z_raised : z_print; + + // Reset E to 0 and set Z to the real position + #if HOME_XY_ONLY + sprintf_P(cmd, PSTR("G92.9Z%s"), dtostrf(z_now, 1, 3, str_1)); + gcode.process_subcommands_now(cmd); + #endif + + // Does Z need to be raised now? It should be raised before homing XY. + if (z_raised > z_now) { + z_now = z_raised; + sprintf_P(cmd, PSTR("G1Z%sF600"), dtostrf(z_now, 1, 3, str_1)); + gcode.process_subcommands_now(cmd); + } + + // Home XY with no Z raise, and also home Z here if Z isn't homing down below. + gcode.process_subcommands_now_P(PSTR("G28R0" TERN_(HOME_XY_ONLY, "XY"))); // No raise during G28 #endif - // Pretend that all axes are homed + #if HOMING_Z_DOWN + // Move to a safe XY position and home Z while avoiding the print. + constexpr xy_pos_t p = POWER_LOSS_ZHOME_POS; + sprintf_P(cmd, PSTR("G1X%sY%sF1000\nG28Z"), dtostrf(p.x, 1, 3, str_1), dtostrf(p.y, 1, 3, str_2)); + gcode.process_subcommands_now(cmd); + #endif + + // Mark all axes as having been homed (no effect on current_position) set_all_homed(); + #if HAS_LEVELING + // Restore Z fade and possibly re-enable bed leveling compensation. + // Leveling may already be enabled due to the ENABLE_LEVELING_AFTER_G28 option. + // TODO: Add a G28 parameter to leave leveling disabled. + sprintf_P(cmd, PSTR("M420S%cZ%s"), '0' + (char)info.flag.leveling, dtostrf(info.fade, 1, 1, str_1)); + gcode.process_subcommands_now(cmd); + + #if HOME_XY_ONLY + // The physical Z was adjusted at power-off so undo the M420S1 correction to Z with G92.9. + sprintf_P(cmd, PSTR("G92.9Z%s"), dtostrf(z_now, 1, 1, str_1)); + gcode.process_subcommands_now(cmd); + #endif + #endif + #if ENABLED(POWER_LOSS_RECOVER_ZHOME) - // Z has been homed so restore Z to ZsavedPos + POWER_LOSS_ZRAISE - sprintf_P(cmd, PSTR("G1 F500 Z%s"), dtostrf(info.current_position.z + POWER_LOSS_ZRAISE, 1, 3, str_1)); + // Z was homed down to the bed, so move up to the raised height. + z_now = z_raised; + sprintf_P(cmd, PSTR("G1Z%sF600"), dtostrf(z_now, 1, 3, str_1)); gcode.process_subcommands_now(cmd); #endif @@ -387,61 +449,54 @@ void PrintJobRecovery::resume() { #if DISABLED(NO_VOLUMETRICS) #if HAS_MULTI_EXTRUDER for (int8_t e = 0; e < EXTRUDERS; e++) { - sprintf_P(cmd, PSTR("M200 T%i D%s"), e, dtostrf(info.filament_size[e], 1, 3, str_1)); + sprintf_P(cmd, PSTR("M200T%iD%s"), e, dtostrf(info.filament_size[e], 1, 3, str_1)); gcode.process_subcommands_now(cmd); } - if (!info.volumetric_enabled) { - sprintf_P(cmd, PSTR("M200 T%i D0"), info.active_extruder); + if (!info.flag.volumetric_enabled) { + sprintf_P(cmd, PSTR("M200T%iD0"), info.active_extruder); gcode.process_subcommands_now(cmd); } #else - if (info.volumetric_enabled) { - sprintf_P(cmd, PSTR("M200 D%s"), dtostrf(info.filament_size[0], 1, 3, str_1)); + if (info.flag.volumetric_enabled) { + sprintf_P(cmd, PSTR("M200D%s"), dtostrf(info.filament_size[0], 1, 3, str_1)); gcode.process_subcommands_now(cmd); } #endif #endif - #if HAS_HEATED_BED - const int16_t bt = info.target_temperature_bed; - if (bt) { - // Restore the bed temperature - sprintf_P(cmd, PSTR("M190 S%i"), bt); - gcode.process_subcommands_now(cmd); - } - #endif - // Restore all hotend temperatures #if HAS_HOTEND HOTEND_LOOP() { - const int16_t et = info.target_temperature[e]; + const celsius_t et = info.target_temperature[e]; if (et) { #if HAS_MULTI_HOTEND - sprintf_P(cmd, PSTR("T%i S"), e); + sprintf_P(cmd, PSTR("T%iS"), e); gcode.process_subcommands_now(cmd); #endif - sprintf_P(cmd, PSTR("M109 S%i"), et); + sprintf_P(cmd, PSTR("M109S%i"), et); gcode.process_subcommands_now(cmd); } } #endif - // Select the previously active tool (with no_move) - #if HAS_MULTI_EXTRUDER + // Restore the previously active tool (with no_move) + #if HAS_MULTI_EXTRUDER || HAS_MULTI_HOTEND sprintf_P(cmd, PSTR("T%i S"), info.active_extruder); gcode.process_subcommands_now(cmd); #endif // Restore print cooling fan speeds - FANS_LOOP(i) { - uint8_t f = info.fan_speed[i]; - if (f) { - sprintf_P(cmd, PSTR("M106 P%i S%i"), i, f); - gcode.process_subcommands_now(cmd); + #if HAS_FAN + FANS_LOOP(i) { + const int f = info.fan_speed[i]; + if (f) { + sprintf_P(cmd, PSTR("M106P%iS%i"), i, f); + gcode.process_subcommands_now(cmd); + } } - } + #endif - // Restore retract and hop state + // Restore retract and hop state from an active `G10` command #if ENABLED(FWRETRACT) LOOP_L_N(e, EXTRUDERS) { if (info.retract[e] != 0.0) { @@ -452,27 +507,18 @@ void PrintJobRecovery::resume() { fwretract.current_hop = info.retract_hop; #endif - #if HAS_LEVELING - // Restore leveling state before 'G92 Z' to ensure - // the Z stepper count corresponds to the native Z. - if (info.fade || info.leveling) { - sprintf_P(cmd, PSTR("M420 S%i Z%s"), int(info.leveling), dtostrf(info.fade, 1, 1, str_1)); - gcode.process_subcommands_now(cmd); - } - #endif - #if ENABLED(GRADIENT_MIX) memcpy(&mixer.gradient, &info.gradient, sizeof(info.gradient)); #endif // Un-retract if there was a retract at outage - #if POWER_LOSS_RETRACT_LEN - gcode.process_subcommands_now_P(PSTR("G1 E" STRINGIFY(POWER_LOSS_RETRACT_LEN) " F3000")); + #if ENABLED(BACKUP_POWER_SUPPLY) && POWER_LOSS_RETRACT_LEN > 0 + gcode.process_subcommands_now_P(PSTR("G1E" STRINGIFY(POWER_LOSS_RETRACT_LEN) "F3000")); #endif - // Additional purge if configured + // Additional purge on resume if configured #if POWER_LOSS_PURGE_LEN - sprintf_P(cmd, PSTR("G1 E%d F200"), (POWER_LOSS_PURGE_LEN) + (POWER_LOSS_RETRACT_LEN)); + sprintf_P(cmd, PSTR("G1 E%d F3000"), (POWER_LOSS_PURGE_LEN) + (POWER_LOSS_RETRACT_LEN)); gcode.process_subcommands_now(cmd); #endif @@ -480,40 +526,35 @@ void PrintJobRecovery::resume() { gcode.process_subcommands_now_P(PSTR("G12")); #endif - // Move back to the saved XY - sprintf_P(cmd, PSTR("G1 X%s Y%s F3000"), + // Move back over to the saved XY + sprintf_P(cmd, PSTR("G1X%sY%sF3000"), dtostrf(info.current_position.x, 1, 3, str_1), dtostrf(info.current_position.y, 1, 3, str_2) ); gcode.process_subcommands_now(cmd); - // Move back to the saved Z - dtostrf(info.current_position.z, 1, 3, str_1); - #if Z_HOME_DIR > 0 || ENABLED(POWER_LOSS_RECOVER_ZHOME) - sprintf_P(cmd, PSTR("G1 Z%s F200"), str_1); - #else - gcode.process_subcommands_now_P(PSTR("G1 Z0 F200")); - sprintf_P(cmd, PSTR("G92.9 Z%s"), str_1); - #endif + // Move back down to the saved Z for printing + sprintf_P(cmd, PSTR("G1Z%sF600"), dtostrf(z_print, 1, 3, str_1)); gcode.process_subcommands_now(cmd); // Restore the feedrate - sprintf_P(cmd, PSTR("G1 F%d"), info.feedrate); + sprintf_P(cmd, PSTR("G1F%d"), info.feedrate); gcode.process_subcommands_now(cmd); // Restore E position with G92.9 - sprintf_P(cmd, PSTR("G92.9 E%s"), dtostrf(info.current_position.e, 1, 3, str_1)); + sprintf_P(cmd, PSTR("G92.9E%s"), dtostrf(info.current_position.e, 1, 3, str_1)); gcode.process_subcommands_now(cmd); - // Relative axis modes - gcode.axis_relative = info.axis_relative; - + TERN_(GCODE_REPEAT_MARKERS, repeat = info.stored_repeat); TERN_(HAS_HOME_OFFSET, home_offset = info.home_offset); TERN_(HAS_POSITION_SHIFT, position_shift = info.position_shift); #if HAS_HOME_OFFSET || HAS_POSITION_SHIFT - LOOP_XYZ(i) update_workspace_offset((AxisEnum)i); + LOOP_LINEAR_AXES(i) update_workspace_offset((AxisEnum)i); #endif + // Relative axis modes + gcode.axis_relative = info.axis_relative; + #if ENABLED(DEBUG_POWER_LOSS_RECOVERY) const uint8_t old_flags = marlin_debug_flags; marlin_debug_flags |= MARLIN_DEBUG_ECHO; @@ -524,10 +565,9 @@ void PrintJobRecovery::resume() { // Resume the SD file from the last position char *fn = info.sd_filename; - extern const char M23_STR[]; sprintf_P(cmd, M23_STR, fn); gcode.process_subcommands_now(cmd); - sprintf_P(cmd, PSTR("M24 S%ld T%ld"), resume_sdpos, info.print_job_elapsed); + sprintf_P(cmd, PSTR("M24S%ldT%ld"), resume_sdpos, info.print_job_elapsed); gcode.process_subcommands_now(cmd); TERN_(DEBUG_POWER_LOSS_RECOVERY, marlin_debug_flags = old_flags); @@ -536,22 +576,30 @@ void PrintJobRecovery::resume() { #if ENABLED(DEBUG_POWER_LOSS_RECOVERY) void PrintJobRecovery::debug(PGM_P const prefix) { - DEBUG_PRINT_P(prefix); - DEBUG_ECHOLNPAIR(" Job Recovery Info...\nvalid_head:", int(info.valid_head), " valid_foot:", int(info.valid_foot)); + DEBUG_ECHOPGM_P(prefix); + DEBUG_ECHOLNPAIR(" Job Recovery Info...\nvalid_head:", info.valid_head, " valid_foot:", info.valid_foot); if (info.valid_head) { if (info.valid_head == info.valid_foot) { DEBUG_ECHOPGM("current_position: "); - LOOP_XYZE(i) { + LOOP_LOGICAL_AXES(i) { if (i) DEBUG_CHAR(','); DEBUG_DECIMAL(info.current_position[i]); } DEBUG_EOL(); - DEBUG_ECHOLNPAIR("zraise: ", info.zraise); + DEBUG_ECHOLNPAIR("feedrate: ", info.feedrate); + + DEBUG_ECHOLNPAIR("zraise: ", info.zraise, " ", info.flag.raised ? "(before)" : ""); + + #if ENABLED(GCODE_REPEAT_MARKERS) + DEBUG_ECHOLNPAIR("repeat index: ", info.stored_repeat.index); + LOOP_L_N(i, info.stored_repeat.index) + DEBUG_ECHOLNPAIR("..... sdpos: ", info.stored_repeat.marker.sdpos, " count: ", info.stored_repeat.marker.counter); + #endif #if HAS_HOME_OFFSET DEBUG_ECHOPGM("home_offset: "); - LOOP_XYZ(i) { + LOOP_LINEAR_AXES(i) { if (i) DEBUG_CHAR(','); DEBUG_DECIMAL(info.home_offset[i]); } @@ -560,17 +608,21 @@ void PrintJobRecovery::resume() { #if HAS_POSITION_SHIFT DEBUG_ECHOPGM("position_shift: "); - LOOP_XYZ(i) { + LOOP_LINEAR_AXES(i) { if (i) DEBUG_CHAR(','); DEBUG_DECIMAL(info.position_shift[i]); } DEBUG_EOL(); #endif - DEBUG_ECHOLNPAIR("feedrate: ", info.feedrate); - #if HAS_MULTI_EXTRUDER - DEBUG_ECHOLNPAIR("active_extruder: ", int(info.active_extruder)); + DEBUG_ECHOLNPAIR("active_extruder: ", info.active_extruder); + #endif + + #if DISABLED(NO_VOLUMETRICS) + DEBUG_ECHOPGM("filament_size:"); + LOOP_L_N(i, EXTRUDERS) DEBUG_ECHOLNPAIR(" ", info.filament_size[i]); + DEBUG_EOL(); #endif #if HAS_HOTEND @@ -589,15 +641,16 @@ void PrintJobRecovery::resume() { #if HAS_FAN DEBUG_ECHOPGM("fan_speed: "); FANS_LOOP(i) { - DEBUG_ECHO(int(info.fan_speed[i])); + DEBUG_ECHO(info.fan_speed[i]); if (i < FAN_COUNT - 1) DEBUG_CHAR(','); } DEBUG_EOL(); #endif #if HAS_LEVELING - DEBUG_ECHOLNPAIR("leveling: ", int(info.leveling), " fade: ", info.fade); + DEBUG_ECHOLNPAIR("leveling: ", info.flag.leveling ? "ON" : "OFF", " fade: ", info.fade); #endif + #if ENABLED(FWRETRACT) DEBUG_ECHOPGM("retract: "); for (int8_t e = 0; e < EXTRUDERS; e++) { @@ -607,11 +660,28 @@ void PrintJobRecovery::resume() { DEBUG_EOL(); DEBUG_ECHOLNPAIR("retract_hop: ", info.retract_hop); #endif + + // Mixing extruder and gradient + #if BOTH(MIXING_EXTRUDER, GRADIENT_MIX) + DEBUG_ECHOLNPAIR("gradient: ", info.gradient.enabled ? "ON" : "OFF"); + #endif + DEBUG_ECHOLNPAIR("sd_filename: ", info.sd_filename); DEBUG_ECHOLNPAIR("sdpos: ", info.sdpos); DEBUG_ECHOLNPAIR("print_job_elapsed: ", info.print_job_elapsed); - DEBUG_ECHOLNPAIR("dryrun: ", int(info.flag.dryrun)); - DEBUG_ECHOLNPAIR("allow_cold_extrusion: ", int(info.flag.allow_cold_extrusion)); + + DEBUG_ECHOPGM("axis_relative:"); + if (TEST(info.axis_relative, REL_X)) DEBUG_ECHOPGM(" REL_X"); + if (TEST(info.axis_relative, REL_Y)) DEBUG_ECHOPGM(" REL_Y"); + if (TEST(info.axis_relative, REL_Z)) DEBUG_ECHOPGM(" REL_Z"); + if (TEST(info.axis_relative, REL_E)) DEBUG_ECHOPGM(" REL_E"); + if (TEST(info.axis_relative, E_MODE_ABS)) DEBUG_ECHOPGM(" E_MODE_ABS"); + if (TEST(info.axis_relative, E_MODE_REL)) DEBUG_ECHOPGM(" E_MODE_REL"); + DEBUG_EOL(); + + DEBUG_ECHOLNPAIR("flag.dryrun: ", AS_DIGIT(info.flag.dryrun)); + DEBUG_ECHOLNPAIR("flag.allow_cold_extrusion: ", AS_DIGIT(info.flag.allow_cold_extrusion)); + DEBUG_ECHOLNPAIR("flag.volumetric_enabled: ", AS_DIGIT(info.flag.volumetric_enabled)); } else DEBUG_ECHOLNPGM("INVALID DATA"); diff --git a/Marlin/src/feature/powerloss.h b/Marlin/src/feature/powerloss.h index e31b2ec915c3..d3ecc6c9cc0b 100644 --- a/Marlin/src/feature/powerloss.h +++ b/Marlin/src/feature/powerloss.h @@ -30,6 +30,10 @@ #include "../inc/MarlinConfig.h" +#if ENABLED(GCODE_REPEAT_MARKERS) + #include "../feature/repeat.h" +#endif + #if ENABLED(MIXING_EXTRUDER) #include "../feature/mixing.h" #endif @@ -38,6 +42,10 @@ #define POWER_LOSS_STATE HIGH #endif +#ifndef POWER_LOSS_ZRAISE + #define POWER_LOSS_ZRAISE 2 +#endif + //#define DEBUG_POWER_LOSS_RECOVERY //#define SAVE_EACH_CMD_MODE //#define SAVE_INFO_INTERVAL_MS 0 @@ -47,40 +55,40 @@ typedef struct { // Machine state xyze_pos_t current_position; + uint16_t feedrate; + float zraise; + // Repeat information + #if ENABLED(GCODE_REPEAT_MARKERS) + Repeat stored_repeat; + #endif + #if HAS_HOME_OFFSET xyz_pos_t home_offset; #endif #if HAS_POSITION_SHIFT xyz_pos_t position_shift; #endif - - uint16_t feedrate; - #if HAS_MULTI_EXTRUDER uint8_t active_extruder; #endif #if DISABLED(NO_VOLUMETRICS) - bool volumetric_enabled; float filament_size[EXTRUDERS]; #endif #if HAS_HOTEND - int16_t target_temperature[HOTENDS]; + celsius_t target_temperature[HOTENDS]; #endif - #if HAS_HEATED_BED - int16_t target_temperature_bed; + celsius_t target_temperature_bed; #endif - #if HAS_FAN uint8_t fan_speed[FAN_COUNT]; #endif #if HAS_LEVELING - bool leveling; float fade; #endif @@ -97,9 +105,6 @@ typedef struct { #endif #endif - // Relative axis modes - uint8_t axis_relative; - // SD Filename and position char sd_filename[MAXPATHNAMELENGTH]; volatile uint32_t sdpos; @@ -107,10 +112,20 @@ typedef struct { // Job elapsed time millis_t print_job_elapsed; + // Relative axis modes + uint8_t axis_relative; + // Misc. Marlin flags struct { + bool raised:1; // Raised before saved bool dryrun:1; // M111 S8 bool allow_cold_extrusion:1; // M302 P1 + #if HAS_LEVELING + bool leveling:1; // M420 S + #endif + #if DISABLED(NO_VOLUMETRICS) + bool volumetric_enabled:1; // M200 S D + #endif } flag; uint8_t valid_foot; @@ -139,12 +154,10 @@ class PrintJobRecovery { static inline void setup() { #if PIN_EXISTS(POWER_LOSS) - #if ENABLED(POWER_LOSS_PULL) - #if POWER_LOSS_STATE == LOW - SET_INPUT_PULLUP(POWER_LOSS_PIN); - #else - SET_INPUT_PULLDOWN(POWER_LOSS_PIN); - #endif + #if ENABLED(POWER_LOSS_PULLUP) + SET_INPUT_PULLUP(POWER_LOSS_PIN); + #elif ENABLED(POWER_LOSS_PULLDOWN) + SET_INPUT_PULLDOWN(POWER_LOSS_PIN); #else SET_INPUT(POWER_LOSS_PIN); #endif @@ -167,15 +180,21 @@ class PrintJobRecovery { static void resume(); static void purge(); - static inline void cancel() { purge(); card.autostart_index = 0; } + static inline void cancel() { purge(); IF_DISABLED(NO_SD_AUTOSTART, card.autofile_begin()); } static void load(); - static void save(const bool force=ENABLED(SAVE_EACH_CMD_MODE), const float zraise=0); + static void save(const bool force=ENABLED(SAVE_EACH_CMD_MODE), const float zraise=POWER_LOSS_ZRAISE, const bool raised=false); #if PIN_EXISTS(POWER_LOSS) static inline void outage() { - if (enabled && READ(POWER_LOSS_PIN) == POWER_LOSS_STATE) - _outage(); + static constexpr uint8_t OUTAGE_THRESHOLD = 3; + static uint8_t outage_counter = 0; + if (enabled && READ(POWER_LOSS_PIN) == POWER_LOSS_STATE) { + outage_counter++; + if (outage_counter >= OUTAGE_THRESHOLD) _outage(); + } + else + outage_counter = 0; } #endif @@ -194,7 +213,7 @@ class PrintJobRecovery { static void write(); #if ENABLED(BACKUP_POWER_SUPPLY) - static void retract_and_lift(const float &zraise); + static void retract_and_lift(const_float_t zraise); #endif #if PIN_EXISTS(POWER_LOSS) diff --git a/Marlin/src/feature/probe_temp_comp.cpp b/Marlin/src/feature/probe_temp_comp.cpp index af8039d8b110..e39896d4dc09 100644 --- a/Marlin/src/feature/probe_temp_comp.cpp +++ b/Marlin/src/feature/probe_temp_comp.cpp @@ -52,7 +52,7 @@ const temp_calib_t ProbeTempComp::cali_info[TSI_COUNT] = { constexpr xyz_pos_t ProbeTempComp::park_point; constexpr xy_pos_t ProbeTempComp::measure_point; -constexpr int ProbeTempComp::probe_calib_bed_temp; +constexpr celsius_t ProbeTempComp::probe_calib_bed_temp; uint8_t ProbeTempComp::calib_idx; // = 0 float ProbeTempComp::init_measurement; // = 0.0 @@ -71,9 +71,9 @@ bool ProbeTempComp::set_offset(const TempSensorID tsi, const uint8_t idx, const void ProbeTempComp::print_offsets() { LOOP_L_N(s, TSI_COUNT) { - float temp = cali_info[s].start_temp; + celsius_t temp = cali_info[s].start_temp; for (int16_t i = -1; i < cali_info[s].measurements; ++i) { - serialprintPGM(s == TSI_BED ? PSTR("Bed") : + SERIAL_ECHOPGM_P(s == TSI_BED ? PSTR("Bed") : #if ENABLED(USE_TEMP_EXT_COMPENSATION) s == TSI_EXT ? PSTR("Extruder") : #endif @@ -88,12 +88,12 @@ void ProbeTempComp::print_offsets() { } } -void ProbeTempComp::prepare_new_calibration(const float &init_meas_z) { +void ProbeTempComp::prepare_new_calibration(const_float_t init_meas_z) { calib_idx = 0; init_measurement = init_meas_z; } -void ProbeTempComp::push_back_new_measurement(const TempSensorID tsi, const float &meas_z) { +void ProbeTempComp::push_back_new_measurement(const TempSensorID tsi, const_float_t meas_z) { switch (tsi) { case TSI_PROBE: case TSI_BED: @@ -114,8 +114,8 @@ bool ProbeTempComp::finish_calibration(const TempSensorID tsi) { } const uint8_t measurements = cali_info[tsi].measurements; - const float start_temp = cali_info[tsi].start_temp, - res_temp = cali_info[tsi].temp_res; + const celsius_t start_temp = cali_info[tsi].start_temp, + res_temp = cali_info[tsi].temp_res; int16_t * const data = sensor_z_offsets[tsi]; // Extrapolate @@ -126,7 +126,7 @@ bool ProbeTempComp::finish_calibration(const TempSensorID tsi) { SERIAL_ECHOPGM("Applying linear extrapolation"); calib_idx--; for (; calib_idx < measurements; ++calib_idx) { - const float temp = start_temp + float(calib_idx) * res_temp; + const celsius_float_t temp = start_temp + float(calib_idx) * res_temp; data[calib_idx] = static_cast(k * temp + d); } } @@ -143,13 +143,13 @@ bool ProbeTempComp::finish_calibration(const TempSensorID tsi) { // Sanity check for (calib_idx = 0; calib_idx < measurements; ++calib_idx) { // Restrict the max. offset - if (abs(data[calib_idx]) > 2000) { + if (ABS(data[calib_idx]) > 2000) { SERIAL_ECHOLNPGM("!Invalid Z-offset detected (0-2)."); clear_offsets(tsi); return false; } // Restrict the max. offset difference between two probings - if (calib_idx > 0 && abs(data[calib_idx - 1] - data[calib_idx]) > 800) { + if (calib_idx > 0 && ABS(data[calib_idx - 1] - data[calib_idx]) > 800) { SERIAL_ECHOLNPGM("!Invalid Z-offset between two probings detected (0-0.8)."); clear_offsets(TSI_PROBE); return false; @@ -159,29 +159,29 @@ bool ProbeTempComp::finish_calibration(const TempSensorID tsi) { return true; } -void ProbeTempComp::compensate_measurement(const TempSensorID tsi, const float &temp, float &meas_z) { +void ProbeTempComp::compensate_measurement(const TempSensorID tsi, const celsius_t temp, float &meas_z) { if (WITHIN(temp, cali_info[tsi].start_temp, cali_info[tsi].end_temp)) meas_z -= get_offset_for_temperature(tsi, temp); } -float ProbeTempComp::get_offset_for_temperature(const TempSensorID tsi, const float &temp) { +float ProbeTempComp::get_offset_for_temperature(const TempSensorID tsi, const celsius_t temp) { const uint8_t measurements = cali_info[tsi].measurements; - const float start_temp = cali_info[tsi].start_temp, - res_temp = cali_info[tsi].temp_res; + const celsius_t start_temp = cali_info[tsi].start_temp, + res_temp = cali_info[tsi].temp_res; const int16_t * const data = sensor_z_offsets[tsi]; - auto point = [&](uint8_t i) { - return xy_float_t({start_temp + i*res_temp, static_cast(data[i])}); + auto point = [&](uint8_t i) -> xy_float_t { + return xy_float_t({ static_cast(start_temp) + i * res_temp, static_cast(data[i]) }); }; - auto linear_interp = [](float x, xy_float_t p1, xy_float_t p2) { + auto linear_interp = [](const_float_t x, xy_float_t p1, xy_float_t p2) { return (p2.y - p1.y) / (p2.x - p2.y) * (x - p1.x) + p1.y; }; // Linear interpolation uint8_t idx = static_cast((temp - start_temp) / res_temp); - // offset in um + // offset in µm float offset = 0.0f; #if !defined(PTC_LINEAR_EXTRAPOLATION) || PTC_LINEAR_EXTRAPOLATION <= 0 @@ -207,17 +207,18 @@ bool ProbeTempComp::linear_regression(const TempSensorID tsi, float &k, float &d if (!WITHIN(calib_idx, 2, cali_info[tsi].measurements)) return false; - const float start_temp = cali_info[tsi].start_temp, - res_temp = cali_info[tsi].temp_res; + const celsius_t start_temp = cali_info[tsi].start_temp, + res_temp = cali_info[tsi].temp_res; const int16_t * const data = sensor_z_offsets[tsi]; float sum_x = start_temp, sum_x2 = sq(start_temp), sum_xy = 0, sum_y = 0; + float xi = static_cast(start_temp); LOOP_L_N(i, calib_idx) { - const float xi = start_temp + (i + 1) * res_temp, - yi = static_cast(data[i]); + const float yi = static_cast(data[i]); + xi += res_temp; sum_x += xi; sum_x2 += sq(xi); sum_xy += xi * yi; diff --git a/Marlin/src/feature/probe_temp_comp.h b/Marlin/src/feature/probe_temp_comp.h index 626dd87f945f..f5f922410c17 100644 --- a/Marlin/src/feature/probe_temp_comp.h +++ b/Marlin/src/feature/probe_temp_comp.h @@ -34,9 +34,9 @@ enum TempSensorID : uint8_t { typedef struct { uint8_t measurements; // Max. number of measurements to be stored (35 - 80°C) - float temp_res, // Resolution in °C between measurements - start_temp, // Base measurement; z-offset == 0 - end_temp; + celsius_t temp_res, // Resolution in °C between measurements + start_temp, // Base measurement; z-offset == 0 + end_temp; } temp_calib_t; /** @@ -47,44 +47,44 @@ typedef struct { // Probe temperature calibration constants #ifndef PTC_SAMPLE_COUNT - #define PTC_SAMPLE_COUNT 10U + #define PTC_SAMPLE_COUNT 10 #endif #ifndef PTC_SAMPLE_RES - #define PTC_SAMPLE_RES 5.0f + #define PTC_SAMPLE_RES 5 #endif #ifndef PTC_SAMPLE_START - #define PTC_SAMPLE_START 30.0f + #define PTC_SAMPLE_START 30 #endif -#define PTC_SAMPLE_END ((PTC_SAMPLE_START) + (PTC_SAMPLE_COUNT) * (PTC_SAMPLE_RES)) +#define PTC_SAMPLE_END (PTC_SAMPLE_START + (PTC_SAMPLE_COUNT) * PTC_SAMPLE_RES) // Bed temperature calibration constants #ifndef BTC_PROBE_TEMP - #define BTC_PROBE_TEMP 30.0f + #define BTC_PROBE_TEMP 30 #endif #ifndef BTC_SAMPLE_COUNT - #define BTC_SAMPLE_COUNT 10U + #define BTC_SAMPLE_COUNT 10 #endif -#ifndef BTC_SAMPLE_STEP - #define BTC_SAMPLE_RES 5.0f +#ifndef BTC_SAMPLE_RES + #define BTC_SAMPLE_RES 5 #endif #ifndef BTC_SAMPLE_START - #define BTC_SAMPLE_START 60.0f + #define BTC_SAMPLE_START 60 #endif -#define BTC_SAMPLE_END ((BTC_SAMPLE_START) + (BTC_SAMPLE_COUNT) * (BTC_SAMPLE_RES)) +#define BTC_SAMPLE_END (BTC_SAMPLE_START + (BTC_SAMPLE_COUNT) * BTC_SAMPLE_RES) #ifndef PTC_PROBE_HEATING_OFFSET #define PTC_PROBE_HEATING_OFFSET 0.5f #endif #ifndef PTC_PROBE_RAISE - #define PTC_PROBE_RAISE 10.0f + #define PTC_PROBE_RAISE 10 #endif static constexpr temp_calib_t cali_info_init[TSI_COUNT] = { - { PTC_SAMPLE_COUNT, PTC_SAMPLE_RES, PTC_SAMPLE_START, PTC_SAMPLE_END }, // Probe - { BTC_SAMPLE_COUNT, BTC_SAMPLE_RES, BTC_SAMPLE_START, BTC_SAMPLE_END }, // Bed + { PTC_SAMPLE_COUNT, PTC_SAMPLE_RES, PTC_SAMPLE_START, PTC_SAMPLE_END }, // Probe + { BTC_SAMPLE_COUNT, BTC_SAMPLE_RES, BTC_SAMPLE_START, BTC_SAMPLE_END }, // Bed #if ENABLED(USE_TEMP_EXT_COMPENSATION) - { 20, 5, 180, 180 + 5 * 20 } // Extruder + { 20, 5, 180, 180 + 5 * 20 } // Extruder #endif }; @@ -100,8 +100,8 @@ class ProbeTempComp { static constexpr xy_pos_t measure_point = PTC_PROBE_POS; // Coordinates to probe //measure_point = { 12.0f, 7.3f }; // Coordinates for the MK52 magnetic heatbed - static constexpr int probe_calib_bed_temp = BED_MAX_TARGET, // Bed temperature while calibrating probe - bed_calib_probe_temp = BTC_PROBE_TEMP; // Probe temperature while calibrating bed + static constexpr celsius_t probe_calib_bed_temp = BED_MAX_TARGET, // Bed temperature while calibrating probe + bed_calib_probe_temp = BTC_PROBE_TEMP; // Probe temperature while calibrating bed static int16_t *sensor_z_offsets[TSI_COUNT], z_offsets_probe[cali_info_init[TSI_PROBE].measurements], // (µm) @@ -121,10 +121,10 @@ class ProbeTempComp { } static bool set_offset(const TempSensorID tsi, const uint8_t idx, const int16_t offset); static void print_offsets(); - static void prepare_new_calibration(const float &init_meas_z); - static void push_back_new_measurement(const TempSensorID tsi, const float &meas_z); + static void prepare_new_calibration(const_float_t init_meas_z); + static void push_back_new_measurement(const TempSensorID tsi, const_float_t meas_z); static bool finish_calibration(const TempSensorID tsi); - static void compensate_measurement(const TempSensorID tsi, const float &temp, float &meas_z); + static void compensate_measurement(const TempSensorID tsi, const celsius_t temp, float &meas_z); private: static uint8_t calib_idx; @@ -135,7 +135,7 @@ class ProbeTempComp { */ static float init_measurement; - static float get_offset_for_temperature(const TempSensorID tsi, const float &temp); + static float get_offset_for_temperature(const TempSensorID tsi, const celsius_t temp); /** * Fit a linear function in measured temperature offsets diff --git a/Marlin/src/feature/repeat.cpp b/Marlin/src/feature/repeat.cpp new file mode 100644 index 000000000000..11e4dd6a93bb --- /dev/null +++ b/Marlin/src/feature/repeat.cpp @@ -0,0 +1,81 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../inc/MarlinConfig.h" + +#if ENABLED(GCODE_REPEAT_MARKERS) + +//#define DEBUG_GCODE_REPEAT_MARKERS + +#include "repeat.h" + +#include "../gcode/gcode.h" +#include "../sd/cardreader.h" + +#define DEBUG_OUT ENABLED(DEBUG_GCODE_REPEAT_MARKERS) +#include "../core/debug_out.h" + +repeat_marker_t Repeat::marker[MAX_REPEAT_NESTING]; +uint8_t Repeat::index; + +void Repeat::add_marker(const uint32_t sdpos, const uint16_t count) { + if (index >= MAX_REPEAT_NESTING) + SERIAL_ECHO_MSG("!Too many markers."); + else { + marker[index].sdpos = sdpos; + marker[index].counter = count ?: -1; + index++; + DEBUG_ECHOLNPAIR("Add Marker ", index, " at ", sdpos, " (", count, ")"); + } +} + +void Repeat::loop() { + if (!index) // No marker? + SERIAL_ECHO_MSG("!No marker set."); // Inform the user. + else { + const uint8_t ind = index - 1; // Active marker's index + if (!marker[ind].counter) { // Did its counter run out? + DEBUG_ECHOLNPAIR("Pass Marker ", index); + index--; // Carry on. Previous marker on the next 'M808'. + } + else { + card.setIndex(marker[ind].sdpos); // Loop back to the marker. + if (marker[ind].counter > 0) // Ignore a negative (or zero) counter. + --marker[ind].counter; // Decrement the counter. If zero this 'M808' will be skipped next time. + DEBUG_ECHOLNPAIR("Goto Marker ", index, " at ", marker[ind].sdpos, " (", marker[ind].counter, ")"); + } + } +} + +void Repeat::cancel() { LOOP_L_N(i, index) marker[i].counter = 0; } + +void Repeat::early_parse_M808(char * const cmd) { + if (is_command_M808(cmd)) { + DEBUG_ECHOLNPAIR("Parsing \"", cmd, "\""); + parser.parse(cmd); + if (parser.seen('L')) + add_marker(card.getIndex(), parser.value_ushort()); + else + Repeat::loop(); + } +} + +#endif // GCODE_REPEAT_MARKERS diff --git a/Marlin/src/feature/repeat.h b/Marlin/src/feature/repeat.h new file mode 100644 index 000000000000..0f4d9425b768 --- /dev/null +++ b/Marlin/src/feature/repeat.h @@ -0,0 +1,53 @@ +/** + * 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 + +#include "../inc/MarlinConfigPre.h" +#include "../gcode/parser.h" + +#include + +#define MAX_REPEAT_NESTING 10 + +typedef struct { + uint32_t sdpos; // The repeat file position + int16_t counter; // The counter for looping +} repeat_marker_t; + +class Repeat { +private: + static repeat_marker_t marker[MAX_REPEAT_NESTING]; + static uint8_t index; +public: + static inline void reset() { index = 0; } + static inline bool is_active() { + LOOP_L_N(i, index) 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]); } + static void early_parse_M808(char * const cmd); + static void add_marker(const uint32_t sdpos, const uint16_t count); + static void loop(); + static void cancel(); +}; + +extern Repeat repeat; diff --git a/Marlin/src/feature/runout.cpp b/Marlin/src/feature/runout.cpp index 71f31f214559..531ca1081f0b 100644 --- a/Marlin/src/feature/runout.cpp +++ b/Marlin/src/feature/runout.cpp @@ -40,24 +40,26 @@ bool FilamentMonitorBase::enabled = true, #endif #if ENABLED(TOOLCHANGE_MIGRATION_FEATURE) - //#define DEBUG_TOOLCHANGE_MIGRATION_FEATURE #include "../module/tool_change.h" + #define DEBUG_OUT ENABLED(DEBUG_TOOLCHANGE_MIGRATION_FEATURE) + #include "../core/debug_out.h" #endif #if HAS_FILAMENT_RUNOUT_DISTANCE float RunoutResponseDelayed::runout_distance_mm = FILAMENT_RUNOUT_DISTANCE_MM; - volatile float RunoutResponseDelayed::runout_mm_countdown[EXTRUDERS]; + volatile float RunoutResponseDelayed::runout_mm_countdown[NUM_RUNOUT_SENSORS]; #if ENABLED(FILAMENT_MOTION_SENSOR) uint8_t FilamentSensorEncoder::motion_detected; #endif #else - int8_t RunoutResponseDebounced::runout_count; // = 0 + int8_t RunoutResponseDebounced::runout_count[NUM_RUNOUT_SENSORS]; // = 0 #endif // // Filament Runout event handler // #include "../MarlinCore.h" +#include "../feature/pause.h" #include "../gcode/queue.h" #if ENABLED(HOST_ACTION_COMMANDS) @@ -68,33 +70,25 @@ bool FilamentMonitorBase::enabled = true, #include "../lcd/extui/ui_api.h" #endif -void event_filament_runout() { +void event_filament_runout(const uint8_t extruder) { - if (TERN0(ADVANCED_PAUSE_FEATURE, did_pause_print)) return; // Action already in progress. Purge triggered repeated runout. + if (did_pause_print) return; // Action already in progress. Purge triggered repeated runout. #if ENABLED(TOOLCHANGE_MIGRATION_FEATURE) if (migration.in_progress) { - #if ENABLED(DEBUG_TOOLCHANGE_MIGRATION_FEATURE) - SERIAL_ECHOLN("Migration Already In Progress"); - #endif + DEBUG_ECHOLNPGM("Migration Already In Progress"); return; // Action already in progress. Purge triggered repeated runout. } if (migration.automode) { - #if ENABLED(DEBUG_TOOLCHANGE_MIGRATION_FEATURE) - SERIAL_ECHOLN("Migration Starting"); - #endif + DEBUG_ECHOLNPGM("Migration Starting"); if (extruder_migration()) return; } #endif - TERN_(EXTENSIBLE_UI, ExtUI::onFilamentRunout(ExtUI::getActiveTool())); + TERN_(EXTENSIBLE_UI, ExtUI::onFilamentRunout(ExtUI::getTool(extruder))); - #if EITHER(HOST_PROMPT_SUPPORT, HOST_ACTION_COMMANDS) - const char tool = '0' - #if NUM_RUNOUT_SENSORS > 1 - + active_extruder - #endif - ; + #if ANY(HOST_PROMPT_SUPPORT, HOST_ACTION_COMMANDS, MULTI_FILAMENT_SENSOR) + const char tool = '0' + TERN0(MULTI_FILAMENT_SENSOR, extruder); #endif //action:out_of_filament @@ -109,9 +103,7 @@ void event_filament_runout() { if (run_runout_script && ( strstr(FILAMENT_RUNOUT_SCRIPT, "M600") || strstr(FILAMENT_RUNOUT_SCRIPT, "M125") - #if ENABLED(ADVANCED_PAUSE_FEATURE) - || strstr(FILAMENT_RUNOUT_SCRIPT, "M25") - #endif + || TERN0(ADVANCED_PAUSE_FEATURE, strstr(FILAMENT_RUNOUT_SCRIPT, "M25")) ) ) { host_action_paused(false); @@ -132,8 +124,22 @@ void event_filament_runout() { SERIAL_EOL(); #endif // HOST_ACTION_COMMANDS - if (run_runout_script) - queue.inject_P(PSTR(FILAMENT_RUNOUT_SCRIPT)); + if (run_runout_script) { + #if MULTI_FILAMENT_SENSOR + char script[strlen(FILAMENT_RUNOUT_SCRIPT) + 1]; + sprintf_P(script, PSTR(FILAMENT_RUNOUT_SCRIPT), tool); + #if ENABLED(FILAMENT_RUNOUT_SENSOR_DEBUG) + SERIAL_ECHOLNPAIR("Runout Command: ", script); + #endif + queue.inject(script); + #else + #if ENABLED(FILAMENT_RUNOUT_SENSOR_DEBUG) + SERIAL_ECHOPGM("Runout Command: "); + SERIAL_ECHOLNPGM(FILAMENT_RUNOUT_SCRIPT); + #endif + queue.inject_P(PSTR(FILAMENT_RUNOUT_SCRIPT)); + #endif + } } #endif // HAS_FILAMENT_SENSOR diff --git a/Marlin/src/feature/runout.h b/Marlin/src/feature/runout.h index a7f836684949..93eb59c2a518 100644 --- a/Marlin/src/feature/runout.h +++ b/Marlin/src/feature/runout.h @@ -30,6 +30,7 @@ #include "../module/planner.h" #include "../module/stepper.h" // for block_t #include "../gcode/queue.h" +#include "../feature/pause.h" #include "../inc/MarlinConfig.h" @@ -37,16 +38,12 @@ #include "../lcd/extui/ui_api.h" #endif -#if ENABLED(ADVANCED_PAUSE_FEATURE) - #include "pause.h" -#endif - //#define FILAMENT_RUNOUT_SENSOR_DEBUG #ifndef FILAMENT_RUNOUT_THRESHOLD #define FILAMENT_RUNOUT_THRESHOLD 5 #endif -void event_filament_runout(); +void event_filament_runout(const uint8_t extruder); template class TFilamentMonitor; @@ -104,12 +101,12 @@ class TFilamentMonitor : public FilamentMonitorBase { #if HAS_FILAMENT_RUNOUT_DISTANCE static inline float& runout_distance() { return response.runout_distance_mm; } - static inline void set_runout_distance(const float &mm) { response.runout_distance_mm = mm; } + static inline void set_runout_distance(const_float_t mm) { response.runout_distance_mm = mm; } #endif // Handle a block completion. RunoutResponseDelayed uses this to // add up the length of filament moved while the filament is out. - static inline void block_completed(const block_t* const b) { + static inline void block_completed(const block_t * const b) { if (enabled) { response.block_completed(b); sensor.block_completed(b); @@ -118,17 +115,45 @@ class TFilamentMonitor : public FilamentMonitorBase { // Give the response a chance to update its counter. static inline void run() { - if ( enabled && !filament_ran_out - && (printingIsActive() || TERN0(ADVANCED_PAUSE_FEATURE, did_pause_print)) - ) { + if (enabled && !filament_ran_out && (printingIsActive() || did_pause_print)) { TERN_(HAS_FILAMENT_RUNOUT_DISTANCE, cli()); // Prevent RunoutResponseDelayed::block_completed from accumulating here response.run(); sensor.run(); - const bool ran_out = response.has_run_out(); + const uint8_t runout_flags = response.has_run_out(); TERN_(HAS_FILAMENT_RUNOUT_DISTANCE, sei()); + #if MULTI_FILAMENT_SENSOR + #if ENABLED(WATCH_ALL_RUNOUT_SENSORS) + const bool ran_out = !!runout_flags; // any sensor triggers + uint8_t extruder = 0; + if (ran_out) { + uint8_t bitmask = runout_flags; + while (!(bitmask & 1)) { + bitmask >>= 1; + extruder++; + } + } + #else + const bool ran_out = TEST(runout_flags, active_extruder); // suppress non active extruders + uint8_t extruder = active_extruder; + #endif + #else + const bool ran_out = !!runout_flags; + uint8_t extruder = active_extruder; + #endif + + #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)); + SERIAL_ECHOPAIR(" -> ", extruder); + if (ran_out) SERIAL_ECHOPGM(" RUN OUT"); + SERIAL_EOL(); + } + #endif + if (ran_out) { filament_ran_out = true; - event_filament_runout(); + event_filament_runout(extruder); planner.synchronize(); } } @@ -149,34 +174,71 @@ class FilamentSensorBase { public: static inline void setup() { - #if ENABLED(FIL_RUNOUT_PULLUP) - #define INIT_RUNOUT_PIN(P) SET_INPUT_PULLUP(P) - #elif ENABLED(FIL_RUNOUT_PULLDOWN) - #define INIT_RUNOUT_PIN(P) SET_INPUT_PULLDOWN(P) - #else - #define INIT_RUNOUT_PIN(P) SET_INPUT(P) + #define _INIT_RUNOUT_PIN(P,S,U,D) do{ if (ENABLED(U)) SET_INPUT_PULLUP(P); else if (ENABLED(D)) SET_INPUT_PULLDOWN(P); else SET_INPUT(P); }while(0) + #define INIT_RUNOUT_PIN(N) _INIT_RUNOUT_PIN(FIL_RUNOUT##N##_PIN, FIL_RUNOUT##N##_STATE, FIL_RUNOUT##N##_PULLUP, FIL_RUNOUT##N##_PULLDOWN) + #if NUM_RUNOUT_SENSORS >= 1 + INIT_RUNOUT_PIN(1); #endif - - #define _INIT_RUNOUT(N) INIT_RUNOUT_PIN(FIL_RUNOUT##N##_PIN); - REPEAT_S(1, INCREMENT(NUM_RUNOUT_SENSORS), _INIT_RUNOUT) - #undef _INIT_RUNOUT - #undef INIT_RUNOUT_PIN + #if NUM_RUNOUT_SENSORS >= 2 + INIT_RUNOUT_PIN(2); + #endif + #if NUM_RUNOUT_SENSORS >= 3 + INIT_RUNOUT_PIN(3); + #endif + #if NUM_RUNOUT_SENSORS >= 4 + INIT_RUNOUT_PIN(4); + #endif + #if NUM_RUNOUT_SENSORS >= 5 + INIT_RUNOUT_PIN(5); + #endif + #if NUM_RUNOUT_SENSORS >= 6 + INIT_RUNOUT_PIN(6); + #endif + #if NUM_RUNOUT_SENSORS >= 7 + INIT_RUNOUT_PIN(7); + #endif + #if NUM_RUNOUT_SENSORS >= 8 + INIT_RUNOUT_PIN(8); + #endif + #undef _INIT_RUNOUT_PIN + #undef INIT_RUNOUT_PIN } // Return a bitmask of runout pin states static inline uint8_t poll_runout_pins() { #define _OR_RUNOUT(N) | (READ(FIL_RUNOUT##N##_PIN) ? _BV((N) - 1) : 0) - return (0 REPEAT_S(1, INCREMENT(NUM_RUNOUT_SENSORS), _OR_RUNOUT)); + return (0 REPEAT_1(NUM_RUNOUT_SENSORS, _OR_RUNOUT)); #undef _OR_RUNOUT } // Return a bitmask of runout flag states (1 bits always indicates runout) static inline uint8_t poll_runout_states() { - return poll_runout_pins() - #if FIL_RUNOUT_STATE == LOW - ^ uint8_t(_BV(NUM_RUNOUT_SENSORS) - 1) + return poll_runout_pins() ^ uint8_t(0 + #if NUM_RUNOUT_SENSORS >= 1 + | (FIL_RUNOUT1_STATE ? 0 : _BV(1 - 1)) + #endif + #if NUM_RUNOUT_SENSORS >= 2 + | (FIL_RUNOUT2_STATE ? 0 : _BV(2 - 1)) + #endif + #if NUM_RUNOUT_SENSORS >= 3 + | (FIL_RUNOUT3_STATE ? 0 : _BV(3 - 1)) + #endif + #if NUM_RUNOUT_SENSORS >= 4 + | (FIL_RUNOUT4_STATE ? 0 : _BV(4 - 1)) + #endif + #if NUM_RUNOUT_SENSORS >= 5 + | (FIL_RUNOUT5_STATE ? 0 : _BV(5 - 1)) + #endif + #if NUM_RUNOUT_SENSORS >= 6 + | (FIL_RUNOUT6_STATE ? 0 : _BV(6 - 1)) #endif - ; + #if NUM_RUNOUT_SENSORS >= 7 + | (FIL_RUNOUT7_STATE ? 0 : _BV(7 - 1)) + #endif + #if NUM_RUNOUT_SENSORS >= 8 + | (FIL_RUNOUT8_STATE ? 0 : _BV(8 - 1)) + #endif + ); } }; @@ -198,7 +260,7 @@ class FilamentSensorBase { change = old_state ^ new_state; old_state = new_state; - #ifdef FILAMENT_RUNOUT_SENSOR_DEBUG + #if ENABLED(FILAMENT_RUNOUT_SENSOR_DEBUG) if (change) { SERIAL_ECHOPGM("Motion detected:"); LOOP_L_N(e, NUM_RUNOUT_SENSORS) @@ -211,7 +273,7 @@ class FilamentSensorBase { } public: - static inline void block_completed(const block_t* const b) { + static inline void block_completed(const block_t * const b) { // If the sensor wheel has moved since the last call to // this method reset the runout counter for the extruder. if (TEST(motion_detected, b->extruder)) @@ -234,30 +296,31 @@ class FilamentSensorBase { private: static inline bool poll_runout_state(const uint8_t extruder) { const uint8_t runout_states = poll_runout_states(); - #if NUM_RUNOUT_SENSORS == 1 - UNUSED(extruder); - #else - if ( !TERN0(DUAL_X_CARRIAGE, dxc_is_duplicating()) + #if MULTI_FILAMENT_SENSOR + if ( !TERN0(DUAL_X_CARRIAGE, idex_is_duplicating()) && !TERN0(MULTI_NOZZLE_DUPLICATION, extruder_duplication_enabled) ) return TEST(runout_states, extruder); // A specific extruder ran out + #else + UNUSED(extruder); #endif return !!runout_states; // Any extruder ran out } public: - static inline void block_completed(const block_t* const) {} + static inline void block_completed(const block_t * const) {} static inline void run() { - const bool out = poll_runout_state(active_extruder); - if (!out) filament_present(active_extruder); - #ifdef FILAMENT_RUNOUT_SENSOR_DEBUG - static bool was_out = false; - if (out != was_out) { - was_out = out; - SERIAL_ECHOPGM("Filament "); - serialprintPGM(out ? PSTR("OUT\n") : PSTR("IN\n")); - } - #endif + LOOP_L_N(s, NUM_RUNOUT_SENSORS) { + const bool out = poll_runout_state(s); + if (!out) filament_present(s); + #if ENABLED(FILAMENT_RUNOUT_SENSOR_DEBUG) + static uint8_t was_out; // = 0 + if (out != TEST(was_out, s)) { + TBI(was_out, s); + SERIAL_ECHOLNPAIR_P(PSTR("Filament Sensor "), '0' + s, out ? PSTR(" OUT") : PSTR(" IN")); + } + #endif + } } }; @@ -273,42 +336,40 @@ class FilamentSensorBase { // during a runout condition. class RunoutResponseDelayed { private: - static volatile float runout_mm_countdown[EXTRUDERS]; + static volatile float runout_mm_countdown[NUM_RUNOUT_SENSORS]; public: static float runout_distance_mm; static inline void reset() { - LOOP_L_N(i, EXTRUDERS) filament_present(i); + LOOP_L_N(i, NUM_RUNOUT_SENSORS) filament_present(i); } static inline void run() { - #ifdef FILAMENT_RUNOUT_SENSOR_DEBUG + #if ENABLED(FILAMENT_RUNOUT_SENSOR_DEBUG) static millis_t t = 0; const millis_t ms = millis(); if (ELAPSED(ms, t)) { t = millis() + 1000UL; - LOOP_L_N(i, EXTRUDERS) { - serialprintPGM(i ? PSTR(", ") : PSTR("Remaining mm: ")); - SERIAL_ECHO(runout_mm_countdown[i]); - } + LOOP_L_N(i, NUM_RUNOUT_SENSORS) + SERIAL_ECHOPAIR_P(i ? PSTR(", ") : PSTR("Remaining mm: "), runout_mm_countdown[i]); SERIAL_EOL(); } #endif } - static inline bool has_run_out() { - return runout_mm_countdown[active_extruder] < 0; + static inline uint8_t has_run_out() { + uint8_t runout_flags = 0; + LOOP_L_N(i, NUM_RUNOUT_SENSORS) if (runout_mm_countdown[i] < 0) SBI(runout_flags, i); + return runout_flags; } static inline void filament_present(const uint8_t extruder) { runout_mm_countdown[extruder] = runout_distance_mm; } - static inline void block_completed(const block_t* const b) { - if (b->steps.x || b->steps.y || b->steps.z - || TERN0(ADVANCED_PAUSE_FEATURE, did_pause_print) // Allow pause purge move to re-trigger runout state - ) { + static inline void block_completed(const block_t * const b) { + if (b->steps.x || b->steps.y || b->steps.z || did_pause_print) { // Allow pause purge move to re-trigger runout state // Only trigger on extrusion with XYZ movement to allow filament change and retract/recover. const uint8_t e = b->extruder; const int32_t steps = b->steps.e; @@ -325,13 +386,28 @@ class FilamentSensorBase { class RunoutResponseDebounced { private: static constexpr int8_t runout_threshold = FILAMENT_RUNOUT_THRESHOLD; - static int8_t runout_count; + static int8_t runout_count[NUM_RUNOUT_SENSORS]; + public: - static inline void reset() { runout_count = runout_threshold; } - static inline void run() { if (runout_count >= 0) runout_count--; } - static inline bool has_run_out() { return runout_count < 0; } - static inline void block_completed(const block_t* const) { } - static inline void filament_present(const uint8_t) { runout_count = runout_threshold; } + static inline void reset() { + LOOP_L_N(i, NUM_RUNOUT_SENSORS) filament_present(i); + } + + static inline void run() { + LOOP_L_N(i, NUM_RUNOUT_SENSORS) if (runout_count[i] >= 0) runout_count[i]--; + } + + static inline uint8_t has_run_out() { + uint8_t runout_flags = 0; + LOOP_L_N(i, NUM_RUNOUT_SENSORS) if (runout_count[i] < 0) SBI(runout_flags, i); + return runout_flags; + } + + static inline void block_completed(const block_t * const) { } + + static inline void filament_present(const uint8_t extruder) { + runout_count[extruder] = runout_threshold; + } }; #endif // !HAS_FILAMENT_RUNOUT_DISTANCE diff --git a/Marlin/src/feature/snmm.cpp b/Marlin/src/feature/snmm.cpp deleted file mode 100644 index 25723f7b38c3..000000000000 --- a/Marlin/src/feature/snmm.cpp +++ /dev/null @@ -1,38 +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 . - * - */ - -#include "../inc/MarlinConfig.h" - -#if ENABLED(MK2_MULTIPLEXER) - -#include "../module/stepper.h" - -void select_multiplexed_stepper(const uint8_t e) { - planner.synchronize(); - disable_e_steppers(); - WRITE(E_MUX0_PIN, TEST(e, 0) ? HIGH : LOW); - WRITE(E_MUX1_PIN, TEST(e, 1) ? HIGH : LOW); - WRITE(E_MUX2_PIN, TEST(e, 2) ? HIGH : LOW); - safe_delay(100); -} - -#endif // MK2_MULTIPLEXER diff --git a/Marlin/src/feature/snmm.h b/Marlin/src/feature/snmm.h deleted file mode 100644 index 10805c8e26b7..000000000000 --- a/Marlin/src/feature/snmm.h +++ /dev/null @@ -1,24 +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 - -void select_multiplexed_stepper(const uint8_t e); diff --git a/Marlin/src/feature/solenoid.cpp b/Marlin/src/feature/solenoid.cpp index 8646ec872f6f..623f223caa1b 100644 --- a/Marlin/src/feature/solenoid.cpp +++ b/Marlin/src/feature/solenoid.cpp @@ -28,48 +28,41 @@ #include "../module/motion.h" // for active_extruder -#if ENABLED(MANUAL_SOLENOID_CONTROL) - #define HAS_SOLENOID(N) HAS_SOLENOID_##N -#else - #define HAS_SOLENOID(N) (HAS_SOLENOID_##N && EXTRUDERS > N) +// PARKING_EXTRUDER options alter the default behavior of solenoids, this ensures compliance of M380-381 + +#if ENABLED(PARKING_EXTRUDER) + #include "../module/tool_change.h" #endif +#define HAS_SOLENOID(N) (HAS_SOLENOID_##N && (ENABLED(MANUAL_SOLENOID_CONTROL) || N < EXTRUDERS)) + // Used primarily with MANUAL_SOLENOID_CONTROL static void set_solenoid(const uint8_t num, const bool active) { - const uint8_t value = active ? HIGH : LOW; + const uint8_t value = active ? PE_MAGNET_ON_STATE : !PE_MAGNET_ON_STATE; switch (num) { - case 0: - OUT_WRITE(SOL0_PIN, value); - break; + case 0: OUT_WRITE(SOL0_PIN, value); break; #if HAS_SOLENOID(1) - case 1: - OUT_WRITE(SOL1_PIN, value); - break; + case 1: OUT_WRITE(SOL1_PIN, value); break; #endif #if HAS_SOLENOID(2) - case 2: - OUT_WRITE(SOL2_PIN, value); - break; + case 2: OUT_WRITE(SOL2_PIN, value); break; #endif #if HAS_SOLENOID(3) - case 3: - OUT_WRITE(SOL3_PIN, value); - break; + case 3: OUT_WRITE(SOL3_PIN, value); break; #endif #if HAS_SOLENOID(4) - case 4: - OUT_WRITE(SOL4_PIN, value); - break; + case 4: OUT_WRITE(SOL4_PIN, value); break; #endif #if HAS_SOLENOID(5) - case 5: - OUT_WRITE(SOL5_PIN, value); - break; + case 5: OUT_WRITE(SOL5_PIN, value); break; #endif - default: - SERIAL_ECHO_MSG(STR_INVALID_SOLENOID); - break; + default: SERIAL_ECHO_MSG(STR_INVALID_SOLENOID); break; } + + #if ENABLED(PARKING_EXTRUDER) + if (!active && active_extruder == num) // If active extruder's solenoid is disabled, carriage is considered parked + parking_extruder_set_parked(true); + #endif } void enable_solenoid(const uint8_t num) { set_solenoid(num, true); } diff --git a/Marlin/src/feature/spindle_laser.cpp b/Marlin/src/feature/spindle_laser.cpp index bc387a93348d..539fafeb3498 100644 --- a/Marlin/src/feature/spindle_laser.cpp +++ b/Marlin/src/feature/spindle_laser.cpp @@ -30,8 +30,19 @@ #include "spindle_laser.h" +#if ENABLED(SPINDLE_SERVO) + #include "../module/servo.h" +#endif + +#if ENABLED(I2C_AMMETER) + #include "../feature/ammeter.h" +#endif + SpindleLaser cutter; uint8_t SpindleLaser::power; +#if ENABLED(LASER_FEATURE) + cutter_test_pulse_t SpindleLaser::testPulse = 50; // Test fire Pulse time ms value. +#endif bool SpindleLaser::isReady; // Ready to apply power setting from the UI to OCR cutter_power_t SpindleLaser::menuPower, // Power set via LCD menu in PWM, PERCENT, or RPM SpindleLaser::unitPower; // LCD status power in PWM, PERCENT, or RPM @@ -39,13 +50,17 @@ cutter_power_t SpindleLaser::menuPower, // Power s #if ENABLED(MARLIN_DEV_MODE) cutter_frequency_t SpindleLaser::frequency; // PWM frequency setting; range: 2K - 50K #endif -#define SPINDLE_LASER_PWM_OFF ((SPINDLE_LASER_PWM_INVERT) ? 255 : 0) +#define SPINDLE_LASER_PWM_OFF TERN(SPINDLE_LASER_PWM_INVERT, 255, 0) // // Init the cutter to a safe OFF state // void SpindleLaser::init() { - OUT_WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ACTIVE_STATE); // Init spindle to off + #if ENABLED(SPINDLE_SERVO) + MOVE_SERVO(SPINDLE_SERVO_NR, SPINDLE_SERVO_MIN); + #else + OUT_WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ACTIVE_STATE); // Init spindle to off + #endif #if ENABLED(SPINDLE_CHANGE_DIR) OUT_WRITE(SPINDLE_DIR_PIN, SPINDLE_INVERT_DIR ? 255 : 0); // Init rotation to clockwise (M3) #endif @@ -57,22 +72,38 @@ void SpindleLaser::init() { set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_FREQUENCY); TERN_(MARLIN_DEV_MODE, frequency = SPINDLE_LASER_FREQUENCY); #endif + #if ENABLED(AIR_EVACUATION) + OUT_WRITE(AIR_EVACUATION_PIN, !AIR_EVACUATION_ACTIVE); // Init Vacuum/Blower OFF + #endif + #if ENABLED(AIR_ASSIST) + OUT_WRITE(AIR_ASSIST_PIN, !AIR_ASSIST_ACTIVE); // Init Air Assist OFF + #endif + #if ENABLED(I2C_AMMETER) + ammeter.init(); // Init I2C Ammeter + #endif } #if ENABLED(SPINDLE_LASER_PWM) /** * Set the cutter PWM directly to the given ocr value */ - void SpindleLaser::set_ocr(const uint8_t ocr) { - WRITE(SPINDLE_LASER_ENA_PIN, SPINDLE_LASER_ACTIVE_STATE); // Turn spindle on - analogWrite(pin_t(SPINDLE_LASER_PWM_PIN), ocr ^ SPINDLE_LASER_PWM_OFF); + void SpindleLaser::_set_ocr(const uint8_t ocr) { #if NEEDS_HARDWARE_PWM && SPINDLE_LASER_FREQUENCY + set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), TERN(MARLIN_DEV_MODE, frequency, SPINDLE_LASER_FREQUENCY)); set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), ocr ^ SPINDLE_LASER_PWM_OFF); + #else + analogWrite(pin_t(SPINDLE_LASER_PWM_PIN), ocr ^ SPINDLE_LASER_PWM_OFF); #endif } + + void SpindleLaser::set_ocr(const uint8_t ocr) { + WRITE(SPINDLE_LASER_ENA_PIN, SPINDLE_LASER_ACTIVE_STATE); // Cutter ON + _set_ocr(ocr); + } + void SpindleLaser::ocr_off() { - WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ACTIVE_STATE); // Turn spindle off - analogWrite(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_OFF); // Only write low byte + WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ACTIVE_STATE); // Cutter OFF + _set_ocr(0); } #endif @@ -89,7 +120,7 @@ void SpindleLaser::apply_power(const uint8_t opwr) { ocr_off(); isReady = false; } - else if (enabled() || ENABLED(CUTTER_POWER_RELATIVE)) { + else if (ENABLED(CUTTER_POWER_RELATIVE) || enabled()) { set_ocr(power); isReady = true; } @@ -97,6 +128,8 @@ void SpindleLaser::apply_power(const uint8_t opwr) { ocr_off(); isReady = false; } + #elif ENABLED(SPINDLE_SERVO) + MOVE_SERVO(SPINDLE_SERVO_NR, power); #else WRITE(SPINDLE_LASER_ENA_PIN, enabled() ? SPINDLE_LASER_ACTIVE_STATE : !SPINDLE_LASER_ACTIVE_STATE); isReady = true; @@ -108,11 +141,33 @@ void SpindleLaser::apply_power(const uint8_t opwr) { // Set the spindle direction and apply immediately // Stop on direction change if SPINDLE_STOP_ON_DIR_CHANGE is enabled // - void SpindleLaser::set_direction(const bool reverse) { + void SpindleLaser::set_reverse(const bool reverse) { const bool dir_state = (reverse == SPINDLE_INVERT_DIR); // Forward (M3) HIGH when not inverted if (TERN0(SPINDLE_STOP_ON_DIR_CHANGE, enabled()) && READ(SPINDLE_DIR_PIN) != dir_state) disable(); WRITE(SPINDLE_DIR_PIN, dir_state); } #endif +#if ENABLED(AIR_EVACUATION) + + // Enable / disable Cutter Vacuum or Laser Blower motor + void SpindleLaser::air_evac_enable() { WRITE(AIR_EVACUATION_PIN, AIR_EVACUATION_ACTIVE); } // Turn ON + + void SpindleLaser::air_evac_disable() { WRITE(AIR_EVACUATION_PIN, !AIR_EVACUATION_ACTIVE); } // Turn OFF + + void SpindleLaser::air_evac_toggle() { TOGGLE(AIR_EVACUATION_PIN); } // Toggle state + +#endif // AIR_EVACUATION + +#if ENABLED(AIR_ASSIST) + + // Enable / disable air assist + void SpindleLaser::air_assist_enable() { WRITE(AIR_ASSIST_PIN, AIR_ASSIST_PIN); } // Turn ON + + void SpindleLaser::air_assist_disable() { WRITE(AIR_ASSIST_PIN, !AIR_ASSIST_PIN); } // Turn OFF + + void SpindleLaser::air_assist_toggle() { TOGGLE(AIR_ASSIST_PIN); } // Toggle state + +#endif // AIR_ASSIST + #endif // HAS_CUTTER diff --git a/Marlin/src/feature/spindle_laser.h b/Marlin/src/feature/spindle_laser.h index 15ff661c73e6..da228cf8a706 100644 --- a/Marlin/src/feature/spindle_laser.h +++ b/Marlin/src/feature/spindle_laser.h @@ -30,34 +30,42 @@ #include "spindle_laser_types.h" +#if USE_BEEPER + #include "../libs/buzzer.h" +#endif + #if ENABLED(LASER_POWER_INLINE) #include "../module/planner.h" #endif #define PCT_TO_PWM(X) ((X) * 255 / 100) +#define PCT_TO_SERVO(X) ((X) * 180 / 100) #ifndef SPEED_POWER_INTERCEPT #define SPEED_POWER_INTERCEPT 0 #endif -#define SPEED_POWER_FLOOR TERN(CUTTER_POWER_RELATIVE, SPEED_POWER_MIN, 0) // #define _MAP(N,S1,S2,D1,D2) ((N)*_MAX((D2)-(D1),0)/_MAX((S2)-(S1),1)+(D1)) class SpindleLaser { public: static constexpr float - min_pct = round(TERN(CUTTER_POWER_RELATIVE, 0, (100 * float(SPEED_POWER_MIN) / TERN(SPINDLE_FEATURE, float(SPEED_POWER_MAX), 100)))), - max_pct = round(TERN(SPINDLE_FEATURE, 100, float(SPEED_POWER_MAX))); + min_pct = TERN(CUTTER_POWER_RELATIVE, 0, TERN(SPINDLE_FEATURE, round(100.0f * (SPEED_POWER_MIN) / (SPEED_POWER_MAX)), SPEED_POWER_MIN)), + max_pct = TERN(SPINDLE_FEATURE, 100, SPEED_POWER_MAX); + + static const inline uint8_t pct_to_ocr(const_float_t pct) { return uint8_t(PCT_TO_PWM(pct)); } - static const inline uint8_t pct_to_ocr(const float pct) { return uint8_t(PCT_TO_PWM(pct)); } + // cpower = configured values (e.g., SPEED_POWER_MAX) - // cpower = configured values (ie SPEED_POWER_MAX) - static const inline uint8_t cpwr_to_pct(const cutter_cpower_t cpwr) { // configured value to pct - return unitPower ? round(100 * (cpwr - SPEED_POWER_FLOOR) / (SPEED_POWER_MAX - SPEED_POWER_FLOOR)) : 0; + // Convert configured power range to a percentage + static const inline uint8_t cpwr_to_pct(const cutter_cpower_t cpwr) { + constexpr cutter_cpower_t power_floor = TERN(CUTTER_POWER_RELATIVE, SPEED_POWER_MIN, 0), + power_range = SPEED_POWER_MAX - power_floor; + return cpwr ? round(100.0f * (cpwr - power_floor) / power_range) : 0; } - // Convert a configured value (cpower)(ie SPEED_POWER_STARTUP) to unit power (upwr, upower), - // which can be PWM, Percent, or RPM (rel/abs). + // Convert a cpower (e.g., SPEED_POWER_STARTUP) to unit power (upwr, upower), + // which can be PWM, Percent, Servo angle, or RPM (rel/abs). static const inline cutter_power_t cpwr_to_upwr(const cutter_cpower_t cpwr) { // STARTUP power to Unit power const cutter_power_t upwr = ( #if ENABLED(SPINDLE_FEATURE) @@ -66,6 +74,8 @@ class SpindleLaser { cpwr // to RPM #elif CUTTER_UNIT_IS(PERCENT) // to PCT cpwr_to_pct(cpwr) + #elif CUTTER_UNIT_IS(SERVO) // to SERVO angle + PCT_TO_SERVO(cpwr_to_pct(cpwr)) #else // to PWM PCT_TO_PWM(cpwr_to_pct(cpwr)) #endif @@ -84,6 +94,10 @@ class SpindleLaser { static const cutter_power_t mpower_min() { return cpwr_to_upwr(SPEED_POWER_MIN); } static const cutter_power_t mpower_max() { return cpwr_to_upwr(SPEED_POWER_MAX); } + #if ENABLED(LASER_FEATURE) + static cutter_test_pulse_t testPulse; // Test fire Pulse ms value + #endif + static bool isReady; // Ready to apply power setting from the UI to OCR static uint8_t power; @@ -111,6 +125,12 @@ class SpindleLaser { #if ENABLED(SPINDLE_LASER_PWM) + private: + + static void _set_ocr(const uint8_t ocr); + + public: + static void set_ocr(const uint8_t ocr); static inline void set_ocr_power(const uint8_t ocr) { power = ocr; set_ocr(ocr); } static void ocr_off(); @@ -137,7 +157,7 @@ class SpindleLaser { #elif CUTTER_UNIT_IS(RPM) 2 #else - #error "???" + #error "CUTTER_UNIT_IS(unknown)" #endif )); } @@ -185,15 +205,34 @@ class SpindleLaser { } #if ENABLED(SPINDLE_CHANGE_DIR) - static void set_direction(const bool reverse); + static void set_reverse(const bool reverse); + static bool is_reverse() { return READ(SPINDLE_DIR_PIN) == SPINDLE_INVERT_DIR; } #else - static inline void set_direction(const bool) {} + static inline void set_reverse(const bool) {} + static bool is_reverse() { return false; } + #endif + + #if ENABLED(AIR_EVACUATION) + static void air_evac_enable(); // Turn On Cutter Vacuum or Laser Blower motor + static void air_evac_disable(); // Turn Off Cutter Vacuum or Laser Blower motor + static void air_evac_toggle(); // Toggle Cutter Vacuum or Laser Blower motor + static inline bool air_evac_state() { // Get current state + return (READ(AIR_EVACUATION_PIN) == AIR_EVACUATION_ACTIVE); + } + #endif + + #if ENABLED(AIR_ASSIST) + static void air_assist_enable(); // Turn on air assist + static void air_assist_disable(); // Turn off air assist + static void air_assist_toggle(); // Toggle air assist + static inline bool air_assist_state() { // Get current state + return (READ(AIR_ASSIST_PIN) == AIR_ASSIST_ACTIVE); + } #endif static inline void disable() { isReady = false; set_enabled(false); } #if HAS_LCD_MENU - static inline void enable_with_dir(const bool reverse) { isReady = true; const uint8_t ocr = TERN(SPINDLE_LASER_PWM, upower_to_ocr(menuPower), 255); @@ -202,11 +241,12 @@ class SpindleLaser { else menuPower = cpwr_to_upwr(SPEED_POWER_STARTUP); unitPower = menuPower; - set_direction(reverse); + set_reverse(reverse); set_enabled(true); } FORCE_INLINE static void enable_forward() { enable_with_dir(false); } FORCE_INLINE static void enable_reverse() { enable_with_dir(true); } + FORCE_INLINE static void enable_same_dir() { enable_with_dir(is_reverse()); } #if ENABLED(SPINDLE_LASER_PWM) static inline void update_from_mpower() { @@ -215,7 +255,21 @@ class SpindleLaser { } #endif - #endif + #if ENABLED(LASER_FEATURE) + /** + * Test fire the laser using the testPulse ms duration + * Also fires with any PWM power that was previous set + * If not set defaults to 80% power + */ + static inline void test_fire_pulse() { + TERN_(USE_BEEPER, buzzer.tone(30, 3000)); + enable_forward(); // Turn Laser on (Spindle speak but same funct) + delay(testPulse); // Delay for time set by user in pulse ms menu screen. + disable(); // Turn laser off + } + #endif + + #endif // HAS_LCD_MENU #if ENABLED(LASER_POWER_INLINE) /** @@ -235,7 +289,7 @@ class SpindleLaser { // Inline modes of all other functions; all enable planner inline power control static inline void set_inline_enabled(const bool enable) { if (enable) - inline_power(cpwr_to_upwr(SPEED_POWER_STARTUP)); + inline_power(255); else { isReady = false; unitPower = menuPower = 0; diff --git a/Marlin/src/feature/spindle_laser_types.h b/Marlin/src/feature/spindle_laser_types.h index 181c4d73ac07..0075e5481900 100644 --- a/Marlin/src/feature/spindle_laser_types.h +++ b/Marlin/src/feature/spindle_laser_types.h @@ -39,12 +39,22 @@ typedef IF<(SPEED_POWER_MAX > 255), uint16_t, uint8_t>::type cutter_cpower_t; #if CUTTER_UNIT_IS(RPM) && SPEED_POWER_MAX > 255 typedef uint16_t cutter_power_t; - #define CUTTER_MENU_POWER_TYPE uint16_5 - #define cutter_power2str ui16tostr5rj + #define CUTTER_MENU_POWER_TYPE uint16_5 + #define cutter_power2str ui16tostr5rj #else typedef uint8_t cutter_power_t; - #define CUTTER_MENU_POWER_TYPE uint8 - #define cutter_power2str ui8tostr3rj + #if CUTTER_UNIT_IS(PERCENT) + #define CUTTER_MENU_POWER_TYPE percent_3 + #define cutter_power2str pcttostrpctrj + #else + #define CUTTER_MENU_POWER_TYPE uint8 + #define cutter_power2str ui8tostr3rj + #endif +#endif + +#if ENABLED(LASER_FEATURE) + typedef uint16_t cutter_test_pulse_t; + #define CUTTER_MENU_PULSE_TYPE uint16_3 #endif #if ENABLED(MARLIN_DEV_MODE) diff --git a/Marlin/src/feature/stepper_driver_safety.cpp b/Marlin/src/feature/stepper_driver_safety.cpp new file mode 100644 index 000000000000..991f5a5906b4 --- /dev/null +++ b/Marlin/src/feature/stepper_driver_safety.cpp @@ -0,0 +1,171 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../inc/MarlinConfig.h" +#include "../lcd/marlinui.h" + +#if HAS_DRIVER_SAFE_POWER_PROTECT + +#include "stepper_driver_safety.h" + +static uint32_t axis_plug_backward = 0; + +void stepper_driver_backward_error(PGM_P str) { + SERIAL_ERROR_START(); + SERIAL_ECHOPGM_P(str); + SERIAL_ECHOLNPGM(" driver is backward!"); + ui.status_printf_P(2, PSTR(S_FMT S_FMT), str, GET_TEXT(MSG_DRIVER_BACKWARD)); +} + +void stepper_driver_backward_check() { + + OUT_WRITE(SAFE_POWER_PIN, LOW); + + #define TEST_BACKWARD(AXIS, BIT) do { \ + SET_INPUT(AXIS##_ENABLE_PIN); \ + OUT_WRITE(AXIS##_STEP_PIN, false); \ + delay(20); \ + if (READ(AXIS##_ENABLE_PIN) == false) { \ + SBI(axis_plug_backward, BIT); \ + stepper_driver_backward_error(PSTR(STRINGIFY(AXIS))); \ + } \ + }while(0) + + #if HAS_X_ENABLE + TEST_BACKWARD(X, 0); + #endif + #if HAS_X2_ENABLE + TEST_BACKWARD(X2, 1); + #endif + + #if HAS_Y_ENABLE + TEST_BACKWARD(Y, 2); + #endif + #if HAS_Y2_ENABLE + TEST_BACKWARD(Y2, 3); + #endif + + #if HAS_Z_ENABLE + TEST_BACKWARD(Z, 4); + #endif + #if HAS_Z2_ENABLE + TEST_BACKWARD(Z2, 5); + #endif + #if HAS_Z3_ENABLE + TEST_BACKWARD(Z3, 6); + #endif + #if HAS_Z4_ENABLE + TEST_BACKWARD(Z4, 7); + #endif + + #if HAS_E0_ENABLE + TEST_BACKWARD(E0, 8); + #endif + #if HAS_E1_ENABLE + TEST_BACKWARD(E1, 9); + #endif + #if HAS_E2_ENABLE + TEST_BACKWARD(E2, 10); + #endif + #if HAS_E3_ENABLE + TEST_BACKWARD(E3, 11); + #endif + #if HAS_E4_ENABLE + TEST_BACKWARD(E4, 12); + #endif + #if HAS_E5_ENABLE + TEST_BACKWARD(E5, 13); + #endif + #if HAS_E6_ENABLE + TEST_BACKWARD(E6, 14); + #endif + #if HAS_E7_ENABLE + TEST_BACKWARD(E7, 15); + #endif + + if (!axis_plug_backward) + WRITE(SAFE_POWER_PIN, HIGH); +} + +void stepper_driver_backward_report() { + if (!axis_plug_backward) return; + + auto _report_if_backward = [](PGM_P axis, uint8_t bit) { + if (TEST(axis_plug_backward, bit)) + stepper_driver_backward_error(axis); + }; + + #define REPORT_BACKWARD(axis, bit) _report_if_backward(PSTR(STRINGIFY(axis)), bit) + + #if HAS_X_ENABLE + REPORT_BACKWARD(X, 0); + #endif + #if HAS_X2_ENABLE + REPORT_BACKWARD(X2, 1); + #endif + + #if HAS_Y_ENABLE + REPORT_BACKWARD(Y, 2); + #endif + #if HAS_Y2_ENABLE + REPORT_BACKWARD(Y2, 3); + #endif + + #if HAS_Z_ENABLE + REPORT_BACKWARD(Z, 4); + #endif + #if HAS_Z2_ENABLE + REPORT_BACKWARD(Z2, 5); + #endif + #if HAS_Z3_ENABLE + REPORT_BACKWARD(Z3, 6); + #endif + #if HAS_Z4_ENABLE + REPORT_BACKWARD(Z4, 7); + #endif + + #if HAS_E0_ENABLE + REPORT_BACKWARD(E0, 8); + #endif + #if HAS_E1_ENABLE + REPORT_BACKWARD(E1, 9); + #endif + #if HAS_E2_ENABLE + REPORT_BACKWARD(E2, 10); + #endif + #if HAS_E3_ENABLE + REPORT_BACKWARD(E3, 11); + #endif + #if HAS_E4_ENABLE + REPORT_BACKWARD(E4, 12); + #endif + #if HAS_E5_ENABLE + REPORT_BACKWARD(E5, 13); + #endif + #if HAS_E6_ENABLE + REPORT_BACKWARD(E6, 14); + #endif + #if HAS_E7_ENABLE + REPORT_BACKWARD(E7, 15); + #endif +} + +#endif // HAS_DRIVER_SAFE_POWER_PROTECT diff --git a/Marlin/src/feature/stepper_driver_safety.h b/Marlin/src/feature/stepper_driver_safety.h new file mode 100644 index 000000000000..46edf3390d77 --- /dev/null +++ b/Marlin/src/feature/stepper_driver_safety.h @@ -0,0 +1,28 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + + +#include "../inc/MarlinConfigPre.h" + +void stepper_driver_backward_check(); +void stepper_driver_backward_report(); diff --git a/Marlin/src/feature/tmc_util.cpp b/Marlin/src/feature/tmc_util.cpp index 781253079ed5..99cfd996c843 100644 --- a/Marlin/src/feature/tmc_util.cpp +++ b/Marlin/src/feature/tmc_util.cpp @@ -147,7 +147,7 @@ static TMC_driver_data get_driver_data(TMC2208Stepper &st) { constexpr uint8_t OTPW_bp = 0, OT_bp = 1; - constexpr uint8_t S2G_bm = 0b11110; // 2..5 + constexpr uint8_t S2G_bm = 0b111100; // 2..5 TMC_driver_data data; const auto ds = data.drv_status = st.DRV_STATUS(); data.is_otpw = TEST(ds, OTPW_bp); @@ -208,10 +208,10 @@ #if ENABLED(STOP_ON_ERROR) void report_driver_error(const TMC_driver_data &data) { SERIAL_ECHOPGM(" driver error detected: 0x"); - SERIAL_PRINTLN(data.drv_status, HEX); + SERIAL_PRINTLN(data.drv_status, PrintBase::Hex); if (data.is_ot) SERIAL_ECHOLNPGM("overtemperature"); if (data.is_s2g) SERIAL_ECHOLNPGM("coil short circuit"); - TERN_(TMC_DEBUG, tmc_report_all(true, true, true, true)); + TERN_(TMC_DEBUG, tmc_report_all()); kill(PSTR("Driver error")); } #endif @@ -233,10 +233,10 @@ void report_polled_driver_data(TMC &st, const TMC_driver_data &data) { const uint32_t pwm_scale = get_pwm_scale(st); st.printLabel(); - SERIAL_CHAR(':'); SERIAL_PRINT(pwm_scale, DEC); + SERIAL_CHAR(':'); SERIAL_ECHO(pwm_scale); #if ENABLED(TMC_DEBUG) #if HAS_TMCX1X0 || HAS_TMC220x - SERIAL_CHAR('/'); SERIAL_PRINT(data.cs_actual, DEC); + SERIAL_CHAR('/'); SERIAL_ECHO(data.cs_actual); #endif #if HAS_STALLGUARD SERIAL_CHAR('/'); @@ -257,7 +257,7 @@ #endif if (st.flag_otpw) SERIAL_CHAR('F'); // otpw Flag SERIAL_CHAR('|'); - if (st.otpw_count > 0) SERIAL_PRINT(st.otpw_count, DEC); + if (st.otpw_count > 0) SERIAL_ECHO(st.otpw_count); SERIAL_CHAR('\t'); } @@ -291,7 +291,7 @@ bool should_step_down = false; if (need_update_error_counters) { - if (data.is_ot /* | data.s2ga | data.s2gb*/) st.error_count++; + if (data.is_ot | data.is_s2g) st.error_count++; else if (st.error_count > 0) st.error_count--; #if ENABLED(STOP_ON_ERROR) @@ -417,6 +417,21 @@ } #endif + #if AXIS_IS_TMC(I) + if (monitor_tmc_driver(stepperI, need_update_error_counters, need_debug_reporting)) + step_current_down(stepperI); + #endif + + #if AXIS_IS_TMC(J) + if (monitor_tmc_driver(stepperJ, need_update_error_counters, need_debug_reporting)) + step_current_down(stepperJ); + #endif + + #if AXIS_IS_TMC(K) + if (monitor_tmc_driver(stepperK, need_update_error_counters, need_debug_reporting)) + step_current_down(stepperK); + #endif + #if AXIS_IS_TMC(E0) (void)monitor_tmc_driver(stepperE0, need_update_error_counters, need_debug_reporting); #endif @@ -497,7 +512,8 @@ TMC_HEND, TMC_HSTRT, TMC_SGT, - TMC_MSCNT + TMC_MSCNT, + TMC_INTERPOLATE }; enum TMC_drv_status_enum : char { TMC_DRV_CODES, @@ -545,14 +561,15 @@ }; template - static void print_vsense(TMC &st) { serialprintPGM(st.vsense() ? PSTR("1=.18") : PSTR("0=.325")); } + static void print_vsense(TMC &st) { SERIAL_ECHOPGM_P(st.vsense() ? PSTR("1=.18") : PSTR("0=.325")); } #if HAS_DRIVER(TMC2130) || HAS_DRIVER(TMC5130) static void _tmc_status(TMC2130Stepper &st, const TMC_debug_enum i) { switch (i) { - case TMC_PWM_SCALE: SERIAL_PRINT(st.PWM_SCALE(), DEC); break; - case TMC_SGT: SERIAL_PRINT(st.sgt(), DEC); break; + case TMC_PWM_SCALE: SERIAL_ECHO(st.PWM_SCALE()); break; + case TMC_SGT: SERIAL_ECHO(st.sgt()); break; case TMC_STEALTHCHOP: serialprint_truefalse(st.en_pwm_mode()); break; + case TMC_INTERPOLATE: serialprint_truefalse(st.intpol()); break; default: break; } } @@ -561,9 +578,9 @@ static void _tmc_parse_drv_status(TMC2130Stepper &st, const TMC_drv_status_enum i) { switch (i) { case TMC_STALLGUARD: if (st.stallguard()) SERIAL_CHAR('*'); break; - case TMC_SG_RESULT: SERIAL_PRINT(st.sg_result(), DEC); break; + case TMC_SG_RESULT: SERIAL_ECHO(st.sg_result()); break; case TMC_FSACTIVE: if (st.fsactive()) SERIAL_CHAR('*'); break; - case TMC_DRV_CS_ACTUAL: SERIAL_PRINT(st.cs_actual(), DEC); break; + case TMC_DRV_CS_ACTUAL: SERIAL_ECHO(st.cs_actual()); break; default: break; } } @@ -578,16 +595,17 @@ static void _tmc_status(TMC2160Stepper &st, const TMC_debug_enum i) { switch (i) { - case TMC_PWM_SCALE: SERIAL_PRINT(st.PWM_SCALE(), DEC); break; - case TMC_SGT: SERIAL_PRINT(st.sgt(), DEC); break; + case TMC_PWM_SCALE: SERIAL_ECHO(st.PWM_SCALE()); break; + case TMC_SGT: SERIAL_ECHO(st.sgt()); break; case TMC_STEALTHCHOP: serialprint_truefalse(st.en_pwm_mode()); break; case TMC_GLOBAL_SCALER: { uint16_t value = st.GLOBAL_SCALER(); - SERIAL_PRINT(value ?: 256, DEC); + SERIAL_ECHO(value ? value : 256); SERIAL_ECHOPGM("/256"); } break; + case TMC_INTERPOLATE: serialprint_truefalse(st.intpol()); break; default: break; } } @@ -596,13 +614,12 @@ #if HAS_TMC220x static void _tmc_status(TMC2208Stepper &st, const TMC_debug_enum i) { switch (i) { - case TMC_PWM_SCALE_SUM: SERIAL_PRINT(st.pwm_scale_sum(), DEC); break; - case TMC_PWM_SCALE_AUTO: SERIAL_PRINT(st.pwm_scale_auto(), DEC); break; - case TMC_PWM_OFS_AUTO: SERIAL_PRINT(st.pwm_ofs_auto(), DEC); break; - case TMC_PWM_GRAD_AUTO: SERIAL_PRINT(st.pwm_grad_auto(), DEC); break; + case TMC_PWM_SCALE_SUM: SERIAL_ECHO(st.pwm_scale_sum()); break; + case TMC_PWM_SCALE_AUTO: SERIAL_ECHO(st.pwm_scale_auto()); break; + case TMC_PWM_OFS_AUTO: SERIAL_ECHO(st.pwm_ofs_auto()); break; + case TMC_PWM_GRAD_AUTO: SERIAL_ECHO(st.pwm_grad_auto()); break; case TMC_STEALTHCHOP: serialprint_truefalse(st.stealth()); break; - case TMC_S2VSA: if (st.s2vsa()) SERIAL_CHAR('*'); break; - case TMC_S2VSB: if (st.s2vsb()) SERIAL_CHAR('*'); break; + case TMC_INTERPOLATE: serialprint_truefalse(st.intpol()); break; default: break; } } @@ -611,8 +628,8 @@ template static void _tmc_status(TMCMarlin &st, const TMC_debug_enum i) { switch (i) { - case TMC_SGT: SERIAL_PRINT(st.SGTHRS(), DEC); break; - case TMC_UART_ADDR: SERIAL_PRINT(st.get_address(), DEC); break; + case TMC_SGT: SERIAL_ECHO(st.SGTHRS()); break; + case TMC_UART_ADDR: SERIAL_ECHO(st.get_address()); break; default: TMC2208Stepper *parent = &st; _tmc_status(*parent, i); @@ -627,7 +644,9 @@ case TMC_T150: if (st.t150()) SERIAL_CHAR('*'); break; case TMC_T143: if (st.t143()) SERIAL_CHAR('*'); break; case TMC_T120: if (st.t120()) SERIAL_CHAR('*'); break; - case TMC_DRV_CS_ACTUAL: SERIAL_PRINT(st.cs_actual(), DEC); break; + case TMC_S2VSA: if (st.s2vsa()) SERIAL_CHAR('*'); break; + case TMC_S2VSB: if (st.s2vsb()) SERIAL_CHAR('*'); break; + case TMC_DRV_CS_ACTUAL: SERIAL_ECHO(st.cs_actual()); break; default: break; } } @@ -635,7 +654,7 @@ #if HAS_DRIVER(TMC2209) static void _tmc_parse_drv_status(TMC2209Stepper &st, const TMC_drv_status_enum i) { switch (i) { - case TMC_SG_RESULT: SERIAL_PRINT(st.SG_RESULT(), DEC); break; + case TMC_SG_RESULT: SERIAL_ECHO(st.SG_RESULT()); break; default: _tmc_parse_drv_status(static_cast(st), i); break; } } @@ -644,6 +663,12 @@ #if HAS_DRIVER(TMC2660) static void _tmc_parse_drv_status(TMC2660Stepper, const TMC_drv_status_enum) { } + static void _tmc_status(TMC2660Stepper &st, const TMC_debug_enum i) { + switch (i) { + case TMC_INTERPOLATE: serialprint_truefalse(st.intpol()); break; + default: break; + } + } #endif template @@ -656,15 +681,15 @@ case TMC_RMS_CURRENT: SERIAL_ECHO(st.rms_current()); break; case TMC_MAX_CURRENT: SERIAL_PRINT((float)st.rms_current() * 1.41, 0); break; case TMC_IRUN: - SERIAL_PRINT(st.irun(), DEC); + SERIAL_ECHO(st.irun()); SERIAL_ECHOPGM("/31"); break; case TMC_IHOLD: - SERIAL_PRINT(st.ihold(), DEC); + SERIAL_ECHO(st.ihold()); SERIAL_ECHOPGM("/31"); break; case TMC_CS_ACTUAL: - SERIAL_PRINT(st.cs_actual(), DEC); + SERIAL_ECHO(st.cs_actual()); SERIAL_ECHOPGM("/31"); break; case TMC_VSENSE: print_vsense(st); break; @@ -684,11 +709,11 @@ #if ENABLED(MONITOR_DRIVER_STATUS) case TMC_OTPW_TRIGGERED: serialprint_truefalse(st.getOTPW()); break; #endif - case TMC_TOFF: SERIAL_PRINT(st.toff(), DEC); break; - case TMC_TBL: SERIAL_PRINT(st.blank_time(), DEC); break; - case TMC_HEND: SERIAL_PRINT(st.hysteresis_end(), DEC); break; - case TMC_HSTRT: SERIAL_PRINT(st.hysteresis_start(), DEC); break; - case TMC_MSCNT: SERIAL_PRINT(st.get_microstep_counter(), DEC); break; + case TMC_TOFF: SERIAL_ECHO(st.toff()); break; + case TMC_TBL: SERIAL_ECHO(st.blank_time()); break; + case TMC_HEND: SERIAL_ECHO(st.hysteresis_end()); break; + case TMC_HSTRT: SERIAL_ECHO(st.hysteresis_start()); break; + case TMC_MSCNT: SERIAL_ECHO(st.get_microstep_counter()); break; default: _tmc_status(st, i); break; } } @@ -704,18 +729,18 @@ case TMC_RMS_CURRENT: SERIAL_ECHO(st.rms_current()); break; case TMC_MAX_CURRENT: SERIAL_PRINT((float)st.rms_current() * 1.41, 0); break; case TMC_IRUN: - SERIAL_PRINT(st.cs(), DEC); + SERIAL_ECHO(st.cs()); SERIAL_ECHOPGM("/31"); break; - case TMC_VSENSE: serialprintPGM(st.vsense() ? PSTR("1=.165") : PSTR("0=.310")); break; + case TMC_VSENSE: SERIAL_ECHOPGM_P(st.vsense() ? PSTR("1=.165") : PSTR("0=.310")); break; case TMC_MICROSTEPS: SERIAL_ECHO(st.microsteps()); break; //case TMC_OTPW: serialprint_truefalse(st.otpw()); break; //case TMC_OTPW_TRIGGERED: serialprint_truefalse(st.getOTPW()); break; - case TMC_SGT: SERIAL_PRINT(st.sgt(), DEC); break; - case TMC_TOFF: SERIAL_PRINT(st.toff(), DEC); break; - case TMC_TBL: SERIAL_PRINT(st.blank_time(), DEC); break; - case TMC_HEND: SERIAL_PRINT(st.hysteresis_end(), DEC); break; - case TMC_HSTRT: SERIAL_PRINT(st.hysteresis_start(), DEC); break; + case TMC_SGT: SERIAL_ECHO(st.sgt()); break; + case TMC_TOFF: SERIAL_ECHO(st.toff()); break; + case TMC_TBL: SERIAL_ECHO(st.blank_time()); break; + case TMC_HEND: SERIAL_ECHO(st.hysteresis_end()); break; + case TMC_HSTRT: SERIAL_ECHO(st.hysteresis_start()); break; default: break; } } @@ -747,128 +772,148 @@ } } - static void tmc_debug_loop(const TMC_debug_enum i, const bool print_x, const bool print_y, const bool print_z, const bool print_e) { - if (print_x) { + static void tmc_debug_loop(const TMC_debug_enum n, LOGICAL_AXIS_ARGS(const bool)) { + if (x) { #if AXIS_IS_TMC(X) - tmc_status(stepperX, i); + tmc_status(stepperX, n); #endif #if AXIS_IS_TMC(X2) - tmc_status(stepperX2, i); + tmc_status(stepperX2, n); #endif } - if (print_y) { + if (TERN0(HAS_Y_AXIS, y)) { #if AXIS_IS_TMC(Y) - tmc_status(stepperY, i); + tmc_status(stepperY, n); #endif #if AXIS_IS_TMC(Y2) - tmc_status(stepperY2, i); + tmc_status(stepperY2, n); #endif } - if (print_z) { + if (TERN0(HAS_Z_AXIS, z)) { #if AXIS_IS_TMC(Z) - tmc_status(stepperZ, i); + tmc_status(stepperZ, n); #endif #if AXIS_IS_TMC(Z2) - tmc_status(stepperZ2, i); + tmc_status(stepperZ2, n); #endif #if AXIS_IS_TMC(Z3) - tmc_status(stepperZ3, i); + tmc_status(stepperZ3, n); #endif #if AXIS_IS_TMC(Z4) - tmc_status(stepperZ4, i); + tmc_status(stepperZ4, n); #endif } - if (print_e) { + #if AXIS_IS_TMC(I) + if (i) tmc_status(stepperI, n); + #endif + #if AXIS_IS_TMC(J) + if (j) tmc_status(stepperJ, n); + #endif + #if AXIS_IS_TMC(K) + if (k) tmc_status(stepperK, n); + #endif + + if (TERN0(HAS_EXTRUDERS, e)) { #if AXIS_IS_TMC(E0) - tmc_status(stepperE0, i); + tmc_status(stepperE0, n); #endif #if AXIS_IS_TMC(E1) - tmc_status(stepperE1, i); + tmc_status(stepperE1, n); #endif #if AXIS_IS_TMC(E2) - tmc_status(stepperE2, i); + tmc_status(stepperE2, n); #endif #if AXIS_IS_TMC(E3) - tmc_status(stepperE3, i); + tmc_status(stepperE3, n); #endif #if AXIS_IS_TMC(E4) - tmc_status(stepperE4, i); + tmc_status(stepperE4, n); #endif #if AXIS_IS_TMC(E5) - tmc_status(stepperE5, i); + tmc_status(stepperE5, n); #endif #if AXIS_IS_TMC(E6) - tmc_status(stepperE6, i); + tmc_status(stepperE6, n); #endif #if AXIS_IS_TMC(E7) - tmc_status(stepperE7, i); + tmc_status(stepperE7, n); #endif } SERIAL_EOL(); } - static void drv_status_loop(const TMC_drv_status_enum i, const bool print_x, const bool print_y, const bool print_z, const bool print_e) { - if (print_x) { + static void drv_status_loop(const TMC_drv_status_enum n, LOGICAL_AXIS_ARGS(const bool)) { + if (x) { #if AXIS_IS_TMC(X) - tmc_parse_drv_status(stepperX, i); + tmc_parse_drv_status(stepperX, n); #endif #if AXIS_IS_TMC(X2) - tmc_parse_drv_status(stepperX2, i); + tmc_parse_drv_status(stepperX2, n); #endif } - if (print_y) { + if (TERN0(HAS_Y_AXIS, y)) { #if AXIS_IS_TMC(Y) - tmc_parse_drv_status(stepperY, i); + tmc_parse_drv_status(stepperY, n); #endif #if AXIS_IS_TMC(Y2) - tmc_parse_drv_status(stepperY2, i); + tmc_parse_drv_status(stepperY2, n); #endif } - if (print_z) { + if (TERN0(HAS_Z_AXIS, z)) { #if AXIS_IS_TMC(Z) - tmc_parse_drv_status(stepperZ, i); + tmc_parse_drv_status(stepperZ, n); #endif #if AXIS_IS_TMC(Z2) - tmc_parse_drv_status(stepperZ2, i); + tmc_parse_drv_status(stepperZ2, n); #endif #if AXIS_IS_TMC(Z3) - tmc_parse_drv_status(stepperZ3, i); + tmc_parse_drv_status(stepperZ3, n); #endif #if AXIS_IS_TMC(Z4) - tmc_parse_drv_status(stepperZ4, i); + tmc_parse_drv_status(stepperZ4, n); #endif } - if (print_e) { + #if AXIS_IS_TMC(I) + if (i) tmc_parse_drv_status(stepperI, n); + #endif + #if AXIS_IS_TMC(J) + if (j) tmc_parse_drv_status(stepperJ, n); + #endif + #if AXIS_IS_TMC(K) + if (k) tmc_parse_drv_status(stepperK, n); + #endif + + if (TERN0(HAS_EXTRUDERS, e)) { #if AXIS_IS_TMC(E0) - tmc_parse_drv_status(stepperE0, i); + tmc_parse_drv_status(stepperE0, n); #endif #if AXIS_IS_TMC(E1) - tmc_parse_drv_status(stepperE1, i); + tmc_parse_drv_status(stepperE1, n); #endif #if AXIS_IS_TMC(E2) - tmc_parse_drv_status(stepperE2, i); + tmc_parse_drv_status(stepperE2, n); #endif #if AXIS_IS_TMC(E3) - tmc_parse_drv_status(stepperE3, i); + tmc_parse_drv_status(stepperE3, n); #endif #if AXIS_IS_TMC(E4) - tmc_parse_drv_status(stepperE4, i); + tmc_parse_drv_status(stepperE4, n); #endif #if AXIS_IS_TMC(E5) - tmc_parse_drv_status(stepperE5, i); + tmc_parse_drv_status(stepperE5, n); #endif #if AXIS_IS_TMC(E6) - tmc_parse_drv_status(stepperE6, i); + tmc_parse_drv_status(stepperE6, n); #endif #if AXIS_IS_TMC(E7) - tmc_parse_drv_status(stepperE7, i); + tmc_parse_drv_status(stepperE7, n); #endif } @@ -879,9 +924,10 @@ * M122 report functions */ - void tmc_report_all(bool print_x, const bool print_y, const bool print_z, const bool print_e) { - #define TMC_REPORT(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); tmc_debug_loop(ITEM, print_x, print_y, print_z, print_e); }while(0) - #define DRV_REPORT(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); drv_status_loop(ITEM, print_x, print_y, print_z, print_e); }while(0) + 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) + TMC_REPORT("\t", TMC_CODES); #if HAS_DRIVER(TMC2209) TMC_REPORT("Address\t", TMC_UART_ADDR); @@ -902,6 +948,7 @@ #endif TMC_REPORT("stealthChop", TMC_STEALTHCHOP); TMC_REPORT("msteps\t", TMC_MICROSTEPS); + TMC_REPORT("interp\t", TMC_INTERPOLATE); TMC_REPORT("tstep\t", TMC_TSTEP); TMC_REPORT("PWM thresh.", TMC_TPWMTHRS); TMC_REPORT("[mm/s]\t", TMC_TPWMTHRS_MMS); @@ -1004,72 +1051,82 @@ } #endif - static void tmc_get_registers(TMC_get_registers_enum i, const bool print_x, const bool print_y, const bool print_z, const bool print_e) { - if (print_x) { + static void tmc_get_registers(TMC_get_registers_enum n, LOGICAL_AXIS_ARGS(const bool)) { + if (x) { #if AXIS_IS_TMC(X) - tmc_get_registers(stepperX, i); + tmc_get_registers(stepperX, n); #endif #if AXIS_IS_TMC(X2) - tmc_get_registers(stepperX2, i); + tmc_get_registers(stepperX2, n); #endif } - if (print_y) { + if (TERN0(HAS_Y_AXIS, y)) { #if AXIS_IS_TMC(Y) - tmc_get_registers(stepperY, i); + tmc_get_registers(stepperY, n); #endif #if AXIS_IS_TMC(Y2) - tmc_get_registers(stepperY2, i); + tmc_get_registers(stepperY2, n); #endif } - if (print_z) { + if (TERN0(HAS_Z_AXIS, z)) { #if AXIS_IS_TMC(Z) - tmc_get_registers(stepperZ, i); + tmc_get_registers(stepperZ, n); #endif #if AXIS_IS_TMC(Z2) - tmc_get_registers(stepperZ2, i); + tmc_get_registers(stepperZ2, n); #endif #if AXIS_IS_TMC(Z3) - tmc_get_registers(stepperZ3, i); + tmc_get_registers(stepperZ3, n); #endif #if AXIS_IS_TMC(Z4) - tmc_get_registers(stepperZ4, i); + tmc_get_registers(stepperZ4, n); #endif } - if (print_e) { + #if AXIS_IS_TMC(I) + if (i) tmc_get_registers(stepperI, n); + #endif + #if AXIS_IS_TMC(J) + if (j) tmc_get_registers(stepperJ, n); + #endif + #if AXIS_IS_TMC(K) + if (k) tmc_get_registers(stepperK, n); + #endif + + if (TERN0(HAS_EXTRUDERS, e)) { #if AXIS_IS_TMC(E0) - tmc_get_registers(stepperE0, i); + tmc_get_registers(stepperE0, n); #endif #if AXIS_IS_TMC(E1) - tmc_get_registers(stepperE1, i); + tmc_get_registers(stepperE1, n); #endif #if AXIS_IS_TMC(E2) - tmc_get_registers(stepperE2, i); + tmc_get_registers(stepperE2, n); #endif #if AXIS_IS_TMC(E3) - tmc_get_registers(stepperE3, i); + tmc_get_registers(stepperE3, n); #endif #if AXIS_IS_TMC(E4) - tmc_get_registers(stepperE4, i); + tmc_get_registers(stepperE4, n); #endif #if AXIS_IS_TMC(E5) - tmc_get_registers(stepperE5, i); + tmc_get_registers(stepperE5, n); #endif #if AXIS_IS_TMC(E6) - tmc_get_registers(stepperE6, i); + tmc_get_registers(stepperE6, n); #endif #if AXIS_IS_TMC(E7) - tmc_get_registers(stepperE7, i); + tmc_get_registers(stepperE7, n); #endif } SERIAL_EOL(); } - void tmc_get_registers(bool print_x, bool print_y, bool print_z, bool print_e) { - #define _TMC_GET_REG(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); tmc_get_registers(ITEM, print_x, print_y, print_z, print_e); }while(0) + 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(NAME, TABS) _TMC_GET_REG(STRINGIFY(NAME) TABS, TMC_GET_##NAME) _TMC_GET_REG("\t", TMC_AXIS_CODES); TMC_GET_REG(GCONF, "\t\t"); @@ -1154,6 +1211,15 @@ #if AXIS_HAS_SPI(Z4) SET_CS_PIN(Z4); #endif + #if AXIS_HAS_SPI(I) + SET_CS_PIN(I); + #endif + #if AXIS_HAS_SPI(J) + SET_CS_PIN(J); + #endif + #if AXIS_HAS_SPI(K) + SET_CS_PIN(K); + #endif #if AXIS_HAS_SPI(E0) SET_CS_PIN(E0); #endif @@ -1197,16 +1263,16 @@ static bool test_connection(TMC &st) { case 1: stat = PSTR("HIGH"); break; case 2: stat = PSTR("LOW"); break; } - serialprintPGM(stat); + SERIAL_ECHOPGM_P(stat); SERIAL_EOL(); return test_result; } -void test_tmc_connection(const bool test_x, const bool test_y, const bool test_z, const bool test_e) { +void test_tmc_connection(LOGICAL_AXIS_ARGS(const bool)) { uint8_t axis_connection = 0; - if (test_x) { + if (x) { #if AXIS_IS_TMC(X) axis_connection += test_connection(stepperX); #endif @@ -1215,7 +1281,7 @@ void test_tmc_connection(const bool test_x, const bool test_y, const bool test_z #endif } - if (test_y) { + if (TERN0(HAS_Y_AXIS, y)) { #if AXIS_IS_TMC(Y) axis_connection += test_connection(stepperY); #endif @@ -1224,7 +1290,7 @@ void test_tmc_connection(const bool test_x, const bool test_y, const bool test_z #endif } - if (test_z) { + if (TERN0(HAS_Z_AXIS, z)) { #if AXIS_IS_TMC(Z) axis_connection += test_connection(stepperZ); #endif @@ -1239,7 +1305,17 @@ void test_tmc_connection(const bool test_x, const bool test_y, const bool test_z #endif } - if (test_e) { + #if AXIS_IS_TMC(I) + if (i) axis_connection += test_connection(stepperI); + #endif + #if AXIS_IS_TMC(J) + if (j) axis_connection += test_connection(stepperJ); + #endif + #if AXIS_IS_TMC(K) + if (k) axis_connection += test_connection(stepperK); + #endif + + if (TERN0(HAS_EXTRUDERS, e)) { #if AXIS_IS_TMC(E0) axis_connection += test_connection(stepperE0); #endif diff --git a/Marlin/src/feature/tmc_util.h b/Marlin/src/feature/tmc_util.h index b65a1254c656..87780486ebaa 100644 --- a/Marlin/src/feature/tmc_util.h +++ b/Marlin/src/feature/tmc_util.h @@ -22,7 +22,7 @@ #pragma once #include "../inc/MarlinConfig.h" -#include "../lcd/ultralcd.h" +#include "../lcd/marlinui.h" #if HAS_TRINAMIC_CONFIG @@ -70,9 +70,9 @@ class TMCStorage { } struct { - TERN_(HAS_STEALTHCHOP, bool stealthChop_enabled = false); - TERN_(HYBRID_THRESHOLD, uint8_t hybrid_thrs = 0); - TERN_(USE_SENSORLESS, int16_t homing_thrs = 0); + OPTCODE(HAS_STEALTHCHOP, bool stealthChop_enabled = false) + OPTCODE(HYBRID_THRESHOLD, uint8_t hybrid_thrs = 0) + OPTCODE(USE_SENSORLESS, int16_t homing_thrs = 0) } stored; }; @@ -103,9 +103,11 @@ class TMCMarlin : public TMC, public TMCStorage { inline uint16_t get_microstep_counter() { return TMC::MSCNT(); } #if HAS_STEALTHCHOP - inline void refresh_stepping_mode() { this->en_pwm_mode(this->stored.stealthChop_enabled); } - inline bool get_stealthChop_status() { return this->en_pwm_mode(); } - inline bool get_stored_stealthChop_status() { return this->stored.stealthChop_enabled; } + inline bool get_stealthChop() { return this->en_pwm_mode(); } + inline bool get_stored_stealthChop() { return this->stored.stealthChop_enabled; } + inline void refresh_stepping_mode() { this->en_pwm_mode(this->stored.stealthChop_enabled); } + inline void set_stealthChop(const bool stch) { this->stored.stealthChop_enabled = stch; refresh_stepping_mode(); } + inline bool toggle_stepping_mode() { set_stealthChop(!this->stored.stealthChop_enabled); return get_stealthChop(); } #endif #if ENABLED(HYBRID_THRESHOLD) @@ -170,9 +172,11 @@ class TMCMarlin : public TMC220 inline uint16_t get_microstep_counter() { return TMC2208Stepper::MSCNT(); } #if HAS_STEALTHCHOP - inline void refresh_stepping_mode() { en_spreadCycle(!this->stored.stealthChop_enabled); } - inline bool get_stealthChop_status() { return !this->en_spreadCycle(); } - inline bool get_stored_stealthChop_status() { return this->stored.stealthChop_enabled; } + inline bool get_stealthChop() { return !this->en_spreadCycle(); } + inline bool get_stored_stealthChop() { return this->stored.stealthChop_enabled; } + inline void refresh_stepping_mode() { this->en_spreadCycle(!this->stored.stealthChop_enabled); } + inline void set_stealthChop(const bool stch) { this->stored.stealthChop_enabled = stch; refresh_stepping_mode(); } + inline bool toggle_stepping_mode() { set_stealthChop(!this->stored.stealthChop_enabled); return get_stealthChop(); } #endif #if ENABLED(HYBRID_THRESHOLD) @@ -216,9 +220,11 @@ class TMCMarlin : public TMC220 inline uint16_t get_microstep_counter() { return TMC2209Stepper::MSCNT(); } #if HAS_STEALTHCHOP - inline void refresh_stepping_mode() { en_spreadCycle(!this->stored.stealthChop_enabled); } - inline bool get_stealthChop_status() { return !this->en_spreadCycle(); } - inline bool get_stored_stealthChop_status() { return this->stored.stealthChop_enabled; } + inline bool get_stealthChop() { return !this->en_spreadCycle(); } + inline bool get_stored_stealthChop() { return this->stored.stealthChop_enabled; } + inline void refresh_stepping_mode() { this->en_spreadCycle(!this->stored.stealthChop_enabled); } + inline void set_stealthChop(const bool stch) { this->stored.stealthChop_enabled = stch; refresh_stepping_mode(); } + inline bool toggle_stepping_mode() { set_stealthChop(!this->stored.stealthChop_enabled); return get_stealthChop(); } #endif #if ENABLED(HYBRID_THRESHOLD) @@ -324,19 +330,19 @@ void tmc_print_current(TMC &st) { void tmc_print_sgt(TMC &st) { st.printLabel(); SERIAL_ECHOPGM(" homing sensitivity: "); - SERIAL_PRINTLN(st.homing_threshold(), DEC); + SERIAL_PRINTLN(st.homing_threshold(), PrintBase::Dec); } #endif void monitor_tmc_drivers(); -void test_tmc_connection(const bool test_x, const bool test_y, const bool test_z, const bool test_e); +void test_tmc_connection(LOGICAL_AXIS_DECL(const bool, true)); #if ENABLED(TMC_DEBUG) #if ENABLED(MONITOR_DRIVER_STATUS) void tmc_set_report_interval(const uint16_t update_interval); #endif - void tmc_report_all(const bool print_x, const bool print_y, const bool print_z, const bool print_e); - void tmc_get_registers(const bool print_x, const bool print_y, const bool print_z, const bool print_e); + void tmc_report_all(LOGICAL_AXIS_DECL(const bool, true)); + void tmc_get_registers(LOGICAL_AXIS_ARGS(const bool)); #endif /** @@ -349,16 +355,11 @@ void test_tmc_connection(const bool test_x, const bool test_y, const bool test_z #if USE_SENSORLESS // Track enabled status of stealthChop and only re-enable where applicable - struct sensorless_t { bool x, y, z, x2, y2, z2, z3, z4; }; + struct sensorless_t { bool LINEAR_AXIS_ARGS(), x2, y2, z2, z3, z4; }; #if ENABLED(IMPROVE_HOMING_RELIABILITY) extern millis_t sg_guard_period; constexpr uint16_t default_sg_guard_duration = 400; - - struct slow_homing_t { - xy_ulong_t acceleration; - TERN_(HAS_CLASSIC_JERK, xy_float_t jerk_xy); - }; #endif bool tmc_enable_stallguard(TMC2130Stepper &st); diff --git a/Marlin/src/feature/tramming.cpp b/Marlin/src/feature/tramming.cpp new file mode 100644 index 000000000000..d03f0cf53bd7 --- /dev/null +++ b/Marlin/src/feature/tramming.cpp @@ -0,0 +1,69 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../inc/MarlinConfigPre.h" + +#if ENABLED(ASSISTED_TRAMMING) + +#include "tramming.h" + +#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 + +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 +}; + +#ifdef ASSISTED_TRAMMING_WAIT_POSITION + + // Move to the defined wait position + void move_to_tramming_wait_pos() { + constexpr xyz_pos_t wait_pos = ASSISTED_TRAMMING_WAIT_POSITION; + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Moving away"); + do_blocking_move_to(wait_pos, XY_PROBE_FEEDRATE_MM_S); + } + +#endif + +#endif // ASSISTED_TRAMMING diff --git a/Marlin/src/feature/tramming.h b/Marlin/src/feature/tramming.h new file mode 100644 index 000000000000..eb27fe82fe2a --- /dev/null +++ b/Marlin/src/feature/tramming.h @@ -0,0 +1,78 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include "../inc/MarlinConfig.h" +#include "../module/probe.h" + +#if !WITHIN(TRAMMING_SCREW_THREAD, 30, 51) || TRAMMING_SCREW_THREAD % 10 > 1 + #error "TRAMMING_SCREW_THREAD must be equal to 30, 31, 40, 41, 50, or 51." +#endif + +constexpr xy_pos_t screws_tilt_adjust_pos[] = TRAMMING_POINT_XY; + +#define G35_PROBE_COUNT COUNT(screws_tilt_adjust_pos) +static_assert(WITHIN(G35_PROBE_COUNT, 3, 6), "TRAMMING_POINT_XY requires between 3 and 6 XY positions."); + +#define VALIDATE_TRAMMING_POINT(N) static_assert(N >= G35_PROBE_COUNT || Probe::build_time::can_reach(screws_tilt_adjust_pos[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 + #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 +#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 + +extern PGM_P const tramming_point_name[]; + +#ifdef ASSISTED_TRAMMING_WAIT_POSITION + void move_to_tramming_wait_pos(); +#else + inline void move_to_tramming_wait_pos() {} +#endif diff --git a/Marlin/src/feature/twibus.cpp b/Marlin/src/feature/twibus.cpp index 3cc20579ac57..755224544c6e 100644 --- a/Marlin/src/feature/twibus.cpp +++ b/Marlin/src/feature/twibus.cpp @@ -28,6 +28,8 @@ #include +TWIBus i2c; + TWIBus::TWIBus() { #if I2C_SLAVE_ADDRESS == 0 Wire.begin(); // No address joins the BUS as the master @@ -81,7 +83,7 @@ void TWIBus::send() { // static void TWIBus::echoprefix(uint8_t bytes, const char pref[], uint8_t adr) { SERIAL_ECHO_START(); - serialprintPGM(pref); + SERIAL_ECHOPGM_P(pref); SERIAL_ECHOPAIR(": from:", adr, " bytes:", bytes, " data:"); } @@ -155,6 +157,14 @@ void TWIBus::flush() { reset(); } + void i2c_on_receive(int bytes) { // just echo all bytes received to serial + i2c.receive(bytes); + } + + void i2c_on_request() { // just send dummy data for now + i2c.reply("Hello World!\n"); + } + #endif #if ENABLED(DEBUG_TWIBUS) @@ -162,7 +172,7 @@ void TWIBus::flush() { // static void TWIBus::prefix(const char func[]) { SERIAL_ECHOPGM("TWIBus::"); - serialprintPGM(func); + SERIAL_ECHOPGM_P(func); SERIAL_ECHOPGM(": "); } void TWIBus::debug(const char func[], uint32_t adr) { diff --git a/Marlin/src/feature/twibus.h b/Marlin/src/feature/twibus.h index 82aa9aa16a2a..59391534824c 100644 --- a/Marlin/src/feature/twibus.h +++ b/Marlin/src/feature/twibus.h @@ -31,6 +31,17 @@ typedef void (*twiReceiveFunc_t)(int bytes); typedef void (*twiRequestFunc_t)(); +/** + * For a light i2c protocol that runs on two boards running Marlin see: + * See https://github.com/MarlinFirmware/Marlin/issues/4776#issuecomment-246262879 + */ +#if I2C_SLAVE_ADDRESS > 0 + + void i2c_on_receive(int bytes); // Demo i2c onReceive handler + void i2c_on_request(); // Demo i2c onRequest handler + +#endif + #define TWIBUS_BUFFER_SIZE 32 /** @@ -238,3 +249,5 @@ class TWIBus { static inline void debug(const char[], uint8_t) {} #endif }; + +extern TWIBus i2c; diff --git a/Marlin/src/feature/z_stepper_align.cpp b/Marlin/src/feature/z_stepper_align.cpp index 87b1f6f25163..1b4eb4474903 100644 --- a/Marlin/src/feature/z_stepper_align.cpp +++ b/Marlin/src/feature/z_stepper_align.cpp @@ -54,27 +54,11 @@ void ZStepperAlign::reset_to_default() { #endif ); - constexpr xyz_pos_t dpo = NOZZLE_TO_PROBE_OFFSET; - - #define LTEST(N) (xy_init[N].x >= _MAX(X_MIN_BED + PROBING_MARGIN_LEFT, X_MIN_POS + dpo.x) - 0.00001f) - #define RTEST(N) (xy_init[N].x <= _MIN(X_MAX_BED - PROBING_MARGIN_RIGHT, X_MAX_POS + dpo.x) + 0.00001f) - #define FTEST(N) (xy_init[N].y >= _MAX(Y_MIN_BED + PROBING_MARGIN_FRONT, Y_MIN_POS + dpo.y) - 0.00001f) - #define BTEST(N) (xy_init[N].y <= _MIN(Y_MAX_BED - PROBING_MARGIN_BACK, Y_MAX_POS + dpo.y) + 0.00001f) - - static_assert(LTEST(0) && RTEST(0), "The 1st Z_STEPPER_ALIGN_XY X is unreachable with the default probe X offset."); - static_assert(FTEST(0) && BTEST(0), "The 1st Z_STEPPER_ALIGN_XY Y is unreachable with the default probe Y offset."); - static_assert(LTEST(1) && RTEST(1), "The 2nd Z_STEPPER_ALIGN_XY X is unreachable with the default probe X offset."); - static_assert(FTEST(1) && BTEST(1), "The 2nd Z_STEPPER_ALIGN_XY Y is unreachable with the default probe Y offset."); - #if NUM_Z_STEPPER_DRIVERS >= 3 - static_assert(LTEST(2) && RTEST(2), "The 3rd Z_STEPPER_ALIGN_XY X is unreachable with the default probe X offset."); - static_assert(FTEST(2) && BTEST(2), "The 3rd Z_STEPPER_ALIGN_XY Y is unreachable with the default probe Y offset."); - #if NUM_Z_STEPPER_DRIVERS >= 4 - static_assert(LTEST(3) && RTEST(3), "The 4th Z_STEPPER_ALIGN_XY X is unreachable with the default probe X offset."); - static_assert(FTEST(3) && BTEST(3), "The 4th Z_STEPPER_ALIGN_XY Y is unreachable with the default probe Y offset."); - #endif - #endif + #define VALIDATE_ALIGN_POINT(N) static_assert(N >= NUM_Z_STEPPER_DRIVERS || Probe::build_time::can_reach(xy_init[N]), \ + "Z_STEPPER_ALIGN_XY point " STRINGIFY(N) " is not reachable with the default NOZZLE_TO_PROBE offset and PROBING_MARGIN.") + VALIDATE_ALIGN_POINT(0); VALIDATE_ALIGN_POINT(1); VALIDATE_ALIGN_POINT(2); VALIDATE_ALIGN_POINT(3); - #else // !defined(Z_STEPPER_ALIGN_XY) + #else // !Z_STEPPER_ALIGN_XY const xy_pos_t xy_init[] = { #if NUM_Z_STEPPER_DRIVERS >= 3 // First probe point... @@ -115,7 +99,7 @@ void ZStepperAlign::reset_to_default() { #endif }; - #endif // !defined(Z_STEPPER_ALIGN_XY) + #endif // !Z_STEPPER_ALIGN_XY COPY(xy, xy_init); diff --git a/Marlin/src/gcode/bedlevel/G26.cpp b/Marlin/src/gcode/bedlevel/G26.cpp index 661128b04ebe..882197139ee1 100644 --- a/Marlin/src/gcode/bedlevel/G26.cpp +++ b/Marlin/src/gcode/bedlevel/G26.cpp @@ -111,7 +111,15 @@ #include "../../module/motion.h" #include "../../module/tool_change.h" #include "../../module/temperature.h" -#include "../../lcd/ultralcd.h" +#include "../../lcd/marlinui.h" + +#if ENABLED(EXTENSIBLE_UI) + #include "../../lcd/extui/ui_api.h" +#endif + +#if ENABLED(UBL_HILBERT_CURVE) + #include "../../feature/bedlevel/hilbert_curve.h" +#endif #define EXTRUSION_MULTIPLIER 1.0 #define PRIME_LENGTH 10.0 @@ -128,6 +136,10 @@ #define G26_XY_FEEDRATE (PLANNER_XY_FEEDRATE() / 3.0) #endif +#ifndef G26_XY_FEEDRATE_TRAVEL + #define G26_XY_FEEDRATE_TRAVEL (PLANNER_XY_FEEDRATE() / 1.5) +#endif + #if CROSSHAIRS_SIZE >= INTERSECTION_CIRCLE_RADIUS #error "CROSSHAIRS_SIZE must be less than INTERSECTION_CIRCLE_RADIUS." #endif @@ -136,29 +148,14 @@ #define G26_ERR true #if ENABLED(ARC_SUPPORT) - void plan_arc(const xyze_pos_t &cart, const ab_float_t &offset, const uint8_t clockwise); + void plan_arc(const xyze_pos_t&, const ab_float_t&, const bool, const uint8_t); #endif constexpr float g26_e_axis_feedrate = 0.025; -static MeshFlags circle_flags, horizontal_mesh_line_flags, vertical_mesh_line_flags; +static MeshFlags circle_flags; float g26_random_deviation = 0.0; -static bool g26_retracted = false; // Track the retracted state of the nozzle so mismatched - // retracts/recovers won't result in a bad state. - -float g26_extrusion_multiplier, - g26_retraction_multiplier, - g26_layer_height, - g26_prime_length; - -xy_pos_t g26_xy_pos; // = { 0, 0 } - -int16_t g26_bed_temp, - g26_hotend_temp; - -int8_t g26_prime_flag; - #if HAS_LCD_MENU /** @@ -174,291 +171,312 @@ int8_t g26_prime_flag; #endif -mesh_index_pair find_closest_circle_to_print(const xy_pos_t &pos) { - float closest = 99999.99; - mesh_index_pair out_point; - - out_point.pos = -1; - - GRID_LOOP(i, j) { - if (!circle_flags.marked(i, j)) { - // We found a circle that needs to be printed - const xy_pos_t m = { _GET_MESH_X(i), _GET_MESH_Y(j) }; - - // Get the distance to this intersection - float f = (pos - m).magnitude(); - - // It is possible that we are being called with the values - // to let us find the closest circle to the start position. - // But if this is not the case, add a small weighting to the - // distance calculation to help it choose a better place to continue. - f += (g26_xy_pos - m).magnitude() / 15.0f; - - // Add the specified amount of Random Noise to our search - if (g26_random_deviation > 1.0) f += random(0.0, g26_random_deviation); - - if (f < closest) { - closest = f; // Found a closer un-printed location - out_point.pos.set(i, j); // Save its data - out_point.distance = closest; - } - } - } - circle_flags.mark(out_point); // Mark this location as done. - return out_point; -} - -void move_to(const float &rx, const float &ry, const float &z, const float &e_delta) { +void move_to(const_float_t rx, const_float_t ry, const_float_t z, const_float_t e_delta) { static float last_z = -999.99; const xy_pos_t dest = { rx, ry }; - const bool has_xy_component = dest != current_position; // Check if X or Y is involved in the movement. - - destination = current_position; + const bool has_xy_component = dest != current_position, // Check if X or Y is involved in the movement. + has_e_component = e_delta != 0.0; if (z != last_z) { - last_z = destination.z = z; - const feedRate_t feed_value = planner.settings.max_feedrate_mm_s[Z_AXIS] * 0.5f; // Use half of the Z_AXIS max feed rate - prepare_internal_move_to_destination(feed_value); - destination = current_position; + last_z = z; + destination.set(current_position.x, current_position.y, z, current_position.e); + const feedRate_t fr_mm_s = planner.settings.max_feedrate_mm_s[Z_AXIS] * 0.5f; // Use half of the Z_AXIS max feed rate + prepare_internal_move_to_destination(fr_mm_s); } - // If X or Y is involved do a 'normal' move. Otherwise retract/recover/hop. + // If X or Y in combination with E is involved do a 'normal' move. + // If X or Y with no E is involved do a 'fast' move + // Otherwise retract/recover/hop. destination = dest; destination.e += e_delta; - const feedRate_t feed_value = has_xy_component ? feedRate_t(G26_XY_FEEDRATE) : planner.settings.max_feedrate_mm_s[E_AXIS] * 0.666f; - prepare_internal_move_to_destination(feed_value); - destination = current_position; + const feedRate_t fr_mm_s = has_xy_component + ? (has_e_component ? feedRate_t(G26_XY_FEEDRATE) : feedRate_t(G26_XY_FEEDRATE_TRAVEL)) + : planner.settings.max_feedrate_mm_s[E_AXIS] * 0.666f; + prepare_internal_move_to_destination(fr_mm_s); } -FORCE_INLINE void move_to(const xyz_pos_t &where, const float &de) { move_to(where.x, where.y, where.z, de); } +void move_to(const xyz_pos_t &where, const_float_t de) { move_to(where.x, where.y, where.z, de); } -void retract_filament(const xyz_pos_t &where) { - if (!g26_retracted) { // Only retract if we are not already retracted! - g26_retracted = true; - move_to(where, -1.0f * g26_retraction_multiplier); - } -} +typedef struct { + float extrusion_multiplier = EXTRUSION_MULTIPLIER, + retraction_multiplier = G26_RETRACT_MULTIPLIER, + layer_height = MESH_TEST_LAYER_HEIGHT, + prime_length = PRIME_LENGTH; -// TODO: Parameterize the Z lift with a define -void retract_lift_move(const xyz_pos_t &s) { - retract_filament(destination); - move_to(current_position.x, current_position.y, current_position.z + 0.5f, 0.0); // Z lift to minimize scraping - move_to(s.x, s.y, s.z + 0.5f, 0.0); // Get to the starting point with no extrusion while lifted -} + celsius_t bed_temp = MESH_TEST_BED_TEMP, + hotend_temp = MESH_TEST_HOTEND_TEMP; + + float nozzle = MESH_TEST_NOZZLE_SIZE, + filament_diameter = DEFAULT_NOMINAL_FILAMENT_DIA, + ooze_amount; // 'O' ... OOZE_AMOUNT + + bool continue_with_closest, // 'C' + keep_heaters_on; // 'K' + + xy_pos_t xy_pos; // = { 0, 0 } -void recover_filament(const xyz_pos_t &where) { - if (g26_retracted) { // Only un-retract if we are retracted. - move_to(where, 1.2f * g26_retraction_multiplier); - g26_retracted = false; + int8_t prime_flag = 0; + + bool g26_retracted = false; // Track the retracted state during G26 so mismatched + // retracts/recovers don't result in a bad state. + + void retract_filament(const xyz_pos_t &where) { + if (!g26_retracted) { // Only retract if we are not already retracted! + g26_retracted = true; + move_to(where, -1.0f * retraction_multiplier); + } } -} -/** - * print_line_from_here_to_there() takes two cartesian coordinates and draws a line from one - * to the other. But there are really three sets of coordinates involved. The first coordinate - * is the present location of the nozzle. We don't necessarily want to print from this location. - * We first need to move the nozzle to the start of line segment where we want to print. Once - * there, we can use the two coordinates supplied to draw the line. - * - * Note: Although we assume the first set of coordinates is the start of the line and the second - * set of coordinates is the end of the line, it does not always work out that way. This function - * optimizes the movement to minimize the travel distance before it can start printing. This saves - * a lot of time and eliminates a lot of nonsensical movement of the nozzle. However, it does - * cause a lot of very little short retracement of th nozzle when it draws the very first line - * segment of a 'circle'. The time this requires is very short and is easily saved by the other - * cases where the optimization comes into play. - */ -void print_line_from_here_to_there(const xyz_pos_t &s, const xyz_pos_t &e) { + // TODO: Parameterize the Z lift with a define + void retract_lift_move(const xyz_pos_t &s) { + retract_filament(destination); + move_to(current_position.x, current_position.y, current_position.z + 0.5f, 0.0f); // Z lift to minimize scraping + move_to(s.x, s.y, s.z + 0.5f, 0.0f); // Get to the starting point with no extrusion while lifted + } - // Distances to the start / end of the line - xy_float_t svec = current_position - s, evec = current_position - e; + void recover_filament(const xyz_pos_t &where) { + if (g26_retracted) { // Only un-retract if we are retracted. + move_to(where, 1.2f * retraction_multiplier); + g26_retracted = false; + } + } - const float dist_start = HYPOT2(svec.x, svec.y), - dist_end = HYPOT2(evec.x, evec.y), - line_length = HYPOT(e.x - s.x, e.y - s.y); + /** + * print_line_from_here_to_there() takes two cartesian coordinates and draws a line from one + * to the other. But there are really three sets of coordinates involved. The first coordinate + * is the present location of the nozzle. We don't necessarily want to print from this location. + * We first need to move the nozzle to the start of line segment where we want to print. Once + * there, we can use the two coordinates supplied to draw the line. + * + * Note: Although we assume the first set of coordinates is the start of the line and the second + * set of coordinates is the end of the line, it does not always work out that way. This function + * optimizes the movement to minimize the travel distance before it can start printing. This saves + * a lot of time and eliminates a lot of nonsensical movement of the nozzle. However, it does + * cause a lot of very little short retracement of th nozzle when it draws the very first line + * segment of a 'circle'. The time this requires is very short and is easily saved by the other + * cases where the optimization comes into play. + */ + void print_line_from_here_to_there(const xyz_pos_t &s, const xyz_pos_t &e) { - // If the end point of the line is closer to the nozzle, flip the direction, - // moving from the end to the start. On very small lines the optimization isn't worth it. - if (dist_end < dist_start && (INTERSECTION_CIRCLE_RADIUS) < ABS(line_length)) - return print_line_from_here_to_there(e, s); + // Distances to the start / end of the line + xy_float_t svec = current_position - s, evec = current_position - e; - // Decide whether to retract & lift - if (dist_start > 2.0) retract_lift_move(s); + const float dist_start = HYPOT2(svec.x, svec.y), + dist_end = HYPOT2(evec.x, evec.y), + line_length = HYPOT(e.x - s.x, e.y - s.y); - move_to(s, 0.0); // Get to the starting point with no extrusion / un-Z lift + // If the end point of the line is closer to the nozzle, flip the direction, + // moving from the end to the start. On very small lines the optimization isn't worth it. + if (dist_end < dist_start && (INTERSECTION_CIRCLE_RADIUS) < ABS(line_length)) + return print_line_from_here_to_there(e, s); - const float e_pos_delta = line_length * g26_e_axis_feedrate * g26_extrusion_multiplier; + // Decide whether to retract & lift + if (dist_start > 2.0) retract_lift_move(s); - recover_filament(destination); - move_to(e, e_pos_delta); // Get to the ending point with an appropriate amount of extrusion -} + move_to(s, 0.0); // Get to the starting point with no extrusion / un-Z lift -inline bool look_for_lines_to_connect() { - xyz_pos_t s, e; - s.z = e.z = g26_layer_height; + const float e_pos_delta = line_length * g26_e_axis_feedrate * extrusion_multiplier; - GRID_LOOP(i, j) { + recover_filament(destination); + move_to(e, e_pos_delta); // Get to the ending point with an appropriate amount of extrusion + } - if (TERN0(HAS_LCD_MENU, user_canceled())) return true; + void connect_neighbor_with_line(const xy_int8_t &p1, int8_t dx, int8_t dy) { + xy_int8_t p2; + p2.x = p1.x + dx; + p2.y = p1.y + dy; + + if (p2.x < 0 || p2.x >= (GRID_MAX_POINTS_X)) return; + if (p2.y < 0 || p2.y >= (GRID_MAX_POINTS_Y)) return; + + if (circle_flags.marked(p1.x, p1.y) && circle_flags.marked(p2.x, p2.y)) { + xyz_pos_t s, e; + s.x = _GET_MESH_X(p1.x) + (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)) * dx; + e.x = _GET_MESH_X(p2.x) - (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)) * dx; + s.y = _GET_MESH_Y(p1.y) + (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)) * dy; + e.y = _GET_MESH_Y(p2.y) - (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)) * dy; + s.z = e.z = layer_height; + + #if HAS_ENDSTOPS + LIMIT(s.y, Y_MIN_POS + 1, Y_MAX_POS - 1); + LIMIT(e.y, Y_MIN_POS + 1, Y_MAX_POS - 1); + LIMIT(s.x, X_MIN_POS + 1, X_MAX_POS - 1); + LIMIT(e.x, X_MIN_POS + 1, X_MAX_POS - 1); + #endif - if (i < (GRID_MAX_POINTS_X)) { // Can't connect to anything farther to the right than GRID_MAX_POINTS_X. - // Already a half circle at the edge of the bed. + if (position_is_reachable(s.x, s.y) && position_is_reachable(e.x, e.y)) + print_line_from_here_to_there(s, e); + } + } - if (circle_flags.marked(i, j) && circle_flags.marked(i + 1, j)) { // Test whether a leftward line can be done - if (!horizontal_mesh_line_flags.marked(i, j)) { - // Two circles need a horizontal line to connect them - s.x = _GET_MESH_X( i ) + (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // right edge - e.x = _GET_MESH_X(i + 1) - (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // left edge + /** + * Turn on the bed and nozzle heat and + * wait for them to get up to temperature. + */ + bool turn_on_heaters() { - LIMIT(s.x, X_MIN_POS + 1, X_MAX_POS - 1); - s.y = e.y = constrain(_GET_MESH_Y(j), Y_MIN_POS + 1, Y_MAX_POS - 1); - LIMIT(e.x, X_MIN_POS + 1, X_MAX_POS - 1); + SERIAL_ECHOLNPGM("Waiting for heatup."); - if (position_is_reachable(s.x, s.y) && position_is_reachable(e.x, e.y)) - print_line_from_here_to_there(s, e); + #if HAS_HEATED_BED - horizontal_mesh_line_flags.mark(i, j); // Mark done, even if skipped - } + if (bed_temp > 25) { + #if HAS_WIRED_LCD + ui.set_status_P(GET_TEXT(MSG_G26_HEATING_BED), 99); + ui.quick_feedback(); + TERN_(HAS_LCD_MENU, ui.capture()); + #endif + thermalManager.setTargetBed(bed_temp); + + // Wait for the temperature to stabilize + if (!thermalManager.wait_for_bed(true OPTARG(G26_CLICK_CAN_CANCEL, true))) + return G26_ERR; } - if (j < (GRID_MAX_POINTS_Y)) { // Can't connect to anything further back than GRID_MAX_POINTS_Y. - // Already a half circle at the edge of the bed. + #else - if (circle_flags.marked(i, j) && circle_flags.marked(i, j + 1)) { // Test whether a downward line can be done - if (!vertical_mesh_line_flags.marked(i, j)) { - // Two circles that need a vertical line to connect them - s.y = _GET_MESH_Y( j ) + (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // top edge - e.y = _GET_MESH_Y(j + 1) - (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // bottom edge + UNUSED(bed_temp); - s.x = e.x = constrain(_GET_MESH_X(i), X_MIN_POS + 1, X_MAX_POS - 1); - LIMIT(s.y, Y_MIN_POS + 1, Y_MAX_POS - 1); - LIMIT(e.y, Y_MIN_POS + 1, Y_MAX_POS - 1); + #endif // HAS_HEATED_BED - if (position_is_reachable(s.x, s.y) && position_is_reachable(e.x, e.y)) - print_line_from_here_to_there(s, e); + // Start heating the active nozzle + #if HAS_WIRED_LCD + ui.set_status_P(GET_TEXT(MSG_G26_HEATING_NOZZLE), 99); + ui.quick_feedback(); + #endif + thermalManager.setTargetHotend(hotend_temp, active_extruder); - vertical_mesh_line_flags.mark(i, j); // Mark done, even if skipped - } - } - } - } + // Wait for the temperature to stabilize + if (!thermalManager.wait_for_hotend(active_extruder, true OPTARG(G26_CLICK_CAN_CANCEL, true))) + return G26_ERR; + + #if HAS_WIRED_LCD + ui.reset_status(); + ui.quick_feedback(); + #endif + + return G26_OK; } - return false; -} -/** - * Turn on the bed and nozzle heat and - * wait for them to get up to temperature. - */ -inline bool turn_on_heaters() { + /** + * Prime the nozzle if needed. Return true on error. + */ + bool prime_nozzle() { + + const feedRate_t fr_slow_e = planner.settings.max_feedrate_mm_s[E_AXIS] / 15.0f; + #if HAS_LCD_MENU && !HAS_TOUCH_BUTTONS // ui.button_pressed issue with touchscreen + #if ENABLED(PREVENT_LENGTHY_EXTRUDE) + float Total_Prime = 0.0; + #endif - SERIAL_ECHOLNPGM("Waiting for heatup."); + if (prime_flag == -1) { // The user wants to control how much filament gets purged + ui.capture(); + ui.set_status_P(GET_TEXT(MSG_G26_MANUAL_PRIME), 99); + ui.chirp(); - #if HAS_HEATED_BED + destination = current_position; - if (g26_bed_temp > 25) { + recover_filament(destination); // Make sure G26 doesn't think the filament is retracted(). + + while (!ui.button_pressed()) { + ui.chirp(); + destination.e += 0.25; + #if ENABLED(PREVENT_LENGTHY_EXTRUDE) + Total_Prime += 0.25; + if (Total_Prime >= EXTRUDE_MAXLENGTH) { + ui.release(); + return G26_ERR; + } + #endif + prepare_internal_move_to_destination(fr_slow_e); + destination = current_position; + planner.synchronize(); // Without this synchronize, the purge is more consistent, + // but because the planner has a buffer, we won't be able + // to stop as quickly. So we put up with the less smooth + // action to give the user a more responsive 'Stop'. + } + + ui.wait_for_release(); + + ui.set_status_P(GET_TEXT(MSG_G26_PRIME_DONE), 99); + ui.quick_feedback(); + ui.release(); + } + else + #endif + { #if HAS_WIRED_LCD - ui.set_status_P(GET_TEXT(MSG_G26_HEATING_BED), 99); + ui.set_status_P(GET_TEXT(MSG_G26_FIXED_LENGTH), 99); ui.quick_feedback(); - TERN_(HAS_LCD_MENU, ui.capture()); #endif - thermalManager.setTargetBed(g26_bed_temp); - - // Wait for the temperature to stabilize - if (!thermalManager.wait_for_bed(true - #if G26_CLICK_CAN_CANCEL - , true - #endif - ) - ) return G26_ERR; + destination = current_position; + destination.e += prime_length; + prepare_internal_move_to_destination(fr_slow_e); + destination.e -= prime_length; + retract_filament(destination); } - #endif // HAS_HEATED_BED + return G26_OK; + } - // Start heating the active nozzle - #if HAS_WIRED_LCD - ui.set_status_P(GET_TEXT(MSG_G26_HEATING_NOZZLE), 99); - ui.quick_feedback(); - #endif - thermalManager.setTargetHotend(g26_hotend_temp, active_extruder); + /** + * Find the nearest point at which to print a circle + */ + mesh_index_pair find_closest_circle_to_print(const xy_pos_t &pos) { - // Wait for the temperature to stabilize - if (!thermalManager.wait_for_hotend(active_extruder, true - #if G26_CLICK_CAN_CANCEL - , true - #endif - )) return G26_ERR; + mesh_index_pair out_point; + out_point.pos = -1; - #if HAS_WIRED_LCD - ui.reset_status(); - ui.quick_feedback(); - #endif + #if ENABLED(UBL_HILBERT_CURVE) - return G26_OK; -} + auto test_func = [](uint8_t i, uint8_t j, void *data) -> bool { + if (!circle_flags.marked(i, j)) { + mesh_index_pair *out_point = (mesh_index_pair*)data; + out_point->pos.set(i, j); // Save its data + return true; + } + return false; + }; -/** - * Prime the nozzle if needed. Return true on error. - */ -inline bool prime_nozzle() { + hilbert_curve::search_from_closest(pos, test_func, &out_point); - const feedRate_t fr_slow_e = planner.settings.max_feedrate_mm_s[E_AXIS] / 15.0f; - #if HAS_LCD_MENU && !HAS_TOUCH_XPT2046 // ui.button_pressed issue with touchscreen - #if ENABLED(PREVENT_LENGTHY_EXTRUDE) - float Total_Prime = 0.0; - #endif + #else - if (g26_prime_flag == -1) { // The user wants to control how much filament gets purged - ui.capture(); - ui.set_status_P(GET_TEXT(MSG_G26_MANUAL_PRIME), 99); - ui.chirp(); + float closest = 99999.99; - destination = current_position; + GRID_LOOP(i, j) { + if (!circle_flags.marked(i, j)) { + // We found a circle that needs to be printed + const xy_pos_t m = { _GET_MESH_X(i), _GET_MESH_Y(j) }; - recover_filament(destination); // Make sure G26 doesn't think the filament is retracted(). + // Get the distance to this intersection + float f = (pos - m).magnitude(); - while (!ui.button_pressed()) { - ui.chirp(); - destination.e += 0.25; - #if ENABLED(PREVENT_LENGTHY_EXTRUDE) - Total_Prime += 0.25; - if (Total_Prime >= EXTRUDE_MAXLENGTH) { - ui.release(); - return G26_ERR; + // It is possible that we are being called with the values + // to let us find the closest circle to the start position. + // But if this is not the case, add a small weighting to the + // distance calculation to help it choose a better place to continue. + f += (xy_pos - m).magnitude() / 15.0f; + + // Add the specified amount of Random Noise to our search + if (g26_random_deviation > 1.0) f += random(0.0, g26_random_deviation); + + if (f < closest) { + closest = f; // Found a closer un-printed location + out_point.pos.set(i, j); // Save its data + out_point.distance = closest; } - #endif - prepare_internal_move_to_destination(fr_slow_e); - destination = current_position; - planner.synchronize(); // Without this synchronize, the purge is more consistent, - // but because the planner has a buffer, we won't be able - // to stop as quickly. So we put up with the less smooth - // action to give the user a more responsive 'Stop'. + } } - ui.wait_for_release(); - - ui.set_status_P(GET_TEXT(MSG_G26_PRIME_DONE), 99); - ui.quick_feedback(); - ui.release(); - } - else - #endif - { - #if HAS_WIRED_LCD - ui.set_status_P(GET_TEXT(MSG_G26_FIXED_LENGTH), 99); - ui.quick_feedback(); #endif - destination = current_position; - destination.e += g26_prime_length; - prepare_internal_move_to_destination(fr_slow_e); - destination.e -= g26_prime_length; - retract_filament(destination); + + circle_flags.mark(out_point); // Mark this location as done. + return out_point; } - return G26_OK; -} +} g26_helper_t; /** * G26: Mesh Validation Pattern generation. @@ -495,20 +513,11 @@ void GcodeSuite::G26() { // Change the tool first, if specified if (parser.seenval('T')) tool_change(parser.value_int()); - g26_extrusion_multiplier = EXTRUSION_MULTIPLIER; - g26_retraction_multiplier = G26_RETRACT_MULTIPLIER; - g26_layer_height = MESH_TEST_LAYER_HEIGHT; - g26_prime_length = PRIME_LENGTH; - g26_bed_temp = MESH_TEST_BED_TEMP; - g26_hotend_temp = MESH_TEST_HOTEND_TEMP; - g26_prime_flag = 0; + g26_helper_t g26; - float g26_nozzle = MESH_TEST_NOZZLE_SIZE, - g26_filament_diameter = DEFAULT_NOMINAL_FILAMENT_DIA, - g26_ooze_amount = parser.linearval('O', OOZE_AMOUNT); - - bool g26_continue_with_closest = parser.boolval('C'), - g26_keep_heaters_on = parser.boolval('K'); + g26.ooze_amount = parser.linearval('O', OOZE_AMOUNT); + g26.continue_with_closest = parser.boolval('C'); + g26.keep_heaters_on = parser.boolval('K'); // Accept 'I' if temperature presets are defined #if PREHEAT_COUNT @@ -518,7 +527,7 @@ void GcodeSuite::G26() { #if HAS_HEATED_BED // Get a temperature from 'I' or 'B' - int16_t bedtemp = 0; + celsius_t bedtemp = 0; // Use the 'I' index if temperature presets are defined #if PREHEAT_COUNT @@ -530,17 +539,17 @@ void GcodeSuite::G26() { if (bedtemp) { if (!WITHIN(bedtemp, 40, BED_MAX_TARGET)) { - SERIAL_ECHOLNPAIR("?Specified bed temperature not plausible (40-", int(BED_MAX_TARGET), "C)."); + SERIAL_ECHOLNPAIR("?Specified bed temperature not plausible (40-", BED_MAX_TARGET, "C)."); return; } - g26_bed_temp = bedtemp; + g26.bed_temp = bedtemp; } #endif // HAS_HEATED_BED if (parser.seenval('L')) { - g26_layer_height = parser.value_linear_units(); - if (!WITHIN(g26_layer_height, 0.0, 2.0)) { + g26.layer_height = parser.value_linear_units(); + if (!WITHIN(g26.layer_height, 0.0, 2.0)) { SERIAL_ECHOLNPGM("?Specified layer height not plausible."); return; } @@ -548,8 +557,8 @@ void GcodeSuite::G26() { if (parser.seen('Q')) { if (parser.has_value()) { - g26_retraction_multiplier = parser.value_float(); - if (!WITHIN(g26_retraction_multiplier, 0.05, 15.0)) { + g26.retraction_multiplier = parser.value_float(); + if (!WITHIN(g26.retraction_multiplier, 0.05, 15.0)) { SERIAL_ECHOLNPGM("?Specified Retraction Multiplier not plausible."); return; } @@ -561,8 +570,8 @@ void GcodeSuite::G26() { } if (parser.seenval('S')) { - g26_nozzle = parser.value_float(); - if (!WITHIN(g26_nozzle, 0.1, 2.0)) { + g26.nozzle = parser.value_float(); + if (!WITHIN(g26.nozzle, 0.1, 2.0)) { SERIAL_ECHOLNPGM("?Specified nozzle size not plausible."); return; } @@ -571,16 +580,16 @@ void GcodeSuite::G26() { if (parser.seen('P')) { if (!parser.has_value()) { #if HAS_LCD_MENU - g26_prime_flag = -1; + g26.prime_flag = -1; #else SERIAL_ECHOLNPGM("?Prime length must be specified when not using an LCD."); return; #endif } else { - g26_prime_flag++; - g26_prime_length = parser.value_linear_units(); - if (!WITHIN(g26_prime_length, 0.0, 25.0)) { + g26.prime_flag++; + g26.prime_length = parser.value_linear_units(); + if (!WITHIN(g26.prime_length, 0.0, 25.0)) { SERIAL_ECHOLNPGM("?Specified prime length not plausible."); return; } @@ -588,20 +597,20 @@ void GcodeSuite::G26() { } if (parser.seenval('F')) { - g26_filament_diameter = parser.value_linear_units(); - if (!WITHIN(g26_filament_diameter, 1.0, 4.0)) { + g26.filament_diameter = parser.value_linear_units(); + if (!WITHIN(g26.filament_diameter, 1.0, 4.0)) { SERIAL_ECHOLNPGM("?Specified filament size not plausible."); return; } } - g26_extrusion_multiplier *= sq(1.75) / sq(g26_filament_diameter); // If we aren't using 1.75mm filament, we need to + g26.extrusion_multiplier *= sq(1.75) / sq(g26.filament_diameter); // If we aren't using 1.75mm filament, we need to // scale up or down the length needed to get the // same volume of filament - g26_extrusion_multiplier *= g26_filament_diameter * sq(g26_nozzle) / sq(0.3); // Scale up by nozzle size + g26.extrusion_multiplier *= g26.filament_diameter * sq(g26.nozzle) / sq(0.3); // Scale up by nozzle size // Get a temperature from 'I' or 'H' - int16_t noztemp = 0; + celsius_t noztemp = 0; // Accept 'I' if temperature presets are defined #if PREHEAT_COUNT @@ -617,7 +626,7 @@ void GcodeSuite::G26() { SERIAL_ECHOLNPGM("?Specified nozzle temperature not plausible."); return; } - g26_hotend_temp = noztemp; + g26.hotend_temp = noztemp; } // 'U' to Randomize and optionally set circle deviation @@ -632,12 +641,12 @@ void GcodeSuite::G26() { #if HAS_LCD_MENU g26_repeats = parser.intval('R', GRID_MAX_POINTS + 1); #else - if (!parser.seen('R')) { + if (parser.seen('R')) + g26_repeats = parser.has_value() ? parser.value_int() : GRID_MAX_POINTS + 1; + else { SERIAL_ECHOLNPGM("?(R)epeat must be specified when not using an LCD."); return; } - else - g26_repeats = parser.has_value() ? parser.value_int() : GRID_MAX_POINTS + 1; #endif if (g26_repeats < 1) { SERIAL_ECHOLNPGM("?(R)epeat value not plausible; must be at least 1."); @@ -645,9 +654,9 @@ void GcodeSuite::G26() { } // Set a position with 'X' and/or 'Y'. Default: current_position - g26_xy_pos.set(parser.seenval('X') ? RAW_X_POSITION(parser.value_linear_units()) : current_position.x, + g26.xy_pos.set(parser.seenval('X') ? RAW_X_POSITION(parser.value_linear_units()) : current_position.x, parser.seenval('Y') ? RAW_Y_POSITION(parser.value_linear_units()) : current_position.y); - if (!position_is_reachable(g26_xy_pos)) { + if (!position_is_reachable(g26.xy_pos)) { SERIAL_ECHOLNPGM("?Specified X,Y coordinate out of bounds."); return; } @@ -655,7 +664,7 @@ void GcodeSuite::G26() { /** * Wait until all parameters are verified before altering the state! */ - set_bed_leveling_enabled(!parser.seen('D')); + set_bed_leveling_enabled(!parser.seen_test('D')); do_z_clearance(Z_CLEARANCE_BETWEEN_PROBES); @@ -665,12 +674,12 @@ void GcodeSuite::G26() { planner.calculate_volumetric_multipliers(); #endif - if (turn_on_heaters() != G26_OK) goto LEAVE; + if (g26.turn_on_heaters() != G26_OK) goto LEAVE; current_position.e = 0.0; sync_plan_position_e(); - if (g26_prime_flag && prime_nozzle() != G26_OK) goto LEAVE; + if (g26.prime_flag && g26.prime_nozzle() != G26_OK) goto LEAVE; /** * Bed is preheated @@ -683,14 +692,12 @@ void GcodeSuite::G26() { */ circle_flags.reset(); - horizontal_mesh_line_flags.reset(); - vertical_mesh_line_flags.reset(); // Move nozzle to the specified height for the first layer destination = current_position; - destination.z = g26_layer_height; + destination.z = g26.layer_height; move_to(destination, 0.0); - move_to(destination, g26_ooze_amount); + move_to(destination, g26.ooze_amount); TERN_(HAS_LCD_MENU, ui.capture()); @@ -715,11 +722,13 @@ void GcodeSuite::G26() { #endif // !ARC_SUPPORT mesh_index_pair location; + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(location.pos, ExtUI::G26_START)); do { // Find the nearest confluence - location = find_closest_circle_to_print(g26_continue_with_closest ? xy_pos_t(current_position) : g26_xy_pos); + location = g26.find_closest_circle_to_print(g26.continue_with_closest ? xy_pos_t(current_position) : g26.xy_pos); if (location.valid()) { + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(location.pos, ExtUI::G26_POINT_START)); const xy_pos_t circle = _GET_MESH_POS(location.pos); // If this mesh location is outside the printable radius, skip it. @@ -747,7 +756,7 @@ void GcodeSuite::G26() { if (!b) { e.x = circle.x; e.y += INTERSECTION_CIRCLE_RADIUS; } arc_length = (f || b) ? ARC_LENGTH(1) : ARC_LENGTH(2); } - else if (r) { // right edge + else if (r) { // right edge if (b) s.set(circle.x - (INTERSECTION_CIRCLE_RADIUS), circle.y); else s.set(circle.x, circle.y + INTERSECTION_CIRCLE_RADIUS); if (f) e.set(circle.x - (INTERSECTION_CIRCLE_RADIUS), circle.y); @@ -767,25 +776,24 @@ void GcodeSuite::G26() { const xy_float_t dist = current_position - s; // Distance from the start of the actual circle const float dist_start = HYPOT2(dist.x, dist.y); const xyze_pos_t endpoint = { - e.x, e.y, g26_layer_height, - current_position.e + (arc_length * g26_e_axis_feedrate * g26_extrusion_multiplier) + e.x, e.y, g26.layer_height, + current_position.e + (arc_length * g26_e_axis_feedrate * g26.extrusion_multiplier) }; if (dist_start > 2.0) { - s.z = g26_layer_height + 0.5f; - retract_lift_move(s); + s.z = g26.layer_height + 0.5f; + g26.retract_lift_move(s); } - s.z = g26_layer_height; + s.z = g26.layer_height; move_to(s, 0.0); // Get to the starting point with no extrusion / un-Z lift - recover_filament(destination); + g26.recover_filament(destination); - const feedRate_t old_feedrate = feedrate_mm_s; - feedrate_mm_s = PLANNER_XY_FEEDRATE() * 0.1f; - plan_arc(endpoint, arc_offset, false); // Draw a counter-clockwise arc - feedrate_mm_s = old_feedrate; - destination = current_position; + { REMEMBER(fr, feedrate_mm_s, PLANNER_XY_FEEDRATE() * 0.1f); + plan_arc(endpoint, arc_offset, false, 0); // Draw a counter-clockwise arc + destination = current_position; + } if (TERN0(HAS_LCD_MENU, user_canceled())) goto LEAVE; // Check if the user wants to stop the Mesh Validation @@ -813,26 +821,32 @@ void GcodeSuite::G26() { if (TERN0(HAS_LCD_MENU, user_canceled())) goto LEAVE; // Check if the user wants to stop the Mesh Validation - xyz_float_t p = { circle.x + _COS(ind ), circle.y + _SIN(ind ), g26_layer_height }, - q = { circle.x + _COS(ind + 1), circle.y + _SIN(ind + 1), g26_layer_height }; + xyz_float_t p = { circle.x + _COS(ind ), circle.y + _SIN(ind ), g26.layer_height }, + q = { circle.x + _COS(ind + 1), circle.y + _SIN(ind + 1), g26.layer_height }; #if IS_KINEMATIC // Check to make sure this segment is entirely on the bed, skip if not. if (!position_is_reachable(p) || !position_is_reachable(q)) continue; - #else + #elif HAS_ENDSTOPS LIMIT(p.x, X_MIN_POS + 1, X_MAX_POS - 1); // Prevent hitting the endstops LIMIT(p.y, Y_MIN_POS + 1, Y_MAX_POS - 1); LIMIT(q.x, X_MIN_POS + 1, X_MAX_POS - 1); LIMIT(q.y, Y_MIN_POS + 1, Y_MAX_POS - 1); #endif - print_line_from_here_to_there(p, q); + g26.print_line_from_here_to_there(p, q); SERIAL_FLUSH(); // Prevent host M105 buffer overrun. } #endif // !ARC_SUPPORT - if (look_for_lines_to_connect()) goto LEAVE; + g26.connect_neighbor_with_line(location.pos, -1, 0); + g26.connect_neighbor_with_line(location.pos, 1, 0); + g26.connect_neighbor_with_line(location.pos, 0, -1); + g26.connect_neighbor_with_line(location.pos, 0, 1); + planner.synchronize(); + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(location.pos, ExtUI::G26_POINT_FINISH)); + if (TERN0(HAS_LCD_MENU, user_canceled())) goto LEAVE; } SERIAL_FLUSH(); // Prevent host M105 buffer overrun. @@ -841,13 +855,11 @@ void GcodeSuite::G26() { LEAVE: ui.set_status_P(GET_TEXT(MSG_G26_LEAVING), -1); + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(location, ExtUI::G26_FINISH)); - retract_filament(destination); + g26.retract_filament(destination); destination.z = Z_CLEARANCE_BETWEEN_PROBES; - move_to(destination, 0); // Raise the nozzle - - destination = g26_xy_pos; // Move back to the starting XY position - move_to(destination, 0); // Move back to the starting position + move_to(destination, 0); // Raise the nozzle #if DISABLED(NO_VOLUMETRICS) parser.volumetric_enabled = volumetric_was_enabled; @@ -856,7 +868,7 @@ void GcodeSuite::G26() { TERN_(HAS_LCD_MENU, ui.release()); // Give back control of the LCD - if (!g26_keep_heaters_on) { + if (!g26.keep_heaters_on) { TERN_(HAS_HEATED_BED, thermalManager.setTargetBed(0)); thermalManager.setTargetHotend(active_extruder, 0); } diff --git a/Marlin/src/gcode/bedlevel/G35.cpp b/Marlin/src/gcode/bedlevel/G35.cpp old mode 100755 new mode 100644 index 0ede4e79c680..3d75a7691537 --- a/Marlin/src/gcode/bedlevel/G35.cpp +++ b/Marlin/src/gcode/bedlevel/G35.cpp @@ -36,35 +36,11 @@ #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) #include "../../core/debug_out.h" -constexpr xy_pos_t screws_tilt_adjust_pos[] = TRAMMING_POINT_XY; - -static PGMSTR(point_name_1, TRAMMING_POINT_NAME_1); -static PGMSTR(point_name_2, TRAMMING_POINT_NAME_2); -static PGMSTR(point_name_3, TRAMMING_POINT_NAME_3); -#ifdef TRAMMING_POINT_NAME_4 - static PGMSTR(point_name_4, TRAMMING_POINT_NAME_4); - #ifdef TRAMMING_POINT_NAME_5 - static PGMSTR(point_name_5, TRAMMING_POINT_NAME_5); - #endif -#endif +// +// Define tramming point names. +// -static 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 - #endif - #endif -}; - -#define G35_PROBE_COUNT COUNT(screws_tilt_adjust_pos) - -#if !WITHIN(TRAMMING_SCREW_THREAD, 30, 51) || TRAMMING_SCREW_THREAD % 10 > 1 - #error "TRAMMING_SCREW_THREAD must be equal to 30, 31, 40, 41, 50, or 51." -#endif - -static_assert(G35_PROBE_COUNT > 2, "TRAMMING_POINT_XY requires at least 3 XY positions."); +#include "../../feature/tramming.h" /** * G35: Read bed corners to help adjust bed screws @@ -96,7 +72,9 @@ void GcodeSuite::G35() { // Disable the leveling matrix before auto-aligning #if HAS_LEVELING - TERN_(RESTORE_LEVELING_AFTER_G35, const bool leveling_was_active = planner.leveling_active); + #if ENABLED(RESTORE_LEVELING_AFTER_G35) + const bool leveling_was_active = planner.leveling_active; + #endif set_bed_leveling_enabled(false); #endif @@ -110,12 +88,11 @@ void GcodeSuite::G35() { tool_change(0, true); #endif - #if HAS_DUPLICATION_MODE - extruder_duplication_enabled = false; - #endif + // Disable duplication mode on homing + TERN_(HAS_DUPLICATION_MODE, set_duplication_enabled(false)); - // Home all before this procedure - home_all_axes(); + // Home only Z axis when X and Y is trusted, otherwise all axes, if needed before this procedure + if (!all_axes_trusted()) process_subcommands_now_P(PSTR("G28Z")); bool err_break = false; @@ -125,20 +102,23 @@ void GcodeSuite::G35() { // In BLTOUCH HS mode, the probe travels in a deployed state. // Users of G35 might have a badly misaligned bed, so raise Z by the // length of the deployed pin (BLTOUCH stroke < 7mm) - current_position.z = (Z_CLEARANCE_BETWEEN_PROBES) + (7 * ENABLED(BLTOUCH_HS_MODE)); - + do_blocking_move_to_z(SUM_TERN(BLTOUCH_HS_MODE, Z_CLEARANCE_BETWEEN_PROBES, 7)); const float z_probed_height = probe.probe_at_point(screws_tilt_adjust_pos[i], PROBE_PT_RAISE, 0, true); if (isnan(z_probed_height)) { - SERIAL_ECHOPAIR("G35 failed at point ", int(i), " (", tramming_point_name[i], ")"); + SERIAL_ECHOPAIR("G35 failed at point ", i + 1, " ("); + SERIAL_ECHOPGM_P((char *)pgm_read_ptr(&tramming_point_name[i])); + SERIAL_CHAR(')'); SERIAL_ECHOLNPAIR_P(SP_X_STR, screws_tilt_adjust_pos[i].x, SP_Y_STR, screws_tilt_adjust_pos[i].y); err_break = true; break; } if (DEBUGGING(LEVELING)) { - DEBUG_ECHOPAIR("Probing point ", int(i), " (", tramming_point_name[i], ")"); - SERIAL_ECHOLNPAIR_P(SP_X_STR, screws_tilt_adjust_pos[i].x, SP_Y_STR, screws_tilt_adjust_pos[i].y, SP_Z_STR, z_probed_height); + DEBUG_ECHOPAIR("Probing point ", i + 1, " ("); + DEBUG_ECHOPGM_P((char *)pgm_read_ptr(&tramming_point_name[i])); + DEBUG_CHAR(')'); + DEBUG_ECHOLNPAIR_P(SP_X_STR, screws_tilt_adjust_pos[i].x, SP_Y_STR, screws_tilt_adjust_pos[i].y, SP_Z_STR, z_probed_height); } z_measured[i] = z_probed_height; @@ -150,16 +130,16 @@ void GcodeSuite::G35() { // Calculate adjusts LOOP_S_L_N(i, 1, G35_PROBE_COUNT) { const float diff = z_measured[0] - z_measured[i], - adjust = abs(diff) < 0.001f ? 0 : diff / threads_factor[(screw_thread - 30) / 10]; + adjust = ABS(diff) < 0.001f ? 0 : diff / threads_factor[(screw_thread - 30) / 10]; const int full_turns = trunc(adjust); const float decimal_part = adjust - float(full_turns); const int minutes = trunc(decimal_part * 60.0f); - SERIAL_ECHOPAIR("Turn ", tramming_point_name[i], - " ", (screw_thread & 1) == (adjust > 0) ? "CCW" : "CW", - " by ", abs(full_turns), " turns"); - if (minutes) SERIAL_ECHOPAIR(" and ", abs(minutes), " minutes"); + SERIAL_ECHOPGM("Turn "); + SERIAL_ECHOPGM_P((char *)pgm_read_ptr(&tramming_point_name[i])); + SERIAL_ECHOPAIR(" ", (screw_thread & 1) == (adjust > 0) ? "CCW" : "CW", " by ", ABS(full_turns), " turns"); + if (minutes) SERIAL_ECHOPAIR(" and ", ABS(minutes), " minutes"); if (ENABLED(REPORT_TRAMMING_MM)) SERIAL_ECHOPAIR(" (", -diff, "mm)"); SERIAL_EOL(); } @@ -180,11 +160,10 @@ void GcodeSuite::G35() { // the probe deployed if it was successful. probe.stow(); + move_to_tramming_wait_pos(); + // After this operation the Z position needs correction set_axis_never_homed(Z_AXIS); - - // Home Z after the alignment procedure - process_subcommands_now_P(PSTR("G28Z")); } #endif // ASSISTED_TRAMMING diff --git a/Marlin/src/gcode/bedlevel/M420.cpp b/Marlin/src/gcode/bedlevel/M420.cpp index 96122c18f882..703e73b5a4ce 100644 --- a/Marlin/src/gcode/bedlevel/M420.cpp +++ b/Marlin/src/gcode/bedlevel/M420.cpp @@ -68,8 +68,8 @@ void GcodeSuite::M420() { y_min = probe.min_y(), y_max = probe.max_y(); #if ENABLED(AUTO_BED_LEVELING_BILINEAR) bilinear_start.set(x_min, y_min); - bilinear_grid_spacing.set((x_max - x_min) / (GRID_MAX_POINTS_X - 1), - (y_max - y_min) / (GRID_MAX_POINTS_Y - 1)); + bilinear_grid_spacing.set((x_max - x_min) / (GRID_MAX_CELLS_X), + (y_max - y_min) / (GRID_MAX_CELLS_Y)); #endif GRID_LOOP(x, y) { Z_VALUES(x, y) = 0.001 * random(-200, 200); @@ -133,7 +133,7 @@ void GcodeSuite::M420() { #endif // AUTO_BED_LEVELING_UBL - const bool seenV = parser.seen('V'); + const bool seenV = parser.seen_test('V'); #if HAS_MESH @@ -156,16 +156,16 @@ void GcodeSuite::M420() { GRID_LOOP(x, y) mesh_sum += Z_VALUES(x, y); const float zmean = mesh_sum / float(GRID_MAX_POINTS); - #else + #else // midrange - // Find the low and high mesh values + // Find the low and high mesh values. float lo_val = 100, hi_val = -100; GRID_LOOP(x, y) { const float z = Z_VALUES(x, y); NOMORE(lo_val, z); NOLESS(hi_val, z); } - // Take the mean of the lowest and highest + // Get the midrange plus C value. (The median may be better.) const float zmean = (lo_val + hi_val) / 2.0 + cval; #endif diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index f7de6c8cee57..29009c6e2d9a 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -41,8 +41,8 @@ #include "../../../module/temperature.h" #endif -#if HAS_DISPLAY - #include "../../../lcd/ultralcd.h" +#if HAS_STATUS_MESSAGE + #include "../../../lcd/marlinui.h" #endif #if ENABLED(AUTO_BED_LEVELING_LINEAR) @@ -61,29 +61,84 @@ #endif #if ENABLED(DWIN_CREALITY_LCD) - #include "../../../lcd/dwin/e3v2/dwin.h" + #include "../../../lcd/e3v2/creality/dwin.h" #endif #if HAS_MULTI_HOTEND #include "../../../module/tool_change.h" #endif -#if ABL_GRID +#if ABL_USES_GRID #if ENABLED(PROBE_Y_FIRST) - #define PR_OUTER_VAR meshCount.x - #define PR_OUTER_END abl_grid_points.x - #define PR_INNER_VAR meshCount.y - #define PR_INNER_END abl_grid_points.y + #define PR_OUTER_VAR abl.meshCount.x + #define PR_OUTER_SIZE abl.grid_points.x + #define PR_INNER_VAR abl.meshCount.y + #define PR_INNER_SIZE abl.grid_points.y #else - #define PR_OUTER_VAR meshCount.y - #define PR_OUTER_END abl_grid_points.y - #define PR_INNER_VAR meshCount.x - #define PR_INNER_END abl_grid_points.x + #define PR_OUTER_VAR abl.meshCount.y + #define PR_OUTER_SIZE abl.grid_points.y + #define PR_INNER_VAR abl.meshCount.x + #define PR_INNER_SIZE abl.grid_points.x #endif #endif #define G29_RETURN(b) return TERN_(G29_RETRY_AND_RECOVER, b) +// For manual probing values persist over multiple G29 +class G29_State { +public: + int verbose_level; + xy_pos_t probePos; + float measured_z; + bool dryrun, + reenable; + + #if EITHER(PROBE_MANUALLY, AUTO_BED_LEVELING_LINEAR) + int abl_probe_index; + #endif + + #if ENABLED(AUTO_BED_LEVELING_LINEAR) + int abl_points; + #elif ENABLED(AUTO_BED_LEVELING_3POINT) + static constexpr int abl_points = 3; + #elif ABL_USES_GRID + static constexpr int abl_points = GRID_MAX_POINTS; + #endif + + #if ABL_USES_GRID + + xy_int8_t meshCount; + + xy_pos_t probe_position_lf, + probe_position_rb; + + xy_float_t gridSpacing; // = { 0.0f, 0.0f } + + #if ENABLED(AUTO_BED_LEVELING_LINEAR) + bool topography_map; + xy_uint8_t grid_points; + #else // Bilinear + static constexpr xy_uint8_t grid_points = { GRID_MAX_POINTS_X, GRID_MAX_POINTS_Y }; + #endif + + #if ENABLED(AUTO_BED_LEVELING_BILINEAR) + float Z_offset; + #endif + + #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 + mean; + #endif + #endif +}; + +#if ABL_USES_GRID && EITHER(AUTO_BED_LEVELING_3POINT, AUTO_BED_LEVELING_BILINEAR) + constexpr xy_uint8_t G29_State::grid_points; + constexpr int G29_State::abl_points; +#endif + /** * G29: Detailed Z probe, probes the bed at 3 or more points. * Will fail if the printer has not been homed with G28. @@ -162,94 +217,45 @@ * There's no extra effect if you have a fixed Z probe. */ G29_TYPE GcodeSuite::G29() { + DEBUG_SECTION(log_G29, "G29", DEBUGGING(LEVELING)); + + TERN_(PROBE_MANUALLY, static) G29_State abl; + + TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_PROBE)); reset_stepper_timeout(); - const bool seenQ = EITHER(DEBUG_LEVELING_FEATURE, PROBE_MANUALLY) && parser.seen('Q'); + const bool seenQ = EITHER(DEBUG_LEVELING_FEATURE, PROBE_MANUALLY) && parser.seen_test('Q'); // G29 Q is also available if debugging #if ENABLED(DEBUG_LEVELING_FEATURE) - const uint8_t old_debug_flags = marlin_debug_flags; - if (seenQ) marlin_debug_flags |= MARLIN_DEBUG_LEVELING; - DEBUG_SECTION(log_G29, "G29", DEBUGGING(LEVELING)); - if (DEBUGGING(LEVELING)) log_machine_info(); - marlin_debug_flags = old_debug_flags; + if (seenQ || DEBUGGING(LEVELING)) log_machine_info(); if (DISABLED(PROBE_MANUALLY) && seenQ) G29_RETURN(false); #endif - const bool seenA = TERN0(PROBE_MANUALLY, parser.seen('A')), + const bool seenA = TERN0(PROBE_MANUALLY, parser.seen_test('A')), no_action = seenA || seenQ, faux = ENABLED(DEBUG_LEVELING_FEATURE) && DISABLED(PROBE_MANUALLY) ? parser.boolval('C') : no_action; - // Don't allow auto-leveling without homing first - if (homing_needed_error()) G29_RETURN(false); - if (!no_action && planner.leveling_active && parser.boolval('O')) { // Auto-level only if needed if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("> Auto-level not needed, skip"); G29_RETURN(false); } - // Define local vars 'static' for manual probing, 'auto' otherwise - #define ABL_VAR TERN_(PROBE_MANUALLY, static) - - ABL_VAR int verbose_level; - ABL_VAR xy_pos_t probePos; - ABL_VAR float measured_z; - ABL_VAR bool dryrun, abl_should_enable; - - #if EITHER(PROBE_MANUALLY, AUTO_BED_LEVELING_LINEAR) - ABL_VAR int abl_probe_index; - #endif - - #if ABL_GRID - - #if ENABLED(PROBE_MANUALLY) - ABL_VAR xy_int8_t meshCount; - #endif - - ABL_VAR xy_pos_t probe_position_lf, probe_position_rb; - ABL_VAR xy_float_t gridSpacing = { 0, 0 }; - - #if ENABLED(AUTO_BED_LEVELING_LINEAR) - ABL_VAR bool do_topography_map; - ABL_VAR xy_uint8_t abl_grid_points; - #else // Bilinear - constexpr xy_uint8_t abl_grid_points = { GRID_MAX_POINTS_X, GRID_MAX_POINTS_Y }; - #endif - - #if ENABLED(AUTO_BED_LEVELING_LINEAR) - ABL_VAR int abl_points; - #else - int constexpr abl_points = GRID_MAX_POINTS; - #endif - - #if ENABLED(AUTO_BED_LEVELING_BILINEAR) - - ABL_VAR float zoffset; - - #elif ENABLED(AUTO_BED_LEVELING_LINEAR) - - ABL_VAR int indexIntoAB[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y]; - - ABL_VAR 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 - - #elif ENABLED(AUTO_BED_LEVELING_3POINT) + // Send 'N' to force homing before G29 (internal only) + if (parser.seen_test('N')) + process_subcommands_now_P(TERN(CAN_SET_LEVELING_AFTER_G28, PSTR("G28L0"), G28_STR)); - #if ENABLED(PROBE_MANUALLY) - int constexpr abl_points = 3; // used to show total points - #endif + // Don't allow auto-leveling without homing first + if (homing_needed_error()) G29_RETURN(false); + #if ENABLED(AUTO_BED_LEVELING_3POINT) vector_3 points[3]; probe.get_three_points(points); - - #endif // AUTO_BED_LEVELING_3POINT + #endif #if ENABLED(AUTO_BED_LEVELING_LINEAR) struct linear_fit_data lsf_results; - incremental_LSF_reset(&lsf_results); #endif /** @@ -260,14 +266,14 @@ G29_TYPE GcodeSuite::G29() { TERN_(HAS_MULTI_HOTEND, if (active_extruder) tool_change(0)); #if EITHER(PROBE_MANUALLY, AUTO_BED_LEVELING_LINEAR) - abl_probe_index = -1; + abl.abl_probe_index = -1; #endif - abl_should_enable = planner.leveling_active; + abl.reenable = planner.leveling_active; #if ENABLED(AUTO_BED_LEVELING_BILINEAR) - const bool seen_w = parser.seen('W'); + const bool seen_w = parser.seen_test('W'); if (seen_w) { if (!leveling_is_valid()) { SERIAL_ERROR_MSG("No bilinear grid"); @@ -286,21 +292,21 @@ G29_TYPE GcodeSuite::G29() { if (!isnan(rx) && !isnan(ry)) { // Get nearest i / j from rx / ry - i = (rx - bilinear_start.x + 0.5 * gridSpacing.x) / gridSpacing.x; - j = (ry - bilinear_start.y + 0.5 * gridSpacing.y) / gridSpacing.y; - LIMIT(i, 0, GRID_MAX_POINTS_X - 1); - LIMIT(j, 0, GRID_MAX_POINTS_Y - 1); + i = (rx - bilinear_start.x + 0.5 * abl.gridSpacing.x) / abl.gridSpacing.x; + j = (ry - bilinear_start.y + 0.5 * abl.gridSpacing.y) / abl.gridSpacing.y; + LIMIT(i, 0, (GRID_MAX_POINTS_X) - 1); + LIMIT(j, 0, (GRID_MAX_POINTS_Y) - 1); } - if (WITHIN(i, 0, GRID_MAX_POINTS_X - 1) && WITHIN(j, 0, GRID_MAX_POINTS_Y)) { + if (WITHIN(i, 0, (GRID_MAX_POINTS_X) - 1) && WITHIN(j, 0, (GRID_MAX_POINTS_Y) - 1)) { set_bed_leveling_enabled(false); z_values[i][j] = rz; TERN_(ABL_BILINEAR_SUBDIVISION, bed_level_virt_interpolate()); TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(i, j, rz)); - set_bed_leveling_enabled(abl_should_enable); - if (abl_should_enable) report_current_position(); + set_bed_leveling_enabled(abl.reenable); + if (abl.reenable) report_current_position(); } G29_RETURN(false); - } // parser.seen('W') + } // parser.seen_test('W') #else @@ -309,98 +315,107 @@ G29_TYPE GcodeSuite::G29() { #endif // Jettison bed leveling data - if (!seen_w && parser.seen('J')) { + if (!seen_w && parser.seen_test('J')) { reset_bed_level(); G29_RETURN(false); } - verbose_level = parser.intval('V'); - if (!WITHIN(verbose_level, 0, 4)) { + abl.verbose_level = parser.intval('V'); + if (!WITHIN(abl.verbose_level, 0, 4)) { SERIAL_ECHOLNPGM("?(V)erbose level implausible (0-4)."); G29_RETURN(false); } - dryrun = parser.boolval('D') || TERN0(PROBE_MANUALLY, no_action); + abl.dryrun = parser.boolval('D') || TERN0(PROBE_MANUALLY, no_action); #if ENABLED(AUTO_BED_LEVELING_LINEAR) - do_topography_map = verbose_level > 2 || parser.boolval('T'); + incremental_LSF_reset(&lsf_results); + + abl.topography_map = abl.verbose_level > 2 || parser.boolval('T'); // X and Y specify points in each direction, overriding the default // These values may be saved with the completed mesh - abl_grid_points.set( + abl.grid_points.set( parser.byteval('X', GRID_MAX_POINTS_X), parser.byteval('Y', GRID_MAX_POINTS_Y) ); - if (parser.seenval('P')) abl_grid_points.x = abl_grid_points.y = parser.value_int(); + if (parser.seenval('P')) abl.grid_points.x = abl.grid_points.y = parser.value_int(); - if (!WITHIN(abl_grid_points.x, 2, GRID_MAX_POINTS_X)) { + if (!WITHIN(abl.grid_points.x, 2, GRID_MAX_POINTS_X)) { SERIAL_ECHOLNPGM("?Probe points (X) implausible (2-" STRINGIFY(GRID_MAX_POINTS_X) ")."); G29_RETURN(false); } - if (!WITHIN(abl_grid_points.y, 2, GRID_MAX_POINTS_Y)) { + if (!WITHIN(abl.grid_points.y, 2, GRID_MAX_POINTS_Y)) { SERIAL_ECHOLNPGM("?Probe points (Y) implausible (2-" STRINGIFY(GRID_MAX_POINTS_Y) ")."); G29_RETURN(false); } - abl_points = abl_grid_points.x * abl_grid_points.y; - mean = 0; + abl.abl_points = abl.grid_points.x * abl.grid_points.y; + abl.mean = 0; #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) - zoffset = parser.linearval('Z'); + abl.Z_offset = parser.linearval('Z'); #endif - #if ABL_GRID + #if ABL_USES_GRID - xy_probe_feedrate_mm_s = MMM_TO_MMS(parser.linearval('S', XY_PROBE_SPEED)); + xy_probe_feedrate_mm_s = MMM_TO_MMS(parser.linearval('S', XY_PROBE_FEEDRATE)); const float x_min = probe.min_x(), x_max = probe.max_x(), y_min = probe.min_y(), y_max = probe.max_y(); if (parser.seen('H')) { const int16_t size = (int16_t)parser.value_linear_units(); - probe_position_lf.set( - _MAX(X_CENTER - size / 2, x_min), - _MAX(Y_CENTER - size / 2, y_min) - ); - probe_position_rb.set( - _MIN(probe_position_lf.x + size, x_max), - _MIN(probe_position_lf.y + size, y_max) - ); + abl.probe_position_lf.set(_MAX((X_CENTER) - size / 2, x_min), _MAX((Y_CENTER) - size / 2, y_min)); + abl.probe_position_rb.set(_MIN(abl.probe_position_lf.x + size, x_max), _MIN(abl.probe_position_lf.y + size, y_max)); } else { - probe_position_lf.set( - parser.seenval('L') ? RAW_X_POSITION(parser.value_linear_units()) : x_min, - parser.seenval('F') ? RAW_Y_POSITION(parser.value_linear_units()) : y_min - ); - probe_position_rb.set( - parser.seenval('R') ? RAW_X_POSITION(parser.value_linear_units()) : x_max, - parser.seenval('B') ? RAW_Y_POSITION(parser.value_linear_units()) : y_max - ); + abl.probe_position_lf.set(parser.linearval('L', x_min), parser.linearval('F', y_min)); + abl.probe_position_rb.set(parser.linearval('R', x_max), parser.linearval('B', y_max)); } - if (!probe.good_bounds(probe_position_lf, probe_position_rb)) { + if (!probe.good_bounds(abl.probe_position_lf, abl.probe_position_rb)) { + if (DEBUGGING(LEVELING)) { + DEBUG_ECHOLNPAIR("G29 L", abl.probe_position_lf.x, " R", abl.probe_position_rb.x, + " F", abl.probe_position_lf.y, " B", abl.probe_position_rb.y); + } SERIAL_ECHOLNPGM("? (L,R,F,B) out of bounds."); G29_RETURN(false); } - // probe at the points of a lattice grid - gridSpacing.set((probe_position_rb.x - probe_position_lf.x) / (abl_grid_points.x - 1), - (probe_position_rb.y - probe_position_lf.y) / (abl_grid_points.y - 1)); + // Probe at the points of a lattice grid + abl.gridSpacing.set((abl.probe_position_rb.x - abl.probe_position_lf.x) / (abl.grid_points.x - 1), + (abl.probe_position_rb.y - abl.probe_position_lf.y) / (abl.grid_points.y - 1)); - #endif // ABL_GRID + #endif // ABL_USES_GRID - if (verbose_level > 0) { + if (abl.verbose_level > 0) { SERIAL_ECHOPGM("G29 Auto Bed Leveling"); - if (dryrun) SERIAL_ECHOPGM(" (DRYRUN)"); + if (abl.dryrun) SERIAL_ECHOPGM(" (DRYRUN)"); SERIAL_EOL(); } planner.synchronize(); - if (!faux) remember_feedrate_scaling_off(); + #if ENABLED(AUTO_BED_LEVELING_3POINT) + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("> 3-point Leveling"); + points[0].z = points[1].z = points[2].z = 0; // Probe at 3 arbitrary points + #endif + + #if BOTH(AUTO_BED_LEVELING_BILINEAR, EXTENSIBLE_UI) + ExtUI::onMeshLevelingStart(); + #endif + + if (!faux) { + remember_feedrate_scaling_off(); + + #if ENABLED(PREHEAT_BEFORE_LEVELING) + if (!abl.dryrun) probe.preheat_for_probing(LEVELING_NOZZLE_TEMP, LEVELING_BED_TEMP); + #endif + } // Disable auto bed leveling during G29. // Be formal so G29 can be done successively without G28. @@ -411,38 +426,27 @@ G29_TYPE GcodeSuite::G29() { if (ENABLED(BLTOUCH)) do_z_clearance(Z_CLEARANCE_DEPLOY_PROBE); else if (probe.deploy()) { - set_bed_leveling_enabled(abl_should_enable); + set_bed_leveling_enabled(abl.reenable); G29_RETURN(false); } #endif #if ENABLED(AUTO_BED_LEVELING_BILINEAR) - if (TERN1(PROBE_MANUALLY, !no_action) - && (gridSpacing != bilinear_grid_spacing || probe_position_lf != bilinear_start) + && (abl.gridSpacing != bilinear_grid_spacing || abl.probe_position_lf != bilinear_start) ) { // Reset grid to 0.0 or "not probed". (Also disables ABL) reset_bed_level(); // Initialize a grid with the given dimensions - bilinear_grid_spacing = gridSpacing; - bilinear_start = probe_position_lf; + bilinear_grid_spacing = abl.gridSpacing; + bilinear_start = abl.probe_position_lf; // Can't re-enable (on error) until the new grid is written - abl_should_enable = false; + abl.reenable = false; } - #endif // AUTO_BED_LEVELING_BILINEAR - #if ENABLED(AUTO_BED_LEVELING_3POINT) - - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("> 3-point Leveling"); - - // Probe at 3 arbitrary points - points[0].z = points[1].z = points[2].z = 0; - - #endif // AUTO_BED_LEVELING_3POINT - } // !g29_in_progress #if ENABLED(PROBE_MANUALLY) @@ -450,7 +454,7 @@ G29_TYPE GcodeSuite::G29() { // For manual probing, get the next index to probe now. // On the first probe this will be incremented to 0. if (!no_action) { - ++abl_probe_index; + ++abl.abl_probe_index; g29_in_progress = true; } @@ -458,25 +462,23 @@ G29_TYPE GcodeSuite::G29() { if (seenA && g29_in_progress) { SERIAL_ECHOLNPGM("Manual G29 aborted"); SET_SOFT_ENDSTOP_LOOSE(false); - set_bed_leveling_enabled(abl_should_enable); + set_bed_leveling_enabled(abl.reenable); g29_in_progress = false; TERN_(LCD_BED_LEVELING, ui.wait_for_move = false); } // Query G29 status - if (verbose_level || seenQ) { + if (abl.verbose_level || seenQ) { SERIAL_ECHOPGM("Manual G29 "); - if (g29_in_progress) { - SERIAL_ECHOPAIR("point ", _MIN(abl_probe_index + 1, abl_points)); - SERIAL_ECHOLNPAIR(" of ", abl_points); - } + if (g29_in_progress) + SERIAL_ECHOLNPAIR("point ", _MIN(abl.abl_probe_index + 1, abl.abl_points), " of ", abl.abl_points); else SERIAL_ECHOLNPGM("idle"); } if (no_action) G29_RETURN(false); - if (abl_probe_index == 0) { + if (abl.abl_probe_index == 0) { // For the initial G29 S2 save software endstop state SET_SOFT_ENDSTOP_LOOSE(true); // Move close to the bed before the first point @@ -485,34 +487,34 @@ G29_TYPE GcodeSuite::G29() { else { #if EITHER(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT) - const uint16_t index = abl_probe_index - 1; + const uint16_t index = abl.abl_probe_index - 1; #endif // For G29 after adjusting Z. // Save the previous Z before going to the next point - measured_z = current_position.z; + abl.measured_z = current_position.z; #if ENABLED(AUTO_BED_LEVELING_LINEAR) - mean += measured_z; - eqnBVector[index] = measured_z; - eqnAMatrix[index + 0 * abl_points] = probePos.x; - eqnAMatrix[index + 1 * abl_points] = probePos.y; - eqnAMatrix[index + 2 * abl_points] = 1; + abl.mean += abl.measured_z; + abl.eqnBVector[index] = abl.measured_z; + abl.eqnAMatrix[index + 0 * abl.abl_points] = abl.probePos.x; + abl.eqnAMatrix[index + 1 * abl.abl_points] = abl.probePos.y; + abl.eqnAMatrix[index + 2 * abl.abl_points] = 1; - incremental_LSF(&lsf_results, probePos, measured_z); + incremental_LSF(&lsf_results, abl.probePos, abl.measured_z); #elif ENABLED(AUTO_BED_LEVELING_3POINT) - points[index].z = measured_z; + points[index].z = abl.measured_z; #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) - const float newz = measured_z + zoffset; - z_values[meshCount.x][meshCount.y] = newz; - TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(meshCount, newz)); + const float newz = abl.measured_z + abl.Z_offset; + z_values[abl.meshCount.x][abl.meshCount.y] = newz; + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(abl.meshCount, newz)); - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR_P(PSTR("Save X"), meshCount.x, SP_Y_STR, meshCount.y, SP_Z_STR, measured_z + zoffset); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR_P(PSTR("Save X"), abl.meshCount.x, SP_Y_STR, abl.meshCount.y, SP_Z_STR, abl.measured_z + abl.Z_offset); #endif } @@ -521,31 +523,31 @@ G29_TYPE GcodeSuite::G29() { // If there's another point to sample, move there with optional lift. // - #if ABL_GRID + #if ABL_USES_GRID // Skip any unreachable points - while (abl_probe_index < abl_points) { + while (abl.abl_probe_index < abl.abl_points) { - // Set meshCount.x, meshCount.y based on abl_probe_index, with zig-zag - PR_OUTER_VAR = abl_probe_index / PR_INNER_END; - PR_INNER_VAR = abl_probe_index - (PR_OUTER_VAR * PR_INNER_END); + // Set abl.meshCount.x, abl.meshCount.y based on abl.abl_probe_index, with zig-zag + PR_OUTER_VAR = abl.abl_probe_index / PR_INNER_SIZE; + PR_INNER_VAR = abl.abl_probe_index - (PR_OUTER_VAR * PR_INNER_SIZE); // Probe in reverse order for every other row/column - const bool zig = (PR_OUTER_VAR & 1); // != ((PR_OUTER_END) & 1); - if (zig) PR_INNER_VAR = (PR_INNER_END - 1) - PR_INNER_VAR; + const bool zig = (PR_OUTER_VAR & 1); // != ((PR_OUTER_SIZE) & 1); + if (zig) PR_INNER_VAR = (PR_INNER_SIZE - 1) - PR_INNER_VAR; - probePos = probe_position_lf + gridSpacing * meshCount.asFloat(); + abl.probePos = abl.probe_position_lf + abl.gridSpacing * abl.meshCount.asFloat(); - TERN_(AUTO_BED_LEVELING_LINEAR, indexIntoAB[meshCount.x][meshCount.y] = abl_probe_index); + TERN_(AUTO_BED_LEVELING_LINEAR, abl.indexIntoAB[abl.meshCount.x][abl.meshCount.y] = abl.abl_probe_index); // Keep looping till a reachable point is found - if (position_is_reachable(probePos)) break; - ++abl_probe_index; + if (position_is_reachable(abl.probePos)) break; + ++abl.abl_probe_index; } // Is there a next point to move to? - if (abl_probe_index < abl_points) { - _manual_goto_xy(probePos); // Can be used here too! + if (abl.abl_probe_index < abl.abl_points) { + _manual_goto_xy(abl.probePos); // Can be used here too! // Disable software endstops to allow manual adjustment // If G29 is not completed, they will not be re-enabled SET_SOFT_ENDSTOP_LOOSE(true); @@ -561,9 +563,9 @@ G29_TYPE GcodeSuite::G29() { #elif ENABLED(AUTO_BED_LEVELING_3POINT) // Probe at 3 arbitrary points - if (abl_probe_index < abl_points) { - probePos = points[abl_probe_index]; - _manual_goto_xy(probePos); + if (abl.abl_probe_index < abl.abl_points) { + abl.probePos = xy_pos_t(points[abl.abl_probe_index]); + _manual_goto_xy(abl.probePos); // Disable software endstops to allow manual adjustment // If G29 is not completed, they will not be re-enabled SET_SOFT_ENDSTOP_LOOSE(true); @@ -576,13 +578,13 @@ G29_TYPE GcodeSuite::G29() { // Re-enable software endstops, if needed SET_SOFT_ENDSTOP_LOOSE(false); - if (!dryrun) { + if (!abl.dryrun) { vector_3 planeNormal = vector_3::cross(points[0] - points[1], points[2] - points[1]).get_normal(); if (planeNormal.z < 0) planeNormal *= -1; planner.bed_level_matrix = matrix_3x3::create_look_at(planeNormal); // Can't re-enable (on error) until the new grid is written - abl_should_enable = false; + abl.reenable = false; } } @@ -593,83 +595,82 @@ G29_TYPE GcodeSuite::G29() { { const ProbePtRaise raise_after = parser.boolval('E') ? PROBE_PT_STOW : PROBE_PT_RAISE; - measured_z = 0; - - #if ABL_GRID + abl.measured_z = 0; - bool zig = PR_OUTER_END & 1; // Always end at RIGHT and BACK_PROBE_BED_POSITION + #if ABL_USES_GRID - measured_z = 0; + bool zig = PR_OUTER_SIZE & 1; // Always end at RIGHT and BACK_PROBE_BED_POSITION - xy_int8_t meshCount; + abl.measured_z = 0; // Outer loop is X with PROBE_Y_FIRST enabled // Outer loop is Y with PROBE_Y_FIRST disabled - for (PR_OUTER_VAR = 0; PR_OUTER_VAR < PR_OUTER_END && !isnan(measured_z); PR_OUTER_VAR++) { + for (PR_OUTER_VAR = 0; PR_OUTER_VAR < PR_OUTER_SIZE && !isnan(abl.measured_z); PR_OUTER_VAR++) { int8_t inStart, inStop, inInc; - if (zig) { // Zig away from origin - inStart = 0; // Left or front - inStop = PR_INNER_END; // Right or back - inInc = 1; // Zig right + if (zig) { // Zig away from origin + inStart = 0; // Left or front + inStop = PR_INNER_SIZE; // Right or back + inInc = 1; // Zig right } - else { // Zag towards origin - inStart = PR_INNER_END - 1; // Right or back - inStop = -1; // Left or front - inInc = -1; // Zag left + else { // Zag towards origin + inStart = PR_INNER_SIZE - 1; // Right or back + inStop = -1; // Left or front + inInc = -1; // Zag left } zig ^= true; // zag // An index to print current state - uint8_t pt_index = (PR_OUTER_VAR) * (PR_INNER_END) + 1; + uint8_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 for (PR_INNER_VAR = inStart; PR_INNER_VAR != inStop; pt_index++, PR_INNER_VAR += inInc) { - probePos = probe_position_lf + gridSpacing * meshCount.asFloat(); + abl.probePos = abl.probe_position_lf + abl.gridSpacing * abl.meshCount.asFloat(); - TERN_(AUTO_BED_LEVELING_LINEAR, indexIntoAB[meshCount.x][meshCount.y] = ++abl_probe_index); // 0... + TERN_(AUTO_BED_LEVELING_LINEAR, abl.indexIntoAB[abl.meshCount.x][abl.meshCount.y] = ++abl.abl_probe_index); // 0... // Avoid probing outside the round or hexagonal area - if (TERN0(IS_KINEMATIC, !probe.can_reach(probePos))) continue; + if (TERN0(IS_KINEMATIC, !probe.can_reach(abl.probePos))) continue; - if (verbose_level) SERIAL_ECHOLNPAIR("Probing mesh point ", int(pt_index), "/", abl_points, "."); - TERN_(HAS_DISPLAY, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_MESH), int(pt_index), int(abl_points))); + if (abl.verbose_level) SERIAL_ECHOLNPAIR("Probing mesh point ", pt_index, "/", abl.abl_points, "."); + TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_MESH), int(pt_index), int(abl.abl_points))); - measured_z = faux ? 0.001f * random(-100, 101) : probe.probe_at_point(probePos, raise_after, verbose_level); + abl.measured_z = faux ? 0.001f * random(-100, 101) : probe.probe_at_point(abl.probePos, raise_after, abl.verbose_level); - if (isnan(measured_z)) { - set_bed_leveling_enabled(abl_should_enable); + if (isnan(abl.measured_z)) { + set_bed_leveling_enabled(abl.reenable); break; // Breaks out of both loops } #if ENABLED(PROBE_TEMP_COMPENSATION) - temp_comp.compensate_measurement(TSI_BED, thermalManager.degBed(), measured_z); - temp_comp.compensate_measurement(TSI_PROBE, thermalManager.degProbe(), measured_z); - TERN_(USE_TEMP_EXT_COMPENSATION, temp_comp.compensate_measurement(TSI_EXT, thermalManager.degHotend(), measured_z)); + temp_comp.compensate_measurement(TSI_BED, thermalManager.degBed(), abl.measured_z); + temp_comp.compensate_measurement(TSI_PROBE, thermalManager.degProbe(), abl.measured_z); + TERN_(USE_TEMP_EXT_COMPENSATION, temp_comp.compensate_measurement(TSI_EXT, thermalManager.degHotend(), abl.measured_z)); #endif #if ENABLED(AUTO_BED_LEVELING_LINEAR) - mean += measured_z; - eqnBVector[abl_probe_index] = measured_z; - eqnAMatrix[abl_probe_index + 0 * abl_points] = probePos.x; - eqnAMatrix[abl_probe_index + 1 * abl_points] = probePos.y; - eqnAMatrix[abl_probe_index + 2 * abl_points] = 1; + abl.mean += abl.measured_z; + abl.eqnBVector[abl.abl_probe_index] = abl.measured_z; + abl.eqnAMatrix[abl.abl_probe_index + 0 * abl.abl_points] = abl.probePos.x; + abl.eqnAMatrix[abl.abl_probe_index + 1 * abl.abl_points] = abl.probePos.y; + abl.eqnAMatrix[abl.abl_probe_index + 2 * abl.abl_points] = 1; - incremental_LSF(&lsf_results, probePos, measured_z); + incremental_LSF(&lsf_results, abl.probePos, abl.measured_z); #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) - z_values[meshCount.x][meshCount.y] = measured_z + zoffset; - TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(meshCount, z_values[meshCount.x][meshCount.y])); + const float z = abl.measured_z + abl.Z_offset; + z_values[abl.meshCount.x][abl.meshCount.y] = z; + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(abl.meshCount, z)); #endif - abl_should_enable = false; + abl.reenable = false; idle_no_sleep(); } // inner @@ -680,36 +681,36 @@ G29_TYPE GcodeSuite::G29() { // Probe at 3 arbitrary points LOOP_L_N(i, 3) { - if (verbose_level) SERIAL_ECHOLNPAIR("Probing point ", int(i + 1), "/3."); - TERN_(HAS_DISPLAY, ui.status_printf_P(0, PSTR(S_FMT " %i/3"), GET_TEXT(MSG_PROBING_MESH), int(i + 1))); + if (abl.verbose_level) SERIAL_ECHOLNPAIR("Probing point ", i + 1, "/3."); + TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/3"), GET_TEXT(MSG_PROBING_MESH), int(i + 1))); // Retain the last probe position - probePos = points[i]; - measured_z = faux ? 0.001 * random(-100, 101) : probe.probe_at_point(probePos, raise_after, verbose_level); - if (isnan(measured_z)) { - set_bed_leveling_enabled(abl_should_enable); + abl.probePos = xy_pos_t(points[i]); + abl.measured_z = faux ? 0.001 * random(-100, 101) : probe.probe_at_point(abl.probePos, raise_after, abl.verbose_level); + if (isnan(abl.measured_z)) { + set_bed_leveling_enabled(abl.reenable); break; } - points[i].z = measured_z; + points[i].z = abl.measured_z; } - if (!dryrun && !isnan(measured_z)) { + if (!abl.dryrun && !isnan(abl.measured_z)) { vector_3 planeNormal = vector_3::cross(points[0] - points[1], points[2] - points[1]).get_normal(); if (planeNormal.z < 0) planeNormal *= -1; planner.bed_level_matrix = matrix_3x3::create_look_at(planeNormal); // Can't re-enable (on error) until the new grid is written - abl_should_enable = false; + abl.reenable = false; } #endif // AUTO_BED_LEVELING_3POINT - TERN_(HAS_DISPLAY, ui.reset_status()); + TERN_(HAS_STATUS_MESSAGE, ui.reset_status()); // Stow the probe. No raise for FIX_MOUNTED_PROBE. if (probe.stow()) { - set_bed_leveling_enabled(abl_should_enable); - measured_z = NAN; + set_bed_leveling_enabled(abl.reenable); + abl.measured_z = NAN; } } #endif // !PROBE_MANUALLY @@ -732,10 +733,10 @@ G29_TYPE GcodeSuite::G29() { #endif // Calculate leveling, print reports, correct the position - if (!isnan(measured_z)) { + if (!isnan(abl.measured_z)) { #if ENABLED(AUTO_BED_LEVELING_BILINEAR) - if (!dryrun) extrapolate_unprobed_bed_level(); + if (!abl.dryrun) extrapolate_unprobed_bed_level(); print_bilinear_leveling_grid(); refresh_bed_level(); @@ -761,39 +762,39 @@ G29_TYPE GcodeSuite::G29() { plane_equation_coefficients.b = -lsf_results.B; // but that is not yet tested. plane_equation_coefficients.d = -lsf_results.D; - mean /= abl_points; + abl.mean /= abl.abl_points; - if (verbose_level) { + if (abl.verbose_level) { SERIAL_ECHOPAIR_F("Eqn coefficients: a: ", plane_equation_coefficients.a, 8); SERIAL_ECHOPAIR_F(" b: ", plane_equation_coefficients.b, 8); SERIAL_ECHOPAIR_F(" d: ", plane_equation_coefficients.d, 8); - if (verbose_level > 2) - SERIAL_ECHOPAIR_F("\nMean of sampled points: ", mean, 8); + if (abl.verbose_level > 2) + SERIAL_ECHOPAIR_F("\nMean of sampled points: ", abl.mean, 8); SERIAL_EOL(); } // Create the matrix but don't correct the position yet - if (!dryrun) + if (!abl.dryrun) planner.bed_level_matrix = matrix_3x3::create_look_at( vector_3(-plane_equation_coefficients.a, -plane_equation_coefficients.b, 1) // We can eliminate the '-' here and up above ); // Show the Topography map if enabled - if (do_topography_map) { + if (abl.topography_map) { float min_diff = 999; auto print_topo_map = [&](PGM_P const title, const bool get_min) { - serialprintPGM(title); - for (int8_t yy = abl_grid_points.y - 1; yy >= 0; yy--) { - LOOP_L_N(xx, abl_grid_points.x) { - const int ind = indexIntoAB[xx][yy]; - xyz_float_t tmp = { eqnAMatrix[ind + 0 * abl_points], - eqnAMatrix[ind + 1 * abl_points], 0 }; - apply_rotation_xyz(planner.bed_level_matrix, tmp); - if (get_min) NOMORE(min_diff, eqnBVector[ind] - tmp.z); - const float subval = get_min ? mean : tmp.z + min_diff, - diff = eqnBVector[ind] - subval; + SERIAL_ECHOPGM_P(title); + for (int8_t yy = abl.grid_points.y - 1; yy >= 0; yy--) { + LOOP_L_N(xx, abl.grid_points.x) { + 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 }; + planner.bed_level_matrix.apply_rotation_xyz(tmp.x, tmp.y, tmp.z); + if (get_min) NOMORE(min_diff, abl.eqnBVector[ind] - tmp.z); + const float subval = get_min ? abl.mean : tmp.z + min_diff, + diff = abl.eqnBVector[ind] - subval; SERIAL_CHAR(' '); if (diff >= 0.0) SERIAL_CHAR('+'); // Include + for column alignment SERIAL_ECHO_F(diff, 5); } // xx @@ -813,10 +814,10 @@ G29_TYPE GcodeSuite::G29() { " | |\n" " O-- FRONT --+\n" " (0,0)\n"), true); - if (verbose_level > 3) + if (abl.verbose_level > 3) print_topo_map(PSTR("\nCorrected Bed Height vs. Bed Topology:\n"), false); - } //do_topography_map + } // abl.topography_map #endif // AUTO_BED_LEVELING_LINEAR @@ -824,10 +825,10 @@ G29_TYPE GcodeSuite::G29() { // For LINEAR and 3POINT leveling correct the current position - if (verbose_level > 0) + if (abl.verbose_level > 0) planner.bed_level_matrix.debug(PSTR("\n\nBed Level Correction Matrix:")); - if (!dryrun) { + if (!abl.dryrun) { // // Correct the current XYZ position based on the tilted plane. // @@ -838,10 +839,10 @@ G29_TYPE GcodeSuite::G29() { planner.force_unapply_leveling(converted); // use conversion machinery // Use the last measured distance to the bed, if possible - if ( NEAR(current_position.x, probePos.x - probe.offset_xy.x) - && NEAR(current_position.y, probePos.y - probe.offset_xy.y) + if ( NEAR(current_position.x, abl.probePos.x - probe.offset_xy.x) + && NEAR(current_position.y, abl.probePos.y - probe.offset_xy.y) ) { - const float simple_z = current_position.z - measured_z; + const float simple_z = current_position.z - abl.measured_z; if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Probed Z", simple_z, " Matrix Z", converted.z, " Discrepancy ", simple_z - converted.z); converted.z = simple_z; } @@ -854,7 +855,7 @@ G29_TYPE GcodeSuite::G29() { #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) - if (!dryrun) { + if (!abl.dryrun) { if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("G29 uncorrected Z:", current_position.z); // Unapply the offset because it is going to be immediately applied @@ -868,8 +869,8 @@ G29_TYPE GcodeSuite::G29() { #endif // ABL_PLANAR // Auto Bed Leveling is complete! Enable if possible. - planner.leveling_active = dryrun ? abl_should_enable : true; - } // !isnan(measured_z) + planner.leveling_active = !abl.dryrun || abl.reenable; + } // !isnan(abl.measured_z) // Restore state after probing if (!faux) restore_feedrate_and_scaling(); @@ -893,7 +894,10 @@ G29_TYPE GcodeSuite::G29() { report_current_position(); - G29_RETURN(isnan(measured_z)); + TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_IDLE)); + + G29_RETURN(isnan(abl.measured_z)); + } #endif // HAS_ABL_NOT_UBL diff --git a/Marlin/src/gcode/bedlevel/mbl/G29.cpp b/Marlin/src/gcode/bedlevel/mbl/G29.cpp index d94c16052bcf..984e008d2782 100644 --- a/Marlin/src/gcode/bedlevel/mbl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/mbl/G29.cpp @@ -34,7 +34,7 @@ #include "../../queue.h" #include "../../../libs/buzzer.h" -#include "../../../lcd/ultralcd.h" +#include "../../../lcd/marlinui.h" #include "../../../module/motion.h" #include "../../../module/stepper.h" @@ -42,6 +42,9 @@ #include "../../../lcd/extui/ui_api.h" #endif +#define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) +#include "../../../core/debug_out.h" + // Save 130 bytes with non-duplication of PSTR inline void echo_not_entered(const char c) { SERIAL_CHAR(c); SERIAL_ECHOLNPGM(" not entered."); } @@ -59,6 +62,18 @@ 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 + #if ENABLED(DEBUG_LEVELING_FEATURE) + const bool seenQ = parser.seen_test('Q'); + if (seenQ || DEBUGGING(LEVELING)) { + log_machine_info(); + if (seenQ) return; + } + #endif + + TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_PROBE)); static int mbl_probe_index = -1; @@ -69,6 +84,7 @@ void GcodeSuite::G29() { } int8_t ix, iy; + ix = iy = 0; switch (state) { case MeshReport: @@ -85,7 +101,8 @@ void GcodeSuite::G29() { mbl.reset(); mbl_probe_index = 0; if (!ui.wait_for_move) { - queue.inject_P(PSTR("G28\nG29 S2")); + queue.inject_P(parser.seen_test('N') ? PSTR("G28" TERN(CAN_SET_LEVELING_AFTER_G28, "L0", "") "\nG29S2") : PSTR("G29S2")); + TERN_(EXTENSIBLE_UI, ExtUI::onMeshLevelingStart()); return; } state = MeshNext; @@ -98,15 +115,20 @@ void GcodeSuite::G29() { // For each G29 S2... if (mbl_probe_index == 0) { // Move close to the bed before the first point - do_blocking_move_to_z(0); + do_blocking_move_to_z(0.4f + #ifdef MANUAL_PROBE_START_Z + + (MANUAL_PROBE_START_Z) - 0.4f + #endif + ); } else { // Save Z for the previous mesh position mbl.set_zigzag_z(mbl_probe_index - 1, current_position.z); + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ix, iy, current_position.z)); 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); @@ -114,14 +136,21 @@ void GcodeSuite::G29() { _manual_goto_xy({ mbl.index_to_xpos[ix], mbl.index_to_ypos[iy] }); } else { - // One last "return to the bed" (as originally coded) at completion - current_position.z = MANUAL_PROBE_HEIGHT; + // Move to the after probing position + current_position.z = ( + #ifdef Z_AFTER_PROBING + Z_AFTER_PROBING + #else + Z_CLEARANCE_BETWEEN_MANUAL_PROBES + #endif + ); line_to_current_position(); planner.synchronize(); // After recording the last point, activate home and activate mbl_probe_index = -1; SERIAL_ECHOLNPGM("Mesh probing done."); + TERN_(HAS_STATUS_MESSAGE, ui.set_status(GET_TEXT(MSG_MESH_DONE))); BUZZ(100, 659); BUZZ(100, 698); @@ -141,9 +170,8 @@ void GcodeSuite::G29() { case MeshSet: if (parser.seenval('I')) { ix = parser.value_int(); - if (!WITHIN(ix, 0, GRID_MAX_POINTS_X - 1)) { - SERIAL_ECHOPAIR("I out of range (0-", int(GRID_MAX_POINTS_X - 1)); - SERIAL_ECHOLNPGM(")"); + if (!WITHIN(ix, 0, (GRID_MAX_POINTS_X) - 1)) { + SERIAL_ECHOLNPAIR("I out of range (0-", (GRID_MAX_POINTS_X) - 1, ")"); return; } } @@ -152,9 +180,8 @@ void GcodeSuite::G29() { if (parser.seenval('J')) { iy = parser.value_int(); - if (!WITHIN(iy, 0, GRID_MAX_POINTS_Y - 1)) { - SERIAL_ECHOPAIR("J out of range (0-", int(GRID_MAX_POINTS_Y - 1)); - SERIAL_ECHOLNPGM(")"); + if (!WITHIN(iy, 0, (GRID_MAX_POINTS_Y) - 1)) { + SERIAL_ECHOLNPAIR("J out of range (0-", (GRID_MAX_POINTS_Y) - 1, ")"); return; } } @@ -183,11 +210,13 @@ void GcodeSuite::G29() { } // switch(state) if (state == MeshNext) { - SERIAL_ECHOPAIR("MBL G29 point ", _MIN(mbl_probe_index, GRID_MAX_POINTS)); - SERIAL_ECHOLNPAIR(" of ", int(GRID_MAX_POINTS)); + SERIAL_ECHOLNPAIR("MBL G29 point ", _MIN(mbl_probe_index, GRID_MAX_POINTS), " of ", GRID_MAX_POINTS); + if (mbl_probe_index > 0) TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_MESH), _MIN(mbl_probe_index, GRID_MAX_POINTS), int(GRID_MAX_POINTS))); } report_current_position(); + + TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_IDLE)); } #endif // MESH_BED_LEVELING diff --git a/Marlin/src/gcode/bedlevel/ubl/G29.cpp b/Marlin/src/gcode/bedlevel/ubl/G29.cpp index 2ef3ab4ceca9..932503d72b97 100644 --- a/Marlin/src/gcode/bedlevel/ubl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/ubl/G29.cpp @@ -31,6 +31,17 @@ #include "../../gcode.h" #include "../../../feature/bedlevel/bedlevel.h" -void GcodeSuite::G29() { ubl.G29(); } +#if ENABLED(FULL_REPORT_TO_HOST_FEATURE) + #include "../../../module/motion.h" +#endif + +void GcodeSuite::G29() { + + TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_PROBE)); + + ubl.G29(); + + TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_IDLE)); +} #endif // AUTO_BED_LEVELING_UBL diff --git a/Marlin/src/gcode/bedlevel/ubl/M421.cpp b/Marlin/src/gcode/bedlevel/ubl/M421.cpp index 600c1fc8ba51..f1e1b76126ed 100644 --- a/Marlin/src/gcode/bedlevel/ubl/M421.cpp +++ b/Marlin/src/gcode/bedlevel/ubl/M421.cpp @@ -21,7 +21,7 @@ */ /** - * unified.cpp - Unified Bed Leveling + * M421.cpp - Unified Bed Leveling */ #include "../../../inc/MarlinConfig.h" @@ -39,31 +39,34 @@ * M421: Set a single Mesh Bed Leveling Z coordinate * * Usage: - * M421 I J Z - * M421 I J Q - * M421 I J N - * M421 C Z - * M421 C Q + * M421 I J Z : Set the Mesh Point IJ to the Z value + * M421 I J Q : Add the Q value to the Mesh Point IJ + * M421 I J N : Set the Mesh Point IJ to NAN (not set) + * M421 C Z : Set the closest Mesh Point to the Z value + * M421 C Q : Add the Q value to the closest Mesh Point */ void GcodeSuite::M421() { xy_int8_t ij = { int8_t(parser.intval('I', -1)), int8_t(parser.intval('J', -1)) }; const bool hasI = ij.x >= 0, hasJ = ij.y >= 0, - hasC = parser.seen('C'), - hasN = parser.seen('N'), + hasC = parser.seen_test('C'), + hasN = parser.seen_test('N'), hasZ = parser.seen('Z'), hasQ = !hasZ && parser.seen('Q'); - if (hasC) ij = ubl.find_closest_mesh_point_of_type(REAL, current_position); + if (hasC) ij = ubl.find_closest_mesh_point_of_type(CLOSEST, current_position); + // Test for bad parameter combinations if (int(hasC) + int(hasI && hasJ) != 1 || !(hasZ || hasQ || hasN)) SERIAL_ERROR_MSG(STR_ERR_M421_PARAMETERS); + + // Test for I J out of range 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 = ubl.z_values[ij.x][ij.y]; - zval = hasN ? NAN : parser.value_linear_units() + (hasQ ? zval : 0); - TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ij.x, ij.y, zval)); + float &zval = ubl.z_values[ij.x][ij.y]; // Altering this Mesh Point + zval = hasN ? NAN : parser.value_linear_units() + (hasQ ? zval : 0); // N=NAN, Z=NEWVAL, or Q=ADDVAL + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ij.x, ij.y, zval)); // Ping ExtUI in case it's showing the mesh } } diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index 34209568035d..f78106b56a2f 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -45,9 +45,13 @@ #include "../../feature/bltouch.h" #endif -#include "../../lcd/ultralcd.h" +#include "../../lcd/marlinui.h" #if ENABLED(DWIN_CREALITY_LCD) - #include "../../lcd/dwin/e3v2/dwin.h" + #include "../../lcd/e3v2/creality/dwin.h" +#endif + +#if ENABLED(EXTENSIBLE_UI) + #include "../../lcd/extui/ui_api.h" #endif #if HAS_L64XX // set L6470 absolute position registers to counts @@ -69,7 +73,7 @@ current_position.set(0.0, 0.0); sync_plan_position(); - const int x_axis_home_dir = x_home_dir(active_extruder); + const int x_axis_home_dir = TOOL_X_HOME_DIR(active_extruder); const float mlx = max_length(X_AXIS), mly = max_length(Y_AXIS), @@ -92,13 +96,13 @@ }; #endif - do_blocking_move_to_xy(1.5 * mlx * x_axis_home_dir, 1.5 * mly * home_dir(Y_AXIS), fr_mm_s); + do_blocking_move_to_xy(1.5 * mlx * x_axis_home_dir, 1.5 * mly * Y_HOME_DIR, fr_mm_s); endstops.validate_homing_move(); current_position.set(0.0, 0.0); - #if ENABLED(SENSORLESS_HOMING) + #if ENABLED(SENSORLESS_HOMING) && DISABLED(ENDSTOPS_ALWAYS_ON_DEFAULT) tmc_disable_stallguard(stepperX, stealth_states.x); tmc_disable_stallguard(stepperY, stealth_states.y); #if AXIS_HAS_STALLGUARD(X2) @@ -126,7 +130,15 @@ * Move the Z probe (or just the nozzle) to the safe homing point * (Z is already at the right height) */ - destination.set(safe_homing_xy, current_position.z); + constexpr xy_float_t safe_homing_xy = { Z_SAFE_HOMING_X_POINT, Z_SAFE_HOMING_Y_POINT }; + #if HAS_HOME_OFFSET + xy_float_t okay_homing_xy = safe_homing_xy; + okay_homing_xy -= home_offset; + #else + constexpr xy_float_t okay_homing_xy = safe_homing_xy; + #endif + + destination.set(okay_homing_xy, current_position.z); TERN_(HOMING_Z_WITH_PROBE, destination -= probe.offset_xy); @@ -134,8 +146,8 @@ if (DEBUGGING(LEVELING)) DEBUG_POS("home_z_safely", destination); - // This causes the carriage on Dual X to unpark - TERN_(DUAL_X_CARRIAGE, active_extruder_parked = false); + // Free the active extruder for movement + TERN_(DUAL_X_CARRIAGE, idex_set_parked(false)); TERN_(SENSORLESS_HOMING, safe_delay(500)); // Short delay needed to settle @@ -152,24 +164,28 @@ #if ENABLED(IMPROVE_HOMING_RELIABILITY) - slow_homing_t begin_slow_homing() { - slow_homing_t slow_homing{0}; - slow_homing.acceleration.set(planner.settings.max_acceleration_mm_per_s2[X_AXIS], - planner.settings.max_acceleration_mm_per_s2[Y_AXIS]); + motion_state_t begin_slow_homing() { + motion_state_t motion_state{0}; + motion_state.acceleration.set(planner.settings.max_acceleration_mm_per_s2[X_AXIS], + planner.settings.max_acceleration_mm_per_s2[Y_AXIS] + OPTARG(DELTA, planner.settings.max_acceleration_mm_per_s2[Z_AXIS]) + ); planner.settings.max_acceleration_mm_per_s2[X_AXIS] = 100; planner.settings.max_acceleration_mm_per_s2[Y_AXIS] = 100; + TERN_(DELTA, planner.settings.max_acceleration_mm_per_s2[Z_AXIS] = 100); #if HAS_CLASSIC_JERK - slow_homing.jerk_xy = planner.max_jerk; - planner.max_jerk.set(0, 0); + motion_state.jerk_state = planner.max_jerk; + planner.max_jerk.set(0, 0 OPTARG(DELTA, 0)); #endif planner.reset_acceleration_rates(); - return slow_homing; + return motion_state; } - void end_slow_homing(const slow_homing_t &slow_homing) { - planner.settings.max_acceleration_mm_per_s2[X_AXIS] = slow_homing.acceleration.x; - planner.settings.max_acceleration_mm_per_s2[Y_AXIS] = slow_homing.acceleration.y; - TERN_(HAS_CLASSIC_JERK, planner.max_jerk = slow_homing.jerk_xy); + void end_slow_homing(const motion_state_t &motion_state) { + planner.settings.max_acceleration_mm_per_s2[X_AXIS] = motion_state.acceleration.x; + planner.settings.max_acceleration_mm_per_s2[Y_AXIS] = motion_state.acceleration.y; + TERN_(DELTA, planner.settings.max_acceleration_mm_per_s2[Z_AXIS] = motion_state.acceleration.z); + TERN_(HAS_CLASSIC_JERK, planner.max_jerk = motion_state.jerk_state); planner.reset_acceleration_rates(); } @@ -183,9 +199,9 @@ * None Home to all axes with no parameters. * With QUICK_HOME enabled XY will home together, then Z. * - * O Home only if position is unknown - * - * Rn Raise by n mm/inches before homing + * L Force leveling state ON (if possible) or OFF after homing (Requires RESTORE_LEVELING_AFTER_G28 or ENABLE_LEVELING_AFTER_G28) + * O Home only if the position is not known and trusted + * R Raise by n mm/inches before homing * * Cartesian/SCARA parameters * @@ -199,7 +215,7 @@ void GcodeSuite::G28() { TERN_(LASER_MOVE_G28_OFF, cutter.set_inline_enabled(false)); // turn off laser - TERN_(DWIN_CREALITY_LCD, HMI_flag.home_flag = true); + TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_HOMING)); #if ENABLED(DUAL_X_CARRIAGE) bool IDEX_saved_duplication_state = extruder_duplication_enabled; @@ -207,8 +223,8 @@ void GcodeSuite::G28() { #endif #if ENABLED(MARLIN_DEV_MODE) - if (parser.seen('S')) { - LOOP_XYZ(a) set_axis_is_at_home((AxisEnum)a); + if (parser.seen_test('S')) { + LOOP_LINEAR_AXES(a) set_axis_is_at_home((AxisEnum)a); sync_plan_position(); SERIAL_ECHOLNPGM("Simulated Homing"); report_current_position(); @@ -217,38 +233,43 @@ void GcodeSuite::G28() { #endif // Home (O)nly if position is unknown - if (!homing_needed() && parser.boolval('O')) { + if (!axes_should_home() && parser.seen_test('O')) { if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("> homing not needed, skip"); return; } + TERN_(DWIN_CREALITY_LCD, DWIN_StartHoming()); + TERN_(EXTENSIBLE_UI, ExtUI::onHomingStart()); + planner.synchronize(); // Wait for planner moves to finish! SET_SOFT_ENDSTOP_LOOSE(false); // Reset a leftover 'loose' motion state // Disable the leveling matrix before homing - #if HAS_LEVELING + #if CAN_SET_LEVELING_AFTER_G28 + const bool leveling_restore_state = parser.boolval('L', TERN1(RESTORE_LEVELING_AFTER_G28, planner.leveling_active)); + #endif - // Cancel the active G29 session - TERN_(PROBE_MANUALLY, g29_in_progress = false); + // Cancel any prior G29 session + TERN_(PROBE_MANUALLY, g29_in_progress = false); - TERN_(RESTORE_LEVELING_AFTER_G28, const bool leveling_was_active = planner.leveling_active); - set_bed_leveling_enabled(false); - #endif + // Disable leveling before homing + TERN_(HAS_LEVELING, set_bed_leveling_enabled(false)); + // Reset to the XY plane TERN_(CNC_WORKSPACE_PLANES, workspace_plane = PLANE_XY); // Count this command as movement / activity reset_stepper_timeout(); #define HAS_CURRENT_HOME(N) (defined(N##_CURRENT_HOME) && N##_CURRENT_HOME != N##_CURRENT) - #if HAS_CURRENT_HOME(X) || HAS_CURRENT_HOME(X2) || HAS_CURRENT_HOME(Y) || HAS_CURRENT_HOME(Y2) + #if HAS_CURRENT_HOME(X) || HAS_CURRENT_HOME(X2) || HAS_CURRENT_HOME(Y) || HAS_CURRENT_HOME(Y2) || (ENABLED(DELTA) && HAS_CURRENT_HOME(Z)) #define HAS_HOMING_CURRENT 1 #endif #if HAS_HOMING_CURRENT auto debug_current = [](PGM_P const s, const int16_t a, const int16_t b){ - serialprintPGM(s); DEBUG_ECHOLNPAIR(" current: ", a, " -> ", b); + DEBUG_ECHOPGM_P(s); DEBUG_ECHOLNPAIR(" current: ", a, " -> ", b); }; #if HAS_CURRENT_HOME(X) const int16_t tmc_save_current_X = stepperX.getMilliamps(); @@ -270,19 +291,30 @@ void GcodeSuite::G28() { stepperY2.rms_current(Y2_CURRENT_HOME); if (DEBUGGING(LEVELING)) debug_current(PSTR("Y2"), tmc_save_current_Y2, Y2_CURRENT_HOME); #endif + #if HAS_CURRENT_HOME(Z) && ENABLED(DELTA) + const int16_t tmc_save_current_Z = stepperZ.getMilliamps(); + stepperZ.rms_current(Z_CURRENT_HOME); + if (DEBUGGING(LEVELING)) debug_current(PSTR("Z"), tmc_save_current_Z, Z_CURRENT_HOME); + #endif #endif - TERN_(IMPROVE_HOMING_RELIABILITY, slow_homing_t slow_homing = begin_slow_homing()); + #if ENABLED(IMPROVE_HOMING_RELIABILITY) + motion_state_t saved_motion_state = begin_slow_homing(); + #endif // Always home with tool 0 active #if HAS_MULTI_HOTEND #if DISABLED(DELTA) || ENABLED(DELTA_HOME_TO_SAFE_ZONE) const uint8_t old_tool_index = active_extruder; #endif + // PARKING_EXTRUDER homing requires different handling of movement / solenoid activation, depending on the side of homing + #if ENABLED(PARKING_EXTRUDER) + const bool pe_final_change_must_unpark = parking_extruder_unpark_after_homing(old_tool_index, X_HOME_DIR + 1 == old_tool_index * 2); + #endif tool_change(0, true); #endif - TERN_(HAS_DUPLICATION_MODE, extruder_duplication_enabled = false); + TERN_(HAS_DUPLICATION_MODE, set_duplication_enabled(false)); remember_feedrate_scaling_off(); @@ -294,42 +326,60 @@ void GcodeSuite::G28() { home_delta(); - TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(slow_homing)); - - #else // NOT DELTA - - const bool homeZ = parser.seen('Z'), - needX = homeZ && TERN0(Z_SAFE_HOMING, axes_should_home(_BV(X_AXIS))), - needY = homeZ && TERN0(Z_SAFE_HOMING, axes_should_home(_BV(Y_AXIS))), - homeX = needX || parser.seen('X'), homeY = needY || parser.seen('Y'), - home_all = homeX == homeY && homeX == homeZ, // All or None - doX = home_all || homeX, doY = home_all || homeY, doZ = home_all || homeZ; - - #if Z_HOME_DIR > 0 // If homing away from BED do Z first - - if (doZ) homeaxis(Z_AXIS); - + TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(saved_motion_state)); + + #elif ENABLED(AXEL_TPARA) + + constexpr bool doZ = true; // for NANODLP_Z_SYNC if your DLP is on a TPARA + + home_TPARA(); + + #else + + #define _UNSAFE(A) (homeZ && TERN0(Z_SAFE_HOMING, axes_should_home(_BV(A##_AXIS)))) + + const bool homeZ = TERN0(HAS_Z_AXIS, parser.seen_test('Z')), + LINEAR_AXIS_LIST( // Other axes should be homed before Z safe-homing + needX = _UNSAFE(X), needY = _UNSAFE(Y), needZ = false, // UNUSED + needI = _UNSAFE(I), needJ = _UNSAFE(J), needK = _UNSAFE(K) + ), + LINEAR_AXIS_LIST( // Home each axis if needed or flagged + homeX = needX || parser.seen_test('X'), + homeY = needY || parser.seen_test('Y'), + homeZZ = homeZ, + homeI = needI || parser.seen_test(AXIS4_NAME), homeJ = needJ || parser.seen_test(AXIS5_NAME), homeK = needK || parser.seen_test(AXIS6_NAME), + ), + home_all = LINEAR_AXIS_GANG( // Home-all if all or none are flagged + homeX == homeX, && homeY == homeX, && homeZ == homeX, + && homeI == homeX, && homeJ == homeX, && homeK == homeX + ), + LINEAR_AXIS_LIST( + doX = home_all || homeX, doY = home_all || homeY, doZ = home_all || homeZ, + doI = home_all || homeI, doJ = home_all || homeJ, doK = home_all || homeK + ); + + #if HAS_Z_AXIS + UNUSED(needZ); UNUSED(homeZZ); + #else + constexpr bool doZ = false; #endif - const float z_homing_height = - ENABLED(UNKNOWN_Z_NO_RAISE) && !TEST(axis_known_position, Z_AXIS) - ? 0 - : (parser.seenval('R') ? parser.value_linear_units() : Z_HOMING_HEIGHT); + TERN_(HOME_Z_FIRST, if (doZ) homeaxis(Z_AXIS)); - if (z_homing_height && (doX || doY || (ENABLED(Z_SAFE_HOMING) && doZ))) { + const float z_homing_height = parser.seenval('R') ? parser.value_linear_units() : Z_HOMING_HEIGHT; + + if (z_homing_height && (LINEAR_AXIS_GANG(doX, || doY, || TERN0(Z_SAFE_HOMING, doZ), || doI, || doJ, || doK))) { // Raise Z before homing any other axes and z is not already high enough (never lower z) if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Raise Z (before homing) by ", z_homing_height); - do_z_clearance(z_homing_height, true, DISABLED(UNKNOWN_Z_NO_RAISE)); + do_z_clearance(z_homing_height); + TERN_(BLTOUCH, bltouch.init()); } - #if ENABLED(QUICK_HOME) - - if (doX && doY) quick_home_xy(); - - #endif + // Diagonal move first if both are homing + TERN_(QUICK_HOME, if (doX && doY) quick_home_xy()); // Home Y (before X) - if (ENABLED(HOME_Y_BEFORE_X) && (doY || (ENABLED(CODEPENDENT_XY_HOMING) && doX))) + if (ENABLED(HOME_Y_BEFORE_X) && (doY || TERN0(CODEPENDENT_XY_HOMING, doX))) homeaxis(Y_AXIS); // Home X @@ -342,16 +392,14 @@ void GcodeSuite::G28() { homeaxis(X_AXIS); // Remember this extruder's position for later tool change - inactive_extruder_x_pos = current_position.x; + inactive_extruder_x = current_position.x; // Home the 1st (left) extruder active_extruder = 0; homeaxis(X_AXIS); - // Consider the active extruder to be parked - raised_parked_position = current_position; - delayed_move_time = 0; - active_extruder_parked = true; + // Consider the active extruder to be in its "parked" position + idex_set_parked(); #else @@ -364,25 +412,34 @@ void GcodeSuite::G28() { if (DISABLED(HOME_Y_BEFORE_X) && doY) homeaxis(Y_AXIS); - TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(slow_homing)); + TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(saved_motion_state)); // Home Z last if homing towards the bed - #if Z_HOME_DIR < 0 - + #if HAS_Z_AXIS && DISABLED(HOME_Z_FIRST) if (doZ) { - TERN_(BLTOUCH, bltouch.init()); + #if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) + stepper.set_all_z_lock(false); + stepper.set_separate_multi_axis(false); + #endif TERN(Z_SAFE_HOMING, home_z_safely(), homeaxis(Z_AXIS)); - probe.move_z_after_homing(); + } + #endif - } // doZ - - #endif // Z_HOME_DIR < 0 + #if LINEAR_AXES >= 4 + if (doI) homeaxis(I_AXIS); + #endif + #if LINEAR_AXES >= 5 + if (doJ) homeaxis(J_AXIS); + #endif + #if LINEAR_AXES >= 6 + if (doK) homeaxis(K_AXIS); + #endif sync_plan_position(); - #endif // !DELTA (G28) + #endif /** * Preserve DXC mode across a G28 for IDEX printers in DXC_DUPLICATION_MODE. @@ -392,30 +449,28 @@ void GcodeSuite::G28() { */ #if ENABLED(DUAL_X_CARRIAGE) - if (dxc_is_duplicating()) { + if (idex_is_duplicating()) { - TERN_(IMPROVE_HOMING_RELIABILITY, slow_homing = begin_slow_homing()); + TERN_(IMPROVE_HOMING_RELIABILITY, saved_motion_state = begin_slow_homing()); // Always home the 2nd (right) extruder first active_extruder = 1; homeaxis(X_AXIS); // Remember this extruder's position for later tool change - inactive_extruder_x_pos = current_position.x; + inactive_extruder_x = current_position.x; // Home the 1st (left) extruder active_extruder = 0; homeaxis(X_AXIS); // Consider the active extruder to be parked - raised_parked_position = current_position; - delayed_move_time = 0; - active_extruder_parked = true; - extruder_duplication_enabled = IDEX_saved_duplication_state; - dual_x_carriage_mode = IDEX_saved_mode; - stepper.set_directions(); - - TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(slow_homing)); + idex_set_parked(); + + dual_x_carriage_mode = IDEX_saved_mode; + set_duplication_enabled(IDEX_saved_duplication_state); + + TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(saved_motion_state)); } #endif // DUAL_X_CARRIAGE @@ -425,18 +480,16 @@ void GcodeSuite::G28() { // Clear endstop state for polled stallGuard endstops TERN_(SPI_ENDSTOPS, endstops.clear_endstop_state()); - #if BOTH(DELTA, DELTA_HOME_TO_SAFE_ZONE) - // move to a height where we can use the full xy-area - do_blocking_move_to_z(delta_clip_start_height); - #endif + // Move to a height where we can use the full xy-area + TERN_(DELTA_HOME_TO_SAFE_ZONE, do_blocking_move_to_z(delta_clip_start_height)); - TERN_(RESTORE_LEVELING_AFTER_G28, set_bed_leveling_enabled(leveling_was_active)); + TERN_(CAN_SET_LEVELING_AFTER_G28, if (leveling_restore_state) set_bed_leveling_enabled()); restore_feedrate_and_scaling(); // Restore the active tool after homing #if HAS_MULTI_HOTEND && (DISABLED(DELTA) || ENABLED(DELTA_HOME_TO_SAFE_ZONE)) - tool_change(old_tool_index, NONE(PARKING_EXTRUDER, DUAL_X_CARRIAGE)); // Do move if one of these + tool_change(old_tool_index, TERN(PARKING_EXTRUDER, !pe_final_change_must_unpark, DISABLED(DUAL_X_CARRIAGE))); // Do move if one of these #endif #if HAS_HOMING_CURRENT @@ -453,26 +506,43 @@ void GcodeSuite::G28() { #if HAS_CURRENT_HOME(Y2) stepperY2.rms_current(tmc_save_current_Y2); #endif - #endif + #if HAS_CURRENT_HOME(Z) && ENABLED(DELTA) + stepperZ.rms_current(tmc_save_current_Z); + #endif + #if HAS_CURRENT_HOME(I) + stepperI.rms_current(tmc_save_current_I); + #endif + #if HAS_CURRENT_HOME(J) + stepperJ.rms_current(tmc_save_current_J); + #endif + #if HAS_CURRENT_HOME(K) + stepperK.rms_current(tmc_save_current_K); + #endif + #endif // HAS_HOMING_CURRENT ui.refresh(); TERN_(DWIN_CREALITY_LCD, DWIN_CompletedHoming()); + TERN_(EXTENSIBLE_UI, ExtUI::onHomingComplete()); report_current_position(); if (ENABLED(NANODLP_Z_SYNC) && (doZ || ENABLED(NANODLP_ALL_AXIS))) SERIAL_ECHOLNPGM(STR_Z_MOVE_COMP); + TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_IDLE)); + #if HAS_L64XX // Set L6470 absolute position registers to counts // constexpr *might* move this to PROGMEM. // If not, this will need a PROGMEM directive and an accessor. + #define _EN_ITEM(N) , E_AXIS static constexpr AxisEnum L64XX_axis_xref[MAX_L64XX] = { - X_AXIS, Y_AXIS, Z_AXIS, - X_AXIS, Y_AXIS, Z_AXIS, Z_AXIS, - E_AXIS, E_AXIS, E_AXIS, E_AXIS, E_AXIS, E_AXIS + LINEAR_AXIS_LIST(X_AXIS, Y_AXIS, Z_AXIS, I_AXIS, J_AXIS, K_AXIS), + X_AXIS, Y_AXIS, Z_AXIS, Z_AXIS, Z_AXIS + REPEAT(E_STEPPERS, _EN_ITEM) }; + #undef _EN_ITEM for (uint8_t j = 1; j <= L64XX::chain[0]; j++) { const uint8_t cv = L64XX::chain[j]; L64xxManager.set_param((L64XX_axis_t)cv, L6470_ABS_POS, stepper.position(L64XX_axis_xref[cv])); diff --git a/Marlin/src/gcode/calibrate/G33.cpp b/Marlin/src/gcode/calibrate/G33.cpp index 53af04d52876..a897a101157c 100644 --- a/Marlin/src/gcode/calibrate/G33.cpp +++ b/Marlin/src/gcode/calibrate/G33.cpp @@ -29,7 +29,7 @@ #include "../../module/motion.h" #include "../../module/stepper.h" #include "../../module/endstops.h" -#include "../../lcd/ultralcd.h" +#include "../../lcd/marlinui.h" #if HAS_BED_PROBE #include "../../module/probe.h" @@ -63,13 +63,17 @@ enum CalEnum : char { // the 7 main calibration points - #define LOOP_CAL_RAD(VAR) LOOP_CAL_PT(VAR, __A, _7P_STEP) #define LOOP_CAL_ACT(VAR, _4P, _OP) LOOP_CAL_PT(VAR, _OP ? _AB : __A, _4P ? _4P_STEP : _7P_STEP) -TERN_(HAS_MULTI_HOTEND, const uint8_t old_tool_index = active_extruder); +#if HAS_MULTI_HOTEND + const uint8_t old_tool_index = active_extruder; +#endif float lcd_probe_pt(const xy_pos_t &xy); void ac_home() { endstops.enable(true); + TERN_(SENSORLESS_HOMING, probe.set_homing_current(true)); home_delta(); + TERN_(SENSORLESS_HOMING, probe.set_homing_current(false)); endstops.not_homing(); } @@ -91,9 +95,9 @@ void ac_cleanup(TERN_(HAS_MULTI_HOTEND, const uint8_t old_tool_index)) { TERN_(HAS_MULTI_HOTEND, tool_change(old_tool_index, true)); } -void print_signed_float(PGM_P const prefix, const float &f) { +void print_signed_float(PGM_P const prefix, const_float_t f) { SERIAL_ECHOPGM(" "); - serialprintPGM(prefix); + SERIAL_ECHOPGM_P(prefix); SERIAL_CHAR(':'); if (f >= 0) SERIAL_CHAR('+'); SERIAL_ECHO_F(f, 2); @@ -345,7 +349,7 @@ static float auto_tune_a() { abc_float_t delta_e = { 0.0f }, delta_t = { 0.0f }; delta_t.reset(); - LOOP_XYZ(axis) { + LOOP_LINEAR_AXES(axis) { delta_t[axis] = diff; calc_kinematics_diff_probe_points(z_pt, delta_e, delta_r, delta_t); delta_t[axis] = 0; @@ -382,16 +386,24 @@ static float auto_tune_a() { * V3 Report settings and probe results * * E Engage the probe for each point + * + * With SENSORLESS_PROBING: + * Use these flags to calibrate stall sensitivity: (e.g., `G33 P1 Y Z` to calibrate X only.) + * X Don't activate stallguard on X. + * Y Don't activate stallguard on Y. + * Z Don't activate stallguard on Z. */ void GcodeSuite::G33() { + TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_PROBE)); + const int8_t probe_points = parser.intval('P', DELTA_CALIBRATION_DEFAULT_POINTS); if (!WITHIN(probe_points, 0, 10)) { SERIAL_ECHOLNPGM("?(P)oints implausible (0-10)."); return; } - const bool towers_set = !parser.seen('T'); + const bool towers_set = !parser.seen_test('T'); const float calibration_precision = parser.floatval('C', 0.0f); if (calibration_precision < 0) { @@ -411,7 +423,13 @@ void GcodeSuite::G33() { return; } - const bool stow_after_each = parser.seen('E'); + const bool stow_after_each = parser.seen_test('E'); + + #if ENABLED(SENSORLESS_PROBING) + probe.test_sensitivity.x = !parser.seen_test('X'); + TERN_(HAS_Y_AXIS, probe.test_sensitivity.y = !parser.seen_test('Y')); + TERN_(HAS_Z_AXIS, probe.test_sensitivity.z = !parser.seen_test('Z')); + #endif const bool _0p_calibration = probe_points == 0, _1p_calibration = probe_points == 1 || probe_points == -1, @@ -449,7 +467,7 @@ void GcodeSuite::G33() { // Report settings PGM_P const checkingac = PSTR("Checking... AC"); - serialprintPGM(checkingac); + SERIAL_ECHOPGM_P(checkingac); if (verbose_level == 0) SERIAL_ECHOPGM(" (DRY-RUN)"); SERIAL_EOL(); ui.set_status_P(checkingac); @@ -521,7 +539,7 @@ void GcodeSuite::G33() { case 1: test_precision = 0.0f; // forced end - LOOP_XYZ(axis) e_delta[axis] = +Z4(CEN); + LOOP_LINEAR_AXES(axis) e_delta[axis] = +Z4(CEN); break; case 2: @@ -569,21 +587,21 @@ void GcodeSuite::G33() { // Normalize angles to least-squares if (_angle_results) { float a_sum = 0.0f; - LOOP_XYZ(axis) a_sum += delta_tower_angle_trim[axis]; - LOOP_XYZ(axis) delta_tower_angle_trim[axis] -= a_sum / 3.0f; + LOOP_LINEAR_AXES(axis) a_sum += delta_tower_angle_trim[axis]; + LOOP_LINEAR_AXES(axis) delta_tower_angle_trim[axis] -= a_sum / 3.0f; } // adjust delta_height and endstops by the max amount const float z_temp = _MAX(delta_endstop_adj.a, delta_endstop_adj.b, delta_endstop_adj.c); delta_height -= z_temp; - LOOP_XYZ(axis) delta_endstop_adj[axis] -= z_temp; + LOOP_LINEAR_AXES(axis) delta_endstop_adj[axis] -= z_temp; } recalc_delta_settings(); NOMORE(zero_std_dev_min, zero_std_dev); // print report - if (verbose_level == 3) + if (verbose_level == 3 || verbose_level == 0) print_calibration_results(z_at_pt, _tower_results, _opposite_results); if (verbose_level != 0) { // !dry run @@ -625,7 +643,7 @@ void GcodeSuite::G33() { } else { // dry run PGM_P const enddryrun = PSTR("End DRY-RUN"); - serialprintPGM(enddryrun); + SERIAL_ECHOPGM_P(enddryrun); SERIAL_ECHO_SP(35); SERIAL_ECHOLNPAIR_F("std dev:", zero_std_dev, 3); @@ -643,6 +661,8 @@ void GcodeSuite::G33() { while (((zero_std_dev < test_precision && iterations < 31) || iterations <= force_iterations) && zero_std_dev > calibration_precision); ac_cleanup(TERN_(HAS_MULTI_HOTEND, old_tool_index)); + + TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_IDLE)); } #endif // DELTA_AUTO_CALIBRATION diff --git a/Marlin/src/gcode/calibrate/G34.cpp b/Marlin/src/gcode/calibrate/G34.cpp index 0ca4490eb6c1..f335a123114a 100644 --- a/Marlin/src/gcode/calibrate/G34.cpp +++ b/Marlin/src/gcode/calibrate/G34.cpp @@ -39,10 +39,11 @@ void GcodeSuite::G34() { // Home before the alignment procedure - if (!all_axes_known()) home_all_axes(); + home_if_needed(); + + TERN_(HAS_LEVELING, TEMPORARY_BED_LEVELING_STATE(false)); SET_SOFT_ENDSTOP_LOOSE(true); - TEMPORARY_BED_LEVELING_STATE(false); TemporaryGlobalEndstopsState unlock_z(false); #ifdef GANTRY_CALIBRATION_COMMANDS_PRE @@ -63,7 +64,7 @@ void GcodeSuite::G34() { // Move Z to pounce position if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Setting Z Pounce"); - do_blocking_move_to_z(zpounce, MMM_TO_MMS(HOMING_FEEDRATE_Z)); + do_blocking_move_to_z(zpounce, homing_feedrate(Z_AXIS)); // Store current motor settings, then apply reduced value @@ -84,7 +85,7 @@ void GcodeSuite::G34() { const float target_current = parser.floatval('S', GANTRY_CALIBRATION_CURRENT); const float previous_current = dac_amps(Z_AXIS, target_current); stepper_dac.set_current_value(Z_AXIS, target_current); - #elif ENABLED(HAS_MOTOR_CURRENT_I2C) + #elif HAS_MOTOR_CURRENT_I2C const uint16_t target_current = parser.intval('S', GANTRY_CALIBRATION_CURRENT); previous_current = dac_amps(Z_AXIS); digipot_i2c.set_current(Z_AXIS, target_current) @@ -128,7 +129,7 @@ void GcodeSuite::G34() { stepper.set_digipot_current(1, previous_current); #elif HAS_MOTOR_CURRENT_DAC stepper_dac.set_current_value(Z_AXIS, previous_current); - #elif ENABLED(HAS_MOTOR_CURRENT_I2C) + #elif HAS_MOTOR_CURRENT_I2C digipot_i2c.set_current(Z_AXIS, previous_current) #elif HAS_TRINAMIC_CONFIG #if AXIS_IS_TMC(Z) diff --git a/Marlin/src/gcode/calibrate/G34_M422.cpp b/Marlin/src/gcode/calibrate/G34_M422.cpp index 24292477f9c1..50f3419c8960 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 ENABLED(Z_STEPPER_AUTO_ALIGN) +#if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) #include "../../feature/z_stepper_align.h" @@ -31,7 +31,7 @@ #include "../../module/stepper.h" #include "../../module/planner.h" #include "../../module/probe.h" -#include "../../lcd/ultralcd.h" // for LCD_MESSAGEPGM +#include "../../lcd/marlinui.h" // for LCD_MESSAGEPGM #if HAS_LEVELING #include "../../feature/bedlevel/bedlevel.h" @@ -48,367 +48,415 @@ #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) #include "../../core/debug_out.h" +#if NUM_Z_STEPPER_DRIVERS >= 3 + #define TRIPLE_Z 1 + #if NUM_Z_STEPPER_DRIVERS >= 4 + #define QUAD_Z 1 + #endif +#endif + /** * G34: Z-Stepper automatic alignment * - * I - * T - * A - * R points based on current probe offsets + * Manual stepper lock controls (reset by G28): + * L Unlock all steppers + * Z<1-4> Z stepper to lock / unlock + * S 0=UNLOCKED 1=LOCKED. If omitted, assume LOCKED. + * + * Examples: + * G34 Z1 ; Lock Z1 + * G34 L Z2 ; Unlock all, then lock Z2 + * G34 Z2 S0 ; Unlock Z2 + * + * With Z_STEPPER_AUTO_ALIGN: + * I Number of tests. If omitted, Z_STEPPER_ALIGN_ITERATIONS. + * T Target Accuracy factor. If omitted, Z_STEPPER_ALIGN_ACC. + * A Provide an Amplification value. If omitted, Z_STEPPER_ALIGN_AMP. + * 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(); - do { // break out on error - - #if NUM_Z_STEPPER_DRIVERS == 4 - SERIAL_ECHOLNPGM("Alignment for 4 steppers is Experimental!"); - #elif NUM_Z_STEPPER_DRIVERS > 4 - SERIAL_ECHOLNPGM("Alignment not supported for over 4 steppers"); - break; - #endif - - const int8_t z_auto_align_iterations = parser.intval('I', Z_STEPPER_ALIGN_ITERATIONS); - if (!WITHIN(z_auto_align_iterations, 1, 30)) { - SERIAL_ECHOLNPGM("?(I)teration out of bounds (1-30)."); - break; + planner.synchronize(); // Prevent damage + + const bool seenL = parser.seen('L'); + if (seenL) stepper.set_all_z_lock(false); + + const bool seenZ = parser.seenval('Z'); + if (seenZ) { + const bool state = parser.boolval('S', true); + switch (parser.intval('Z')) { + case 1: stepper.set_z1_lock(state); break; + case 2: stepper.set_z2_lock(state); break; + #if TRIPLE_Z + case 3: stepper.set_z3_lock(state); break; + #if QUAD_Z + case 4: stepper.set_z4_lock(state); break; + #endif + #endif } + } - const float z_auto_align_accuracy = parser.floatval('T', Z_STEPPER_ALIGN_ACC); - if (!WITHIN(z_auto_align_accuracy, 0.01f, 1.0f)) { - SERIAL_ECHOLNPGM("?(T)arget accuracy out of bounds (0.01-1.0)."); - break; - } + if (seenL || seenZ) { + stepper.set_separate_multi_axis(seenZ); + return; + } - const float z_auto_align_amplification = - #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) - Z_STEPPER_ALIGN_AMP; - #else - parser.floatval('A', Z_STEPPER_ALIGN_AMP); - if (!WITHIN(ABS(z_auto_align_amplification), 0.5f, 2.0f)) { - SERIAL_ECHOLNPGM("?(A)mplification out of bounds (0.5-2.0)."); - break; - } - #endif + #if ENABLED(Z_STEPPER_AUTO_ALIGN) + do { // break out on error - if (parser.seen('R')) z_stepper_align.reset_to_default(); + const int8_t z_auto_align_iterations = parser.intval('I', Z_STEPPER_ALIGN_ITERATIONS); + if (!WITHIN(z_auto_align_iterations, 1, 30)) { + SERIAL_ECHOLNPGM("?(I)teration out of bounds (1-30)."); + break; + } - const ProbePtRaise raise_after = parser.boolval('E') ? PROBE_PT_STOW : PROBE_PT_RAISE; + const float z_auto_align_accuracy = parser.floatval('T', Z_STEPPER_ALIGN_ACC); + if (!WITHIN(z_auto_align_accuracy, 0.01f, 1.0f)) { + SERIAL_ECHOLNPGM("?(T)arget accuracy out of bounds (0.01-1.0)."); + break; + } - // Wait for planner moves to finish! - planner.synchronize(); + const float z_auto_align_amplification = TERN(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS, Z_STEPPER_ALIGN_AMP, parser.floatval('A', Z_STEPPER_ALIGN_AMP)); + if (!WITHIN(ABS(z_auto_align_amplification), 0.5f, 2.0f)) { + SERIAL_ECHOLNPGM("?(A)mplification out of bounds (0.5-2.0)."); + break; + } - // Disable the leveling matrix before auto-aligning - #if HAS_LEVELING - TERN_(RESTORE_LEVELING_AFTER_G34, const bool leveling_was_active = planner.leveling_active); - set_bed_leveling_enabled(false); - #endif + if (parser.seen('R')) z_stepper_align.reset_to_default(); - TERN_(CNC_WORKSPACE_PLANES, workspace_plane = PLANE_XY); + const ProbePtRaise raise_after = parser.boolval('E') ? PROBE_PT_STOW : PROBE_PT_RAISE; - // Always home with tool 0 active - #if HAS_MULTI_HOTEND - const uint8_t old_tool_index = active_extruder; - tool_change(0, true); - #endif + // Disable the leveling matrix before auto-aligning + #if HAS_LEVELING + #if ENABLED(RESTORE_LEVELING_AFTER_G34) + const bool leveling_was_active = planner.leveling_active; + #endif + set_bed_leveling_enabled(false); + #endif - TERN_(HAS_DUPLICATION_MODE, extruder_duplication_enabled = false); - - // In BLTOUCH HS mode, the probe travels in a deployed state. - // Users of G34 might have a badly misaligned bed, so raise Z by the - // length of the deployed pin (BLTOUCH stroke < 7mm) - #define Z_BASIC_CLEARANCE (Z_CLEARANCE_BETWEEN_PROBES + 7.0f * BOTH(BLTOUCH, BLTOUCH_HS_MODE)) - - // Compute a worst-case clearance height to probe from. After the first - // iteration this will be re-calculated based on the actual bed position - auto magnitude2 = [&](const uint8_t i, const uint8_t j) { - const xy_pos_t diff = z_stepper_align.xy[i] - z_stepper_align.xy[j]; - return HYPOT2(diff.x, diff.y); - }; - float z_probe = Z_BASIC_CLEARANCE + (G34_MAX_GRADE) * 0.01f * SQRT( - #if NUM_Z_STEPPER_DRIVERS == 3 - _MAX(magnitude2(0, 1), magnitude2(1, 2), magnitude2(2, 0)) - #elif NUM_Z_STEPPER_DRIVERS == 4 - _MAX(magnitude2(0, 1), magnitude2(1, 2), magnitude2(2, 3), - magnitude2(3, 0), magnitude2(0, 2), magnitude2(1, 3)) - #else - magnitude2(0, 1) + TERN_(CNC_WORKSPACE_PLANES, workspace_plane = PLANE_XY); + + // Always home with tool 0 active + #if HAS_MULTI_HOTEND + const uint8_t old_tool_index = active_extruder; + tool_change(0, true); #endif - ); - // Home before the alignment procedure - if (!all_axes_known()) home_all_axes(); + TERN_(HAS_DUPLICATION_MODE, set_duplication_enabled(false)); - // Move the Z coordinate realm towards the positive - dirty trick - current_position.z += z_probe * 0.5f; - sync_plan_position(); - // Now, the Z origin lies below the build plate. That allows to probe deeper, before run_z_probe throws an error. - // This hack is un-done at the end of G34 - either by re-homing, or by using the probed heights of the last iteration. + // In BLTOUCH HS mode, the probe travels in a deployed state. + // Users of G34 might have a badly misaligned bed, so raise Z by the + // length of the deployed pin (BLTOUCH stroke < 7mm) + #define Z_BASIC_CLEARANCE (Z_CLEARANCE_BETWEEN_PROBES + 7.0f * BOTH(BLTOUCH, BLTOUCH_HS_MODE)) - #if DISABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) - float last_z_align_move[NUM_Z_STEPPER_DRIVERS] = ARRAY_N(NUM_Z_STEPPER_DRIVERS, 10000.0f, 10000.0f, 10000.0f, 10000.0f); - #else - float last_z_align_level_indicator = 10000.0f; - #endif - float z_measured[NUM_Z_STEPPER_DRIVERS] = { 0 }, - z_maxdiff = 0.0f, - amplification = z_auto_align_amplification; + // Compute a worst-case clearance height to probe from. After the first + // iteration this will be re-calculated based on the actual bed position + auto magnitude2 = [&](const uint8_t i, const uint8_t j) { + const xy_pos_t diff = z_stepper_align.xy[i] - z_stepper_align.xy[j]; + return HYPOT2(diff.x, diff.y); + }; + float z_probe = Z_BASIC_CLEARANCE + (G34_MAX_GRADE) * 0.01f * SQRT(_MAX(0, magnitude2(0, 1) + #if TRIPLE_Z + , magnitude2(2, 1), magnitude2(2, 0) + #if QUAD_Z + , magnitude2(3, 2), magnitude2(3, 1), magnitude2(3, 0) + #endif + #endif + )); - #if DISABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) - bool adjustment_reverse = false; - #endif + // Home before the alignment procedure + home_if_needed(); - #if HAS_DISPLAY - PGM_P const msg_iteration = GET_TEXT(MSG_ITERATION); - const uint8_t iter_str_len = strlen_P(msg_iteration); - #endif + // Move the Z coordinate realm towards the positive - dirty trick + current_position.z += z_probe * 0.5f; + sync_plan_position(); + // Now, the Z origin lies below the build plate. That allows to probe deeper, before run_z_probe throws an error. + // This hack is un-done at the end of G34 - either by re-homing, or by using the probed heights of the last iteration. - // Final z and iteration values will be used after breaking the loop - float z_measured_min; - uint8_t iteration = 0; - bool err_break = false; // To break out of nested loops - while (iteration < z_auto_align_iterations) { - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("> probing all positions."); - - const int iter = iteration + 1; - SERIAL_ECHOLNPAIR("\nG34 Iteration: ", iter); - #if HAS_DISPLAY - char str[iter_str_len + 2 + 1]; - sprintf_P(str, msg_iteration, iter); - ui.set_status(str); + #if DISABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) + float last_z_align_move[NUM_Z_STEPPER_DRIVERS] = ARRAY_N_1(NUM_Z_STEPPER_DRIVERS, 10000.0f); + #else + float last_z_align_level_indicator = 10000.0f; #endif + float z_measured[NUM_Z_STEPPER_DRIVERS] = { 0 }, + z_maxdiff = 0.0f, + amplification = z_auto_align_amplification; - // Initialize minimum value - z_measured_min = 100000.0f; - float z_measured_max = -100000.0f; - - // Probe all positions (one per Z-Stepper) - LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS) { - // iteration odd/even --> downward / upward stepper sequence - const uint8_t iprobe = (iteration & 1) ? NUM_Z_STEPPER_DRIVERS - 1 - i : i; - - // Safe clearance even on an incline - if ((iteration == 0 || i > 0) && z_probe > current_position.z) do_blocking_move_to_z(z_probe); - - if (DEBUGGING(LEVELING)) - DEBUG_ECHOLNPAIR_P(PSTR("Probing X"), z_stepper_align.xy[iprobe].x, SP_Y_STR, z_stepper_align.xy[iprobe].y); - - // Probe a Z height for each stepper. - // Probing sanity check is disabled, as it would trigger even in normal cases because - // current_position.z has been manually altered in the "dirty trick" above. - const float z_probed_height = probe.probe_at_point(z_stepper_align.xy[iprobe], raise_after, 0, true, false); - if (isnan(z_probed_height)) { - SERIAL_ECHOLNPGM("Probing failed"); - LCD_MESSAGEPGM(MSG_LCD_PROBING_FAILED); - err_break = true; - break; - } + #if DISABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) + bool adjustment_reverse = false; + #endif - // 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; + #if HAS_STATUS_MESSAGE + PGM_P const msg_iteration = GET_TEXT(MSG_ITERATION); + const uint8_t iter_str_len = strlen_P(msg_iteration); + #endif - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", int(iprobe + 1), " measured position is ", z_measured[iprobe]); + // Final z and iteration values will be used after breaking the loop + float z_measured_min; + uint8_t iteration = 0; + bool err_break = false; // To break out of nested loops + while (iteration < z_auto_align_iterations) { + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("> probing all positions."); + + const int iter = iteration + 1; + SERIAL_ECHOLNPAIR("\nG34 Iteration: ", iter); + #if HAS_STATUS_MESSAGE + char str[iter_str_len + 2 + 1]; + sprintf_P(str, msg_iteration, iter); + ui.set_status(str); + #endif - // Remember the minimum measurement to calculate the correction later on - z_measured_min = _MIN(z_measured_min, z_measured[iprobe]); - z_measured_max = _MAX(z_measured_max, z_measured[iprobe]); - } // for (i) + // Initialize minimum value + z_measured_min = 100000.0f; + float z_measured_max = -100000.0f; - if (err_break) break; + // Probe all positions (one per Z-Stepper) + LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS) { + // iteration odd/even --> downward / upward stepper sequence + const uint8_t iprobe = (iteration & 1) ? NUM_Z_STEPPER_DRIVERS - 1 - i : i; + + // Safe clearance even on an incline + if ((iteration == 0 || i > 0) && z_probe > current_position.z) do_blocking_move_to_z(z_probe); + + if (DEBUGGING(LEVELING)) + DEBUG_ECHOLNPAIR_P(PSTR("Probing X"), z_stepper_align.xy[iprobe].x, SP_Y_STR, z_stepper_align.xy[iprobe].y); + + // Probe a Z height for each stepper. + // Probing sanity check is disabled, as it would trigger even in normal cases because + // current_position.z has been manually altered in the "dirty trick" above. + const float z_probed_height = probe.probe_at_point(z_stepper_align.xy[iprobe], raise_after, 0, true, false); + if (isnan(z_probed_height)) { + SERIAL_ECHOLNPGM("Probing failed"); + LCD_MESSAGEPGM(MSG_LCD_PROBING_FAILED); + err_break = true; + break; + } - // Adapt the next probe clearance height based on the new measurements. - // Safe_height = lowest distance to bed (= highest measurement) plus highest measured misalignment. - z_maxdiff = z_measured_max - z_measured_min; - z_probe = Z_BASIC_CLEARANCE + z_measured_max + z_maxdiff; + // 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; - #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) - // Replace the initial values in z_measured with calculated heights at - // each stepper position. This allows the adjustment algorithm to be - // shared between both possible probing mechanisms. + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", iprobe + 1, " measured position is ", z_measured[iprobe]); - // This must be done after the next z_probe height is calculated, so that - // the height is calculated from actual print area positions, and not - // extrapolated motor movements. + // Remember the minimum measurement to calculate the correction later on + z_measured_min = _MIN(z_measured_min, z_measured[iprobe]); + z_measured_max = _MAX(z_measured_max, z_measured[iprobe]); + } // for (i) - // Compute the least-squares fit for all probed points. - // Calculate the Z position of each stepper and store it in z_measured. - // 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_STEPPER_DRIVERS) { - SERIAL_ECHOLNPAIR("PROBEPT_", int(i), ": ", z_measured[i]); - incremental_LSF(&lfd, z_stepper_align.xy[i], z_measured[i]); - } - finish_incremental_LSF(&lfd); + if (err_break) break; - z_measured_min = 100000.0f; - LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS) { - 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]); - } + // Adapt the next probe clearance height based on the new measurements. + // Safe_height = lowest distance to bed (= highest measurement) plus highest measured misalignment. + z_maxdiff = z_measured_max - z_measured_min; + z_probe = Z_BASIC_CLEARANCE + z_measured_max + z_maxdiff; + + #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) + // Replace the initial values in z_measured with calculated heights at + // each stepper position. This allows the adjustment algorithm to be + // shared between both possible probing mechanisms. + + // This must be done after the next z_probe height is calculated, so that + // the height is calculated from actual print area positions, and not + // extrapolated motor movements. + + // Compute the least-squares fit for all probed points. + // Calculate the Z position of each stepper and store it in z_measured. + // 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_STEPPER_DRIVERS) { + SERIAL_ECHOLNPAIR("PROBEPT_", i, ": ", z_measured[i]); + incremental_LSF(&lfd, z_stepper_align.xy[i], z_measured[i]); + } + finish_incremental_LSF(&lfd); - SERIAL_ECHOLNPAIR("CALCULATED STEPPER POSITIONS: Z1=", z_measured[0], " Z2=", z_measured[1], " Z3=", z_measured[2]); - #endif + z_measured_min = 100000.0f; + LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS) { + 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]); + } - SERIAL_ECHOLNPAIR("\n" - "DIFFERENCE Z1-Z2=", ABS(z_measured[0] - z_measured[1]) - #if NUM_Z_STEPPER_DRIVERS == 3 - , " Z2-Z3=", ABS(z_measured[1] - z_measured[2]) - , " Z3-Z1=", ABS(z_measured[2] - z_measured[0]) - #endif - ); - #if HAS_DISPLAY - char fstr1[10]; - #if NUM_Z_STEPPER_DRIVERS == 2 - char msg[6 + (6 + 5) * 1 + 1]; - #else - char msg[6 + (6 + 5) * 3 + 1], fstr2[10], fstr3[10]; + SERIAL_ECHOLNPAIR( + LIST_N(DOUBLE(NUM_Z_STEPPER_DRIVERS), + "Calculated Z1=", z_measured[0], + " Z2=", z_measured[1], + " Z3=", z_measured[2], + " Z4=", z_measured[3] + ) + ); #endif - sprintf_P(msg, - PSTR("Diffs Z1-Z2=%s" - #if NUM_Z_STEPPER_DRIVERS == 3 - " Z2-Z3=%s" - " Z3-Z1=%s" + + SERIAL_ECHOLNPAIR("\n" + "Z2-Z1=", ABS(z_measured[1] - z_measured[0]) + #if TRIPLE_Z + , " Z3-Z2=", ABS(z_measured[2] - z_measured[1]) + , " Z3-Z1=", ABS(z_measured[2] - z_measured[0]) + #if QUAD_Z + , " Z4-Z3=", ABS(z_measured[3] - z_measured[2]) + , " Z4-Z2=", ABS(z_measured[3] - z_measured[1]) + , " Z4-Z1=", ABS(z_measured[3] - z_measured[0]) #endif - ), dtostrf(ABS(z_measured[0] - z_measured[1]), 1, 3, fstr1) - #if NUM_Z_STEPPER_DRIVERS == 3 - , dtostrf(ABS(z_measured[1] - z_measured[2]), 1, 3, fstr2) - , dtostrf(ABS(z_measured[2] - z_measured[0]), 1, 3, fstr3) #endif ); - ui.set_status(msg); - #endif - auto decreasing_accuracy = [](const float &v1, const float &v2){ - if (v1 < v2 * 0.7f) { - SERIAL_ECHOLNPGM("Decreasing Accuracy Detected."); - LCD_MESSAGEPGM(MSG_DECREASING_ACCURACY); - return true; - } - return false; - }; + #if HAS_STATUS_MESSAGE + char fstr1[10]; + char msg[6 + (6 + 5) * NUM_Z_STEPPER_DRIVERS + 1] + #if TRIPLE_Z + , fstr2[10], fstr3[10] + #if QUAD_Z + , fstr4[10], fstr5[10], fstr6[10] + #endif + #endif + ; + sprintf_P(msg, + PSTR("1:2=%s" TERN_(TRIPLE_Z, " 3-2=%s 3-1=%s") TERN_(QUAD_Z, " 4-3=%s 4-2=%s 4-1=%s")), + dtostrf(ABS(z_measured[1] - z_measured[0]), 1, 3, fstr1) + OPTARG(TRIPLE_Z, + dtostrf(ABS(z_measured[2] - z_measured[1]), 1, 3, fstr2), + dtostrf(ABS(z_measured[2] - z_measured[0]), 1, 3, fstr3)) + OPTARG(QUAD_Z, + dtostrf(ABS(z_measured[3] - z_measured[2]), 1, 3, fstr4), + dtostrf(ABS(z_measured[3] - z_measured[1]), 1, 3, fstr5), + dtostrf(ABS(z_measured[3] - z_measured[0]), 1, 3, fstr6)) + ); + ui.set_status(msg); + #endif - #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) + auto decreasing_accuracy = [](const_float_t v1, const_float_t v2) { + if (v1 < v2 * 0.7f) { + SERIAL_ECHOLNPGM("Decreasing Accuracy Detected."); + LCD_MESSAGEPGM(MSG_DECREASING_ACCURACY); + return true; + } + return false; + }; - // Check if the applied corrections go in the correct direction. - // Calculate the sum of the absolute deviations from the mean of the probe measurements. - // Compare to the last iteration to ensure it's getting better. + #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) + // Check if the applied corrections go in the correct direction. + // Calculate the sum of the absolute deviations from the mean of the probe measurements. + // Compare to the last iteration to ensure it's getting better. - // Calculate mean value as a reference - float z_measured_mean = 0.0f; - LOOP_L_N(zstepper, NUM_Z_STEPPER_DRIVERS) z_measured_mean += z_measured[zstepper]; - z_measured_mean /= NUM_Z_STEPPER_DRIVERS; + // Calculate mean value as a reference + float z_measured_mean = 0.0f; + LOOP_L_N(zstepper, NUM_Z_STEPPER_DRIVERS) z_measured_mean += z_measured[zstepper]; + z_measured_mean /= NUM_Z_STEPPER_DRIVERS; - // Calculate the sum of the absolute deviations from the mean value - float z_align_level_indicator = 0.0f; - LOOP_L_N(zstepper, NUM_Z_STEPPER_DRIVERS) - z_align_level_indicator += ABS(z_measured[zstepper] - z_measured_mean); + // Calculate the sum of the absolute deviations from the mean value + float z_align_level_indicator = 0.0f; + LOOP_L_N(zstepper, NUM_Z_STEPPER_DRIVERS) + z_align_level_indicator += ABS(z_measured[zstepper] - z_measured_mean); - // If it's getting worse, stop and throw an error - err_break = decreasing_accuracy(last_z_align_level_indicator, z_align_level_indicator); - if (err_break) break; + // If it's getting worse, stop and throw an error + err_break = decreasing_accuracy(last_z_align_level_indicator, z_align_level_indicator); + if (err_break) break; - last_z_align_level_indicator = z_align_level_indicator; - #endif + last_z_align_level_indicator = z_align_level_indicator; + #endif - // The following correction actions are to be enabled for select Z-steppers only - stepper.set_separate_multi_axis(true); - - bool success_break = true; - // Correct the individual stepper offsets - LOOP_L_N(zstepper, NUM_Z_STEPPER_DRIVERS) { - // Calculate current stepper move - float z_align_move = z_measured[zstepper] - z_measured_min; - const float z_align_abs = ABS(z_align_move); - - #if DISABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) - // Optimize one iteration's correction based on the first measurements - if (z_align_abs) amplification = (iteration == 1) ? _MIN(last_z_align_move[zstepper] / z_align_abs, 2.0f) : z_auto_align_amplification; - - // Check for less accuracy compared to last move - if (decreasing_accuracy(last_z_align_move[zstepper], z_align_abs)) { - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", int(zstepper + 1), " last_z_align_move = ", last_z_align_move[zstepper]); - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", int(zstepper + 1), " z_align_abs = ", z_align_abs); - adjustment_reverse = !adjustment_reverse; - } + // The following correction actions are to be enabled for select Z-steppers only + stepper.set_separate_multi_axis(true); + + bool success_break = true; + // Correct the individual stepper offsets + LOOP_L_N(zstepper, NUM_Z_STEPPER_DRIVERS) { + // Calculate current stepper move + float z_align_move = z_measured[zstepper] - z_measured_min; + const float z_align_abs = ABS(z_align_move); + + #if DISABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) + // Optimize one iteration's correction based on the first measurements + if (z_align_abs) amplification = (iteration == 1) ? _MIN(last_z_align_move[zstepper] / z_align_abs, 2.0f) : z_auto_align_amplification; + + // Check for less accuracy compared to last move + if (decreasing_accuracy(last_z_align_move[zstepper], z_align_abs)) { + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", zstepper + 1, " last_z_align_move = ", last_z_align_move[zstepper]); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", zstepper + 1, " z_align_abs = ", z_align_abs); + adjustment_reverse = !adjustment_reverse; + } + + // Remember the alignment for the next iteration, but only if steppers move, + // otherwise it would be just zero (in case this stepper was at z_measured_min already) + if (z_align_abs > 0) last_z_align_move[zstepper] = z_align_abs; + #endif - // Remember the alignment for the next iteration, but only if steppers move, - // otherwise it would be just zero (in case this stepper was at z_measured_min already) - if (z_align_abs > 0) last_z_align_move[zstepper] = z_align_abs; - #endif + // Stop early if all measured points achieve accuracy target + if (z_align_abs > z_auto_align_accuracy) success_break = false; - // Stop early if all measured points achieve accuracy target - if (z_align_abs > z_auto_align_accuracy) success_break = false; + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", zstepper + 1, " corrected by ", z_align_move); - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", int(zstepper + 1), " corrected by ", z_align_move); + // Lock all steppers except one + stepper.set_all_z_lock(true, zstepper); - // Lock all steppers except one - stepper.set_all_z_lock(true, zstepper); + #if DISABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) + // Decreasing accuracy was detected so move was inverted. + // Will match reversed Z steppers on dual steppers. Triple will need more work to map. + if (adjustment_reverse) { + z_align_move = -z_align_move; + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", zstepper + 1, " correction reversed to ", z_align_move); + } + #endif - #if DISABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) - // Decreasing accuracy was detected so move was inverted. - // Will match reversed Z steppers on dual steppers. Triple will need more work to map. - if (adjustment_reverse) { - z_align_move = -z_align_move; - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", int(zstepper + 1), " correction reversed to ", z_align_move); - } - #endif + // Do a move to correct part of the misalignment for the current stepper + do_blocking_move_to_z(amplification * z_align_move + current_position.z); + } // for (zstepper) - // Do a move to correct part of the misalignment for the current stepper - do_blocking_move_to_z(amplification * z_align_move + current_position.z); - } // for (zstepper) + // Back to normal stepper operations + stepper.set_all_z_lock(false); + stepper.set_separate_multi_axis(false); - // Back to normal stepper operations - stepper.set_all_z_lock(false); - stepper.set_separate_multi_axis(false); + if (err_break) break; - if (err_break) break; + if (success_break) { + SERIAL_ECHOLNPGM("Target accuracy achieved."); + LCD_MESSAGEPGM(MSG_ACCURACY_ACHIEVED); + break; + } - if (success_break) { - SERIAL_ECHOLNPGM("Target accuracy achieved."); - LCD_MESSAGEPGM(MSG_ACCURACY_ACHIEVED); - break; - } + iteration++; + } // while (iteration < z_auto_align_iterations) - iteration++; - } // while (iteration < z_auto_align_iterations) + if (err_break) + SERIAL_ECHOLNPGM("G34 aborted."); + else { + SERIAL_ECHOLNPAIR("Did ", iteration + (iteration != z_auto_align_iterations), " of ", z_auto_align_iterations); + SERIAL_ECHOLNPAIR_F("Accuracy: ", z_maxdiff); + } - if (err_break) - SERIAL_ECHOLNPGM("G34 aborted."); - else { - SERIAL_ECHOLNPAIR("Did ", int(iteration + (iteration != z_auto_align_iterations)), " of ", int(z_auto_align_iterations)); - SERIAL_ECHOLNPAIR_F("Accuracy: ", z_maxdiff); - } + // Stow the probe because the last call to probe.probe_at_point(...) + // leaves the probe deployed when it's successful. + IF_DISABLED(TOUCH_MI_PROBE, probe.stow()); - // Stow the probe, as the last call to probe.probe_at_point(...) left - // the probe deployed if it was successful. - probe.stow(); - - #if ENABLED(HOME_AFTER_G34) - // After this operation the z position needs correction - set_axis_never_homed(Z_AXIS); - // Home Z after the alignment procedure - process_subcommands_now_P(PSTR("G28Z")); - #else - // 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; - sync_plan_position(); - #endif + #if ENABLED(HOME_AFTER_G34) + // After this operation the z position needs correction + set_axis_never_homed(Z_AXIS); + // Home Z after the alignment procedure + process_subcommands_now_P(PSTR("G28Z")); + #else + // 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; + 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 + // 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) - set_bed_leveling_enabled(leveling_was_active); - #endif + #if BOTH(HAS_LEVELING, RESTORE_LEVELING_AFTER_G34) + set_bed_leveling_enabled(leveling_was_active); + #endif - }while(0); + }while(0); + #endif // Z_STEPPER_AUTO_ALIGN } +#endif // Z_MULTI_ENDSTOPS || Z_STEPPER_AUTO_ALIGN + +#if ENABLED(Z_STEPPER_AUTO_ALIGN) + /** * M422: Set a Z-Stepper automatic alignment XY point. * Use repeatedly to set multiple points. @@ -434,42 +482,28 @@ void GcodeSuite::M422() { if (!parser.seen_any()) { LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS) - SERIAL_ECHOLNPAIR_P(PSTR("M422 S"), int(i + 1), SP_X_STR, z_stepper_align.xy[i].x, SP_Y_STR, z_stepper_align.xy[i].y); + SERIAL_ECHOLNPAIR_P(PSTR("M422 S"), i + 1, SP_X_STR, z_stepper_align.xy[i].x, SP_Y_STR, z_stepper_align.xy[i].y); #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS) - SERIAL_ECHOLNPAIR_P(PSTR("M422 W"), int(i + 1), SP_X_STR, z_stepper_align.stepper_xy[i].x, SP_Y_STR, z_stepper_align.stepper_xy[i].y); + SERIAL_ECHOLNPAIR_P(PSTR("M422 W"), i + 1, SP_X_STR, z_stepper_align.stepper_xy[i].x, SP_Y_STR, z_stepper_align.stepper_xy[i].y); #endif return; } const bool is_probe_point = parser.seen('S'); - #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) - if (is_probe_point && parser.seen('W')) { - SERIAL_ECHOLNPGM("?(S) and (W) may not be combined."); - return; - } - #endif + if (TERN0(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS, is_probe_point && parser.seen('W'))) { + SERIAL_ECHOLNPGM("?(S) and (W) may not be combined."); + return; + } xy_pos_t *pos_dest = ( - #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) - !is_probe_point ? z_stepper_align.stepper_xy : - #endif + TERN_(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS, !is_probe_point ? z_stepper_align.stepper_xy :) z_stepper_align.xy ); - if (!is_probe_point - #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) - && !parser.seen('W') - #endif - ) { - SERIAL_ECHOLNPGM( - #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) - "?(S) or (W) is required." - #else - "?(S) is required." - #endif - ); + if (!is_probe_point && TERN1(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS, !parser.seen('W'))) { + SERIAL_ECHOLNPGM("?(S)" TERN_(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS, " or (W)") " is required."); return; } @@ -478,7 +512,7 @@ void GcodeSuite::M422() { if (is_probe_point) { position_index = parser.intval('S') - 1; if (!WITHIN(position_index, 0, int8_t(NUM_Z_STEPPER_DRIVERS) - 1)) { - SERIAL_ECHOLNPGM("?(S) Z-ProbePosition index invalid."); + SERIAL_ECHOLNPGM("?(S) Probe-position index invalid."); return; } } @@ -486,7 +520,7 @@ void GcodeSuite::M422() { #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) position_index = parser.intval('W') - 1; if (!WITHIN(position_index, 0, NUM_Z_STEPPER_DRIVERS - 1)) { - SERIAL_ECHOLNPGM("?(W) Z-Stepper index invalid."); + SERIAL_ECHOLNPGM("?(W) Z-stepper index invalid."); return; } #endif diff --git a/Marlin/src/gcode/calibrate/G425.cpp b/Marlin/src/gcode/calibrate/G425.cpp index 8968f789995f..c8efea858ca5 100644 --- a/Marlin/src/gcode/calibrate/G425.cpp +++ b/Marlin/src/gcode/calibrate/G425.cpp @@ -30,7 +30,7 @@ #include "../../feature/backlash.h" #endif -#include "../../lcd/ultralcd.h" +#include "../../lcd/marlinui.h" #include "../../module/motion.h" #include "../../module/planner.h" #include "../../module/tool_change.h" @@ -73,11 +73,23 @@ #if BOTH(CALIBRATION_MEASURE_LEFT, CALIBRATION_MEASURE_RIGHT) #define HAS_X_CENTER 1 #endif -#if BOTH(CALIBRATION_MEASURE_FRONT, CALIBRATION_MEASURE_BACK) +#if HAS_Y_AXIS && BOTH(CALIBRATION_MEASURE_FRONT, CALIBRATION_MEASURE_BACK) #define HAS_Y_CENTER 1 #endif +#if LINEAR_AXES >= 4 && BOTH(CALIBRATION_MEASURE_IMIN, CALIBRATION_MEASURE_IMAX) + #define HAS_I_CENTER 1 +#endif +#if LINEAR_AXES >= 5 && BOTH(CALIBRATION_MEASURE_JMIN, CALIBRATION_MEASURE_JMAX) + #define HAS_J_CENTER 1 +#endif +#if LINEAR_AXES >= 6 && BOTH(CALIBRATION_MEASURE_KMIN, CALIBRATION_MEASURE_KMAX) + #define HAS_K_CENTER 1 +#endif -enum side_t : uint8_t { TOP, RIGHT, FRONT, LEFT, BACK, NUM_SIDES }; +enum side_t : uint8_t { + TOP, RIGHT, FRONT, LEFT, BACK, NUM_SIDES, + LIST_N(DOUBLE(SUB3(LINEAR_AXES)), IMINIMUM, IMAXIMUM, JMINIMUM, JMAXIMUM, KMINIMUM, KMAXIMUM) +}; static constexpr xyz_pos_t true_center CALIBRATION_OBJECT_CENTER; static constexpr xyz_float_t dimensions CALIBRATION_OBJECT_DIMENSIONS; @@ -105,7 +117,7 @@ struct measurements_t { #endif inline void calibration_move() { - do_blocking_move_to(current_position, MMM_TO_MMS(CALIBRATION_FEEDRATE_TRAVEL)); + do_blocking_move_to((xyz_pos_t)current_position, MMM_TO_MMS(CALIBRATION_FEEDRATE_TRAVEL)); } /** @@ -143,14 +155,16 @@ inline void park_above_object(measurements_t &m, const float uncertainty) { #endif +#if !PIN_EXISTS(CALIBRATION) + #include "../../module/probe.h" +#endif + inline bool read_calibration_pin() { return ( #if PIN_EXISTS(CALIBRATION) READ(CALIBRATION_PIN) != CALIBRATION_PIN_INVERTING - #elif HAS_CUSTOM_PROBE_PIN - READ(Z_MIN_PROBE_PIN) != Z_MIN_PROBE_ENDSTOP_INVERTING #else - READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING + PROBE_TRIGGERED() #endif ); } @@ -172,7 +186,7 @@ float measuring_movement(const AxisEnum axis, const int dir, const bool stop_sta destination = current_position; for (float travel = 0; travel < limit; travel += step) { destination[axis] += dir * step; - do_blocking_move_to(destination, mms); + do_blocking_move_to((xyz_pos_t)destination, mms); planner.synchronize(); if (read_calibration_pin() == stop_state) break; } @@ -192,18 +206,22 @@ float measuring_movement(const AxisEnum axis, const int dir, const bool stop_sta inline float measure(const AxisEnum axis, const int dir, const bool stop_state, float * const backlash_ptr, const float uncertainty) { const bool fast = uncertainty == CALIBRATION_MEASUREMENT_UNKNOWN; - // Save position - destination = current_position; - const float start_pos = destination[axis]; + // Save the current position of the specified axis + const float start_pos = current_position[axis]; + + // Take a measurement. Only the specified axis will be affected. const float measured_pos = measuring_movement(axis, dir, stop_state, fast); + // Measure backlash if (backlash_ptr && !fast) { const float release_pos = measuring_movement(axis, -dir, !stop_state, fast); *backlash_ptr = ABS(release_pos - measured_pos); } - // Return to starting position + + // Move back to the starting position + destination = current_position; destination[axis] = start_pos; - do_blocking_move_to(destination, MMM_TO_MMS(CALIBRATION_FEEDRATE_TRAVEL)); + do_blocking_move_to((xyz_pos_t)destination, MMM_TO_MMS(CALIBRATION_FEEDRATE_TRAVEL)); return measured_pos; } @@ -224,7 +242,15 @@ inline void probe_side(measurements_t &m, const float uncertainty, const side_t park_above_object(m, uncertainty); switch (side) { - #if AXIS_CAN_CALIBRATE(Z) + #if AXIS_CAN_CALIBRATE(X) + case RIGHT: dir = -1; + case LEFT: axis = X_AXIS; break; + #endif + #if LINEAR_AXES >= 2 && AXIS_CAN_CALIBRATE(Y) + case BACK: dir = -1; + case FRONT: axis = Y_AXIS; break; + #endif + #if HAS_Z_AXIS && 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; @@ -232,13 +258,17 @@ inline void probe_side(measurements_t &m, const float uncertainty, const side_t return; } #endif - #if AXIS_CAN_CALIBRATE(X) - case LEFT: axis = X_AXIS; break; - case RIGHT: axis = X_AXIS; dir = -1; break; + #if LINEAR_AXES >= 4 && AXIS_CAN_CALIBRATE(I) + case IMINIMUM: dir = -1; + case IMAXIMUM: axis = I_AXIS; break; #endif - #if AXIS_CAN_CALIBRATE(Y) - case FRONT: axis = Y_AXIS; break; - case BACK: axis = Y_AXIS; dir = -1; break; + #if LINEAR_AXES >= 5 && AXIS_CAN_CALIBRATE(J) + case JMINIMUM: dir = -1; + case JMAXIMUM: axis = J_AXIS; break; + #endif + #if LINEAR_AXES >= 6 && AXIS_CAN_CALIBRATE(K) + case KMINIMUM: dir = -1; + case KMAXIMUM: axis = K_AXIS; break; #endif default: return; } @@ -283,14 +313,23 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { probe_side(m, uncertainty, TOP); #endif - TERN_(CALIBRATION_MEASURE_RIGHT, probe_side(m, uncertainty, RIGHT, probe_top_at_edge)); - TERN_(CALIBRATION_MEASURE_FRONT, probe_side(m, uncertainty, FRONT, probe_top_at_edge)); - TERN_(CALIBRATION_MEASURE_LEFT, probe_side(m, uncertainty, LEFT, probe_top_at_edge)); - TERN_(CALIBRATION_MEASURE_BACK, probe_side(m, uncertainty, BACK, probe_top_at_edge)); + TERN_(CALIBRATION_MEASURE_RIGHT, probe_side(m, uncertainty, RIGHT, probe_top_at_edge)); + TERN_(CALIBRATION_MEASURE_FRONT, probe_side(m, uncertainty, FRONT, probe_top_at_edge)); + TERN_(CALIBRATION_MEASURE_LEFT, probe_side(m, uncertainty, LEFT, probe_top_at_edge)); + TERN_(CALIBRATION_MEASURE_BACK, probe_side(m, uncertainty, BACK, probe_top_at_edge)); + TERN_(CALIBRATION_MEASURE_IMIN, probe_side(m, uncertainty, IMINIMUM, probe_top_at_edge)); + TERN_(CALIBRATION_MEASURE_IMAX, probe_side(m, uncertainty, IMAXIMUM, probe_top_at_edge)); + TERN_(CALIBRATION_MEASURE_JMIN, probe_side(m, uncertainty, JMINIMUM, probe_top_at_edge)); + TERN_(CALIBRATION_MEASURE_JMAX, probe_side(m, uncertainty, JMAXIMUM, probe_top_at_edge)); + TERN_(CALIBRATION_MEASURE_KMIN, probe_side(m, uncertainty, KMINIMUM, probe_top_at_edge)); + TERN_(CALIBRATION_MEASURE_KMAX, probe_side(m, uncertainty, KMAXIMUM, probe_top_at_edge)); // Compute the measured center of the calibration object. - TERN_(HAS_X_CENTER, m.obj_center.x = (m.obj_side[LEFT] + m.obj_side[RIGHT]) / 2); - TERN_(HAS_Y_CENTER, m.obj_center.y = (m.obj_side[FRONT] + m.obj_side[BACK]) / 2); + TERN_(HAS_X_CENTER, m.obj_center.x = (m.obj_side[LEFT] + m.obj_side[RIGHT]) / 2); + TERN_(HAS_Y_CENTER, m.obj_center.y = (m.obj_side[FRONT] + m.obj_side[BACK]) / 2); + TERN_(HAS_I_CENTER, m.obj_center.i = (m.obj_side[IMINIMUM] + m.obj_side[IMAXIMUM]) / 2); + TERN_(HAS_J_CENTER, m.obj_center.j = (m.obj_side[JMINIMUM] + m.obj_side[JMAXIMUM]) / 2); + TERN_(HAS_K_CENTER, m.obj_center.k = (m.obj_side[KMINIMUM] + m.obj_side[KMAXIMUM]) / 2); // Compute the outside diameter of the nozzle at the height // at which it makes contact with the calibration object @@ -301,23 +340,20 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { // The difference between the known and the measured location // of the calibration object is the positional error - m.pos_error.x = (0 - #if HAS_X_CENTER - + true_center.x - m.obj_center.x - #endif - ); - m.pos_error.y = (0 - #if HAS_Y_CENTER - + true_center.y - m.obj_center.y - #endif + LINEAR_AXIS_CODE( + m.pos_error.x = TERN0(HAS_X_CENTER, true_center.x - m.obj_center.x), + m.pos_error.y = TERN0(HAS_Y_CENTER, true_center.y - m.obj_center.y), + m.pos_error.z = true_center.z - m.obj_center.z, + m.pos_error.i = TERN0(HAS_I_CENTER, true_center.i - m.obj_center.i), + m.pos_error.j = TERN0(HAS_J_CENTER, true_center.j - m.obj_center.j), + m.pos_error.k = TERN0(HAS_K_CENTER, true_center.k - m.obj_center.k) ); - m.pos_error.z = true_center.z - m.obj_center.z; } #if ENABLED(CALIBRATION_REPORTING) inline void report_measured_faces(const measurements_t &m) { SERIAL_ECHOLNPGM("Sides:"); - #if AXIS_CAN_CALIBRATE(Z) + #if HAS_Z_AXIS && AXIS_CAN_CALIBRATE(Z) SERIAL_ECHOLNPAIR(" Top: ", m.obj_side[TOP]); #endif #if ENABLED(CALIBRATION_MEASURE_LEFT) @@ -326,11 +362,37 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { #if ENABLED(CALIBRATION_MEASURE_RIGHT) SERIAL_ECHOLNPAIR(" Right: ", m.obj_side[RIGHT]); #endif - #if ENABLED(CALIBRATION_MEASURE_FRONT) - SERIAL_ECHOLNPAIR(" Front: ", m.obj_side[FRONT]); + #if HAS_Y_AXIS + #if ENABLED(CALIBRATION_MEASURE_FRONT) + SERIAL_ECHOLNPAIR(" Front: ", m.obj_side[FRONT]); + #endif + #if ENABLED(CALIBRATION_MEASURE_BACK) + SERIAL_ECHOLNPAIR(" Back: ", m.obj_side[BACK]); + #endif #endif - #if ENABLED(CALIBRATION_MEASURE_BACK) - SERIAL_ECHOLNPAIR(" Back: ", m.obj_side[BACK]); + #if LINEAR_AXES >= 4 + #if ENABLED(CALIBRATION_MEASURE_IMIN) + SERIAL_ECHOLNPAIR(" " STR_I_MIN ": ", m.obj_side[IMINIMUM]); + #endif + #if ENABLED(CALIBRATION_MEASURE_IMAX) + SERIAL_ECHOLNPAIR(" " STR_I_MAX ": ", m.obj_side[IMAXIMUM]); + #endif + #endif + #if LINEAR_AXES >= 5 + #if ENABLED(CALIBRATION_MEASURE_JMIN) + SERIAL_ECHOLNPAIR(" " STR_J_MIN ": ", m.obj_side[JMINIMUM]); + #endif + #if ENABLED(CALIBRATION_MEASURE_JMAX) + SERIAL_ECHOLNPAIR(" " STR_J_MAX ": ", m.obj_side[JMAXIMUM]); + #endif + #endif + #if LINEAR_AXES >= 6 + #if ENABLED(CALIBRATION_MEASURE_KMIN) + SERIAL_ECHOLNPAIR(" " STR_K_MIN ": ", m.obj_side[KMINIMUM]); + #endif + #if ENABLED(CALIBRATION_MEASURE_KMAX) + SERIAL_ECHOLNPAIR(" " STR_K_MAX ": ", m.obj_side[KMAXIMUM]); + #endif #endif SERIAL_EOL(); } @@ -344,6 +406,15 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { SERIAL_ECHOLNPAIR_P(SP_Y_STR, m.obj_center.y); #endif SERIAL_ECHOLNPAIR_P(SP_Z_STR, m.obj_center.z); + #if HAS_I_CENTER + SERIAL_ECHOLNPAIR_P(SP_I_STR, m.obj_center.i); + #endif + #if HAS_J_CENTER + SERIAL_ECHOLNPAIR_P(SP_J_STR, m.obj_center.j); + #endif + #if HAS_K_CENTER + SERIAL_ECHOLNPAIR_P(SP_K_STR, m.obj_center.k); + #endif SERIAL_EOL(); } @@ -357,7 +428,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { SERIAL_ECHOLNPAIR(" Right: ", m.backlash[RIGHT]); #endif #endif - #if AXIS_CAN_CALIBRATE(Y) + #if HAS_Y_AXIS && AXIS_CAN_CALIBRATE(Y) #if ENABLED(CALIBRATION_MEASURE_FRONT) SERIAL_ECHOLNPAIR(" Front: ", m.backlash[FRONT]); #endif @@ -365,39 +436,71 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { SERIAL_ECHOLNPAIR(" Back: ", m.backlash[BACK]); #endif #endif - #if AXIS_CAN_CALIBRATE(Z) + #if HAS_Z_AXIS && AXIS_CAN_CALIBRATE(Z) SERIAL_ECHOLNPAIR(" Top: ", m.backlash[TOP]); #endif + #if LINEAR_AXES >= 4 && AXIS_CAN_CALIBRATE(I) + #if ENABLED(CALIBRATION_MEASURE_IMIN) + SERIAL_ECHOLNPAIR(" " STR_I_MIN ": ", m.backlash[IMINIMUM]); + #endif + #if ENABLED(CALIBRATION_MEASURE_IMAX) + SERIAL_ECHOLNPAIR(" " STR_I_MAX ": ", m.backlash[IMAXIMUM]); + #endif + #endif + #if LINEAR_AXES >= 5 && AXIS_CAN_CALIBRATE(J) + #if ENABLED(CALIBRATION_MEASURE_JMIN) + SERIAL_ECHOLNPAIR(" " STR_J_MIN ": ", m.backlash[JMINIMUM]); + #endif + #if ENABLED(CALIBRATION_MEASURE_JMAX) + SERIAL_ECHOLNPAIR(" " STR_J_MAX ": ", m.backlash[JMAXIMUM]); + #endif + #endif + #if LINEAR_AXES >= 6 && AXIS_CAN_CALIBRATE(K) + #if ENABLED(CALIBRATION_MEASURE_KMIN) + SERIAL_ECHOLNPAIR(" " STR_K_MIN ": ", m.backlash[KMINIMUM]); + #endif + #if ENABLED(CALIBRATION_MEASURE_KMAX) + SERIAL_ECHOLNPAIR(" " STR_K_MAX ": ", m.backlash[KMAXIMUM]); + #endif + #endif SERIAL_EOL(); } inline void report_measured_positional_error(const measurements_t &m) { SERIAL_CHAR('T'); - SERIAL_ECHO(int(active_extruder)); + SERIAL_ECHO(active_extruder); SERIAL_ECHOLNPGM(" Positional Error:"); - #if HAS_X_CENTER + #if HAS_X_CENTER && AXIS_CAN_CALIBRATE(X) SERIAL_ECHOLNPAIR_P(SP_X_STR, m.pos_error.x); #endif - #if HAS_Y_CENTER + #if HAS_Y_CENTER && AXIS_CAN_CALIBRATE(Y) SERIAL_ECHOLNPAIR_P(SP_Y_STR, m.pos_error.y); #endif - if (AXIS_CAN_CALIBRATE(Z)) SERIAL_ECHOLNPAIR_P(SP_Z_STR, m.pos_error.z); + #if HAS_Z_AXIS && AXIS_CAN_CALIBRATE(Z) + SERIAL_ECHOLNPAIR_P(SP_Z_STR, m.pos_error.z); + #endif + #if HAS_I_CENTER && AXIS_CAN_CALIBRATE(I) + SERIAL_ECHOLNPAIR_P(SP_I_STR, m.pos_error.i); + #endif + #if HAS_J_CENTER && AXIS_CAN_CALIBRATE(J) + SERIAL_ECHOLNPAIR_P(SP_J_STR, m.pos_error.j); + #endif + #if HAS_K_CENTER && AXIS_CAN_CALIBRATE(K) + SERIAL_ECHOLNPAIR_P(SP_Z_STR, m.pos_error.z); + #endif SERIAL_EOL(); } inline void report_measured_nozzle_dimensions(const measurements_t &m) { SERIAL_ECHOLNPGM("Nozzle Tip Outer Dimensions:"); - #if HAS_X_CENTER || HAS_Y_CENTER - #if HAS_X_CENTER - SERIAL_ECHOLNPAIR_P(SP_X_STR, m.nozzle_outer_dimension.x); - #endif - #if HAS_Y_CENTER - SERIAL_ECHOLNPAIR_P(SP_Y_STR, m.nozzle_outer_dimension.y); - #endif - #else - UNUSED(m); + #if HAS_X_CENTER + SERIAL_ECHOLNPAIR_P(SP_X_STR, m.nozzle_outer_dimension.x); + #endif + #if HAS_Y_CENTER + SERIAL_ECHOLNPAIR_P(SP_Y_STR, m.nozzle_outer_dimension.y); #endif SERIAL_EOL(); + UNUSED(m); } #if HAS_HOTEND_OFFSET @@ -406,7 +509,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { // inline void report_hotend_offsets() { LOOP_S_L_N(e, 1, HOTENDS) - SERIAL_ECHOLNPAIR_P(PSTR("T"), int(e), PSTR(" Hotend Offset X"), hotend_offset[e].x, SP_Y_STR, hotend_offset[e].y, SP_Z_STR, hotend_offset[e].z); + SERIAL_ECHOLNPAIR_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 @@ -446,8 +549,33 @@ inline void calibrate_backlash(measurements_t &m, const float uncertainty) { backlash.distance_mm.y = m.backlash[BACK]; #endif - if (AXIS_CAN_CALIBRATE(Z)) backlash.distance_mm.z = m.backlash[TOP]; - #endif + TERN_(HAS_Z_AXIS, if (AXIS_CAN_CALIBRATE(Z)) backlash.distance_mm.z = m.backlash[TOP]); + + #if HAS_I_CENTER + backlash.distance_mm.i = (m.backlash[IMINIMUM] + m.backlash[IMAXIMUM]) / 2; + #elif ENABLED(CALIBRATION_MEASURE_IMIN) + backlash.distance_mm.i = m.backlash[IMINIMUM]; + #elif ENABLED(CALIBRATION_MEASURE_IMAX) + backlash.distance_mm.i = m.backlash[IMAXIMUM]; + #endif + + #if HAS_J_CENTER + backlash.distance_mm.j = (m.backlash[JMINIMUM] + m.backlash[JMAXIMUM]) / 2; + #elif ENABLED(CALIBRATION_MEASURE_JMIN) + backlash.distance_mm.j = m.backlash[JMINIMUM]; + #elif ENABLED(CALIBRATION_MEASURE_JMAX) + backlash.distance_mm.j = m.backlash[JMAXIMUM]; + #endif + + #if HAS_K_CENTER + backlash.distance_mm.k = (m.backlash[KMINIMUM] + m.backlash[KMAXIMUM]) / 2; + #elif ENABLED(CALIBRATION_MEASURE_KMIN) + backlash.distance_mm.k = m.backlash[KMINIMUM]; + #elif ENABLED(CALIBRATION_MEASURE_KMAX) + backlash.distance_mm.k = m.backlash[KMAXIMUM]; + #endif + + #endif // BACKLASH_GCODE } #if ENABLED(BACKLASH_GCODE) @@ -457,7 +585,10 @@ inline void calibrate_backlash(measurements_t &m, const float uncertainty) { // New scope for TEMPORARY_BACKLASH_CORRECTION TEMPORARY_BACKLASH_CORRECTION(all_on); TEMPORARY_BACKLASH_SMOOTHING(0.0f); - const xyz_float_t move = { AXIS_CAN_CALIBRATE(X) * 3, AXIS_CAN_CALIBRATE(Y) * 3, AXIS_CAN_CALIBRATE(Z) * 3 }; + const xyz_float_t move = LINEAR_AXIS_ARRAY( + AXIS_CAN_CALIBRATE(X) * 3, AXIS_CAN_CALIBRATE(Y) * 3, AXIS_CAN_CALIBRATE(Z) * 3, + AXIS_CAN_CALIBRATE(I) * 3, AXIS_CAN_CALIBRATE(J) * 3, AXIS_CAN_CALIBRATE(K) * 3 + ); current_position += move; calibration_move(); current_position -= move; calibration_move(); } @@ -485,11 +616,7 @@ inline void calibrate_toolhead(measurements_t &m, const float uncertainty, const TEMPORARY_BACKLASH_CORRECTION(all_on); TEMPORARY_BACKLASH_SMOOTHING(0.0f); - #if HAS_MULTI_HOTEND - set_nozzle(m, extruder); - #else - UNUSED(extruder); - #endif + TERN(HAS_MULTI_HOTEND, set_nozzle(m, extruder), UNUSED(extruder)); probe_sides(m, uncertainty); @@ -508,6 +635,10 @@ inline void calibrate_toolhead(measurements_t &m, const float uncertainty, const if (ENABLED(HAS_Y_CENTER) && AXIS_CAN_CALIBRATE(Y)) update_measurements(m, Y_AXIS); if (AXIS_CAN_CALIBRATE(Z)) update_measurements(m, Z_AXIS); + TERN_(HAS_I_CENTER, update_measurements(m, I_AXIS)); + TERN_(HAS_J_CENTER, update_measurements(m, J_AXIS)); + TERN_(HAS_K_CENTER, update_measurements(m, K_AXIS)); + sync_plan_position(); } @@ -587,12 +718,12 @@ void GcodeSuite::G425() { SET_SOFT_ENDSTOP_LOOSE(true); measurements_t m; - float uncertainty = parser.seenval('U') ? parser.value_float() : CALIBRATION_MEASUREMENT_UNCERTAIN; + const float uncertainty = parser.floatval('U', CALIBRATION_MEASUREMENT_UNCERTAIN); - if (parser.seen('B')) + if (parser.seen_test('B')) calibrate_backlash(m, uncertainty); - else if (parser.seen('T')) - calibrate_toolhead(m, uncertainty, parser.has_value() ? parser.value_int() : active_extruder); + else if (parser.seen_test('T')) + calibrate_toolhead(m, uncertainty, parser.intval('T', active_extruder)); #if ENABLED(CALIBRATION_REPORTING) else if (parser.seen('V')) { probe_sides(m, uncertainty); diff --git a/Marlin/src/gcode/calibrate/G76_M192_M871.cpp b/Marlin/src/gcode/calibrate/G76_M192_M871.cpp index 89393b4582c1..2d1b9443bf17 100644 --- a/Marlin/src/gcode/calibrate/G76_M192_M871.cpp +++ b/Marlin/src/gcode/calibrate/G76_M192_M871.cpp @@ -36,17 +36,7 @@ #include "../../module/temperature.h" #include "../../module/probe.h" #include "../../feature/probe_temp_comp.h" - -#include "../../lcd/ultralcd.h" -#include "../../MarlinCore.h" // for wait_for_heatup and idle() - -#if ENABLED(PRINTJOB_TIMER_AUTOSTART) - #include "../../module/printcounter.h" -#endif - -#if ENABLED(PRINTER_EVENTS_LEDS) - #include "../../feature/leds/leds.h" -#endif +#include "../../lcd/marlinui.h" /** * G76: calibrate probe and/or bed temperature offsets @@ -57,7 +47,7 @@ * Compensation values are deltas to first probe measurement at bed temp. = 60°C. * - The hotend will not be heated at any time. * - On my Průša MK3S clone I put a piece of paper between the probe and the hotend - * so the hotend fan would not cool my probe constantly. Alternativly you could just + * so the hotend fan would not cool my probe constantly. Alternatively you could just * make sure the fan is not running while running the calibration process. * * Probe calibration: @@ -91,6 +81,12 @@ * - `B` - Run bed temperature calibration. * - `P` - Run probe temperature calibration. */ + +static void say_waiting_for() { SERIAL_ECHOPGM("Waiting for "); } +static void say_waiting_for_probe_heating() { say_waiting_for(); SERIAL_ECHOLNPGM("probe heating."); } +static void say_successfully_calibrated() { SERIAL_ECHOPGM("Successfully calibrated"); } +static void say_failed_to_calibrate() { SERIAL_ECHOPGM("!Failed to calibrate"); } + void GcodeSuite::G76() { // Check if heated bed is available and z-homing is done with probe #if TEMP_SENSOR_BED == 0 || !(HOMING_Z_WITH_PROBE) @@ -107,14 +103,14 @@ void GcodeSuite::G76() { return (timeout && ELAPSED(ms, timeout)); }; - auto wait_for_temps = [&](const float tb, const float tp, millis_t &ntr, const millis_t timeout=0) { - SERIAL_ECHOLNPGM("Waiting for bed and probe temperature."); - while (fabs(thermalManager.degBed() - tb) > 0.1f || thermalManager.degProbe() > tp) + auto wait_for_temps = [&](const celsius_t tb, const celsius_t tp, millis_t &ntr, const millis_t timeout=0) { + say_waiting_for(); SERIAL_ECHOLNPGM("bed and probe temperature."); + while (thermalManager.wholeDegBed() != tb || thermalManager.wholeDegProbe() > tp) if (report_temps(ntr, timeout)) return true; return false; }; - auto g76_probe = [](const TempSensorID sid, uint16_t &targ, const xy_pos_t &nozpos) { + auto g76_probe = [](const TempSensorID sid, celsius_t &targ, const xy_pos_t &nozpos) { do_z_clearance(5.0); // Raise nozzle before probing const float measured_z = probe.probe_at_point(nozpos, PROBE_PT_STOW, 0, false); // verbose=0, probe_relative=false if (isnan(measured_z)) @@ -144,7 +140,7 @@ void GcodeSuite::G76() { const xyz_pos_t parkpos = temp_comp.park_point, probe_pos_xyz = xyz_pos_t(temp_comp.measure_point) + xyz_pos_t({ 0.0f, 0.0f, PTC_PROBE_HEATING_OFFSET }), - noz_pos_xyz = probe_pos_xyz - xy_pos_t(probe.offset_xy); // Nozzle position based on probe position + noz_pos_xyz = probe_pos_xyz - probe.offset_xy; // Nozzle position based on probe position if (do_bed_cal || do_probe_cal) { // Ensure park position is reachable @@ -162,12 +158,11 @@ void GcodeSuite::G76() { return; } - process_subcommands_now_P(PSTR("G28")); + process_subcommands_now_P(G28_STR); } remember_feedrate_scaling_off(); - /****************************************** * Calibrate bed temperature offsets ******************************************/ @@ -175,17 +170,17 @@ void GcodeSuite::G76() { // Report temperatures every second and handle heating timeouts millis_t next_temp_report = millis() + 1000; - auto report_targets = [&](const uint16_t tb, const uint16_t tp) { + auto report_targets = [&](const celsius_t tb, const celsius_t tp) { SERIAL_ECHOLNPAIR("Target Bed:", tb, " Probe:", tp); }; if (do_bed_cal) { - uint16_t target_bed = cali_info_init[TSI_BED].start_temp, - target_probe = temp_comp.bed_calib_probe_temp; + celsius_t target_bed = cali_info_init[TSI_BED].start_temp, + target_probe = temp_comp.bed_calib_probe_temp; - SERIAL_ECHOLNPGM("Waiting for cooling."); - while (thermalManager.degBed() > target_bed || thermalManager.degProbe() > target_probe) + say_waiting_for(); SERIAL_ECHOLNPGM(" cooling."); + while (thermalManager.wholeDegBed() > target_bed || thermalManager.wholeDegProbe() > target_probe) report_temps(next_temp_report); // Disable leveling so it won't mess with us @@ -207,19 +202,24 @@ void GcodeSuite::G76() { // Move the nozzle to the probing point and wait for the probe to reach target temp do_blocking_move_to(noz_pos_xyz); - SERIAL_ECHOLNPGM("Waiting for probe heating."); - while (thermalManager.degProbe() < target_probe) + say_waiting_for_probe_heating(); + SERIAL_EOL(); + while (thermalManager.wholeDegProbe() < target_probe) report_temps(next_temp_report); const float measured_z = g76_probe(TSI_BED, target_bed, noz_pos_xyz); - if (isnan(measured_z) || target_bed > BED_MAX_TARGET) break; + if (isnan(measured_z) || target_bed > (BED_MAX_TARGET)) break; } SERIAL_ECHOLNPAIR("Retrieved measurements: ", temp_comp.get_index()); - if (temp_comp.finish_calibration(TSI_BED)) - SERIAL_ECHOLNPGM("Successfully calibrated bed."); - else - SERIAL_ECHOLNPGM("!Failed to calibrate bed. Values reset."); + if (temp_comp.finish_calibration(TSI_BED)) { + say_successfully_calibrated(); + SERIAL_ECHOLNPGM(" bed."); + } + else { + say_failed_to_calibrate(); + SERIAL_ECHOLNPGM(" bed. Values reset."); + } // Cleanup thermalManager.setTargetBed(0); @@ -236,10 +236,10 @@ void GcodeSuite::G76() { do_blocking_move_to(parkpos); // Initialize temperatures - const uint16_t target_bed = temp_comp.probe_calib_bed_temp; + const celsius_t target_bed = temp_comp.probe_calib_bed_temp; thermalManager.setTargetBed(target_bed); - uint16_t target_probe = cali_info_init[TSI_PROBE].start_temp; + celsius_t target_probe = cali_info_init[TSI_PROBE].start_temp; report_targets(target_bed, target_probe); @@ -254,8 +254,9 @@ void GcodeSuite::G76() { // Move probe to probing point and wait for it to reach target temperature do_blocking_move_to(noz_pos_xyz); - SERIAL_ECHOLNPAIR("Waiting for probe heating. Bed:", target_bed, " Probe:", target_probe); - const millis_t probe_timeout_ms = millis() + 900UL * 1000UL; + say_waiting_for_probe_heating(); + SERIAL_ECHOLNPAIR(" Bed:", target_bed, " Probe:", target_probe); + const millis_t probe_timeout_ms = millis() + SEC_TO_MS(900UL); while (thermalManager.degProbe() < target_probe) { if (report_temps(next_temp_report, probe_timeout_ms)) { SERIAL_ECHOLNPGM("!Probe heating timed out."); @@ -271,9 +272,9 @@ void GcodeSuite::G76() { SERIAL_ECHOLNPAIR("Retrieved measurements: ", temp_comp.get_index()); if (temp_comp.finish_calibration(TSI_PROBE)) - SERIAL_ECHOPGM("Successfully calibrated"); + say_successfully_calibrated(); else - SERIAL_ECHOPGM("!Failed to calibrate"); + say_failed_to_calibrate(); SERIAL_ECHOLNPGM(" probe."); // Cleanup @@ -349,7 +350,7 @@ void GcodeSuite::M192() { return; } - const float target_temp = parser.value_celsius(); + const celsius_t target_temp = parser.value_celsius(); ui.set_status_P(thermalManager.isProbeBelowTemp(target_temp) ? GET_TEXT(MSG_PROBE_HEATING) : GET_TEXT(MSG_PROBE_COOLING)); thermalManager.wait_for_probe(target_temp, no_wait_for_cooling); } diff --git a/Marlin/src/gcode/calibrate/M100.cpp b/Marlin/src/gcode/calibrate/M100.cpp index 9ac2380e7964..ee572e033d75 100644 --- a/Marlin/src/gcode/calibrate/M100.cpp +++ b/Marlin/src/gcode/calibrate/M100.cpp @@ -51,7 +51,7 @@ * Also, there are two support functions that can be called from a developer's C code. * * uint16_t check_for_free_memory_corruption(PGM_P const free_memory_start); - * void M100_dump_routine(PGM_P const title, const char * const start, const char * const end); + * void M100_dump_routine(PGM_P const title, const char * const start, const uintptr_t size); * * Initial version by Roxy-3D */ @@ -151,7 +151,7 @@ inline int32_t count_test_bytes(const char * const start_free_memory) { * the block. If so, it may indicate memory corruption due to a bad pointer. * Unexpected bytes are flagged in the right column. */ - inline void dump_free_memory(char *start_free_memory, char *end_free_memory) { + void dump_free_memory(char *start_free_memory, char *end_free_memory) { // // Start and end the dump on a nice 16 byte boundary // (even though the values are not 16-byte aligned). @@ -182,12 +182,12 @@ inline int32_t count_test_bytes(const char * const start_free_memory) { } } - void M100_dump_routine(PGM_P const title, const char * const start, const char * const end) { - serialprintPGM(title); - SERIAL_EOL(); + void M100_dump_routine(PGM_P const title, const char * const start, const uintptr_t size) { + SERIAL_ECHOLNPGM_P(title); // // Round the start and end locations to produce full lines of output // + const char * const end = start + size - 1; dump_free_memory( (char*)(uintptr_t(uint32_t(start) & ~0xFUL)), // Align to 16-byte boundary (char*)(uintptr_t(uint32_t(end) | 0xFUL)) // Align end_free_memory to the 15th byte (at or above end_free_memory) @@ -197,27 +197,27 @@ inline int32_t count_test_bytes(const char * const start_free_memory) { #endif // M100_FREE_MEMORY_DUMPER inline int check_for_free_memory_corruption(PGM_P const title) { - serialprintPGM(title); + SERIAL_ECHOPGM_P(title); char *start_free_memory = free_memory_start, *end_free_memory = free_memory_end; int n = end_free_memory - start_free_memory; - SERIAL_ECHOPAIR("\nfmc() n=", n); - SERIAL_ECHOPAIR("\nfree_memory_start=", hex_address(free_memory_start)); - SERIAL_ECHOLNPAIR(" end_free_memory=", hex_address(end_free_memory)); + SERIAL_ECHOLNPAIR("\nfmc() n=", n, + "\nfree_memory_start=", hex_address(free_memory_start), + " end=", hex_address(end_free_memory)); if (end_free_memory < start_free_memory) { SERIAL_ECHOPGM(" end_free_memory < Heap "); - // SET_INPUT_PULLUP(63); // if the developer has a switch wired up to their controller board - // safe_delay(5); // this code can be enabled to pause the display as soon as the - // while ( READ(63)) // malfunction is detected. It is currently defaulting to a switch - // idle(); // being on pin-63 which is unassigend and available on most controller - // safe_delay(20); // boards. - // while ( !READ(63)) - // idle(); + //SET_INPUT_PULLUP(63); // if the developer has a switch wired up to their controller board + //safe_delay(5); // this code can be enabled to pause the display as soon as the + //while ( READ(63)) // malfunction is detected. It is currently defaulting to a switch + // idle(); // being on pin-63 which is unassigend and available on most controller + //safe_delay(20); // boards. + //while ( !READ(63)) + // idle(); serial_delay(20); #if ENABLED(M100_FREE_MEMORY_DUMPER) - M100_dump_routine(PSTR(" Memory corruption detected with end_free_memory 8) { - // SERIAL_ECHOPAIR("Found ", j); - // SERIAL_ECHOLNPAIR(" bytes free at ", hex_address(start_free_memory + i)); + //SERIAL_ECHOPAIR("Found ", j); + //SERIAL_ECHOLNPAIR(" bytes free at ", hex_address(start_free_memory + i)); i += j; block_cnt++; - SERIAL_ECHOPAIR(" (", block_cnt); - SERIAL_ECHOPAIR(") found=", j); - SERIAL_ECHOLNPGM(" "); + SERIAL_ECHOLNPAIR(" (", block_cnt, ") found=", j); } } } @@ -269,8 +267,7 @@ inline void free_memory_pool_report(char * const start_free_memory, const int32_ if (*addr == TEST_BYTE) { const int32_t j = count_test_bytes(addr); if (j > 8) { - SERIAL_ECHOPAIR("Found ", j); - SERIAL_ECHOLNPAIR(" bytes free at ", hex_address(addr)); + SERIAL_ECHOLNPAIR("Found ", j, " bytes free at ", hex_address(addr)); if (j > max_cnt) { max_cnt = j; max_addr = addr; @@ -280,11 +277,10 @@ inline void free_memory_pool_report(char * const start_free_memory, const int32_ } } } - if (block_cnt > 1) { - SERIAL_ECHOLNPGM("\nMemory Corruption detected in free memory area."); - SERIAL_ECHOPAIR("\nLargest free block is ", max_cnt); - SERIAL_ECHOLNPAIR(" bytes at ", hex_address(max_addr)); - } + if (block_cnt > 1) SERIAL_ECHOLNPAIR( + "\nMemory Corruption detected in free memory area." + "\nLargest free block is ", max_cnt, " bytes at ", hex_address(max_addr) + ); SERIAL_ECHOLNPAIR("check_for_free_memory_corruption() = ", check_for_free_memory_corruption(PSTR("M100 F "))); } @@ -294,12 +290,12 @@ inline void free_memory_pool_report(char * const start_free_memory, const int32_ * Corrupt locations in the free memory pool and report the corrupt addresses. * This is useful to check the correctness of the M100 D and the M100 F commands. */ - inline void corrupt_free_memory(char *start_free_memory, const uint32_t size) { + inline void corrupt_free_memory(char *start_free_memory, const uintptr_t size) { start_free_memory += 8; const uint32_t near_top = top_of_stack() - start_free_memory - 250, // -250 to avoid interrupt activity that's altered the stack. j = near_top / (size + 1); - SERIAL_ECHOLNPGM("Corrupting free memory block.\n"); + SERIAL_ECHOLNPGM("Corrupting free memory block."); for (uint32_t i = 1; i <= size; i++) { char * const addr = start_free_memory + i * j; *addr = i; @@ -322,8 +318,8 @@ inline void init_free_memory(char *start_free_memory, int32_t size) { return; } - start_free_memory += 8; // move a few bytes away from the heap just because we don't want - // to be altering memory that close to it. + start_free_memory += 8; // move a few bytes away from the heap just because we + // don't want to be altering memory that close to it. memset(start_free_memory, TEST_BYTE, size); SERIAL_ECHO(size); @@ -342,16 +338,16 @@ inline void init_free_memory(char *start_free_memory, int32_t size) { * M100: Free Memory Check */ void GcodeSuite::M100() { - char *sp = top_of_stack(); if (!free_memory_end) free_memory_end = sp - MEMORY_END_CORRECTION; - SERIAL_ECHOPAIR("\nbss_end : ", hex_address(end_bss)); - if (heaplimit) SERIAL_ECHOPAIR("\n__heaplimit : ", hex_address(heaplimit)); - SERIAL_ECHOPAIR("\nfree_memory_start : ", hex_address(free_memory_start)); + SERIAL_ECHOPAIR("\nbss_end : ", hex_address(end_bss)); + if (heaplimit) SERIAL_ECHOPAIR("\n__heaplimit : ", hex_address(heaplimit)); + SERIAL_ECHOPAIR("\nfree_memory_start : ", hex_address(free_memory_start)); if (stacklimit) SERIAL_ECHOPAIR("\n__stacklimit : ", hex_address(stacklimit)); - SERIAL_ECHOPAIR("\nfree_memory_end : ", hex_address(free_memory_end)); - if (MEMORY_END_CORRECTION) SERIAL_ECHOPAIR("\nMEMORY_END_CORRECTION: ", MEMORY_END_CORRECTION); - SERIAL_ECHOLNPAIR("\nStack Pointer : ", hex_address(sp)); + SERIAL_ECHOPAIR("\nfree_memory_end : ", hex_address(free_memory_end)); + if (MEMORY_END_CORRECTION) + SERIAL_ECHOPAIR("\nMEMORY_END_CORRECTION : ", MEMORY_END_CORRECTION); + SERIAL_ECHOLNPAIR("\nStack Pointer : ", hex_address(sp)); // Always init on the first invocation of M100 static bool m100_not_initialized = true; @@ -369,10 +365,8 @@ void GcodeSuite::M100() { return free_memory_pool_report(free_memory_start, free_memory_end - free_memory_start); #if ENABLED(M100_FREE_MEMORY_CORRUPTOR) - if (parser.seen('C')) return corrupt_free_memory(free_memory_start, parser.value_int()); - #endif } diff --git a/Marlin/src/gcode/calibrate/M425.cpp b/Marlin/src/gcode/calibrate/M425.cpp index 40441ac08d16..f30de00a0fdf 100644 --- a/Marlin/src/gcode/calibrate/M425.cpp +++ b/Marlin/src/gcode/calibrate/M425.cpp @@ -48,15 +48,20 @@ void GcodeSuite::M425() { auto axis_can_calibrate = [](const uint8_t a) { switch (a) { - default: - case X_AXIS: return AXIS_CAN_CALIBRATE(X); - case Y_AXIS: return AXIS_CAN_CALIBRATE(Y); - case Z_AXIS: return AXIS_CAN_CALIBRATE(Z); + default: return false; + LINEAR_AXIS_CODE( + case X_AXIS: return AXIS_CAN_CALIBRATE(X), + case Y_AXIS: return AXIS_CAN_CALIBRATE(Y), + case Z_AXIS: return AXIS_CAN_CALIBRATE(Z), + case I_AXIS: return AXIS_CAN_CALIBRATE(I), + case J_AXIS: return AXIS_CAN_CALIBRATE(J), + case K_AXIS: return AXIS_CAN_CALIBRATE(K), + ); } }; - LOOP_XYZ(a) { - if (axis_can_calibrate(a) && parser.seen(XYZ_CHAR(a))) { + LOOP_LINEAR_AXES(a) { + if (axis_can_calibrate(a) && parser.seen(AXIS_CHAR(a))) { planner.synchronize(); backlash.distance_mm[a] = parser.has_value() ? parser.value_linear_units() : backlash.get_measurement(AxisEnum(a)); noArgs = false; @@ -83,8 +88,8 @@ void GcodeSuite::M425() { SERIAL_ECHOLNPGM("active:"); SERIAL_ECHOLNPAIR(" Correction Amount/Fade-out: F", backlash.get_correction(), " (F1.0 = full, F0.0 = none)"); SERIAL_ECHOPGM(" Backlash Distance (mm): "); - LOOP_XYZ(a) if (axis_can_calibrate(a)) { - SERIAL_CHAR(' ', XYZ_CHAR(a)); + LOOP_LINEAR_AXES(a) if (axis_can_calibrate(a)) { + SERIAL_CHAR(' ', AXIS_CHAR(a)); SERIAL_ECHO(backlash.distance_mm[a]); SERIAL_EOL(); } @@ -96,8 +101,8 @@ void GcodeSuite::M425() { #if ENABLED(MEASURE_BACKLASH_WHEN_PROBING) SERIAL_ECHOPGM(" Average measured backlash (mm):"); if (backlash.has_any_measurement()) { - LOOP_XYZ(a) if (axis_can_calibrate(a) && backlash.has_measurement(AxisEnum(a))) { - SERIAL_CHAR(' ', XYZ_CHAR(a)); + LOOP_LINEAR_AXES(a) if (axis_can_calibrate(a) && backlash.has_measurement(AxisEnum(a))) { + SERIAL_CHAR(' ', AXIS_CHAR(a)); SERIAL_ECHO(backlash.get_measurement(AxisEnum(a))); } } diff --git a/Marlin/src/gcode/calibrate/M48.cpp b/Marlin/src/gcode/calibrate/M48.cpp index 8640dfa39166..19b11f602a42 100644 --- a/Marlin/src/gcode/calibrate/M48.cpp +++ b/Marlin/src/gcode/calibrate/M48.cpp @@ -27,7 +27,7 @@ #include "../gcode.h" #include "../../module/motion.h" #include "../../module/probe.h" -#include "../../lcd/ultralcd.h" +#include "../../lcd/marlinui.h" #include "../../feature/bedlevel/bedlevel.h" @@ -51,8 +51,6 @@ * This function requires the machine to be homed before invocation. */ -extern const char SP_Y_STR[]; - void GcodeSuite::M48() { if (homing_needed_error()) return; @@ -119,7 +117,7 @@ void GcodeSuite::M48() { max = -99999.9, // Largest value sampled so far sample_set[n_samples]; // Storage for sampled values - auto dev_report = [](const bool verbose, const float &mean, const float &sigma, const float &min, const float &max, const bool final=false) { + auto dev_report = [](const bool verbose, const_float_t mean, const_float_t sigma, const_float_t min, const_float_t max, const bool final=false) { if (verbose) { SERIAL_ECHOPAIR_F("Mean: ", mean, 6); if (!final) SERIAL_ECHOPAIR_F(" Sigma: ", sigma, 6); @@ -144,7 +142,7 @@ void GcodeSuite::M48() { float sample_sum = 0.0; LOOP_L_N(n, n_samples) { - #if HAS_WIRED_LCD + #if HAS_STATUS_MESSAGE // Display M48 progress in the status bar ui.status_printf_P(0, PSTR(S_FMT ": %d/%d"), GET_TEXT(MSG_M48_POINT), int(n + 1), int(n_samples)); #endif @@ -204,7 +202,7 @@ void GcodeSuite::M48() { if (verbose_level > 3) SERIAL_ECHOLNPAIR_P(PSTR("Moving inward: X"), next_pos.x, SP_Y_STR, next_pos.y); } - #else + #elif HAS_ENDSTOPS // For a rectangular bed just keep the probe in bounds LIMIT(next_pos.x, X_MIN_POS, X_MAX_POS); LIMIT(next_pos.y, Y_MIN_POS, Y_MAX_POS); @@ -243,8 +241,9 @@ void GcodeSuite::M48() { if (verbose_level > 1) { SERIAL_ECHO(n + 1); - SERIAL_ECHOPAIR(" of ", int(n_samples)); + SERIAL_ECHOPAIR(" of ", n_samples); SERIAL_ECHOPAIR_F(": z: ", pz, 3); + SERIAL_CHAR(' '); dev_report(verbose_level > 2, mean, sigma, min, max); SERIAL_EOL(); } @@ -258,7 +257,7 @@ void GcodeSuite::M48() { SERIAL_ECHOLNPGM("Finished!"); dev_report(verbose_level > 0, mean, sigma, min, max, true); - #if HAS_WIRED_LCD + #if HAS_STATUS_MESSAGE // Display M48 results in the status bar char sigma_str[8]; ui.status_printf_P(0, PSTR(S_FMT ": %s"), GET_TEXT(MSG_M48_DEVIATION), dtostrf(sigma, 2, 6, sigma_str)); diff --git a/Marlin/src/gcode/calibrate/M665.cpp b/Marlin/src/gcode/calibrate/M665.cpp index 557204cc1102..0d0c4146d931 100644 --- a/Marlin/src/gcode/calibrate/M665.cpp +++ b/Marlin/src/gcode/calibrate/M665.cpp @@ -40,21 +40,21 @@ * X = Alpha (Tower 1) angle trim * Y = Beta (Tower 2) angle trim * Z = Gamma (Tower 3) angle trim - * A = Alpha (Tower 1) digonal rod trim - * B = Beta (Tower 2) digonal rod trim - * C = Gamma (Tower 3) digonal rod trim + * A = Alpha (Tower 1) diagonal rod trim + * B = Beta (Tower 2) diagonal rod trim + * C = Gamma (Tower 3) diagonal rod trim */ void GcodeSuite::M665() { - if (parser.seen('H')) delta_height = parser.value_linear_units(); - if (parser.seen('L')) delta_diagonal_rod = parser.value_linear_units(); - if (parser.seen('R')) delta_radius = parser.value_linear_units(); - if (parser.seen('S')) delta_segments_per_second = parser.value_float(); - if (parser.seen('X')) delta_tower_angle_trim.a = parser.value_float(); - if (parser.seen('Y')) delta_tower_angle_trim.b = parser.value_float(); - if (parser.seen('Z')) delta_tower_angle_trim.c = parser.value_float(); - if (parser.seen('A')) delta_diagonal_rod_trim.a = parser.value_float(); - if (parser.seen('B')) delta_diagonal_rod_trim.b = parser.value_float(); - if (parser.seen('C')) delta_diagonal_rod_trim.c = parser.value_float(); + if (parser.seenval('H')) delta_height = parser.value_linear_units(); + if (parser.seenval('L')) delta_diagonal_rod = parser.value_linear_units(); + if (parser.seenval('R')) delta_radius = parser.value_linear_units(); + if (parser.seenval('S')) segments_per_second = parser.value_float(); + if (parser.seenval('X')) delta_tower_angle_trim.a = parser.value_float(); + if (parser.seenval('Y')) delta_tower_angle_trim.b = parser.value_float(); + if (parser.seenval('Z')) delta_tower_angle_trim.c = parser.value_float(); + if (parser.seenval('A')) delta_diagonal_rod_trim.a = parser.value_float(); + if (parser.seenval('B')) delta_diagonal_rod_trim.b = parser.value_float(); + if (parser.seenval('C')) delta_diagonal_rod_trim.c = parser.value_float(); recalc_delta_settings(); } @@ -76,7 +76,7 @@ * B, T, and Y are all aliases for the elbow angle */ void GcodeSuite::M665() { - if (parser.seenval('S')) delta_segments_per_second = parser.value_float(); + if (parser.seenval('S')) segments_per_second = parser.value_float(); #if HAS_SCARA_OFFSET diff --git a/Marlin/src/gcode/calibrate/M666.cpp b/Marlin/src/gcode/calibrate/M666.cpp index e915aa8ff7b7..872344e4e923 100644 --- a/Marlin/src/gcode/calibrate/M666.cpp +++ b/Marlin/src/gcode/calibrate/M666.cpp @@ -27,30 +27,72 @@ #include "../gcode.h" #if ENABLED(DELTA) - #include "../../module/delta.h" #include "../../module/motion.h" +#else + #include "../../module/endstops.h" +#endif + +#define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) +#include "../../core/debug_out.h" - #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) - #include "../../core/debug_out.h" +void M666_report(const bool forReplay=true) { + if (!forReplay) { SERIAL_ECHOLNPGM("; Endstop adjustment:"); SERIAL_ECHO_START(); } + #if ENABLED(DELTA) + SERIAL_ECHOLNPAIR_P( + PSTR(" M666 X"), LINEAR_UNIT(delta_endstop_adj.a) + , SP_Y_STR, LINEAR_UNIT(delta_endstop_adj.b) + , SP_Z_STR, LINEAR_UNIT(delta_endstop_adj.c) + ); + #else + SERIAL_ECHOPGM(" M666"); + #if ENABLED(X_DUAL_ENDSTOPS) + SERIAL_ECHOLNPAIR_P(SP_X_STR, LINEAR_UNIT(endstops.x2_endstop_adj)); + #endif + #if ENABLED(Y_DUAL_ENDSTOPS) + SERIAL_ECHOLNPAIR_P(SP_Y_STR, LINEAR_UNIT(endstops.y2_endstop_adj)); + #endif + #if ENABLED(Z_MULTI_ENDSTOPS) + #if NUM_Z_STEPPER_DRIVERS >= 3 + SERIAL_ECHOPAIR(" S2 Z", LINEAR_UNIT(endstops.z3_endstop_adj)); + if (!forReplay) SERIAL_ECHO_START(); + SERIAL_ECHOPAIR(" M666 S3 Z", LINEAR_UNIT(endstops.z3_endstop_adj)); + #if NUM_Z_STEPPER_DRIVERS >= 4 + if (!forReplay) SERIAL_ECHO_START(); + SERIAL_ECHOPAIR(" M666 S4 Z", LINEAR_UNIT(endstops.z4_endstop_adj)); + #endif + #else + SERIAL_ECHOLNPAIR_P(SP_Z_STR, LINEAR_UNIT(endstops.z2_endstop_adj)); + #endif + #endif + #endif +} + +#if ENABLED(DELTA) /** * M666: Set delta endstop adjustment */ void GcodeSuite::M666() { DEBUG_SECTION(log_M666, "M666", DEBUGGING(LEVELING)); - LOOP_XYZ(i) { - if (parser.seen(XYZ_CHAR(i))) { + bool is_err = false, is_set = false; + LOOP_LINEAR_AXES(i) { + if (parser.seen(AXIS_CHAR(i))) { + is_set = true; const float v = parser.value_linear_units(); - if (v * Z_HOME_DIR <= 0) delta_endstop_adj[i] = v; - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("delta_endstop_adj[", XYZ_CHAR(i), "] = ", delta_endstop_adj[i]); + if (v > 0) + is_err = true; + else { + delta_endstop_adj[i] = v; + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("delta_endstop_adj[", AS_CHAR(AXIS_CHAR(i)), "] = ", v); + } } } + if (is_err) SERIAL_ECHOLNPAIR("?M666 offsets must be <= 0"); + if (!is_set) M666_report(); } -#elif HAS_EXTRA_ENDSTOPS - - #include "../../module/endstops.h" +#else /** * M666: Set Dual Endstops offsets for X, Y, and/or Z. @@ -71,33 +113,17 @@ #endif #if ENABLED(Z_MULTI_ENDSTOPS) if (parser.seenval('Z')) { - #if NUM_Z_STEPPER_DRIVERS >= 3 - const float z_adj = parser.value_linear_units(); - const int ind = parser.intval('S'); - if (!ind || ind == 2) endstops.z2_endstop_adj = z_adj; - if (!ind || ind == 3) endstops.z3_endstop_adj = z_adj; - #if NUM_Z_STEPPER_DRIVERS >= 4 - if (!ind || ind == 4) endstops.z4_endstop_adj = z_adj; - #endif + const float z_adj = parser.value_linear_units(); + #if NUM_Z_STEPPER_DRIVERS == 2 + endstops.z2_endstop_adj = z_adj; #else - endstops.z2_endstop_adj = parser.value_linear_units(); + const int ind = parser.intval('S'); + #define _SET_ZADJ(N) if (!ind || ind == N) endstops.z##N##_endstop_adj = z_adj; + REPEAT_S(2, INCREMENT(NUM_Z_STEPPER_DRIVERS), _SET_ZADJ) #endif } #endif - if (!parser.seen("XYZ")) { - SERIAL_ECHOPGM("Dual Endstop Adjustment (mm): "); - #if ENABLED(X_DUAL_ENDSTOPS) - SERIAL_ECHOPAIR(" X2:", endstops.x2_endstop_adj); - #endif - #if ENABLED(Y_DUAL_ENDSTOPS) - SERIAL_ECHOPAIR(" Y2:", endstops.y2_endstop_adj); - #endif - #if ENABLED(Z_MULTI_ENDSTOPS) - #define _ECHO_ZADJ(N) SERIAL_ECHOPAIR(" Z" STRINGIFY(N) ":", endstops.z##N##_endstop_adj); - REPEAT_S(2, INCREMENT(NUM_Z_STEPPER_DRIVERS), _ECHO_ZADJ) - #endif - SERIAL_EOL(); - } + if (!parser.seen("XYZ")) M666_report(); } #endif // HAS_EXTRA_ENDSTOPS diff --git a/Marlin/src/gcode/calibrate/M852.cpp b/Marlin/src/gcode/calibrate/M852.cpp index b60f41748fec..73b18ad4665e 100644 --- a/Marlin/src/gcode/calibrate/M852.cpp +++ b/Marlin/src/gcode/calibrate/M852.cpp @@ -86,14 +86,14 @@ void GcodeSuite::M852() { // When skew is changed the current position changes if (setval) { - set_current_from_steppers_for_axis(ALL_AXES); + set_current_from_steppers_for_axis(ALL_AXES_ENUM); sync_plan_position(); report_current_position(); } if (!ijk) { SERIAL_ECHO_START(); - serialprintPGM(GET_TEXT(MSG_SKEW_FACTOR)); + SERIAL_ECHOPGM("Skew Factor"); SERIAL_ECHOPAIR_F(" XY: ", planner.skew_factor.xy, 6); #if ENABLED(SKEW_CORRECTION_FOR_Z) SERIAL_ECHOPAIR_F(" XZ: ", planner.skew_factor.xz, 6); diff --git a/Marlin/src/gcode/config/M200-M205.cpp b/Marlin/src/gcode/config/M200-M205.cpp index cb17fc45a6e8..a2bcb8bb86a8 100644 --- a/Marlin/src/gcode/config/M200-M205.cpp +++ b/Marlin/src/gcode/config/M200-M205.cpp @@ -86,9 +86,9 @@ void GcodeSuite::M201() { if (parser.seenval('G')) planner.xy_freq_min_speed_factor = constrain(parser.value_float(), 1, 100) / 100; #endif - LOOP_XYZE(i) { - if (parser.seen(axis_codes[i])) { - const uint8_t a = (i == E_AXIS ? uint8_t(E_AXIS_N(target_extruder)) : i); + LOOP_LOGICAL_AXES(i) { + if (parser.seenval(axis_codes[i])) { + const uint8_t a = TERN(HAS_EXTRUDERS, (i == E_AXIS ? uint8_t(E_AXIS_N(target_extruder)) : i), i); planner.set_max_acceleration(a, parser.value_axis_units((AxisEnum)a)); } } @@ -104,9 +104,9 @@ void GcodeSuite::M203() { const int8_t target_extruder = get_target_extruder_from_command(); if (target_extruder < 0) return; - LOOP_XYZE(i) - if (parser.seen(axis_codes[i])) { - const uint8_t a = (i == E_AXIS ? uint8_t(E_AXIS_N(target_extruder)) : i); + LOOP_LOGICAL_AXES(i) + if (parser.seenval(axis_codes[i])) { + const uint8_t a = TERN(HAS_EXTRUDERS, (i == E_AXIS ? uint8_t(E_AXIS_N(target_extruder)) : i), i); planner.set_max_feedrate(a, parser.value_axis_units((AxisEnum)a)); } } @@ -147,24 +147,17 @@ void GcodeSuite::M204() { * J = Junction Deviation (mm) (If not using CLASSIC_JERK) */ void GcodeSuite::M205() { - #if HAS_JUNCTION_DEVIATION - #define J_PARAM "J" - #else - #define J_PARAM - #endif - #if HAS_CLASSIC_JERK - #define XYZE_PARAM "XYZE" - #else - #define XYZE_PARAM - #endif - if (!parser.seen("BST" J_PARAM XYZE_PARAM)) return; + if (!parser.seen("BST" TERN_(HAS_JUNCTION_DEVIATION, "J") TERN_(HAS_CLASSIC_JERK, "XYZE"))) return; //planner.synchronize(); - if (parser.seen('B')) planner.settings.min_segment_time_us = parser.value_ulong(); - if (parser.seen('S')) planner.settings.min_feedrate_mm_s = parser.value_linear_units(); - if (parser.seen('T')) planner.settings.min_travel_feedrate_mm_s = parser.value_linear_units(); + if (parser.seenval('B')) planner.settings.min_segment_time_us = parser.value_ulong(); + 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 (parser.seen('J')) { + #if HAS_CLASSIC_JERK && (AXIS4_NAME == 'J' || AXIS5_NAME == 'J' || AXIS6_NAME == '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)) { planner.junction_deviation_mm = junc_dev; @@ -175,17 +168,19 @@ void GcodeSuite::M205() { } #endif #if HAS_CLASSIC_JERK - if (parser.seen('X')) planner.set_max_jerk(X_AXIS, parser.value_linear_units()); - if (parser.seen('Y')) planner.set_max_jerk(Y_AXIS, parser.value_linear_units()); - if (parser.seen('Z')) { - planner.set_max_jerk(Z_AXIS, parser.value_linear_units()); - #if HAS_MESH && DISABLED(LIMITED_JERK_EDITING) - if (planner.max_jerk.z <= 0.1f) - SERIAL_ECHOLNPGM("WARNING! Low Z Jerk may lead to unwanted pauses."); - #endif - } - #if HAS_CLASSIC_E_JERK - if (parser.seen('E')) planner.set_max_jerk(E_AXIS, parser.value_linear_units()); + bool seenZ = false; + LOGICAL_AXIS_CODE( + if (parser.seenval('E')) planner.set_max_jerk(E_AXIS, parser.value_linear_units()), + if (parser.seenval('X')) planner.set_max_jerk(X_AXIS, parser.value_linear_units()), + if (parser.seenval('Y')) planner.set_max_jerk(Y_AXIS, parser.value_linear_units()), + if ((seenZ = parser.seenval('Z'))) planner.set_max_jerk(Z_AXIS, parser.value_linear_units()), + if (parser.seenval(AXIS4_NAME)) planner.set_max_jerk(I_AXIS, parser.value_linear_units()), + if (parser.seenval(AXIS5_NAME)) planner.set_max_jerk(J_AXIS, parser.value_linear_units()), + if (parser.seenval(AXIS6_NAME)) planner.set_max_jerk(K_AXIS, parser.value_linear_units()) + ); + #if HAS_MESH && DISABLED(LIMITED_JERK_EDITING) + if (seenZ && planner.max_jerk.z <= 0.1f) + SERIAL_ECHOLNPGM("WARNING! Low Z Jerk may lead to unwanted pauses."); #endif - #endif + #endif // HAS_CLASSIC_JERK } diff --git a/Marlin/src/gcode/config/M217.cpp b/Marlin/src/gcode/config/M217.cpp index b57dec31f360..2035ae55abeb 100644 --- a/Marlin/src/gcode/config/M217.cpp +++ b/Marlin/src/gcode/config/M217.cpp @@ -33,12 +33,10 @@ #include "../../MarlinCore.h" // for SP_X_STR, etc. -extern const char SP_X_STR[], SP_Y_STR[], SP_Z_STR[]; - void M217_report(const bool eeprom=false) { #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) - serialprintPGM(eeprom ? PSTR(" M217") : PSTR("Toolchange:")); + SERIAL_ECHOPGM_P(eeprom ? PSTR(" M217") : PSTR("Toolchange:")); SERIAL_ECHOPAIR(" S", LINEAR_UNIT(toolchange_settings.swap_length)); SERIAL_ECHOPAIR_P(SP_B_STR, LINEAR_UNIT(toolchange_settings.extra_resume), SP_E_STR, LINEAR_UNIT(toolchange_settings.extra_prime), @@ -49,7 +47,7 @@ void M217_report(const bool eeprom=false) { " G", toolchange_settings.fan_time); #if ENABLED(TOOLCHANGE_MIGRATION_FEATURE) - SERIAL_ECHOPAIR(" A", int(migration.automode)); + SERIAL_ECHOPAIR(" A", migration.automode); SERIAL_ECHOPAIR(" L", LINEAR_UNIT(migration.last)); #endif diff --git a/Marlin/src/gcode/config/M220.cpp b/Marlin/src/gcode/config/M220.cpp index 1bec6a778204..75339f10b9fc 100644 --- a/Marlin/src/gcode/config/M220.cpp +++ b/Marlin/src/gcode/config/M220.cpp @@ -31,17 +31,15 @@ * * Report the current speed percentage factor if no parameter is specified * - * With PRUSA_MMU2... + * For MMU2 and MMU2S devices... * B : Flag to back up the current factor * R : Flag to restore the last-saved factor */ void GcodeSuite::M220() { - #if ENABLED(PRUSA_MMU2) - static int16_t backup_feedrate_percentage = 100; - if (parser.seen('B')) backup_feedrate_percentage = feedrate_percentage; - if (parser.seen('R')) feedrate_percentage = backup_feedrate_percentage; - #endif + static int16_t backup_feedrate_percentage = 100; + if (parser.seen('B')) backup_feedrate_percentage = feedrate_percentage; + if (parser.seen('R')) feedrate_percentage = backup_feedrate_percentage; if (parser.seenval('S')) feedrate_percentage = parser.value_int(); diff --git a/Marlin/src/gcode/config/M221.cpp b/Marlin/src/gcode/config/M221.cpp index 7ba22d1901d5..e380bfb1c7d0 100644 --- a/Marlin/src/gcode/config/M221.cpp +++ b/Marlin/src/gcode/config/M221.cpp @@ -23,7 +23,7 @@ #include "../gcode.h" #include "../../module/planner.h" -#if EXTRUDERS +#if HAS_EXTRUDERS /** * M221: Set extrusion percentage (M221 T0 S95) diff --git a/Marlin/src/gcode/config/M281.cpp b/Marlin/src/gcode/config/M281.cpp index 018ca1c0928d..eeb0fcc470e1 100644 --- a/Marlin/src/gcode/config/M281.cpp +++ b/Marlin/src/gcode/config/M281.cpp @@ -34,7 +34,9 @@ * U - Stowed Angle */ void GcodeSuite::M281() { + if (!parser.seenval('P')) return; + const int servo_index = parser.value_int(); if (WITHIN(servo_index, 0, NUM_SERVOS - 1)) { #if ENABLED(BLTOUCH) @@ -53,16 +55,14 @@ void GcodeSuite::M281() { angle_change = true; } if (!angle_change) { - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR(" Servo ", servo_index, - " L", servo_angles[servo_index][0], - " U", servo_angles[servo_index][1]); + SERIAL_ECHO_MSG(" Servo ", servo_index, + " L", servo_angles[servo_index][0], + " U", servo_angles[servo_index][1]); } } - else { - SERIAL_ERROR_START(); - SERIAL_ECHOLNPAIR("Servo ", servo_index, " out of range"); - } + else + SERIAL_ERROR_MSG("Servo ", servo_index, " out of range"); + } #endif // EDITABLE_SERVO_ANGLES diff --git a/Marlin/src/gcode/config/M302.cpp b/Marlin/src/gcode/config/M302.cpp index afdc6c9e8506..e3ce5a10ef0e 100644 --- a/Marlin/src/gcode/config/M302.cpp +++ b/Marlin/src/gcode/config/M302.cpp @@ -55,7 +55,7 @@ void GcodeSuite::M302() { // Report current state SERIAL_ECHO_START(); SERIAL_ECHOPGM("Cold extrudes are "); - serialprintPGM(thermalManager.allow_cold_extrude ? PSTR("en") : PSTR("dis")); + SERIAL_ECHOPGM_P(thermalManager.allow_cold_extrude ? PSTR("en") : PSTR("dis")); SERIAL_ECHOLNPAIR("abled (min temp ", thermalManager.extrude_min_temp, "C)"); } } diff --git a/Marlin/src/gcode/config/M304.cpp b/Marlin/src/gcode/config/M304.cpp index 10739be3f8c3..b1af5a5ae21f 100644 --- a/Marlin/src/gcode/config/M304.cpp +++ b/Marlin/src/gcode/config/M304.cpp @@ -35,14 +35,15 @@ * D - Set the D value */ void GcodeSuite::M304() { + if (parser.seen('P')) thermalManager.temp_bed.pid.Kp = parser.value_float(); if (parser.seen('I')) thermalManager.temp_bed.pid.Ki = scalePID_i(parser.value_float()); if (parser.seen('D')) thermalManager.temp_bed.pid.Kd = scalePID_d(parser.value_float()); - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR(" p:", thermalManager.temp_bed.pid.Kp, - " i:", unscalePID_i(thermalManager.temp_bed.pid.Ki), - " d:", unscalePID_d(thermalManager.temp_bed.pid.Kd)); + SERIAL_ECHO_MSG(" p:", thermalManager.temp_bed.pid.Kp, + " i:", unscalePID_i(thermalManager.temp_bed.pid.Ki), + " d:", unscalePID_d(thermalManager.temp_bed.pid.Kd)); + } #endif // PIDTEMPBED diff --git a/Marlin/src/gcode/config/M305.cpp b/Marlin/src/gcode/config/M305.cpp index 3e7206aee49d..10ef55c17341 100644 --- a/Marlin/src/gcode/config/M305.cpp +++ b/Marlin/src/gcode/config/M305.cpp @@ -49,10 +49,8 @@ void GcodeSuite::M305() { const bool do_set = parser.seen("BCRT"); // A valid P index is required - if (t_index >= (USER_THERMISTORS) || (do_set && t_index < 0)) { - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR("!Invalid index. (0 <= P <= ", int(USER_THERMISTORS - 1), ")"); - } + if (t_index >= (USER_THERMISTORS) || (do_set && t_index < 0)) + SERIAL_ECHO_MSG("!Invalid index. (0 <= P <= ", USER_THERMISTORS - 1, ")"); else if (do_set) { if (parser.seen('R')) // Pullup resistor value if (!thermalManager.set_pull_up_res(t_index, parser.value_float())) diff --git a/Marlin/src/gcode/config/M309.cpp b/Marlin/src/gcode/config/M309.cpp new file mode 100644 index 000000000000..2247481b2579 --- /dev/null +++ b/Marlin/src/gcode/config/M309.cpp @@ -0,0 +1,48 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(PIDTEMPCHAMBER) + +#include "../gcode.h" +#include "../../module/temperature.h" + +/** + * M309 - Set and/or Report the current Chamber PID values + * + * P - Set the P value + * I - Set the I value + * D - Set the D value + */ +void GcodeSuite::M309() { + if (parser.seen('P')) thermalManager.temp_chamber.pid.Kp = parser.value_float(); + if (parser.seen('I')) thermalManager.temp_chamber.pid.Ki = scalePID_i(parser.value_float()); + if (parser.seen('D')) thermalManager.temp_chamber.pid.Kd = scalePID_d(parser.value_float()); + + SERIAL_ECHO_START(); + SERIAL_ECHOLNPAIR(" p:", thermalManager.temp_chamber.pid.Kp, + " i:", unscalePID_i(thermalManager.temp_chamber.pid.Ki), + " d:", unscalePID_d(thermalManager.temp_chamber.pid.Kd)); +} + +#endif // PIDTEMPCHAMBER diff --git a/Marlin/src/gcode/config/M43.cpp b/Marlin/src/gcode/config/M43.cpp index 1e780ca05afd..84757e740370 100644 --- a/Marlin/src/gcode/config/M43.cpp +++ b/Marlin/src/gcode/config/M43.cpp @@ -47,7 +47,7 @@ #endif #if HAS_RESUME_CONTINUE - #include "../../lcd/ultralcd.h" + #include "../../lcd/marlinui.h" #endif #ifndef GET_PIN_MAP_PIN_M43 @@ -131,7 +131,7 @@ inline void servo_probe_test() { const uint8_t probe_index = parser.byteval('P', Z_PROBE_SERVO_NR); SERIAL_ECHOLNPAIR("Servo probe test\n" - ". using index: ", int(probe_index), + ". using index: ", probe_index, ", deploy angle: ", servo_angles[probe_index][0], ", stow angle: ", servo_angles[probe_index][1] ); @@ -143,7 +143,7 @@ inline void servo_probe_test() { #define PROBE_TEST_PIN Z_MIN_PIN constexpr bool probe_inverting = Z_MIN_ENDSTOP_INVERTING; - SERIAL_ECHOLNPAIR(". Probe Z_MIN_PIN: ", int(PROBE_TEST_PIN)); + SERIAL_ECHOLNPAIR(". Probe Z_MIN_PIN: ", PROBE_TEST_PIN); SERIAL_ECHOPGM(". Z_MIN_ENDSTOP_INVERTING: "); #else @@ -151,7 +151,7 @@ inline void servo_probe_test() { #define PROBE_TEST_PIN Z_MIN_PROBE_PIN constexpr bool probe_inverting = Z_MIN_PROBE_ENDSTOP_INVERTING; - SERIAL_ECHOLNPAIR(". Probe Z_MIN_PROBE_PIN: ", int(PROBE_TEST_PIN)); + SERIAL_ECHOLNPAIR(". Probe Z_MIN_PROBE_PIN: ", PROBE_TEST_PIN); SERIAL_ECHOPGM( ". Z_MIN_PROBE_ENDSTOP_INVERTING: "); #endif @@ -288,8 +288,8 @@ inline void servo_probe_test() { * S - Start Pin number. If not given, will default to 0 * L - End Pin number. If not given, will default to last pin defined for this board * I - Flag to ignore Marlin's pin protection. Use with caution!!!! - * R - Repeat pulses on each pin this number of times before continueing to next pin - * W - Wait time (in miliseconds) between pulses. If not given will default to 500 + * R - Repeat pulses on each pin this number of times before continuing to next pin + * W - Wait time (in milliseconds) between pulses. If not given will default to 500 * * M43 S - Servo probe test * P - Probe index (optional - defaults to 0 @@ -303,7 +303,7 @@ void GcodeSuite::M43() { if (parser.seen('E')) { endstops.monitor_flag = parser.value_bool(); SERIAL_ECHOPGM("endstop monitor "); - serialprintPGM(endstops.monitor_flag ? PSTR("en") : PSTR("dis")); + SERIAL_ECHOPGM_P(endstops.monitor_flag ? PSTR("en") : PSTR("dis")); SERIAL_ECHOLNPGM("abled"); return; } diff --git a/Marlin/src/gcode/config/M575.cpp b/Marlin/src/gcode/config/M575.cpp index 44723b7f2fe6..7739510cf3cf 100644 --- a/Marlin/src/gcode/config/M575.cpp +++ b/Marlin/src/gcode/config/M575.cpp @@ -52,19 +52,25 @@ void GcodeSuite::M575() { case 2400: case 9600: case 19200: case 38400: case 57600: case 115200: case 250000: case 500000: case 1000000: { const int8_t port = parser.intval('P', -99); - const bool set0 = (port == -99 || port == 0); - if (set0) SERIAL_ECHO_MSG(" Serial ", '0', " baud rate set to ", baud); + const bool set1 = (port == -99 || port == 0); + if (set1) SERIAL_ECHO_MSG(" Serial ", AS_CHAR('0'), " baud rate set to ", baud); #if HAS_MULTI_SERIAL - const bool set1 = (port == -99 || port == 1); - if (set1) SERIAL_ECHO_MSG(" Serial ", '1', " baud rate set to ", baud); + const bool set2 = (port == -99 || port == 1); + if (set2) SERIAL_ECHO_MSG(" Serial ", AS_CHAR('1'), " baud rate set to ", baud); + #ifdef SERIAL_PORT_3 + const bool set3 = (port == -99 || port == 2); + if (set3) SERIAL_ECHO_MSG(" Serial ", AS_CHAR('2'), " baud rate set to ", baud); + #endif #endif SERIAL_FLUSH(); - if (set0) { MYSERIAL0.end(); MYSERIAL0.begin(baud); } - + if (set1) { MYSERIAL1.end(); MYSERIAL1.begin(baud); } #if HAS_MULTI_SERIAL - if (set1) { MYSERIAL1.end(); MYSERIAL1.begin(baud); } + if (set2) { MYSERIAL2.end(); MYSERIAL2.begin(baud); } + #ifdef SERIAL_PORT_3 + if (set3) { MYSERIAL3.end(); MYSERIAL3.begin(baud); } + #endif #endif } break; diff --git a/Marlin/src/gcode/config/M92.cpp b/Marlin/src/gcode/config/M92.cpp index 0a7d52b633cc..544c66a0768a 100644 --- a/Marlin/src/gcode/config/M92.cpp +++ b/Marlin/src/gcode/config/M92.cpp @@ -25,10 +25,15 @@ void report_M92(const bool echo=true, const int8_t e=-1) { if (echo) SERIAL_ECHO_START(); else SERIAL_CHAR(' '); - SERIAL_ECHOPAIR_P(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])); - #if DISABLED(DISTINCT_E_FACTORS) + SERIAL_ECHOPAIR_P(LIST_N(DOUBLE(LINEAR_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, LINEAR_UNIT(planner.settings.axis_steps_per_mm[I_AXIS]), + SP_J_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[J_AXIS]), + SP_K_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[K_AXIS])) + ); + #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS) SERIAL_ECHOPAIR_P(SP_E_STR, VOLUMETRIC_UNIT(planner.settings.axis_steps_per_mm[E_AXIS])); #endif SERIAL_EOL(); @@ -37,12 +42,12 @@ void report_M92(const bool echo=true, const int8_t e=-1) { LOOP_L_N(i, E_STEPPERS) { if (e >= 0 && i != e) continue; if (echo) SERIAL_ECHO_START(); else SERIAL_CHAR(' '); - SERIAL_ECHOLNPAIR_P(PSTR(" M92 T"), (int)i, + SERIAL_ECHOLNPAIR_P(PSTR(" M92 T"), i, SP_E_STR, VOLUMETRIC_UNIT(planner.settings.axis_steps_per_mm[E_AXIS_N(i)])); } #endif - UNUSED_E(e); + UNUSED(e); } /** @@ -64,28 +69,28 @@ void GcodeSuite::M92() { if (target_extruder < 0) return; // No arguments? Show M92 report. - if (!parser.seen("XYZE" - #if ENABLED(MAGIC_NUMBERS_GCODE) - "HL" - #endif + if (!parser.seen( + LOGICAL_AXIS_GANG("E", "X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR) + TERN_(MAGIC_NUMBERS_GCODE, "HL") )) return report_M92(true, target_extruder); - LOOP_XYZE(i) { + LOOP_LOGICAL_AXES(i) { if (parser.seenval(axis_codes[i])) { - if (i == E_AXIS) { - const float value = parser.value_per_axis_units((AxisEnum)(E_AXIS_N(target_extruder))); - if (value < 20) { - float factor = planner.settings.axis_steps_per_mm[E_AXIS_N(target_extruder)] / value; // increase e constants if M92 E14 is given for netfab. - #if HAS_CLASSIC_JERK && HAS_CLASSIC_E_JERK - planner.max_jerk.e *= factor; - #endif - planner.settings.max_feedrate_mm_s[E_AXIS_N(target_extruder)] *= factor; - planner.max_acceleration_steps_per_s2[E_AXIS_N(target_extruder)] *= factor; - } - planner.settings.axis_steps_per_mm[E_AXIS_N(target_extruder)] = value; - } - else { + if (TERN1(HAS_EXTRUDERS, i != E_AXIS)) planner.settings.axis_steps_per_mm[i] = parser.value_per_axis_units((AxisEnum)i); + else { + #if HAS_EXTRUDERS + const float value = parser.value_per_axis_units((AxisEnum)(E_AXIS_N(target_extruder))); + if (value < 20) { + float factor = planner.settings.axis_steps_per_mm[E_AXIS_N(target_extruder)] / value; // increase e constants if M92 E14 is given for netfab. + #if HAS_CLASSIC_JERK && HAS_CLASSIC_E_JERK + planner.max_jerk.e *= factor; + #endif + planner.settings.max_feedrate_mm_s[E_AXIS_N(target_extruder)] *= factor; + planner.max_acceleration_steps_per_s2[E_AXIS_N(target_extruder)] *= factor; + } + planner.settings.axis_steps_per_mm[E_AXIS_N(target_extruder)] = value; + #endif } } } diff --git a/Marlin/src/gcode/control/M10-M11.cpp b/Marlin/src/gcode/control/M10-M11.cpp new file mode 100644 index 000000000000..d5a69dcfccfb --- /dev/null +++ b/Marlin/src/gcode/control/M10-M11.cpp @@ -0,0 +1,44 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(AIR_EVACUATION) + +#include "../gcode.h" +#include "../../feature/spindle_laser.h" + +/** + * M10: Vacuum or Blower On + */ +void GcodeSuite::M10() { + cutter.air_evac_enable(); // Turn on Vacuum or Blower motor +} + +/** + * M11: Vacuum or Blower OFF + */ +void GcodeSuite::M11() { + cutter.air_evac_disable(); // Turn off Vacuum or Blower motor +} + +#endif // AIR_EVACUATION diff --git a/Marlin/src/gcode/control/M108_M112_M410.cpp b/Marlin/src/gcode/control/M108_M112_M410.cpp index df145d5d11c9..309c806c8fc5 100644 --- a/Marlin/src/gcode/control/M108_M112_M410.cpp +++ b/Marlin/src/gcode/control/M108_M112_M410.cpp @@ -25,7 +25,8 @@ #if DISABLED(EMERGENCY_PARSER) #include "../gcode.h" -#include "../../MarlinCore.h" // for wait_for_heatup, kill, quickstop_stepper +#include "../../MarlinCore.h" // for wait_for_heatup, kill, M112_KILL_STR +#include "../../module/motion.h" // for quickstop_stepper /** * M108: Stop the waiting for heaters in M109, M190, M303. Does not affect the target temperature. diff --git a/Marlin/src/gcode/control/M111.cpp b/Marlin/src/gcode/control/M111.cpp index cc871bf38b52..e762e3387fca 100644 --- a/Marlin/src/gcode/control/M111.cpp +++ b/Marlin/src/gcode/control/M111.cpp @@ -49,29 +49,29 @@ void GcodeSuite::M111() { LOOP_L_N(i, COUNT(debug_strings)) { if (TEST(marlin_debug_flags, i)) { if (comma++) SERIAL_CHAR(','); - serialprintPGM((char*)pgm_read_ptr(&debug_strings[i])); + SERIAL_ECHOPGM_P((char*)pgm_read_ptr(&debug_strings[i])); } } } else { SERIAL_ECHOPGM(STR_DEBUG_OFF); - #if !IS_AT90USB + #if !defined(__AVR__) || !defined(USBCON) #if ENABLED(SERIAL_STATS_RX_BUFFER_OVERRUNS) - SERIAL_ECHOPAIR("\nBuffer Overruns: ", MYSERIAL0.buffer_overruns()); + SERIAL_ECHOPAIR("\nBuffer Overruns: ", MYSERIAL1.buffer_overruns()); #endif #if ENABLED(SERIAL_STATS_RX_FRAMING_ERRORS) - SERIAL_ECHOPAIR("\nFraming Errors: ", MYSERIAL0.framing_errors()); + SERIAL_ECHOPAIR("\nFraming Errors: ", MYSERIAL1.framing_errors()); #endif #if ENABLED(SERIAL_STATS_DROPPED_RX) - SERIAL_ECHOPAIR("\nDropped bytes: ", MYSERIAL0.dropped()); + SERIAL_ECHOPAIR("\nDropped bytes: ", MYSERIAL1.dropped()); #endif #if ENABLED(SERIAL_STATS_MAX_RX_QUEUED) - SERIAL_ECHOPAIR("\nMax RX Queue Size: ", MYSERIAL0.rxMaxEnqueued()); + SERIAL_ECHOPAIR("\nMax RX Queue Size: ", MYSERIAL1.rxMaxEnqueued()); #endif - #endif // !IS_AT90USB + #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 499feef71586..4ebb81cf7ea7 100644 --- a/Marlin/src/gcode/control/M17_M18_M84.cpp +++ b/Marlin/src/gcode/control/M17_M18_M84.cpp @@ -22,7 +22,7 @@ #include "../gcode.h" #include "../../MarlinCore.h" // for stepper_inactive_time, disable_e_steppers -#include "../../lcd/ultralcd.h" +#include "../../lcd/marlinui.h" #include "../../module/stepper.h" #if ENABLED(AUTO_BED_LEVELING_UBL) @@ -33,11 +33,16 @@ * M17: Enable stepper motors */ void GcodeSuite::M17() { - if (parser.seen("XYZE")) { - if (parser.seen('X')) ENABLE_AXIS_X(); - if (parser.seen('Y')) ENABLE_AXIS_Y(); - if (parser.seen('Z')) ENABLE_AXIS_Z(); - if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen('E'))) enable_e_steppers(); + if (parser.seen(LOGICAL_AXIS_GANG("E", "X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR))) { + LOGICAL_AXIS_CODE( + if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen_test('E'))) enable_e_steppers(), + if (parser.seen_test('X')) ENABLE_AXIS_X(), + if (parser.seen_test('Y')) ENABLE_AXIS_Y(), + if (parser.seen_test('Z')) ENABLE_AXIS_Z(), + if (parser.seen_test(AXIS4_NAME)) ENABLE_AXIS_I(), + if (parser.seen_test(AXIS5_NAME)) ENABLE_AXIS_J(), + if (parser.seen_test(AXIS6_NAME)) ENABLE_AXIS_K() + ); } else { LCD_MESSAGEPGM(MSG_NO_MOVE); @@ -54,12 +59,17 @@ void GcodeSuite::M18_M84() { stepper_inactive_time = parser.value_millis_from_seconds(); } else { - if (parser.seen("XYZE")) { + if (parser.seen(LOGICAL_AXIS_GANG("E", "X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR))) { planner.synchronize(); - if (parser.seen('X')) DISABLE_AXIS_X(); - if (parser.seen('Y')) DISABLE_AXIS_Y(); - if (parser.seen('Z')) DISABLE_AXIS_Z(); - if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen('E'))) disable_e_steppers(); + LOGICAL_AXIS_CODE( + if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen_test('E'))) disable_e_steppers(), + if (parser.seen_test('X')) DISABLE_AXIS_X(), + if (parser.seen_test('Y')) DISABLE_AXIS_Y(), + if (parser.seen_test('Z')) DISABLE_AXIS_Z(), + if (parser.seen_test(AXIS4_NAME)) DISABLE_AXIS_I(), + if (parser.seen_test(AXIS5_NAME)) DISABLE_AXIS_J(), + if (parser.seen_test(AXIS6_NAME)) DISABLE_AXIS_K() + ); } else planner.finish_and_disable(); diff --git a/Marlin/src/gcode/control/M211.cpp b/Marlin/src/gcode/control/M211.cpp index 2049f1eb6955..2ba777ba650e 100644 --- a/Marlin/src/gcode/control/M211.cpp +++ b/Marlin/src/gcode/control/M211.cpp @@ -39,8 +39,8 @@ void GcodeSuite::M211() { SERIAL_ECHOPGM(STR_SOFT_ENDSTOPS); if (parser.seen('S')) soft_endstop._enabled = parser.value_bool(); serialprint_onoff(soft_endstop._enabled); - print_xyz(l_soft_min, PSTR(STR_SOFT_MIN), PSTR(" ")); - print_xyz(l_soft_max, PSTR(STR_SOFT_MAX)); + print_pos(l_soft_min, PSTR(STR_SOFT_MIN), PSTR(" ")); + print_pos(l_soft_max, PSTR(STR_SOFT_MAX)); } #endif diff --git a/Marlin/src/gcode/control/M226.cpp b/Marlin/src/gcode/control/M226.cpp index ad717e614d8a..63f022e82bd8 100644 --- a/Marlin/src/gcode/control/M226.cpp +++ b/Marlin/src/gcode/control/M226.cpp @@ -28,6 +28,8 @@ #include "../../MarlinCore.h" // for pin_is_protected and idle() #include "../../module/stepper.h" +void protected_pin_err(); + /** * M226: Wait until the specified pin reaches the state required (M226 P S) */ diff --git a/Marlin/src/gcode/control/M280.cpp b/Marlin/src/gcode/control/M280.cpp index 6ccbb7becc2f..187c9a9b1998 100644 --- a/Marlin/src/gcode/control/M280.cpp +++ b/Marlin/src/gcode/control/M280.cpp @@ -31,7 +31,9 @@ * M280: Get or set servo position. P [S] */ void GcodeSuite::M280() { + if (!parser.seen('P')) return; + const int servo_index = parser.value_int(); if (WITHIN(servo_index, 0, NUM_SERVOS - 1)) { if (parser.seen('S')) { @@ -41,15 +43,12 @@ void GcodeSuite::M280() { else MOVE_SERVO(servo_index, a); } - else { - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR(" Servo ", servo_index, ": ", servo[servo_index].read()); - } - } - else { - SERIAL_ERROR_START(); - SERIAL_ECHOLNPAIR("Servo ", servo_index, " out of range"); + else + SERIAL_ECHO_MSG(" Servo ", servo_index, ": ", servo[servo_index].read()); } + else + SERIAL_ERROR_MSG("Servo ", servo_index, " out of range"); + } #endif // HAS_SERVOS diff --git a/Marlin/src/gcode/control/M3-M5.cpp b/Marlin/src/gcode/control/M3-M5.cpp index 1326c30669a2..711bb7e5e4a7 100644 --- a/Marlin/src/gcode/control/M3-M5.cpp +++ b/Marlin/src/gcode/control/M3-M5.cpp @@ -69,9 +69,13 @@ void GcodeSuite::M3_M4(const bool is_M4) { auto get_s_power = [] { if (parser.seenval('S')) { const float spwr = parser.value_float(); - cutter.unitPower = TERN(SPINDLE_LASER_PWM, + #if ENABLED(SPINDLE_SERVO) + cutter.unitPower = spwr; + #else + cutter.unitPower = TERN(SPINDLE_LASER_PWM, cutter.power_to_range(cutter_power_t(round(spwr))), spwr > 0 ? 255 : 0); + #endif } else cutter.unitPower = cutter.cpwr_to_upwr(SPEED_POWER_STARTUP); @@ -99,7 +103,7 @@ void GcodeSuite::M3_M4(const bool is_M4) { #endif planner.synchronize(); // Wait for previous movement commands (G0/G0/G2/G3) to complete before changing power - cutter.set_direction(is_M4); + cutter.set_reverse(is_M4); #if ENABLED(SPINDLE_LASER_PWM) if (parser.seenval('O')) { @@ -108,6 +112,8 @@ void GcodeSuite::M3_M4(const bool is_M4) { } else cutter.set_power(cutter.upower_to_ocr(get_s_power())); + #elif ENABLED(SPINDLE_SERVO) + cutter.set_power(get_s_power()); #else cutter.set_enabled(true); #endif diff --git a/Marlin/src/gcode/control/M350_M351.cpp b/Marlin/src/gcode/control/M350_M351.cpp index 463bd2ad5815..a92238e4bbf2 100644 --- a/Marlin/src/gcode/control/M350_M351.cpp +++ b/Marlin/src/gcode/control/M350_M351.cpp @@ -34,7 +34,7 @@ */ void GcodeSuite::M350() { if (parser.seen('S')) LOOP_LE_N(i, 4) stepper.microstep_mode(i, parser.value_byte()); - LOOP_XYZE(i) if (parser.seen(axis_codes[i])) stepper.microstep_mode(i, parser.value_byte()); + LOOP_LOGICAL_AXES(i) if (parser.seen(axis_codes[i])) stepper.microstep_mode(i, parser.value_byte()); if (parser.seen('B')) stepper.microstep_mode(4, parser.value_byte()); stepper.microstep_readings(); } @@ -46,15 +46,15 @@ void GcodeSuite::M350() { void GcodeSuite::M351() { if (parser.seenval('S')) switch (parser.value_byte()) { case 1: - LOOP_XYZE(i) if (parser.seenval(axis_codes[i])) stepper.microstep_ms(i, parser.value_byte(), -1, -1); + LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) stepper.microstep_ms(i, parser.value_byte(), -1, -1); if (parser.seenval('B')) stepper.microstep_ms(4, parser.value_byte(), -1, -1); break; case 2: - LOOP_XYZE(i) if (parser.seenval(axis_codes[i])) stepper.microstep_ms(i, -1, parser.value_byte(), -1); + LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) stepper.microstep_ms(i, -1, parser.value_byte(), -1); if (parser.seenval('B')) stepper.microstep_ms(4, -1, parser.value_byte(), -1); break; case 3: - LOOP_XYZE(i) if (parser.seenval(axis_codes[i])) stepper.microstep_ms(i, -1, -1, parser.value_byte()); + LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) stepper.microstep_ms(i, -1, -1, parser.value_byte()); if (parser.seenval('B')) stepper.microstep_ms(4, -1, -1, parser.value_byte()); break; } diff --git a/Marlin/src/gcode/control/M42.cpp b/Marlin/src/gcode/control/M42.cpp index c635c06ec63b..908260ed25dd 100644 --- a/Marlin/src/gcode/control/M42.cpp +++ b/Marlin/src/gcode/control/M42.cpp @@ -31,6 +31,17 @@ #include "../../module/temperature.h" #endif +#ifdef MAPLE_STM32F1 + // these are enums on the F1... + #define INPUT_PULLDOWN INPUT_PULLDOWN + #define INPUT_ANALOG INPUT_ANALOG + #define OUTPUT_OPEN_DRAIN OUTPUT_OPEN_DRAIN +#endif + +void protected_pin_err() { + SERIAL_ERROR_MSG(STR_ERR_PROTECTED_PIN); +} + /** * M42: Change pin status via GCode * @@ -51,13 +62,20 @@ void GcodeSuite::M42() { if (!parser.boolval('I') && pin_is_protected(pin)) return protected_pin_err(); + bool avoidWrite = false; if (parser.seenval('M')) { switch (parser.value_byte()) { - case 0: pinMode(pin, INPUT); break; + case 0: pinMode(pin, INPUT); avoidWrite = true; break; case 1: pinMode(pin, OUTPUT); break; - case 2: pinMode(pin, INPUT_PULLUP); break; + case 2: pinMode(pin, INPUT_PULLUP); avoidWrite = true; break; #ifdef INPUT_PULLDOWN - case 3: pinMode(pin, INPUT_PULLDOWN); break; + case 3: pinMode(pin, INPUT_PULLDOWN); avoidWrite = true; break; + #endif + #ifdef INPUT_ANALOG + case 4: pinMode(pin, INPUT_ANALOG); avoidWrite = true; break; + #endif + #ifdef OUTPUT_OPEN_DRAIN + case 5: pinMode(pin, OUTPUT_OPEN_DRAIN); break; #endif default: SERIAL_ECHOLNPGM("Invalid Pin Mode"); return; } @@ -95,8 +113,22 @@ void GcodeSuite::M42() { } #endif - pinMode(pin, OUTPUT); + if (avoidWrite) { + SERIAL_ECHOLNPGM("?Cannot write to INPUT"); + return; + } + + // 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 + #ifndef OUTPUT_OPEN_DRAIN + pinMode(pin, OUTPUT); + #endif extDigitalWrite(pin, pin_status); + + #ifdef ARDUINO_ARCH_STM32 + // A simple I/O will be set to 0 by analogWrite() + if (pin_status <= 1) return; + #endif analogWrite(pin, pin_status); } diff --git a/Marlin/src/gcode/control/M605.cpp b/Marlin/src/gcode/control/M605.cpp index 5dc36428b503..23d43dd0a60b 100644 --- a/Marlin/src/gcode/control/M605.cpp +++ b/Marlin/src/gcode/control/M605.cpp @@ -68,29 +68,14 @@ const DualXMode previous_mode = dual_x_carriage_mode; dual_x_carriage_mode = (DualXMode)parser.value_byte(); - mirrored_duplication_mode = false; - - if (dual_x_carriage_mode == DXC_MIRRORED_MODE) { - if (previous_mode != DXC_DUPLICATION_MODE) { - SERIAL_ECHOLNPGM("Printer must be in DXC_DUPLICATION_MODE prior to "); - SERIAL_ECHOLNPGM("specifying DXC_MIRRORED_MODE."); - dual_x_carriage_mode = DEFAULT_DUAL_X_CARRIAGE_MODE; - return; - } - mirrored_duplication_mode = true; - stepper.set_directions(); - float x_jog = current_position.x - .1; - for (uint8_t i = 2; --i;) { - planner.buffer_line(x_jog, current_position.y, current_position.z, current_position.e, feedrate_mm_s, 0); - x_jog += .1; - } - return; - } + idex_set_mirrored_mode(false); switch (dual_x_carriage_mode) { + case DXC_FULL_CONTROL_MODE: case DXC_AUTO_PARK_MODE: break; + case DXC_DUPLICATION_MODE: // Set the X offset, but no less than the safety gap if (parser.seen('X')) duplicate_extruder_x_offset = _MAX(parser.value_linear_units(), (X2_MIN_POS) - (X1_MIN_POS)); @@ -98,14 +83,35 @@ // Always switch back to tool 0 if (active_extruder != 0) tool_change(0); break; + + case DXC_MIRRORED_MODE: { + if (previous_mode != DXC_DUPLICATION_MODE) { + SERIAL_ECHOLNPGM("Printer must be in DXC_DUPLICATION_MODE prior to "); + SERIAL_ECHOLNPGM("specifying DXC_MIRRORED_MODE."); + dual_x_carriage_mode = DEFAULT_DUAL_X_CARRIAGE_MODE; + return; + } + idex_set_mirrored_mode(true); + + // Do a small 'jog' motion in the X axis + xyze_pos_t dest = current_position; dest.x -= 0.1f; + for (uint8_t i = 2; --i;) { + planner.buffer_line(dest, feedrate_mm_s, 0); + dest.x += 0.1f; + } + } return; + default: dual_x_carriage_mode = DEFAULT_DUAL_X_CARRIAGE_MODE; break; } - active_extruder_parked = false; - extruder_duplication_enabled = false; - stepper.set_directions(); - delayed_move_time = 0; + + idex_set_parked(false); + set_duplication_enabled(false); + + #ifdef EVENT_GCODE_IDEX_AFTER_MODECHANGE + gcode.process_subcommands_now_P(PSTR(EVENT_GCODE_IDEX_AFTER_MODECHANGE)); + #endif } else if (!parser.seen('W')) // if no S or W parameter, the DXC mode gets reset to the user's default dual_x_carriage_mode = DEFAULT_DUAL_X_CARRIAGE_MODE; @@ -121,26 +127,26 @@ case DXC_DUPLICATION_MODE: DEBUG_ECHOPGM("DUPLICATION"); break; case DXC_MIRRORED_MODE: DEBUG_ECHOPGM("MIRRORED"); break; } - DEBUG_ECHOPAIR("\nActive Ext: ", int(active_extruder)); + DEBUG_ECHOPAIR("\nActive Ext: ", active_extruder); if (!active_extruder_parked) DEBUG_ECHOPGM(" NOT "); DEBUG_ECHOPGM(" parked."); DEBUG_ECHOPAIR("\nactive_extruder_x_pos: ", current_position.x); - DEBUG_ECHOPAIR("\ninactive_extruder_x_pos: ", inactive_extruder_x_pos); - DEBUG_ECHOPAIR("\nextruder_duplication_enabled: ", int(extruder_duplication_enabled)); + DEBUG_ECHOPAIR("\ninactive_extruder_x: ", inactive_extruder_x); + DEBUG_ECHOPAIR("\nextruder_duplication_enabled: ", extruder_duplication_enabled); DEBUG_ECHOPAIR("\nduplicate_extruder_x_offset: ", duplicate_extruder_x_offset); DEBUG_ECHOPAIR("\nduplicate_extruder_temp_offset: ", duplicate_extruder_temp_offset); DEBUG_ECHOPAIR("\ndelayed_move_time: ", delayed_move_time); - DEBUG_ECHOPAIR("\nX1 Home X: ", x_home_pos(0), "\nX1_MIN_POS=", int(X1_MIN_POS), "\nX1_MAX_POS=", int(X1_MAX_POS)); - DEBUG_ECHOPAIR("\nX2 Home X: ", x_home_pos(1), "\nX2_MIN_POS=", int(X2_MIN_POS), "\nX2_MAX_POS=", int(X2_MAX_POS)); - DEBUG_ECHOPAIR("\nX2_HOME_DIR=", int(X2_HOME_DIR), "\nX2_HOME_POS=", int(X2_HOME_POS)); + DEBUG_ECHOPAIR("\nX1 Home X: ", x_home_pos(0), "\nX1_MIN_POS=", X1_MIN_POS, "\nX1_MAX_POS=", X1_MAX_POS); + DEBUG_ECHOPAIR("\nX2 Home X: ", x_home_pos(1), "\nX2_MIN_POS=", X2_MIN_POS, "\nX2_MAX_POS=", X2_MAX_POS); + DEBUG_ECHOPAIR("\nX2_HOME_DIR=", X2_HOME_DIR, "\nX2_HOME_POS=", X2_HOME_POS); DEBUG_ECHOPAIR("\nDEFAULT_DUAL_X_CARRIAGE_MODE=", STRINGIFY(DEFAULT_DUAL_X_CARRIAGE_MODE)); DEBUG_ECHOPAIR("\toolchange_settings.z_raise=", toolchange_settings.z_raise); - DEBUG_ECHOPAIR("\nDEFAULT_DUPLICATION_X_OFFSET=", int(DEFAULT_DUPLICATION_X_OFFSET)); + DEBUG_ECHOPAIR("\nDEFAULT_DUPLICATION_X_OFFSET=", DEFAULT_DUPLICATION_X_OFFSET); DEBUG_EOL(); HOTEND_LOOP() { - DEBUG_ECHOPAIR_P(SP_T_STR, int(e)); - LOOP_XYZ(a) DEBUG_ECHOPAIR(" hotend_offset[", int(e), "].", XYZ_CHAR(a) | 0x20, "=", hotend_offset[e][a]); + DEBUG_ECHOPAIR_P(SP_T_STR, e); + LOOP_LINEAR_AXES(a) DEBUG_ECHOPAIR(" hotend_offset[", e, "].", AS_CHAR(AXIS_CHAR(a) | 0x20), "=", hotend_offset[e][a]); DEBUG_EOL(); } DEBUG_EOL(); @@ -166,7 +172,7 @@ if (parser.seenval('P')) duplication_e_mask = parser.value_int(); // Set the mask directly else if (parser.seenval('E')) duplication_e_mask = pow(2, parser.value_int() + 1) - 1; // Set the mask by E index ena = (2 == parser.intval('S', extruder_duplication_enabled ? 2 : 0)); - extruder_duplication_enabled = ena && (duplication_e_mask >= 3); + set_duplication_enabled(ena && (duplication_e_mask >= 3)); } SERIAL_ECHO_START(); SERIAL_ECHOPGM(STR_DUPLICATION_MODE); diff --git a/Marlin/src/gcode/control/M7-M9.cpp b/Marlin/src/gcode/control/M7-M9.cpp index a33e43288b75..ccde4f552cb9 100644 --- a/Marlin/src/gcode/control/M7-M9.cpp +++ b/Marlin/src/gcode/control/M7-M9.cpp @@ -20,9 +20,9 @@ * */ -#include "../../inc/MarlinConfig.h" +#include "../../inc/MarlinConfigPre.h" -#if ENABLED(COOLANT_CONTROL) +#if ANY(COOLANT_MIST, COOLANT_FLOOD, AIR_ASSIST) #include "../gcode.h" #include "../../module/planner.h" @@ -37,27 +37,41 @@ } #endif -#if ENABLED(COOLANT_FLOOD) +#if EITHER(COOLANT_FLOOD, AIR_ASSIST) + + #if ENABLED(AIR_ASSIST) + #include "../../feature/spindle_laser.h" + #endif + /** - * M8: Flood Coolant On + * M8: Flood Coolant / Air Assist ON */ void GcodeSuite::M8() { - planner.synchronize(); // Wait for move to arrive - WRITE(COOLANT_FLOOD_PIN, !(COOLANT_FLOOD_INVERT)); // Turn on Flood coolant + planner.synchronize(); // Wait for move to arrive + #if ENABLED(COOLANT_FLOOD) + WRITE(COOLANT_FLOOD_PIN, !(COOLANT_FLOOD_INVERT)); // Turn on Flood coolant + #endif + #if ENABLED(AIR_ASSIST) + cutter.air_assist_enable(); // Turn on Air Assist + #endif } + #endif /** - * M9: Coolant OFF + * M9: Coolant / Air Assist OFF */ void GcodeSuite::M9() { - planner.synchronize(); // Wait for move to arrive + planner.synchronize(); // Wait for move to arrive #if ENABLED(COOLANT_MIST) - WRITE(COOLANT_MIST_PIN, COOLANT_MIST_INVERT); // Turn off Mist coolant + WRITE(COOLANT_MIST_PIN, COOLANT_MIST_INVERT); // Turn off Mist coolant #endif #if ENABLED(COOLANT_FLOOD) - WRITE(COOLANT_FLOOD_PIN, COOLANT_FLOOD_INVERT); // Turn off Flood coolant + WRITE(COOLANT_FLOOD_PIN, COOLANT_FLOOD_INVERT); // Turn off Flood coolant + #endif + #if ENABLED(AIR_ASSIST) + cutter.air_assist_disable(); // Turn off Air Assist #endif } -#endif // COOLANT_CONTROL +#endif // COOLANT_MIST | COOLANT_FLOOD | AIR_ASSIST diff --git a/Marlin/src/gcode/control/M80_M81.cpp b/Marlin/src/gcode/control/M80_M81.cpp index 6302bb5c6787..1b5ea2f7eff0 100644 --- a/Marlin/src/gcode/control/M80_M81.cpp +++ b/Marlin/src/gcode/control/M80_M81.cpp @@ -25,7 +25,7 @@ #include "../../module/temperature.h" #include "../../module/planner.h" // for planner.finish_and_disable #include "../../module/printcounter.h" // for print_job_timer.stop -#include "../../lcd/ultralcd.h" // for LCD_MESSAGEPGM_P +#include "../../lcd/marlinui.h" // for LCD_MESSAGEPGM_P #include "../../inc/MarlinConfig.h" @@ -56,7 +56,7 @@ // S: Report the current power supply state and exit if (parser.seen('S')) { - serialprintPGM(powersupply_on ? PSTR("PS:1\n") : PSTR("PS:0\n")); + SERIAL_ECHOPGM_P(powersupply_on ? PSTR("PS:1\n") : PSTR("PS:0\n")); return; } @@ -89,9 +89,10 @@ */ void GcodeSuite::M81() { thermalManager.disable_all_heaters(); - print_job_timer.stop(); planner.finish_and_disable(); + print_job_timer.stop(); + #if HAS_FAN thermalManager.zero_fan_speeds(); #if ENABLED(PROBING_FANS_OFF) @@ -105,7 +106,7 @@ void GcodeSuite::M81() { #if HAS_SUICIDE suicide(); #elif ENABLED(PSU_CONTROL) - PSU_OFF(); + PSU_OFF_SOON(); #endif LCD_MESSAGEPGM_P(PSTR(MACHINE_NAME " " STR_OFF ".")); diff --git a/Marlin/src/gcode/control/M999.cpp b/Marlin/src/gcode/control/M999.cpp index 3bd908cad640..b7219673a3d6 100644 --- a/Marlin/src/gcode/control/M999.cpp +++ b/Marlin/src/gcode/control/M999.cpp @@ -22,7 +22,7 @@ #include "../gcode.h" -#include "../../lcd/ultralcd.h" // for lcd_reset_alert_level +#include "../../lcd/marlinui.h" // for lcd_reset_alert_level #include "../../MarlinCore.h" // for marlin_state #include "../queue.h" // for flush_and_request_resend @@ -41,5 +41,5 @@ void GcodeSuite::M999() { if (parser.boolval('S')) return; - queue.flush_and_request_resend(); + queue.flush_and_request_resend(queue.ring_buffer.command_port()); } diff --git a/Marlin/src/gcode/control/T.cpp b/Marlin/src/gcode/control/T.cpp index d95e60ff8d70..6a084d83ad27 100644 --- a/Marlin/src/gcode/control/T.cpp +++ b/Marlin/src/gcode/control/T.cpp @@ -27,8 +27,8 @@ #include "../../module/motion.h" #endif -#if ENABLED(PRUSA_MMU2) - #include "../../feature/mmu2/mmu2.h" +#if HAS_PRUSA_MMU2 + #include "../../feature/mmu/mmu2.h" #endif #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) @@ -40,7 +40,7 @@ * F[units/min] Set the movement feedrate * S1 Don't move the tool in XY after change * - * For PRUSA_MMU2: + * 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. * Tx Same as T?, but nozzle doesn't have to be preheated. Tc requires a preheated nozzle to finish filament load. @@ -54,23 +54,17 @@ void GcodeSuite::T(const int8_t tool_index) { // Count this command as movement / activity reset_stepper_timeout(); - #if ENABLED(PRUSA_MMU2) + #if HAS_PRUSA_MMU2 if (parser.string_arg) { mmu2.tool_change(parser.string_arg); // Special commands T?/Tx/Tc return; } #endif - #if EXTRUDERS < 2 - - tool_change(tool_index); - - #else - - tool_change( - tool_index, - (tool_index == active_extruder) || parser.boolval('S') - ); - - #endif + 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') + #endif + ); } diff --git a/Marlin/src/gcode/eeprom/M500-M504.cpp b/Marlin/src/gcode/eeprom/M500-M504.cpp index 26c50a6129a0..cd7833c701bf 100644 --- a/Marlin/src/gcode/eeprom/M500-M504.cpp +++ b/Marlin/src/gcode/eeprom/M500-M504.cpp @@ -75,7 +75,7 @@ void GcodeSuite::M502() { if (dowrite) { val = parser.byteval('V'); persistentStore.write_data(addr, &val); - SERIAL_ECHOLNPAIR("Wrote address ", addr, " with ", int(val)); + SERIAL_ECHOLNPAIR("Wrote address ", addr, " with ", val); } else { if (parser.seenval('T')) { @@ -90,7 +90,7 @@ void GcodeSuite::M502() { } else { persistentStore.read_data(addr, &val); - SERIAL_ECHOLNPAIR("Read address ", addr, " and got ", int(val)); + SERIAL_ECHOLNPAIR("Read address ", addr, " and got ", val); } } return; diff --git a/Marlin/src/gcode/feature/L6470/M122.cpp b/Marlin/src/gcode/feature/L6470/M122.cpp index d2b7f73997f8..cfac42764278 100644 --- a/Marlin/src/gcode/feature/L6470/M122.cpp +++ b/Marlin/src/gcode/feature/L6470/M122.cpp @@ -41,16 +41,16 @@ inline void L6470_say_status(const L64XX_axis_t axis) { SERIAL_ECHO(temp_buf); print_bin(sh.STATUS_AXIS_RAW); switch (sh.STATUS_AXIS_LAYOUT) { - case L6470_STATUS_LAYOUT: serialprintPGM(PSTR(" L6470")); break; - case L6474_STATUS_LAYOUT: serialprintPGM(PSTR(" L6474")); break; - case L6480_STATUS_LAYOUT: serialprintPGM(PSTR(" L6480/powerSTEP01")); break; + case L6470_STATUS_LAYOUT: SERIAL_ECHOPGM(" L6470"); break; + case L6474_STATUS_LAYOUT: SERIAL_ECHOPGM(" L6474"); break; + case L6480_STATUS_LAYOUT: SERIAL_ECHOPGM(" L6480/powerSTEP01"); break; } #endif SERIAL_ECHOPGM("\n...OUTPUT: "); - serialprintPGM(sh.STATUS_AXIS & STATUS_HIZ ? PSTR("OFF") : PSTR("ON ")); + SERIAL_ECHOPGM_P(sh.STATUS_AXIS & STATUS_HIZ ? PSTR("OFF") : PSTR("ON ")); SERIAL_ECHOPGM(" BUSY: "); echo_yes_no((sh.STATUS_AXIS & STATUS_BUSY) == 0); SERIAL_ECHOPGM(" DIR: "); - serialprintPGM((((sh.STATUS_AXIS & STATUS_DIR) >> 4) ^ L64xxManager.index_to_dir[axis]) ? PSTR("FORWARD") : PSTR("REVERSE")); + SERIAL_ECHOPGM_P((((sh.STATUS_AXIS & STATUS_DIR) >> 4) ^ L64xxManager.index_to_dir[axis]) ? PSTR("FORWARD") : PSTR("REVERSE")); if (sh.STATUS_AXIS_LAYOUT == L6480_STATUS_LAYOUT) { SERIAL_ECHOPGM(" Last Command: "); if (sh.STATUS_AXIS & sh.STATUS_AXIS_WRONG_CMD) SERIAL_ECHOPGM("VALID"); @@ -67,7 +67,7 @@ inline void L6470_say_status(const L64XX_axis_t axis) { SERIAL_ECHOPGM(" Last Command: "); if (!(sh.STATUS_AXIS & sh.STATUS_AXIS_WRONG_CMD)) SERIAL_ECHOPGM("IN"); SERIAL_ECHOPGM("VALID "); - serialprintPGM(sh.STATUS_AXIS & sh.STATUS_AXIS_NOTPERF_CMD ? PSTR("COMPLETED ") : PSTR("Not PERFORMED")); + SERIAL_ECHOPGM_P(sh.STATUS_AXIS & sh.STATUS_AXIS_NOTPERF_CMD ? PSTR("COMPLETED ") : PSTR("Not PERFORMED")); SERIAL_ECHOPAIR("\n...THERMAL: ", !(sh.STATUS_AXIS & sh.STATUS_AXIS_TH_SD) ? "SHUTDOWN " : !(sh.STATUS_AXIS & sh.STATUS_AXIS_TH_WRN) ? "WARNING " : "OK "); } SERIAL_ECHOPGM(" OVERCURRENT:"); echo_yes_no((sh.STATUS_AXIS & sh.STATUS_AXIS_OCD) == 0); diff --git a/Marlin/src/gcode/feature/L6470/M906.cpp b/Marlin/src/gcode/feature/L6470/M906.cpp index 7bd446a1ab77..b1beed068a7b 100644 --- a/Marlin/src/gcode/feature/L6470/M906.cpp +++ b/Marlin/src/gcode/feature/L6470/M906.cpp @@ -32,31 +32,6 @@ #define DEBUG_OUT ENABLED(L6470_CHITCHAT) #include "../../../core/debug_out.h" -/** - * M906: report or set KVAL_HOLD which sets the maximum effective voltage provided by the - * PWMs to the steppers - * - * On L6474 this sets the TVAL register (same address). - * - * I - select which driver(s) to change on multi-driver axis - * 0 - (default) all drivers on the axis or E0 - * 1 - monitor only X, Y, Z or E1 - * 2 - monitor only X2, Y2, Z2 or E2 - * 3 - monitor only Z3 or E3 - * 4 - monitor only Z4 or E4 - * 5 - monitor only E5 - * Xxxx, Yxxx, Zxxx, Exxx - axis to change (optional) - * L6474 - current in mA (4A max) - * All others - 0-255 - */ - -/** - * Sets KVAL_HOLD wich affects the current being driven through the stepper. - * - * L6470 is used in the STEP-CLOCK mode. KVAL_HOLD is the only KVAL_xxx - * that affects the effective voltage seen by the stepper. - */ - /** * MACRO to fetch information on the items associated with current limiting * and maximum voltage output. @@ -132,7 +107,7 @@ void L64XX_report_current(L64XX &motor, const L64XX_axis_t axis) { SERIAL_ECHOPAIR("...MicroSteps: ", MicroSteps, " ADC_OUT: ", L6470_ADC_out); SERIAL_ECHOPGM(" Vs_compensation: "); - serialprintPGM((motor.GetParam(sh.L6470_AXIS_CONFIG) & CONFIG_EN_VSCOMP) ? PSTR("ENABLED ") : PSTR("DISABLED")); + SERIAL_ECHOPGM_P((motor.GetParam(sh.L6470_AXIS_CONFIG) & CONFIG_EN_VSCOMP) ? PSTR("ENABLED ") : PSTR("DISABLED")); SERIAL_ECHOLNPAIR(" Compensation coefficient: ~", comp_coef * 0.01f); SERIAL_ECHOPAIR("...KVAL_HOLD: ", motor.GetParam(L6470_KVAL_HOLD), @@ -220,6 +195,28 @@ void L64XX_report_current(L64XX &motor, const L64XX_axis_t axis) { } } +/** + * M906: report or set KVAL_HOLD which sets the maximum effective voltage provided by the + * PWMs to the steppers + * + * On L6474 this sets the TVAL register (same address). + * + * I - select which driver(s) to change on multi-driver axis + * 0 - (default) all drivers on the axis or E0 + * 1 - monitor only X, Y, Z or E1 + * 2 - monitor only X2, Y2, Z2 or E2 + * 3 - monitor only Z3 or E3 + * 4 - monitor only Z4 or E4 + * 5 - monitor only E5 + * Xxxx, Yxxx, Zxxx, Exxx - axis to change (optional) + * L6474 - current in mA (4A max) + * All others - 0-255 + * + * Sets KVAL_HOLD which affects the current being driven through the stepper. + * + * L6470 is used in the STEP-CLOCK mode. KVAL_HOLD is the only KVAL_xxx + * that affects the effective voltage seen by the stepper. + */ void GcodeSuite::M906() { L64xxManager.pause_monitor(true); // Keep monitor_driver() from stealing status @@ -234,7 +231,7 @@ void GcodeSuite::M906() { const uint8_t index = parser.byteval('I'); #endif - LOOP_XYZE(i) if (uint16_t value = parser.intval(axis_codes[i])) { + LOOP_LOGICAL_AXES(i) if (uint16_t value = parser.intval(axis_codes[i])) { report_current = false; @@ -252,58 +249,67 @@ void GcodeSuite::M906() { if (index == 1) L6470_SET_KVAL_HOLD(X2); #endif break; - case Y_AXIS: - #if AXIS_IS_L64XX(Y) - if (index == 0) L6470_SET_KVAL_HOLD(Y); - #endif - #if AXIS_IS_L64XX(Y2) - if (index == 1) L6470_SET_KVAL_HOLD(Y2); - #endif - break; - case Z_AXIS: - #if AXIS_IS_L64XX(Z) - if (index == 0) L6470_SET_KVAL_HOLD(Z); - #endif - #if AXIS_IS_L64XX(Z2) - if (index == 1) L6470_SET_KVAL_HOLD(Z2); - #endif - #if AXIS_IS_L64XX(Z3) - if (index == 2) L6470_SET_KVAL_HOLD(Z3); - #endif - #if AXIS_DRIVER_TYPE_Z4(L6470) - if (index == 3) L6470_SET_KVAL_HOLD(Z4); - #endif - break; - case E_AXIS: { - const int8_t target_extruder = get_target_extruder_from_command(); - if (target_extruder < 0) return; - switch (target_extruder) { - #if AXIS_IS_L64XX(E0) - case 0: L6470_SET_KVAL_HOLD(E0); break; - #endif - #if AXIS_IS_L64XX(E1) - case 1: L6470_SET_KVAL_HOLD(E1); break; - #endif - #if AXIS_IS_L64XX(E2) - case 2: L6470_SET_KVAL_HOLD(E2); break; + + #if HAS_Y_AXIS + case Y_AXIS: + #if AXIS_IS_L64XX(Y) + if (index == 0) L6470_SET_KVAL_HOLD(Y); #endif - #if AXIS_IS_L64XX(E3) - case 3: L6470_SET_KVAL_HOLD(E3); break; + #if AXIS_IS_L64XX(Y2) + if (index == 1) L6470_SET_KVAL_HOLD(Y2); #endif - #if AXIS_IS_L64XX(E4) - case 4: L6470_SET_KVAL_HOLD(E4); break; + break; + #endif + + #if HAS_Z_AXIS + case Z_AXIS: + #if AXIS_IS_L64XX(Z) + if (index == 0) L6470_SET_KVAL_HOLD(Z); #endif - #if AXIS_IS_L64XX(E5) - case 5: L6470_SET_KVAL_HOLD(E5); break; + #if AXIS_IS_L64XX(Z2) + if (index == 1) L6470_SET_KVAL_HOLD(Z2); #endif - #if AXIS_IS_L64XX(E6) - case 6: L6470_SET_KVAL_HOLD(E6); break; + #if AXIS_IS_L64XX(Z3) + if (index == 2) L6470_SET_KVAL_HOLD(Z3); #endif - #if AXIS_IS_L64XX(E7) - case 7: L6470_SET_KVAL_HOLD(E7); break; + #if AXIS_DRIVER_TYPE_Z4(L6470) + if (index == 3) L6470_SET_KVAL_HOLD(Z4); #endif - } - } break; + break; + #endif + + #if E_STEPPERS + case E_AXIS: { + const int8_t target_e_stepper = get_target_e_stepper_from_command(); + if (target_e_stepper < 0) return; + switch (target_e_stepper) { + #if AXIS_IS_L64XX(E0) + case 0: L6470_SET_KVAL_HOLD(E0); break; + #endif + #if AXIS_IS_L64XX(E1) + case 1: L6470_SET_KVAL_HOLD(E1); break; + #endif + #if AXIS_IS_L64XX(E2) + case 2: L6470_SET_KVAL_HOLD(E2); break; + #endif + #if AXIS_IS_L64XX(E3) + case 3: L6470_SET_KVAL_HOLD(E3); break; + #endif + #if AXIS_IS_L64XX(E4) + case 4: L6470_SET_KVAL_HOLD(E4); break; + #endif + #if AXIS_IS_L64XX(E5) + case 5: L6470_SET_KVAL_HOLD(E5); break; + #endif + #if AXIS_IS_L64XX(E6) + case 6: L6470_SET_KVAL_HOLD(E6); break; + #endif + #if AXIS_IS_L64XX(E7) + case 7: L6470_SET_KVAL_HOLD(E7); break; + #endif + } + } break; + #endif } } diff --git a/Marlin/src/gcode/feature/L6470/M916-918.cpp b/Marlin/src/gcode/feature/L6470/M916-918.cpp index 8165b71e4490..3dd21ef98527 100644 --- a/Marlin/src/gcode/feature/L6470/M916-918.cpp +++ b/Marlin/src/gcode/feature/L6470/M916-918.cpp @@ -119,7 +119,7 @@ void GcodeSuite::M916() { M91x_counter_max = 256; // KVAL_HOLD is 8 bits uint8_t M91x_delay_s = parser.byteval('D'); // get delay in seconds - millis_t M91x_delay_ms = M91x_delay_s * 60 * 1000; + millis_t M91x_delay_ms = SEC_TO_MS(M91x_delay_s * 60); millis_t M91x_delay_end; DEBUG_ECHOLNPGM(".\n."); @@ -177,7 +177,7 @@ void GcodeSuite::M916() { if ((status_composite & (sh.STATUS_AXIS_TH_WRN | sh.STATUS_AXIS_TH_SD))) DEBUG_ECHOLNPGM(".\n.\nTest completed normally - Thermal warning/shutdown has occurred"); else if (status_composite) - DEBUG_ECHOLNPGM(".\n.\nTest completed abnormally - non-thermal error has occured"); + DEBUG_ECHOLNPGM(".\n.\nTest completed abnormally - non-thermal error has occurred"); else DEBUG_ECHOLNPGM(".\n.\nTest completed normally - Unable to get to thermal warning/shutdown"); @@ -308,8 +308,8 @@ void GcodeSuite::M917() { L64xxManager.set_param(axis_index[j], L6470_KVAL_HOLD, kval_hold); } DEBUG_ECHOLNPGM("."); - gcode.reset_stepper_timeout(); // reset_stepper_timeout to keep steppers powered - watchdog_refresh();; // beat the dog + gcode.reset_stepper_timeout(); // keep steppers powered + watchdog_refresh(); safe_delay(5000); status_composite_temp = 0; for (j = 0; j < driver_count; j++) { diff --git a/Marlin/src/gcode/feature/advance/M900.cpp b/Marlin/src/gcode/feature/advance/M900.cpp index 5c7155d7c9b5..1d76ebf7d531 100644 --- a/Marlin/src/gcode/feature/advance/M900.cpp +++ b/Marlin/src/gcode/feature/advance/M900.cpp @@ -43,7 +43,7 @@ void GcodeSuite::M900() { auto echo_value_oor = [](const char ltr, const bool ten=true) { - SERIAL_CHAR('?'); SERIAL_CHAR(ltr); + SERIAL_CHAR('?', ltr); SERIAL_ECHOPGM(" value out of range"); if (ten) SERIAL_ECHOPGM(" (0-10)"); SERIAL_ECHOLNPGM("."); @@ -115,12 +115,12 @@ void GcodeSuite::M900() { #if ENABLED(EXTRA_LIN_ADVANCE_K) #if EXTRUDERS < 2 - SERIAL_ECHOLNPAIR("Advance S", int(new_slot), " K", kref, "(S", int(!new_slot), " K", lref, ")"); + SERIAL_ECHOLNPAIR("Advance S", new_slot, " K", kref, "(S", !new_slot, " K", lref, ")"); #else LOOP_L_N(i, EXTRUDERS) { const bool slot = TEST(lin_adv_slot, i); - SERIAL_ECHOLNPAIR("Advance T", int(i), " S", int(slot), " K", planner.extruder_advance_K[i], - "(S", int(!slot), " K", other_extruder_advance_K[i], ")"); + SERIAL_ECHOLNPAIR("Advance T", i, " S", slot, " K", planner.extruder_advance_K[i], + "(S", !slot, " K", other_extruder_advance_K[i], ")"); SERIAL_EOL(); } #endif diff --git a/Marlin/src/gcode/feature/camera/M240.cpp b/Marlin/src/gcode/feature/camera/M240.cpp index fc350d8a558c..f5c910a9e943 100644 --- a/Marlin/src/gcode/feature/camera/M240.cpp +++ b/Marlin/src/gcode/feature/camera/M240.cpp @@ -47,7 +47,7 @@ #endif #ifdef PHOTO_RETRACT_MM - inline void e_move_m240(const float length, const feedRate_t &fr_mm_s) { + inline void e_move_m240(const float length, const_feedRate_t fr_mm_s) { if (length && thermalManager.hotEnoughToExtrude(active_extruder)) unscaled_e_move(length, fr_mm_s); } diff --git a/Marlin/src/gcode/feature/caselight/M355.cpp b/Marlin/src/gcode/feature/caselight/M355.cpp index bb6b57f666e3..b3b863f02e1f 100644 --- a/Marlin/src/gcode/feature/caselight/M355.cpp +++ b/Marlin/src/gcode/feature/caselight/M355.cpp @@ -41,10 +41,12 @@ */ void GcodeSuite::M355() { bool didset = false; - if (parser.seenval('P')) { - didset = true; - caselight.brightness = parser.value_byte(); - } + #if CASELIGHT_USES_BRIGHTNESS + if (parser.seenval('P')) { + didset = true; + caselight.brightness = parser.value_byte(); + } + #endif const bool sflag = parser.seenval('S'); if (sflag) { didset = true; @@ -58,8 +60,13 @@ void GcodeSuite::M355() { if (!caselight.on) SERIAL_ECHOLNPGM(STR_OFF); else { - if (!PWM_PIN(CASE_LIGHT_PIN)) SERIAL_ECHOLNPGM(STR_ON); - else SERIAL_ECHOLN(int(caselight.brightness)); + #if CASELIGHT_USES_BRIGHTNESS + if (TERN(CASE_LIGHT_USE_NEOPIXEL, true, TERN0(NEED_CASE_LIGHT_PIN, PWM_PIN(CASE_LIGHT_PIN)))) { + SERIAL_ECHOLN(int(caselight.brightness)); + return; + } + #endif + SERIAL_ECHOLNPGM(STR_ON); } } diff --git a/Marlin/src/gcode/feature/clean/G12.cpp b/Marlin/src/gcode/feature/clean/G12.cpp index 216db5bae374..b19932eb983d 100644 --- a/Marlin/src/gcode/feature/clean/G12.cpp +++ b/Marlin/src/gcode/feature/clean/G12.cpp @@ -42,6 +42,7 @@ * P0 S : Stroke cleaning with S strokes * P1 Sn T : Zigzag cleaning with S repeats and T zigzags * P2 Sn R : Circle cleaning with S repeats and R radius + * X, Y, Z : Specify axes to move during cleaning. Default: ALL. */ void GcodeSuite::G12() { // Don't allow nozzle cleaning without homing first diff --git a/Marlin/src/gcode/feature/controllerfan/M710.cpp b/Marlin/src/gcode/feature/controllerfan/M710.cpp index 67d4ad8abf54..aa382a3ea9eb 100644 --- a/Marlin/src/gcode/feature/controllerfan/M710.cpp +++ b/Marlin/src/gcode/feature/controllerfan/M710.cpp @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * Copyright (C) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. - * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm + * 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 @@ -27,7 +27,7 @@ #include "../../gcode.h" #include "../../../feature/controllerfan.h" -void M710_report(const bool forReplay) { +void M710_report(const bool forReplay=true) { if (!forReplay) { SERIAL_ECHOLNPGM("; Controller Fan"); SERIAL_ECHO_START(); } SERIAL_ECHOLNPAIR(" M710" " S", int(controllerFan.settings.active_speed), @@ -75,7 +75,7 @@ void GcodeSuite::M710() { if (seenD) controllerFan.settings.duration = parser.value_ushort(); if (!(seenR || seenS || seenI || seenA || seenD)) - M710_report(false); + M710_report(); } #endif // CONTROLLER_FAN_EDITABLE diff --git a/Marlin/src/gcode/feature/digipot/M907-M910.cpp b/Marlin/src/gcode/feature/digipot/M907-M910.cpp index e46366620798..bd741f8a64b4 100644 --- a/Marlin/src/gcode/feature/digipot/M907-M910.cpp +++ b/Marlin/src/gcode/feature/digipot/M907-M910.cpp @@ -34,7 +34,7 @@ #include "../../../feature/digipot/digipot.h" #endif -#if ENABLED(HAS_MOTOR_CURRENT_DAC) +#if HAS_MOTOR_CURRENT_DAC #include "../../../feature/dac/stepper_dac.h" #endif @@ -44,7 +44,7 @@ void GcodeSuite::M907() { #if HAS_MOTOR_CURRENT_SPI - LOOP_XYZE(i) if (parser.seenval(axis_codes[i])) stepper.set_digipot_current(i, parser.value_int()); + LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) stepper.set_digipot_current(i, parser.value_int()); if (parser.seenval('B')) stepper.set_digipot_current(4, parser.value_int()); if (parser.seenval('S')) LOOP_LE_N(i, 4) stepper.set_digipot_current(i, parser.value_int()); @@ -64,19 +64,21 @@ void GcodeSuite::M907() { #if HAS_MOTOR_CURRENT_I2C // this one uses actual amps in floating point - LOOP_XYZE(i) if (parser.seenval(axis_codes[i])) digipot_i2c.set_current(i, parser.value_float()); + LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) digipot_i2c.set_current(i, parser.value_float()); // Additional extruders use B,C,D for channels 4,5,6. // TODO: Change these parameters because 'E' is used. B? - for (uint8_t i = E_AXIS + 1; i < DIGIPOT_I2C_NUM_CHANNELS; i++) - if (parser.seenval('B' + i - (E_AXIS + 1))) digipot_i2c.set_current(i, parser.value_float()); + #if HAS_EXTRUDERS + for (uint8_t i = E_AXIS + 1; i < DIGIPOT_I2C_NUM_CHANNELS; i++) + if (parser.seenval('B' + i - (E_AXIS + 1))) digipot_i2c.set_current(i, parser.value_float()); + #endif #endif - #if ENABLED(HAS_MOTOR_CURRENT_DAC) + #if HAS_MOTOR_CURRENT_DAC if (parser.seenval('S')) { const float dac_percent = parser.value_float(); LOOP_LE_N(i, 4) stepper_dac.set_current_percent(i, dac_percent); } - LOOP_XYZE(i) if (parser.seenval(axis_codes[i])) stepper_dac.set_current_percent(i, parser.value_float()); + LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) stepper_dac.set_current_percent(i, parser.value_float()); #endif } @@ -90,7 +92,7 @@ void GcodeSuite::M907() { TERN_(HAS_MOTOR_CURRENT_DAC, stepper_dac.set_current_value(parser.byteval('P', -1), parser.ushortval('S', 0))); } - #if ENABLED(HAS_MOTOR_CURRENT_DAC) + #if HAS_MOTOR_CURRENT_DAC void GcodeSuite::M909() { stepper_dac.print_values(); } void GcodeSuite::M910() { stepper_dac.commit_eeprom(); } diff --git a/Marlin/src/gcode/feature/filwidth/M404-M407.cpp b/Marlin/src/gcode/feature/filwidth/M404-M407.cpp index 516289fe2779..a70f7a61fec7 100644 --- a/Marlin/src/gcode/feature/filwidth/M404-M407.cpp +++ b/Marlin/src/gcode/feature/filwidth/M404-M407.cpp @@ -26,7 +26,6 @@ #include "../../../feature/filwidth.h" #include "../../../module/planner.h" -#include "../../../module/temperature.h" #include "../../../MarlinCore.h" #include "../../gcode.h" diff --git a/Marlin/src/gcode/feature/fwretract/M207-M209.cpp b/Marlin/src/gcode/feature/fwretract/M207-M209.cpp index 538f16cde60b..5793d73f948c 100644 --- a/Marlin/src/gcode/feature/fwretract/M207-M209.cpp +++ b/Marlin/src/gcode/feature/fwretract/M207-M209.cpp @@ -29,46 +29,24 @@ /** * M207: Set firmware retraction values - * - * S[+units] retract_length - * W[+units] swap_retract_length (multi-extruder) - * F[units/min] retract_feedrate_mm_s - * Z[units] retract_zraise */ -void GcodeSuite::M207() { - if (parser.seen('S')) fwretract.settings.retract_length = parser.value_axis_units(E_AXIS); - if (parser.seen('F')) fwretract.settings.retract_feedrate_mm_s = MMM_TO_MMS(parser.value_axis_units(E_AXIS)); - if (parser.seen('Z')) fwretract.settings.retract_zraise = parser.value_linear_units(); - if (parser.seen('W')) fwretract.settings.swap_retract_length = parser.value_axis_units(E_AXIS); -} +void GcodeSuite::M207() { fwretract.M207(); } /** * M208: Set firmware un-retraction values - * - * S[+units] retract_recover_extra (in addition to M207 S*) - * W[+units] swap_retract_recover_extra (multi-extruder) - * F[units/min] retract_recover_feedrate_mm_s - * R[units/min] swap_retract_recover_feedrate_mm_s */ -void GcodeSuite::M208() { - if (parser.seen('S')) fwretract.settings.retract_recover_extra = parser.value_axis_units(E_AXIS); - if (parser.seen('F')) fwretract.settings.retract_recover_feedrate_mm_s = MMM_TO_MMS(parser.value_axis_units(E_AXIS)); - if (parser.seen('R')) fwretract.settings.swap_retract_recover_feedrate_mm_s = MMM_TO_MMS(parser.value_axis_units(E_AXIS)); - if (parser.seen('W')) fwretract.settings.swap_retract_recover_extra = parser.value_axis_units(E_AXIS); -} +void GcodeSuite::M208() { fwretract.M208(); } #if ENABLED(FWRETRACT_AUTORETRACT) /** * M209: Enable automatic retract (M209 S1) - * For slicers that don't support G10/11, reversed extrude-only - * moves will be classified as retraction. + * + * For slicers that don't support G10/11, reversed + * extruder-only moves can be classified as retraction. */ - void GcodeSuite::M209() { - if (MIN_AUTORETRACT <= MAX_AUTORETRACT && parser.seen('S')) - fwretract.enable_autoretract(parser.value_bool()); - } + void GcodeSuite::M209() { fwretract.M209(); } -#endif // FWRETRACT_AUTORETRACT +#endif #endif // FWRETRACT diff --git a/Marlin/src/gcode/feature/i2c/M260_M261.cpp b/Marlin/src/gcode/feature/i2c/M260_M261.cpp index 526d9101e1c7..438d1527f5f7 100644 --- a/Marlin/src/gcode/feature/i2c/M260_M261.cpp +++ b/Marlin/src/gcode/feature/i2c/M260_M261.cpp @@ -26,7 +26,7 @@ #include "../../gcode.h" -#include "../../../MarlinCore.h" // for i2c +#include "../../../feature/twibus.h" /** * M260: Send data to a I2C slave device diff --git a/Marlin/src/gcode/feature/leds/M150.cpp b/Marlin/src/gcode/feature/leds/M150.cpp index cf09bf14ead7..4d271007e56e 100644 --- a/Marlin/src/gcode/feature/leds/M150.cpp +++ b/Marlin/src/gcode/feature/leds/M150.cpp @@ -52,33 +52,40 @@ * M150 I1 R ; Set NEOPIXEL index 1 to red * M150 S1 I1 R ; Set SEPARATE index 1 to red */ - void GcodeSuite::M150() { #if ENABLED(NEOPIXEL_LED) - const uint8_t index = parser.intval('I', -1); + const int8_t index = parser.intval('I', -1); #if ENABLED(NEOPIXEL2_SEPARATE) - const uint8_t unit = parser.intval('S'), - brightness = unit ? neo2.brightness() : neo.brightness(); - *(unit ? &neo2.neoindex : &neo.neoindex) = index; + int8_t brightness, unit = parser.intval('S', -1); + switch (unit) { + case -1: neo2.neoindex = index; // fall-thru + case 0: neo.neoindex = index; brightness = neo.brightness(); break; + case 1: neo2.neoindex = index; brightness = neo2.brightness(); break; + } #else const uint8_t brightness = neo.brightness(); neo.neoindex = index; #endif #endif - const LEDColor color = MakeLEDColor( + const LEDColor color = LEDColor( parser.seen('R') ? (parser.has_value() ? parser.value_byte() : 255) : 0, parser.seen('U') ? (parser.has_value() ? parser.value_byte() : 255) : 0, - parser.seen('B') ? (parser.has_value() ? parser.value_byte() : 255) : 0, - parser.seen('W') ? (parser.has_value() ? parser.value_byte() : 255) : 0, - parser.seen('P') ? (parser.has_value() ? parser.value_byte() : 255) : brightness + parser.seen('B') ? (parser.has_value() ? parser.value_byte() : 255) : 0 + OPTARG(HAS_WHITE_LED, parser.seen('W') ? (parser.has_value() ? parser.value_byte() : 255) : 0) + OPTARG(NEOPIXEL_LED, parser.seen('P') ? (parser.has_value() ? parser.value_byte() : 255) : brightness) ); #if ENABLED(NEOPIXEL2_SEPARATE) - if (unit == 1) { leds2.set_color(color); return; } + switch (unit) { + case 0: leds.set_color(color); return; + case 1: leds2.set_color(color); return; + } #endif + // If 'S' is not specified use both leds.set_color(color); + TERN_(NEOPIXEL2_SEPARATE, leds2.set_color(color)); } #endif // HAS_COLOR_LEDS diff --git a/Marlin/src/gcode/feature/leds/M7219.cpp b/Marlin/src/gcode/feature/leds/M7219.cpp index a6ee71174b54..40d3554dfe6e 100644 --- a/Marlin/src/gcode/feature/leds/M7219.cpp +++ b/Marlin/src/gcode/feature/leds/M7219.cpp @@ -82,7 +82,7 @@ void GcodeSuite::M7219() { LOOP_L_N(r, MAX7219_LINES) { SERIAL_ECHOPGM("led_line["); if (r < 10) SERIAL_CHAR(' '); - SERIAL_ECHO(int(r)); + SERIAL_ECHO(r); SERIAL_ECHOPGM("]="); for (uint8_t b = 8; b--;) SERIAL_CHAR('0' + TEST(max7219.led_line[r], b)); SERIAL_EOL(); diff --git a/Marlin/src/gcode/feature/mixing/M166.cpp b/Marlin/src/gcode/feature/mixing/M166.cpp index 9e071a47ec27..5f788344eb98 100644 --- a/Marlin/src/gcode/feature/mixing/M166.cpp +++ b/Marlin/src/gcode/feature/mixing/M166.cpp @@ -30,10 +30,10 @@ #include "../../../feature/mixing.h" inline void echo_mix() { - SERIAL_ECHOPAIR(" (", int(mixer.mix[0]), "%|", int(mixer.mix[1]), "%)"); + SERIAL_ECHOPAIR(" (", mixer.mix[0], "%|", mixer.mix[1], "%)"); } -inline void echo_zt(const int t, const float &z) { +inline void echo_zt(const int t, const_float_t z) { mixer.update_mix_from_vtool(t); SERIAL_ECHOPAIR_P(SP_Z_STR, z, SP_T_STR, t); echo_mix(); @@ -74,7 +74,7 @@ void GcodeSuite::M166() { #if ENABLED(GRADIENT_VTOOL) if (mixer.gradient.vtool_index >= 0) { - SERIAL_ECHOPAIR(" (T", int(mixer.gradient.vtool_index)); + SERIAL_ECHOPAIR(" (T", mixer.gradient.vtool_index); SERIAL_CHAR(')'); } #endif diff --git a/Marlin/src/gcode/feature/network/M552-M554.cpp b/Marlin/src/gcode/feature/network/M552-M554.cpp new file mode 100644 index 000000000000..22c718c04228 --- /dev/null +++ b/Marlin/src/gcode/feature/network/M552-M554.cpp @@ -0,0 +1,126 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_ETHERNET + +#include "../../../feature/ethernet.h" +#include "../../../core/serial.h" +#include "../../gcode.h" + +void say_ethernet() { SERIAL_ECHOPGM(" Ethernet "); } + +void ETH0_report() { + say_ethernet(); + SERIAL_ECHO_TERNARY(ethernet.hardware_enabled, "port ", "en", "dis", "abled.\n"); + if (ethernet.hardware_enabled) { + say_ethernet(); + SERIAL_ECHO_TERNARY(ethernet.have_telnet_client, "client ", "en", "dis", "abled.\n"); + } + else + SERIAL_ECHOLNPGM("Send 'M552 S1' to enable."); +} + +void MAC_report() { + uint8_t mac[6]; + if (ethernet.hardware_enabled) { + Ethernet.MACAddress(mac); + SERIAL_ECHOPGM(" MAC: "); + LOOP_L_N(i, 6) { + if (mac[i] < 16) SERIAL_CHAR('0'); + SERIAL_PRINT(mac[i], PrintBase::Hex); + if (i < 5) SERIAL_CHAR(':'); + } + } + SERIAL_EOL(); +} + +// Display current values when the link is active, +// otherwise show the stored values +void ip_report(const uint16_t cmd, PGM_P const post, const IPAddress &ipo) { + SERIAL_CHAR('M'); SERIAL_ECHO(cmd); SERIAL_CHAR(' '); + LOOP_L_N(i, 4) { + SERIAL_ECHO(ipo[i]); + if (i < 3) SERIAL_CHAR('.'); + } + SERIAL_ECHOPGM(" ; "); + SERIAL_ECHOPGM_P(post); + SERIAL_EOL(); +} +void M552_report() { + ip_report(552, PSTR("ip address"), Ethernet.linkStatus() == LinkON ? Ethernet.localIP() : ethernet.ip); +} +void M553_report() { + ip_report(553, PSTR("subnet mask"), Ethernet.linkStatus() == LinkON ? Ethernet.subnetMask() : ethernet.subnet); +} +void M554_report() { + ip_report(554, PSTR("gateway"), Ethernet.linkStatus() == LinkON ? Ethernet.gatewayIP() : ethernet.gateway); +} + +/** + * M552: Set IP address, enable/disable network interface + * + * S0 : disable networking + * S1 : enable networking + * S-1 : reset network interface + * + * Pnnn : Set IP address, 0.0.0.0 means acquire an IP address using DHCP + */ +void GcodeSuite::M552() { + const bool seenP = parser.seenval('P'); + if (seenP) ethernet.ip.fromString(parser.value_string()); + + const bool seenS = parser.seenval('S'); + if (seenS) { + switch (parser.value_int()) { + case -1: + if (ethernet.telnetClient) ethernet.telnetClient.stop(); + ethernet.init(); + break; + case 0: ethernet.hardware_enabled = false; break; + case 1: ethernet.hardware_enabled = true; break; + default: break; + } + } + const bool nopar = !seenS && !seenP; + if (nopar || seenS) ETH0_report(); + if (nopar || seenP) M552_report(); +} + +/** + * M553 Pnnn - Set netmask + */ +void GcodeSuite::M553() { + if (parser.seenval('P')) ethernet.subnet.fromString(parser.value_string()); + M553_report(); +} + +/** + * M554 Pnnn - Set Gateway + */ +void GcodeSuite::M554() { + if (parser.seenval('P')) ethernet.gateway.fromString(parser.value_string()); + M554_report(); +} + +#endif // HAS_ETHERNET diff --git a/Marlin/src/gcode/feature/password/M510-M512.cpp b/Marlin/src/gcode/feature/password/M510-M512.cpp index 79f1da065b3c..eeb9b1df2231 100644 --- a/Marlin/src/gcode/feature/password/M510-M512.cpp +++ b/Marlin/src/gcode/feature/password/M510-M512.cpp @@ -58,7 +58,7 @@ void GcodeSuite::M510() { if (password.is_set && parser.ulongval('P') != password.value) { SERIAL_ECHOLNPGM(STR_WRONG_PASSWORD); return; - } + } if (parser.seenval('S')) { password.value_entry = parser.ulongval('S'); diff --git a/Marlin/src/gcode/feature/pause/G60.cpp b/Marlin/src/gcode/feature/pause/G60.cpp index 6f695b99a942..79451235b1d9 100644 --- a/Marlin/src/gcode/feature/pause/G60.cpp +++ b/Marlin/src/gcode/feature/pause/G60.cpp @@ -47,11 +47,13 @@ void GcodeSuite::G60() { SBI(saved_slots[slot >> 3], slot & 0x07); #if ENABLED(SAVED_POSITIONS_DEBUG) + DEBUG_ECHOPAIR(STR_SAVED_POS " S", slot); const xyze_pos_t &pos = stored_position[slot]; - DEBUG_ECHOPAIR_F(STR_SAVED_POS " S", slot); - DEBUG_ECHOPAIR_F(" : X", pos.x); - DEBUG_ECHOPAIR_F_P(SP_Y_STR, pos.y); - DEBUG_ECHOLNPAIR_F_P(SP_Z_STR, pos.z); + DEBUG_ECHOLNPAIR_F_P( + LIST_N(DOUBLE(LOGICAL_AXES), SP_E_STR, pos.e, + PSTR(" : X"), pos.x, SP_Y_STR, pos.y, SP_Z_STR, pos.z, + SP_I_STR, pos.i, SP_J_STR, pos.j, SP_K_STR, pos.k) + ); #endif } diff --git a/Marlin/src/gcode/feature/pause/G61.cpp b/Marlin/src/gcode/feature/pause/G61.cpp index d8049f02bcef..a10c8217ef44 100644 --- a/Marlin/src/gcode/feature/pause/G61.cpp +++ b/Marlin/src/gcode/feature/pause/G61.cpp @@ -27,18 +27,26 @@ #include "../../../module/planner.h" #include "../../gcode.h" #include "../../../module/motion.h" +#include "../../../module/planner.h" + +#define DEBUG_OUT ENABLED(SAVED_POSITIONS_DEBUG) +#include "../../../core/debug_out.h" /** * G61: Return to saved position * * F - Feedrate (optional) for the move back. * S - Slot # (0-based) to restore from (default 0). - * X Y Z - Axes to restore. At least one is required. + * X Y Z E - Axes to restore. At least one is required. + * + * If XYZE are not given, default restore uses the smart blocking move. */ void GcodeSuite::G61(void) { const uint8_t slot = parser.byteval('S'); + #define SYNC_E(POINT) TERN_(HAS_EXTRUDERS, planner.set_e_position_mm((destination.e = current_position.e = (POINT)))) + #if SAVED_POSITIONS < 256 if (slot >= SAVED_POSITIONS) { SERIAL_ERROR_MSG(STR_INVALID_POS_SLOT STRINGIFY(SAVED_POSITIONS)); @@ -47,24 +55,41 @@ void GcodeSuite::G61(void) { #endif // No saved position? No axes being restored? - if (!TEST(saved_slots[slot >> 3], slot & 0x07) || !parser.seen("XYZ")) return; + if (!TEST(saved_slots[slot >> 3], slot & 0x07)) return; // Apply any given feedrate over 0.0 + feedRate_t saved_feedrate = feedrate_mm_s; const float fr = parser.linearval('F'); if (fr > 0.0) feedrate_mm_s = MMM_TO_MMS(fr); - SERIAL_ECHOPAIR(STR_RESTORING_POS " S", int(slot)); - LOOP_XYZ(i) { - destination[i] = parser.seen(XYZ_CHAR(i)) - ? stored_position[slot][i] + parser.value_axis_units((AxisEnum)i) - : current_position[i]; - SERIAL_CHAR(' ', XYZ_CHAR(i)); - SERIAL_ECHO_F(destination[i]); + if (!parser.seen_axis()) { + DEBUG_ECHOLNPGM("Default position restore"); + do_blocking_move_to(stored_position[slot], feedrate_mm_s); + SYNC_E(stored_position[slot].e); + } + else { + if (parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR))) { + DEBUG_ECHOPAIR(STR_RESTORING_POS " S", slot); + LOOP_LINEAR_AXES(i) { + destination[i] = parser.seen(AXIS_CHAR(i)) + ? stored_position[slot][i] + parser.value_axis_units((AxisEnum)i) + : current_position[i]; + DEBUG_CHAR(' ', AXIS_CHAR(i)); + DEBUG_ECHO_F(destination[i]); + } + DEBUG_EOL(); + // Move to the saved position + prepare_line_to_destination(); + } + #if HAS_EXTRUDERS + if (parser.seen_test('E')) { + DEBUG_ECHOLNPAIR(STR_RESTORING_POS " S", slot, " E", current_position.e, "=>", stored_position[slot].e); + SYNC_E(stored_position[slot].e); + } + #endif } - SERIAL_EOL(); - // Move to the saved position - prepare_line_to_destination(); + 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 db78e870d71a..bc31e1225d86 100644 --- a/Marlin/src/gcode/feature/pause/M125.cpp +++ b/Marlin/src/gcode/feature/pause/M125.cpp @@ -27,13 +27,10 @@ #include "../../gcode.h" #include "../../parser.h" #include "../../../feature/pause.h" +#include "../../../lcd/marlinui.h" #include "../../../module/motion.h" -#include "../../../sd/cardreader.h" #include "../../../module/printcounter.h" - -#if HAS_LCD_MENU - #include "../../../lcd/ultralcd.h" -#endif +#include "../../../sd/cardreader.h" #if ENABLED(POWER_LOSS_RECOVERY) #include "../../../feature/powerloss.h" @@ -49,14 +46,17 @@ * position and waits, resuming with a button click or M108. * Without PARK_HEAD_ON_PAUSE the M125 command does nothing. * - * L = override retract length - * X = override X - * Y = override Y - * Z = override Z raise + * L = Override retract Length + * X = Override park position X + * Y = Override park position Y + * Z = Override Z raise + * + * With an LCD menu: + * P = Always show a prompt and await a response */ void GcodeSuite::M125() { // Initial retract before move to filament change position - const float retract = -ABS(parser.seen('L') ? parser.value_axis_units(E_AXIS) : (PAUSE_PARK_RETRACT_LENGTH)); + const float retract = TERN0(HAS_EXTRUDERS, -ABS(parser.axisunitsval('L', E_AXIS, PAUSE_PARK_RETRACT_LENGTH))); xyz_pos_t park_point = NOZZLE_PARK_POINT; @@ -73,13 +73,13 @@ void GcodeSuite::M125() { const bool sd_printing = TERN0(SDSUPPORT, IS_SD_PRINTING()); - TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_PARKING, PAUSE_MODE_PAUSE_PRINT)); + ui.pause_show_message(PAUSE_MESSAGE_PARKING, PAUSE_MODE_PAUSE_PRINT); - const bool show_lcd = TERN0(HAS_LCD_MENU, parser.seenval('P')); + // If possible, show an LCD prompt with the 'P' flag + const bool show_lcd = TERN0(HAS_LCD_MENU, parser.boolval('P')); - if (pause_print(retract, park_point, 0, show_lcd)) { - TERN_(POWER_LOSS_RECOVERY, if (recovery.enabled) recovery.save(true)); - if (ENABLED(EXTENSIBLE_UI) || !sd_printing || show_lcd) { + if (pause_print(retract, park_point, show_lcd, 0)) { + if (ENABLED(EXTENSIBLE_UI) || BOTH(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/M600.cpp b/Marlin/src/gcode/feature/pause/M600.cpp index 7c9be54b2916..541fa08350e6 100644 --- a/Marlin/src/gcode/feature/pause/M600.cpp +++ b/Marlin/src/gcode/feature/pause/M600.cpp @@ -28,15 +28,12 @@ #include "../../../feature/pause.h" #include "../../../module/motion.h" #include "../../../module/printcounter.h" +#include "../../../lcd/marlinui.h" #if HAS_MULTI_EXTRUDER #include "../../../module/tool_change.h" #endif -#if HAS_LCD_MENU - #include "../../../lcd/ultralcd.h" -#endif - #if ENABLED(MMU2_MENUS) #include "../../../lcd/menu/menu_mmu2.h" #endif @@ -84,11 +81,11 @@ void GcodeSuite::M600() { #if ENABLED(DUAL_X_CARRIAGE) int8_t DXC_ext = target_extruder; - if (!parser.seen('T')) { // If no tool index is specified, M600 was (probably) sent in response to filament runout. - // In this case, for duplicating modes set DXC_ext to the extruder that ran out. - #if HAS_FILAMENT_SENSOR && NUM_RUNOUT_SENSORS > 1 - if (dxc_is_duplicating()) - DXC_ext = (READ(FIL_RUNOUT2_PIN) == FIL_RUNOUT_STATE) ? 1 : 0; + if (!parser.seen_test('T')) { // If no tool index is specified, M600 was (probably) sent in response to filament runout. + // In this case, for duplicating modes set DXC_ext to the extruder that ran out. + #if MULTI_FILAMENT_SENSOR + if (idex_is_duplicating()) + DXC_ext = (READ(FIL_RUNOUT2_PIN) == FIL_RUNOUT2_STATE) ? 1 : 0; #else DXC_ext = active_extruder; #endif @@ -96,24 +93,24 @@ void GcodeSuite::M600() { #endif // Show initial "wait for start" message - #if HAS_LCD_MENU && DISABLED(MMU2_MENUS) - lcd_pause_show_message(PAUSE_MESSAGE_CHANGING, PAUSE_MODE_PAUSE_PRINT, target_extruder); + #if DISABLED(MMU2_MENUS) + ui.pause_show_message(PAUSE_MESSAGE_CHANGING, PAUSE_MODE_PAUSE_PRINT, target_extruder); #endif #if ENABLED(HOME_BEFORE_FILAMENT_CHANGE) // If needed, home before parking for filament change - if (!all_axes_known()) home_all_axes(); + home_if_needed(true); #endif #if HAS_MULTI_EXTRUDER // Change toolhead if specified const uint8_t active_extruder_before_filament_change = active_extruder; - if (active_extruder != target_extruder && TERN1(DUAL_X_CARRIAGE, !dxc_is_duplicating())) + if (active_extruder != target_extruder && TERN1(DUAL_X_CARRIAGE, !idex_is_duplicating())) tool_change(target_extruder, false); #endif // Initial retract before move to filament change position - const float retract = -ABS(parser.seen('E') ? parser.value_axis_units(E_AXIS) : (PAUSE_PARK_RETRACT_LENGTH)); + const float retract = -ABS(parser.axisunitsval('E', E_AXIS, PAUSE_PARK_RETRACT_LENGTH)); xyz_pos_t park_point NOZZLE_PARK_POINT; @@ -135,15 +132,11 @@ void GcodeSuite::M600() { fast_load_length = 0.0f; #else // Unload filament - const float unload_length = -ABS(parser.seen('U') ? parser.value_axis_units(E_AXIS) - : fc_settings[active_extruder].unload_length); - + const float unload_length = -ABS(parser.axisunitsval('U', E_AXIS, fc_settings[active_extruder].unload_length)); // Slow load filament constexpr float slow_load_length = FILAMENT_CHANGE_SLOW_LOAD_LENGTH; - // Fast load filament - const float fast_load_length = ABS(parser.seen('L') ? parser.value_axis_units(E_AXIS) - : fc_settings[active_extruder].load_length); + const float fast_load_length = ABS(parser.axisunitsval('L', E_AXIS, fc_settings[active_extruder].load_length)); #endif const int beep_count = parser.intval('B', -1 @@ -152,7 +145,7 @@ void GcodeSuite::M600() { #endif ); - if (pause_print(retract, park_point, unload_length, true DXC_PASS)) { + if (pause_print(retract, park_point, true, unload_length DXC_PASS)) { #if ENABLED(MMU2_MENUS) mmu2_M600(); resume_print(slow_load_length, fast_load_length, 0, beep_count DXC_PASS); diff --git a/Marlin/src/gcode/feature/pause/M701_M702.cpp b/Marlin/src/gcode/feature/pause/M701_M702.cpp index c1f7223142c3..0a649dadd47a 100644 --- a/Marlin/src/gcode/feature/pause/M701_M702.cpp +++ b/Marlin/src/gcode/feature/pause/M701_M702.cpp @@ -29,17 +29,14 @@ #include "../../../module/motion.h" #include "../../../module/temperature.h" #include "../../../feature/pause.h" +#include "../../../lcd/marlinui.h" #if HAS_MULTI_EXTRUDER #include "../../../module/tool_change.h" #endif -#if HAS_LCD_MENU - #include "../../../lcd/ultralcd.h" -#endif - -#if ENABLED(PRUSA_MMU2) - #include "../../../feature/mmu2/mmu2.h" +#if HAS_PRUSA_MMU2 + #include "../../../feature/mmu/mmu2.h" #endif #if ENABLED(MIXING_EXTRUDER) @@ -59,10 +56,8 @@ void GcodeSuite::M701() { xyz_pos_t park_point = NOZZLE_PARK_POINT; - #if ENABLED(NO_MOTION_BEFORE_HOMING) - // Don't raise Z if the machine isn't homed - if (axes_should_home()) park_point.z = 0; - #endif + // Don't raise Z if the machine isn't homed + if (TERN0(NO_MOTION_BEFORE_HOMING, axes_should_home())) park_point.z = 0; #if ENABLED(MIXING_EXTRUDER) const int8_t target_e_stepper = get_target_e_stepper_from_command(); @@ -84,21 +79,29 @@ void GcodeSuite::M701() { if (parser.seenval('Z')) park_point.z = parser.linearval('Z'); // Show initial "wait for load" message - TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_LOAD, PAUSE_MODE_LOAD_FILAMENT, target_extruder)); + ui.pause_show_message(PAUSE_MESSAGE_LOAD, PAUSE_MODE_LOAD_FILAMENT, target_extruder); - #if HAS_MULTI_EXTRUDER && DISABLED(PRUSA_MMU2) + #if HAS_MULTI_EXTRUDER && (HAS_PRUSA_MMU1 || !HAS_MMU) // Change toolhead if specified uint8_t active_extruder_before_filament_change = active_extruder; if (active_extruder != target_extruder) tool_change(target_extruder, false); #endif - // Lift Z axis - if (park_point.z > 0) - do_blocking_move_to_z(_MIN(current_position.z + park_point.z, Z_MAX_POS), feedRate_t(NOZZLE_PARK_Z_FEEDRATE)); + auto move_z_by = [](const_float_t zdist) { + if (zdist) { + destination = current_position; + destination.z += zdist; + prepare_internal_move_to_destination(NOZZLE_PARK_Z_FEEDRATE); + } + }; + + // Raise the Z axis (with max limit) + const float park_raise = _MIN(park_point.z, (Z_MAX_POS) - current_position.z); + move_z_by(park_raise); // Load filament - #if ENABLED(PRUSA_MMU2) + #if HAS_PRUSA_MMU2 mmu2.load_filament_to_nozzle(target_extruder); #else constexpr float purge_length = ADVANCED_PAUSE_PURGE_LENGTH, @@ -118,10 +121,9 @@ void GcodeSuite::M701() { #endif // Restore Z axis - if (park_point.z > 0) - do_blocking_move_to_z(_MAX(current_position.z - park_point.z, 0), feedRate_t(NOZZLE_PARK_Z_FEEDRATE)); + move_z_by(-park_raise); - #if HAS_MULTI_EXTRUDER && DISABLED(PRUSA_MMU2) + #if HAS_MULTI_EXTRUDER && (HAS_PRUSA_MMU1 || !HAS_MMU) // Restore toolhead if it was changed if (active_extruder_before_filament_change != active_extruder) tool_change(active_extruder_before_filament_change, false); @@ -130,7 +132,7 @@ void GcodeSuite::M701() { TERN_(MIXING_EXTRUDER, mixer.T(old_mixing_tool)); // Restore original mixing tool // Show status screen - TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_STATUS)); + ui.pause_show_message(PAUSE_MESSAGE_STATUS); } /** @@ -147,10 +149,8 @@ void GcodeSuite::M701() { void GcodeSuite::M702() { xyz_pos_t park_point = NOZZLE_PARK_POINT; - #if ENABLED(NO_MOTION_BEFORE_HOMING) - // Don't raise Z if the machine isn't homed - if (axes_should_home()) park_point.z = 0; - #endif + // Don't raise Z if the machine isn't homed + if (TERN0(NO_MOTION_BEFORE_HOMING, axes_should_home())) park_point.z = 0; #if ENABLED(MIXING_EXTRUDER) const uint8_t old_mixing_tool = mixer.get_current_vtool(); @@ -184,9 +184,9 @@ void GcodeSuite::M702() { if (parser.seenval('Z')) park_point.z = parser.linearval('Z'); // Show initial "wait for unload" message - TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_UNLOAD, PAUSE_MODE_UNLOAD_FILAMENT, target_extruder)); + ui.pause_show_message(PAUSE_MESSAGE_UNLOAD, PAUSE_MODE_UNLOAD_FILAMENT, target_extruder); - #if HAS_MULTI_EXTRUDER && DISABLED(PRUSA_MMU2) + #if HAS_MULTI_EXTRUDER && (HAS_PRUSA_MMU1 || !HAS_MMU) // Change toolhead if specified uint8_t active_extruder_before_filament_change = active_extruder; if (active_extruder != target_extruder) @@ -198,7 +198,7 @@ void GcodeSuite::M702() { do_blocking_move_to_z(_MIN(current_position.z + park_point.z, Z_MAX_POS), feedRate_t(NOZZLE_PARK_Z_FEEDRATE)); // Unload filament - #if ENABLED(PRUSA_MMU2) + #if HAS_PRUSA_MMU2 mmu2.unload(); #else #if BOTH(HAS_MULTI_EXTRUDER, FILAMENT_UNLOAD_ALL_EXTRUDERS) @@ -227,7 +227,7 @@ void GcodeSuite::M702() { if (park_point.z > 0) do_blocking_move_to_z(_MAX(current_position.z - park_point.z, 0), feedRate_t(NOZZLE_PARK_Z_FEEDRATE)); - #if HAS_MULTI_EXTRUDER && DISABLED(PRUSA_MMU2) + #if HAS_MULTI_EXTRUDER && (HAS_PRUSA_MMU1 || !HAS_MMU) // Restore toolhead if it was changed if (active_extruder_before_filament_change != active_extruder) tool_change(active_extruder_before_filament_change, false); @@ -236,7 +236,7 @@ void GcodeSuite::M702() { TERN_(MIXING_EXTRUDER, mixer.T(old_mixing_tool)); // Restore original mixing tool // Show status screen - TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_STATUS)); + ui.pause_show_message(PAUSE_MESSAGE_STATUS); } #endif // ADVANCED_PAUSE_FEATURE diff --git a/Marlin/src/gcode/feature/power_monitor/M430.cpp b/Marlin/src/gcode/feature/power_monitor/M430.cpp index 7639ea962d9b..34430fbc388e 100644 --- a/Marlin/src/gcode/feature/power_monitor/M430.cpp +++ b/Marlin/src/gcode/feature/power_monitor/M430.cpp @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * Copyright (C) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. - * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm + * 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 @@ -42,7 +42,7 @@ void GcodeSuite::M430() { #if ENABLED(POWER_MONITOR_CURRENT) if (parser.seen('I')) { power_monitor.set_current_display(parser.value_bool()); do_report = false; } #endif - #if HAS_POWER_MONITOR_VREF + #if ENABLED(POWER_MONITOR_VOLTAGE) if (parser.seen('V')) { power_monitor.set_voltage_display(parser.value_bool()); do_report = false; } #endif #if HAS_POWER_MONITOR_WATTS @@ -53,11 +53,11 @@ void GcodeSuite::M430() { SERIAL_ECHOLNPAIR( #if ENABLED(POWER_MONITOR_CURRENT) "Current: ", power_monitor.getAmps(), "A" - #if HAS_POWER_MONITOR_VREF + #if ENABLED(POWER_MONITOR_VOLTAGE) " " #endif #endif - #if HAS_POWER_MONITOR_VREF + #if ENABLED(POWER_MONITOR_VOLTAGE) "Voltage: ", power_monitor.getVolts(), "V" #endif #if HAS_POWER_MONITOR_WATTS diff --git a/Marlin/src/gcode/feature/powerloss/M1000.cpp b/Marlin/src/gcode/feature/powerloss/M1000.cpp index e9477dd2fbf3..ea92dc66b307 100644 --- a/Marlin/src/gcode/feature/powerloss/M1000.cpp +++ b/Marlin/src/gcode/feature/powerloss/M1000.cpp @@ -27,7 +27,7 @@ #include "../../gcode.h" #include "../../../feature/powerloss.h" #include "../../../module/motion.h" -#include "../../../lcd/ultralcd.h" +#include "../../../lcd/marlinui.h" #if ENABLED(EXTENSIBLE_UI) #include "../../../lcd/extui/ui_api.h" #endif @@ -40,7 +40,7 @@ void menu_job_recovery(); inline void plr_error(PGM_P const prefix) { #if ENABLED(DEBUG_POWER_LOSS_RECOVERY) DEBUG_ECHO_START(); - serialprintPGM(prefix); + DEBUG_ECHOPGM_P(prefix); DEBUG_ECHOLNPGM(" Job Recovery Data"); #else UNUSED(prefix); @@ -59,7 +59,7 @@ inline void plr_error(PGM_P const prefix) { void GcodeSuite::M1000() { if (recovery.valid()) { - if (parser.seen('S')) { + if (parser.seen_test('S')) { #if HAS_LCD_MENU ui.goto_screen(menu_job_recovery); #elif ENABLED(DWIN_CREALITY_LCD) @@ -70,7 +70,7 @@ void GcodeSuite::M1000() { SERIAL_ECHO_MSG("Resume requires LCD."); #endif } - else if (parser.seen('C')) { + else if (parser.seen_test('C')) { #if HAS_LCD_MENU lcd_power_loss_recovery_cancel(); #else diff --git a/Marlin/src/gcode/feature/powerloss/M413.cpp b/Marlin/src/gcode/feature/powerloss/M413.cpp index 3538ccaa6e07..18aeb507b1cf 100644 --- a/Marlin/src/gcode/feature/powerloss/M413.cpp +++ b/Marlin/src/gcode/feature/powerloss/M413.cpp @@ -27,7 +27,7 @@ #include "../../gcode.h" #include "../../../feature/powerloss.h" #include "../../../module/motion.h" -#include "../../../lcd/ultralcd.h" +#include "../../../lcd/marlinui.h" /** * M413: Enable / Disable power-loss recovery @@ -48,14 +48,14 @@ void GcodeSuite::M413() { #if ENABLED(DEBUG_POWER_LOSS_RECOVERY) if (parser.seen("RL")) recovery.load(); - if (parser.seen('W')) recovery.save(true); - if (parser.seen('P')) recovery.purge(); - if (parser.seen('D')) recovery.debug(PSTR("M413")); + if (parser.seen_test('W')) recovery.save(true); + if (parser.seen_test('P')) recovery.purge(); + if (parser.seen_test('D')) recovery.debug(PSTR("M413")); #if PIN_EXISTS(POWER_LOSS) - if (parser.seen('O')) recovery._outage(); + if (parser.seen_test('O')) recovery._outage(); #endif - if (parser.seen('E')) serialprintPGM(recovery.exists() ? PSTR("PLR Exists\n") : PSTR("No PLR\n")); - if (parser.seen('V')) serialprintPGM(recovery.valid() ? PSTR("Valid\n") : PSTR("Invalid\n")); + if (parser.seen_test('E')) SERIAL_ECHOPGM_P(recovery.exists() ? PSTR("PLR Exists\n") : PSTR("No PLR\n")); + if (parser.seen_test('V')) SERIAL_ECHOPGM_P(recovery.valid() ? PSTR("Valid\n") : PSTR("Invalid\n")); #endif } diff --git a/Marlin/src/gcode/feature/prusa_MMU2/M403.cpp b/Marlin/src/gcode/feature/prusa_MMU2/M403.cpp index 91e35dbf657c..bca2013e88ba 100644 --- a/Marlin/src/gcode/feature/prusa_MMU2/M403.cpp +++ b/Marlin/src/gcode/feature/prusa_MMU2/M403.cpp @@ -22,10 +22,10 @@ #include "../../../inc/MarlinConfigPre.h" -#if ENABLED(PRUSA_MMU2) +#if HAS_PRUSA_MMU2 #include "../../gcode.h" -#include "../../../feature/mmu2/mmu2.h" +#include "../../../feature/mmu/mmu2.h" /** * M403: Set filament type for MMU2 @@ -40,10 +40,10 @@ void GcodeSuite::M403() { int8_t index = parser.intval('E', -1), type = parser.intval('F', -1); - if (WITHIN(index, 0, 4) && WITHIN(type, 0, 2)) + if (WITHIN(index, 0, EXTRUDERS - 1) && WITHIN(type, 0, 2)) mmu2.set_filament_type(index, type); else SERIAL_ECHO_MSG("M403 - bad arguments."); } -#endif // PRUSA_MMU2 +#endif // HAS_PRUSA_MMU2 diff --git a/Marlin/src/gcode/feature/runout/M412.cpp b/Marlin/src/gcode/feature/runout/M412.cpp index 130f9c83e3ac..9a063571326f 100644 --- a/Marlin/src/gcode/feature/runout/M412.cpp +++ b/Marlin/src/gcode/feature/runout/M412.cpp @@ -44,7 +44,7 @@ void GcodeSuite::M412() { #if ENABLED(HOST_ACTION_COMMANDS) if (parser.seen('H')) runout.host_handling = parser.value_bool(); #endif - const bool seenR = parser.seen('R'), seenS = parser.seen('S'); + const bool seenR = parser.seen_test('R'), seenS = parser.seen('S'); if (seenR || seenS) runout.reset(); if (seenS) runout.enabled = parser.value_bool(); #if HAS_FILAMENT_RUNOUT_DISTANCE @@ -54,10 +54,15 @@ void GcodeSuite::M412() { else { SERIAL_ECHO_START(); SERIAL_ECHOPGM("Filament runout "); - serialprintln_onoff(runout.enabled); + serialprint_onoff(runout.enabled); #if HAS_FILAMENT_RUNOUT_DISTANCE - SERIAL_ECHOLNPAIR("Filament runout distance (mm): ", runout.runout_distance()); + SERIAL_ECHOPAIR(" ; Distance ", runout.runout_distance(), "mm"); #endif + #if ENABLED(HOST_ACTION_COMMANDS) + SERIAL_ECHOPGM(" ; Host handling "); + serialprint_onoff(runout.host_handling); + #endif + SERIAL_EOL(); } } diff --git a/Marlin/src/gcode/feature/trinamic/M122.cpp b/Marlin/src/gcode/feature/trinamic/M122.cpp index 46e4365f38c2..fdab54877433 100644 --- a/Marlin/src/gcode/feature/trinamic/M122.cpp +++ b/Marlin/src/gcode/feature/trinamic/M122.cpp @@ -32,29 +32,33 @@ * M122: Debug TMC drivers */ void GcodeSuite::M122() { - xyze_bool_t print_axis = { false, false, false, false }; + xyze_bool_t print_axis = ARRAY_N_1(LOGICAL_AXES, false); + bool print_all = true; - LOOP_XYZE(i) if (parser.seen(axis_codes[i])) { print_axis[i] = true; print_all = false; } + LOOP_LOGICAL_AXES(i) if (parser.seen_test(axis_codes[i])) { print_axis[i] = true; print_all = false; } - if (print_all) LOOP_XYZE(i) print_axis[i] = true; + if (print_all) LOOP_LOGICAL_AXES(i) print_axis[i] = true; if (parser.boolval('I')) restore_stepper_drivers(); #if ENABLED(TMC_DEBUG) #if ENABLED(MONITOR_DRIVER_STATUS) - uint16_t interval = MONITOR_DRIVER_STATUS_INTERVAL_MS; - if (parser.seen('S') && !parser.value_bool()) interval = 0; - if (parser.seenval('P')) NOMORE(interval, parser.value_ushort()); - tmc_set_report_interval(interval); + const bool sflag = parser.seen_test('S'), sval = sflag && parser.value_bool(); + if (sflag && !sval) + tmc_set_report_interval(0); + else if (parser.seenval('P')) + tmc_set_report_interval(_MAX(250, parser.value_ushort())); + else if (sval) + tmc_set_report_interval(MONITOR_DRIVER_STATUS_INTERVAL_MS); #endif - if (parser.seen('V')) - tmc_get_registers(print_axis.x, print_axis.y, print_axis.z, print_axis.e); + if (parser.seen_test('V')) + tmc_get_registers(LOGICAL_AXIS_ELEM(print_axis)); else - tmc_report_all(print_axis.x, print_axis.y, print_axis.z, print_axis.e); + tmc_report_all(LOGICAL_AXIS_ELEM(print_axis)); #endif - test_tmc_connection(print_axis.x, print_axis.y, print_axis.z, print_axis.e); + test_tmc_connection(LOGICAL_AXIS_ELEM(print_axis)); } #endif // HAS_TRINAMIC_CONFIG diff --git a/Marlin/src/gcode/feature/trinamic/M569.cpp b/Marlin/src/gcode/feature/trinamic/M569.cpp index e72d03e76728..9a7f1fbce902 100644 --- a/Marlin/src/gcode/feature/trinamic/M569.cpp +++ b/Marlin/src/gcode/feature/trinamic/M569.cpp @@ -32,8 +32,7 @@ template void tmc_say_stealth_status(TMC &st) { st.printLabel(); SERIAL_ECHOPGM(" driver mode:\t"); - serialprintPGM(st.get_stealthChop_status() ? PSTR("stealthChop") : PSTR("spreadCycle")); - SERIAL_EOL(); + SERIAL_ECHOLNPGM_P(st.get_stealthChop() ? PSTR("stealthChop") : PSTR("spreadCycle")); } template void tmc_set_stealthChop(TMC &st, const bool enable) { @@ -41,132 +40,88 @@ void tmc_set_stealthChop(TMC &st, const bool enable) { st.refresh_stepping_mode(); } -static void set_stealth_status(const bool enable, const int8_t target_extruder) { +static void set_stealth_status(const bool enable, const int8_t target_e_stepper) { #define TMC_SET_STEALTH(Q) tmc_set_stealthChop(stepper##Q, enable) - #if AXIS_HAS_STEALTHCHOP(X) || AXIS_HAS_STEALTHCHOP(X2) \ - || AXIS_HAS_STEALTHCHOP(Y) || AXIS_HAS_STEALTHCHOP(Y2) \ - || AXIS_HAS_STEALTHCHOP(Z) || AXIS_HAS_STEALTHCHOP(Z2) \ - || AXIS_HAS_STEALTHCHOP(Z3) || AXIS_HAS_STEALTHCHOP(Z4) + #if X_HAS_STEALTHCHOP || Y_HAS_STEALTHCHOP || Z_HAS_STEALTHCHOP \ + || I_HAS_STEALTHCHOP || J_HAS_STEALTHCHOP || K_HAS_STEALTHCHOP \ + || X2_HAS_STEALTHCHOP || Y2_HAS_STEALTHCHOP || Z2_HAS_STEALTHCHOP || Z3_HAS_STEALTHCHOP || Z4_HAS_STEALTHCHOP const uint8_t index = parser.byteval('I'); #endif - LOOP_XYZE(i) if (parser.seen(axis_codes[i])) { + LOOP_LOGICAL_AXES(i) if (parser.seen(axis_codes[i])) { switch (i) { case X_AXIS: - #if AXIS_HAS_STEALTHCHOP(X) - if (index == 0) TMC_SET_STEALTH(X); - #endif - #if AXIS_HAS_STEALTHCHOP(X2) - if (index == 1) TMC_SET_STEALTH(X2); - #endif + TERN_(X_HAS_STEALTHCHOP, if (index == 0) TMC_SET_STEALTH(X)); + TERN_(X2_HAS_STEALTHCHOP, if (index == 1) TMC_SET_STEALTH(X2)); break; - case Y_AXIS: - #if AXIS_HAS_STEALTHCHOP(Y) - if (index == 0) TMC_SET_STEALTH(Y); - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - if (index == 1) TMC_SET_STEALTH(Y2); - #endif - break; - case Z_AXIS: - #if AXIS_HAS_STEALTHCHOP(Z) - if (index == 0) TMC_SET_STEALTH(Z); - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - if (index == 1) TMC_SET_STEALTH(Z2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z3) - if (index == 2) TMC_SET_STEALTH(Z3); - #endif - #if AXIS_HAS_STEALTHCHOP(Z4) - if (index == 3) TMC_SET_STEALTH(Z4); - #endif - break; - case E_AXIS: { - if (target_extruder < 0) return; - switch (target_extruder) { - #if AXIS_HAS_STEALTHCHOP(E0) - case 0: TMC_SET_STEALTH(E0); break; - #endif - #if AXIS_HAS_STEALTHCHOP(E1) - case 1: TMC_SET_STEALTH(E1); break; - #endif - #if AXIS_HAS_STEALTHCHOP(E2) - case 2: TMC_SET_STEALTH(E2); break; - #endif - #if AXIS_HAS_STEALTHCHOP(E3) - case 3: TMC_SET_STEALTH(E3); break; - #endif - #if AXIS_HAS_STEALTHCHOP(E4) - case 4: TMC_SET_STEALTH(E4); break; - #endif - #if AXIS_HAS_STEALTHCHOP(E5) - case 5: TMC_SET_STEALTH(E5); break; - #endif - #if AXIS_HAS_STEALTHCHOP(E6) - case 6: TMC_SET_STEALTH(E6); break; - #endif - #if AXIS_HAS_STEALTHCHOP(E7) - case 7: TMC_SET_STEALTH(E7); break; - #endif - } - } break; + + #if HAS_Y_AXIS + case Y_AXIS: + TERN_(Y_HAS_STEALTHCHOP, if (index == 0) TMC_SET_STEALTH(Y)); + TERN_(Y2_HAS_STEALTHCHOP, if (index == 1) TMC_SET_STEALTH(Y2)); + break; + #endif + + #if HAS_Z_AXIS + case Z_AXIS: + TERN_(Z_HAS_STEALTHCHOP, if (index == 0) TMC_SET_STEALTH(Z)); + TERN_(Z2_HAS_STEALTHCHOP, if (index == 1) TMC_SET_STEALTH(Z2)); + TERN_(Z3_HAS_STEALTHCHOP, if (index == 2) TMC_SET_STEALTH(Z3)); + TERN_(Z4_HAS_STEALTHCHOP, if (index == 3) TMC_SET_STEALTH(Z4)); + break; + #endif + + #if I_HAS_STEALTHCHOP + case I_AXIS: TMC_SET_STEALTH(I); break; + #endif + #if J_HAS_STEALTHCHOP + case J_AXIS: TMC_SET_STEALTH(J); break; + #endif + #if K_HAS_STEALTHCHOP + case K_AXIS: TMC_SET_STEALTH(K); break; + #endif + + #if E_STEPPERS + case E_AXIS: { + if (target_e_stepper < 0) return; + switch (target_e_stepper) { + TERN_(E0_HAS_STEALTHCHOP, case 0: TMC_SET_STEALTH(E0); break;) + TERN_(E1_HAS_STEALTHCHOP, case 1: TMC_SET_STEALTH(E1); break;) + TERN_(E2_HAS_STEALTHCHOP, case 2: TMC_SET_STEALTH(E2); break;) + TERN_(E3_HAS_STEALTHCHOP, case 3: TMC_SET_STEALTH(E3); break;) + TERN_(E4_HAS_STEALTHCHOP, case 4: TMC_SET_STEALTH(E4); break;) + TERN_(E5_HAS_STEALTHCHOP, case 5: TMC_SET_STEALTH(E5); break;) + TERN_(E6_HAS_STEALTHCHOP, case 6: TMC_SET_STEALTH(E6); break;) + TERN_(E7_HAS_STEALTHCHOP, case 7: TMC_SET_STEALTH(E7); break;) + } + } break; + #endif } } } static void say_stealth_status() { #define TMC_SAY_STEALTH_STATUS(Q) tmc_say_stealth_status(stepper##Q) - - #if AXIS_HAS_STEALTHCHOP(X) - TMC_SAY_STEALTH_STATUS(X); - #endif - #if AXIS_HAS_STEALTHCHOP(X2) - TMC_SAY_STEALTH_STATUS(X2); - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - TMC_SAY_STEALTH_STATUS(Y); - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - TMC_SAY_STEALTH_STATUS(Y2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - TMC_SAY_STEALTH_STATUS(Z); - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - TMC_SAY_STEALTH_STATUS(Z2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z3) - TMC_SAY_STEALTH_STATUS(Z3); - #endif - #if AXIS_HAS_STEALTHCHOP(Z4) - TMC_SAY_STEALTH_STATUS(Z4); - #endif - #if AXIS_HAS_STEALTHCHOP(E0) - TMC_SAY_STEALTH_STATUS(E0); - #endif - #if AXIS_HAS_STEALTHCHOP(E1) - TMC_SAY_STEALTH_STATUS(E1); - #endif - #if AXIS_HAS_STEALTHCHOP(E2) - TMC_SAY_STEALTH_STATUS(E2); - #endif - #if AXIS_HAS_STEALTHCHOP(E3) - TMC_SAY_STEALTH_STATUS(E3); - #endif - #if AXIS_HAS_STEALTHCHOP(E4) - TMC_SAY_STEALTH_STATUS(E4); - #endif - #if AXIS_HAS_STEALTHCHOP(E5) - TMC_SAY_STEALTH_STATUS(E5); - #endif - #if AXIS_HAS_STEALTHCHOP(E6) - TMC_SAY_STEALTH_STATUS(E6); - #endif - #if AXIS_HAS_STEALTHCHOP(E7) - TMC_SAY_STEALTH_STATUS(E7); - #endif + OPTCODE( X_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(X)) + OPTCODE(X2_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(X2)) + OPTCODE( Y_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(Y)) + OPTCODE(Y2_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(Y2)) + OPTCODE( Z_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(Z)) + OPTCODE(Z2_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(Z2)) + OPTCODE(Z3_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(Z3)) + OPTCODE(Z4_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(Z4)) + OPTCODE( I_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(I)) + OPTCODE( J_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(J)) + OPTCODE( K_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(K)) + OPTCODE(E0_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E0)) + OPTCODE(E1_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E1)) + OPTCODE(E2_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E2)) + OPTCODE(E3_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E3)) + OPTCODE(E4_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E4)) + OPTCODE(E5_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E5)) + OPTCODE(E6_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E6)) + OPTCODE(E7_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E7)) } /** @@ -178,7 +133,7 @@ static void say_stealth_status() { */ void GcodeSuite::M569() { if (parser.seen('S')) - set_stealth_status(parser.value_bool(), get_target_extruder_from_command()); + set_stealth_status(parser.value_bool(), get_target_e_stepper_from_command()); else say_stealth_status(); } diff --git a/Marlin/src/gcode/feature/trinamic/M906.cpp b/Marlin/src/gcode/feature/trinamic/M906.cpp index e834ebd67d95..9e56e513581d 100644 --- a/Marlin/src/gcode/feature/trinamic/M906.cpp +++ b/Marlin/src/gcode/feature/trinamic/M906.cpp @@ -48,11 +48,11 @@ void GcodeSuite::M906() { bool report = true; - #if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4) + #if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4) || AXIS_IS_TMC(I) || AXIS_IS_TMC(J) || AXIS_IS_TMC(K) const uint8_t index = parser.byteval('I'); #endif - LOOP_XYZE(i) if (uint16_t value = parser.intval(axis_codes[i])) { + LOOP_LOGICAL_AXES(i) if (uint16_t value = parser.intval(axis_codes[i])) { report = false; switch (i) { case X_AXIS: @@ -63,58 +63,77 @@ void GcodeSuite::M906() { if (index == 1) TMC_SET_CURRENT(X2); #endif break; - case Y_AXIS: - #if AXIS_IS_TMC(Y) - if (index == 0) TMC_SET_CURRENT(Y); - #endif - #if AXIS_IS_TMC(Y2) - if (index == 1) TMC_SET_CURRENT(Y2); - #endif - break; - case Z_AXIS: - #if AXIS_IS_TMC(Z) - if (index == 0) TMC_SET_CURRENT(Z); - #endif - #if AXIS_IS_TMC(Z2) - if (index == 1) TMC_SET_CURRENT(Z2); - #endif - #if AXIS_IS_TMC(Z3) - if (index == 2) TMC_SET_CURRENT(Z3); - #endif - #if AXIS_IS_TMC(Z4) - if (index == 3) TMC_SET_CURRENT(Z4); - #endif - break; - case E_AXIS: { - const int8_t target_extruder = get_target_extruder_from_command(); - if (target_extruder < 0) return; - switch (target_extruder) { - #if AXIS_IS_TMC(E0) - case 0: TMC_SET_CURRENT(E0); break; - #endif - #if AXIS_IS_TMC(E1) - case 1: TMC_SET_CURRENT(E1); break; - #endif - #if AXIS_IS_TMC(E2) - case 2: TMC_SET_CURRENT(E2); break; + + #if HAS_Y_AXIS + case Y_AXIS: + #if AXIS_IS_TMC(Y) + if (index == 0) TMC_SET_CURRENT(Y); #endif - #if AXIS_IS_TMC(E3) - case 3: TMC_SET_CURRENT(E3); break; + #if AXIS_IS_TMC(Y2) + if (index == 1) TMC_SET_CURRENT(Y2); #endif - #if AXIS_IS_TMC(E4) - case 4: TMC_SET_CURRENT(E4); break; + break; + #endif + + #if HAS_Z_AXIS + case Z_AXIS: + #if AXIS_IS_TMC(Z) + if (index == 0) TMC_SET_CURRENT(Z); #endif - #if AXIS_IS_TMC(E5) - case 5: TMC_SET_CURRENT(E5); break; + #if AXIS_IS_TMC(Z2) + if (index == 1) TMC_SET_CURRENT(Z2); #endif - #if AXIS_IS_TMC(E6) - case 6: TMC_SET_CURRENT(E6); break; + #if AXIS_IS_TMC(Z3) + if (index == 2) TMC_SET_CURRENT(Z3); #endif - #if AXIS_IS_TMC(E7) - case 7: TMC_SET_CURRENT(E7); break; + #if AXIS_IS_TMC(Z4) + if (index == 3) TMC_SET_CURRENT(Z4); #endif - } - } break; + break; + #endif + + #if AXIS_IS_TMC(I) + case I_AXIS: TMC_SET_CURRENT(I); break; + #endif + #if AXIS_IS_TMC(J) + case J_AXIS: TMC_SET_CURRENT(J); break; + #endif + #if AXIS_IS_TMC(K) + case K_AXIS: TMC_SET_CURRENT(K); break; + #endif + + #if E_STEPPERS + case E_AXIS: { + const int8_t target_e_stepper = get_target_e_stepper_from_command(); + if (target_e_stepper < 0) return; + switch (target_e_stepper) { + #if AXIS_IS_TMC(E0) + case 0: TMC_SET_CURRENT(E0); break; + #endif + #if AXIS_IS_TMC(E1) + case 1: TMC_SET_CURRENT(E1); break; + #endif + #if AXIS_IS_TMC(E2) + case 2: TMC_SET_CURRENT(E2); break; + #endif + #if AXIS_IS_TMC(E3) + case 3: TMC_SET_CURRENT(E3); break; + #endif + #if AXIS_IS_TMC(E4) + case 4: TMC_SET_CURRENT(E4); break; + #endif + #if AXIS_IS_TMC(E5) + case 5: TMC_SET_CURRENT(E5); break; + #endif + #if AXIS_IS_TMC(E6) + case 6: TMC_SET_CURRENT(E6); break; + #endif + #if AXIS_IS_TMC(E7) + case 7: TMC_SET_CURRENT(E7); break; + #endif + } + } break; + #endif } } @@ -143,6 +162,15 @@ void GcodeSuite::M906() { #if AXIS_IS_TMC(Z4) TMC_SAY_CURRENT(Z4); #endif + #if AXIS_IS_TMC(I) + TMC_SAY_CURRENT(I); + #endif + #if AXIS_IS_TMC(J) + TMC_SAY_CURRENT(J); + #endif + #if AXIS_IS_TMC(K) + TMC_SAY_CURRENT(K); + #endif #if AXIS_IS_TMC(E0) TMC_SAY_CURRENT(E0); #endif diff --git a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp index 8c840db5bf9c..fca16c063025 100644 --- a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp +++ b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp @@ -35,12 +35,30 @@ #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)) - #define M91x_SOME_X (M91x_USE(X) || M91x_USE(X2)) - #define M91x_SOME_Y (M91x_USE(Y) || M91x_USE(Y2)) - #define M91x_SOME_Z (M91x_USE(Z) || M91x_USE(Z2) || M91x_USE(Z3) || M91x_USE(Z4)) - #define M91x_SOME_E (M91x_USE_E(0) || M91x_USE_E(1) || M91x_USE_E(2) || M91x_USE_E(3) || M91x_USE_E(4) || M91x_USE_E(5) || M91x_USE_E(6) || M91x_USE_E(7)) + #if M91x_USE(X) || M91x_USE(X2) + #define M91x_SOME_X 1 + #endif + #if LINEAR_AXES >= 2 && (M91x_USE(Y) || M91x_USE(Y2)) + #define M91x_SOME_Y 1 + #endif + #if HAS_Z_AXIS && (M91x_USE(Z) || M91x_USE(Z2) || M91x_USE(Z3) || M91x_USE(Z4)) + #define M91x_SOME_Z 1 + #endif + #if LINEAR_AXES >= 4 && M91x_USE(I) + #define M91x_USE_I 1 + #endif + #if LINEAR_AXES >= 5 && M91x_USE(J) + #define M91x_USE_J 1 + #endif + #if LINEAR_AXES >= 6 && M91x_USE(K) + #define M91x_USE_K 1 + #endif - #if !M91x_SOME_X && !M91x_SOME_Y && !M91x_SOME_Z && !M91x_SOME_E + #if M91x_USE_E(0) || M91x_USE_E(1) || M91x_USE_E(2) || M91x_USE_E(3) || M91x_USE_E(4) || M91x_USE_E(5) || M91x_USE_E(6) || M91x_USE_E(7) + #define M91x_SOME_E 1 + #endif + + #if !M91x_SOME_X && !M91x_SOME_Y && !M91x_SOME_Z && !M91x_USE_I && !M91x_USE_J && !M91x_USE_K && !M91x_SOME_E #error "MONITOR_DRIVER_STATUS requires at least one TMC2130, 2160, 2208, 2209, 2660, 5130, or 5160." #endif @@ -73,6 +91,9 @@ #if M91x_USE(Z4) tmc_report_otpw(stepperZ4); #endif + TERN_(M91x_USE_I, tmc_report_otpw(stepperI)); + TERN_(M91x_USE_J, tmc_report_otpw(stepperJ)); + TERN_(M91x_USE_K, tmc_report_otpw(stepperK)); #if M91x_USE_E(0) tmc_report_otpw(stepperE0); #endif @@ -112,31 +133,15 @@ * M912 E1 ; clear E1 only */ void GcodeSuite::M912() { - #if M91x_SOME_X - const bool hasX = parser.seen(axis_codes.x); - #else - constexpr bool hasX = false; - #endif - - #if M91x_SOME_Y - const bool hasY = parser.seen(axis_codes.y); - #else - constexpr bool hasY = false; - #endif + const bool hasX = TERN0(M91x_SOME_X, parser.seen(axis_codes.x)), + hasY = TERN0(M91x_SOME_Y, parser.seen(axis_codes.y)), + hasZ = TERN0(M91x_SOME_Z, parser.seen(axis_codes.z)), + hasI = TERN0(M91x_USE_I, parser.seen(axis_codes.i)), + hasJ = TERN0(M91x_USE_J, parser.seen(axis_codes.j)), + hasK = TERN0(M91x_USE_K, parser.seen(axis_codes.k)), + hasE = TERN0(M91x_SOME_E, parser.seen(axis_codes.e)); - #if M91x_SOME_Z - const bool hasZ = parser.seen(axis_codes.z); - #else - constexpr bool hasZ = false; - #endif - - #if M91x_SOME_E - const bool hasE = parser.seen(axis_codes.e); - #else - constexpr bool hasE = false; - #endif - - const bool hasNone = !hasX && !hasY && !hasZ && !hasE; + const bool hasNone = !hasE && !hasX && !hasY && !hasZ && !hasI && !hasJ && !hasK; #if M91x_SOME_X const int8_t xval = int8_t(parser.byteval(axis_codes.x, 0xFF)); @@ -174,6 +179,19 @@ #endif #endif + #if M91x_USE_I + const int8_t ival = int8_t(parser.byteval(axis_codes.i, 0xFF)); + if (hasNone || ival == 1 || (hasI && ival < 0)) tmc_clear_otpw(stepperI); + #endif + #if M91x_USE_J + const int8_t jval = int8_t(parser.byteval(axis_codes.j, 0xFF)); + if (hasNone || jval == 1 || (hasJ && jval < 0)) tmc_clear_otpw(stepperJ); + #endif + #if M91x_USE_K + const int8_t kval = int8_t(parser.byteval(axis_codes.k, 0xFF)); + if (hasNone || kval == 1 || (hasK && kval < 0)) tmc_clear_otpw(stepperK); + #endif + #if M91x_SOME_E const int8_t eval = int8_t(parser.byteval(axis_codes.e, 0xFF)); #if M91x_USE_E(0) @@ -216,126 +234,78 @@ #define TMC_SET_PWMTHRS_E(E) stepperE##E.set_pwm_thrs(value) bool report = true; - #if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4) + #if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4) || AXIS_IS_TMC(I) || AXIS_IS_TMC(J) || AXIS_IS_TMC(K) const uint8_t index = parser.byteval('I'); #endif - LOOP_XYZE(i) if (int32_t value = parser.longval(axis_codes[i])) { + LOOP_LOGICAL_AXES(i) if (int32_t value = parser.longval(axis_codes[i])) { report = false; switch (i) { case X_AXIS: - #if AXIS_HAS_STEALTHCHOP(X) - if (index < 2) TMC_SET_PWMTHRS(X,X); - #endif - #if AXIS_HAS_STEALTHCHOP(X2) - if (!(index & 1)) TMC_SET_PWMTHRS(X,X2); - #endif + TERN_(X_HAS_STEALTHCHOP, if (index < 2) TMC_SET_PWMTHRS(X,X)); + TERN_(X2_HAS_STEALTHCHOP, if (!(index & 1)) TMC_SET_PWMTHRS(X,X2)); break; case Y_AXIS: - #if AXIS_HAS_STEALTHCHOP(Y) - if (index < 2) TMC_SET_PWMTHRS(Y,Y); - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - if (!(index & 1)) TMC_SET_PWMTHRS(Y,Y2); - #endif + TERN_(Y_HAS_STEALTHCHOP, if (index < 2) TMC_SET_PWMTHRS(Y,Y)); + TERN_(Y2_HAS_STEALTHCHOP, if (!(index & 1)) TMC_SET_PWMTHRS(Y,Y2)); break; + + #if I_HAS_STEALTHCHOP + case I_AXIS: TMC_SET_PWMTHRS(I,I); break; + #endif + #if J_HAS_STEALTHCHOP + case J_AXIS: TMC_SET_PWMTHRS(J,J); break; + #endif + #if K_HAS_STEALTHCHOP + case K_AXIS: TMC_SET_PWMTHRS(K,K); break; + #endif + case Z_AXIS: - #if AXIS_HAS_STEALTHCHOP(Z) - if (index < 2) TMC_SET_PWMTHRS(Z,Z); - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - if (index == 0 || index == 2) TMC_SET_PWMTHRS(Z,Z2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z3) - if (index == 0 || index == 3) TMC_SET_PWMTHRS(Z,Z3); - #endif - #if AXIS_HAS_STEALTHCHOP(Z4) - if (index == 0 || index == 4) TMC_SET_PWMTHRS(Z,Z4); - #endif + TERN_(Z_HAS_STEALTHCHOP, if (index < 2) TMC_SET_PWMTHRS(Z,Z)); + TERN_(Z2_HAS_STEALTHCHOP, if (index == 0 || index == 2) TMC_SET_PWMTHRS(Z,Z2)); + TERN_(Z3_HAS_STEALTHCHOP, if (index == 0 || index == 3) TMC_SET_PWMTHRS(Z,Z3)); + TERN_(Z4_HAS_STEALTHCHOP, if (index == 0 || index == 4) TMC_SET_PWMTHRS(Z,Z4)); break; - case E_AXIS: { - #if E_STEPPERS - const int8_t target_extruder = get_target_extruder_from_command(); - if (target_extruder < 0) return; - switch (target_extruder) { - #if AXIS_HAS_STEALTHCHOP(E0) - case 0: TMC_SET_PWMTHRS_E(0); break; - #endif - #if E_STEPPERS > 1 && AXIS_HAS_STEALTHCHOP(E1) - case 1: TMC_SET_PWMTHRS_E(1); break; - #endif - #if E_STEPPERS > 2 && AXIS_HAS_STEALTHCHOP(E2) - case 2: TMC_SET_PWMTHRS_E(2); break; - #endif - #if E_STEPPERS > 3 && AXIS_HAS_STEALTHCHOP(E3) - case 3: TMC_SET_PWMTHRS_E(3); break; - #endif - #if E_STEPPERS > 4 && AXIS_HAS_STEALTHCHOP(E4) - case 4: TMC_SET_PWMTHRS_E(4); break; - #endif - #if E_STEPPERS > 5 && AXIS_HAS_STEALTHCHOP(E5) - case 5: TMC_SET_PWMTHRS_E(5); break; - #endif - #if E_STEPPERS > 6 && AXIS_HAS_STEALTHCHOP(E6) - case 6: TMC_SET_PWMTHRS_E(6); break; - #endif - #if E_STEPPERS > 7 && AXIS_HAS_STEALTHCHOP(E7) - case 7: TMC_SET_PWMTHRS_E(7); break; - #endif + #if E_STEPPERS + case E_AXIS: { + const int8_t target_e_stepper = get_target_e_stepper_from_command(); + if (target_e_stepper < 0) return; + switch (target_e_stepper) { + TERN_(E0_HAS_STEALTHCHOP, case 0: TMC_SET_PWMTHRS_E(0); break;) + TERN_(E1_HAS_STEALTHCHOP, case 1: TMC_SET_PWMTHRS_E(1); break;) + TERN_(E2_HAS_STEALTHCHOP, case 2: TMC_SET_PWMTHRS_E(2); break;) + TERN_(E3_HAS_STEALTHCHOP, case 3: TMC_SET_PWMTHRS_E(3); break;) + TERN_(E4_HAS_STEALTHCHOP, case 4: TMC_SET_PWMTHRS_E(4); break;) + TERN_(E5_HAS_STEALTHCHOP, case 5: TMC_SET_PWMTHRS_E(5); break;) + TERN_(E6_HAS_STEALTHCHOP, case 6: TMC_SET_PWMTHRS_E(6); break;) + TERN_(E7_HAS_STEALTHCHOP, case 7: TMC_SET_PWMTHRS_E(7); break;) } - #endif // E_STEPPERS - } break; + } break; + #endif // E_STEPPERS } } if (report) { - #if AXIS_HAS_STEALTHCHOP(X) - TMC_SAY_PWMTHRS(X,X); - #endif - #if AXIS_HAS_STEALTHCHOP(X2) - TMC_SAY_PWMTHRS(X,X2); - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - TMC_SAY_PWMTHRS(Y,Y); - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - TMC_SAY_PWMTHRS(Y,Y2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - TMC_SAY_PWMTHRS(Z,Z); - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - TMC_SAY_PWMTHRS(Z,Z2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z3) - TMC_SAY_PWMTHRS(Z,Z3); - #endif - #if AXIS_HAS_STEALTHCHOP(Z4) - TMC_SAY_PWMTHRS(Z,Z4); - #endif - #if E_STEPPERS && AXIS_HAS_STEALTHCHOP(E0) - TMC_SAY_PWMTHRS_E(0); - #endif - #if E_STEPPERS > 1 && AXIS_HAS_STEALTHCHOP(E1) - TMC_SAY_PWMTHRS_E(1); - #endif - #if E_STEPPERS > 2 && AXIS_HAS_STEALTHCHOP(E2) - TMC_SAY_PWMTHRS_E(2); - #endif - #if E_STEPPERS > 3 && AXIS_HAS_STEALTHCHOP(E3) - TMC_SAY_PWMTHRS_E(3); - #endif - #if E_STEPPERS > 4 && AXIS_HAS_STEALTHCHOP(E4) - TMC_SAY_PWMTHRS_E(4); - #endif - #if E_STEPPERS > 5 && AXIS_HAS_STEALTHCHOP(E5) - TMC_SAY_PWMTHRS_E(5); - #endif - #if E_STEPPERS > 6 && AXIS_HAS_STEALTHCHOP(E6) - TMC_SAY_PWMTHRS_E(6); - #endif - #if E_STEPPERS > 7 && AXIS_HAS_STEALTHCHOP(E7) - TMC_SAY_PWMTHRS_E(7); - #endif + TERN_( X_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(X,X)); + TERN_(X2_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(X,X2)); + TERN_( Y_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(Y,Y)); + TERN_(Y2_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(Y,Y2)); + TERN_( Z_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(Z,Z)); + TERN_(Z2_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(Z,Z2)); + TERN_(Z3_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(Z,Z3)); + TERN_(Z4_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(Z,Z4)); + + TERN_( I_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(I,I)); + TERN_( J_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(J,J)); + TERN_( K_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(K,K)); + + TERN_(E0_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(0)); + TERN_(E1_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(1)); + TERN_(E2_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(2)); + TERN_(E3_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(3)); + TERN_(E4_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(4)); + TERN_(E5_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(5)); + TERN_(E6_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(6)); + TERN_(E7_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(7)); } } #endif // HYBRID_THRESHOLD @@ -348,7 +318,7 @@ bool report = true; const uint8_t index = parser.byteval('I'); - LOOP_XYZ(i) if (parser.seen(XYZ_CHAR(i))) { + LOOP_LINEAR_AXES(i) if (parser.seen(AXIS_CHAR(i))) { const int16_t value = parser.value_int(); report = false; switch (i) { @@ -388,6 +358,15 @@ #endif break; #endif + #if I_SENSORLESS && AXIS_HAS_STALLGUARD(I) + case I_AXIS: stepperI.homing_threshold(value); break; + #endif + #if J_SENSORLESS && AXIS_HAS_STALLGUARD(J) + case J_AXIS: stepperJ.homing_threshold(value); break; + #endif + #if K_SENSORLESS && AXIS_HAS_STALLGUARD(K) + case K_AXIS: stepperK.homing_threshold(value); break; + #endif } } @@ -422,6 +401,15 @@ tmc_print_sgt(stepperZ4); #endif #endif + #if I_SENSORLESS && AXIS_HAS_STALLGUARD(I) + tmc_print_sgt(stepperI); + #endif + #if J_SENSORLESS && AXIS_HAS_STALLGUARD(J) + tmc_print_sgt(stepperJ); + #endif + #if K_SENSORLESS && AXIS_HAS_STALLGUARD(K) + tmc_print_sgt(stepperK); + #endif } } #endif // USE_SENSORLESS diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index f2bd81e670dc..7933c3141a11 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -40,7 +40,7 @@ GcodeSuite gcode; #include "../module/printcounter.h" #endif -#if ENABLED(HOST_PROMPT_SUPPORT) +#if ENABLED(HOST_ACTION_COMMANDS) #include "../feature/host_actions.h" #endif @@ -57,11 +57,15 @@ GcodeSuite gcode; #include "../feature/spindle_laser.h" #endif +#if ENABLED(FLOWMETER_SAFETY) + #include "../feature/cooler.h" +#endif + #if ENABLED(PASSWORD_FEATURE) #include "../feature/password/password.h" #endif -#include "../MarlinCore.h" // for idle() +#include "../MarlinCore.h" // for idle, kill // Inactivity shutdown millis_t GcodeSuite::previous_move_ms = 0, @@ -70,11 +74,14 @@ millis_t GcodeSuite::previous_move_ms = 0, // Relative motion mode for each logical axis static constexpr xyze_bool_t ar_init = AXIS_RELATIVE_MODES; -uint8_t GcodeSuite::axis_relative = ( - (ar_init.x ? _BV(REL_X) : 0) - | (ar_init.y ? _BV(REL_Y) : 0) - | (ar_init.z ? _BV(REL_Z) : 0) - | (ar_init.e ? _BV(REL_E) : 0) +uint8_t GcodeSuite::axis_relative = 0 LOGICAL_AXIS_GANG( + | (ar_init.e << REL_E), + | (ar_init.x << REL_X), + | (ar_init.y << REL_Y), + | (ar_init.z << REL_Z), + | (ar_init.i << REL_I), + | (ar_init.j << REL_J), + | (ar_init.k << REL_K) ); #if EITHER(HAS_AUTO_REPORTING, HOST_KEEPALIVE_FEATURE) @@ -105,7 +112,7 @@ int8_t GcodeSuite::get_target_extruder_from_command() { if (e < EXTRUDERS) return e; SERIAL_ECHO_START(); SERIAL_CHAR('M'); SERIAL_ECHO(parser.codenum); - SERIAL_ECHOLNPAIR(" " STR_INVALID_EXTRUDER " ", int(e)); + SERIAL_ECHOLNPAIR(" " STR_INVALID_EXTRUDER " ", e); return -1; } return active_extruder; @@ -124,7 +131,7 @@ int8_t GcodeSuite::get_target_e_stepper_from_command() { if (e == -1) SERIAL_ECHOLNPGM(" " STR_E_STEPPER_NOT_SPECIFIED); else - SERIAL_ECHOLNPAIR(" " STR_INVALID_E_STEPPER " ", int(e)); + SERIAL_ECHOLNPAIR(" " STR_INVALID_E_STEPPER " ", e); return -1; } @@ -136,7 +143,7 @@ int8_t GcodeSuite::get_target_e_stepper_from_command() { * - Set the feedrate, if included */ void GcodeSuite::get_destination_from_command() { - xyze_bool_t seen = { false, false, false, false }; + xyze_bool_t seen{false}; #if ENABLED(CANCEL_OBJECTS) const bool &skip_move = cancelable.skipping; @@ -145,8 +152,8 @@ void GcodeSuite::get_destination_from_command() { #endif // Get new XYZ position, whether absolute or relative - LOOP_XYZ(i) { - if ( (seen[i] = parser.seenval(XYZ_CHAR(i))) ) { + LOOP_LINEAR_AXES(i) { + if ( (seen[i] = parser.seenval(AXIS_CHAR(i))) ) { const float v = parser.value_axis_units((AxisEnum)i); if (skip_move) destination[i] = current_position[i]; @@ -157,13 +164,15 @@ void GcodeSuite::get_destination_from_command() { destination[i] = current_position[i]; } - // Get new E position, whether absolute or relative - if ( (seen.e = parser.seenval('E')) ) { - const float v = parser.value_axis_units(E_AXIS); - destination.e = axis_is_relative(E_AXIS) ? current_position.e + v : v; - } - else - destination.e = current_position.e; + #if HAS_EXTRUDERS + // Get new E position, whether absolute or relative + if ( (seen.e = parser.seenval('E')) ) { + const float v = parser.value_axis_units(E_AXIS); + destination.e = axis_is_relative(E_AXIS) ? current_position.e + v : v; + } + else + destination.e = current_position.e; + #endif #if ENABLED(POWER_LOSS_RECOVERY) && !PIN_EXISTS(POWER_LOSS) // Only update power loss recovery on moves with E @@ -207,7 +216,36 @@ void GcodeSuite::dwell(millis_t time) { * When G29_RETRY_AND_RECOVER is enabled, call G29() in * a loop with recovery and retry handling. */ -#if BOTH(HAS_LEVELING, G29_RETRY_AND_RECOVER) +#if ENABLED(G29_RETRY_AND_RECOVER) + + void GcodeSuite::event_probe_recover() { + TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_INFO, PSTR("G29 Retrying"), DISMISS_STR)); + #ifdef ACTION_ON_G29_RECOVER + host_action(PSTR(ACTION_ON_G29_RECOVER)); + #endif + #ifdef G29_RECOVER_COMMANDS + process_subcommands_now_P(PSTR(G29_RECOVER_COMMANDS)); + #endif + } + + #if ENABLED(G29_HALT_ON_FAILURE) + #include "../lcd/marlinui.h" + #endif + + void GcodeSuite::event_probe_failure() { + #ifdef ACTION_ON_G29_FAILURE + host_action(PSTR(ACTION_ON_G29_FAILURE)); + #endif + #ifdef G29_FAILURE_COMMANDS + process_subcommands_now_P(PSTR(G29_FAILURE_COMMANDS)); + #endif + #if ENABLED(G29_HALT_ON_FAILURE) + #ifdef ACTION_ON_CANCEL + host_action_cancel(); + #endif + kill(GET_TEXT(MSG_LCD_PROBING_FAILED)); + #endif + } #ifndef G29_MAX_RETRIES #define G29_MAX_RETRIES 0 @@ -216,7 +254,10 @@ void GcodeSuite::dwell(millis_t time) { void GcodeSuite::G29_with_retry() { uint8_t retries = G29_MAX_RETRIES; while (G29()) { // G29 should return true for failed probes ONLY - if (retries--) event_probe_recover(); + if (retries) { + event_probe_recover(); + --retries; + } else { event_probe_failure(); return; @@ -230,14 +271,7 @@ void GcodeSuite::dwell(millis_t time) { #endif } -#endif // HAS_LEVELING && G29_RETRY_AND_RECOVER - -// -// Placeholders for non-migrated codes -// -#if ENABLED(M100_FREE_MEMORY_WATCHER) - extern void M100_dump_routine(PGM_P const title, const char * const start, const char * const end); -#endif +#endif // G29_RETRY_AND_RECOVER /** * Process the parsed command and dispatch it to its handler @@ -250,14 +284,24 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { * Will still block Gcodes if M511 is disabled, in which case the printer should be unlocked via LCD Menu */ #if ENABLED(PASSWORD_FEATURE) - if (password.is_locked && !(parser.command_letter == 'M' && parser.codenum == 511)) { + if (password.is_locked && !parser.is_command('M', 511)) { SERIAL_ECHO_MSG(STR_PRINTER_LOCKED); + if (!no_ok) queue.ok_to_send(); return; } #endif - // Handle a known G, M, or T + #if ENABLED(FLOWMETER_SAFETY) + if (cooler.flowfault) { + SERIAL_ECHO_MSG(STR_FLOWMETER_FAULT); + return; + } + #endif + + // Handle a known command or reply "unknown command" + switch (parser.command_letter) { + case 'G': switch (parser.codenum) { case 0: case 1: // G0: Fast Move, G1: Linear Move @@ -327,7 +371,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 33: G33(); break; // G33: Delta Auto-Calibration #endif - #if EITHER(Z_STEPPER_AUTO_ALIGN, MECHANICAL_GANTRY_CALIBRATION) + #if ANY(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN, MECHANICAL_GANTRY_CALIBRATION) case 34: G34(); break; // G34: Z Stepper automatic alignment using probe #endif @@ -342,6 +386,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { break; #endif + #if HAS_MESH + case 42: G42(); break; // G42: Coordinated move to a mesh point + #endif + #if ENABLED(CNC_COORDINATE_SYSTEMS) case 53: G53(); break; // G53: (prefix) Apply native workspace case 54: G54(); break; // G54: Switch to Workspace 1 @@ -370,10 +418,6 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 92: G92(); break; // G92: Set current axis position(s) - #if HAS_MESH - case 42: G42(); break; // G42: Coordinated move to a mesh point - #endif - #if ENABLED(CALIBRATION_GCODE) case 425: G425(); break; // G425: Perform calibration with calibration cube #endif @@ -399,14 +443,21 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 5: M5(); break; // M5: Turn OFF Laser | Spindle #endif - #if ENABLED(COOLANT_CONTROL) - #if ENABLED(COOLANT_MIST) - case 7: M7(); break; // M7: Mist coolant ON - #endif - #if ENABLED(COOLANT_FLOOD) - case 8: M8(); break; // M8: Flood coolant ON - #endif - case 9: M9(); break; // M9: Coolant OFF + #if ENABLED(COOLANT_MIST) + case 7: M7(); break; // M7: Coolant Mist ON + #endif + + #if EITHER(AIR_ASSIST, COOLANT_FLOOD) + case 8: M8(); break; // M8: Air Assist / Coolant Flood ON + #endif + + #if EITHER(AIR_ASSIST, COOLANT_CONTROL) + case 9: M9(); break; // M9: Air Assist / Coolant OFF + #endif + + #if ENABLED(AIR_EVACUATION) + case 10: M10(); break; // M10: Vacuum or Blower motor ON + case 11: M11(); break; // M11: Vacuum or Blower motor OFF #endif #if ENABLED(EXTERNAL_CLOSED_LOOP_CONTROLLER) @@ -431,7 +482,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 28: M28(); break; // M28: Start SD write case 29: M29(); break; // M29: Stop SD write case 30: M30(); break; // M30 Delete File - case 32: M32(); break; // M32: Select file and start SD print + + #if HAS_MEDIA_SUBCALLS + case 32: M32(); break; // M32: Select file and start SD print + #endif #if ENABLED(LONG_FILENAME_HOST_SUPPORT) case 33: M33(); break; // M33: Get the long full path to a file or folder @@ -474,7 +528,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 100: M100(); break; // M100: Free Memory Report #endif - #if EXTRUDERS + #if HAS_EXTRUDERS case 104: M104(); break; // M104: Set hot end temperature case 109: M109(); break; // M109: Wait for hotend temperature to reach target #endif @@ -514,6 +568,15 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 191: M191(); break; // M191: Wait for chamber temperature to reach target #endif + #if HAS_COOLER + case 143: M143(); break; // M143: Set cooler temperature + case 193: M193(); break; // M193: Wait for cooler temperature to reach target + #endif + + #if ENABLED(AUTO_REPORT_POSITION) + case 154: M154(); break; // M154: Set position auto-report interval + #endif + #if BOTH(AUTO_REPORT_TEMPERATURES, HAS_TEMP_SENSOR) case 155: M155(); break; // M155: Set temperature auto-report interval #endif @@ -541,14 +604,18 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { #endif case 81: M81(); break; // M81: Turn off Power, including Power Supply, if possible - case 82: M82(); break; // M82: Set E axis normal mode (same as other axes) - case 83: M83(); break; // M83: Set E axis relative mode + #if HAS_EXTRUDERS + 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 case 114: M114(); break; // M114: Report current position case 115: M115(); break; // M115: Report capabilities - case 117: M117(); break; // M117: Set LCD message text, if possible + + case 117: TERN_(HAS_STATUS_MESSAGE, M117()); break; // M117: Set LCD message text, if possible + case 118: M118(); break; // M118: Display a message in the host console case 119: M119(); break; // M119: Report endstop states case 120: M120(); break; // M120: Enable endstops @@ -619,7 +686,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 220: M220(); break; // M220: Set Feedrate Percentage: S ("FR" on your LCD) - #if EXTRUDERS + #if HAS_EXTRUDERS case 221: M221(); break; // M221: Set Flow Percentage #endif @@ -650,6 +717,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 304: M304(); break; // M304: Set bed PID parameters #endif + #if ENABLED(PIDTEMPCHAMBER) + case 309: M309(); break; // M309: Set chamber PID parameters + #endif + #if ENABLED(PHOTO_GCODE) case 240: M240(); break; // M240: Trigger a camera #endif @@ -658,6 +729,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 250: M250(); break; // M250: Set LCD contrast #endif + #if HAS_LCD_BRIGHTNESS + case 256: M256(); break; // M256: Set LCD brightness + #endif + #if ENABLED(EXPERIMENTAL_I2CBUS) case 260: M260(); break; // M260: Send data to an i2c slave case 261: M261(); break; // M261: Request data from an i2c slave @@ -699,7 +774,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 402: M402(); break; // M402: Stow probe #endif - #if ENABLED(PRUSA_MMU2) + #if HAS_PRUSA_MMU2 case 403: M403(); break; #endif @@ -714,6 +789,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 412: M412(); break; // M412: Enable/Disable filament runout detection #endif + #if HAS_MULTI_LANGUAGE + case 414: M414(); break; // M414: Select multi language menu + #endif + #if HAS_LEVELING case 420: M420(); break; // M420: Enable/Disable Bed Leveling #endif @@ -754,8 +833,8 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 511: M511(); break; // M511: Unlock Printer #endif #if ENABLED(PASSWORD_CHANGE_GCODE) - case 512: M512(); break; - #endif // M512: Set/Change/Remove Password + case 512: M512(); break; // M512: Set/Change/Remove Password + #endif #endif #if ENABLED(SDSUPPORT) @@ -766,6 +845,12 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 540: M540(); break; // M540: Set abort on endstop hit for SD printing #endif + #if HAS_ETHERNET + case 552: M552(); break; // M552: Set IP address + case 553: M553(); break; // M553: Set gateway + case 554: M554(); break; // M554: Set netmask + #endif + #if ENABLED(BAUD_RATE_GCODE) case 575: M575(); break; // M575: Set serial baudrate #endif @@ -827,7 +912,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 907: M907(); break; // M907: Set digital trimpot motor current using axis codes. #if EITHER(HAS_MOTOR_CURRENT_SPI, HAS_MOTOR_CURRENT_DAC) case 908: M908(); break; // M908: Control digital trimpot directly. - #if ENABLED(HAS_MOTOR_CURRENT_DAC) + #if HAS_MOTOR_CURRENT_DAC case 909: M909(); break; // M909: Print digipot/DAC current value case 910: M910(); break; // M910: Commit digipot/DAC value to external EEPROM #endif @@ -873,6 +958,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 800: parser.debug(); break; // M800: GCode Parser Test for M #endif + #if ENABLED(GCODE_REPEAT_MARKERS) + case 808: M808(); break; // M808: Set / Goto repeat markers + #endif + #if ENABLED(I2C_POSITION_ENCODERS) case 860: M860(); break; // M860: Report encoder module position case 861: M861(); break; // M861: Report encoder module status @@ -918,6 +1007,14 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 1001: M1001(); break; // M1001: [INTERNAL] Handle SD completion #endif + #if ENABLED(DGUS_LCD_UI_MKS) + case 1002: M1002(); break; // M1002: [INTERNAL] Tool-change and Relative E Move + #endif + + #if ENABLED(UBL_MESH_WIZARD) + case 1004: M1004(); break; // M1004: UBL Mesh Wizard + #endif + #if ENABLED(MAX7219_GCODE) case 7219: M7219(); break; // M7219: Set LEDs, columns, and rows #endif @@ -932,6 +1029,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 'D': D(parser.codenum); break; // Dn: Debug codes #endif + #if ENABLED(REALTIME_REPORTING_COMMANDS) + case 'S': case 'P': case 'R': break; // Invalid S, P, R commands already filtered + #endif + default: #if ENABLED(WIFI_CUSTOM_COMMAND) if (wifi_custom_command(parser.command_ptr)) break; @@ -940,32 +1041,36 @@ 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 } +#if ENABLED(M100_FREE_MEMORY_DUMPER) + void M100_dump_routine(PGM_P const title, const char * const start, const uintptr_t size); +#endif + /** * Process a single command and dispatch it to its handler * This is called from the main loop() */ void GcodeSuite::process_next_command() { - char * const current_command = queue.command_buffer[queue.index_r]; + GCodeQueue::CommandLine &command = queue.ring_buffer.peek_next_command(); - PORT_REDIRECT(queue.port[queue.index_r]); + PORT_REDIRECT(SERIAL_PORTMASK(command.port)); - #if ENABLED(POWER_LOSS_RECOVERY) - recovery.queue_index_r = queue.index_r; - #endif + TERN_(POWER_LOSS_RECOVERY, recovery.queue_index_r = queue.ring_buffer.index_r); if (DEBUGGING(ECHO)) { SERIAL_ECHO_START(); - SERIAL_ECHOLN(current_command); + SERIAL_ECHOLN(command.buffer); #if ENABLED(M100_FREE_MEMORY_DUMPER) - SERIAL_ECHOPAIR("slot:", queue.index_r); - M100_dump_routine(PSTR(" Command Queue:"), &queue.command_buffer[0][0], &queue.command_buffer[BUFSIZE - 1][MAX_CMD_SIZE - 1]); + SERIAL_ECHOPAIR("slot:", queue.ring_buffer.index_r); + M100_dump_routine(PSTR(" Command Queue:"), (const char*)&queue.ring_buffer, sizeof(queue.ring_buffer)); #endif } // Parse the next command in the queue - parser.parse(current_command); + parser.parse(command.buffer); process_parsed_command(); } @@ -983,7 +1088,7 @@ void GcodeSuite::process_subcommands_now_P(PGM_P pgcode) { strncpy_P(cmd, pgcode, len); // Copy the command to the stack cmd[len] = '\0'; // End with a nul parser.parse(cmd); // Parse the command - process_parsed_command(true); // Process it + process_parsed_command(true); // Process it (no "ok") if (!delim) break; // Last command? pgcode = delim + 1; // Get the next command } @@ -996,9 +1101,9 @@ void GcodeSuite::process_subcommands_now(char * gcode) { char * const delim = strchr(gcode, '\n'); // Get address of next newline if (delim) *delim = '\0'; // Replace with nul parser.parse(gcode); // Parse the current command - if (delim) *delim = '\n'; // Put back the newline - process_parsed_command(true); // Process it + process_parsed_command(true); // Process it (no "ok") if (!delim) break; // Last command? + *delim = '\n'; // Put back the newline gcode = delim + 1; // Get the next command } parser.parse(saved_cmd); // Restore the parser state @@ -1015,16 +1120,20 @@ void GcodeSuite::process_subcommands_now(char * gcode) { static millis_t next_busy_signal_ms = 0; if (!autoreport_paused && host_keepalive_interval && busy_state != NOT_BUSY) { if (PENDING(ms, next_busy_signal_ms)) return; + PORT_REDIRECT(SerialMask::All); switch (busy_state) { case IN_HANDLER: case IN_PROCESS: SERIAL_ECHO_MSG(STR_BUSY_PROCESSING); + TERN_(FULL_REPORT_TO_HOST_FEATURE, report_current_position_moving()); break; case PAUSED_FOR_USER: SERIAL_ECHO_MSG(STR_BUSY_PAUSED_FOR_USER); + TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_HOLD)); break; case PAUSED_FOR_INPUT: SERIAL_ECHO_MSG(STR_BUSY_PAUSED_FOR_INPUT); + TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_HOLD)); break; default: break; diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 3d745eff8939..9f47c9f67991 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -86,6 +86,8 @@ * M7 - Turn mist coolant ON. (Requires COOLANT_CONTROL) * M8 - Turn flood coolant ON. (Requires COOLANT_CONTROL) * M9 - Turn coolant OFF. (Requires COOLANT_CONTROL) + * M10 - Turn Vacuum or Blower motor ON (Requires AIR_EVACUATION) + * M11 - Turn Vacuum or Blower motor OFF (Requires AIR_EVACUATION) * M12 - Set up closed loop control system. (Requires EXTERNAL_CLOSED_LOOP_CONTROLLER) * M16 - Expected printer check. (Requires EXPECTED_PRINTER_CHECK) * M17 - Enable/Power all stepper motors @@ -153,9 +155,11 @@ * M129 - EtoP Closed. (Requires BARICUDA) * M140 - Set bed target temp. S * M141 - Set heated chamber target temp. S (Requires a chamber heater) + * M143 - Set cooler target temp. S (Requires a laser cooling device) * M145 - Set heatup values for materials on the LCD. H B F for S (0=PLA, 1=ABS) * M149 - Set temperature units. (Requires TEMPERATURE_UNITS_SUPPORT) * M150 - Set Status LED Color as R U B W P. Values 0-255. (Requires BLINKM, RGB_LED, RGBW_LED, NEOPIXEL_LED, PCA9533, or PCA9632). + * M154 - Auto-report position with interval of S. (Requires AUTO_REPORT_POSITION) * M155 - Auto-report temperatures with interval of S. (Requires AUTO_REPORT_TEMPERATURES) * M163 - Set a single proportion for a mixing extruder. (Requires MIXING_EXTRUDER) * M164 - Commit the mix and save to a virtual tool (current, or as specified by 'S'). (Requires MIXING_EXTRUDER) @@ -163,6 +167,7 @@ * M166 - Set the Gradient Mix for the mixing extruder. (Requires GRADIENT_MIX) * M190 - S Wait for bed current temp to reach target temp. ** Wait only when heating! ** * R Wait for bed current temp to reach target temp. ** Wait for heating or cooling. ** + * M193 - R Wait for cooler temp to reach target temp. ** Wait for cooling. ** * M200 - Set filament diameter, D, setting E axis units to cubic. (Use S0 to revert to linear units.) * M201 - Set max acceleration in units/s^2 for print moves: "M201 X Y Z E" * M202 - Set max acceleration in units/s^2 for travel moves: "M202 X Y Z E" ** UNUSED IN MARLIN! ** @@ -181,11 +186,12 @@ * M217 - Set filament swap parameters: "M217 S P R". (Requires SINGLENOZZLE) * M218 - Set/get a tool offset: "M218 T X Y". (Requires 2 or more extruders) * M220 - Set Feedrate Percentage: "M220 S" (i.e., "FR" on the LCD) - * Use "M220 B" to back up the Feedrate Percentage and "M220 R" to restore it. (Requires PRUSA_MMU2) + * Use "M220 B" to back up the Feedrate Percentage and "M220 R" to restore it. (Requires an MMU_MODEL version 2 or 2S) * M221 - Set Flow Percentage: "M221 S" * M226 - Wait until a pin is in a given state: "M226 P S" (Requires DIRECT_PIN_CONTROL) * M240 - Trigger a camera to take a photograph. (Requires PHOTO_GCODE) * M250 - Set LCD contrast: "M250 C" (0-63). (Requires LCD support) + * M256 - Set LCD brightness: "M256 B" (0-255). (Requires an LCD with brightness control) * M260 - i2c Send Data (Requires EXPERIMENTAL_I2CBUS) * M261 - i2c Request Data (Requires EXPERIMENTAL_I2CBUS) * M280 - Set servo position absolute: "M280 P S". (Requires servos) @@ -197,6 +203,7 @@ * M303 - PID relay autotune S sets the target temperature. Default 150C. (Requires PIDTEMP) * M304 - Set bed PID parameters P I and D. (Requires PIDTEMPBED) * M305 - Set user thermistor parameters R T and P. (Requires TEMP_SENSOR_x 1000) + * M309 - Set chamber PID parameters P I and D. (Requires PIDTEMPCHAMBER) * M350 - Set microstepping mode. (Requires digital microstepping pins.) * M351 - Toggle MS1 MS2 pins directly. (Requires digital microstepping pins.) * M355 - Set Case Light on/off and set brightness. (Requires CASE_LIGHT_PIN) @@ -213,6 +220,7 @@ * M410 - Quickstop. Abort all planned moves. * M412 - Enable / Disable Filament Runout Detection. (Requires FILAMENT_RUNOUT_SENSOR) * M413 - Enable / Disable Power-Loss Recovery. (Requires POWER_LOSS_RECOVERY) + * M414 - Set language by index. (Requires LCD_LANGUAGE_2...) * M420 - Enable/Disable Leveling (with current values) S1=enable S0=disable (Requires MESH_BED_LEVELING or ABL) * M421 - Set a single Z coordinate in the Mesh Leveling grid. X Y Z (Requires MESH_BED_LEVELING, AUTO_BED_LEVELING_BILINEAR, or AUTO_BED_LEVELING_UBL) * M422 - Set Z Stepper automatic alignment position using probe. X Y A (Requires Z_STEPPER_AUTO_ALIGN) @@ -230,6 +238,9 @@ * M512 - Set/Change/Remove Password * M524 - Abort the current SD print job started with M24. (Requires SDSUPPORT) * M540 - Enable/disable SD card abort on endstop hit: "M540 S". (Requires SD_ABORT_ON_ENDSTOP_HIT) + * M552 - Get or set IP address. Enable/disable network interface. (Requires enabled Ethernet port) + * M553 - Get or set IP netmask. (Requires enabled Ethernet port) + * M554 - Get or set IP gateway. (Requires enabled Ethernet port) * M569 - Enable stealthChop on an axis. (Requires at least one _DRIVER_TYPE to be TMC2130/2160/2208/2209/5130/5160) * M600 - Pause for filament change: "M600 X Y Z E L". (Requires ADVANCED_PAUSE_FEATURE) * M603 - Configure filament change: "M603 T U L". (Requires ADVANCED_PAUSE_FEATURE) @@ -239,6 +250,7 @@ * M672 - Set/Reset Duet Smart Effector's sensitivity. (Requires DUET_SMART_EFFECTOR and SMART_EFFECTOR_MOD_PIN) * M701 - Load filament (Requires FILAMENT_LOAD_UNLOAD_GCODES) * M702 - Unload filament (Requires FILAMENT_LOAD_UNLOAD_GCODES) + * M808 - Set or Goto a Repeat Marker (Requires GCODE_REPEAT_MARKERS) * M810-M819 - Define/execute a G-code macro (Requires GCODE_MACROS) * M851 - Set Z probe's XYZ offsets in current units. (Negative values: X=left, Y=front, Z=below) * M852 - Set skew factors: "M852 [I] [J] [K]". (Requires SKEW_CORRECTION_GCODE, and SKEW_CORRECTION_FOR_Z for IJ) @@ -303,7 +315,14 @@ #define HAS_FAST_MOVES 1 #endif -enum AxisRelative : uint8_t { REL_X, REL_Y, REL_Z, REL_E, E_MODE_ABS, E_MODE_REL }; +enum AxisRelative : uint8_t { + LOGICAL_AXIS_LIST(REL_E, REL_X, REL_Y, REL_Z, REL_I, REL_J, REL_K) + #if HAS_EXTRUDERS + , E_MODE_ABS, E_MODE_REL + #endif +}; + +extern const char G28_STR[]; class GcodeSuite { public: @@ -311,23 +330,31 @@ class GcodeSuite { static uint8_t axis_relative; static inline bool axis_is_relative(const AxisEnum a) { - if (a == E_AXIS) { - if (TEST(axis_relative, E_MODE_REL)) return true; - if (TEST(axis_relative, E_MODE_ABS)) return false; - } + #if HAS_EXTRUDERS + if (a == E_AXIS) { + if (TEST(axis_relative, E_MODE_REL)) return true; + if (TEST(axis_relative, E_MODE_ABS)) return false; + } + #endif return TEST(axis_relative, a); } static inline void set_relative_mode(const bool rel) { - axis_relative = rel ? _BV(REL_X) | _BV(REL_Y) | _BV(REL_Z) | _BV(REL_E) : 0; - } - static inline void set_e_relative() { - CBI(axis_relative, E_MODE_ABS); - SBI(axis_relative, E_MODE_REL); - } - static inline void set_e_absolute() { - CBI(axis_relative, E_MODE_REL); - SBI(axis_relative, E_MODE_ABS); + axis_relative = rel ? (0 LOGICAL_AXIS_GANG( + | _BV(REL_E), + | _BV(REL_X), | _BV(REL_Y), | _BV(REL_Z), + | _BV(REL_I), | _BV(REL_J), | _BV(REL_K) + )) : 0; } + #if HAS_EXTRUDERS + static inline void set_e_relative() { + CBI(axis_relative, E_MODE_ABS); + SBI(axis_relative, E_MODE_REL); + } + static inline void set_e_absolute() { + CBI(axis_relative, E_MODE_REL); + SBI(axis_relative, E_MODE_ABS); + } + #endif #if ENABLED(CNC_WORKSPACE_PLANES) /** @@ -365,9 +392,8 @@ class GcodeSuite { static void process_subcommands_now_P(PGM_P pgcode); static void process_subcommands_now(char * gcode); - static inline void home_all_axes() { - extern const char G28_STR[]; - process_subcommands_now_P(G28_STR); + static inline void home_all_axes(const bool keep_leveling=false) { + process_subcommands_now_P(keep_leveling ? G28_STR : TERN(CAN_SET_LEVELING_AFTER_G28, PSTR("G28L0"), G28_STR)); } #if EITHER(HAS_AUTO_REPORTING, HOST_KEEPALIVE_FEATURE) @@ -399,6 +425,7 @@ class GcodeSuite { static uint8_t host_keepalive_interval; static void host_keepalive(); + static inline bool host_keepalive_is_paused() { return busy_state >= PAUSED_FOR_USER; } #define KEEPALIVE_STATE(N) REMEMBER(_KA_, gcode.busy_state, gcode.N) #else @@ -409,24 +436,34 @@ class GcodeSuite { private: - TERN_(MARLIN_DEV_MODE, static void D(const int16_t dcode)); + #if ENABLED(MARLIN_DEV_MODE) + static void D(const int16_t dcode); + #endif static void G0_G1(TERN_(HAS_FAST_MOVES, const bool fast_move=false)); - TERN_(ARC_SUPPORT, static void G2_G3(const bool clockwise)); + #if ENABLED(ARC_SUPPORT) + static void G2_G3(const bool clockwise); + #endif static void G4(); - TERN_(BEZIER_CURVE_SUPPORT, static void G5()); + #if ENABLED(BEZIER_CURVE_SUPPORT) + static void G5(); + #endif - TERN_(DIRECT_STEPPING, static void G6()); + #if ENABLED(DIRECT_STEPPING) + static void G6(); + #endif #if ENABLED(FWRETRACT) static void G10(); static void G11(); #endif - TERN_(NOZZLE_CLEAN_FEATURE, static void G12()); + #if ENABLED(NOZZLE_CLEAN_FEATURE) + static void G12(); + #endif #if ENABLED(CNC_WORKSPACE_PLANES) static void G17(); @@ -439,14 +476,20 @@ class GcodeSuite { static void G21(); #endif - TERN_(G26_MESH_VALIDATION, static void G26()); + #if ENABLED(G26_MESH_VALIDATION) + static void G26(); + #endif - TERN_(NOZZLE_PARK_FEATURE, static void G27()); + #if ENABLED(NOZZLE_PARK_FEATURE) + static void G27(); + #endif static void G28(); #if HAS_LEVELING #if ENABLED(G29_RETRY_AND_RECOVER) + static void event_probe_failure(); + static void event_probe_recover(); static void G29_with_retry(); #define G29_TYPE bool #else @@ -463,19 +506,29 @@ class GcodeSuite { #endif #endif - TERN_(DELTA_AUTO_CALIBRATION, static void G33()); + #if ENABLED(DELTA_AUTO_CALIBRATION) + static void G33(); + #endif - #if EITHER(Z_STEPPER_AUTO_ALIGN, MECHANICAL_GANTRY_CALIBRATION) + #if ANY(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN, MECHANICAL_GANTRY_CALIBRATION) static void G34(); #endif - TERN_(Z_STEPPER_AUTO_ALIGN, static void M422()); + #if ENABLED(Z_STEPPER_AUTO_ALIGN) + static void M422(); + #endif - TERN_(ASSISTED_TRAMMING, static void G35()); + #if ENABLED(ASSISTED_TRAMMING) + static void G35(); + #endif - TERN_(G38_PROBE_TARGET, static void G38(const int8_t subcode)); + #if ENABLED(G38_PROBE_TARGET) + static void G38(const int8_t subcode); + #endif - TERN_(HAS_MESH, static void G42()); + #if HAS_MESH + static void G42(); + #endif #if ENABLED(CNC_COORDINATE_SYSTEMS) static void G53(); @@ -487,35 +540,58 @@ class GcodeSuite { static void G59(); #endif - TERN_(PROBE_TEMP_COMPENSATION, static void G76()); + #if ENABLED(PROBE_TEMP_COMPENSATION) + static void G76(); + #endif #if SAVED_POSITIONS static void G60(); static void G61(); #endif - TERN_(GCODE_MOTION_MODES, static void G80()); + #if ENABLED(GCODE_MOTION_MODES) + static void G80(); + #endif static void G92(); - TERN_(CALIBRATION_GCODE, static void G425()); + #if ENABLED(CALIBRATION_GCODE) + static void G425(); + #endif - TERN_(HAS_RESUME_CONTINUE, static void M0_M1()); + #if HAS_RESUME_CONTINUE + static void M0_M1(); + #endif #if HAS_CUTTER static void M3_M4(const bool is_M4); static void M5(); #endif - #if ENABLED(COOLANT_CONTROL) - TERN_(COOLANT_MIST, static void M7()); - TERN_(COOLANT_FLOOD, static void M8()); + #if ENABLED(COOLANT_MIST) + static void M7(); + #endif + + #if EITHER(AIR_ASSIST, COOLANT_FLOOD) + static void M8(); + #endif + + #if EITHER(AIR_ASSIST, COOLANT_CONTROL) static void M9(); #endif - TERN_(EXTERNAL_CLOSED_LOOP_CONTROLLER, static void M12()); + #if ENABLED(AIR_EVACUATION) + static void M10(); + static void M11(); + #endif + + #if ENABLED(EXTERNAL_CLOSED_LOOP_CONTROLLER) + static void M12(); + #endif - TERN_(EXPECTED_PRINTER_CHECK, static void M16()); + #if ENABLED(EXPECTED_PRINTER_CHECK) + static void M16(); + #endif static void M17(); @@ -538,39 +614,61 @@ class GcodeSuite { static void M31(); #if ENABLED(SDSUPPORT) - static void M32(); - TERN_(LONG_FILENAME_HOST_SUPPORT, static void M33()); + #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) static void M34(); #endif #endif - TERN_(DIRECT_PIN_CONTROL, static void M42()); - TERN_(PINS_DEBUGGING, static void M43()); + #if ENABLED(DIRECT_PIN_CONTROL) + static void M42(); + #endif + #if ENABLED(PINS_DEBUGGING) + static void M43(); + #endif - TERN_(Z_MIN_PROBE_REPEATABILITY_TEST, static void M48()); + #if ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST) + static void M48(); + #endif - TERN_(LCD_SET_PROGRESS_MANUALLY, static void M73()); + #if ENABLED(LCD_SET_PROGRESS_MANUALLY) + static void M73(); + #endif static void M75(); static void M76(); static void M77(); - TERN_(PRINTCOUNTER, static void M78()); - - TERN_(PSU_CONTROL, static void M80()); + #if ENABLED(PRINTCOUNTER) + static void M78(); + #endif + #if ENABLED(PSU_CONTROL) + static void M80(); + #endif static void M81(); - static void M82(); - static void M83(); + + #if HAS_EXTRUDERS + static void M82(); + static void M83(); + #endif + static void M85(); static void M92(); - TERN_(M100_FREE_MEMORY_WATCHER, static void M100()); + #if ENABLED(M100_FREE_MEMORY_WATCHER) + static void M100(); + #endif - #if EXTRUDERS - static void M104(); - static void M109(); + #if HAS_EXTRUDERS + static void M104_M109(const bool isM109); + FORCE_INLINE static void M104() { M104_M109(false); } + FORCE_INLINE static void M109() { M104_M109(true); } #endif static void M105(); @@ -584,23 +682,33 @@ class GcodeSuite { static void M108(); static void M112(); static void M410(); - TERN_(HOST_PROMPT_SUPPORT, static void M876()); + #if ENABLED(HOST_PROMPT_SUPPORT) + static void M876(); + #endif #endif static void M110(); static void M111(); - TERN_(HOST_KEEPALIVE_FEATURE, static void M113()); + #if ENABLED(HOST_KEEPALIVE_FEATURE) + static void M113(); + #endif static void M114(); static void M115(); - static void M117(); + + #if HAS_STATUS_MESSAGE + static void M117(); + #endif + static void M118(); static void M119(); static void M120(); static void M121(); - TERN_(PARK_HEAD_ON_PAUSE, static void M125()); + #if ENABLED(PARK_HEAD_ON_PAUSE) + static void M125(); + #endif #if ENABLED(BARICUDA) #if HAS_HEATER_1 @@ -614,8 +722,9 @@ class GcodeSuite { #endif #if HAS_HEATED_BED - static void M140(); - static void M190(); + static void M140_M190(const bool isM190); + FORCE_INLINE static void M140() { M140_M190(false); } + FORCE_INLINE static void M190() { M140_M190(true); } #endif #if HAS_HEATED_CHAMBER @@ -623,13 +732,26 @@ class GcodeSuite { static void M191(); #endif + #if HAS_COOLER + static void M143(); + static void M193(); + #endif + #if PREHEAT_COUNT static void M145(); #endif - TERN_(TEMPERATURE_UNITS_SUPPORT, static void M149()); + #if ENABLED(TEMPERATURE_UNITS_SUPPORT) + static void M149(); + #endif - TERN_(HAS_COLOR_LEDS, static void M150()); + #if HAS_COLOR_LEDS + static void M150(); + #endif + + #if ENABLED(AUTO_REPORT_POSITION) + static void M154(); + #endif #if BOTH(AUTO_REPORT_TEMPERATURES, HAS_TEMP_SENSOR) static void M155(); @@ -638,8 +760,12 @@ class GcodeSuite { #if ENABLED(MIXING_EXTRUDER) static void M163(); static void M164(); - TERN_(DIRECT_MIXING_IN_G1, static void M165()); - TERN_(GRADIENT_MIX, static void M166()); + #if ENABLED(DIRECT_MIXING_IN_G1) + static void M165(); + #endif + #if ENABLED(GRADIENT_MIX) + static void M166(); + #endif #endif static void M200(); @@ -653,31 +779,49 @@ class GcodeSuite { static void M204(); static void M205(); - TERN_(HAS_M206_COMMAND, static void M206()); + #if HAS_M206_COMMAND + static void M206(); + #endif #if ENABLED(FWRETRACT) static void M207(); static void M208(); - TERN_(FWRETRACT_AUTORETRACT, static void M209()); + #if ENABLED(FWRETRACT_AUTORETRACT) + static void M209(); + #endif #endif static void M211(); - TERN_(HAS_MULTI_EXTRUDER, static void M217()); + #if HAS_MULTI_EXTRUDER + static void M217(); + #endif - TERN_(HAS_HOTEND_OFFSET, static void M218()); + #if HAS_HOTEND_OFFSET + static void M218(); + #endif static void M220(); - #if EXTRUDERS + #if HAS_EXTRUDERS static void M221(); #endif - TERN_(DIRECT_PIN_CONTROL, static void M226()); + #if ENABLED(DIRECT_PIN_CONTROL) + static void M226(); + #endif + + #if ENABLED(PHOTO_GCODE) + static void M240(); + #endif - TERN_(PHOTO_GCODE, static void M240()); + #if HAS_LCD_CONTRAST + static void M250(); + #endif - TERN_(HAS_LCD_CONTRAST, static void M250()); + #if HAS_LCD_BRIGHTNESS + static void M256(); + #endif #if ENABLED(EXPERIMENTAL_I2CBUS) static void M260(); @@ -686,31 +830,55 @@ class GcodeSuite { #if HAS_SERVOS static void M280(); - TERN_(EDITABLE_SERVO_ANGLES, static void M281()); + #if ENABLED(EDITABLE_SERVO_ANGLES) + static void M281(); + #endif #endif - TERN_(BABYSTEPPING, static void M290()); + #if ENABLED(BABYSTEPPING) + static void M290(); + #endif - TERN_(HAS_BUZZER, static void M300()); + #if HAS_BUZZER + static void M300(); + #endif - TERN_(PIDTEMP, static void M301()); + #if ENABLED(PIDTEMP) + static void M301(); + #endif - TERN_(PREVENT_COLD_EXTRUSION, static void M302()); + #if ENABLED(PREVENT_COLD_EXTRUSION) + static void M302(); + #endif - TERN_(HAS_PID_HEATING, static void M303()); + #if HAS_PID_HEATING + static void M303(); + #endif - TERN_(PIDTEMPBED, static void M304()); + #if ENABLED(PIDTEMPBED) + static void M304(); + #endif + + #if HAS_USER_THERMISTORS + static void M305(); + #endif - TERN_(HAS_USER_THERMISTORS, static void M305()); + #if ENABLED(PIDTEMPCHAMBER) + static void M309(); + #endif #if HAS_MICROSTEPS static void M350(); static void M351(); #endif - TERN_(CASE_LIGHT_ENABLE, static void M355()); + #if ENABLED(CASE_LIGHT_ENABLE) + static void M355(); + #endif - TERN_(REPETIER_GCODE_M360, static void M360()); + #if ENABLED(REPETIER_GCODE_M360) + static void M360(); + #endif #if ENABLED(MORGAN_SCARA) static bool M360(); @@ -732,7 +900,9 @@ class GcodeSuite { static void M402(); #endif - TERN_(PRUSA_MMU2, static void M403()); + #if HAS_PRUSA_MMU2 + static void M403(); + #endif #if ENABLED(FILAMENT_WIDTH_SENSOR) static void M404(); @@ -741,20 +911,34 @@ class GcodeSuite { static void M407(); #endif - TERN_(HAS_FILAMENT_SENSOR, static void M412()); + #if HAS_FILAMENT_SENSOR + static void M412(); + #endif + + #if HAS_MULTI_LANGUAGE + static void M414(); + #endif #if HAS_LEVELING static void M420(); static void M421(); #endif - TERN_(BACKLASH_GCODE, static void M425()); + #if ENABLED(BACKLASH_GCODE) + static void M425(); + #endif - TERN_(HAS_M206_COMMAND, static void M428()); + #if HAS_M206_COMMAND + static void M428(); + #endif - TERN_(HAS_POWER_MONITOR, static void M430()); + #if HAS_POWER_MONITOR + static void M430(); + #endif - TERN_(CANCEL_OBJECTS, static void M486()); + #if ENABLED(CANCEL_OBJECTS) + static void M486(); + #endif static void M500(); static void M501(); @@ -762,7 +946,9 @@ class GcodeSuite { #if DISABLED(DISABLE_M503) static void M503(); #endif - TERN_(EEPROM_SETTINGS, static void M504()); + #if ENABLED(EEPROM_SETTINGS) + static void M504(); + #endif #if ENABLED(PASSWORD_FEATURE) static void M510(); @@ -774,20 +960,36 @@ class GcodeSuite { #endif #endif - TERN_(SDSUPPORT, static void M524()); + #if ENABLED(SDSUPPORT) + static void M524(); + #endif + + #if ENABLED(SD_ABORT_ON_ENDSTOP_HIT) + static void M540(); + #endif - TERN_(SD_ABORT_ON_ENDSTOP_HIT, static void M540()); + #if HAS_ETHERNET + static void M552(); + static void M553(); + static void M554(); + #endif - TERN_(BAUD_RATE_GCODE, static void M575()); + #if ENABLED(BAUD_RATE_GCODE) + static void M575(); + #endif #if ENABLED(ADVANCED_PAUSE_FEATURE) static void M600(); static void M603(); #endif - TERN_(HAS_DUPLICATION_MODE, static void M605()); + #if HAS_DUPLICATION_MODE + static void M605(); + #endif - TERN_(IS_KINEMATIC, static void M665()); + #if IS_KINEMATIC + static void M665(); + #endif #if ENABLED(DELTA) || HAS_EXTRA_ENDSTOPS static void M666(); @@ -802,11 +1004,21 @@ class GcodeSuite { static void M702(); #endif - TERN_(GCODE_MACROS, static void M810_819()); + #if ENABLED(GCODE_REPEAT_MARKERS) + static void M808(); + #endif + + #if ENABLED(GCODE_MACROS) + static void M810_819(); + #endif - TERN_(HAS_BED_PROBE, static void M851()); + #if HAS_BED_PROBE + static void M851(); + #endif - TERN_(SKEW_CORRECTION_GCODE, static void M852()); + #if ENABLED(SKEW_CORRECTION_GCODE) + static void M852(); + #endif #if ENABLED(I2C_POSITION_ENCODERS) FORCE_INLINE static void M860() { I2CPEM.M860(); } @@ -826,18 +1038,26 @@ class GcodeSuite { static void M871(); #endif - TERN_(LIN_ADVANCE, static void M900()); + #if ENABLED(LIN_ADVANCE) + static void M900(); + #endif #if HAS_TRINAMIC_CONFIG static void M122(); static void M906(); - TERN_(HAS_STEALTHCHOP, static void M569()); + #if HAS_STEALTHCHOP + static void M569(); + #endif #if ENABLED(MONITOR_DRIVER_STATUS) static void M911(); static void M912(); #endif - TERN_(HYBRID_THRESHOLD, static void M913()); - TERN_(USE_SENSORLESS, static void M914()); + #if ENABLED(HYBRID_THRESHOLD) + static void M913(); + #endif + #if ENABLED(USE_SENSORLESS) + static void M914(); + #endif #endif #if HAS_L64XX @@ -852,25 +1072,33 @@ class GcodeSuite { static void M907(); #if EITHER(HAS_MOTOR_CURRENT_SPI, HAS_MOTOR_CURRENT_DAC) static void M908(); - #if ENABLED(HAS_MOTOR_CURRENT_DAC) + #if HAS_MOTOR_CURRENT_DAC static void M909(); static void M910(); #endif #endif #endif - TERN_(SDSUPPORT, static void M928()); + #if ENABLED(SDSUPPORT) + static void M928(); + #endif - TERN_(MAGNETIC_PARKING_EXTRUDER, static void M951()); + #if ENABLED(MAGNETIC_PARKING_EXTRUDER) + static void M951(); + #endif - TERN_(TOUCH_SCREEN_CALIBRATION, static void M995()); + #if ENABLED(TOUCH_SCREEN_CALIBRATION) + static void M995(); + #endif #if BOTH(HAS_SPI_FLASH, SDSUPPORT) static void M993(); static void M994(); #endif - TERN_(PLATFORM_M997_SUPPORT, static void M997()); + #if ENABLED(PLATFORM_M997_SUPPORT) + static void M997(); + #endif static void M999(); @@ -879,11 +1107,25 @@ class GcodeSuite { static void M1000(); #endif - TERN_(SDSUPPORT, static void M1001()); + #if ENABLED(SDSUPPORT) + static void M1001(); + #endif + + #if ENABLED(DGUS_LCD_UI_MKS) + static void M1002(); + #endif - TERN_(MAX7219_GCODE, static void M7219()); + #if ENABLED(UBL_MESH_WIZARD) + static void M1004(); + #endif - TERN_(CONTROLLER_FAN_EDITABLE, static void M710()); + #if ENABLED(MAX7219_GCODE) + static void M7219(); + #endif + + #if ENABLED(CONTROLLER_FAN_EDITABLE) + static void M710(); + #endif static void T(const int8_t tool_index); diff --git a/Marlin/src/gcode/gcode_d.cpp b/Marlin/src/gcode/gcode_d.cpp index 1f38a85b9135..52a273964a81 100644 --- a/Marlin/src/gcode/gcode_d.cpp +++ b/Marlin/src/gcode/gcode_d.cpp @@ -29,6 +29,10 @@ #include "../libs/hex_print.h" #include "../HAL/shared/eeprom_if.h" #include "../HAL/shared/Delay.h" + #include "../sd/cardreader.h" + #include "../MarlinCore.h" // for kill + + extern void dump_delay_accuracy_check(); /** * Dn: G-code for development and testing @@ -41,12 +45,16 @@ switch (dcode) { case -1: - for (;;); // forever + for (;;) { /* loop forever (watchdog reset) */ } case 0: HAL_reboot(); break; + case 10: + kill(PSTR("D10"), PSTR("KILL TEST"), parser.seen_test('P')); + break; + case 1: { // Zero or pattern-fill the EEPROM data #if ENABLED(EEPROM_SETTINGS) @@ -54,9 +62,7 @@ size_t total = persistentStore.capacity(); int pos = 0; const uint8_t value = 0x0; - while(total--) { - persistentStore.write_data(pos, &value, 1); - } + while (total--) persistentStore.write_data(pos, &value, 1); persistentStore.access_finish(); #else settings.reset(); @@ -70,7 +76,7 @@ uint8_t *pointer = parser.hex_adr_val('A'); uint16_t len = parser.ushortval('C', 1); uintptr_t addr = (uintptr_t)pointer; - NOMORE(addr, (size_t)(SRAM_SIZE - 1)); + NOMORE(addr, size_t(SRAM_SIZE - 1)); NOMORE(len, SRAM_SIZE - addr); if (parser.seenval('X')) { // Write the hex bytes after the X @@ -91,100 +97,173 @@ uint8_t *pointer = parser.hex_adr_val('A'); uint16_t len = parser.ushortval('C', 1); uintptr_t addr = (uintptr_t)pointer; - #ifndef MARLIN_EEPROM_SIZE - #define MARLIN_EEPROM_SIZE size_t(E2END + 1) - #endif - NOMORE(addr, (size_t)(MARLIN_EEPROM_SIZE - 1)); - NOMORE(len, MARLIN_EEPROM_SIZE - addr); + NOMORE(addr, size_t(persistentStore.capacity() - 1)); + NOMORE(len, persistentStore.capacity() - addr); if (parser.seenval('X')) { uint16_t val = parser.hex_val('X'); #if ENABLED(EEPROM_SETTINGS) persistentStore.access_start(); - while(len--) { + while (len--) { int pos = 0; persistentStore.write_data(pos, (uint8_t *)&val, sizeof(val)); } SERIAL_EOL(); persistentStore.access_finish(); #else - SERIAL_ECHOLN("NO EEPROM"); + SERIAL_ECHOLNPGM("NO EEPROM"); #endif } else { - while (len--) { - // Read bytes from EEPROM - #if ENABLED(EEPROM_SETTINGS) - persistentStore.access_start(); - uint8_t val; - while(len--) { - int pos = 0; - if (!persistentStore.read_data(pos, (uint8_t *)&val, sizeof(val))) { - print_hex_byte(val); - } - } - SERIAL_EOL(); - persistentStore.access_finish(); - #else - SERIAL_ECHOLN("NO EEPROM"); - #endif - } + // Read bytes from EEPROM + #if ENABLED(EEPROM_SETTINGS) + persistentStore.access_start(); + int pos = 0; + uint8_t val; + while (len--) if (!persistentStore.read_data(pos, &val, 1)) print_hex_byte(val); + SERIAL_EOL(); + persistentStore.access_finish(); + #else + SERIAL_ECHOLNPGM("NO EEPROM"); + len = 0; + #endif SERIAL_EOL(); } } break; - #endif + #endif case 4: { // D4 Read / Write PIN - // const uint8_t pin = parser.byteval('P'); - // const bool is_out = parser.boolval('F'), - // val = parser.byteval('V', LOW); + //const bool is_out = parser.boolval('F'); + //const uint8_t pin = parser.byteval('P'), + // val = parser.byteval('V', LOW); if (parser.seenval('X')) { // TODO: Write the hex bytes after the X //while (len--) { //} } else { - // while (len--) { - // TODO: Read bytes from EEPROM - // print_hex_byte(eeprom_read_byte(*(adr++)); - // } + //while (len--) { + //// TODO: Read bytes from EEPROM + // print_hex_byte(eeprom_read_byte(adr++)); + //} SERIAL_EOL(); } } break; - case 5: { // D4 Read / Write onboard Flash + case 5: { // D5 Read / Write onboard Flash #define FLASH_SIZE 1024 uint8_t *pointer = parser.hex_adr_val('A'); uint16_t len = parser.ushortval('C', 1); uintptr_t addr = (uintptr_t)pointer; - NOMORE(addr, (size_t)(FLASH_SIZE - 1)); + NOMORE(addr, size_t(FLASH_SIZE - 1)); NOMORE(len, FLASH_SIZE - addr); if (parser.seenval('X')) { // TODO: Write the hex bytes after the X - //while (len--) { - //} + //while (len--) {} } else { - // while (len--) { - // TODO: Read bytes from EEPROM - // print_hex_byte(eeprom_read_byte(adr++)); - // } + //while (len--) { + //// TODO: Read bytes from EEPROM + // print_hex_byte(eeprom_read_byte(adr++)); + //} SERIAL_EOL(); } } break; + case 6: // D6 Check delay loop accuracy + dump_delay_accuracy_check(); + break; + + case 7: // D7 dump the current serial port type (hence configuration) + SERIAL_ECHOLNPAIR("Current serial configuration RX_BS:", RX_BUFFER_SIZE, ", TX_BS:", TX_BUFFER_SIZE); + SERIAL_ECHOLN(gtn(&SERIAL_IMPL)); + break; + case 100: { // D100 Disable heaters and attempt a hard hang (Watchdog Test) - SERIAL_ECHOLN("Disabling heaters and attempting to trigger Watchdog"); - SERIAL_ECHOLN("(USE_WATCHDOG " TERN(USE_WATCHDOG, "ENABLED", "DISABLED") ")"); + SERIAL_ECHOLNPGM("Disabling heaters and attempting to trigger Watchdog"); + SERIAL_ECHOLNPGM("(USE_WATCHDOG " TERN(USE_WATCHDOG, "ENABLED", "DISABLED") ")"); thermalManager.disable_all_heaters(); delay(1000); // Allow time to print DISABLE_ISRS(); // Use a low-level delay that does not rely on interrupts to function // Do not spin forever, to avoid thermal risks if heaters are enabled and // watchdog does not work. - DELAY_US(10000000); + for (int i = 10000; i--;) DELAY_US(1000UL); ENABLE_ISRS(); - SERIAL_ECHOLN("FAILURE: Watchdog did not trigger board reset."); - } + SERIAL_ECHOLNPGM("FAILURE: Watchdog did not trigger board reset."); + } break; + + #if ENABLED(SDSUPPORT) + + case 101: { // D101 Test SD Write + card.openFileWrite("test.gco"); + if (!card.isFileOpen()) { + SERIAL_ECHOLNPAIR("Failed to open test.gco to write."); + return; + } + __attribute__((aligned(sizeof(size_t)))) uint8_t buf[512]; + + uint16_t c; + for (c = 0; c < COUNT(buf); c++) + buf[c] = 'A' + (c % ('Z' - 'A')); + + c = 1024 * 4; + while (c--) { + TERN_(USE_WATCHDOG, watchdog_refresh()); + card.write(buf, COUNT(buf)); + } + SERIAL_ECHOLNPGM(" done"); + card.closefile(); + } break; + + case 102: { // D102 Test SD Read + char testfile[] = "test.gco"; + card.openFileRead(testfile); + if (!card.isFileOpen()) { + SERIAL_ECHOLNPAIR("Failed to open test.gco to read."); + return; + } + __attribute__((aligned(sizeof(size_t)))) uint8_t buf[512]; + uint16_t c = 1024 * 4; + while (c--) { + TERN_(USE_WATCHDOG, watchdog_refresh()); + card.read(buf, COUNT(buf)); + bool error = false; + for (uint16_t i = 0; i < COUNT(buf); i++) { + if (buf[i] != ('A' + (i % ('Z' - 'A')))) { + error = true; + break; + } + } + if (error) { + SERIAL_ECHOLNPGM(" Read error!"); + break; + } + } + SERIAL_ECHOLNPGM(" done"); + card.closefile(); + } break; + + #endif // SDSUPPORT + + #if ENABLED(POSTMORTEM_DEBUGGING) + + case 451: { // Trigger all kind of faults to test exception catcher + SERIAL_ECHOLNPGM("Disabling heaters"); + thermalManager.disable_all_heaters(); + delay(1000); // Allow time to print + volatile uint8_t type[5] = { parser.byteval('T', 1) }; + + // The code below is obviously wrong and it's full of quirks to fool the compiler from optimizing away the code + switch (type[0]) { + case 1: default: *(int*)0 = 451; break; // Write at bad address + case 2: { volatile int a = 0; volatile int b = 452 / a; *(int*)&a = b; } break; // Divide by zero (some CPUs accept this, like ARM) + case 3: { *(uint32_t*)&type[1] = 453; volatile int a = *(int*)&type[1]; type[0] = a / 255; } break; // Unaligned access (some CPUs accept this) + case 4: { volatile void (*func)() = (volatile void (*)()) 0xE0000000; func(); } break; // Invalid instruction + } + break; + } + + #endif } } diff --git a/Marlin/src/gcode/geometry/G17-G19.cpp b/Marlin/src/gcode/geometry/G17-G19.cpp index 7510eaba8c3d..0154598ccb22 100644 --- a/Marlin/src/gcode/geometry/G17-G19.cpp +++ b/Marlin/src/gcode/geometry/G17-G19.cpp @@ -29,7 +29,7 @@ inline void report_workspace_plane() { SERIAL_ECHO_START(); SERIAL_ECHOPGM("Workspace Plane "); - serialprintPGM( + SERIAL_ECHOPGM_P( gcode.workspace_plane == GcodeSuite::PLANE_YZ ? PSTR("YZ\n") : gcode.workspace_plane == GcodeSuite::PLANE_ZX ? PSTR("ZX\n") : PSTR("XY\n") diff --git a/Marlin/src/gcode/geometry/G53-G59.cpp b/Marlin/src/gcode/geometry/G53-G59.cpp index 05bc522768a2..a5a9f70a8b61 100644 --- a/Marlin/src/gcode/geometry/G53-G59.cpp +++ b/Marlin/src/gcode/geometry/G53-G59.cpp @@ -39,7 +39,7 @@ bool GcodeSuite::select_coordinate_system(const int8_t _new) { xyz_float_t new_offset{0}; if (WITHIN(_new, 0, MAX_COORDINATE_SYSTEMS - 1)) new_offset = coordinate_system[_new]; - LOOP_XYZ(i) { + LOOP_LINEAR_AXES(i) { if (position_shift[i] != new_offset[i]) { position_shift[i] = new_offset[i]; update_workspace_offset((AxisEnum)i); diff --git a/Marlin/src/gcode/geometry/G92.cpp b/Marlin/src/gcode/geometry/G92.cpp index 1a0382ed7c2b..990236c0e878 100644 --- a/Marlin/src/gcode/geometry/G92.cpp +++ b/Marlin/src/gcode/geometry/G92.cpp @@ -29,77 +29,105 @@ #endif /** - * G92: Set current position to given X Y Z E + * G92: Set the Current Position to the given X Y Z E values. + * + * Behind the scenes the G92 command may modify the Current Position + * or the Position Shift depending on settings and sub-commands. + * + * Since E has no Workspace Offset, it is always set directly. + * + * Without Workspace Offsets (e.g., with NO_WORKSPACE_OFFSETS): + * G92 : Set NATIVE Current Position to the given X Y Z E. + * + * Using Workspace Offsets (default Marlin behavior): + * G92 : Modify Workspace Offsets so the reported position shows the given X Y Z E. + * G92.1 : Zero XYZ Workspace Offsets (so the reported position = the native position). + * + * With POWER_LOSS_RECOVERY: + * G92.9 : Set NATIVE Current Position to the given X Y Z E. */ void GcodeSuite::G92() { - bool sync_E = false, sync_XYZ = false; + #if HAS_EXTRUDERS + bool sync_E = false; + #endif + bool sync_XYZE = false; - #if ENABLED(USE_GCODE_SUBCODES) + #if USE_GCODE_SUBCODES const uint8_t subcode_G92 = parser.subcode; #else constexpr uint8_t subcode_G92 = 0; #endif switch (subcode_G92) { - default: break; - #if ENABLED(CNC_COORDINATE_SYSTEMS) - case 1: { - // Zero the G92 values and restore current position - #if !IS_SCARA - LOOP_XYZ(i) if (position_shift[i]) { - position_shift[i] = 0; - update_workspace_offset((AxisEnum)i); - } - #endif // Not SCARA - } return; + default: return; // Ignore unknown G92.x + + #if ENABLED(CNC_COORDINATE_SYSTEMS) && !IS_SCARA + case 1: // G92.1 - Zero the Workspace Offset + LOOP_LINEAR_AXES(i) if (position_shift[i]) { + position_shift[i] = 0; + update_workspace_offset((AxisEnum)i); + } + break; #endif + #if ENABLED(POWER_LOSS_RECOVERY) - case 9: { - LOOP_XYZE(i) { + case 9: // G92.9 - Set Current Position directly (like Marlin 1.0) + LOOP_LOGICAL_AXES(i) { if (parser.seenval(axis_codes[i])) { + if (TERN1(HAS_EXTRUDERS, i != E_AXIS)) + sync_XYZE = true; + else { + TERN_(HAS_EXTRUDERS, sync_E = true); + } current_position[i] = parser.value_axis_units((AxisEnum)i); - if (i == E_AXIS) sync_E = true; else sync_XYZ = true; } } - } break; + break; #endif - case 0: { - LOOP_XYZE(i) { + + case 0: + LOOP_LOGICAL_AXES(i) { if (parser.seenval(axis_codes[i])) { - const float l = parser.value_axis_units((AxisEnum)i), - v = i == E_AXIS ? l : LOGICAL_TO_NATIVE(l, i), - d = v - current_position[i]; + 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? if (!NEAR_ZERO(d)) { - #if IS_SCARA || !HAS_POSITION_SHIFT - if (i == E_AXIS) sync_E = true; else sync_XYZ = true; - current_position[i] = v; // Without workspaces revert to Marlin 1.0 behavior - #elif HAS_POSITION_SHIFT - if (i == E_AXIS) { - sync_E = true; - current_position.e = v; // When using coordinate spaces, only E is set directly + #if HAS_POSITION_SHIFT && !IS_SCARA // When using workspaces... + if (TERN1(HAS_EXTRUDERS, i != E_AXIS)) { + position_shift[i] += d; // ...most axes offset the workspace... + update_workspace_offset((AxisEnum)i); } else { - position_shift[i] += d; // Other axes simply offset the coordinate space - update_workspace_offset((AxisEnum)i); + #if HAS_EXTRUDERS + sync_E = true; + current_position.e = v; // ...but E is set directly + #endif } + #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) #endif } } } - } break; + break; } #if ENABLED(CNC_COORDINATE_SYSTEMS) - // Apply workspace offset to the active coordinate system + // Apply Workspace Offset to the active coordinate system if (WITHIN(active_coordinate_system, 0, MAX_COORDINATE_SYSTEMS - 1)) coordinate_system[active_coordinate_system] = position_shift; #endif - if (sync_XYZ) sync_plan_position(); - else if (sync_E) sync_plan_position_e(); - - #if DISABLED(DIRECT_STEPPING) - report_current_position(); + if (sync_XYZE) sync_plan_position(); + #if HAS_EXTRUDERS + else if (sync_E) sync_plan_position_e(); #endif + + IF_DISABLED(DIRECT_STEPPING, report_current_position()); } diff --git a/Marlin/src/gcode/geometry/M206_M428.cpp b/Marlin/src/gcode/geometry/M206_M428.cpp index a477a1a526ef..51f3e7c14c04 100644 --- a/Marlin/src/gcode/geometry/M206_M428.cpp +++ b/Marlin/src/gcode/geometry/M206_M428.cpp @@ -26,8 +26,22 @@ #include "../gcode.h" #include "../../module/motion.h" -#include "../../lcd/ultralcd.h" +#include "../../lcd/marlinui.h" #include "../../libs/buzzer.h" +#include "../../MarlinCore.h" + +void M206_report() { + SERIAL_ECHOLNPAIR_P( + LIST_N(DOUBLE(LINEAR_AXES), + PSTR("M206 X"), home_offset.x, + SP_Y_STR, home_offset.y, + SP_Z_STR, home_offset.z, + SP_I_STR, home_offset.i, + SP_J_STR, home_offset.j, + SP_K_STR, home_offset.k, + ) + ); +} /** * M206: Set Additional Homing Offset (X Y Z). SCARA aliases T=X, P=Y @@ -37,8 +51,8 @@ * *** In the 2.0 release, it will simply be disabled by default. */ void GcodeSuite::M206() { - LOOP_XYZ(i) - if (parser.seen(XYZ_CHAR(i))) + LOOP_LINEAR_AXES(i) + if (parser.seen(AXIS_CHAR(i))) set_home_offset((AxisEnum)i, parser.value_linear_units()); #if ENABLED(MORGAN_SCARA) @@ -46,7 +60,10 @@ void GcodeSuite::M206() { if (parser.seen('P')) set_home_offset(B_AXIS, parser.value_float()); // Psi #endif - report_current_position(); + if (!parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z", "I", "J", "K"))) + M206_report(); + else + report_current_position(); } /** @@ -64,7 +81,7 @@ void GcodeSuite::M428() { if (homing_needed_error()) return; xyz_float_t diff; - LOOP_XYZ(i) { + LOOP_LINEAR_AXES(i) { diff[i] = base_home_pos((AxisEnum)i) - current_position[i]; if (!WITHIN(diff[i], -20, 20) && home_dir((AxisEnum)i) > 0) diff[i] = -current_position[i]; @@ -76,7 +93,7 @@ void GcodeSuite::M428() { } } - LOOP_XYZ(i) set_home_offset((AxisEnum)i, diff[i]); + LOOP_LINEAR_AXES(i) set_home_offset((AxisEnum)i, diff[i]); report_current_position(); LCD_MESSAGEPGM(MSG_HOME_OFFSETS_APPLIED); BUZZ(100, 659); diff --git a/Marlin/src/gcode/host/M110.cpp b/Marlin/src/gcode/host/M110.cpp index b12b38ea0f12..2634b198978d 100644 --- a/Marlin/src/gcode/host/M110.cpp +++ b/Marlin/src/gcode/host/M110.cpp @@ -29,6 +29,6 @@ void GcodeSuite::M110() { if (parser.seenval('N')) - queue.last_N[queue.command_port()] = parser.value_long(); + queue.set_current_line_number(parser.value_long()); } diff --git a/Marlin/src/gcode/host/M113.cpp b/Marlin/src/gcode/host/M113.cpp index ce826d6acde6..ddabcefb1312 100644 --- a/Marlin/src/gcode/host/M113.cpp +++ b/Marlin/src/gcode/host/M113.cpp @@ -32,14 +32,14 @@ * S Optional. Set the keepalive interval. */ void GcodeSuite::M113() { + if (parser.seenval('S')) { host_keepalive_interval = parser.value_byte(); NOMORE(host_keepalive_interval, 60); } - else { - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR("M113 S", (unsigned long)host_keepalive_interval); - } + else + SERIAL_ECHO_MSG("M113 S", host_keepalive_interval); + } #endif // HOST_KEEPALIVE_FEATURE diff --git a/Marlin/src/gcode/host/M114.cpp b/Marlin/src/gcode/host/M114.cpp index 85a38f6462a8..7d69033319b7 100644 --- a/Marlin/src/gcode/host/M114.cpp +++ b/Marlin/src/gcode/host/M114.cpp @@ -34,7 +34,7 @@ #include "../../core/debug_out.h" #endif - void report_xyze(const xyze_pos_t &pos, const uint8_t n=XYZE, const uint8_t precision=3) { + void report_all_axis_pos(const xyze_pos_t &pos, const uint8_t n=XYZE, const uint8_t precision=3) { char str[12]; LOOP_L_N(a, n) { SERIAL_CHAR(' ', axis_codes[a], ':'); @@ -43,26 +43,25 @@ } SERIAL_EOL(); } - inline void report_xyz(const xyze_pos_t &pos) { report_xyze(pos, XYZ); } + inline void report_linear_axis_pos(const xyze_pos_t &pos) { report_all_axis_pos(pos, XYZ); } - void report_xyz(const xyz_pos_t &pos, const uint8_t precision=3) { + void report_linear_axis_pos(const xyz_pos_t &pos, const uint8_t precision=3) { char str[12]; - LOOP_XYZ(a) { - SERIAL_CHAR(' ', XYZ_CHAR(a), ':'); + LOOP_LINEAR_AXES(a) { + SERIAL_CHAR(' ', AXIS_CHAR(a), ':'); SERIAL_ECHO(dtostrf(pos[a], 1, precision, str)); } SERIAL_EOL(); } void report_current_position_detail() { - // Position as sent by G-code SERIAL_ECHOPGM("\nLogical:"); - report_xyz(current_position.asLogical()); + report_linear_axis_pos(current_position.asLogical()); // Cartesian position in native machine space SERIAL_ECHOPGM("Raw: "); - report_xyz(current_position); + report_linear_axis_pos(current_position); xyze_pos_t leveled = current_position; @@ -70,24 +69,20 @@ // Current position with leveling applied SERIAL_ECHOPGM("Leveled:"); planner.apply_leveling(leveled); - report_xyz(leveled); + report_linear_axis_pos(leveled); // Test planner un-leveling. This should match the Raw result. SERIAL_ECHOPGM("UnLevel:"); xyze_pos_t unleveled = leveled; planner.unapply_leveling(unleveled); - report_xyz(unleveled); + report_linear_axis_pos(unleveled); #endif #if IS_KINEMATIC // Kinematics applied to the leveled position - #if IS_SCARA - SERIAL_ECHOPGM("ScaraK: "); - #else - SERIAL_ECHOPGM("DeltaK: "); - #endif + SERIAL_ECHOPGM(TERN(IS_SCARA, "ScaraK: ", "DeltaK: ")); inverse_kinematics(leveled); // writes delta[] - report_xyz(delta); + report_linear_axis_pos(delta); #endif planner.synchronize(); @@ -130,6 +125,15 @@ #if AXIS_IS_L64XX(Z4) REPORT_ABSOLUTE_POS(Z4); #endif + #if AXIS_IS_L64XX(I) + REPORT_ABSOLUTE_POS(I); + #endif + #if AXIS_IS_L64XX(J) + REPORT_ABSOLUTE_POS(J); + #endif + #if AXIS_IS_L64XX(K) + REPORT_ABSOLUTE_POS(K); + #endif #if AXIS_IS_L64XX(E0) REPORT_ABSOLUTE_POS(E0); #endif @@ -158,7 +162,7 @@ #endif // HAS_L64XX SERIAL_ECHOPGM("Stepper:"); - LOOP_XYZE(i) { + LOOP_LOGICAL_AXES(i) { SERIAL_CHAR(' ', axis_codes[i], ':'); SERIAL_ECHO(stepper.position((AxisEnum)i)); } @@ -170,17 +174,25 @@ planner.get_axis_position_degrees(B_AXIS) }; SERIAL_ECHOPGM("Degrees:"); - report_xyze(deg, 2); + report_all_axis_pos(deg, 2); #endif SERIAL_ECHOPGM("FromStp:"); get_cartesian_from_steppers(); // writes 'cartes' (with forward kinematics) - xyze_pos_t from_steppers = { cartes.x, cartes.y, cartes.z, planner.get_axis_position_mm(E_AXIS) }; - report_xyze(from_steppers); + xyze_pos_t from_steppers = LOGICAL_AXIS_ARRAY( + planner.get_axis_position_mm(E_AXIS), + cartes.x, cartes.y, cartes.z, + planner.get_axis_position_mm(I_AXIS), + planner.get_axis_position_mm(J_AXIS), + planner.get_axis_position_mm(K_AXIS) + ); + report_all_axis_pos(from_steppers); const xyze_float_t diff = from_steppers - leveled; SERIAL_ECHOPGM("Diff: "); - report_xyze(diff); + report_all_axis_pos(diff); + + TERN_(FULL_REPORT_TO_HOST_FEATURE, report_current_grblstate_moving()); } #endif // M114_DETAIL @@ -196,7 +208,7 @@ void GcodeSuite::M114() { #if ENABLED(M114_DETAIL) - if (parser.seen('D')) { + if (parser.seen_test('D')) { #if DISABLED(M114_LEGACY) planner.synchronize(); #endif @@ -204,16 +216,20 @@ void GcodeSuite::M114() { report_current_position_detail(); return; } - if (parser.seen('E')) { - SERIAL_ECHOLNPAIR("Count E:", stepper.position(E_AXIS)); - return; - } + #if HAS_EXTRUDERS + if (parser.seen_test('E')) { + SERIAL_ECHOLNPAIR("Count E:", stepper.position(E_AXIS)); + return; + } + #endif #endif #if ENABLED(M114_REALTIME) - if (parser.seen('R')) { report_real_position(); return; } + if (parser.seen_test('R')) { report_real_position(); return; } #endif TERN_(M114_LEGACY, planner.synchronize()); report_current_position_projected(); + + TERN_(FULL_REPORT_TO_HOST_FEATURE, report_current_grblstate_moving()); } diff --git a/Marlin/src/gcode/host/M115.cpp b/Marlin/src/gcode/host/M115.cpp index 53c5163bbaf6..3b88c6905e15 100644 --- a/Marlin/src/gcode/host/M115.cpp +++ b/Marlin/src/gcode/host/M115.cpp @@ -22,17 +22,23 @@ #include "../gcode.h" #include "../../inc/MarlinConfig.h" +#include "../queue.h" // for getting the command port + #if ENABLED(M115_GEOMETRY_REPORT) #include "../../module/motion.h" #endif +#if ENABLED(CASE_LIGHT_ENABLE) + #include "../../feature/caselight.h" +#endif + #if ENABLED(EXTENDED_CAPABILITIES_REPORT) static void cap_line(PGM_P const name, bool ena=false) { SERIAL_ECHOPGM("Cap:"); - serialprintPGM(name); - SERIAL_CHAR(':'); - SERIAL_ECHOLN(int(ena ? 1 : 0)); + SERIAL_ECHOPGM_P(name); + SERIAL_CHAR(':', '0' + ena); + SERIAL_EOL(); } #endif @@ -48,6 +54,9 @@ void GcodeSuite::M115() { "PROTOCOL_VERSION:" PROTOCOL_VERSION " " "MACHINE_TYPE:" MACHINE_NAME " " "EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " " + #if LINEAR_AXES != XYZ + "AXIS_COUNT:" STRINGIFY(LINEAR_AXES) " " + #endif #ifdef MACHINE_UUID "UUID:" MACHINE_UUID #endif @@ -55,6 +64,9 @@ void GcodeSuite::M115() { #if ENABLED(EXTENDED_CAPABILITIES_REPORT) + // The port that sent M115 + serial_index_t port = queue.ring_buffer.command_port(); + // PAREN_COMMENTS TERN_(PAREN_COMMENTS, cap_line(PSTR("PAREN_COMMENTS"), true)); @@ -65,7 +77,7 @@ void GcodeSuite::M115() { cap_line(PSTR("SERIAL_XON_XOFF"), ENABLED(SERIAL_XON_XOFF)); // BINARY_FILE_TRANSFER (M28 B1) - cap_line(PSTR("BINARY_FILE_TRANSFER"), ENABLED(BINARY_FILE_TRANSFER)); + cap_line(PSTR("BINARY_FILE_TRANSFER"), ENABLED(BINARY_FILE_TRANSFER)); // TODO: Use SERIAL_IMPL.has_feature(port, SerialFeature::BinaryFileTransfer) once implemented // EEPROM (M500, M501) cap_line(PSTR("EEPROM"), ENABLED(EEPROM_SETTINGS)); @@ -73,6 +85,9 @@ void GcodeSuite::M115() { // Volumetric Extrusion (M200) cap_line(PSTR("VOLUMETRIC"), DISABLED(NO_VOLUMETRICS)); + // AUTOREPORT_POS (M154) + cap_line(PSTR("AUTOREPORT_POS"), ENABLED(AUTO_REPORT_POSITION)); + // AUTOREPORT_TEMP (M155) cap_line(PSTR("AUTOREPORT_TEMP"), ENABLED(AUTO_REPORT_TEMPERATURES)); @@ -102,17 +117,26 @@ void GcodeSuite::M115() { // TOGGLE_LIGHTS (M355) cap_line(PSTR("TOGGLE_LIGHTS"), ENABLED(CASE_LIGHT_ENABLE)); - cap_line(PSTR("CASE_LIGHT_BRIGHTNESS"), TERN0(CASE_LIGHT_ENABLE, PWM_PIN(CASE_LIGHT_PIN))); + cap_line(PSTR("CASE_LIGHT_BRIGHTNESS"), TERN0(CASE_LIGHT_ENABLE, caselight.has_brightness())); // EMERGENCY_PARSER (M108, M112, M410, M876) cap_line(PSTR("EMERGENCY_PARSER"), ENABLED(EMERGENCY_PARSER)); + // HOST ACTION COMMANDS (paused, resume, resumed, cancel, etc.) + cap_line(PSTR("HOST_ACTION_COMMANDS"), ENABLED(HOST_ACTION_COMMANDS)); + // PROMPT SUPPORT (M876) cap_line(PSTR("PROMPT_SUPPORT"), ENABLED(HOST_PROMPT_SUPPORT)); // SDCARD (M20, M23, M24, etc.) cap_line(PSTR("SDCARD"), ENABLED(SDSUPPORT)); + // REPEAT (M808) + cap_line(PSTR("REPEAT"), ENABLED(GCODE_REPEAT_MARKERS)); + + // SD_WRITE (M928, M28, M29) + cap_line(PSTR("SD_WRITE"), ENABLED(SDSUPPORT) && DISABLED(SDCARD_READONLY)); + // AUTOREPORT_SD_STATUS (M27 extension) cap_line(PSTR("AUTOREPORT_SD_STATUS"), ENABLED(AUTO_REPORT_SD_STATUS)); @@ -134,6 +158,12 @@ void GcodeSuite::M115() { // CHAMBER_TEMPERATURE (M141, M191) cap_line(PSTR("CHAMBER_TEMPERATURE"), ENABLED(HAS_HEATED_CHAMBER)); + // COOLER_TEMPERATURE (M143, M193) + cap_line(PSTR("COOLER_TEMPERATURE"), ENABLED(HAS_COOLER)); + + // MEATPACK Compression + cap_line(PSTR("MEATPACK"), SERIAL_IMPL.has_feature(port, SerialFeature::MeatPack)); + // Machine Geometry #if ENABLED(M115_GEOMETRY_REPORT) const xyz_pos_t dmin = { X_MIN_POS, Y_MIN_POS, Z_MIN_POS }, diff --git a/Marlin/src/gcode/host/M118.cpp b/Marlin/src/gcode/host/M118.cpp index 3be290254125..d6e591add947 100644 --- a/Marlin/src/gcode/host/M118.cpp +++ b/Marlin/src/gcode/host/M118.cpp @@ -52,22 +52,9 @@ void GcodeSuite::M118() { while (*p == ' ') ++p; } - #if HAS_MULTI_SERIAL - const int8_t old_serial = serial_port_index; - if (WITHIN(port, 0, NUM_SERIAL)) - serial_port_index = ( - port == 0 ? SERIAL_BOTH - : port == 1 ? SERIAL_PORT - #ifdef SERIAL_PORT_2 - : port == 2 ? SERIAL_PORT_2 - #endif - : SERIAL_PORT - ); - #endif + PORT_REDIRECT(WITHIN(port, 0, NUM_SERIAL) ? (port ? SERIAL_PORTMASK(port - 1) : SerialMask::All) : multiSerial.portMask); if (hasE) SERIAL_ECHO_START(); - if (hasA) SERIAL_ECHOPGM("// "); + if (hasA) SERIAL_ECHOPGM("//"); SERIAL_ECHOLN(p); - - TERN_(HAS_MULTI_SERIAL, serial_port_index = old_serial); } diff --git a/Marlin/src/gcode/host/M154.cpp b/Marlin/src/gcode/host/M154.cpp new file mode 100644 index 000000000000..156e6b69b624 --- /dev/null +++ b/Marlin/src/gcode/host/M154.cpp @@ -0,0 +1,40 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../inc/MarlinConfigPre.h" + +#if ENABLED(AUTO_REPORT_POSITION) + +#include "../gcode.h" +#include "../../module/motion.h" + +/** + * M154: Set position auto-report interval. M154 S + */ +void GcodeSuite::M154() { + + if (parser.seenval('S')) + position_auto_reporter.set_interval(parser.value_byte()); + +} + +#endif // AUTO_REPORT_POSITION diff --git a/Marlin/src/gcode/host/M360.cpp b/Marlin/src/gcode/host/M360.cpp index 9970dc4df95c..7a0b8e3ab0f7 100644 --- a/Marlin/src/gcode/host/M360.cpp +++ b/Marlin/src/gcode/host/M360.cpp @@ -28,16 +28,23 @@ #include "../../module/motion.h" #include "../../module/planner.h" -static void config_prefix(PGM_P const name, PGM_P const pref=nullptr) { +#if HAS_EXTRUDERS + #include "../../module/temperature.h" +#endif + +static void config_prefix(PGM_P const name, PGM_P const pref=nullptr, const int8_t ind=-1) { SERIAL_ECHOPGM("Config:"); - if (pref) serialprintPGM(pref); - serialprintPGM(name); - SERIAL_CHAR(':'); + if (pref) SERIAL_ECHOPGM_P(pref); + if (ind >= 0) { SERIAL_ECHO(ind); SERIAL_CHAR(':'); } + SERIAL_ECHOPAIR_P(name, AS_CHAR(':')); } -static void config_line(PGM_P const name, const float val, PGM_P const pref=nullptr) { - config_prefix(name, pref); +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); SERIAL_ECHOLN(val); } +static void config_line_e(const int8_t e, PGM_P const name, const float val) { + config_line(name, val, PSTR("Extr."), e + 1); +} /** * M360: Report Firmware configuration @@ -52,19 +59,19 @@ void GcodeSuite::M360() { // // Basics and Enabled items // - config_line(PSTR("Baudrate"), BAUDRATE); - config_line(PSTR("InputBuffer"), MAX_CMD_SIZE); - config_line(PSTR("PrintlineCache"), BUFSIZE); - config_line(PSTR("MixingExtruder"), ENABLED(MIXING_EXTRUDER)); - config_line(PSTR("SDCard"), ENABLED(SDSUPPORT)); - config_line(PSTR("Fan"), ENABLED(HAS_FAN)); - config_line(PSTR("LCD"), ENABLED(HAS_DISPLAY)); + config_line(PSTR("Baudrate"), BAUDRATE); + config_line(PSTR("InputBuffer"), MAX_CMD_SIZE); + config_line(PSTR("PrintlineCache"), BUFSIZE); + config_line(PSTR("MixingExtruder"), ENABLED(MIXING_EXTRUDER)); + config_line(PSTR("SDCard"), ENABLED(SDSUPPORT)); + config_line(PSTR("Fan"), ENABLED(HAS_FAN)); + config_line(PSTR("LCD"), ENABLED(HAS_DISPLAY)); config_line(PSTR("SoftwarePowerSwitch"), 1); config_line(PSTR("SupportLocalFilamentchange"), ENABLED(ADVANCED_PAUSE_FEATURE)); - config_line(PSTR("CaseLights"), ENABLED(CASE_LIGHT_ENABLE)); - config_line(PSTR("ZProbe"), ENABLED(HAS_BED_PROBE)); - config_line(PSTR("Autolevel"), ENABLED(HAS_LEVELING)); - config_line(PSTR("EEPROM"), ENABLED(EEPROM_SETTINGS)); + config_line(PSTR("CaseLights"), ENABLED(CASE_LIGHT_ENABLE)); + config_line(PSTR("ZProbe"), ENABLED(HAS_BED_PROBE)); + config_line(PSTR("Autolevel"), ENABLED(HAS_LEVELING)); + config_line(PSTR("EEPROM"), ENABLED(EEPROM_SETTINGS)); // // Homing Directions @@ -96,15 +103,15 @@ void GcodeSuite::M360() { PGMSTR(UNRET_STR, "RetractionUndo"); PGMSTR(SPEED_STR, "Speed"); // M10 Retract with swap (long) moves - config_line(PSTR("Length"), fwretract.settings.retract_length, RET_STR); - config_line(SPEED_STR, fwretract.settings.retract_feedrate_mm_s, RET_STR); - config_line(PSTR("ZLift"), fwretract.settings.retract_zraise, RET_STR); + config_line(PSTR("Length"), fwretract.settings.retract_length, RET_STR); + config_line(SPEED_STR, fwretract.settings.retract_feedrate_mm_s, RET_STR); + config_line(PSTR("ZLift"), fwretract.settings.retract_zraise, RET_STR); config_line(PSTR("LongLength"), fwretract.settings.swap_retract_length, RET_STR); // M11 Recover (undo) with swap (long) moves - config_line(SPEED_STR, fwretract.settings.retract_recover_feedrate_mm_s, UNRET_STR); - config_line(PSTR("ExtraLength"), fwretract.settings.retract_recover_extra, UNRET_STR); + config_line(SPEED_STR, fwretract.settings.retract_recover_feedrate_mm_s, UNRET_STR); + config_line(PSTR("ExtraLength"), fwretract.settings.retract_recover_extra, UNRET_STR); config_line(PSTR("ExtraLongLength"), fwretract.settings.swap_retract_recover_extra, UNRET_STR); - config_line(PSTR("LongSpeed"), fwretract.settings.swap_retract_recover_feedrate_mm_s, UNRET_STR); + config_line(PSTR("LongSpeed"), fwretract.settings.swap_retract_recover_feedrate_mm_s, UNRET_STR); #endif // @@ -164,25 +171,14 @@ void GcodeSuite::M360() { // Per-Extruder settings // config_line(PSTR("NumExtruder"), EXTRUDERS); - #if EXTRUDERS - #define DIAM_VALUE(N) TERN(NO_VOLUMETRICS, DEFAULT_NOMINAL_FILAMENT_DIA, planner.filament_size[N]) - #if HAS_LINEAR_E_JERK - #define E_JERK_VAL(N) planner.max_e_jerk[E_INDEX_N(N)] - #elif HAS_CLASSIC_JERK - #define E_JERK_VAL(N) planner.max_jerk.e - #else - #define E_JERK_VAL(N) DEFAULT_EJERK - #endif - #define _EXTR_ITEM(N) do{ \ - PGMSTR(EXTR_STR, "Extr." STRINGIFY(INCREMENT(N)) ":"); \ - config_line(JERK_STR, E_JERK_VAL(N), EXTR_STR); \ - config_line(PSTR("MaxSpeed"), planner.settings.max_feedrate_mm_s[E_AXIS_N(N)], EXTR_STR); \ - config_line(PSTR("Acceleration"), planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(N)], EXTR_STR); \ - config_line(PSTR("Diameter"), DIAM_VALUE(N), EXTR_STR); \ - config_line(PSTR("MaxTemp"), (HEATER_##N##_MAXTEMP) - (HOTEND_OVERSHOOT), EXTR_STR); \ - }while(0) - - REPEAT(EXTRUDERS, _EXTR_ITEM); + #if HAS_EXTRUDERS + LOOP_L_N(e, EXTRUDERS) { + config_line_e(e, JERK_STR, TERN(HAS_LINEAR_E_JERK, planner.max_e_jerk[E_INDEX_N(e)], TERN(HAS_CLASSIC_JERK, planner.max_jerk.e, DEFAULT_EJERK))); + config_line_e(e, PSTR("MaxSpeed"), planner.settings.max_feedrate_mm_s[E_AXIS_N(e)]); + config_line_e(e, PSTR("Acceleration"), planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(e)]); + config_line_e(e, PSTR("Diameter"), TERN(NO_VOLUMETRICS, DEFAULT_NOMINAL_FILAMENT_DIA, planner.filament_size[e])); + config_line_e(e, PSTR("MaxTemp"), thermalManager.hotend_maxtemp[e]); + } #endif } diff --git a/Marlin/src/gcode/lcd/M0_M1.cpp b/Marlin/src/gcode/lcd/M0_M1.cpp index 1d18b706029c..414c4ce02396 100644 --- a/Marlin/src/gcode/lcd/M0_M1.cpp +++ b/Marlin/src/gcode/lcd/M0_M1.cpp @@ -32,7 +32,7 @@ #include "../../MarlinCore.h" // for wait_for_user_response() #if HAS_LCD_MENU - #include "../../lcd/ultralcd.h" + #include "../../lcd/marlinui.h" #elif ENABLED(EXTENSIBLE_UI) #include "../../lcd/extui/ui_api.h" #endif diff --git a/Marlin/src/gcode/lcd/M117.cpp b/Marlin/src/gcode/lcd/M117.cpp index 8459135f3018..f26694bd6463 100644 --- a/Marlin/src/gcode/lcd/M117.cpp +++ b/Marlin/src/gcode/lcd/M117.cpp @@ -20,8 +20,12 @@ * */ +#include "../../inc/MarlinConfig.h" + +#if HAS_STATUS_MESSAGE + #include "../gcode.h" -#include "../../lcd/ultralcd.h" +#include "../../lcd/marlinui.h" /** * M117: Set LCD Status Message @@ -34,3 +38,5 @@ void GcodeSuite::M117() { ui.reset_status(); } + +#endif // HAS_STATUS_MESSAGE diff --git a/Marlin/src/gcode/lcd/M145.cpp b/Marlin/src/gcode/lcd/M145.cpp index abd4dcc7439b..d6a57d22157e 100644 --- a/Marlin/src/gcode/lcd/M145.cpp +++ b/Marlin/src/gcode/lcd/M145.cpp @@ -25,7 +25,11 @@ #if PREHEAT_COUNT #include "../gcode.h" -#include "../../lcd/ultralcd.h" +#include "../../lcd/marlinui.h" + +#if HAS_HOTEND + #include "../../module/temperature.h" +#endif /** * M145: Set the heatup state for a material in the LCD menu @@ -43,7 +47,7 @@ void GcodeSuite::M145() { preheat_t &mat = ui.material_preset[material]; #if HAS_HOTEND if (parser.seenval('H')) - mat.hotend_temp = constrain(parser.value_int(), EXTRUDE_MINTEMP, (HEATER_0_MAXTEMP) - (HOTEND_OVERSHOOT)); + mat.hotend_temp = constrain(parser.value_int(), EXTRUDE_MINTEMP, thermalManager.hotend_max_target(0)); #endif #if HAS_HEATED_BED if (parser.seenval('B')) diff --git a/Marlin/src/gcode/lcd/M250.cpp b/Marlin/src/gcode/lcd/M250.cpp index f42daaeac428..f553044d31c0 100644 --- a/Marlin/src/gcode/lcd/M250.cpp +++ b/Marlin/src/gcode/lcd/M250.cpp @@ -25,7 +25,7 @@ #if HAS_LCD_CONTRAST #include "../gcode.h" -#include "../../lcd/ultralcd.h" +#include "../../lcd/marlinui.h" /** * M250: Read and optionally set the LCD contrast diff --git a/Marlin/src/gcode/lcd/M256.cpp b/Marlin/src/gcode/lcd/M256.cpp new file mode 100644 index 000000000000..e292acc4ed44 --- /dev/null +++ b/Marlin/src/gcode/lcd/M256.cpp @@ -0,0 +1,37 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../inc/MarlinConfig.h" + +#if HAS_LCD_BRIGHTNESS + +#include "../gcode.h" +#include "../../lcd/marlinui.h" + +/** + * M256: Set the LCD brightness + */ +void GcodeSuite::M256() { + if (parser.seenval('B')) ui.set_brightness(parser.value_int()); + SERIAL_ECHOLNPAIR("LCD Brightness: ", ui.brightness); +} + +#endif // HAS_LCD_BRIGHTNESS diff --git a/Marlin/src/gcode/lcd/M300.cpp b/Marlin/src/gcode/lcd/M300.cpp index 56d9ee5d7350..5250774955fb 100644 --- a/Marlin/src/gcode/lcd/M300.cpp +++ b/Marlin/src/gcode/lcd/M300.cpp @@ -26,7 +26,7 @@ #include "../gcode.h" -#include "../../lcd/ultralcd.h" // i2c-based BUZZ +#include "../../lcd/marlinui.h" // i2c-based BUZZ #include "../../libs/buzzer.h" // Buzzer, if possible /** diff --git a/Marlin/src/gcode/lcd/M414.cpp b/Marlin/src/gcode/lcd/M414.cpp new file mode 100644 index 000000000000..760028a899f2 --- /dev/null +++ b/Marlin/src/gcode/lcd/M414.cpp @@ -0,0 +1,44 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../inc/MarlinConfig.h" + +#if HAS_MULTI_LANGUAGE + +#include "../gcode.h" +#include "../../MarlinCore.h" +#include "../../lcd/marlinui.h" + +/** + * M414: Set the language for the UI + * + * Parameters + * S : The language to select + */ +void GcodeSuite::M414() { + + if (parser.seenval('S')) + ui.set_language(parser.value_byte()); + +} + +#endif // HAS_MULTI_LANGUAGE diff --git a/Marlin/src/gcode/lcd/M73.cpp b/Marlin/src/gcode/lcd/M73.cpp index 7a5454419da9..8996e5c88ecb 100644 --- a/Marlin/src/gcode/lcd/M73.cpp +++ b/Marlin/src/gcode/lcd/M73.cpp @@ -25,7 +25,7 @@ #if ENABLED(LCD_SET_PROGRESS_MANUALLY) #include "../gcode.h" -#include "../../lcd/ultralcd.h" +#include "../../lcd/marlinui.h" #include "../../sd/cardreader.h" /** @@ -35,13 +35,13 @@ * M73 P25 ; Set progress to 25% */ void GcodeSuite::M73() { - if (parser.seen('P')) + if (parser.seenval('P')) ui.set_progress((PROGRESS_SCALE) > 1 ? parser.value_float() * (PROGRESS_SCALE) : parser.value_byte() ); - #if BOTH(LCD_SET_PROGRESS_MANUALLY, USE_M73_REMAINING_TIME) - if (parser.seen('R')) ui.set_remaining_time(60 * parser.value_ulong()); + #if ENABLED(USE_M73_REMAINING_TIME) + if (parser.seenval('R')) ui.set_remaining_time(60 * parser.value_ulong()); #endif } diff --git a/Marlin/src/gcode/lcd/M995.cpp b/Marlin/src/gcode/lcd/M995.cpp index 72d0d29f7683..d5f825c0c8d7 100644 --- a/Marlin/src/gcode/lcd/M995.cpp +++ b/Marlin/src/gcode/lcd/M995.cpp @@ -25,14 +25,23 @@ #if ENABLED(TOUCH_SCREEN_CALIBRATION) #include "../gcode.h" -#include "../../lcd/menu/menu.h" + +#if HAS_TFT_LVGL_UI + #include "../../lcd/extui/mks_ui/draw_touch_calibration.h" +#else + #include "../../lcd/menu/menu.h" +#endif /** * M995: Touch screen calibration for TFT display */ void GcodeSuite::M995() { - ui.goto_screen(touch_screen_calibration); + #if HAS_TFT_LVGL_UI + lv_draw_touch_calibration_screen(); + #else + ui.goto_screen(touch_screen_calibration); + #endif } diff --git a/Marlin/src/gcode/motion/G0_G1.cpp b/Marlin/src/gcode/motion/G0_G1.cpp index 9ac49bd93cf1..eb79180c6988 100644 --- a/Marlin/src/gcode/motion/G0_G1.cpp +++ b/Marlin/src/gcode/motion/G0_G1.cpp @@ -49,11 +49,17 @@ void GcodeSuite::G0_G1(TERN_(HAS_FAST_MOVES, const bool fast_move/*=false*/)) { if (IsRunning() #if ENABLED(NO_MOTION_BEFORE_HOMING) && !homing_needed_error( - (parser.seen('X') ? _BV(X_AXIS) : 0) - | (parser.seen('Y') ? _BV(Y_AXIS) : 0) - | (parser.seen('Z') ? _BV(Z_AXIS) : 0) ) + LINEAR_AXIS_GANG( + (parser.seen_test('X') ? _BV(X_AXIS) : 0), + | (parser.seen_test('Y') ? _BV(Y_AXIS) : 0), + | (parser.seen_test('Z') ? _BV(Z_AXIS) : 0), + | (parser.seen_test(AXIS4_NAME) ? _BV(I_AXIS) : 0), + | (parser.seen_test(AXIS5_NAME) ? _BV(J_AXIS) : 0), + | (parser.seen_test(AXIS6_NAME) ? _BV(K_AXIS) : 0)) + ) #endif ) { + TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_RUNNING)); #ifdef G0_FEEDRATE feedRate_t old_feedrate; @@ -82,7 +88,9 @@ void GcodeSuite::G0_G1(TERN_(HAS_FAST_MOVES, const bool fast_move/*=false*/)) { if (MIN_AUTORETRACT <= MAX_AUTORETRACT) { // When M209 Autoretract is enabled, convert E-only moves to firmware retract/recover moves - if (fwretract.autoretract_enabled && parser.seen('E') && !(parser.seen('X') || parser.seen('Y') || parser.seen('Z'))) { + if (fwretract.autoretract_enabled && parser.seen_test('E') + && !parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR)) + ) { const float echange = destination.e - current_position.e; // Is this a retract or recover move? if (WITHIN(ABS(echange), MIN_AUTORETRACT, MAX_AUTORETRACT) && fwretract.retracted[active_extruder] == (echange > 0.0)) { @@ -116,6 +124,9 @@ void GcodeSuite::G0_G1(TERN_(HAS_FAST_MOVES, const bool fast_move/*=false*/)) { planner.synchronize(); SERIAL_ECHOLNPGM(STR_Z_MOVE_COMP); } + TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_IDLE)); + #else + TERN_(FULL_REPORT_TO_HOST_FEATURE, report_current_grblstate_moving()); #endif } } diff --git a/Marlin/src/gcode/motion/G2_G3.cpp b/Marlin/src/gcode/motion/G2_G3.cpp index 61d9f1d3a66d..094afdb70e8f 100644 --- a/Marlin/src/gcode/motion/G2_G3.cpp +++ b/Marlin/src/gcode/motion/G2_G3.cpp @@ -41,18 +41,18 @@ #endif /** - * Plan an arc in 2 dimensions + * Plan an arc in 2 dimensions, with optional linear motion in a 3rd dimension * - * The arc is approximated by generating many small linear segments. - * The length of each segment is configured in MM_PER_ARC_SEGMENT (Default 1mm) - * Arcs should only be made relatively large (over 5mm), as larger arcs with - * larger segments will tend to be more efficient. Your slicer should have - * options for G2/G3 arc generation. In future these options may be GCode tunable. + * The arc is traced by generating many small linear segments, as configured by + * MM_PER_ARC_SEGMENT (Default 1mm). In the future we hope more slicers will include + * an option to generate G2/G3 arcs for curved surfaces, as this will allow faster + * boards to produce much smoother curved surfaces. */ void plan_arc( const xyze_pos_t &cart, // Destination position const ab_float_t &offset, // Center of rotation relative to current_position - const uint8_t clockwise // Clockwise? + const bool clockwise, // Clockwise? + const uint8_t circles // Take the scenic route ) { #if ENABLED(CNC_WORKSPACE_PLANES) AxisEnum p_axis, q_axis, l_axis; @@ -63,7 +63,7 @@ void plan_arc( case GcodeSuite::PLANE_ZX: p_axis = Z_AXIS; q_axis = X_AXIS; l_axis = Y_AXIS; break; } #else - constexpr AxisEnum p_axis = X_AXIS, q_axis = Y_AXIS, l_axis = Z_AXIS; + constexpr AxisEnum p_axis = X_AXIS, q_axis = Y_AXIS OPTARG(HAS_Z_AXIS, l_axis = Z_AXIS); #endif // Radius vector from center to current location @@ -73,32 +73,76 @@ void plan_arc( center_P = current_position[p_axis] - rvec.a, center_Q = current_position[q_axis] - rvec.b, rt_X = cart[p_axis] - center_P, - rt_Y = cart[q_axis] - center_Q, - start_L = current_position[l_axis], - linear_travel = cart[l_axis] - start_L, - extruder_travel = cart.e - current_position.e; - - // CCW angle of rotation between position and target from the circle center. Only one atan2() trig computation required. - float angular_travel = ATAN2(rvec.a * rt_Y - rvec.b * rt_X, rvec.a * rt_X + rvec.b * rt_Y); - if (angular_travel < 0) angular_travel += RADIANS(360); + rt_Y = cart[q_axis] - center_Q + OPTARG(HAS_Z_AXIS, start_L = current_position[l_axis]); + #ifdef MIN_ARC_SEGMENTS - uint16_t min_segments = CEIL((MIN_ARC_SEGMENTS) * (angular_travel / RADIANS(360))); - NOLESS(min_segments, 1U); + uint16_t min_segments = MIN_ARC_SEGMENTS; #else constexpr uint16_t min_segments = 1; #endif - if (clockwise) angular_travel -= RADIANS(360); - // Make a circle if the angular rotation is 0 and the target is current position - if (angular_travel == 0 && current_position[p_axis] == cart[p_axis] && current_position[q_axis] == cart[q_axis]) { - angular_travel = RADIANS(360); + // Angle of rotation between position and target from the circle center. + float angular_travel, abs_angular_travel; + + // Do a full circle if starting and ending positions are "identical" + if (NEAR(current_position[p_axis], cart[p_axis]) && NEAR(current_position[q_axis], cart[q_axis])) { + // Preserve direction for circles + angular_travel = clockwise ? -RADIANS(360) : RADIANS(360); + abs_angular_travel = RADIANS(360); + } + else { + // Calculate the angle + angular_travel = ATAN2(rvec.a * rt_Y - rvec.b * rt_X, rvec.a * rt_X + rvec.b * rt_Y); + + // Angular travel too small to detect? Just return. + if (!angular_travel) return; + + // Make sure angular travel over 180 degrees goes the other way around. + switch (((angular_travel < 0) << 1) | clockwise) { + case 1: angular_travel -= RADIANS(360); break; // Positive but CW? Reverse direction. + case 2: angular_travel += RADIANS(360); break; // Negative but CCW? Reverse direction. + } + + abs_angular_travel = ABS(angular_travel); + #ifdef MIN_ARC_SEGMENTS - min_segments = MIN_ARC_SEGMENTS; + min_segments = CEIL(min_segments * abs_angular_travel / RADIANS(360)); + NOLESS(min_segments, 1U); #endif } - const float flat_mm = radius * angular_travel, - mm_of_travel = linear_travel ? HYPOT(flat_mm, linear_travel) : ABS(flat_mm); + #if HAS_Z_AXIS + float linear_travel = cart[l_axis] - start_L; + #endif + #if HAS_EXTRUDERS + float extruder_travel = cart.e - current_position.e; + #endif + + // If circling around... + if (TERN0(ARC_P_CIRCLES, circles)) { + const float total_angular = abs_angular_travel + circles * RADIANS(360), // Total rotation with all circles and remainder + part_per_circle = RADIANS(360) / total_angular; // Each circle's part of the total + + #if HAS_Z_AXIS + const float l_per_circle = linear_travel * part_per_circle; // L movement per circle + #endif + #if HAS_EXTRUDERS + const float e_per_circle = extruder_travel * part_per_circle; // E movement per circle + #endif + + xyze_pos_t temp_position = current_position; // for plan_arc to compare to current_position + for (uint16_t n = circles; n--;) { + TERN_(HAS_EXTRUDERS, temp_position.e += e_per_circle); // Destination E axis + TERN_(HAS_Z_AXIS, temp_position[l_axis] += l_per_circle); // Destination L axis + plan_arc(temp_position, offset, clockwise, 0); // Plan a single whole circle + } + TERN_(HAS_Z_AXIS, linear_travel = cart[l_axis] - current_position[l_axis]); + TERN_(HAS_EXTRUDERS, extruder_travel = cart.e - current_position.e); + } + + const float flat_mm = radius * abs_angular_travel, + mm_of_travel = TERN_(HAS_Z_AXIS, linear_travel ? HYPOT(flat_mm, linear_travel) :) flat_mm; if (mm_of_travel < 0.001f) return; const feedRate_t scaled_fr_mm_s = MMS_SCALED(feedrate_mm_s); @@ -147,17 +191,22 @@ void plan_arc( // Vector rotation matrix values xyze_pos_t raw; const float theta_per_segment = angular_travel / segments, - linear_per_segment = linear_travel / segments, - extruder_per_segment = extruder_travel / segments, sq_theta_per_segment = sq(theta_per_segment), - sin_T = theta_per_segment - sq_theta_per_segment*theta_per_segment/6, + sin_T = theta_per_segment - sq_theta_per_segment * theta_per_segment / 6, cos_T = 1 - 0.5f * sq_theta_per_segment; // Small angle approximation + #if HAS_Z_AXIS && DISABLED(AUTO_BED_LEVELING_UBL) + const float linear_per_segment = linear_travel / segments; + #endif + #if HAS_EXTRUDERS + const float extruder_per_segment = extruder_travel / segments; + #endif + // Initialize the linear axis - raw[l_axis] = current_position[l_axis]; + TERN_(HAS_Z_AXIS, raw[l_axis] = current_position[l_axis]); // Initialize the extruder axis - raw.e = current_position.e; + TERN_(HAS_EXTRUDERS, raw.e = current_position.e); #if ENABLED(SCARA_FEEDRATE_SCALING) const float inv_duration = scaled_fr_mm_s / seg_length; @@ -203,13 +252,11 @@ void plan_arc( // Update raw location raw[p_axis] = center_P + rvec.a; raw[q_axis] = center_Q + rvec.b; - #if ENABLED(AUTO_BED_LEVELING_UBL) - raw[l_axis] = start_L; - UNUSED(linear_per_segment); - #else - raw[l_axis] += linear_per_segment; + #if HAS_Z_AXIS + raw[l_axis] = TERN(AUTO_BED_LEVELING_UBL, start_L, raw[l_axis] + linear_per_segment); #endif - raw.e += extruder_per_segment; + + TERN_(HAS_EXTRUDERS, raw.e += extruder_per_segment); apply_motion_limits(raw); @@ -218,15 +265,13 @@ void plan_arc( #endif if (!planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, 0 - #if ENABLED(SCARA_FEEDRATE_SCALING) - , inv_duration - #endif + OPTARG(SCARA_FEEDRATE_SCALING, inv_duration) )) break; } // Ensure last segment arrives at target location. raw = cart; - TERN_(AUTO_BED_LEVELING_UBL, raw[l_axis] = start_L); + TERN_(AUTO_BED_LEVELING_UBL, TERN_(HAS_Z_AXIS, raw[l_axis] = start_L)); apply_motion_limits(raw); @@ -235,12 +280,10 @@ void plan_arc( #endif planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, 0 - #if ENABLED(SCARA_FEEDRATE_SCALING) - , inv_duration - #endif + OPTARG(SCARA_FEEDRATE_SCALING, inv_duration) ); - TERN_(AUTO_BED_LEVELING_UBL, raw[l_axis] = start_L); + TERN_(AUTO_BED_LEVELING_UBL, TERN_(HAS_Z_AXIS, raw[l_axis] = start_L)); current_position = raw; } // plan_arc @@ -260,12 +303,12 @@ void plan_arc( * Mixing IJ/JK/KI with R will throw an error. * * - R specifies the radius. X or Y (Y or Z / Z or X) is required. - * Omitting both XY/YZ/ZX will throw an error. - * XY/YZ/ZX must differ from the current XY/YZ/ZX. - * Mixing R with IJ/JK/KI will throw an error. + * Omitting both XY/YZ/ZX will throw an error. + * XY/YZ/ZX must differ from the current XY/YZ/ZX. + * Mixing R with IJ/JK/KI will throw an error. * * - P specifies the number of full circles to do - * before the specified arc move. + * before the specified arc move. * * Examples: * @@ -275,6 +318,8 @@ void plan_arc( void GcodeSuite::G2_G3(const bool clockwise) { if (MOTION_CONDITIONS) { + TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_RUNNING)); + #if ENABLED(SF_ARC_FIX) const bool relative_mode_backup = relative_mode; relative_mode = true; @@ -320,20 +365,21 @@ void GcodeSuite::G2_G3(const bool clockwise) { #if ENABLED(ARC_P_CIRCLES) // P indicates number of circles to do - int8_t circles_to_do = parser.byteval('P'); + const int8_t circles_to_do = parser.byteval('P'); if (!WITHIN(circles_to_do, 0, 100)) SERIAL_ERROR_MSG(STR_ERR_ARC_ARGS); - - while (circles_to_do--) - plan_arc(current_position, arc_offset, clockwise); + #else + constexpr uint8_t circles_to_do = 0; #endif // Send the arc to the planner - plan_arc(destination, arc_offset, clockwise); + plan_arc(destination, arc_offset, clockwise, circles_to_do); reset_stepper_timeout(); } else SERIAL_ERROR_MSG(STR_ERR_ARC_ARGS); + + TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_IDLE)); } } diff --git a/Marlin/src/gcode/motion/G4.cpp b/Marlin/src/gcode/motion/G4.cpp index 3a37fe5b2c4e..724ed7f1cad9 100644 --- a/Marlin/src/gcode/motion/G4.cpp +++ b/Marlin/src/gcode/motion/G4.cpp @@ -22,7 +22,7 @@ #include "../gcode.h" #include "../../module/stepper.h" -#include "../../lcd/ultralcd.h" +#include "../../lcd/marlinui.h" /** * G4: Dwell S or P diff --git a/Marlin/src/gcode/motion/M290.cpp b/Marlin/src/gcode/motion/M290.cpp index 18cc161fce29..2b57a6b99a9b 100644 --- a/Marlin/src/gcode/motion/M290.cpp +++ b/Marlin/src/gcode/motion/M290.cpp @@ -27,7 +27,6 @@ #include "../gcode.h" #include "../../feature/babystep.h" #include "../../module/probe.h" -#include "../../module/temperature.h" #include "../../module/planner.h" #if ENABLED(BABYSTEP_ZPROBE_OFFSET) @@ -40,17 +39,15 @@ #if ENABLED(BABYSTEP_ZPROBE_OFFSET) - FORCE_INLINE void mod_probe_offset(const float &offs) { + FORCE_INLINE void mod_probe_offset(const_float_t offs) { if (TERN1(BABYSTEP_HOTEND_Z_OFFSET, active_extruder == 0)) { probe.offset.z += offs; - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR(STR_PROBE_OFFSET " " STR_Z, probe.offset.z); + SERIAL_ECHO_MSG(STR_PROBE_OFFSET " " STR_Z, probe.offset.z); } else { #if ENABLED(BABYSTEP_HOTEND_Z_OFFSET) hotend_offset[active_extruder].z -= offs; - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR(STR_PROBE_OFFSET STR_Z ": ", hotend_offset[active_extruder].z); + SERIAL_ECHO_MSG(STR_PROBE_OFFSET STR_Z ": ", hotend_offset[active_extruder].z); #endif } } @@ -72,12 +69,12 @@ */ void GcodeSuite::M290() { #if ENABLED(BABYSTEP_XY) - LOOP_XYZ(a) - if (parser.seenval(XYZ_CHAR(a)) || (a == Z_AXIS && parser.seenval('S'))) { + LOOP_LINEAR_AXES(a) + if (parser.seenval(AXIS_CHAR(a)) || (a == Z_AXIS && parser.seenval('S'))) { const float offs = constrain(parser.value_axis_units((AxisEnum)a), -2, 2); babystep.add_mm((AxisEnum)a, offs); #if ENABLED(BABYSTEP_ZPROBE_OFFSET) - if (a == Z_AXIS && (!parser.seen('P') || parser.value_bool())) mod_probe_offset(offs); + if (a == Z_AXIS && parser.boolval('P', true)) mod_probe_offset(offs); #endif } #else @@ -85,12 +82,12 @@ void GcodeSuite::M290() { const float offs = constrain(parser.value_axis_units(Z_AXIS), -2, 2); babystep.add_mm(Z_AXIS, offs); #if ENABLED(BABYSTEP_ZPROBE_OFFSET) - if (!parser.seen('P') || parser.value_bool()) mod_probe_offset(offs); + if (parser.boolval('P', true)) mod_probe_offset(offs); #endif } #endif - if (!parser.seen("XYZ") || parser.seen('R')) { + if (!parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR)) || parser.seen('R')) { SERIAL_ECHO_START(); #if ENABLED(BABYSTEP_ZPROBE_OFFSET) @@ -100,7 +97,7 @@ void GcodeSuite::M290() { #if ENABLED(BABYSTEP_HOTEND_Z_OFFSET) { SERIAL_ECHOLNPAIR_P( - PSTR("Hotend "), int(active_extruder) + PSTR("Hotend "), active_extruder #if ENABLED(BABYSTEP_XY) , PSTR("Offset X"), hotend_offset[active_extruder].x , SP_Y_STR, hotend_offset[active_extruder].y diff --git a/Marlin/src/gcode/parser.cpp b/Marlin/src/gcode/parser.cpp index 9c5085b97eca..e4e297344940 100644 --- a/Marlin/src/gcode/parser.cpp +++ b/Marlin/src/gcode/parser.cpp @@ -28,10 +28,6 @@ #include "../MarlinCore.h" -#if HAS_MULTI_SERIAL - #include "queue.h" -#endif - // Must be declared for allocation and to satisfy the linker // Zero values need no initialization. @@ -49,15 +45,15 @@ char *GCodeParser::command_ptr, *GCodeParser::string_arg, *GCodeParser::value_ptr; char GCodeParser::command_letter; -int GCodeParser::codenum; +uint16_t GCodeParser::codenum; -#if ENABLED(USE_GCODE_SUBCODES) +#if USE_GCODE_SUBCODES uint8_t GCodeParser::subcode; #endif #if ENABLED(GCODE_MOTION_MODES) int16_t GCodeParser::motion_mode_codenum = -1; - #if ENABLED(USE_GCODE_SUBCODES) + #if USE_GCODE_SUBCODES uint8_t GCodeParser::motion_mode_subcode; #endif #endif @@ -110,8 +106,10 @@ void GCodeParser::reset() { #endif -// Populate all fields by parsing a single line of GCode -// 58 bytes of SRAM are used to speed up seen/value +/** + * 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. + */ void GCodeParser::parse(char *p) { reset(); // No codes to report @@ -151,15 +149,35 @@ void GCodeParser::parse(char *p) { #define SIGNED_CODENUM 1 #endif - // Bail if the letter is not G, M, or T - // (or a valid parameter for the current motion mode) - switch (letter) { + /** + * Screen for good command letters. + * With Realtime Reporting, commands S000, P000, and R000 are allowed. + */ + #if ENABLED(REALTIME_REPORTING_COMMANDS) + switch (letter) { + case 'P': case 'R' ... 'S': { + uint8_t digits = 0; + char *a = p; + while (*a++ == '0') digits++; // Count up '0' characters + if (digits == 3) { // Three '0' digits is a good command + codenum = 0; + command_letter = letter; + return; + } + } + } + #endif - case 'G': case 'M': case 'T': TERN_(MARLIN_DEV_MODE, case 'D':) + /** + * Screen for good command letters. G, M, and T are always accepted. + * With Motion Modes enabled any axis letter can come first. + */ + switch (letter) { + case 'G': case 'M': case 'T': TERN_(MARLIN_DEV_MODE, case 'D':) { // Skip spaces to get the numeric part while (*p == ' ') p++; - #if ENABLED(PRUSA_MMU2) + #if HAS_PRUSA_MMU2 if (letter == 'T') { // check for special MMU2 T?/Tx/Tc commands if (*p == '?' || *p == 'x' || *p == 'c') { @@ -177,23 +195,21 @@ void GCodeParser::parse(char *p) { // A '?' signifies an unknown command command_letter = letter; - { - #if ENABLED(SIGNED_CODENUM) - int sign = 1; // Allow for a negative code like D-1 or T-1 - if (*p == '-') { sign = -1; ++p; } - #endif + #if ENABLED(SIGNED_CODENUM) + int sign = 1; // Allow for a negative code like D-1 or T-1 + if (*p == '-') { sign = -1; ++p; } + #endif - // Get the code number - integer digits only - codenum = 0; + // Get the code number - integer digits only + codenum = 0; - do { codenum = codenum * 10 + *p++ - '0'; } while (NUMERIC(*p)); + do { codenum = codenum * 10 + *p++ - '0'; } while (NUMERIC(*p)); - // Apply the sign, if any - TERN_(SIGNED_CODENUM, codenum *= sign); - } + // Apply the sign, if any + TERN_(SIGNED_CODENUM, codenum *= sign); // Allow for decimal point in command - #if ENABLED(USE_GCODE_SUBCODES) + #if USE_GCODE_SUBCODES if (*p == '.') { p++; while (NUMERIC(*p)) @@ -206,48 +222,54 @@ void GCodeParser::parse(char *p) { #if ENABLED(GCODE_MOTION_MODES) if (letter == 'G' - && (codenum <= TERN(ARC_SUPPORT, 3, 1) || codenum == 5 || TERN0(G38_PROBE_TARGET, codenum == 38)) + && (codenum <= TERN(ARC_SUPPORT, 3, 1) || TERN0(BEZIER_CURVE_SUPPORT, codenum == 5) || TERN0(G38_PROBE_TARGET, codenum == 38)) ) { motion_mode_codenum = codenum; TERN_(USE_GCODE_SUBCODES, motion_mode_subcode = subcode); } #endif - break; + } break; #if ENABLED(GCODE_MOTION_MODES) + + #if EITHER(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)) + ) return; + #endif + + #if ENABLED(BEZIER_CURVE_SUPPORT) + case 'Q': if (motion_mode_codenum != 5) return; + #endif + #if ENABLED(ARC_SUPPORT) - case 'I' ... 'J': case 'R': - if (motion_mode_codenum != 2 && motion_mode_codenum != 3) return; + case 'R': if (!WITHIN(motion_mode_codenum, 2, 3)) return; #endif - case 'P' ... 'Q': - if (motion_mode_codenum != 5) return; - case 'X' ... 'Z': case 'E' ... 'F': + + LOGICAL_AXIS_GANG(case 'E':, case 'X':, case 'Y':, case 'Z':, case AXIS4_NAME:, case AXIS5_NAME:, case AXIS6_NAME:) + case 'F': if (motion_mode_codenum < 0) return; command_letter = 'G'; codenum = motion_mode_codenum; TERN_(USE_GCODE_SUBCODES, subcode = motion_mode_subcode); p--; // Back up one character to use the current parameter - break; - #endif // GCODE_MOTION_MODES + break; + + #endif default: return; } // The command parameters (if any) start here, for sure! - #if DISABLED(FASTER_GCODE_PARSER) - command_args = p; // Scan for parameters in seen() - #endif + IF_DISABLED(FASTER_GCODE_PARSER, command_args = p); // Scan for parameters in seen() // Only use string_arg for these M codes if (letter == 'M') switch (codenum) { - #if ENABLED(GCODE_MACROS) - case 810 ... 819: - #endif - #if ENABLED(EXPECTED_PRINTER_CHECK) - case 16: - #endif + TERN_(GCODE_MACROS, case 810 ... 819:) + TERN_(EXPECTED_PRINTER_CHECK, case 16:) case 23: case 28: case 30: case 117 ... 118: case 928: string_arg = unescape_string(p); return; @@ -274,7 +296,7 @@ void GCodeParser::parse(char *p) { // Special handling for M32 [P] !/path/to/file.g# // The path must be the last parameter - if (param == '!' && letter == 'M' && codenum == 32) { + if (param == '!' && is_command('M', 32)) { string_arg = p; // Name starts after '!' char * const lb = strchr(p, '#'); // Already seen '#' as SD char (to pause buffering) if (lb) *lb = '\0'; // Safe to mark the end of the filename @@ -311,7 +333,7 @@ void GCodeParser::parse(char *p) { #if ENABLED(DEBUG_GCODE_PARSER) if (debug) { - SERIAL_ECHOPAIR("Got param ", param, " at index ", (int)(p - command_ptr - 1)); + SERIAL_ECHOPAIR("Got param ", AS_CHAR(param), " at index ", p - command_ptr - 1); if (has_val) SERIAL_ECHOPGM(" (has_val)"); } #endif @@ -395,8 +417,8 @@ void GCodeParser::unknown_command_warning() { "\n sec-ms: ", value_millis_from_seconds(), "\n int: ", value_int(), "\n ushort: ", value_ushort(), - "\n byte: ", (int)value_byte(), - "\n bool: ", (int)value_bool(), + "\n byte: ", value_byte(), + "\n bool: ", value_bool(), "\n linear: ", value_linear_units(), "\n celsius: ", value_celsius() ); diff --git a/Marlin/src/gcode/parser.h b/Marlin/src/gcode/parser.h index 42b85ca27195..08cf10004a16 100644 --- a/Marlin/src/gcode/parser.h +++ b/Marlin/src/gcode/parser.h @@ -84,14 +84,14 @@ class GCodeParser { static char *command_ptr, // The command, so it can be echoed *string_arg, // string of command line command_letter; // G, M, or T - static int codenum; // 123 - #if ENABLED(USE_GCODE_SUBCODES) + static uint16_t codenum; // 123 + #if USE_GCODE_SUBCODES static uint8_t subcode; // .1 #endif #if ENABLED(GCODE_MOTION_MODES) static int16_t motion_mode_codenum; - #if ENABLED(USE_GCODE_SUBCODES) + #if USE_GCODE_SUBCODES static uint8_t motion_mode_subcode; #endif FORCE_INLINE static void cancel_motion_mode() { motion_mode_codenum = -1; } @@ -133,9 +133,9 @@ class GCodeParser { param[ind] = ptr ? ptr - command_ptr : 0; // parameter offset or 0 #if ENABLED(DEBUG_GCODE_PARSER) if (codenum == 800) { - SERIAL_ECHOPAIR("Set bit ", (int)ind, " of codebits (", hex_address((void*)(codebits >> 16))); + SERIAL_ECHOPAIR("Set bit ", ind, " of codebits (", hex_address((void*)(codebits >> 16))); print_hex_word((uint16_t)(codebits & 0xFFFF)); - SERIAL_ECHOLNPAIR(") | param = ", (int)param[ind]); + SERIAL_ECHOLNPAIR(") | param = ", param[ind]); } #endif } @@ -226,7 +226,7 @@ class GCodeParser { // Seen any axis parameter static inline bool seen_axis() { - return seen_test('X') || seen_test('Y') || seen_test('Z') || seen_test('E'); + return seen(LOGICAL_AXIS_GANG("E", "X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR)); } #if ENABLED(GCODE_QUOTED_STRINGS) @@ -244,8 +244,11 @@ class GCodeParser { static bool chain(); #endif + // Test whether the parsed command matches the input + static inline bool is_command(const char ltr, const uint16_t num) { return command_letter == ltr && codenum == num; } + // The code value pointer was set - FORCE_INLINE static bool has_value() { return value_ptr != nullptr; } + FORCE_INLINE static bool has_value() { return !!value_ptr; } // Seen a parameter with a value static inline bool seenval(const char c) { return seen(c) && has_value(); } @@ -279,7 +282,7 @@ class GCodeParser { // Code value for use as time static inline millis_t value_millis() { return value_ulong(); } - static inline millis_t value_millis_from_seconds() { return (millis_t)(value_float() * 1000); } + static inline millis_t value_millis_from_seconds() { return (millis_t)SEC_TO_MS(value_float()); } // Reduce to fewer bits static inline int16_t value_int() { return (int16_t)value_long(); } @@ -292,8 +295,8 @@ class GCodeParser { // Units modes: Inches, Fahrenheit, Kelvin #if ENABLED(INCH_MODE_SUPPORT) - static inline float mm_to_linear_unit(const float mm) { return mm / linear_unit_factor; } - static inline float mm_to_volumetric_unit(const float mm) { return mm / (volumetric_enabled ? volumetric_unit_factor : linear_unit_factor); } + static inline float mm_to_linear_unit(const_float_t mm) { return mm / linear_unit_factor; } + static inline float mm_to_volumetric_unit(const_float_t mm) { return mm / (volumetric_enabled ? volumetric_unit_factor : linear_unit_factor); } // Init linear units by constructor GCodeParser() { set_input_linear_units(LINEARUNIT_MM); } @@ -308,24 +311,34 @@ class GCodeParser { } static inline float axis_unit_factor(const AxisEnum axis) { - return (axis >= E_AXIS && volumetric_enabled ? volumetric_unit_factor : linear_unit_factor); + return ( + #if HAS_EXTRUDERS + axis >= E_AXIS && volumetric_enabled ? volumetric_unit_factor : linear_unit_factor + #else + linear_unit_factor + #endif + ); } - static inline float linear_value_to_mm(const float v) { return v * linear_unit_factor; } + static inline float linear_value_to_mm(const_float_t v) { return v * linear_unit_factor; } static inline float axis_value_to_mm(const AxisEnum axis, const float v) { return v * axis_unit_factor(axis); } static inline float per_axis_value(const AxisEnum axis, const float v) { return v / axis_unit_factor(axis); } #else - static inline float mm_to_linear_unit(const float mm) { return mm; } - static inline float mm_to_volumetric_unit(const float mm) { return mm; } + static inline float mm_to_linear_unit(const_float_t mm) { return mm; } + static inline float mm_to_volumetric_unit(const_float_t mm) { return mm; } - static inline float linear_value_to_mm(const float v) { return v; } + static inline float linear_value_to_mm(const_float_t v) { return v; } static inline float axis_value_to_mm(const AxisEnum, const float v) { return v; } static inline float per_axis_value(const AxisEnum, const float v) { return v; } #endif + static inline bool using_inch_units() { return mm_to_linear_unit(1.0f) != 1.0f; } + + #define IN_TO_MM(I) ((I) * 25.4f) + #define MM_TO_IN(M) ((M) / 25.4f) #define LINEAR_UNIT(V) parser.mm_to_linear_unit(V) #define VOLUMETRIC_UNIT(V) parser.mm_to_volumetric_unit(V) @@ -345,52 +358,45 @@ class GCodeParser { static inline PGM_P temp_units_name() { return input_temp_units == TEMPUNIT_K ? PSTR("Kelvin") : input_temp_units == TEMPUNIT_F ? PSTR("Fahrenheit") : PSTR("Celsius"); } - static inline float to_temp_units(const float &f) { + static inline float to_temp_units(celsius_t c) { switch (input_temp_units) { - case TEMPUNIT_F: - return f * 0.5555555556f + 32; - case TEMPUNIT_K: - return f + 273.15f; - case TEMPUNIT_C: default: - return f; + case TEMPUNIT_C: return c; + case TEMPUNIT_K: return c + 273.15f; + case TEMPUNIT_F: return c * 0.5555555556f + 32; } } #endif // HAS_LCD_MENU && !DISABLE_M503 - static inline float value_celsius() { - const float f = value_float(); + static inline celsius_t value_celsius() { + float f = value_float(); switch (input_temp_units) { - case TEMPUNIT_F: - return (f - 32) * 0.5555555556f; - case TEMPUNIT_K: - return f - 273.15f; - case TEMPUNIT_C: default: - return f; + case TEMPUNIT_C: break; + case TEMPUNIT_K: f -= 273.15f; + case TEMPUNIT_F: f = (f - 32) * 0.5555555556f; } + return LROUND(f); } - static inline float value_celsius_diff() { + static inline celsius_t value_celsius_diff() { + float f = value_float(); switch (input_temp_units) { - case TEMPUNIT_F: - return value_float() * 0.5555555556f; - case TEMPUNIT_C: - case TEMPUNIT_K: default: - return value_float(); + case TEMPUNIT_C: + case TEMPUNIT_K: break; + case TEMPUNIT_F: f *= 0.5555555556f; } + return LROUND(f); } - #define TEMP_UNIT(N) parser.to_temp_units(N) - #else // !TEMPERATURE_UNITS_SUPPORT - static inline float value_celsius() { return value_float(); } - static inline float value_celsius_diff() { return value_float(); } + static inline float to_temp_units(int16_t c) { return (float)c; } - #define TEMP_UNIT(N) (N) + static inline celsius_t value_celsius() { return value_int(); } + static inline celsius_t value_celsius_diff() { return value_int(); } #endif // !TEMPERATURE_UNITS_SUPPORT @@ -399,16 +405,18 @@ class GCodeParser { void unknown_command_warning(); // Provide simple value accessors with default option - static inline char* stringval(const char c, char * const dval=nullptr) { return seenval(c) ? value_string() : dval; } - static inline float floatval(const char c, const float dval=0.0) { return seenval(c) ? value_float() : dval; } - static inline bool boolval(const char c, const bool dval=false) { return seenval(c) ? value_bool() : (seen(c) ? true : dval); } - static inline uint8_t byteval(const char c, const uint8_t dval=0) { return seenval(c) ? value_byte() : dval; } - static inline int16_t intval(const char c, const int16_t dval=0) { return seenval(c) ? value_int() : dval; } - static inline uint16_t ushortval(const char c, const uint16_t dval=0) { return seenval(c) ? value_ushort() : dval; } - static inline int32_t longval(const char c, const int32_t dval=0) { return seenval(c) ? value_long() : dval; } - static inline uint32_t ulongval(const char c, const uint32_t dval=0) { return seenval(c) ? value_ulong() : dval; } - static inline float linearval(const char c, const float dval=0) { return seenval(c) ? value_linear_units() : dval; } - static inline float celsiusval(const char c, const float dval=0) { return seenval(c) ? value_celsius() : dval; } + static inline char* stringval(const char c, char * const dval=nullptr) { return seenval(c) ? value_string() : dval; } + static inline float floatval(const char c, const float dval=0.0) { return seenval(c) ? value_float() : dval; } + static inline bool boolval(const char c, const bool dval=false) { return seenval(c) ? value_bool() : (seen(c) ? true : dval); } + static inline uint8_t byteval(const char c, const uint8_t dval=0) { return seenval(c) ? value_byte() : dval; } + static inline int16_t intval(const char c, const int16_t dval=0) { return seenval(c) ? value_int() : dval; } + static inline uint16_t ushortval(const char c, const uint16_t dval=0) { return seenval(c) ? value_ushort() : dval; } + static inline int32_t longval(const char c, const int32_t dval=0) { return seenval(c) ? value_long() : dval; } + static inline uint32_t ulongval(const char c, const uint32_t dval=0) { return seenval(c) ? value_ulong() : dval; } + static inline float linearval(const char c, const float dval=0) { return seenval(c) ? value_linear_units() : dval; } + static inline float axisunitsval(const char c, const AxisEnum a, const float dval=0) + { return seenval(c) ? value_axis_units(a) : dval; } + static inline celsius_t celsiusval(const char c, const float dval=0) { return seenval(c) ? value_celsius() : dval; } #if ENABLED(MARLIN_DEV_MODE) diff --git a/Marlin/src/gcode/probe/G38.cpp b/Marlin/src/gcode/probe/G38.cpp index b06cd47359c7..6906805fca14 100644 --- a/Marlin/src/gcode/probe/G38.cpp +++ b/Marlin/src/gcode/probe/G38.cpp @@ -38,7 +38,7 @@ inline void G38_single_probe(const uint8_t move_value) { planner.synchronize(); G38_move = 0; endstops.hit_on_purpose(); - set_current_from_steppers_for_axis(ALL_AXES); + set_current_from_steppers_for_axis(ALL_AXES_ENUM); sync_plan_position(); } @@ -49,7 +49,7 @@ inline bool G38_run_probe() { #if MULTIPLE_PROBING > 1 // Get direction of move and retract xyz_float_t retract_mm; - LOOP_XYZ(i) { + LOOP_LINEAR_AXES(i) { const float dist = destination[i] - current_position[i]; retract_mm[i] = ABS(dist) < G38_MINIMUM_MOVE ? 0 : home_bump_mm((AxisEnum)i) * (dist > 0 ? -1 : 1); } @@ -119,7 +119,7 @@ void GcodeSuite::G38(const int8_t subcode) { ; // If any axis has enough movement, do the move - LOOP_XYZ(i) + LOOP_LINEAR_AXES(i) if (ABS(destination[i] - current_position[i]) >= G38_MINIMUM_MOVE) { if (!parser.seenval('F')) feedrate_mm_s = homing_feedrate((AxisEnum)i); // If G38.2 fails throw an error diff --git a/Marlin/src/gcode/probe/M401_M402.cpp b/Marlin/src/gcode/probe/M401_M402.cpp index 8e9bd11b81d7..bd9bb44c4061 100644 --- a/Marlin/src/gcode/probe/M401_M402.cpp +++ b/Marlin/src/gcode/probe/M401_M402.cpp @@ -33,6 +33,7 @@ */ void GcodeSuite::M401() { probe.deploy(); + TERN_(PROBE_TARE, probe.tare()); report_current_position(); } diff --git a/Marlin/src/gcode/probe/M851.cpp b/Marlin/src/gcode/probe/M851.cpp index ee60e9ebc011..ee6244932e6d 100644 --- a/Marlin/src/gcode/probe/M851.cpp +++ b/Marlin/src/gcode/probe/M851.cpp @@ -28,8 +28,6 @@ #include "../../feature/bedlevel/bedlevel.h" #include "../../module/probe.h" -extern const char SP_Y_STR[], SP_Z_STR[]; - /** * M851: Set the nozzle-to-probe offsets in current units */ @@ -60,7 +58,7 @@ void GcodeSuite::M851() { if (WITHIN(x, -(X_BED_SIZE), X_BED_SIZE)) offs.x = x; else { - SERIAL_ECHOLNPAIR("?X out of range (-", int(X_BED_SIZE), " to ", int(X_BED_SIZE), ")"); + SERIAL_ECHOLNPAIR("?X out of range (-", X_BED_SIZE, " to ", X_BED_SIZE, ")"); ok = false; } #else @@ -74,7 +72,7 @@ void GcodeSuite::M851() { if (WITHIN(y, -(Y_BED_SIZE), Y_BED_SIZE)) offs.y = y; else { - SERIAL_ECHOLNPAIR("?Y out of range (-", int(Y_BED_SIZE), " to ", int(Y_BED_SIZE), ")"); + SERIAL_ECHOLNPAIR("?Y out of range (-", Y_BED_SIZE, " to ", Y_BED_SIZE, ")"); ok = false; } #else @@ -87,7 +85,7 @@ void GcodeSuite::M851() { if (WITHIN(z, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX)) offs.z = z; else { - SERIAL_ECHOLNPAIR("?Z out of range (", int(Z_PROBE_OFFSET_RANGE_MIN), " to ", int(Z_PROBE_OFFSET_RANGE_MAX), ")"); + SERIAL_ECHOLNPAIR("?Z out of range (", Z_PROBE_OFFSET_RANGE_MIN, " to ", Z_PROBE_OFFSET_RANGE_MAX, ")"); ok = false; } } diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp index a02d2c016042..09755fbf21a8 100644 --- a/Marlin/src/gcode/queue.cpp +++ b/Marlin/src/gcode/queue.cpp @@ -29,16 +29,22 @@ GCodeQueue queue; #include "gcode.h" -#include "../lcd/ultralcd.h" +#include "../lcd/marlinui.h" #include "../sd/cardreader.h" +#include "../module/motion.h" #include "../module/planner.h" #include "../module/temperature.h" #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 @@ -47,44 +53,24 @@ GCodeQueue queue; #include "../feature/powerloss.h" #endif -/** - * GCode line number handling. Hosts may opt to include line numbers when - * sending commands to Marlin, and lines will be checked for sequentiality. - * M110 N sets the current line number. - */ -long GCodeQueue::last_N[NUM_SERIAL]; +#if ENABLED(GCODE_REPEAT_MARKERS) + #include "../feature/repeat.h" +#endif -/** - * GCode Command Queue - * A simple ring buffer of BUFSIZE command strings. - * - * Commands are copied into this buffer by the command injectors - * (immediate, serial, sd card) and they are processed sequentially by - * the main loop. The gcode.process_next_command method parses the next - * command and hands off execution to individual handler functions. - */ -uint8_t GCodeQueue::length = 0, // Count of commands in the queue - GCodeQueue::index_r = 0, // Ring buffer read position - GCodeQueue::index_w = 0; // Ring buffer write position +// Frequently used G-code strings +PGMSTR(G28_STR, "G28"); -char GCodeQueue::command_buffer[BUFSIZE][MAX_CMD_SIZE]; +GCodeQueue::SerialState GCodeQueue::serial_state[NUM_SERIAL] = { 0 }; +GCodeQueue::RingBuffer GCodeQueue::ring_buffer = { 0 }; -/* - * The port that the command was received on - */ -#if HAS_MULTI_SERIAL - int16_t GCodeQueue::port[BUFSIZE]; +#if NO_TIMEOUTS > 0 + static millis_t last_command_time = 0; #endif /** * Serial command injection */ -// Number of characters read in the current line of serial input -static int serial_count[NUM_SERIAL] = { 0 }; - -bool send_ok[BUFSIZE]; - /** * Next Injected PROGMEM Command pointer. (nullptr == empty) * Internal commands are enqueued ahead of serial / SD commands. @@ -96,38 +82,14 @@ PGM_P GCodeQueue::injected_commands_P; // = nullptr */ char GCodeQueue::injected_commands[64]; // = { 0 } -GCodeQueue::GCodeQueue() { - // Send "ok" after commands by default - LOOP_L_N(i, COUNT(send_ok)) send_ok[i] = true; -} -/** - * Check whether there are any commands yet to be executed - */ -bool GCodeQueue::has_commands_queued() { - return queue.length || injected_commands_P || injected_commands[0]; -} - -/** - * Clear the Marlin command queue - */ -void GCodeQueue::clear() { - index_r = index_w = length = 0; -} - -/** - * Once a new command is in the ring buffer, call this to commit it - */ -void GCodeQueue::_commit_command(bool say_ok - #if HAS_MULTI_SERIAL - , int16_t p/*=-1*/ - #endif +void GCodeQueue::RingBuffer::commit_command(bool skip_ok + OPTARG(HAS_MULTI_SERIAL, serial_index_t serial_ind/*=-1*/) ) { - send_ok[index_w] = say_ok; - TERN_(HAS_MULTI_SERIAL, port[index_w] = p); + commands[index_w].skip_ok = skip_ok; + TERN_(HAS_MULTI_SERIAL, commands[index_w].port = serial_ind); TERN_(POWER_LOSS_RECOVERY, recovery.commit_sdpos(index_w)); - if (++index_w >= BUFSIZE) index_w = 0; - length++; + advance_pos(index_w, 1); } /** @@ -135,36 +97,29 @@ void GCodeQueue::_commit_command(bool say_ok * Return true if the command was successfully added. * Return false for a full buffer, or if the 'command' is a comment. */ -bool GCodeQueue::_enqueue(const char* cmd, bool say_ok/*=false*/ - #if HAS_MULTI_SERIAL - , int16_t pn/*=-1*/ - #endif +bool GCodeQueue::RingBuffer::enqueue(const char *cmd, bool skip_ok/*=true*/ + OPTARG(HAS_MULTI_SERIAL, serial_index_t serial_ind/*=-1*/) ) { if (*cmd == ';' || length >= BUFSIZE) return false; - strcpy(command_buffer[index_w], cmd); - _commit_command(say_ok + strcpy(commands[index_w].buffer, cmd); + commit_command(skip_ok #if HAS_MULTI_SERIAL - , pn + , serial_ind #endif ); return true; } -#define ISEOL(C) ((C) == '\n' || (C) == '\r') - /** * Enqueue with Serial Echo * Return true if the command was consumed */ -bool GCodeQueue::enqueue_one(const char* cmd) { - - //SERIAL_ECHOPGM("enqueue_one(\""); - //SERIAL_ECHO(cmd); - //SERIAL_ECHOPGM("\") \n"); +bool GCodeQueue::enqueue_one(const char *cmd) { + //SERIAL_ECHOLNPAIR("enqueue_one(\"", cmd, "\")"); if (*cmd == 0 || ISEOL(*cmd)) return true; - if (_enqueue(cmd)) { + if (ring_buffer.enqueue(cmd)) { SERIAL_ECHO_MSG(STR_ENQUEUEING, cmd, "\""); return true; } @@ -176,7 +131,7 @@ bool GCodeQueue::enqueue_one(const char* cmd) { * Return 'true' if any commands were processed. */ bool GCodeQueue::process_injected_command_P() { - if (injected_commands_P == nullptr) return false; + if (!injected_commands_P) return false; char c; size_t i = 0; @@ -228,7 +183,7 @@ bool GCodeQueue::process_injected_command() { * Enqueue and return only when commands are actually enqueued. * Never call this from a G-code handler! */ -void GCodeQueue::enqueue_one_now(const char* cmd) { while (!enqueue_one(cmd)) idle(); } +void GCodeQueue::enqueue_one_now(const char *cmd) { while (!enqueue_one(cmd)) idle(); } /** * Attempt to enqueue a single G-code command @@ -242,7 +197,7 @@ bool GCodeQueue::enqueue_one_P(PGM_P const pgcode) { char cmd[i + 1]; memcpy_P(cmd, p, i); cmd[i] = '\0'; - return _enqueue(cmd); + return ring_buffer.enqueue(cmd); } /** @@ -273,24 +228,28 @@ void GCodeQueue::enqueue_now_P(PGM_P const pgcode) { * P Planner space remaining * B Block queue space remaining */ -void GCodeQueue::ok_to_send() { +void GCodeQueue::RingBuffer::ok_to_send() { + #if NO_TIMEOUTS > 0 + // Start counting from the last command's execution + last_command_time = millis(); + #endif + CommandLine &command = commands[index_r]; #if HAS_MULTI_SERIAL - const int16_t pn = command_port(); - if (pn < 0) return; - PORT_REDIRECT(pn); // Reply to the serial port that sent the command + const serial_index_t serial_ind = command.port; + if (!serial_ind.valid()) return; // Optimization here, skip processing if it's not going anywhere + PORT_REDIRECT(SERIAL_PORTMASK(serial_ind)); // Reply to the serial port that sent the command #endif - if (!send_ok[index_r]) return; + if (command.skip_ok) return; SERIAL_ECHOPGM(STR_OK); #if ENABLED(ADVANCED_OK) - char* p = command_buffer[index_r]; + char* p = command.buffer; if (*p == 'N') { - SERIAL_ECHO(' '); - SERIAL_ECHO(*p++); + SERIAL_CHAR(' ', *p++); while (NUMERIC_SIGNED(*p)) - SERIAL_ECHO(*p++); + SERIAL_CHAR(*p++); } - SERIAL_ECHOPAIR_P(SP_P_STR, int(planner.moves_free()), - SP_B_STR, int(BUFSIZE - length)); + SERIAL_ECHOPAIR_P(SP_P_STR, planner.moves_free(), + SP_B_STR, BUFSIZE - length); #endif SERIAL_EOL(); } @@ -299,40 +258,46 @@ void GCodeQueue::ok_to_send() { * Send a "Resend: nnn" message to the host to * indicate that a command needs to be re-sent. */ -void GCodeQueue::flush_and_request_resend() { - const int16_t pn = command_port(); +void GCodeQueue::flush_and_request_resend(const serial_index_t serial_ind) { #if HAS_MULTI_SERIAL - if (pn < 0) return; - PORT_REDIRECT(pn); // Reply to the serial port that sent the command + if (!serial_ind.valid()) return; // Optimization here, skip if the command came from SD or Flash Drive + PORT_REDIRECT(SERIAL_PORTMASK(serial_ind)); // Reply to the serial port that sent the command #endif SERIAL_FLUSH(); - SERIAL_ECHOPGM(STR_RESEND); - SERIAL_ECHOLN(last_N[pn] + 1); - ok_to_send(); + SERIAL_ECHOLNPAIR(STR_RESEND, serial_state[serial_ind.index].last_N + 1); + SERIAL_ECHOLNPGM(STR_OK); } -inline bool serial_data_available() { - return MYSERIAL0.available() || TERN0(HAS_MULTI_SERIAL, MYSERIAL1.available()); +static bool serial_data_available(serial_index_t index) { + const int a = SERIAL_IMPL.available(index); + #if BOTH(RX_BUFFER_MONITOR, RX_BUFFER_SIZE) + if (a > RX_BUFFER_SIZE - 2) { + PORT_REDIRECT(SERIAL_PORTMASK(index)); + SERIAL_ERROR_MSG("RX BUF overflow, increase RX_BUFFER_SIZE: ", a); + } + #endif + return a > 0; } -inline int read_serial(const uint8_t index) { - switch (index) { - case 0: return MYSERIAL0.read(); - #if HAS_MULTI_SERIAL - case 1: return MYSERIAL1.read(); - #endif - default: return -1; +#if NO_TIMEOUTS > 0 + // Multiserial already handles dispatch to/from multiple ports + static bool any_serial_data_available() { + LOOP_L_N(p, NUM_SERIAL) + if (serial_data_available(p)) + return true; + return false; } -} +#endif + +inline int read_serial(const serial_index_t index) { return SERIAL_IMPL.read(index); } -void GCodeQueue::gcode_line_error(PGM_P const err, const int8_t pn) { - PORT_REDIRECT(pn); // Reply to the serial port that sent the command +void GCodeQueue::gcode_line_error(PGM_P const err, const serial_index_t serial_ind) { + PORT_REDIRECT(SERIAL_PORTMASK(serial_ind)); // Reply to the serial port that sent the command SERIAL_ERROR_START(); - serialprintPGM(err); - SERIAL_ECHOLN(last_N[pn]); - while (read_serial(pn) != -1); // Clear out the RX buffer - flush_and_request_resend(); - serial_count[pn] = 0; + SERIAL_ECHOLNPAIR_P(err, serial_state[serial_ind.index].last_N); + while (read_serial(serial_ind) != -1) { /* nada */ } // Clear out the RX buffer. Why don't use flush here ? + flush_and_request_resend(serial_ind); + serial_state[serial_ind.index].count = 0; } FORCE_INLINE bool is_M29(const char * const cmd) { // matches "M29" & "M29 ", but not "M290", etc @@ -403,11 +368,14 @@ inline void process_stream_char(const char c, uint8_t &sis, char (&buff)[MAX_CMD * keep sensor readings going and watchdog alive. */ inline bool process_line_done(uint8_t &sis, char (&buff)[MAX_CMD_SIZE], int &ind) { - sis = PS_NORMAL; - buff[ind] = 0; - if (ind) { ind = 0; return false; } - thermalManager.manage_heater(); - return true; + sis = PS_NORMAL; // "Normal" Serial Input State + buff[ind] = '\0'; // Of course, I'm a Terminator. + const bool is_empty = (ind == 0); // An empty line? + if (is_empty) + thermalManager.manage_heater(); // Keep sensors satisfied + else + ind = 0; // Start a new line + return is_empty; // Inform the caller } /** @@ -416,10 +384,6 @@ inline bool process_line_done(uint8_t &sis, char (&buff)[MAX_CMD_SIZE], int &ind * left on the serial port. */ void GCodeQueue::get_serial_commands() { - static char serial_line_buffer[NUM_SERIAL][MAX_CMD_SIZE]; - - static uint8_t serial_input_state[NUM_SERIAL] = { PS_NORMAL }; - #if ENABLED(BINARY_FILE_TRANSFER) if (card.flag.binary_mode) { /** @@ -427,7 +391,7 @@ void GCodeQueue::get_serial_commands() { * receive buffer (which limits the packet size to MAX_CMD_SIZE). * The receive buffer also limits the packet size for reliable transmission. */ - binaryStream[card.transfer_port_index].receive(serial_line_buffer[card.transfer_port_index]); + binaryStream[card.transfer_port_index.index].receive(serial_state[card.transfer_port_index.index].line_buffer); return; } #endif @@ -435,39 +399,56 @@ void GCodeQueue::get_serial_commands() { // If the command buffer is empty for too long, // send "wait" to indicate Marlin is still waiting. #if NO_TIMEOUTS > 0 - static millis_t last_command_time = 0; const millis_t ms = millis(); - if (length == 0 && !serial_data_available() && ELAPSED(ms, last_command_time + NO_TIMEOUTS)) { + if (ring_buffer.empty() && !any_serial_data_available() && ELAPSED(ms, last_command_time + NO_TIMEOUTS)) { SERIAL_ECHOLNPGM(STR_WAIT); last_command_time = ms; } #endif - /** - * Loop while serial characters are incoming and the queue is not full - */ - while (length < BUFSIZE && serial_data_available()) { - LOOP_L_N(i, NUM_SERIAL) { - - const int c = read_serial(i); - if (c < 0) continue; + // Loop while serial characters are incoming and the queue is not full + for (bool hadData = true; hadData;) { + // Unless a serial port has data, this will exit on next iteration + hadData = false; + + LOOP_L_N(p, NUM_SERIAL) { + // Check if the queue is full and exit if it is. + if (ring_buffer.full()) return; + + // No data for this port ? Skip it + if (!serial_data_available(p)) continue; + + // Ok, we have some data to process, let's make progress here + hadData = true; + + const int c = read_serial(p); + if (c < 0) { + // This should never happen, let's log it + PORT_REDIRECT(SERIAL_PORTMASK(p)); // Reply to the serial port that sent the command + // Crash here to get more information why it failed + BUG_ON("SP available but read -1"); + SERIAL_ERROR_MSG(STR_ERR_SERIAL_MISMATCH); + SERIAL_FLUSH(); + continue; + } - const char serial_char = c; + const char serial_char = (char)c; + SerialState &serial = serial_state[p]; if (ISEOL(serial_char)) { // Reset our state, continue if the line was empty - if (process_line_done(serial_input_state[i], serial_line_buffer[i], serial_count[i])) + if (process_line_done(serial.input_state, serial.line_buffer, serial.count)) continue; - char* command = serial_line_buffer[i]; + char* command = serial.line_buffer; while (*command == ' ') command++; // Skip leading spaces char *npos = (*command == 'N') ? command : nullptr; // Require the N parameter to start the line if (npos) { - bool M110 = strstr_P(command, PSTR("M110")) != nullptr; + const bool M110 = !!strstr_P(command, PSTR("M110")); if (M110) { char* n2pos = strchr(command + 4, 'N'); @@ -476,25 +457,36 @@ void GCodeQueue::get_serial_commands() { const long gcode_N = strtol(npos + 1, nullptr, 10); - if (gcode_N != last_N[i] + 1 && !M110) - return gcode_line_error(PSTR(STR_ERR_LINE_NO), i); + if (gcode_N != serial.last_N + 1 && !M110) { + // In case of error on a serial port, don't prevent other serial port from making progress + gcode_line_error(PSTR(STR_ERR_LINE_NO), p); + break; + } char *apos = strrchr(command, '*'); if (apos) { uint8_t checksum = 0, count = uint8_t(apos - command); while (count) checksum ^= command[--count]; - if (strtol(apos + 1, nullptr, 10) != checksum) - return gcode_line_error(PSTR(STR_ERR_CHECKSUM_MISMATCH), i); + if (strtol(apos + 1, nullptr, 10) != checksum) { + // In case of error on a serial port, don't prevent other serial port from making progress + gcode_line_error(PSTR(STR_ERR_CHECKSUM_MISMATCH), p); + break; + } + } + else { + // In case of error on a serial port, don't prevent other serial port from making progress + gcode_line_error(PSTR(STR_ERR_NO_CHECKSUM), p); + break; } - else - return gcode_line_error(PSTR(STR_ERR_NO_CHECKSUM), i); - last_N[i] = gcode_N; + serial.last_N = gcode_N; } #if ENABLED(SDSUPPORT) // Pronterface "M29" and "M29 " has no line number - else if (card.flag.saving && !is_M29(command)) - return gcode_line_error(PSTR(STR_ERR_NO_CHECKSUM), i); + else if (card.flag.saving && !is_M29(command)) { + gcode_line_error(PSTR(STR_ERR_NO_CHECKSUM), p); + break; + } #endif // @@ -505,14 +497,10 @@ void GCodeQueue::get_serial_commands() { char* gpos = strchr(command, 'G'); if (gpos) { switch (strtol(gpos + 1, nullptr, 10)) { - case 0: case 1: - #if ENABLED(ARC_SUPPORT) - case 2: case 3: - #endif - #if ENABLED(BEZIER_CURVE_SUPPORT) - case 5: - #endif - PORT_REDIRECT(i); // Reply to the serial port that sent the command + case 0 ... 1: + TERN_(ARC_SUPPORT, case 2 ... 3:) + TERN_(BEZIER_CURVE_SUPPORT, case 5:) + PORT_REDIRECT(SERIAL_PORTMASK(p)); // Reply to the serial port that sent the command SERIAL_ECHOLNPGM(STR_ERR_STOPPED); LCD_MESSAGEPGM(MSG_STOPPED); break; @@ -522,29 +510,28 @@ void GCodeQueue::get_serial_commands() { #if DISABLED(EMERGENCY_PARSER) // Process critical commands early - if (strcmp_P(command, PSTR("M108")) == 0) { - wait_for_heatup = false; - TERN_(HAS_LCD_MENU, wait_for_user = false); + if (command[0] == 'M') switch (command[3]) { + case '8': if (command[2] == '0' && command[1] == '1') { wait_for_heatup = false; TERN_(HAS_LCD_MENU, wait_for_user = false); } break; + case '2': if (command[2] == '1' && command[1] == '1') kill(M112_KILL_STR, nullptr, true); break; + case '0': if (command[1] == '4' && command[2] == '1') quickstop_stepper(); break; } - if (strcmp_P(command, PSTR("M112")) == 0) kill(M112_KILL_STR, nullptr, true); - if (strcmp_P(command, PSTR("M410")) == 0) quickstop_stepper(); #endif - #if defined(NO_TIMEOUTS) && NO_TIMEOUTS > 0 + #if NO_TIMEOUTS > 0 last_command_time = ms; #endif // Add the command to the queue - _enqueue(serial_line_buffer[i], true + ring_buffer.enqueue(serial.line_buffer, false #if HAS_MULTI_SERIAL - , i + , p #endif ); } else - process_stream_char(serial_char, serial_input_state[i], serial_line_buffer[i], serial_count[i]); + process_stream_char(serial_char, serial.input_state, serial.line_buffer, serial.count); - } // for NUM_SERIAL + } // NUM_SERIAL loop } // queue has space, serial has data } @@ -559,33 +546,45 @@ void GCodeQueue::get_serial_commands() { inline void GCodeQueue::get_sdcard_commands() { static uint8_t sd_input_state = PS_NORMAL; - if (!IS_SD_PRINTING()) return; + // Get commands if there are more in the file + if (!IS_SD_FETCHING()) return; int sd_count = 0; - bool card_eof = card.eof(); - while (length < BUFSIZE && !card_eof) { + while (!ring_buffer.full() && !card.eof()) { const int16_t n = card.get(); - card_eof = card.eof(); + const bool card_eof = card.eof(); if (n < 0 && !card_eof) { SERIAL_ERROR_MSG(STR_SD_ERR_READ); continue; } + CommandLine &command = ring_buffer.commands[ring_buffer.index_w]; const char sd_char = (char)n; const bool is_eol = ISEOL(sd_char); if (is_eol || card_eof) { // Reset stream state, terminate the buffer, and commit a non-empty command if (!is_eol && sd_count) ++sd_count; // End of file with no newline - if (!process_line_done(sd_input_state, command_buffer[index_w], sd_count)) { - _commit_command(false); - #if ENABLED(POWER_LOSS_RECOVERY) - recovery.cmd_sdpos = card.getIndex(); // Prime for the NEXT _commit_command + if (!process_line_done(sd_input_state, command.buffer, sd_count)) { + + // M808 L saves the sdpos of the next line. M808 loops to a new sdpos. + TERN_(GCODE_REPEAT_MARKERS, repeat.early_parse_M808(command.buffer)); + + #if DISABLED(PARK_HEAD_ON_PAUSE) + // When M25 is non-blocking it can still suspend SD commands + // Otherwise the M125 handler needs to know SD printing is active + if (command.buffer[0] == 'M' && command.buffer[1] == '2' && command.buffer[2] == '5' && !NUMERIC(command.buffer[3])) + card.pauseSDPrint(); #endif + + // Put the new command into the buffer (no "ok" sent) + ring_buffer.commit_command(true); + + // Prime Power-Loss Recovery for the NEXT commit_command + TERN_(POWER_LOSS_RECOVERY, recovery.cmd_sdpos = card.getIndex()); } - if (card_eof) card.fileHasFinished(); // Handle end of file reached + if (card.eof()) card.fileHasFinished(); // Handle end of file reached } else - process_stream_char(sd_char, sd_input_state, command_buffer[index_w], sd_count); - + process_stream_char(sd_char, sd_input_state, command.buffer, sd_count); } } @@ -598,12 +597,21 @@ void GCodeQueue::get_serial_commands() { * - The SD card file being actively printed */ void GCodeQueue::get_available_commands() { + if (ring_buffer.full()) return; get_serial_commands(); TERN_(SDSUPPORT, get_sdcard_commands()); } +/** + * Run the entire queue in-place. Blocks SD completion/abort until complete. + */ +void GCodeQueue::exhaust() { + while (ring_buffer.occupied()) advance(); + planner.synchronize(); +} + /** * Get the next command in the queue, optionally log it to SD, then dispatch it */ @@ -613,23 +621,23 @@ void GCodeQueue::advance() { if (process_injected_command_P() || process_injected_command()) return; // Return if the G-code buffer is empty - if (!length) return; + if (ring_buffer.empty()) return; #if ENABLED(SDSUPPORT) if (card.flag.saving) { - char* command = command_buffer[index_r]; - if (is_M29(command)) { + char * const cmd = ring_buffer.peek_next_command_string(); + if (is_M29(cmd)) { // M29 closes the file card.closefile(); SERIAL_ECHOLNPGM(STR_FILE_SAVED); - #if !IS_AT90USB + #if !defined(__AVR__) || !defined(USBCON) #if ENABLED(SERIAL_STATS_DROPPED_RX) - SERIAL_ECHOLNPAIR("Dropped bytes: ", MYSERIAL0.dropped()); + SERIAL_ECHOLNPAIR("Dropped bytes: ", MYSERIAL1.dropped()); #endif #if ENABLED(SERIAL_STATS_MAX_RX_QUEUED) - SERIAL_ECHOLNPAIR("Max RX Queue Size: ", MYSERIAL0.rxMaxEnqueued()); + SERIAL_ECHOLNPAIR("Max RX Queue Size: ", MYSERIAL1.rxMaxEnqueued()); #endif #endif @@ -637,7 +645,7 @@ void GCodeQueue::advance() { } else { // Write the string from the read buffer to SD - card.write_command(command); + card.write_command(cmd); if (card.flag.logging) gcode.process_next_command(); // The card is saving because it's logging else @@ -654,7 +662,5 @@ void GCodeQueue::advance() { #endif // SDSUPPORT // The queue may be reset by a command handler or by code invoked by idle() within a handler - --length; - if (++index_r >= BUFSIZE) index_r = 0; - + ring_buffer.advance_pos(ring_buffer.index_r, -1); } diff --git a/Marlin/src/gcode/queue.h b/Marlin/src/gcode/queue.h index 966af2871ffe..3474a402c38d 100644 --- a/Marlin/src/gcode/queue.h +++ b/Marlin/src/gcode/queue.h @@ -31,44 +31,84 @@ class GCodeQueue { public: /** - * GCode 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. + * The buffers per serial port. */ + struct SerialState { + /** + * GCode 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. + */ + long last_N; + int count; //!< Number of characters read in the current line of serial input + char line_buffer[MAX_CMD_SIZE]; //!< The current line accumulator + uint8_t input_state; //!< The input state + }; - static long last_N[NUM_SERIAL]; + static SerialState serial_state[NUM_SERIAL]; //!< Serial states for each serial port /** * GCode Command Queue - * A simple ring buffer of BUFSIZE command strings. + * A simple (circular) ring buffer of BUFSIZE command strings. * * Commands are copied into this buffer by the command injectors * (immediate, serial, sd card) and they are processed sequentially by * the main loop. The gcode.process_next_command method parses the next * command and hands off execution to individual handler functions. */ - static uint8_t length, // Count of commands in the queue - index_r; // Ring buffer read position - - static char command_buffer[BUFSIZE][MAX_CMD_SIZE]; + struct CommandLine { + char buffer[MAX_CMD_SIZE]; //!< The command buffer + bool skip_ok; //!< Skip sending ok when command is processed? + #if HAS_MULTI_SERIAL + serial_index_t port; //!< Serial port the command was received on + #endif + }; /** - * The port that the command was received on + * A handy ring buffer type */ - #if HAS_MULTI_SERIAL - static int16_t port[BUFSIZE]; - #endif + struct RingBuffer { + uint8_t length, //!< Number of commands in the queue + index_r, //!< Ring buffer's read position + index_w; //!< Ring buffer's write position + CommandLine commands[BUFSIZE]; //!< The ring buffer of commands - static int16_t command_port() { - return TERN0(HAS_MULTI_SERIAL, port[index_r]); - } + inline serial_index_t command_port() const { return TERN0(HAS_MULTI_SERIAL, commands[index_r].port); } + + inline void clear() { length = index_r = index_w = 0; } + + 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()) + ); - GCodeQueue(); + bool enqueue(const char *cmd, bool skip_ok = true + OPTARG(HAS_MULTI_SERIAL, serial_index_t serial_ind = serial_index_t()) + ); + + void ok_to_send(); + + inline bool full(uint8_t cmdCount=1) const { return length > (BUFSIZE - cmdCount); } + + inline bool occupied() const { return length != 0; } + + inline bool empty() const { return !occupied(); } + + inline CommandLine& peek_next_command() { return commands[index_r]; } + + inline char* peek_next_command_string() { return peek_next_command().buffer; } + }; + + /** + * The ring buffer of commands + */ + static RingBuffer ring_buffer; /** * Clear the Marlin command queue */ - static void clear(); + static void clear() { ring_buffer.clear(); } /** * Next Injected Command (PROGMEM) pointer. (nullptr == empty) @@ -99,7 +139,7 @@ class GCodeQueue { /** * Enqueue and return only when commands are actually enqueued */ - static void enqueue_one_now(const char* cmd); + static void enqueue_one_now(const char *cmd); /** * Attempt to enqueue a single G-code command @@ -115,13 +155,18 @@ class GCodeQueue { /** * Check whether there are any commands yet to be executed */ - static bool has_commands_queued(); + static bool has_commands_queued() { return ring_buffer.length || injected_commands_P || injected_commands[0]; } /** * Get the next command in the queue, optionally log it to SD, then dispatch it */ static void advance(); + /** + * Run the entire queue in-place + */ + static void exhaust(); + /** * Add to the circular command queue the next command from: * - The command-injection queue (injected_commands_P) @@ -139,17 +184,20 @@ class GCodeQueue { * P Planner space remaining * B Block queue space remaining */ - static void ok_to_send(); + static inline void ok_to_send() { ring_buffer.ok_to_send(); } /** * Clear the serial line and request a resend of * the next expected line number. */ - static void flush_and_request_resend(); + static void flush_and_request_resend(const serial_index_t serial_ind); -private: + /** + * (Re)Set the current line number for the last received command + */ + static inline void set_current_line_number(long n) { serial_state[ring_buffer.command_port().index].last_N = n; } - static uint8_t index_w; // Ring buffer write position +private: static void get_serial_commands(); @@ -157,18 +205,6 @@ class GCodeQueue { static void get_sdcard_commands(); #endif - static void _commit_command(bool say_ok - #if HAS_MULTI_SERIAL - , int16_t p=-1 - #endif - ); - - static bool _enqueue(const char* cmd, bool say_ok=false - #if HAS_MULTI_SERIAL - , int16_t p=-1 - #endif - ); - // Process the next "immediate" command (PROGMEM) static bool process_injected_command_P(); @@ -179,10 +215,13 @@ class GCodeQueue { * Enqueue with Serial Echo * Return true on success */ - static bool enqueue_one(const char* cmd); + static bool enqueue_one(const char *cmd); - static void gcode_line_error(PGM_P const err, const int8_t pn); + static void gcode_line_error(PGM_P const err, const serial_index_t serial_ind); + friend class GcodeSuite; }; extern GCodeQueue queue; + +extern const char G28_STR[]; diff --git a/Marlin/src/gcode/scara/M360-M364.cpp b/Marlin/src/gcode/scara/M360-M364.cpp index 562beee4f98e..f32fa09de071 100644 --- a/Marlin/src/gcode/scara/M360-M364.cpp +++ b/Marlin/src/gcode/scara/M360-M364.cpp @@ -31,7 +31,7 @@ inline bool SCARA_move_to_cal(const uint8_t delta_a, const uint8_t delta_b) { if (IsRunning()) { - forward_kinematics_SCARA(delta_a, delta_b); + forward_kinematics(delta_a, delta_b); do_blocking_move_to_xy(cartes); return true; } diff --git a/Marlin/src/gcode/sd/M1001.cpp b/Marlin/src/gcode/sd/M1001.cpp index b28429f6315d..cd4933ff2765 100644 --- a/Marlin/src/gcode/sd/M1001.cpp +++ b/Marlin/src/gcode/sd/M1001.cpp @@ -25,14 +25,16 @@ #if ENABLED(SDSUPPORT) #include "../gcode.h" +#include "../../module/planner.h" #include "../../module/printcounter.h" +#include "../../sd/cardreader.h" #ifdef SD_FINISHED_RELEASECOMMAND #include "../queue.h" #endif #if EITHER(LCD_SET_PROGRESS_MANUALLY, SD_REPRINT_LAST_SELECTED_FILE) - #include "../../lcd/ultralcd.h" + #include "../../lcd/marlinui.h" #endif #if ENABLED(POWER_LOSS_RECOVERY) @@ -40,7 +42,7 @@ #endif #if HAS_LEDS_OFF_FLAG - #include "../../MarlinCore.h" // for wait_for_user_response + #include "../../MarlinCore.h" // for wait_for_user_response() #include "../../feature/leds/printer_event_leds.h" #endif @@ -60,6 +62,16 @@ * M1001: Execute actions for SD print completion */ void GcodeSuite::M1001() { + planner.synchronize(); + + // SD Printing is finished when the queue reaches M1001 + card.flag.sdprinting = card.flag.sdprintdone = false; + + // If there's another auto#.g file to run... + if (TERN(NO_SD_AUTOSTART, false, card.autofile_check())) return; + + // Purge the recovery file... + TERN_(POWER_LOSS_RECOVERY, recovery.purge()); // Report total print time const bool long_print = print_job_timer.duration() > 60; @@ -71,12 +83,9 @@ void GcodeSuite::M1001() { // Set the progress bar "done" state TERN_(LCD_SET_PROGRESS_MANUALLY, ui.set_progress_done()); - // Purge the recovery file - TERN_(POWER_LOSS_RECOVERY, recovery.purge()); - // Announce SD file completion { - PORT_REDIRECT(SERIAL_BOTH); + PORT_REDIRECT(SerialMask::All); SERIAL_ECHOLNPGM(STR_FILE_PRINTED); } @@ -86,16 +95,18 @@ void GcodeSuite::M1001() { printerEventLEDs.onPrintCompleted(); TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_PRINT_DONE))); TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT(MSG_PRINT_DONE), CONTINUE_STR)); - wait_for_user_response(1000UL * TERN(HAS_LCD_MENU, PE_LEDS_COMPLETED_TIME, 30)); + wait_for_user_response(SEC_TO_MS(TERN(HAS_LCD_MENU, PE_LEDS_COMPLETED_TIME, 30))); printerEventLEDs.onResumeAfterWait(); } #endif // Inject SD_FINISHED_RELEASECOMMAND, if any #ifdef SD_FINISHED_RELEASECOMMAND - queue.inject_P(PSTR(SD_FINISHED_RELEASECOMMAND)); + gcode.process_subcommands_now_P(PSTR(SD_FINISHED_RELEASECOMMAND)); #endif + TERN_(EXTENSIBLE_UI, ExtUI::onPrintFinished()); + // Re-select the last printed file in the UI TERN_(SD_REPRINT_LAST_SELECTED_FILE, ui.reselect_last_file()); } diff --git a/Marlin/src/gcode/sd/M20.cpp b/Marlin/src/gcode/sd/M20.cpp index 7ac4affdae9c..573183833854 100644 --- a/Marlin/src/gcode/sd/M20.cpp +++ b/Marlin/src/gcode/sd/M20.cpp @@ -33,7 +33,7 @@ void GcodeSuite::M20() { if (card.flag.mounted) { SERIAL_ECHOLNPGM(STR_BEGIN_FILE_LIST); - card.ls(); + card.ls(TERN_(LONG_FILENAME_HOST_SUPPORT, parser.boolval('L'))); SERIAL_ECHOLNPGM(STR_END_FILE_LIST); } else diff --git a/Marlin/src/gcode/sd/M21_M22.cpp b/Marlin/src/gcode/sd/M21_M22.cpp index 77df751fc774..f42784d8eb43 100644 --- a/Marlin/src/gcode/sd/M21_M22.cpp +++ b/Marlin/src/gcode/sd/M21_M22.cpp @@ -26,6 +26,7 @@ #include "../gcode.h" #include "../../sd/cardreader.h" +#include "../../lcd/marlinui.h" /** * M21: Init SD Card @@ -35,6 +36,9 @@ void GcodeSuite::M21() { card.mount(); } /** * M22: Release SD Card */ -void GcodeSuite::M22() { card.release(); } +void GcodeSuite::M22() { + if (!IS_SD_PRINTING()) card.release(); + IF_ENABLED(TFT_COLOR_UI, ui.refresh(LCDVIEW_CALL_REDRAW_NEXT)); +} #endif // SDSUPPORT diff --git a/Marlin/src/gcode/sd/M23.cpp b/Marlin/src/gcode/sd/M23.cpp index b88f66b59162..51bc82413040 100644 --- a/Marlin/src/gcode/sd/M23.cpp +++ b/Marlin/src/gcode/sd/M23.cpp @@ -26,7 +26,7 @@ #include "../gcode.h" #include "../../sd/cardreader.h" -#include "../../lcd/ultralcd.h" +#include "../../lcd/marlinui.h" /** * M23: Open a file diff --git a/Marlin/src/gcode/sd/M24_M25.cpp b/Marlin/src/gcode/sd/M24_M25.cpp index bdb37f605cbf..4cb040feb35c 100644 --- a/Marlin/src/gcode/sd/M24_M25.cpp +++ b/Marlin/src/gcode/sd/M24_M25.cpp @@ -27,7 +27,7 @@ #include "../gcode.h" #include "../../sd/cardreader.h" #include "../../module/printcounter.h" -#include "../../lcd/ultralcd.h" +#include "../../lcd/marlinui.h" #if ENABLED(PARK_HEAD_ON_PAUSE) #include "../../feature/pause.h" @@ -41,6 +41,10 @@ #include "../../feature/powerloss.h" #endif +#if ENABLED(DGUS_LCD_UI_MKS) + #include "../../lcd/extui/dgus/DGUSDisplayDef.h" +#endif + #include "../../MarlinCore.h" // for startOrResumeJob /** @@ -48,6 +52,11 @@ */ void GcodeSuite::M24() { + #if ENABLED(DGUS_LCD_UI_MKS) + if ((print_job_timer.isPaused() || print_job_timer.isRunning()) && !parser.seen("ST")) + MKS_resume_print_move(); + #endif + #if ENABLED(POWER_LOSS_RECOVERY) if (parser.seenval('S')) card.setIndex(parser.value_long()); if (parser.seenval('T')) print_job_timer.resume(parser.value_long()); @@ -61,7 +70,7 @@ void GcodeSuite::M24() { #endif if (card.isFileOpen()) { - card.startFileprint(); // 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()); } @@ -78,6 +87,10 @@ void GcodeSuite::M24() { /** * M25: Pause SD Print + * + * With PARK_HEAD_ON_PAUSE: + * Invoke M125 to store the current position and move to the park + * position. M24 will move the head back before resuming the print. */ void GcodeSuite::M25() { @@ -92,15 +105,15 @@ void GcodeSuite::M25() { if (IS_SD_PRINTING()) card.pauseSDPrint(); #endif - #if ENABLED(POWER_LOSS_RECOVERY) + #if ENABLED(POWER_LOSS_RECOVERY) && DISABLED(DGUS_LCD_UI_MKS) if (recovery.enabled) recovery.save(true); #endif print_job_timer.pause(); - #if DISABLED(DWIN_CREALITY_LCD) - ui.reset_status(); - #endif + TERN_(DGUS_LCD_UI_MKS, MKS_pause_print_move()); + + IF_DISABLED(DWIN_CREALITY_LCD, ui.reset_status()); #if ENABLED(HOST_ACTION_COMMANDS) TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_PAUSE_RESUME, PSTR("Pause SD"), PSTR("Resume"))); diff --git a/Marlin/src/gcode/sd/M27.cpp b/Marlin/src/gcode/sd/M27.cpp index 8592b8af2582..88238190e259 100644 --- a/Marlin/src/gcode/sd/M27.cpp +++ b/Marlin/src/gcode/sd/M27.cpp @@ -33,18 +33,20 @@ * OR, with 'C' get the current filename. */ void GcodeSuite::M27() { - if (parser.seen('C')) { + if (parser.seen_test('C')) { SERIAL_ECHOPGM("Current file: "); - card.printFilename(); + card.printSelectedFilename(); + return; } #if ENABLED(AUTO_REPORT_SD_STATUS) - else if (parser.seenval('S')) - card.set_auto_report_interval(parser.value_byte()); + if (parser.seenval('S')) { + card.auto_reporter.set_interval(parser.value_byte()); + return; + } #endif - else - card.report_status(); + card.report_status(); } #endif // SDSUPPORT diff --git a/Marlin/src/gcode/sd/M28_M29.cpp b/Marlin/src/gcode/sd/M28_M29.cpp index 6f3f2450a195..373938d99b4b 100644 --- a/Marlin/src/gcode/sd/M28_M29.cpp +++ b/Marlin/src/gcode/sd/M28_M29.cpp @@ -49,7 +49,7 @@ void GcodeSuite::M28() { // Binary transfer mode if ((card.flag.binary_mode = binary_mode)) { SERIAL_ECHO_MSG("Switching to Binary Protocol"); - TERN_(HAS_MULTI_SERIAL, card.transfer_port_index = queue.port[queue.index_r]); + TERN_(HAS_MULTI_SERIAL, card.transfer_port_index = queue.ring_buffer.command_port().index); } else card.openFileWrite(p); diff --git a/Marlin/src/gcode/sd/M32.cpp b/Marlin/src/gcode/sd/M32.cpp index 55ec6ea49741..3baa552e6e73 100644 --- a/Marlin/src/gcode/sd/M32.cpp +++ b/Marlin/src/gcode/sd/M32.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA_SUBCALLS #include "../gcode.h" #include "../../sd/cardreader.h" @@ -49,11 +49,11 @@ void GcodeSuite::M32() { if (parser.seenval('S')) card.setIndex(parser.value_long()); - card.startFileprint(); + card.startOrResumeFilePrinting(); // Procedure calls count as normal print time. if (!call_procedure) startOrResumeJob(); } } -#endif // SDSUPPORT +#endif // HAS_MEDIA_SUBCALLS diff --git a/Marlin/src/gcode/sd/M524.cpp b/Marlin/src/gcode/sd/M524.cpp index 089d2e2f0c41..e7159155655c 100644 --- a/Marlin/src/gcode/sd/M524.cpp +++ b/Marlin/src/gcode/sd/M524.cpp @@ -33,7 +33,7 @@ void GcodeSuite::M524() { if (IS_SD_PRINTING()) - card.flag.abort_sd_printing = true; + card.abortFilePrintSoon(); else if (card.isMounted()) card.closefile(); diff --git a/Marlin/src/gcode/sd/M808.cpp b/Marlin/src/gcode/sd/M808.cpp new file mode 100644 index 000000000000..548683430c1f --- /dev/null +++ b/Marlin/src/gcode/sd/M808.cpp @@ -0,0 +1,51 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(GCODE_REPEAT_MARKERS) + +#include "../gcode.h" +#include "../../feature/repeat.h" + +/** + * M808: Set / Goto a repeat marker + * + * L - Set a repeat marker with 'count' repetitions. If omitted, infinity. + * + * Examples: + * + * M808 L ; Set a loop marker with a count of infinity + * M808 L2 ; Set a loop marker with a count of 2 + * M808 ; Decrement and loop if not zero. + */ +void GcodeSuite::M808() { + + // Handled early and ignored here in the queue. + // Allowed to go into the queue for logging purposes. + + // M808 K sent from the host to cancel all loops + if (parser.seen_test('K')) repeat.cancel(); + +} + +#endif // GCODE_REPEAT_MARKERS diff --git a/Marlin/src/gcode/stats/M31.cpp b/Marlin/src/gcode/stats/M31.cpp index b39108bb903e..355701f6a413 100644 --- a/Marlin/src/gcode/stats/M31.cpp +++ b/Marlin/src/gcode/stats/M31.cpp @@ -24,17 +24,16 @@ #include "../../core/serial.h" #include "../../module/printcounter.h" #include "../../libs/duration_t.h" -#include "../../lcd/ultralcd.h" +#include "../../lcd/marlinui.h" /** * M31: Get the time since the start of SD Print (or last M109) */ void GcodeSuite::M31() { - char buffer[21]; + char buffer[22]; duration_t(print_job_timer.duration()).toString(buffer); ui.set_status(buffer); - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR("Print time: ", buffer); + SERIAL_ECHO_MSG("Print time: ", buffer); } diff --git a/Marlin/src/gcode/stats/M75-M78.cpp b/Marlin/src/gcode/stats/M75-M78.cpp index 908e6e5a31ee..568d9b0e2707 100644 --- a/Marlin/src/gcode/stats/M75-M78.cpp +++ b/Marlin/src/gcode/stats/M75-M78.cpp @@ -22,7 +22,7 @@ #include "../gcode.h" #include "../../module/printcounter.h" -#include "../../lcd/ultralcd.h" +#include "../../lcd/marlinui.h" #include "../../MarlinCore.h" // for startOrResumeJob diff --git a/Marlin/src/gcode/temp/M104_M109.cpp b/Marlin/src/gcode/temp/M104_M109.cpp index a289983b9294..efda04def50a 100644 --- a/Marlin/src/gcode/temp/M104_M109.cpp +++ b/Marlin/src/gcode/temp/M104_M109.cpp @@ -28,13 +28,13 @@ #include "../../inc/MarlinConfigPre.h" -#if EXTRUDERS +#if HAS_EXTRUDERS #include "../gcode.h" #include "../../module/temperature.h" #include "../../module/motion.h" #include "../../module/planner.h" -#include "../../lcd/ultralcd.h" +#include "../../lcd/marlinui.h" #include "../../MarlinCore.h" // for startOrResumeJob, etc. @@ -45,95 +45,35 @@ #endif #endif -#if ENABLED(SINGLENOZZLE) +#if ENABLED(SINGLENOZZLE_STANDBY_TEMP) #include "../../module/tool_change.h" #endif /** * M104: Set Hotend Temperature target and return immediately - * - * Parameters: - * I : Material Preset index (if material presets are defined) - * T : Tool index. If omitted, applies to the active tool - * S : The target temperature in current units - */ -void GcodeSuite::M104() { - - if (DEBUGGING(DRYRUN)) return; - - #if ENABLED(MIXING_EXTRUDER) && MIXING_VIRTUAL_TOOLS > 1 - constexpr int8_t target_extruder = 0; - #else - const int8_t target_extruder = get_target_extruder_from_command(); - if (target_extruder < 0) return; - #endif - - bool got_temp = false; - int16_t temp = 0; - - // Accept 'I' if temperature presets are defined - #if PREHEAT_COUNT - got_temp = parser.seenval('I'); - if (got_temp) { - const uint8_t index = parser.value_byte(); - temp = ui.material_preset[_MIN(index, PREHEAT_COUNT - 1)].hotend_temp; - } - #endif - - // If no 'I' get the temperature from 'S' - if (!got_temp) { - got_temp = parser.seenval('S'); - if (got_temp) temp = parser.value_celsius(); - } - - if (got_temp) { - #if ENABLED(SINGLENOZZLE_STANDBY_TEMP) - singlenozzle_temp[target_extruder] = temp; - if (target_extruder != active_extruder) return; - #endif - thermalManager.setTargetHotend(temp, target_extruder); - - #if ENABLED(DUAL_X_CARRIAGE) - if (dxc_is_duplicating() && target_extruder == 0) - thermalManager.setTargetHotend(temp ? temp + duplicate_extruder_temp_offset : 0, 1); - #endif - - #if ENABLED(PRINTJOB_TIMER_AUTOSTART) - /** - * Stop the timer at the end of print. Start is managed by 'heat and wait' M109. - * Hotends use EXTRUDE_MINTEMP / 2 to allow nozzles to be put into hot standby - * mode, for instance in a dual extruder setup, without affecting the running - * print timer. - */ - thermalManager.check_timer_autostart(false, true); - #endif - } - - TERN_(AUTOTEMP, planner.autotemp_M104_M109()); -} - -/** * M109: Set Hotend Temperature target and wait * * Parameters * I : Material Preset index (if material presets are defined) * T : Tool index. If omitted, applies to the active tool - * S : The target temperature in current units. Wait for heating only. - * R : The target temperature in current units. Wait for heating and cooling. + * S : The target temperature in current units. For M109, only wait when heating up. * * With AUTOTEMP... * F : Autotemp Scaling Factor. Set non-zero to enable Auto-temp. * S : Minimum temperature, in current units. * B : Maximum temperature, in current units. * + * M109 Parameters + * R : The target temperature in current units. Wait for heating and cooling. + * * Examples - * M109 S100 : Set target to 100°. Wait until the hotend is at or above 100°. + * M104 S100 : Set target to 100° and return. * M109 R150 : Set target to 150°. Wait until the hotend gets close to 150°. * * With PRINTJOB_TIMER_AUTOSTART turning on heaters will start the print job timer * (used by printingIsActive, etc.) and turning off heaters will stop the timer. */ -void GcodeSuite::M109() { +void GcodeSuite::M104_M109(const bool isM109) { if (DEBUGGING(DRYRUN)) return; @@ -145,7 +85,7 @@ void GcodeSuite::M109() { #endif bool got_temp = false; - int16_t temp = 0; + celsius_t temp = 0; // Accept 'I' if temperature presets are defined #if PREHEAT_COUNT @@ -160,19 +100,19 @@ void GcodeSuite::M109() { bool no_wait_for_cooling = false; if (!got_temp) { no_wait_for_cooling = parser.seenval('S'); - got_temp = no_wait_for_cooling || parser.seenval('R'); - if (got_temp) temp = int16_t(parser.value_celsius()); + got_temp = no_wait_for_cooling || (isM109 && parser.seenval('R')); + if (got_temp) temp = parser.value_celsius(); } if (got_temp) { #if ENABLED(SINGLENOZZLE_STANDBY_TEMP) - singlenozzle_temp[target_extruder] = temp; + thermalManager.singlenozzle_temp[target_extruder] = temp; if (target_extruder != active_extruder) return; #endif thermalManager.setTargetHotend(temp, target_extruder); #if ENABLED(DUAL_X_CARRIAGE) - if (dxc_is_duplicating() && target_extruder == 0) + if (idex_is_duplicating() && target_extruder == 0) thermalManager.setTargetHotend(temp ? temp + duplicate_extruder_temp_offset : 0, 1); #endif @@ -182,18 +122,16 @@ void GcodeSuite::M109() { * standby mode, (e.g., in a dual extruder setup) without affecting * the running print timer. */ - thermalManager.check_timer_autostart(true, true); + thermalManager.auto_job_check_timer(isM109, true); #endif - #if HAS_DISPLAY - if (thermalManager.isHeatingHotend(target_extruder) || !no_wait_for_cooling) - thermalManager.set_heating_message(target_extruder); - #endif + if (thermalManager.isHeatingHotend(target_extruder) || !no_wait_for_cooling) + thermalManager.set_heating_message(target_extruder); } TERN_(AUTOTEMP, planner.autotemp_M104_M109()); - if (got_temp) + if (isM109 && got_temp) (void)thermalManager.wait_for_hotend(target_extruder, no_wait_for_cooling); } diff --git a/Marlin/src/gcode/temp/M105.cpp b/Marlin/src/gcode/temp/M105.cpp index eefc3ae9f17f..4de5ba8eefe1 100644 --- a/Marlin/src/gcode/temp/M105.cpp +++ b/Marlin/src/gcode/temp/M105.cpp @@ -35,11 +35,7 @@ void GcodeSuite::M105() { #if HAS_TEMP_SENSOR - thermalManager.print_heater_states(target_extruder - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - , parser.boolval('R') - #endif - ); + thermalManager.print_heater_states(target_extruder OPTARG(HAS_TEMP_REDUNDANT, parser.boolval('R'))); SERIAL_EOL(); diff --git a/Marlin/src/gcode/temp/M106_M107.cpp b/Marlin/src/gcode/temp/M106_M107.cpp index 17ff8c3c8f60..3f85c53d78ae 100644 --- a/Marlin/src/gcode/temp/M106_M107.cpp +++ b/Marlin/src/gcode/temp/M106_M107.cpp @@ -28,8 +28,12 @@ #include "../../module/motion.h" #include "../../module/temperature.h" +#if ENABLED(LASER_SYNCHRONOUS_M106_M107) + #include "../../module/planner.h" +#endif + #if PREHEAT_COUNT - #include "../../lcd/ultralcd.h" + #include "../../lcd/marlinui.h" #endif #if ENABLED(SINGLENOZZLE) @@ -56,40 +60,58 @@ */ void GcodeSuite::M106() { const uint8_t pfan = parser.byteval('P', _ALT_P); + if (pfan >= _CNT_P) return; + #if REDUNDANT_PART_COOLING_FAN + if (pfan == REDUNDANT_PART_COOLING_FAN) return; + #endif + + #if ENABLED(EXTRA_FAN_SPEED) + const uint16_t t = parser.intval('T'); + if (t > 0) return thermalManager.set_temp_fan_speed(pfan, t); + #endif + + const uint16_t dspeed = parser.seen_test('A') ? thermalManager.fan_speed[active_extruder] : 255; - if (pfan < _CNT_P) { + uint16_t speed = dspeed; - #if ENABLED(EXTRA_FAN_SPEED) - const uint16_t t = parser.intval('T'); - if (t > 0) return thermalManager.set_temp_fan_speed(pfan, t); - #endif + // Accept 'I' if temperature presets are defined + #if PREHEAT_COUNT + const bool got_preset = parser.seenval('I'); + if (got_preset) speed = ui.material_preset[_MIN(parser.value_byte(), PREHEAT_COUNT - 1)].fan_speed; + #else + constexpr bool got_preset = false; + #endif - const uint16_t dspeed = parser.seen('A') ? thermalManager.fan_speed[active_extruder] : 255; + if (!got_preset && parser.seenval('S')) + speed = parser.value_ushort(); - uint16_t speed = dspeed; + TERN_(FOAMCUTTER_XYUV, speed *= 2.55); // Get command in % of max heat - // Accept 'I' if temperature presets are defined - #if PREHEAT_COUNT - const bool got_preset = parser.seenval('I'); - if (got_preset) speed = ui.material_preset[_MIN(parser.value_byte(), PREHEAT_COUNT - 1)].fan_speed; - #else - constexpr bool got_preset = false; - #endif + // Set speed, with constraint + thermalManager.set_fan_speed(pfan, speed); - if (!got_preset && parser.seenval('S')) - speed = parser.value_ushort(); + TERN_(LASER_SYNCHRONOUS_M106_M107, planner.buffer_sync_block(BLOCK_FLAG_SYNC_FANS)); - // Set speed, with constraint - thermalManager.set_fan_speed(pfan, speed); - } + if (TERN0(DUAL_X_CARRIAGE, idex_is_duplicating())) // pfan == 0 when duplicating + thermalManager.set_fan_speed(1 - pfan, speed); } /** * M107: Fan Off */ void GcodeSuite::M107() { - const uint8_t p = parser.byteval('P', _ALT_P); - thermalManager.set_fan_speed(p, 0); + const uint8_t pfan = parser.byteval('P', _ALT_P); + if (pfan >= _CNT_P) return; + #if REDUNDANT_PART_COOLING_FAN + if (pfan == REDUNDANT_PART_COOLING_FAN) return; + #endif + + thermalManager.set_fan_speed(pfan, 0); + + if (TERN0(DUAL_X_CARRIAGE, idex_is_duplicating())) // pfan == 0 when duplicating + thermalManager.set_fan_speed(1 - pfan, 0); + + TERN_(LASER_SYNCHRONOUS_M106_M107, planner.buffer_sync_block(BLOCK_FLAG_SYNC_FANS)); } #endif // HAS_FAN diff --git a/Marlin/src/gcode/temp/M140_M190.cpp b/Marlin/src/gcode/temp/M140_M190.cpp index 9438b9e0c23c..857e11dde53f 100644 --- a/Marlin/src/gcode/temp/M140_M190.cpp +++ b/Marlin/src/gcode/temp/M140_M190.cpp @@ -32,80 +32,35 @@ #include "../gcode.h" #include "../../module/temperature.h" -#include "../../module/motion.h" -#include "../../lcd/ultralcd.h" - -#if ENABLED(PRINTJOB_TIMER_AUTOSTART) - #include "../../module/printcounter.h" -#endif - -#if ENABLED(PRINTER_EVENT_LEDS) - #include "../../feature/leds/leds.h" -#endif - -#include "../../MarlinCore.h" // for wait_for_heatup, idle, startOrResumeJob +#include "../../lcd/marlinui.h" /** - * M140: Set bed temperature + * M140 - Set Bed Temperature target and return immediately + * M190 - Set Bed Temperature target and wait * * I : Preset index (if material presets are defined) * S : The target temperature in current units - */ -void GcodeSuite::M140() { - if (DEBUGGING(DRYRUN)) return; - - bool got_temp = false; - int16_t temp = 0; - - // Accept 'I' if temperature presets are defined - #if PREHEAT_COUNT - got_temp = parser.seenval('I'); - if (got_temp) { - const uint8_t index = parser.value_byte(); - temp = ui.material_preset[_MIN(index, PREHEAT_COUNT - 1)].bed_temp; - } - #endif - - // If no 'I' get the temperature from 'S' - if (!got_temp) { - got_temp = parser.seenval('S'); - if (got_temp) temp = parser.value_celsius(); - } - - if (got_temp) { - thermalManager.setTargetBed(temp); - - #if ENABLED(PRINTJOB_TIMER_AUTOSTART) - /** - * Stop the timer at the end of print. Hotend, bed target, and chamber - * temperatures need to be set below mintemp. Order of M140, M104, and M141 - * at the end of the print does not matter. - */ - thermalManager.check_timer_autostart(false, true); - #endif - } -} - -/** - * M190 - Set Bed Temperature target and wait * - * Parameters: + * Parameters * I : Preset index (if material presets are defined) * S : The target temperature in current units. Wait for heating only. + * + * M190 Parameters * R : The target temperature in current units. Wait for heating and cooling. * - * Examples: - * M190 S60 : Set target to 60°. Wait until the bed is at or above 60°. + * Examples + * M140 S60 : Set target to 60° and return right away. * M190 R40 : Set target to 40°. Wait until the bed gets close to 40°. * * With PRINTJOB_TIMER_AUTOSTART turning on heaters will start the print job timer * (used by printingIsActive, etc.) and turning off heaters will stop the timer. */ -void GcodeSuite::M190() { +void GcodeSuite::M140_M190(const bool isM190) { + if (DEBUGGING(DRYRUN)) return; bool got_temp = false; - int16_t temp = 0; + celsius_t temp = 0; // Accept 'I' if temperature presets are defined #if PREHEAT_COUNT @@ -120,19 +75,21 @@ void GcodeSuite::M190() { bool no_wait_for_cooling = false; if (!got_temp) { no_wait_for_cooling = parser.seenval('S'); - got_temp = no_wait_for_cooling || parser.seenval('R'); - if (got_temp) temp = int16_t(parser.value_celsius()); + got_temp = no_wait_for_cooling || (isM190 && parser.seenval('R')); + if (got_temp) temp = parser.value_celsius(); } if (!got_temp) return; thermalManager.setTargetBed(temp); - TERN_(PRINTJOB_TIMER_AUTOSTART, thermalManager.check_timer_autostart(true, false)); - ui.set_status_P(thermalManager.isHeatingBed() ? GET_TEXT(MSG_BED_HEATING) : GET_TEXT(MSG_BED_COOLING)); - thermalManager.wait_for_bed(no_wait_for_cooling); + // 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) + thermalManager.wait_for_bed(no_wait_for_cooling); } #endif // HAS_HEATED_BED diff --git a/Marlin/src/gcode/temp/M141_M191.cpp b/Marlin/src/gcode/temp/M141_M191.cpp index 41a79825aa3b..ed7637c92aa6 100644 --- a/Marlin/src/gcode/temp/M141_M191.cpp +++ b/Marlin/src/gcode/temp/M141_M191.cpp @@ -32,19 +32,7 @@ #include "../gcode.h" #include "../../module/temperature.h" - -#include "../../module/motion.h" -#include "../../lcd/ultralcd.h" - -#if ENABLED(PRINTJOB_TIMER_AUTOSTART) - #include "../../module/printcounter.h" -#endif - -#if ENABLED(PRINTER_EVENT_LEDS) - #include "../../feature/leds/leds.h" -#endif - -#include "../../MarlinCore.h" // for wait_for_heatup, idle, startOrResumeJob +#include "../../lcd/marlinui.h" /** * M141: Set chamber temperature @@ -60,7 +48,7 @@ void GcodeSuite::M141() { * temperatures need to be set below mintemp. Order of M140, M104, and M141 * at the end of the print does not matter. */ - thermalManager.check_timer_autostart(false, true); + thermalManager.auto_job_check_timer(false, true); #endif } } @@ -75,7 +63,7 @@ void GcodeSuite::M191() { const bool no_wait_for_cooling = parser.seenval('S'); if (no_wait_for_cooling || parser.seenval('R')) { thermalManager.setTargetChamber(parser.value_celsius()); - TERN_(PRINTJOB_TIMER_AUTOSTART, thermalManager.check_timer_autostart(true, false)); + TERN_(PRINTJOB_TIMER_AUTOSTART, thermalManager.auto_job_check_timer(true, false)); } else return; diff --git a/Marlin/src/gcode/temp/M143_M193.cpp b/Marlin/src/gcode/temp/M143_M193.cpp new file mode 100644 index 000000000000..aef4350e6048 --- /dev/null +++ b/Marlin/src/gcode/temp/M143_M193.cpp @@ -0,0 +1,67 @@ +/** + * 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 . + * + */ + +/** + * gcode/temp/M143_M193.cpp + * + * Laser Cooler target temperature control + */ + +#include "../../inc/MarlinConfig.h" + +#if HAS_COOLER + +#include "../../feature/cooler.h" +extern Cooler cooler; + +#include "../gcode.h" +#include "../../module/temperature.h" +#include "../../lcd/marlinui.h" + +/** + * M143: Set cooler temperature + */ +void GcodeSuite::M143() { + if (DEBUGGING(DRYRUN)) return; + if (parser.seenval('S')) { + thermalManager.setTargetCooler(parser.value_celsius()); + parser.value_celsius() ? cooler.enable() : cooler.disable(); + } +} + +/** + * M193: Sxxx Wait for laser current temp to reach target temp. Waits only when cooling. + */ +void GcodeSuite::M193() { + if (DEBUGGING(DRYRUN)) return; + + if (parser.seenval('S')) { + cooler.enable(); + thermalManager.setTargetCooler(parser.value_celsius()); + if (thermalManager.isLaserCooling()) { + ui.set_status_P(GET_TEXT(MSG_LASER_COOLING)); + thermalManager.wait_for_cooler(true); + } + } +} + +#endif // HAS_COOLER diff --git a/Marlin/src/gcode/temp/M155.cpp b/Marlin/src/gcode/temp/M155.cpp index 30129a0e6ff7..48c23986aeb5 100644 --- a/Marlin/src/gcode/temp/M155.cpp +++ b/Marlin/src/gcode/temp/M155.cpp @@ -33,7 +33,7 @@ void GcodeSuite::M155() { if (parser.seenval('S')) - thermalManager.set_auto_report_interval(parser.value_byte()); + thermalManager.auto_reporter.set_interval(parser.value_byte()); } diff --git a/Marlin/src/gcode/temp/M303.cpp b/Marlin/src/gcode/temp/M303.cpp index ccce09b4f1ee..ad3afe6e460b 100644 --- a/Marlin/src/gcode/temp/M303.cpp +++ b/Marlin/src/gcode/temp/M303.cpp @@ -25,7 +25,7 @@ #if HAS_PID_HEATING #include "../gcode.h" -#include "../../lcd/ultralcd.h" +#include "../../lcd/marlinui.h" #include "../../module/temperature.h" #if ENABLED(EXTENSIBLE_UI) @@ -40,45 +40,50 @@ * C Number of times to repeat the procedure. (Minimum: 3, Default: 5) * U Flag to apply the result to the current PID values * - * With PID_DEBUG: + * With PID_DEBUG, PID_BED_DEBUG, or PID_CHAMBER_DEBUG: * D Toggle PID debugging and EXIT without further action. */ -#if ENABLED(PID_DEBUG) - bool pid_debug_flag = 0; -#endif - void GcodeSuite::M303() { - #if ENABLED(PID_DEBUG) - if (parser.seen('D')) { - pid_debug_flag = !pid_debug_flag; + #if ANY(PID_DEBUG, PID_BED_DEBUG, PID_CHAMBER_DEBUG) + if (parser.seen_test('D')) { + thermalManager.pid_debug_flag ^= true; SERIAL_ECHO_START(); SERIAL_ECHOPGM("PID Debug "); - serialprintln_onoff(pid_debug_flag); + serialprintln_onoff(thermalManager.pid_debug_flag); return; } #endif - #define SI TERN(PIDTEMPBED, H_BED, H_E0) - #define EI TERN(PIDTEMP, HOTENDS - 1, H_BED) - const heater_id_t e = (heater_id_t)parser.intval('E'); - if (!WITHIN(e, SI, EI)) { - SERIAL_ECHOLNPGM(STR_PID_BAD_EXTRUDER_NUM); - TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_BAD_EXTRUDER_NUM)); - return; + const heater_id_t hid = (heater_id_t)parser.intval('E'); + celsius_t default_temp; + switch (hid) { + #if ENABLED(PIDTEMP) + case 0 ... HOTENDS - 1: default_temp = PREHEAT_1_TEMP_HOTEND; break; + #endif + #if ENABLED(PIDTEMPBED) + case H_BED: default_temp = PREHEAT_1_TEMP_BED; break; + #endif + #if ENABLED(PIDTEMPCHAMBER) + case H_CHAMBER: default_temp = PREHEAT_1_TEMP_CHAMBER; break; + #endif + default: + SERIAL_ECHOLNPGM(STR_PID_BAD_HEATER_ID); + TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_BAD_EXTRUDER_NUM)); + return; } + const celsius_t temp = parser.celsiusval('S', default_temp); const int c = parser.intval('C', 5); const bool u = parser.boolval('U'); - const int16_t temp = parser.celsiusval('S', e < 0 ? PREHEAT_1_TEMP_BED : PREHEAT_1_TEMP_HOTEND); #if DISABLED(BUSY_WHILE_HEATING) KEEPALIVE_STATE(NOT_BUSY); #endif - ui.set_status(GET_TEXT(MSG_PID_AUTOTUNE)); - thermalManager.PID_autotune(temp, e, c, u); + LCD_MESSAGEPGM(MSG_PID_AUTOTUNE); + thermalManager.PID_autotune(temp, hid, c, u); ui.reset_status(); } diff --git a/Marlin/src/gcode/units/M82_M83.cpp b/Marlin/src/gcode/units/M82_M83.cpp index d93f0ea5adf3..c1767e805739 100644 --- a/Marlin/src/gcode/units/M82_M83.cpp +++ b/Marlin/src/gcode/units/M82_M83.cpp @@ -20,6 +20,10 @@ * */ +#include "../../inc/MarlinConfigPre.h" + +#if HAS_EXTRUDERS + #include "../gcode.h" /** @@ -31,3 +35,5 @@ void GcodeSuite::M82() { set_e_absolute(); } * M83: Set E codes relative while in Absolute Coordinates (G90) mode */ void GcodeSuite::M83() { set_e_relative(); } + +#endif // HAS_EXTRUDERS diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 45921f7be3b0..137b9fce3ec1 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -26,19 +26,14 @@ * Conditionals that need to be set before Configuration_adv.h or pins.h */ -// Kinematics -#if ENABLED(MORGAN_SCARA) - #define IS_SCARA 1 - #define IS_KINEMATIC 1 -#elif ENABLED(DELTA) - #define IS_KINEMATIC 1 -#else - #define IS_CARTESIAN 1 +// MKS_LCD12864A/B is a variant of MKS_MINI_12864 +#if EITHER(MKS_LCD12864A, MKS_LCD12864B) + #define MKS_MINI_12864 #endif -// MKS_LCD12864 is a variant of MKS_MINI_12864 -#if ENABLED(MKS_LCD12864) - #define MKS_MINI_12864 +// MKS_MINI_12864_V3 is simply identical to FYSETC_MINI_12864_2_1 +#if ENABLED(MKS_MINI_12864_V3) + #define FYSETC_MINI_12864_2_1 #endif /** @@ -46,7 +41,7 @@ * * DOGLCD : Run a Graphical LCD through U8GLib (with MarlinUI) * IS_ULTIPANEL : Define LCD_PINS_D5/6/7 for direct-connected "Ultipanel" LCDs - * IS_ULTRA_LCD : Ultra LCD, not necessarily Ultipanel. Used most often with NEWPANEL. + * IS_ULTRA_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 * U8GLIB_ST7920 : Most common DOGM display SPI interface, supporting a "lightweight" display mode. @@ -60,6 +55,10 @@ #define MINIPANEL +#elif ENABLED(YHCB2004) + + #define IS_ULTIPANEL 1 + #elif ENABLED(CARTESIO_UI) #define DOGLCD @@ -72,13 +71,12 @@ #elif ENABLED(ZONESTAR_LCD) - #define ADC_KEYPAD - #define IS_RRW_KEYPAD + #define HAS_ADC_BUTTONS 1 #define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0 #define ADC_KEY_NUM 8 #define IS_ULTIPANEL 1 - // This helps to implement ADC_KEYPAD menus + // This helps to implement HAS_ADC_BUTTONS menus #define REVERSE_MENU_DIRECTION #define ENCODER_PULSES_PER_STEP 1 #define ENCODER_STEPS_PER_MENU_ITEM 1 @@ -86,25 +84,21 @@ #elif ENABLED(ZONESTAR_12864LCD) #define DOGLCD - #define IS_RRD_SC + #define IS_RRD_SC 1 #define U8GLIB_ST7920 #elif ENABLED(ZONESTAR_12864OLED) - #define IS_RRD_SC + #define IS_RRD_SC 1 #define U8GLIB_SH1106 #elif ENABLED(ZONESTAR_12864OLED_SSD1306) - #define IS_RRD_SC + #define IS_RRD_SC 1 #define IS_U8GLIB_SSD1306 #elif ENABLED(RADDS_DISPLAY) #define IS_ULTIPANEL 1 #define ENCODER_PULSES_PER_STEP 2 -#elif EITHER(ANET_FULL_GRAPHICS_LCD, BQ_LCD_SMART_CONTROLLER) - - #define IS_RRD_FG_SC - #elif ANY(miniVIKI, VIKI2, ELB_FULL_GRAPHIC_CONTROLLER, AZSMZ_12864) #define DOGLCD @@ -137,26 +131,26 @@ #define U8GLIB_ST7920 #define IS_ULTIPANEL 1 -#elif ENABLED(CR10_STOCKDISPLAY) - - #define IS_RRD_FG_SC - #define BOARD_ST7920_DELAY_1 DELAY_NS(125) - #define BOARD_ST7920_DELAY_2 DELAY_NS(125) - #define BOARD_ST7920_DELAY_3 DELAY_NS(125) - #elif ENABLED(MKS_12864OLED) - #define IS_RRD_SC + #define IS_RRD_SC 1 #define U8GLIB_SH1106 #elif ENABLED(MKS_12864OLED_SSD1306) - #define IS_RRD_SC + #define IS_RRD_SC 1 #define IS_U8GLIB_SSD1306 +#elif ENABLED(SAV_3DGLCD) + + #ifdef U8GLIB_SSD1306 + #define IS_U8GLIB_SSD1306 + #endif + #define IS_NEWPANEL 1 + #elif ENABLED(FYSETC_242_OLED_12864) - #define IS_RRD_SC + #define IS_RRD_SC 1 #define U8GLIB_SH1106 #define LED_CONTROL_MENU @@ -213,20 +207,20 @@ #elif ENABLED(MAKEBOARD_MINI_2_LINE_DISPLAY_1602) - #define IS_RRD_SC + #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 + #define IS_ULTIPANEL 1 // Note that IS_ULTIPANEL leads to HAS_WIRED_LCD #if ENABLED(SDSUPPORT) && DISABLED(LCD_PROGRESS_BAR) #define LCD_PROGRESS_BAR #endif #if ENABLED(TFTGLCD_PANEL_I2C) - #define LCD_I2C_ADDRESS 0x27 // Must be equal to panel's I2C slave addres + #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 @@ -239,12 +233,37 @@ #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. + +#elif ENABLED(CR10_STOCKDISPLAY) + + #define IS_RRD_FG_SC 1 + #define BOARD_ST7920_DELAY_1 DELAY_NS(125) + #define BOARD_ST7920_DELAY_2 DELAY_NS(125) + #define BOARD_ST7920_DELAY_3 DELAY_NS(125) + +#elif ANY(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER, ANET_FULL_GRAPHICS_LCD, ANET_FULL_GRAPHICS_LCD_ALT_WIRING, BQ_LCD_SMART_CONTROLLER, K3D_FULL_GRAPHIC_SMART_CONTROLLER) + + #define IS_RRD_FG_SC 1 + +#elif ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) + + #define IS_RRD_SC 1 // RepRapDiscount LCD or Graphical LCD with rotary click encoder + +#elif ENABLED(K3D_242_OLED_CONTROLLER) + + #define IS_RRD_SC 1 + #define U8GLIB_SSD1309 + #endif -#if ENABLED(IS_RRD_FG_SC) - #define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER +// ST7920-based graphical displays +#if ANY(IS_RRD_FG_SC, LCD_FOR_MELZI, SILVER_GATE_GLCD_CONTROLLER) + #define DOGLCD + #define U8GLIB_ST7920 + #define IS_RRD_SC 1 #endif +// ST7565 / 64128N graphical displays #if EITHER(MAKRPANEL, MINIPANEL) #define IS_ULTIPANEL 1 #define DOGLCD @@ -278,30 +297,16 @@ // 128x64 I2C OLED LCDs - SSD1306/SSD1309/SH1106 #if ANY(U8GLIB_SSD1306, U8GLIB_SSD1309, U8GLIB_SH1106) #define HAS_U8GLIB_I2C_OLED 1 -#endif -#if HAS_U8GLIB_I2C_OLED - #define IS_ULTRA_LCD + #define IS_ULTRA_LCD 1 #define DOGLCD #endif -// ST7920-based graphical displays -#if ANY(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER, LCD_FOR_MELZI, SILVER_GATE_GLCD_CONTROLLER) - #define DOGLCD - #define U8GLIB_ST7920 - #define IS_RRD_SC -#endif - -// RepRapDiscount LCD or Graphical LCD with rotary click encoder -#if ENABLED(IS_RRD_SC) - #define REPRAP_DISCOUNT_SMART_CONTROLLER -#endif - /** * SPI Ultipanels */ // Basic Ultipanel-like displays -#if ANY(ULTIMAKERCONTROLLER, REPRAP_DISCOUNT_SMART_CONTROLLER, G3D_PANEL, RIGIDBOT_PANEL, PANEL_ONE, U8GLIB_SH1106) +#if ANY(ULTIMAKERCONTROLLER, IS_RRD_SC, G3D_PANEL, RIGIDBOT_PANEL, PANEL_ONE, U8GLIB_SH1106) #define IS_ULTIPANEL 1 #endif @@ -311,36 +316,31 @@ #define IS_ULTIPANEL 1 #endif -// Compatibility -#if ENABLED(FSMC_GRAPHICAL_TFT) - #define TFT_CLASSIC_UI - #define TFT_INTERFACE_FSMC +// 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 -#elif ENABLED(SPI_GRAPHICAL_TFT) - #define TFT_CLASSIC_UI - #define TFT_INTERFACE_SPI - #define TFT_GENERIC -#elif EITHER(TFT_320x240, TFT_480x320) - #define TFT_COLOR_UI + #warning "Don't forget to update your TFT settings in Configuration.h." +#endif + +#if ANY(FSMC_GRAPHICAL_TFT, TFT_320x240, TFT_480x320, TFT_LVGL_UI_FSMC) #define TFT_INTERFACE_FSMC - #define TFT_GENERIC -#elif EITHER(TFT_320x240_SPI, TFT_480x320_SPI) - #define TFT_COLOR_UI +#elif ANY(SPI_GRAPHICAL_TFT, TFT_320x240_SPI, TFT_480x320_SPI, TFT_LVGL_UI_SPI) #define TFT_INTERFACE_SPI - #define TFT_GENERIC -#elif ENABLED(TFT_LVGL_UI_FSMC) - #define TFT_LVGL_UI - #define TFT_INTERFACE_FSMC - #define TFT_GENERIC -#elif ENABLED(TFT_LVGL_UI_SPI) +#endif + +#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 - #define TFT_INTERFACE_SPI - #define TFT_GENERIC #endif // FSMC/SPI TFT Panels (LVGL) #if ENABLED(TFT_LVGL_UI) #define HAS_TFT_LVGL_UI 1 + #define SERIAL_RUNTIME_HOOK 1 #endif // FSMC/SPI TFT Panels @@ -352,7 +352,7 @@ #define DOGLCD #define IS_ULTIPANEL 1 #define DELAYED_BACKLIGHT_INIT -#elif ENABLED(TFT_LVGL_UI) +#elif HAS_TFT_LVGL_UI #define DELAYED_BACKLIGHT_INIT #endif @@ -410,13 +410,17 @@ #define STD_ENCODER_PULSES_PER_STEP 2 #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 -#elif ANY(REPRAP_DISCOUNT_SMART_CONTROLLER, miniVIKI, VIKI2, ELB_FULL_GRAPHIC_CONTROLLER, AZSMZ_12864, OLED_PANEL_TINYBOY2, BQ_LCD_SMART_CONTROLLER, LCD_I2C_PANELOLU2) +#elif ANY(IS_RRD_SC, miniVIKI, VIKI2, ELB_FULL_GRAPHIC_CONTROLLER, AZSMZ_12864, OLED_PANEL_TINYBOY2, BQ_LCD_SMART_CONTROLLER, LCD_I2C_PANELOLU2) #define STD_ENCODER_PULSES_PER_STEP 4 #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 #endif +#if EITHER(LCD_I2C_TYPE_MCP23017, LCD_I2C_TYPE_MCP23008) && DISABLED(NO_LCD_DETECT) + #define DETECT_I2C_LCD_DEVICE 1 +#endif + #ifndef STD_ENCODER_PULSES_PER_STEP #if ENABLED(TOUCH_SCREEN) #define STD_ENCODER_PULSES_PER_STEP 2 @@ -447,48 +451,38 @@ #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 ENABLED(IS_ULTIPANEL) - #define ULTIPANEL -#endif -#if ENABLED(ULTIPANEL) - #define IS_ULTRA_LCD - #define NEWPANEL -#endif -#if ENABLED(IS_ULTRA_LCD) - #define ULTRA_LCD +#if EITHER(IS_ULTIPANEL, ULTRA_LCD) + #define IS_ULTRA_LCD 1 #endif -#if ENABLED(IS_RRW_KEYPAD) - #define REPRAPWORLD_KEYPAD +#if EITHER(IS_ULTIPANEL, REPRAPWORLD_KEYPAD) + #define IS_NEWPANEL 1 #endif -// Keypad needs a move step -#if ENABLED(REPRAPWORLD_KEYPAD) - #define NEWPANEL +#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 // Aliases for LCD features -#if ANY(DGUS_LCD_UI_ORIGIN, DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_HIPRECY) +#if ANY(DGUS_LCD_UI_ORIGIN, DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_HIPRECY,DGUS_LCD_UI_MKS) #define HAS_DGUS_LCD 1 #endif // 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) - #define IS_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 // Aliases for LCD features -#if EITHER(ULTRA_LCD, EXTENSIBLE_UI) - #define HAS_DISPLAY 1 -#endif - -#if ENABLED(ULTRA_LCD) +#if IS_ULTRA_LCD #define HAS_WIRED_LCD 1 #if ENABLED(DOGLCD) #define HAS_MARLINUI_U8GLIB 1 @@ -499,11 +493,16 @@ #endif #endif -#if ENABLED(ULTIPANEL) && DISABLED(NO_LCD_MENUS) - #define HAS_LCD_MENU 1 +#if EITHER(HAS_WIRED_LCD, EXTENSIBLE_UI) + #define HAS_DISPLAY 1 #endif -#if ENABLED(ADC_KEYPAD) - #define HAS_ADC_BUTTONS 1 + +#if ANY(HAS_DISPLAY, DWIN_CREALITY_LCD, GLOBAL_STATUS_MESSAGE) + #define HAS_STATUS_MESSAGE 1 +#endif + +#if IS_ULTIPANEL && DISABLED(NO_LCD_MENUS) + #define HAS_LCD_MENU 1 #endif #if HAS_MARLINUI_U8GLIB @@ -515,6 +514,36 @@ #endif #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 + +#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 + #endif + #if MMU_MODEL >= EXTENDABLE_EMU_MMU2 + #define HAS_EXTENDABLE_MMU 1 + #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: @@ -524,22 +553,29 @@ * E_STEPPERS - Number of actual E stepper motors * E_MANUAL - Number of E steppers for LCD move options */ - -#if EXTRUDERS == 0 +#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 SINGLENOZZLE #undef SWITCHING_EXTRUDER #undef SWITCHING_NOZZLE #undef MIXING_EXTRUDER - #undef MK2_MULTIPLEXER - #undef PRUSA_MMU2 #undef HOTEND_IDLE_TIMEOUT -#elif EXTRUDERS > 1 - #define HAS_MULTI_EXTRUDER 1 + #undef DISABLE_E #endif -#if ENABLED(SWITCHING_EXTRUDER) // One stepper for every two EXTRUDERS +#if ENABLED(E_DUAL_STEPPER_DRIVERS) // E0/E1 steppers act in tandem as E0 + + #define E_STEPPERS 2 + +#elif ENABLED(SWITCHING_EXTRUDER) // One stepper for every two EXTRUDERS + #if EXTRUDERS > 4 #define E_STEPPERS 3 #elif EXTRUDERS > 2 @@ -550,26 +586,33 @@ #if DISABLED(SWITCHING_NOZZLE) #define HOTENDS E_STEPPERS #endif -#elif ENABLED(MIXING_EXTRUDER) + +#elif ENABLED(MIXING_EXTRUDER) // Multiple feeds are mixed proportionally + #define E_STEPPERS MIXING_STEPPERS #define E_MANUAL 1 #if MIXING_STEPPERS == 2 #define HAS_DUAL_MIXING 1 #endif -#elif ENABLED(SWITCHING_TOOLHEAD) + +#elif ENABLED(SWITCHING_TOOLHEAD) // Toolchanger + #define E_STEPPERS EXTRUDERS #define E_MANUAL EXTRUDERS -#elif ENABLED(PRUSA_MMU2) + +#elif HAS_PRUSA_MMU2 // Průša Multi-Material Unit v2 + #define E_STEPPERS 1 + #endif -// No inactive extruders with MK2_MULTIPLEXER or SWITCHING_NOZZLE -#if EITHER(MK2_MULTIPLEXER, SWITCHING_NOZZLE) +// No inactive extruders with SWITCHING_NOZZLE or Průša MMU1 +#if ENABLED(SWITCHING_NOZZLE) || HAS_PRUSA_MMU1 #undef DISABLE_INACTIVE_EXTRUDER #endif -// Průša MK2 Multiplexer and MMU 2.0 force SINGLENOZZLE -#if EITHER(MK2_MULTIPLEXER, PRUSA_MMU2) +// Průša MMU1, MMU(S) 2.0 and EXTENDABLE_EMU_MMU2(S) force SINGLENOZZLE +#if HAS_MMU #define SINGLENOZZLE #endif @@ -590,6 +633,56 @@ #define E_MANUAL EXTRUDERS #endif +/** + * Number of Linear Axes (e.g., XYZ) + * All the logical axes except for the tool (E) axis + */ +#ifndef LINEAR_AXES + #define LINEAR_AXES XYZ +#endif +#if LINEAR_AXES >= XY + #define HAS_Y_AXIS 1 + #if LINEAR_AXES >= XYZ + #define HAS_Z_AXIS 1 + #endif +#endif + +/** + * Number of Logical Axes (e.g., XYZE) + * All the 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(LINEAR_AXES) +#else + #define LOGICAL_AXES LINEAR_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 + * well 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 (LINEAR_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 + #if HOTENDS #define HAS_HOTEND 1 #ifndef HOTEND_OVERSHOOT @@ -606,13 +699,9 @@ // Helper macros for extruder and hotend arrays #define HOTEND_LOOP() for (int8_t e = 0; e < HOTENDS; e++) #define ARRAY_BY_EXTRUDERS(V...) ARRAY_N(EXTRUDERS, V) -#define ARRAY_BY_EXTRUDERS1(v1) ARRAY_BY_EXTRUDERS(v1, v1, v1, v1, v1, v1, v1, v1) +#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_BY_HOTENDS(v1, v1, v1, v1, v1, v1, v1, v1) - -#if ENABLED(SWITCHING_EXTRUDER) && (DISABLED(SWITCHING_NOZZLE) || SWITCHING_EXTRUDER_SERVO_NR != SWITCHING_NOZZLE_SERVO_NR) - #define DO_SWITCH_EXTRUDER 1 -#endif +#define ARRAY_BY_HOTENDS1(v1) ARRAY_N_1(HOTENDS, v1) /** * Default hotend offsets, if not defined @@ -630,30 +719,18 @@ #endif /** - * DISTINCT_E_FACTORS affects how some E factors are accessed + * Disable unused SINGLENOZZLE sub-options */ -#if ENABLED(DISTINCT_E_FACTORS) && E_STEPPERS > 1 - #define DISTINCT_E E_STEPPERS - #define XYZE_N (XYZ + E_STEPPERS) - #define E_INDEX_N(E) (E) - #define E_AXIS_N(E) AxisEnum(E_AXIS + E) - #define UNUSED_E(E) NOOP -#else - #undef DISTINCT_E_FACTORS - #define DISTINCT_E 1 - #define XYZE_N XYZE - #define E_INDEX_N(E) 0 - #define E_AXIS_N(E) E_AXIS - #define UNUSED_E(E) UNUSED(E) +#if DISABLED(SINGLENOZZLE) + #undef SINGLENOZZLE_STANDBY_TEMP #endif - -#if ENABLED(DWIN_CREALITY_LCD) - #define SERIAL_CATCHALL 0 +#if !BOTH(HAS_FAN, SINGLENOZZLE) + #undef SINGLENOZZLE_STANDBY_FAN #endif -// Pressure sensor with a BLTouch-like interface -#if ENABLED(CREALITY_TOUCH) - #define BLTOUCH +// 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 #endif /** @@ -664,14 +741,19 @@ #ifndef Z_PROBE_SERVO_NR #define Z_PROBE_SERVO_NR 0 #endif - #undef DEACTIVATE_SERVOS_AFTER_MOVE + #ifdef DEACTIVATE_SERVOS_AFTER_MOVE + #error "BLTOUCH requires DEACTIVATE_SERVOS_AFTER_MOVE to be to disabled. Please update your Configuration.h file." + #endif // Always disable probe pin inverting for BLTouch - #undef Z_MIN_PROBE_ENDSTOP_INVERTING - #define Z_MIN_PROBE_ENDSTOP_INVERTING false + #if Z_MIN_PROBE_ENDSTOP_INVERTING + #error "BLTOUCH requires Z_MIN_PROBE_ENDSTOP_INVERTING set to false. Please update your Configuration.h file." + #endif + #if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) - #undef Z_MIN_ENDSTOP_INVERTING - #define Z_MIN_ENDSTOP_INVERTING false + #if Z_MIN_ENDSTOP_INVERTING + #error "BLTOUCH requires Z_MIN_ENDSTOP_INVERTING set to false. Please update your Configuration.h file." + #endif #endif #endif @@ -689,24 +771,149 @@ #endif /** - * Set flags for enabled probes + * Set a flag for any type of bed probe, including the paper-test */ #if ANY(HAS_Z_SERVO_PROBE, FIX_MOUNTED_PROBE, NOZZLE_AS_PROBE, TOUCH_MI_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, SOLENOID_PROBE, SENSORLESS_PROBING, RACK_AND_PINION_PROBE) #define HAS_BED_PROBE 1 #endif -#if ANY(HAS_BED_PROBE, PROBE_MANUALLY, MESH_BED_LEVELING) - #define PROBE_SELECTED 1 +/** + * Fill in undefined Filament Sensor options + */ +#if ENABLED(FILAMENT_RUNOUT_SENSOR) + #if NUM_RUNOUT_SENSORS >= 1 + #ifndef FIL_RUNOUT1_STATE + #define FIL_RUNOUT1_STATE FIL_RUNOUT_STATE + #endif + #ifndef FIL_RUNOUT1_PULLUP + #define FIL_RUNOUT1_PULLUP FIL_RUNOUT_PULLUP + #endif + #ifndef FIL_RUNOUT1_PULLDOWN + #define FIL_RUNOUT1_PULLDOWN FIL_RUNOUT_PULLDOWN + #endif + #endif + #if NUM_RUNOUT_SENSORS >= 2 + #ifndef FIL_RUNOUT2_STATE + #define FIL_RUNOUT2_STATE FIL_RUNOUT_STATE + #endif + #ifndef FIL_RUNOUT2_PULLUP + #define FIL_RUNOUT2_PULLUP FIL_RUNOUT_PULLUP + #endif + #ifndef FIL_RUNOUT2_PULLDOWN + #define FIL_RUNOUT2_PULLDOWN FIL_RUNOUT_PULLDOWN + #endif + #endif + #if NUM_RUNOUT_SENSORS >= 3 + #ifndef FIL_RUNOUT3_STATE + #define FIL_RUNOUT3_STATE FIL_RUNOUT_STATE + #endif + #ifndef FIL_RUNOUT3_PULLUP + #define FIL_RUNOUT3_PULLUP FIL_RUNOUT_PULLUP + #endif + #ifndef FIL_RUNOUT3_PULLDOWN + #define FIL_RUNOUT3_PULLDOWN FIL_RUNOUT_PULLDOWN + #endif + #endif + #if NUM_RUNOUT_SENSORS >= 4 + #ifndef FIL_RUNOUT4_STATE + #define FIL_RUNOUT4_STATE FIL_RUNOUT_STATE + #endif + #ifndef FIL_RUNOUT4_PULLUP + #define FIL_RUNOUT4_PULLUP FIL_RUNOUT_PULLUP + #endif + #ifndef FIL_RUNOUT4_PULLDOWN + #define FIL_RUNOUT4_PULLDOWN FIL_RUNOUT_PULLDOWN + #endif + #endif + #if NUM_RUNOUT_SENSORS >= 5 + #ifndef FIL_RUNOUT5_STATE + #define FIL_RUNOUT5_STATE FIL_RUNOUT_STATE + #endif + #ifndef FIL_RUNOUT5_PULLUP + #define FIL_RUNOUT5_PULLUP FIL_RUNOUT_PULLUP + #endif + #ifndef FIL_RUNOUT5_PULLDOWN + #define FIL_RUNOUT5_PULLDOWN FIL_RUNOUT_PULLDOWN + #endif + #endif + #if NUM_RUNOUT_SENSORS >= 6 + #ifndef FIL_RUNOUT6_STATE + #define FIL_RUNOUT6_STATE FIL_RUNOUT_STATE + #endif + #ifndef FIL_RUNOUT6_PULLUP + #define FIL_RUNOUT6_PULLUP FIL_RUNOUT_PULLUP + #endif + #ifndef FIL_RUNOUT6_PULLDOWN + #define FIL_RUNOUT6_PULLDOWN FIL_RUNOUT_PULLDOWN + #endif + #endif + #if NUM_RUNOUT_SENSORS >= 7 + #ifndef FIL_RUNOUT7_STATE + #define FIL_RUNOUT7_STATE FIL_RUNOUT_STATE + #endif + #ifndef FIL_RUNOUT7_PULLUP + #define FIL_RUNOUT7_PULLUP FIL_RUNOUT_PULLUP + #endif + #ifndef FIL_RUNOUT7_PULLDOWN + #define FIL_RUNOUT7_PULLDOWN FIL_RUNOUT_PULLDOWN + #endif + #endif + #if NUM_RUNOUT_SENSORS >= 8 + #ifndef FIL_RUNOUT8_STATE + #define FIL_RUNOUT8_STATE FIL_RUNOUT_STATE + #endif + #ifndef FIL_RUNOUT8_PULLUP + #define FIL_RUNOUT8_PULLUP FIL_RUNOUT_PULLUP + #endif + #ifndef FIL_RUNOUT8_PULLDOWN + #define FIL_RUNOUT8_PULLDOWN FIL_RUNOUT_PULLDOWN + #endif + #endif +#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 +#endif +#if Y_HOME_DIR > 0 + #define Y_HOME_TO_MAX 1 +#elif Y_HOME_DIR < 0 + #define Y_HOME_TO_MIN 1 +#endif +#if Z_HOME_DIR > 0 + #define Z_HOME_TO_MAX 1 +#elif Z_HOME_DIR < 0 + #define Z_HOME_TO_MIN 1 +#endif +#if I_HOME_DIR > 0 + #define I_HOME_TO_MAX 1 +#elif I_HOME_DIR < 0 + #define I_HOME_TO_MIN 1 +#endif +#if J_HOME_DIR > 0 + #define J_HOME_TO_MAX 1 +#elif J_HOME_DIR < 0 + #define J_HOME_TO_MIN 1 +#endif +#if K_HOME_DIR > 0 + #define K_HOME_TO_MAX 1 +#elif K_HOME_DIR < 0 + #define K_HOME_TO_MIN 1 #endif +/** + * 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 DISABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) - #define HAS_CUSTOM_PROBE_PIN 1 + #if DISABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) && !BOTH(DELTA, SENSORLESS_PROBING) + #define USES_Z_MIN_PROBE_PIN 1 #endif - #if Z_HOME_DIR < 0 && (!HAS_CUSTOM_PROBE_PIN || ENABLED(USE_PROBE_FOR_Z_HOMING)) + #if Z_HOME_TO_MIN && TERN1(USES_Z_MIN_PROBE_PIN, ENABLED(USE_PROBE_FOR_Z_HOMING)) #define HOMING_Z_WITH_PROBE 1 #endif #ifndef Z_PROBE_LOW_POINT @@ -725,10 +932,15 @@ #else // Clear probe pin settings when no probe is selected #undef Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN + #undef USE_PROBE_FOR_Z_HOMING +#endif + +#if Z_HOME_TO_MAX + #define HOME_Z_FIRST // If homing away from BED do Z first #endif /** - * Set granular options based on the specific type of leveling + * Conditionals based on the type of Bed Leveling */ #if ENABLED(AUTO_BED_LEVELING_UBL) #undef LCD_BED_LEVELING @@ -740,7 +952,7 @@ #define ABL_PLANAR 1 #endif #if EITHER(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_BILINEAR) - #define ABL_GRID 1 + #define ABL_USES_GRID 1 #endif #if ANY(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_3POINT) #define HAS_ABL_NOT_UBL 1 @@ -763,11 +975,16 @@ #define PLANNER_LEVELING 1 #endif #endif -#if EITHER(HAS_ABL_OR_UBL, Z_MIN_PROBE_REPEATABILITY_TEST) - #define HAS_PROBING_PROCEDURE 1 -#endif #if !HAS_LEVELING #undef RESTORE_LEVELING_AFTER_G28 + #undef ENABLE_LEVELING_AFTER_G28 + #undef G29_RETRY_AND_RECOVER +#endif +#if !HAS_LEVELING || EITHER(MESH_BED_LEVELING, AUTO_BED_LEVELING_UBL) + #undef PROBE_MANUALLY +#endif +#if ANY(HAS_BED_PROBE, PROBE_MANUALLY, MESH_BED_LEVELING) + #define PROBE_SELECTED 1 #endif #ifdef GRID_MAX_POINTS_X @@ -775,21 +992,62 @@ #define GRID_LOOP(A,B) LOOP_L_N(A, GRID_MAX_POINTS_X) LOOP_L_N(B, GRID_MAX_POINTS_Y) #endif -#ifndef INVERT_X_DIR - #define INVERT_X_DIR false -#endif -#ifndef INVERT_Y_DIR - #define INVERT_Y_DIR false +// Slim menu optimizations +#if ENABLED(SLIM_LCD_MENUS) + #define BOOT_MARLIN_LOGO_SMALL #endif -#ifndef INVERT_Z_DIR - #define INVERT_Z_DIR false + +/** + * CoreXY, CoreXZ, and CoreYZ - and their reverse + */ +#if EITHER(COREXY, COREYX) + #define CORE_IS_XY 1 +#endif +#if EITHER(COREXZ, COREZX) + #define CORE_IS_XZ 1 +#endif +#if EITHER(COREYZ, COREZY) + #define CORE_IS_YZ 1 +#endif +#if CORE_IS_XY || CORE_IS_XZ || CORE_IS_YZ + #define IS_CORE 1 +#endif +#if IS_CORE + #if CORE_IS_XY + #define CORE_AXIS_1 A_AXIS + #define CORE_AXIS_2 B_AXIS + #define NORMAL_AXIS Z_AXIS + #elif CORE_IS_XZ + #define CORE_AXIS_1 A_AXIS + #define NORMAL_AXIS Y_AXIS + #define CORE_AXIS_2 C_AXIS + #elif CORE_IS_YZ + #define NORMAL_AXIS X_AXIS + #define CORE_AXIS_1 B_AXIS + #define CORE_AXIS_2 C_AXIS + #endif + #define CORESIGN(n) (ANY(COREYX, COREZX, COREZY) ? (-(n)) : (n)) +#elif ENABLED(MARKFORGED_XY) + // Markforged kinematics + #define CORE_AXIS_1 A_AXIS + #define CORE_AXIS_2 B_AXIS + #define NORMAL_AXIS Z_AXIS #endif -#ifndef INVERT_E_DIR - #define INVERT_E_DIR false + +#if ANY(MORGAN_SCARA, MP_SCARA, AXEL_TPARA) + #define IS_SCARA 1 + #define IS_KINEMATIC 1 +#elif ENABLED(DELTA) + #define IS_KINEMATIC 1 +#else + #define IS_CARTESIAN 1 + #if !IS_CORE + #define IS_FULL_CARTESIAN 1 + #endif #endif -#if ENABLED(SLIM_LCD_MENUS) - #define BOOT_MARLIN_LOGO_SMALL +#if DISABLED(DELTA) + #undef DELTA_HOME_TO_SAFE_ZONE #endif // This flag indicates some kind of jerk storage is needed @@ -802,17 +1060,132 @@ #endif // E jerk exists with JD disabled (of course) but also when Linear Advance is disabled on Delta/SCARA -#if ENABLED(CLASSIC_JERK) || (IS_KINEMATIC && DISABLED(LIN_ADVANCE)) +#if HAS_EXTRUDERS && (ENABLED(CLASSIC_JERK) || (IS_KINEMATIC && DISABLED(LIN_ADVANCE))) #define HAS_CLASSIC_E_JERK 1 #endif -#ifndef SPI_SPEED - #define SPI_SPEED SPI_FULL_SPEED +// +// Serial Port Info +// +#ifdef SERIAL_PORT_2 + #define HAS_MULTI_SERIAL 1 + #ifdef SERIAL_PORT_3 + #define NUM_SERIAL 3 + #else + #define NUM_SERIAL 2 + #endif +#elif defined(SERIAL_PORT) + #define NUM_SERIAL 1 +#else + #define NUM_SERIAL 0 + #undef BAUD_RATE_GCODE #endif - -#if SERIAL_PORT == -1 || SERIAL_PORT_2 == -1 +#if SERIAL_PORT == -1 || SERIAL_PORT_2 == -1 || SERIAL_PORT_3 == -1 #define HAS_USB_SERIAL 1 #endif +#if SERIAL_PORT_2 == -2 + #define HAS_ETHERNET 1 +#endif + +#if ENABLED(DWIN_CREALITY_LCD) + #define SERIAL_CATCHALL 0 + #ifndef LCD_SERIAL_PORT + #if MB(BTT_SKR_MINI_E3_V1_0, BTT_SKR_MINI_E3_V1_2, BTT_SKR_MINI_E3_V2_0, BTT_SKR_E3_TURBO) + #define LCD_SERIAL_PORT 1 + #else + #define LCD_SERIAL_PORT 3 // Creality 4.x board + #endif + #endif +#endif + +// Fallback Stepper Driver types that don't depend on Configuration_adv.h +#ifndef X_DRIVER_TYPE + #define X_DRIVER_TYPE A4988 +#endif +#ifndef X2_DRIVER_TYPE + #define X2_DRIVER_TYPE A4988 +#endif +#ifndef Y_DRIVER_TYPE + #define Y_DRIVER_TYPE A4988 +#endif +#ifndef Y2_DRIVER_TYPE + #define Y2_DRIVER_TYPE A4988 +#endif +#ifndef Z_DRIVER_TYPE + #define Z_DRIVER_TYPE A4988 +#endif +#ifndef Z2_DRIVER_TYPE + #define Z2_DRIVER_TYPE A4988 +#endif +#ifndef Z3_DRIVER_TYPE + #define Z3_DRIVER_TYPE A4988 +#endif +#ifndef Z4_DRIVER_TYPE + #define Z4_DRIVER_TYPE A4988 +#endif +#if E_STEPPERS <= 0 + #undef E0_DRIVER_TYPE +#elif !defined(E0_DRIVER_TYPE) + #define E0_DRIVER_TYPE A4988 +#endif +#if E_STEPPERS <= 1 + #undef E1_DRIVER_TYPE +#elif !defined(E1_DRIVER_TYPE) + #define E1_DRIVER_TYPE A4988 +#endif +#if E_STEPPERS <= 2 + #undef E2_DRIVER_TYPE +#elif !defined(E2_DRIVER_TYPE) + #define E2_DRIVER_TYPE A4988 +#endif +#if E_STEPPERS <= 3 + #undef E3_DRIVER_TYPE +#elif !defined(E3_DRIVER_TYPE) + #define E3_DRIVER_TYPE A4988 +#endif +#if E_STEPPERS <= 4 + #undef E4_DRIVER_TYPE +#elif !defined(E4_DRIVER_TYPE) + #define E4_DRIVER_TYPE A4988 +#endif +#if E_STEPPERS <= 5 + #undef E5_DRIVER_TYPE +#elif !defined(E5_DRIVER_TYPE) + #define E5_DRIVER_TYPE A4988 +#endif +#if E_STEPPERS <= 6 + #undef E6_DRIVER_TYPE +#elif !defined(E6_DRIVER_TYPE) + #define E6_DRIVER_TYPE A4988 +#endif +#if E_STEPPERS <= 7 + #undef E7_DRIVER_TYPE +#elif !defined(E7_DRIVER_TYPE) + #define E7_DRIVER_TYPE A4988 +#endif + +// Fallback axis inverting +#ifndef INVERT_X_DIR + #define INVERT_X_DIR false +#endif +#if HAS_Y_AXIS && !defined(INVERT_Y_DIR) + #define INVERT_Y_DIR false +#endif +#if HAS_Z_AXIS && !defined(INVERT_Z_DIR) + #define INVERT_Z_DIR false +#endif +#if LINEAR_AXES >= 4 && !defined(INVERT_I_DIR) + #define INVERT_I_DIR false +#endif +#if LINEAR_AXES >= 5 && !defined(INVERT_J_DIR) + #define INVERT_J_DIR false +#endif +#if LINEAR_AXES >= 6 && !defined(INVERT_K_DIR) + #define INVERT_K_DIR false +#endif +#if HAS_EXTRUDERS && !defined(INVERT_E_DIR) + #define INVERT_E_DIR false +#endif /** * This setting is also used by M109 when trying to calculate @@ -834,115 +1207,196 @@ * - TFT_COLOR * - GRAPHICAL_TFT_UPSCALE */ -#if ENABLED(MKS_TS35_V2_0) - // Most common: ST7796 +#if ENABLED(MKS_TS35_V2_0) // ST7796 + #define TFT_DEFAULT_DRIVER ST7796 #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY) - #define TFT_WIDTH 480 - #define TFT_HEIGHT 320 + #define TFT_RES_480x320 #define TFT_INTERFACE_SPI - #define GRAPHICAL_TFT_UPSCALE 3 -#elif ENABLED(MKS_ROBIN_TFT24) - // Most common: ST7789 +#elif ENABLED(ANET_ET5_TFT35) // ST7796 + #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY) + #define TFT_RES_480x320 + #define TFT_INTERFACE_FSMC +#elif ENABLED(ANET_ET4_TFT28) // ST7789 #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_Y) - #define TFT_WIDTH 320 - #define TFT_HEIGHT 240 + #define TFT_RES_320x240 #define TFT_INTERFACE_FSMC - #define GRAPHICAL_TFT_UPSCALE 2 -#elif ENABLED(MKS_ROBIN_TFT28) - // Most common: ST7789 +#elif ENABLED(MKS_ROBIN_TFT24) // ST7789 #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_Y) - #define TFT_WIDTH 320 - #define TFT_HEIGHT 240 + #define TFT_RES_320x240 #define TFT_INTERFACE_FSMC - #define GRAPHICAL_TFT_UPSCALE 2 -#elif ENABLED(MKS_ROBIN_TFT32) - // Most common: ST7789 +#elif ENABLED(MKS_ROBIN_TFT28) // ST7789 #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_Y) - #define TFT_WIDTH 320 - #define TFT_HEIGHT 240 + #define TFT_RES_320x240 #define TFT_INTERFACE_FSMC - #define GRAPHICAL_TFT_UPSCALE 2 -#elif ENABLED(MKS_ROBIN_TFT35) - // Most common: ILI9488 +#elif ENABLED(MKS_ROBIN_TFT32) // ST7789 + #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_Y) + #define TFT_RES_320x240 + #define TFT_INTERFACE_FSMC +#elif ENABLED(MKS_ROBIN_TFT35) // ILI9488 #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_X | TFT_INVERT_Y) - #define TFT_WIDTH 480 - #define TFT_HEIGHT 320 + #define TFT_RES_480x320 #define TFT_INTERFACE_FSMC - #define GRAPHICAL_TFT_UPSCALE 3 #elif ENABLED(MKS_ROBIN_TFT43) - #define TFT_DEFAULT_ORIENTATION 0 #define TFT_DRIVER SSD1963 - #define TFT_WIDTH 480 - #define TFT_HEIGHT 272 - #define TFT_INTERFACE_FSMC - #define GRAPHICAL_TFT_UPSCALE 2 -#elif ENABLED(MKS_ROBIN_TFT_V1_1R) - // ILI9328 or R61505 - #define TFT_DEFAULT_ORIENTATION (TFT_INVERT_X | TFT_INVERT_Y | TFT_EXCHANGE_XY) - #define TFT_WIDTH 320 - #define TFT_HEIGHT 240 + #define TFT_DEFAULT_ORIENTATION 0 + #define TFT_RES_480x272 #define TFT_INTERFACE_FSMC - #define GRAPHICAL_TFT_UPSCALE 2 -#elif EITHER(TFT_TRONXY_X5SA, ANYCUBIC_TFT35) +#elif ENABLED(MKS_ROBIN_TFT_V1_1R) // ILI9328 or R61505 #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_X | TFT_INVERT_Y) + #define TFT_RES_320x240 + #define TFT_INTERFACE_FSMC +#elif EITHER(TFT_TRONXY_X5SA, ANYCUBIC_TFT35) // ILI9488 #define TFT_DRIVER ILI9488 - #define TFT_WIDTH 480 - #define TFT_HEIGHT 320 + #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_X | TFT_INVERT_Y) + #define TFT_RES_480x320 #define TFT_INTERFACE_FSMC - #define GRAPHICAL_TFT_UPSCALE 3 #elif ENABLED(LONGER_LK_TFT28) #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_X | TFT_INVERT_Y) - #define TFT_WIDTH 320 - #define TFT_HEIGHT 240 + #define TFT_RES_320x240 #define TFT_INTERFACE_FSMC - #define GRAPHICAL_TFT_UPSCALE 2 +#elif ENABLED(BIQU_BX_TFT70) // RGB + #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY) + #define TFT_RES_1024x600 + #define TFT_INTERFACE_LTDC + #if ENABLED(TOUCH_SCREEN) + #define TFT_TOUCH_DEVICE_GT911 + #endif #elif ENABLED(TFT_GENERIC) #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_X | TFT_INVERT_Y) + #if NONE(TFT_RES_320x240, TFT_RES_480x272, TFT_RES_480x320) + #define TFT_RES_320x240 + #endif + #if NONE(TFT_INTERFACE_FSMC, TFT_INTERFACE_SPI) + #define TFT_INTERFACE_SPI + #endif #endif -// FSMC/SPI TFT Panels using standard HAL/tft/tft_(fsmc|spi).h +#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 + #define GRAPHICAL_TFT_UPSCALE 4 +#endif + +// FSMC/SPI TFT Panels using standard HAL/tft/tft_(fsmc|spi|ltdc).h #if ENABLED(TFT_INTERFACE_FSMC) #define HAS_FSMC_TFT 1 - #if ENABLED(TFT_CLASSIC_UI) - #define FSMC_GRAPHICAL_TFT - #elif ENABLED(TFT_LVGL_UI) - #define TFT_LVGL_UI_FSMC + #if TFT_SCALED_DOGLCD + #define HAS_FSMC_GRAPHICAL_TFT 1 + #elif HAS_TFT_LVGL_UI + #define HAS_TFT_LVGL_UI_FSMC 1 #endif #elif ENABLED(TFT_INTERFACE_SPI) #define HAS_SPI_TFT 1 - #if ENABLED(TFT_CLASSIC_UI) - #define SPI_GRAPHICAL_TFT - #elif ENABLED(TFT_LVGL_UI) - #define TFT_LVGL_UI_SPI + #if TFT_SCALED_DOGLCD + #define HAS_SPI_GRAPHICAL_TFT 1 + #elif HAS_TFT_LVGL_UI + #define HAS_TFT_LVGL_UI_SPI 1 + #endif +#elif ENABLED(TFT_INTERFACE_LTDC) + #define HAS_LTDC_TFT 1 + #if TFT_SCALED_DOGLCD + #define HAS_LTDC_GRAPHICAL_TFT 1 + #elif HAS_TFT_LVGL_UI + #define HAS_TFT_LVGL_UI_LTDC 1 #endif #endif -#if ENABLED(TFT_COLOR_UI) && TFT_HEIGHT == 240 - #if ENABLED(TFT_INTERFACE_SPI) - #define TFT_320x240_SPI - #elif ENABLED(TFT_INTERFACE_FSMC) - #define TFT_320x240 - #endif -#elif ENABLED(TFT_COLOR_UI) && TFT_HEIGHT == 320 - #if ENABLED(TFT_INTERFACE_SPI) - #define TFT_480x320_SPI - #elif ENABLED(TFT_INTERFACE_FSMC) - #define TFT_480x320 +#if ENABLED(TFT_COLOR_UI) + #if TFT_HEIGHT == 240 + #if ENABLED(TFT_INTERFACE_SPI) + #define TFT_320x240_SPI + #elif ENABLED(TFT_INTERFACE_FSMC) + #define TFT_320x240 + #endif + #elif TFT_HEIGHT == 320 + #if ENABLED(TFT_INTERFACE_SPI) + #define TFT_480x320_SPI + #elif ENABLED(TFT_INTERFACE_FSMC) + #define TFT_480x320 + #endif + #elif TFT_HEIGHT == 272 + #if ENABLED(TFT_INTERFACE_SPI) + #define TFT_480x272_SPI + #elif ENABLED(TFT_INTERFACE_FSMC) + #define TFT_480x272 + #endif + #elif TFT_HEIGHT == 600 + #if ENABLED(TFT_INTERFACE_LTDC) + #define TFT_1024x600_LTDC + #endif #endif #endif -// Fewer lines with touch buttons on-screen #if EITHER(TFT_320x240, TFT_320x240_SPI) #define HAS_UI_320x240 1 - #define LCD_HEIGHT TERN(TOUCH_SCREEN, 6, 7) #elif EITHER(TFT_480x320, TFT_480x320_SPI) #define HAS_UI_480x320 1 - #define LCD_HEIGHT TERN(TOUCH_SCREEN, 6, 7) +#elif EITHER(TFT_480x272, TFT_480x272_SPI) + #define HAS_UI_480x272 1 +#elif defined(TFT_1024x600_LTDC) + #define HAS_UI_1024x600 1 +#endif +#if ANY(HAS_UI_320x240, HAS_UI_480x320, HAS_UI_480x272) + #define LCD_HEIGHT TERN(TOUCH_SCREEN, 6, 7) // Fewer lines with touch buttons onscreen +#elif HAS_UI_1024x600 + #define LCD_HEIGHT TERN(TOUCH_SCREEN, 12, 13) // Fewer lines with touch buttons onscreen #endif // This emulated DOGM has 'touch/xpt2046', not 'tft/xpt2046' -#if ENABLED(TOUCH_SCREEN) && !HAS_GRAPHICAL_TFT - #undef TOUCH_SCREEN - #undef TOUCH_SCREEN_CALIBRATION - #define HAS_TOUCH_XPT2046 1 +#if ENABLED(TOUCH_SCREEN) + #if NONE(TFT_TOUCH_DEVICE_GT911, TFT_TOUCH_DEVICE_XPT2046) + #define TFT_TOUCH_DEVICE_XPT2046 // ADS7843/XPT2046 ADC Touchscreen such as ILI9341 2.8 + #endif + #if ENABLED(TFT_TOUCH_DEVICE_GT911) // GT911 Capacitive touch screen such as BIQU_BX_TFT70 + #undef TOUCH_SCREEN_CALIBRATION + #undef TOUCH_CALIBRATION_AUTO_SAVE + #endif + #if !HAS_GRAPHICAL_TFT + #undef TOUCH_SCREEN + #if ENABLED(TFT_CLASSIC_UI) + #define HAS_TOUCH_BUTTONS 1 + #if ENABLED(TFT_TOUCH_DEVICE_GT911) + #define HAS_CAP_TOUCH_BUTTONS 1 + #else + #define HAS_RES_TOUCH_BUTTONS 1 + #endif + #endif + #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 ANY(USE_XMIN_PLUG, USE_YMIN_PLUG, USE_ZMIN_PLUG, USE_XMAX_PLUG, USE_YMAX_PLUG, USE_ZMAX_PLUG) + #define HAS_ENDSTOPS 1 + #define COORDINATE_OKAY(N,L,H) WITHIN(N,L,H) +#else + #define COORDINATE_OKAY(N,L,H) true +#endif + +/** + * LED Backlight INDEX END + */ +#if defined(NEOPIXEL_BKGD_INDEX_FIRST) && !defined(NEOPIXEL_BKGD_INDEX_LAST) + #define NEOPIXEL_BKGD_INDEX_LAST NEOPIXEL_BKGD_INDEX_FIRST #endif diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index bab05e5ff60d..7fe0ee6deff6 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -26,6 +26,10 @@ * Defines that depend on advanced configuration. */ +#ifndef AXIS_RELATIVE_MODES + #define AXIS_RELATIVE_MODES {} +#endif + #ifdef SWITCHING_NOZZLE_E1_SERVO_NR #define SWITCHING_NOZZLE_TWO_SERVOS 1 #endif @@ -33,7 +37,7 @@ // Determine NUM_SERVOS if none was supplied #ifndef NUM_SERVOS #define NUM_SERVOS 0 - #if ANY(CHAMBER_VENT, HAS_Z_SERVO_PROBE, SWITCHING_EXTRUDER, SWITCHING_NOZZLE) + #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) @@ -62,6 +66,10 @@ #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 @@ -71,7 +79,7 @@ #define SERVO_DELAY { 50 } #endif -#if EXTRUDERS == 0 +#if !HAS_EXTRUDERS #define NO_VOLUMETRICS #undef TEMP_SENSOR_0 #undef TEMP_SENSOR_1 @@ -99,6 +107,9 @@ #undef THERMAL_PROTECTION_PERIOD #undef WATCH_TEMP_PERIOD #undef SHOW_TEMP_ADC_VALUES + #undef LCD_SHOW_E_TOTAL + #undef MANUAL_E_MOVES_RELATIVE + #undef STEALTHCHOP_E #endif #if TEMP_SENSOR_BED == 0 @@ -110,6 +121,10 @@ #undef THERMAL_PROTECTION_CHAMBER #endif +#if TEMP_SENSOR_COOLER == 0 + #undef THERMAL_PROTECTION_COOLER +#endif + #if ENABLED(MIXING_EXTRUDER) && (ENABLED(RETRACT_SYNC_MIXING) || BOTH(FILAMENT_LOAD_UNLOAD_GCODES, FILAMENT_UNLOAD_ALL_EXTRUDERS)) #define HAS_MIXER_SYNC_CHANNEL 1 #endif @@ -124,9 +139,15 @@ #if ENABLED(FILAMENT_RUNOUT_SENSOR) #define HAS_FILAMENT_SENSOR 1 + #if NUM_RUNOUT_SENSORS > 1 + #define MULTI_FILAMENT_SENSOR 1 + #endif #ifdef FILAMENT_RUNOUT_DISTANCE_MM #define HAS_FILAMENT_RUNOUT_DISTANCE 1 #endif + #if ENABLED(MIXING_EXTRUDER) + #define WATCH_ALL_RUNOUT_SENSORS + #endif #endif // Let SD_FINISHED_RELEASECOMMAND stand in for SD_FINISHED_STEPPERRELEASE @@ -138,17 +159,25 @@ #undef SD_FINISHED_RELEASECOMMAND #endif +#if ENABLED(NO_SD_AUTOSTART) + #undef MENU_ADDAUTOSTART +#endif + #if EITHER(SDSUPPORT, LCD_SET_PROGRESS_MANUALLY) #define HAS_PRINT_PROGRESS 1 #endif +#if ENABLED(SDSUPPORT) && SD_PROCEDURE_DEPTH + #define HAS_MEDIA_SUBCALLS 1 +#endif + #if HAS_PRINT_PROGRESS && EITHER(PRINT_PROGRESS_SHOW_DECIMALS, SHOW_REMAINING_TIME) #define HAS_PRINT_PROGRESS_PERMYRIAD 1 #endif #if ANY(MARLIN_BRICKOUT, MARLIN_INVADERS, MARLIN_SNAKE, MARLIN_MAZE) #define HAS_GAMES 1 - #if (1 < ENABLED(MARLIN_BRICKOUT) + ENABLED(MARLIN_INVADERS) + ENABLED(MARLIN_SNAKE) + ENABLED(MARLIN_MAZE)) + #if MANY(MARLIN_BRICKOUT, MARLIN_INVADERS, MARLIN_SNAKE, MARLIN_MAZE) #define HAS_GAME_MENU 1 #endif #endif @@ -163,7 +192,7 @@ #if EITHER(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS) #define HAS_SOFTWARE_ENDSTOPS 1 #endif -#if ANY(EXTENSIBLE_UI, NEWPANEL, EMERGENCY_PARSER, HAS_ADC_BUTTONS, DWIN_CREALITY_LCD) +#if ANY(EXTENSIBLE_UI, IS_NEWPANEL, EMERGENCY_PARSER, HAS_ADC_BUTTONS, DWIN_CREALITY_LCD) #define HAS_RESUME_CONTINUE 1 #endif @@ -178,16 +207,39 @@ #define HAS_MOTOR_CURRENT_I2C 1 #endif +#if ENABLED(Z_STEPPER_AUTO_ALIGN) + #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) + #undef Z_STEPPER_ALIGN_AMP + #endif + #ifndef Z_STEPPER_ALIGN_AMP + #define Z_STEPPER_ALIGN_AMP 1.0 + #endif +#endif + // Multiple Z steppers #ifndef NUM_Z_STEPPER_DRIVERS #define NUM_Z_STEPPER_DRIVERS 1 #endif -#if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) - #undef Z_STEPPER_ALIGN_AMP +// Fallback Stepper Driver types that depend on Configuration_adv.h +#if NONE(DUAL_X_CARRIAGE, X_DUAL_STEPPER_DRIVERS) + #undef X2_DRIVER_TYPE #endif -#ifndef Z_STEPPER_ALIGN_AMP - #define Z_STEPPER_ALIGN_AMP 1.0 +#if DISABLED(Y_DUAL_STEPPER_DRIVERS) + #undef Y2_DRIVER_TYPE +#endif + +#if NUM_Z_STEPPER_DRIVERS < 4 + #undef Z4_DRIVER_TYPE + #undef INVERT_Z4_VS_Z_DIR + #if NUM_Z_STEPPER_DRIVERS < 3 + #undef Z3_DRIVER_TYPE + #undef INVERT_Z3_VS_Z_DIR + #if NUM_Z_STEPPER_DRIVERS < 2 + #undef Z2_DRIVER_TYPE + #undef INVERT_Z2_VS_Z_DIR + #endif + #endif #endif // @@ -200,7 +252,7 @@ #define _CUTTER_POWER_PERCENT 2 #define _CUTTER_POWER_RPM 3 #define _CUTTER_POWER(V) _CAT(_CUTTER_POWER_, V) - #define CUTTER_UNIT_IS(V) (_CUTTER_POWER(CUTTER_POWER_UNIT) == _CUTTER_POWER(V)) + #define CUTTER_UNIT_IS(V) (_CUTTER_POWER(CUTTER_POWER_UNIT) == _CUTTER_POWER(V)) #endif // Add features that need hardware PWM here @@ -208,10 +260,7 @@ #define NEEDS_HARDWARE_PWM 1 #endif -#if defined(__AVR__) && defined(USBCON) - #define IS_AT90USB 1 - #undef SERIAL_XON_XOFF // Not supported on USB-native devices -#else +#if !defined(__AVR__) || !defined(USBCON) // Define constants and variables for buffering serial data. // Use only 0 or powers of 2 greater than 1 // : [0, 4, 8, 16, 32, 64, 128, 256, 512, 1024, 2048, ...] @@ -223,6 +272,9 @@ #ifndef TX_BUFFER_SIZE #define TX_BUFFER_SIZE 32 #endif +#else + // SERIAL_XON_XOFF not supported on USB-native devices + #undef SERIAL_XON_XOFF #endif #if ENABLED(HOST_ACTION_COMMANDS) @@ -325,19 +377,14 @@ #endif #endif -// If platform requires early initialization of watchdog to properly boot -#if ENABLED(USE_WATCHDOG) && defined(ARDUINO_ARCH_SAM) - #define EARLY_WATCHDOG 1 -#endif - // Full Touch Screen needs 'tft/xpt2046' -#if EITHER(TOUCH_SCREEN, HAS_TFT_LVGL_UI) +#if EITHER(TFT_TOUCH_DEVICE_XPT2046, HAS_TFT_LVGL_UI) #define HAS_TFT_XPT2046 1 #endif // Touch Screen or "Touch Buttons" need XPT2046 pins // but they use different components -#if EITHER(HAS_TFT_XPT2046, HAS_TOUCH_XPT2046) +#if HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS #define NEED_TOUCH_PINS 1 #endif @@ -351,6 +398,20 @@ #define POLL_JOG #endif +#if X2_HOME_DIR > 0 + #define X2_HOME_TO_MAX 1 +#elif X2_HOME_DIR < 0 + #define X2_HOME_TO_MIN 1 +#endif + +#ifndef HOMING_BUMP_MM + #define HOMING_BUMP_MM { 0, 0, 0 } +#endif + +#if ENABLED(USB_FLASH_DRIVE_SUPPORT) && NONE(USE_OTG_USB_HOST, USE_UHS3_USB) + #define USE_UHS2_USB +#endif + /** * Driver Timings (in nanoseconds) * NOTE: Driver timing order is longest-to-shortest duration. @@ -428,6 +489,37 @@ #endif #endif +// Remove unused STEALTHCHOP flags +#if LINEAR_AXES < 6 + #undef STEALTHCHOP_K + #undef CALIBRATION_MEASURE_KMIN + #undef CALIBRATION_MEASURE_KMAX + #if LINEAR_AXES < 5 + #undef STEALTHCHOP_J + #undef CALIBRATION_MEASURE_JMIN + #undef CALIBRATION_MEASURE_JMAX + #if LINEAR_AXES < 4 + #undef STEALTHCHOP_I + #undef CALIBRATION_MEASURE_IMIN + #undef CALIBRATION_MEASURE_IMAX + #if LINEAR_AXES < 3 + #undef Z_IDLE_HEIGHT + #undef STEALTHCHOP_Z + #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_STEPPER_DRIVERS + #undef CNC_WORKSPACE_PLANES + #if LINEAR_AXES < 2 + #undef STEALTHCHOP_Y + #endif + #endif + #endif + #endif +#endif + // // SD Card connection methods // Defined here so pins and sanity checks can use them @@ -445,12 +537,9 @@ // Power Monitor sensors #if EITHER(POWER_MONITOR_CURRENT, POWER_MONITOR_VOLTAGE) #define HAS_POWER_MONITOR 1 -#endif -#if ENABLED(POWER_MONITOR_CURRENT) && defined(POWER_MONITOR_FIXED_VOLTAGE) - #define HAS_POWER_MONITOR_VREF 1 -#endif -#if BOTH(HAS_POWER_MONITOR_VREF, POWER_MONITOR_CURRENT) - #define HAS_POWER_MONITOR_WATTS 1 + #if ENABLED(POWER_MONITOR_CURRENT) && (ENABLED(POWER_MONITOR_VOLTAGE) || defined(POWER_MONITOR_FIXED_VOLTAGE)) + #define HAS_POWER_MONITOR_WATTS 1 + #endif #endif // Flag if an EEPROM type is pre-selected @@ -463,41 +552,30 @@ #define NEED_HEX_PRINT 1 #endif +// 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) + #define CASE_LIGHT_IS_COLOR_LED 1 + #else + #define NEED_CASE_LIGHT_PIN 1 + #endif +#endif + // Flag whether least_squares_fit.cpp is used #if ANY(AUTO_BED_LEVELING_UBL, AUTO_BED_LEVELING_LINEAR, Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) #define NEED_LSF 1 #endif -// Flag the indexed serial ports that are in use -#define ANY_SERIAL_IS(N) (defined(SERIAL_PORT) && SERIAL_PORT == (N)) || (defined(SERIAL_PORT_2) && SERIAL_PORT_2 == (N)) || (defined(LCD_SERIAL_PORT) && LCD_SERIAL_PORT == (N)) -#if ANY_SERIAL_IS(-1) - #define USING_SERIAL_DEFAULT -#endif -#if ANY_SERIAL_IS(0) - #define USING_SERIAL_0 1 -#endif -#if ANY_SERIAL_IS(1) - #define USING_SERIAL_1 1 -#endif -#if ANY_SERIAL_IS(2) - #define USING_SERIAL_2 1 -#endif -#if ANY_SERIAL_IS(3) - #define USING_SERIAL_3 1 -#endif -#if ANY_SERIAL_IS(4) - #define USING_SERIAL_4 1 -#endif -#if ANY_SERIAL_IS(5) - #define USING_SERIAL_5 1 -#endif -#if ANY_SERIAL_IS(6) - #define USING_SERIAL_6 1 +#if BOTH(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 #endif -#if ANY_SERIAL_IS(7) - #define USING_SERIAL_7 1 + +#if !HAS_MULTI_SERIAL + #undef MEATPACK_ON_SERIAL_PORT_2 #endif -#if ANY_SERIAL_IS(8) - #define USING_SERIAL_8 1 +#if EITHER(MEATPACK_ON_SERIAL_PORT_1, MEATPACK_ON_SERIAL_PORT_2) + #define HAS_MEATPACK 1 #endif -#undef ANY_SERIAL_IS diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 798bf009c639..2fb276b10c23 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -78,17 +78,49 @@ /** * Axis lengths and center */ +#ifndef AXIS4_NAME + #define AXIS4_NAME 'A' +#endif +#ifndef AXIS5_NAME + #define AXIS5_NAME 'B' +#endif +#ifndef AXIS6_NAME + #define AXIS6_NAME 'C' +#endif + #define X_MAX_LENGTH (X_MAX_POS - (X_MIN_POS)) -#define Y_MAX_LENGTH (Y_MAX_POS - (Y_MIN_POS)) -#define Z_MAX_LENGTH (Z_MAX_POS - (Z_MIN_POS)) +#if HAS_Y_AXIS + #define Y_MAX_LENGTH (Y_MAX_POS - (Y_MIN_POS)) +#endif +#if HAS_Z_AXIS + #define Z_MAX_LENGTH (Z_MAX_POS - (Z_MIN_POS)) +#endif +#if LINEAR_AXES >= 4 + #define I_MAX_LENGTH (I_MAX_POS - (I_MIN_POS)) +#endif +#if LINEAR_AXES >= 5 + #define J_MAX_LENGTH (J_MAX_POS - (J_MIN_POS)) +#endif +#if LINEAR_AXES >= 6 + #define K_MAX_LENGTH (K_MAX_POS - (K_MIN_POS)) +#endif // Defined only if the sanity-check is bypassed #ifndef X_BED_SIZE #define X_BED_SIZE X_MAX_LENGTH #endif -#ifndef Y_BED_SIZE +#if HAS_Y_AXIS && !defined(Y_BED_SIZE) #define Y_BED_SIZE Y_MAX_LENGTH #endif +#if LINEAR_AXES >= 4 && !defined(I_BED_SIZE) + #define I_BED_SIZE I_MAX_LENGTH +#endif +#if LINEAR_AXES >= 5 && !defined(J_BED_SIZE) + #define J_BED_SIZE J_MAX_LENGTH +#endif +#if LINEAR_AXES >= 6 && !defined(K_BED_SIZE) + #define K_BED_SIZE K_MAX_LENGTH +#endif // Require 0,0 bed center for Delta and SCARA #if IS_KINEMATIC @@ -97,15 +129,53 @@ // Define center values for future use #define _X_HALF_BED ((X_BED_SIZE) / 2) -#define _Y_HALF_BED ((Y_BED_SIZE) / 2) +#if HAS_Y_AXIS + #define _Y_HALF_BED ((Y_BED_SIZE) / 2) +#endif +#if LINEAR_AXES >= 4 + #define _I_HALF_IMAX ((I_BED_SIZE) / 2) +#endif +#if LINEAR_AXES >= 5 + #define _J_HALF_JMAX ((J_BED_SIZE) / 2) +#endif +#if LINEAR_AXES >= 6 + #define _K_HALF_KMAX ((K_BED_SIZE) / 2) +#endif + #define X_CENTER TERN(BED_CENTER_AT_0_0, 0, _X_HALF_BED) -#define Y_CENTER TERN(BED_CENTER_AT_0_0, 0, _Y_HALF_BED) +#if HAS_Y_AXIS + #define Y_CENTER TERN(BED_CENTER_AT_0_0, 0, _Y_HALF_BED) + #define XY_CENTER { X_CENTER, Y_CENTER } +#endif +#if LINEAR_AXES >= 4 + #define I_CENTER TERN(BED_CENTER_AT_0_0, 0, _I_HALF_BED) +#endif +#if LINEAR_AXES >= 5 + #define J_CENTER TERN(BED_CENTER_AT_0_0, 0, _J_HALF_BED) +#endif +#if LINEAR_AXES >= 6 + #define K_CENTER TERN(BED_CENTER_AT_0_0, 0, _K_HALF_BED) +#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) -#define Y_MIN_BED (Y_CENTER - _Y_HALF_BED) -#define Y_MAX_BED (Y_MIN_BED + Y_BED_SIZE) +#if HAS_Y_AXIS + #define Y_MIN_BED (Y_CENTER - _Y_HALF_BED) + #define Y_MAX_BED (Y_MIN_BED + Y_BED_SIZE) +#endif +#if LINEAR_AXES >= 4 + #define I_MINIM (I_CENTER - _I_HALF_BED_SIZE) + #define I_MAXIM (I_MINIM + I_BED_SIZE) +#endif +#if LINEAR_AXES >= 5 + #define J_MINIM (J_CENTER - _J_HALF_BED_SIZE) + #define J_MAXIM (J_MINIM + J_BED_SIZE) +#endif +#if LINEAR_AXES >= 6 + #define K_MINIM (K_CENTER - _K_HALF_BED_SIZE) + #define K_MAXIM (K_MINIM + K_BED_SIZE) +#endif /** * Dual X Carriage @@ -119,49 +189,12 @@ #endif #endif -/** - * CoreXY, CoreXZ, and CoreYZ - and their reverse - */ -#if EITHER(COREXY, COREYX) - #define CORE_IS_XY 1 -#endif -#if EITHER(COREXZ, COREZX) - #define CORE_IS_XZ 1 -#endif -#if EITHER(COREYZ, COREZY) - #define CORE_IS_YZ 1 -#endif -#if CORE_IS_XY || CORE_IS_XZ || CORE_IS_YZ - #define IS_CORE 1 -#endif -#if IS_CORE - #if CORE_IS_XY - #define CORE_AXIS_1 A_AXIS - #define CORE_AXIS_2 B_AXIS - #define NORMAL_AXIS Z_AXIS - #elif CORE_IS_XZ - #define CORE_AXIS_1 A_AXIS - #define NORMAL_AXIS Y_AXIS - #define CORE_AXIS_2 C_AXIS - #elif CORE_IS_YZ - #define NORMAL_AXIS X_AXIS - #define CORE_AXIS_1 B_AXIS - #define CORE_AXIS_2 C_AXIS - #endif - #define CORESIGN(n) (ANY(COREYX, COREZX, COREZY) ? (-(n)) : (n)) -#elif ENABLED(MARKFORGED_XY) - // Markforged kinematics - #define CORE_AXIS_1 A_AXIS - #define CORE_AXIS_2 B_AXIS - #define NORMAL_AXIS Z_AXIS -#endif - // Calibration codes only for non-core axes #if EITHER(BACKLASH_GCODE, CALIBRATION_GCODE) #if EITHER(IS_CORE, MARKFORGED_XY) #define CAN_CALIBRATE(A,B) (_AXIS(A) == B) #else - #define CAN_CALIBRATE(A,B) 1 + #define CAN_CALIBRATE(A,B) true #endif #endif #define AXIS_CAN_CALIBRATE(A) CAN_CALIBRATE(A,NORMAL_AXIS) @@ -179,7 +212,9 @@ */ #if IS_SCARA #undef SLOWDOWN - #define QUICK_HOME + #if DISABLED(AXEL_TPARA) + #define QUICK_HOME + #endif #define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2) #endif @@ -189,7 +224,7 @@ #ifdef MANUAL_X_HOME_POS #define X_HOME_POS MANUAL_X_HOME_POS #else - #define X_END_POS (X_HOME_DIR < 0 ? X_MIN_POS : X_MAX_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 @@ -197,21 +232,45 @@ #endif #endif -#ifdef MANUAL_Y_HOME_POS - #define Y_HOME_POS MANUAL_Y_HOME_POS -#else - #define Y_END_POS (Y_HOME_DIR < 0 ? Y_MIN_POS : Y_MAX_POS) - #if ENABLED(BED_CENTER_AT_0_0) - #define Y_HOME_POS TERN(DELTA, 0, Y_END_POS) +#if HAS_Y_AXIS + #ifdef MANUAL_Y_HOME_POS + #define Y_HOME_POS MANUAL_Y_HOME_POS #else - #define Y_HOME_POS TERN(DELTA, Y_MIN_POS + (Y_BED_SIZE) * 0.5, Y_END_POS) + #define Y_END_POS TERN(Y_HOME_TO_MIN, Y_MIN_POS, Y_MAX_POS) + #if ENABLED(BED_CENTER_AT_0_0) + #define Y_HOME_POS TERN(DELTA, 0, Y_END_POS) + #else + #define Y_HOME_POS TERN(DELTA, Y_MIN_POS + (Y_BED_SIZE) * 0.5, Y_END_POS) + #endif #endif #endif #ifdef MANUAL_Z_HOME_POS #define Z_HOME_POS MANUAL_Z_HOME_POS #else - #define Z_HOME_POS (Z_HOME_DIR < 0 ? Z_MIN_POS : Z_MAX_POS) + #define Z_HOME_POS TERN(Z_HOME_TO_MIN, Z_MIN_POS, Z_MAX_POS) +#endif + +#if LINEAR_AXES >= 4 + #ifdef MANUAL_I_HOME_POS + #define I_HOME_POS MANUAL_I_HOME_POS + #else + #define I_HOME_POS TERN(I_HOME_TO_MIN, I_MIN_POS, I_MAX_POS) + #endif +#endif +#if LINEAR_AXES >= 5 + #ifdef MANUAL_J_HOME_POS + #define J_HOME_POS MANUAL_J_HOME_POS + #else + #define J_HOME_POS TERN(J_HOME_TO_MIN, J_MIN_POS, J_MAX_POS) + #endif +#endif +#if LINEAR_AXES >= 6 + #ifdef MANUAL_K_HOME_POS + #define K_HOME_POS MANUAL_K_HOME_POS + #else + #define K_HOME_POS TERN(K_HOME_TO_MIN, K_MIN_POS, K_MAX_POS) + #endif #endif /** @@ -258,6 +317,11 @@ #endif #endif +#ifdef GRID_MAX_POINTS_X + #define GRID_MAX_CELLS_X (GRID_MAX_POINTS_X - 1) + #define GRID_MAX_CELLS_Y (GRID_MAX_POINTS_Y - 1) +#endif + /** * Host keep alive */ @@ -299,12 +363,16 @@ #elif ENABLED(AZSMZ_12864) #define _LCD_CONTRAST_MIN 120 #define _LCD_CONTRAST_INIT 190 -#elif ENABLED(MKS_LCD12864) +#elif EITHER(MKS_LCD12864A, MKS_LCD12864B) #define _LCD_CONTRAST_MIN 120 #define _LCD_CONTRAST_INIT 205 #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) #define _LCD_CONTRAST_MIN 120 #define _LCD_CONTRAST_INIT 195 +#elif ENABLED(MKS_MINI_12864_V3) + #define _LCD_CONTRAST_MIN 255 + #define _LCD_CONTRAST_INIT 255 + #define _LCD_CONTRAST_MAX 255 #elif ENABLED(FYSETC_MINI_12864) #define _LCD_CONTRAST_INIT 220 #elif ENABLED(ULTI_CONTROLLER) @@ -359,7 +427,7 @@ */ #if ENABLED(SDSUPPORT) - #if SD_CONNECTION_IS(ONBOARD) && DISABLED(NO_SD_HOST_DRIVE) && !defined(ARDUINO_GRAND_CENTRAL_M4) + #if HAS_SD_HOST_DRIVE && SD_CONNECTION_IS(ONBOARD) // // The external SD card is not used. Hardware SPI is used to access the card. // When sharing the SD card with a PC we want the menu options to @@ -369,21 +437,31 @@ #define HAS_SHARED_MEDIA 1 #endif - #if PIN_EXISTS(SD_DETECT) - #if HAS_LCD_MENU && (SD_CONNECTION_IS(LCD) || !defined(SDCARD_CONNECTION)) - #undef SD_DETECT_STATE - #if ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) - #define SD_DETECT_STATE HIGH - #endif - #endif - #ifndef SD_DETECT_STATE + // Set SD_DETECT_STATE based on hardware if not overridden + #if PIN_EXISTS(SD_DETECT) && !defined(SD_DETECT_STATE) + #if BOTH(HAS_LCD_MENU, ELB_FULL_GRAPHIC_CONTROLLER) && (SD_CONNECTION_IS(LCD) || !defined(SDCARD_CONNECTION)) + #define SD_DETECT_STATE HIGH + #else #define SD_DETECT_STATE LOW #endif #endif + // Extender cable doesn't support SD_DETECT_PIN + #if ENABLED(NO_SD_DETECT) + #undef SD_DETECT_PIN + #endif + + #if DISABLED(USB_FLASH_DRIVE_SUPPORT) || BOTH(MULTI_VOLUME, VOLUME_SD_ONBOARD) + #if ENABLED(SDIO_SUPPORT) + #define NEED_SD2CARD_SDIO 1 + #else + #define NEED_SD2CARD_SPI 1 + #endif + #endif + #endif -#if ANY(HAS_GRAPHICAL_TFT, LCD_USE_DMA_FSMC, FSMC_GRAPHICAL_TFT, SPI_GRAPHICAL_TFT) || !PIN_EXISTS(SD_DETECT) +#if ANY(HAS_GRAPHICAL_TFT, LCD_USE_DMA_FSMC, HAS_FSMC_GRAPHICAL_TFT, HAS_SPI_GRAPHICAL_TFT) || !PIN_EXISTS(SD_DETECT) #define NO_LCD_REINIT 1 // Suppress LCD re-initialization #endif @@ -393,15 +471,24 @@ #ifndef DISABLE_INACTIVE_X #define DISABLE_INACTIVE_X DISABLE_X #endif -#ifndef DISABLE_INACTIVE_Y +#if HAS_Y_AXIS && !defined(DISABLE_INACTIVE_Y) #define DISABLE_INACTIVE_Y DISABLE_Y #endif -#ifndef DISABLE_INACTIVE_Z +#if HAS_Z_AXIS && !defined(DISABLE_INACTIVE_Z) #define DISABLE_INACTIVE_Z DISABLE_Z #endif #ifndef DISABLE_INACTIVE_E #define DISABLE_INACTIVE_E DISABLE_E #endif +#if LINEAR_AXES >= 4 && !defined(DISABLE_INACTIVE_I) + #define DISABLE_INACTIVE_I DISABLE_I +#endif +#if LINEAR_AXES >= 5 && !defined(DISABLE_INACTIVE_J) + #define DISABLE_INACTIVE_J DISABLE_J +#endif +#if LINEAR_AXES >= 6 && !defined(DISABLE_INACTIVE_K) + #define DISABLE_INACTIVE_K DISABLE_K +#endif /** * Power Supply @@ -416,43 +503,148 @@ #endif #endif -#if !defined(PSU_POWERUP_DELAY) && ENABLED(PSU_CONTROL) - #define PSU_POWERUP_DELAY 250 +#if ENABLED(PSU_CONTROL) + #ifndef PSU_POWERUP_DELAY + #define PSU_POWERUP_DELAY 250 + #endif + #ifndef POWER_OFF_DELAY + #define POWER_OFF_DELAY 0 + #endif #endif /** * Temp Sensor defines */ -#define ANY_TEMP_SENSOR_IS(n) (TEMP_SENSOR_0 == (n) || TEMP_SENSOR_1 == (n) || TEMP_SENSOR_2 == (n) || TEMP_SENSOR_3 == (n) || TEMP_SENSOR_4 == (n) || TEMP_SENSOR_5 == (n) || TEMP_SENSOR_6 == (n) || TEMP_SENSOR_7 == (n) || TEMP_SENSOR_BED == (n) || TEMP_SENSOR_PROBE == (n) || TEMP_SENSOR_CHAMBER == (n)) - +#define ANY_TEMP_SENSOR_IS(n) ( \ + n == TEMP_SENSOR_0 || n == TEMP_SENSOR_1 || n == TEMP_SENSOR_2 || n == TEMP_SENSOR_3 \ + || n == TEMP_SENSOR_4 || n == TEMP_SENSOR_5 || n == TEMP_SENSOR_6 || n == TEMP_SENSOR_7 \ + || n == TEMP_SENSOR_BED \ + || n == TEMP_SENSOR_PROBE \ + || n == TEMP_SENSOR_CHAMBER \ + || n == TEMP_SENSOR_COOLER \ + || n == TEMP_SENSOR_REDUNDANT ) #if ANY_TEMP_SENSOR_IS(1000) #define HAS_USER_THERMISTORS 1 #endif +#undef ANY_TEMP_SENSOR_IS -#if TEMP_SENSOR_0 == -5 || TEMP_SENSOR_0 == -3 || TEMP_SENSOR_0 == -2 - #define HEATER_0_USES_MAX6675 - #if TEMP_SENSOR_0 == -3 - #define HEATER_0_MAX6675_TMIN -270 - #define HEATER_0_MAX6675_TMAX 1800 - #else - #define HEATER_0_MAX6675_TMIN 0 - #define HEATER_0_MAX6675_TMAX 1024 +// Usurp a sensor to do redundant readings +#if TEMP_SENSOR_REDUNDANT + #ifndef TEMP_SENSOR_REDUNDANT_SOURCE + #define TEMP_SENSOR_REDUNDANT_SOURCE 1 + #endif + #ifndef TEMP_SENSOR_REDUNDANT_TARGET + #define TEMP_SENSOR_REDUNDANT_TARGET 0 + #endif + #if !PIN_EXISTS(TEMP_REDUNDANT) + #ifndef TEMP_SENSOR_REDUNDANT_MAX_DIFF + #define TEMP_SENSOR_REDUNDANT_MAX_DIFF 10 + #endif + #if TEMP_SENSOR_REDUNDANT_SOURCE == -5 + #if !PIN_EXISTS(TEMP_COOLER) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to COOLER requires TEMP_COOLER_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_COOLER_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == -4 + #if !PIN_EXISTS(TEMP_PROBE) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to PROBE requires TEMP_PROBE_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_PROBE_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == -2 + #if !PIN_EXISTS(TEMP_CHAMBER) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to CHAMBER requires TEMP_CHAMBER_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_CHAMBER_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == -1 + #if !PIN_EXISTS(TEMP_BED) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to BED requires TEMP_BED_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_BED_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 0 + #if !PIN_EXISTS(TEMP_0) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 0 requires TEMP_0_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_0_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 1 + #if !PIN_EXISTS(TEMP_1) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 1 requires TEMP_1_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_1_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 2 + #if !PIN_EXISTS(TEMP_2) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 2 requires TEMP_2_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_2_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 3 + #if !PIN_EXISTS(TEMP_3) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 3 requires TEMP_3_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_3_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 4 + #if !PIN_EXISTS(TEMP_4) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 4 requires TEMP_4_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_4_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 5 + #if !PIN_EXISTS(TEMP_5) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 5 requires TEMP_5_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_5_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 6 + #if !PIN_EXISTS(TEMP_6) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 6 requires TEMP_6_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_6_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 7 + #if !PIN_EXISTS(TEMP_7) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 7 requires TEMP_7_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_7_PIN + #endif + #endif #endif +#endif + +#if TEMP_SENSOR_0 == -5 || TEMP_SENSOR_0 == -3 || TEMP_SENSOR_0 == -2 + #define TEMP_SENSOR_0_IS_MAX_TC 1 #if TEMP_SENSOR_0 == -5 - #define MAX6675_IS_MAX31865 + #define TEMP_SENSOR_0_IS_MAX31865 1 + #define TEMP_SENSOR_0_MAX_TC_TMIN 0 + #define TEMP_SENSOR_0_MAX_TC_TMAX 1024 + #ifndef MAX31865_SENSOR_WIRES_0 + #define MAX31865_SENSOR_WIRES_0 2 + #endif #elif TEMP_SENSOR_0 == -3 - #define MAX6675_IS_MAX31855 + #define TEMP_SENSOR_0_IS_MAX31855 1 + #define TEMP_SENSOR_0_MAX_TC_TMIN -270 + #define TEMP_SENSOR_0_MAX_TC_TMAX 1800 + #elif TEMP_SENSOR_0 == -2 + #define TEMP_SENSOR_0_IS_MAX6675 1 + #define TEMP_SENSOR_0_MAX_TC_TMIN 0 + #define TEMP_SENSOR_0_MAX_TC_TMAX 1024 #endif #elif TEMP_SENSOR_0 == -4 - #define HEATER_0_USES_AD8495 + #define TEMP_SENSOR_0_IS_AD8495 1 #elif TEMP_SENSOR_0 == -1 - #define HEATER_0_USES_AD595 + #define TEMP_SENSOR_0_IS_AD595 1 #elif TEMP_SENSOR_0 > 0 - #define THERMISTOR_HEATER_0 TEMP_SENSOR_0 - #define HEATER_0_USES_THERMISTOR + #define TEMP_SENSOR_0_IS_THERMISTOR 1 #if TEMP_SENSOR_0 == 1000 - #define HEATER_0_USER_THERMISTOR + #define TEMP_SENSOR_0_IS_CUSTOM 1 + #elif TEMP_SENSOR_0 == 998 || TEMP_SENSOR_0 == 999 + #define TEMP_SENSOR_0_IS_DUMMY 1 #endif #else #undef HEATER_0_MINTEMP @@ -460,14 +652,24 @@ #endif #if TEMP_SENSOR_1 == -5 || TEMP_SENSOR_1 == -3 || TEMP_SENSOR_1 == -2 - #define HEATER_1_USES_MAX6675 - #if TEMP_SENSOR_1 == -3 - #define HEATER_1_MAX6675_TMIN -270 - #define HEATER_1_MAX6675_TMAX 1800 - #else - #define HEATER_1_MAX6675_TMIN 0 - #define HEATER_1_MAX6675_TMAX 1024 + #define TEMP_SENSOR_1_IS_MAX_TC 1 + #if TEMP_SENSOR_1 == -5 + #define TEMP_SENSOR_1_IS_MAX31865 1 + #define TEMP_SENSOR_1_MAX_TC_TMIN 0 + #define TEMP_SENSOR_1_MAX_TC_TMAX 1024 + #ifndef MAX31865_SENSOR_WIRES_1 + #define MAX31865_SENSOR_WIRES_1 2 + #endif + #elif TEMP_SENSOR_1 == -3 + #define TEMP_SENSOR_1_IS_MAX31855 1 + #define TEMP_SENSOR_1_MAX_TC_TMIN -270 + #define TEMP_SENSOR_1_MAX_TC_TMAX 1800 + #elif TEMP_SENSOR_1 == -2 + #define TEMP_SENSOR_1_IS_MAX6675 1 + #define TEMP_SENSOR_1_MAX_TC_TMIN 0 + #define TEMP_SENSOR_1_MAX_TC_TMAX 1024 #endif + #if TEMP_SENSOR_1 != TEMP_SENSOR_0 #if TEMP_SENSOR_1 == -5 #error "If MAX31865 Thermocouple (-5) is used for TEMP_SENSOR_1 then TEMP_SENSOR_0 must match." @@ -478,33 +680,278 @@ #endif #endif #elif TEMP_SENSOR_1 == -4 - #define HEATER_1_USES_AD8495 + #define TEMP_SENSOR_1_IS_AD8495 1 #elif TEMP_SENSOR_1 == -1 - #define HEATER_1_USES_AD595 + #define TEMP_SENSOR_1_IS_AD595 1 #elif TEMP_SENSOR_1 > 0 - #define THERMISTOR_HEATER_1 TEMP_SENSOR_1 - #define HEATER_1_USES_THERMISTOR + #define TEMP_SENSOR_1_IS_THERMISTOR 1 #if TEMP_SENSOR_1 == 1000 - #define HEATER_1_USER_THERMISTOR + #define TEMP_SENSOR_1_IS_CUSTOM 1 + #elif TEMP_SENSOR_1 == 998 || TEMP_SENSOR_1 == 999 + #define TEMP_SENSOR_1_IS_DUMMY 1 #endif #else #undef HEATER_1_MINTEMP #undef HEATER_1_MAXTEMP #endif +#if TEMP_SENSOR_REDUNDANT == -5 || TEMP_SENSOR_REDUNDANT == -3 || TEMP_SENSOR_REDUNDANT == -2 + #define TEMP_SENSOR_REDUNDANT_IS_MAX_TC 1 + + #if TEMP_SENSOR_REDUNDANT == -5 + #if TEMP_SENSOR_REDUNDANT_SOURCE != 0 && TEMP_SENSOR_REDUNDANT_SOURCE != 1 + #error "MAX31865 Thermocouples (-5) not supported for TEMP_SENSOR_REDUNDANT_SOURCE other than TEMP_SENSOR_0/TEMP_SENSOR_1 (0/1)." + #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 TEMP_SENSOR_REDUNDANT_SOURCE != 0 && TEMP_SENSOR_REDUNDANT_SOURCE != 1 + #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_REDUNDANT_SOURCE other than TEMP_SENSOR_0/TEMP_SENSOR_1 (0/1)." + #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 TEMP_SENSOR_REDUNDANT_SOURCE != 0 && TEMP_SENSOR_REDUNDANT_SOURCE != 1 + #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_REDUNDANT_SOURCE other than TEMP_SENSOR_0/TEMP_SENSOR_1 (0/1)." + #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 + + // mimic setting up the source TEMP_SENSOR + #if TEMP_SENSOR_REDUNDANT_SOURCE == 0 + #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 + #ifndef MAX31865_SENSOR_WIRES_0 + #define MAX31865_SENSOR_WIRES_0 2 + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 1 + #define TEMP_SENSOR_1_MAX_TC_TMIN TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN + #define TEMP_SENSOR_1_MAX_TC_TMAX TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX + #ifndef MAX31865_SENSOR_WIRES_1 + #define MAX31865_SENSOR_WIRES_1 2 + #endif + #endif + + #if (TEMP_SENSOR_0_IS_MAX_TC && TEMP_SENSOR_REDUNDANT != TEMP_SENSOR_0) || (TEMP_SENSOR_1_IS_MAX_TC && TEMP_SENSOR_REDUNDANT != TEMP_SENSOR_1) + #if TEMP_SENSOR_REDUNDANT == -5 + #error "If MAX31865 Thermocouple (-5) is used for TEMP_SENSOR_0/TEMP_SENSOR_1 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 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 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 > 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_0_IS_MAX_TC || TEMP_SENSOR_1_IS_MAX_TC || TEMP_SENSOR_REDUNDANT_IS_MAX_TC + #define HAS_MAX_TC 1 +#endif +#if TEMP_SENSOR_0_IS_MAX6675 || TEMP_SENSOR_1_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_REDUNDANT_IS_MAX31855 + #define HAS_MAX31855 1 +#endif +#if TEMP_SENSOR_0_IS_MAX31865 || TEMP_SENSOR_1_IS_MAX31865 || TEMP_SENSOR_REDUNDANT_IS_MAX31865 + #define HAS_MAX31865 1 +#endif + +// +// 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_0_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 1) + + #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 + + #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 + + // 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_0_IS_MAX_TC + + #if TEMP_SENSOR_1_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 1) + + #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 + + // 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 + #endif + + #endif // TEMP_SENSOR_1_IS_MAX_TC + + // + // User-defined thermocouple libraries + // + // 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) + #define LIB_USR_MAX6675 1 + #endif + #if BOTH(HAS_MAX31855, LIB_MAX31855) + #define LIB_USR_MAX31855 1 + #endif + #if BOTH(HAS_MAX31865, LIB_MAX31865) + #define LIB_USR_MAX31865 1 + #elif HAS_MAX31865 + #define LIB_INTERNAL_MAX31865 1 + #endif + +#endif //HAS_MAX_TC + #if TEMP_SENSOR_2 == -4 - #define HEATER_2_USES_AD8495 + #define TEMP_SENSOR_2_IS_AD8495 1 #elif TEMP_SENSOR_2 == -3 #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_2." #elif TEMP_SENSOR_2 == -2 #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_2." #elif TEMP_SENSOR_2 == -1 - #define HEATER_2_USES_AD595 + #define TEMP_SENSOR_2_IS_AD595 1 #elif TEMP_SENSOR_2 > 0 - #define THERMISTOR_HEATER_2 TEMP_SENSOR_2 - #define HEATER_2_USES_THERMISTOR + #define TEMP_SENSOR_2_IS_THERMISTOR 1 #if TEMP_SENSOR_2 == 1000 - #define HEATER_2_USER_THERMISTOR + #define TEMP_SENSOR_2_IS_CUSTOM 1 + #elif TEMP_SENSOR_2 == 998 || TEMP_SENSOR_2 == 999 + #define TEMP_SENSOR_2_IS_DUMMY 1 #endif #else #undef HEATER_2_MINTEMP @@ -512,18 +959,19 @@ #endif #if TEMP_SENSOR_3 == -4 - #define HEATER_3_USES_AD8495 + #define TEMP_SENSOR_3_IS_AD8495 1 #elif TEMP_SENSOR_3 == -3 #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_3." #elif TEMP_SENSOR_3 == -2 #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_3." #elif TEMP_SENSOR_3 == -1 - #define HEATER_3_USES_AD595 + #define TEMP_SENSOR_3_IS_AD595 1 #elif TEMP_SENSOR_3 > 0 - #define THERMISTOR_HEATER_3 TEMP_SENSOR_3 - #define HEATER_3_USES_THERMISTOR + #define TEMP_SENSOR_3_IS_THERMISTOR 1 #if TEMP_SENSOR_3 == 1000 - #define HEATER_3_USER_THERMISTOR + #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 @@ -531,18 +979,19 @@ #endif #if TEMP_SENSOR_4 == -4 - #define HEATER_4_USES_AD8495 + #define TEMP_SENSOR_4_IS_AD8495 1 #elif TEMP_SENSOR_4 == -3 #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_4." #elif TEMP_SENSOR_4 == -2 #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_4." #elif TEMP_SENSOR_4 == -1 - #define HEATER_4_USES_AD595 + #define TEMP_SENSOR_4_IS_AD595 1 #elif TEMP_SENSOR_4 > 0 - #define THERMISTOR_HEATER_4 TEMP_SENSOR_4 - #define HEATER_4_USES_THERMISTOR + #define TEMP_SENSOR_4_IS_THERMISTOR 1 #if TEMP_SENSOR_4 == 1000 - #define HEATER_4_USER_THERMISTOR + #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 @@ -550,18 +999,19 @@ #endif #if TEMP_SENSOR_5 == -4 - #define HEATER_5_USES_AD8495 + #define TEMP_SENSOR_5_IS_AD8495 1 #elif TEMP_SENSOR_5 == -3 #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_5." #elif TEMP_SENSOR_5 == -2 #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_5." #elif TEMP_SENSOR_5 == -1 - #define HEATER_5_USES_AD595 + #define TEMP_SENSOR_5_IS_AD595 1 #elif TEMP_SENSOR_5 > 0 - #define THERMISTOR_HEATER_5 TEMP_SENSOR_5 - #define HEATER_5_USES_THERMISTOR + #define TEMP_SENSOR_5_IS_THERMISTOR 1 #if TEMP_SENSOR_5 == 1000 - #define HEATER_5_USER_THERMISTOR + #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 @@ -569,18 +1019,19 @@ #endif #if TEMP_SENSOR_6 == -4 - #define HEATER_6_USES_AD8495 + #define TEMP_SENSOR_6_IS_AD8495 1 #elif TEMP_SENSOR_6 == -3 #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_6." #elif TEMP_SENSOR_6 == -2 #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_6." #elif TEMP_SENSOR_6 == -1 - #define HEATER_6_USES_AD595 + #define TEMP_SENSOR_6_IS_AD595 1 #elif TEMP_SENSOR_6 > 0 - #define THERMISTOR_HEATER_6 TEMP_SENSOR_6 - #define HEATER_6_USES_THERMISTOR + #define TEMP_SENSOR_6_IS_THERMISTOR 1 #if TEMP_SENSOR_6 == 1000 - #define HEATER_6_USER_THERMISTOR + #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 @@ -588,18 +1039,19 @@ #endif #if TEMP_SENSOR_7 == -4 - #define HEATER_7_USES_AD8495 + #define TEMP_SENSOR_7_IS_AD8495 1 #elif TEMP_SENSOR_7 == -3 #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_7." #elif TEMP_SENSOR_7 == -2 #error "MAX7775 Thermocouples (-2) not supported for TEMP_SENSOR_7." #elif TEMP_SENSOR_7 == -1 - #define HEATER_7_USES_AD595 + #define TEMP_SENSOR_7_IS_AD595 1 #elif TEMP_SENSOR_7 > 0 - #define THERMISTOR_HEATER_7 TEMP_SENSOR_7 - #define HEATER_7_USES_THERMISTOR + #define TEMP_SENSOR_7_IS_THERMISTOR 1 #if TEMP_SENSOR_7 == 1000 - #define HEATER_7_USER_THERMISTOR + #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 @@ -607,18 +1059,19 @@ #endif #if TEMP_SENSOR_BED == -4 - #define HEATER_BED_USES_AD8495 + #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 HEATER_BED_USES_AD595 + #define TEMP_SENSOR_BED_IS_AD595 1 #elif TEMP_SENSOR_BED > 0 - #define THERMISTORBED TEMP_SENSOR_BED - #define HEATER_BED_USES_THERMISTOR + #define TEMP_SENSOR_BED_IS_THERMISTOR 1 #if TEMP_SENSOR_BED == 1000 - #define HEATER_BED_USER_THERMISTOR + #define TEMP_SENSOR_BED_IS_CUSTOM 1 + #elif TEMP_SENSOR_BED == 998 || TEMP_SENSOR_BED == 999 + #define TEMP_SENSOR_BED_IS_DUMMY 1 #endif #else #undef BED_MINTEMP @@ -626,49 +1079,67 @@ #endif #if TEMP_SENSOR_CHAMBER == -4 - #define HEATER_CHAMBER_USES_AD8495 + #define TEMP_SENSOR_CHAMBER_IS_AD8495 1 #elif TEMP_SENSOR_CHAMBER == -3 #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_CHAMBER." #elif TEMP_SENSOR_CHAMBER == -2 #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_CHAMBER." #elif TEMP_SENSOR_CHAMBER == -1 - #define HEATER_CHAMBER_USES_AD595 + #define TEMP_SENSOR_CHAMBER_IS_AD595 1 #elif TEMP_SENSOR_CHAMBER > 0 - #define THERMISTORCHAMBER TEMP_SENSOR_CHAMBER - #define HEATER_CHAMBER_USES_THERMISTOR + #define TEMP_SENSOR_CHAMBER_IS_THERMISTOR 1 #if TEMP_SENSOR_CHAMBER == 1000 - #define HEATER_CHAMBER_USER_THERMISTOR + #define TEMP_SENSOR_CHAMBER_IS_CUSTOM 1 + #elif TEMP_SENSOR_CHAMBER == 998 || TEMP_SENSOR_CHAMBER == 999 + #define TEMP_SENSOR_CHAMBER_IS_DUMMY 1 #endif #else #undef CHAMBER_MINTEMP #undef CHAMBER_MAXTEMP #endif +#if TEMP_SENSOR_COOLER == -4 + #define TEMP_SENSOR_COOLER_IS_AD8495 1 +#elif TEMP_SENSOR_COOLER == -3 + #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_COOLER." +#elif TEMP_SENSOR_COOLER == -2 + #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 > 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 COOLER_MINTEMP + #undef COOLER_MAXTEMP +#endif + #if TEMP_SENSOR_PROBE == -4 - #define HEATER_PROBE_USES_AD8495 + #define TEMP_SENSOR_PROBE_IS_AD8495 1 #elif TEMP_SENSOR_PROBE == -3 #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_PROBE." #elif TEMP_SENSOR_PROBE == -2 #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_PROBE." #elif TEMP_SENSOR_PROBE == -1 - #define HEATER_PROBE_USES_AD595 + #define TEMP_SENSOR_PROBE_IS_AD595 1 #elif TEMP_SENSOR_PROBE > 0 - #define THERMISTORPROBE TEMP_SENSOR_PROBE - #define PROBE_USES_THERMISTOR + #define TEMP_SENSOR_PROBE_IS_THERMISTOR 1 #if TEMP_SENSOR_PROBE == 1000 - #define PROBE_USER_THERMISTOR + #define TEMP_SENSOR_PROBE_IS_CUSTOM 1 + #elif TEMP_SENSOR_PROBE == 998 || TEMP_SENSOR_PROBE == 999 + #define TEMP_SENSOR_PROBE_IS_DUMMY 1 #endif #endif -#define HOTEND_USES_THERMISTOR ANY( \ - HEATER_0_USES_THERMISTOR, HEATER_1_USES_THERMISTOR, HEATER_2_USES_THERMISTOR, HEATER_3_USES_THERMISTOR, \ - HEATER_4_USES_THERMISTOR, HEATER_5_USES_THERMISTOR, HEATER_6_USES_THERMISTOR, HEATER_7_USES_THERMISTOR ) - /** * X_DUAL_ENDSTOPS endstop reassignment */ #if ENABLED(X_DUAL_ENDSTOPS) - #if X_HOME_DIR > 0 + #if X_HOME_TO_MAX #ifndef X2_MAX_ENDSTOP_INVERTING #if X2_USE_ENDSTOP == _XMIN_ #define X2_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING @@ -791,7 +1262,7 @@ * Y_DUAL_ENDSTOPS endstop reassignment */ #if ENABLED(Y_DUAL_ENDSTOPS) - #if Y_HOME_DIR > 0 + #if Y_HOME_TO_MAX #ifndef Y2_MAX_ENDSTOP_INVERTING #if Y2_USE_ENDSTOP == _XMIN_ #define Y2_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING @@ -915,7 +1386,7 @@ */ #if ENABLED(Z_MULTI_ENDSTOPS) - #if Z_HOME_DIR > 0 + #if Z_HOME_TO_MAX #ifndef Z2_MAX_ENDSTOP_INVERTING #if Z2_USE_ENDSTOP == _XMIN_ #define Z2_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING @@ -1034,7 +1505,7 @@ #endif #if NUM_Z_STEPPER_DRIVERS >= 3 - #if Z_HOME_DIR > 0 + #if Z_HOME_TO_MAX #ifndef Z3_MAX_ENDSTOP_INVERTING #if Z3_USE_ENDSTOP == _XMIN_ #define Z3_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING @@ -1154,7 +1625,7 @@ #endif #if NUM_Z_STEPPER_DRIVERS >= 4 - #if Z_HOME_DIR > 0 + #if Z_HOME_TO_MAX #ifndef Z4_MAX_ENDSTOP_INVERTING #if Z4_USE_ENDSTOP == _XMIN_ #define Z4_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING @@ -1288,6 +1759,15 @@ #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_XMIN_PLUG) #define ENDSTOPPULLUP_XMIN #endif @@ -1297,6 +1777,15 @@ #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 #endif /** @@ -1354,219 +1843,278 @@ #define HAS_X2_MS_PINS 1 #endif -#if PIN_EXISTS(Y_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y)) - #define HAS_Y_ENABLE 1 -#endif -#if PIN_EXISTS(Y_DIR) - #define HAS_Y_DIR 1 -#endif -#if PIN_EXISTS(Y_STEP) - #define HAS_Y_STEP 1 -#endif -#if PIN_EXISTS(Y_MS1) - #define HAS_Y_MS_PINS 1 -#endif +#if HAS_Y_AXIS + #if PIN_EXISTS(Y_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y)) + #define HAS_Y_ENABLE 1 + #endif + #if PIN_EXISTS(Y_DIR) + #define HAS_Y_DIR 1 + #endif + #if PIN_EXISTS(Y_STEP) + #define HAS_Y_STEP 1 + #endif + #if PIN_EXISTS(Y_MS1) + #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 + #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 -#if PIN_EXISTS(Z_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z)) - #define HAS_Z_ENABLE 1 -#endif -#if PIN_EXISTS(Z_DIR) - #define HAS_Z_DIR 1 -#endif -#if PIN_EXISTS(Z_STEP) - #define HAS_Z_STEP 1 -#endif -#if PIN_EXISTS(Z_MS1) - #define HAS_Z_MS_PINS 1 +#if HAS_Z_AXIS + #if PIN_EXISTS(Z_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z)) + #define HAS_Z_ENABLE 1 + #endif + #if PIN_EXISTS(Z_DIR) + #define HAS_Z_DIR 1 + #endif + #if PIN_EXISTS(Z_STEP) + #define HAS_Z_STEP 1 + #endif + #if PIN_EXISTS(Z_MS1) + #define HAS_Z_MS_PINS 1 + #endif #endif -#if PIN_EXISTS(Z2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z2)) - #define HAS_Z2_ENABLE 1 -#endif -#if PIN_EXISTS(Z2_DIR) - #define HAS_Z2_DIR 1 -#endif -#if PIN_EXISTS(Z2_STEP) - #define HAS_Z2_STEP 1 -#endif -#if PIN_EXISTS(Z2_MS1) - #define HAS_Z2_MS_PINS 1 +#if NUM_Z_STEPPER_DRIVERS >= 2 + #if PIN_EXISTS(Z2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z2)) + #define HAS_Z2_ENABLE 1 + #endif + #if PIN_EXISTS(Z2_DIR) + #define HAS_Z2_DIR 1 + #endif + #if PIN_EXISTS(Z2_STEP) + #define HAS_Z2_STEP 1 + #endif + #if PIN_EXISTS(Z2_MS1) + #define HAS_Z2_MS_PINS 1 + #endif #endif -#if PIN_EXISTS(Z3_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z3)) - #define HAS_Z3_ENABLE 1 -#endif -#if PIN_EXISTS(Z3_DIR) - #define HAS_Z3_DIR 1 -#endif -#if PIN_EXISTS(Z3_STEP) - #define HAS_Z3_STEP 1 -#endif -#if PIN_EXISTS(Z3_MS1) - #define HAS_Z3_MS_PINS 1 +#if NUM_Z_STEPPER_DRIVERS >= 3 + #if PIN_EXISTS(Z3_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z3)) + #define HAS_Z3_ENABLE 1 + #endif + #if PIN_EXISTS(Z3_DIR) + #define HAS_Z3_DIR 1 + #endif + #if PIN_EXISTS(Z3_STEP) + #define HAS_Z3_STEP 1 + #endif + #if PIN_EXISTS(Z3_MS1) + #define HAS_Z3_MS_PINS 1 + #endif #endif -#if PIN_EXISTS(Z4_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z4)) - #define HAS_Z4_ENABLE 1 -#endif -#if PIN_EXISTS(Z4_DIR) - #define HAS_Z4_DIR 1 -#endif -#if PIN_EXISTS(Z4_STEP) - #define HAS_Z4_STEP 1 -#endif -#if PIN_EXISTS(Z4_MS1) - #define HAS_Z4_MS_PINS 1 +#if NUM_Z_STEPPER_DRIVERS >= 4 + #if PIN_EXISTS(Z4_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z4)) + #define HAS_Z4_ENABLE 1 + #endif + #if PIN_EXISTS(Z4_DIR) + #define HAS_Z4_DIR 1 + #endif + #if PIN_EXISTS(Z4_STEP) + #define HAS_Z4_STEP 1 + #endif + #if PIN_EXISTS(Z4_MS1) + #define HAS_Z4_MS_PINS 1 + #endif #endif -// Extruder steppers and solenoids -#if PIN_EXISTS(E0_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E0)) - #define HAS_E0_ENABLE 1 -#endif -#if PIN_EXISTS(E0_DIR) - #define HAS_E0_DIR 1 -#endif -#if PIN_EXISTS(E0_STEP) - #define HAS_E0_STEP 1 -#endif -#if PIN_EXISTS(E0_MS1) - #define HAS_E0_MS_PINS 1 -#endif -#if PIN_EXISTS(SOL0) - #define HAS_SOLENOID_0 1 +#if LINEAR_AXES >= 4 + #if PIN_EXISTS(I_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(I)) + #define HAS_I_ENABLE 1 + #endif + #if PIN_EXISTS(I_DIR) + #define HAS_I_DIR 1 + #endif + #if PIN_EXISTS(I_STEP) + #define HAS_I_STEP 1 + #endif + #if PIN_EXISTS(I_MS1) + #define HAS_I_MS_PINS 1 + #endif #endif -#if PIN_EXISTS(E1_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E1)) - #define HAS_E1_ENABLE 1 -#endif -#if PIN_EXISTS(E1_DIR) - #define HAS_E1_DIR 1 -#endif -#if PIN_EXISTS(E1_STEP) - #define HAS_E1_STEP 1 -#endif -#if PIN_EXISTS(E1_MS1) - #define HAS_E1_MS_PINS 1 -#endif -#if PIN_EXISTS(SOL1) - #define HAS_SOLENOID_1 1 +#if LINEAR_AXES >= 5 + #if PIN_EXISTS(J_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(J)) + #define HAS_J_ENABLE 1 + #endif + #if PIN_EXISTS(J_DIR) + #define HAS_J_DIR 1 + #endif + #if PIN_EXISTS(J_STEP) + #define HAS_J_STEP 1 + #endif + #if PIN_EXISTS(J_MS1) + #define HAS_J_MS_PINS 1 + #endif #endif -#if PIN_EXISTS(E2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E2)) - #define HAS_E2_ENABLE 1 -#endif -#if PIN_EXISTS(E2_DIR) - #define HAS_E2_DIR 1 -#endif -#if PIN_EXISTS(E2_STEP) - #define HAS_E2_STEP 1 -#endif -#if PIN_EXISTS(E2_MS1) - #define HAS_E2_MS_PINS 1 -#endif -#if PIN_EXISTS(SOL2) - #define HAS_SOLENOID_2 1 +#if LINEAR_AXES >= 6 + #if PIN_EXISTS(K_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(K)) + #define HAS_K_ENABLE 1 + #endif + #if PIN_EXISTS(K_DIR) + #define HAS_K_DIR 1 + #endif + #if PIN_EXISTS(K_STEP) + #define HAS_K_STEP 1 + #endif + #if PIN_EXISTS(K_MS1) + #define HAS_K_MS_PINS 1 + #endif #endif -#if PIN_EXISTS(E3_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E3)) - #define HAS_E3_ENABLE 1 -#endif -#if PIN_EXISTS(E3_DIR) - #define HAS_E3_DIR 1 -#endif -#if PIN_EXISTS(E3_STEP) - #define HAS_E3_STEP 1 -#endif -#if PIN_EXISTS(E3_MS1) - #define HAS_E3_MS_PINS 1 -#endif -#if PIN_EXISTS(SOL3) - #define HAS_SOLENOID_3 1 -#endif +// Extruder steppers and solenoids +#if HAS_EXTRUDERS -#if PIN_EXISTS(E4_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E4)) - #define HAS_E4_ENABLE 1 -#endif -#if PIN_EXISTS(E4_DIR) - #define HAS_E4_DIR 1 -#endif -#if PIN_EXISTS(E4_STEP) - #define HAS_E4_STEP 1 -#endif -#if PIN_EXISTS(E4_MS1) - #define HAS_E4_MS_PINS 1 -#endif -#if PIN_EXISTS(SOL4) - #define HAS_SOLENOID_4 1 -#endif + #if PIN_EXISTS(E0_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E0)) + #define HAS_E0_ENABLE 1 + #endif + #if PIN_EXISTS(E0_DIR) + #define HAS_E0_DIR 1 + #endif + #if PIN_EXISTS(E0_STEP) + #define HAS_E0_STEP 1 + #endif + #if PIN_EXISTS(E0_MS1) + #define HAS_E0_MS_PINS 1 + #endif + #if PIN_EXISTS(SOL0) + #define HAS_SOLENOID_0 1 + #endif -#if PIN_EXISTS(E5_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E5)) - #define HAS_E5_ENABLE 1 -#endif -#if PIN_EXISTS(E5_DIR) - #define HAS_E5_DIR 1 -#endif -#if PIN_EXISTS(E5_STEP) - #define HAS_E5_STEP 1 -#endif -#if PIN_EXISTS(E5_MS1) - #define HAS_E5_MS_PINS 1 -#endif -#if PIN_EXISTS(SOL5) - #define HAS_SOLENOID_5 1 -#endif + #if PIN_EXISTS(E1_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E1)) + #define HAS_E1_ENABLE 1 + #endif + #if PIN_EXISTS(E1_DIR) + #define HAS_E1_DIR 1 + #endif + #if PIN_EXISTS(E1_STEP) + #define HAS_E1_STEP 1 + #endif + #if PIN_EXISTS(E1_MS1) + #define HAS_E1_MS_PINS 1 + #endif + #if PIN_EXISTS(SOL1) + #define HAS_SOLENOID_1 1 + #endif -#if PIN_EXISTS(E6_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E6)) - #define HAS_E6_ENABLE 1 -#endif -#if PIN_EXISTS(E6_DIR) - #define HAS_E6_DIR 1 -#endif -#if PIN_EXISTS(E6_STEP) - #define HAS_E6_STEP 1 -#endif -#if PIN_EXISTS(E6_MS1) - #define HAS_E6_MS_PINS 1 -#endif -#if PIN_EXISTS(SOL6) - #define HAS_SOLENOID_6 1 -#endif + #if PIN_EXISTS(E2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E2)) + #define HAS_E2_ENABLE 1 + #endif + #if PIN_EXISTS(E2_DIR) + #define HAS_E2_DIR 1 + #endif + #if PIN_EXISTS(E2_STEP) + #define HAS_E2_STEP 1 + #endif + #if PIN_EXISTS(E2_MS1) + #define HAS_E2_MS_PINS 1 + #endif + #if PIN_EXISTS(SOL2) + #define HAS_SOLENOID_2 1 + #endif -#if PIN_EXISTS(E7_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E7)) - #define HAS_E7_ENABLE 1 -#endif -#if PIN_EXISTS(E7_DIR) - #define HAS_E7_DIR 1 -#endif -#if PIN_EXISTS(E7_STEP) - #define HAS_E7_STEP 1 -#endif -#if PIN_EXISTS(E7_MS1) - #define HAS_E7_MS_PINS 1 -#endif -#if PIN_EXISTS(SOL7) - #define HAS_SOLENOID_7 1 -#endif + #if PIN_EXISTS(E3_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E3)) + #define HAS_E3_ENABLE 1 + #endif + #if PIN_EXISTS(E3_DIR) + #define HAS_E3_DIR 1 + #endif + #if PIN_EXISTS(E3_STEP) + #define HAS_E3_STEP 1 + #endif + #if PIN_EXISTS(E3_MS1) + #define HAS_E3_MS_PINS 1 + #endif + #if PIN_EXISTS(SOL3) + #define HAS_SOLENOID_3 1 + #endif + + #if PIN_EXISTS(E4_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E4)) + #define HAS_E4_ENABLE 1 + #endif + #if PIN_EXISTS(E4_DIR) + #define HAS_E4_DIR 1 + #endif + #if PIN_EXISTS(E4_STEP) + #define HAS_E4_STEP 1 + #endif + #if PIN_EXISTS(E4_MS1) + #define HAS_E4_MS_PINS 1 + #endif + #if PIN_EXISTS(SOL4) + #define HAS_SOLENOID_4 1 + #endif + + #if PIN_EXISTS(E5_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E5)) + #define HAS_E5_ENABLE 1 + #endif + #if PIN_EXISTS(E5_DIR) + #define HAS_E5_DIR 1 + #endif + #if PIN_EXISTS(E5_STEP) + #define HAS_E5_STEP 1 + #endif + #if PIN_EXISTS(E5_MS1) + #define HAS_E5_MS_PINS 1 + #endif + #if PIN_EXISTS(SOL5) + #define HAS_SOLENOID_5 1 + #endif + + #if PIN_EXISTS(E6_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E6)) + #define HAS_E6_ENABLE 1 + #endif + #if PIN_EXISTS(E6_DIR) + #define HAS_E6_DIR 1 + #endif + #if PIN_EXISTS(E6_STEP) + #define HAS_E6_STEP 1 + #endif + #if PIN_EXISTS(E6_MS1) + #define HAS_E6_MS_PINS 1 + #endif + #if PIN_EXISTS(SOL6) + #define HAS_SOLENOID_6 1 + #endif + + #if PIN_EXISTS(E7_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E7)) + #define HAS_E7_ENABLE 1 + #endif + #if PIN_EXISTS(E7_DIR) + #define HAS_E7_DIR 1 + #endif + #if PIN_EXISTS(E7_STEP) + #define HAS_E7_STEP 1 + #endif + #if PIN_EXISTS(E7_MS1) + #define HAS_E7_MS_PINS 1 + #endif + #if PIN_EXISTS(SOL7) + #define HAS_SOLENOID_7 1 + #endif + +#endif // HAS_EXTRUDERS // // Trinamic Stepper Drivers // #if HAS_TRINAMIC_CONFIG - #if ANY(STEALTHCHOP_XY, STEALTHCHOP_Z, STEALTHCHOP_E) + #if ANY(STEALTHCHOP_E, STEALTHCHOP_XY, STEALTHCHOP_Z, STEALTHCHOP_I, STEALTHCHOP_J, STEALTHCHOP_K) #define STEALTHCHOP_ENABLED 1 #endif #if EITHER(SENSORLESS_HOMING, SENSORLESS_PROBING) @@ -1603,10 +2151,211 @@ #if defined(Z4_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z4) #define Z4_SENSORLESS 1 #endif + #if defined(I_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(I) + #define I_SENSORLESS 1 + #endif + #if defined(J_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(J) + #define J_SENSORLESS 1 + #endif + #if defined(K_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(K) + #define K_SENSORLESS 1 + #endif + + #if AXIS_HAS_STEALTHCHOP(X) + #define X_HAS_STEALTHCHOP 1 + #endif + #if AXIS_HAS_STEALTHCHOP(X2) + #define X2_HAS_STEALTHCHOP 1 + #endif + #if AXIS_HAS_STEALTHCHOP(Y) + #define Y_HAS_STEALTHCHOP 1 + #endif + #if AXIS_HAS_STEALTHCHOP(Y2) + #define Y2_HAS_STEALTHCHOP 1 + #endif + #if AXIS_HAS_STEALTHCHOP(Z) + #define Z_HAS_STEALTHCHOP 1 + #endif + #if AXIS_HAS_STEALTHCHOP(Z2) + #define Z2_HAS_STEALTHCHOP 1 + #endif + #if AXIS_HAS_STEALTHCHOP(Z3) + #define Z3_HAS_STEALTHCHOP 1 + #endif + #if AXIS_HAS_STEALTHCHOP(Z4) + #define Z4_HAS_STEALTHCHOP 1 + #endif + #if AXIS_HAS_STEALTHCHOP(I) + #define I_HAS_STEALTHCHOP 1 + #endif + #if AXIS_HAS_STEALTHCHOP(J) + #define J_HAS_STEALTHCHOP 1 + #endif + #if AXIS_HAS_STEALTHCHOP(K) + #define K_HAS_STEALTHCHOP 1 + #endif + #if E_STEPPERS > 0 && AXIS_HAS_STEALTHCHOP(E0) + #define E0_HAS_STEALTHCHOP 1 + #endif + #if E_STEPPERS > 1 && AXIS_HAS_STEALTHCHOP(E1) + #define E1_HAS_STEALTHCHOP 1 + #endif + #if E_STEPPERS > 2 && AXIS_HAS_STEALTHCHOP(E2) + #define E2_HAS_STEALTHCHOP 1 + #endif + #if E_STEPPERS > 3 && AXIS_HAS_STEALTHCHOP(E3) + #define E3_HAS_STEALTHCHOP 1 + #endif + #if E_STEPPERS > 4 && AXIS_HAS_STEALTHCHOP(E4) + #define E4_HAS_STEALTHCHOP 1 + #endif + #if E_STEPPERS > 5 && AXIS_HAS_STEALTHCHOP(E5) + #define E5_HAS_STEALTHCHOP 1 + #endif + #if E_STEPPERS > 6 && AXIS_HAS_STEALTHCHOP(E6) + #define E6_HAS_STEALTHCHOP 1 + #endif + #if E_STEPPERS > 7 && AXIS_HAS_STEALTHCHOP(E7) + #define E7_HAS_STEALTHCHOP 1 + #endif + #if ENABLED(SPI_ENDSTOPS) #define X_SPI_SENSORLESS X_SENSORLESS - #define Y_SPI_SENSORLESS Y_SENSORLESS - #define Z_SPI_SENSORLESS Z_SENSORLESS + #if HAS_Y_AXIS + #define Y_SPI_SENSORLESS Y_SENSORLESS + #endif + #if HAS_Z_AXIS + #define Z_SPI_SENSORLESS Z_SENSORLESS + #endif + #if LINEAR_AXES >= 4 + #define I_SPI_SENSORLESS I_SENSORLESS + #endif + #if LINEAR_AXES >= 5 + #define J_SPI_SENSORLESS J_SENSORLESS + #endif + #if LINEAR_AXES >= 6 + #define K_SPI_SENSORLESS K_SENSORLESS + #endif + #endif + #ifndef X_INTERPOLATE + #define X_INTERPOLATE INTERPOLATE + #endif + #ifndef X2_INTERPOLATE + #define X2_INTERPOLATE INTERPOLATE + #endif + #ifndef Y_INTERPOLATE + #define Y_INTERPOLATE INTERPOLATE + #endif + #ifndef Y2_INTERPOLATE + #define Y2_INTERPOLATE INTERPOLATE + #endif + #ifndef Z_INTERPOLATE + #define Z_INTERPOLATE INTERPOLATE + #endif + #ifndef Z2_INTERPOLATE + #define Z2_INTERPOLATE INTERPOLATE + #endif + #ifndef Z3_INTERPOLATE + #define Z3_INTERPOLATE INTERPOLATE + #endif + #ifndef Z4_INTERPOLATE + #define Z4_INTERPOLATE INTERPOLATE + #endif + #if LINEAR_AXES >= 4 + #ifndef I_INTERPOLATE + #define I_INTERPOLATE INTERPOLATE + #endif + #endif + #if LINEAR_AXES >= 5 + #ifndef J_INTERPOLATE + #define J_INTERPOLATE INTERPOLATE + #endif + #endif + #if LINEAR_AXES >= 6 + #ifndef K_INTERPOLATE + #define K_INTERPOLATE INTERPOLATE + #endif + #endif + #ifndef E0_INTERPOLATE + #define E0_INTERPOLATE INTERPOLATE + #endif + #ifndef E1_INTERPOLATE + #define E1_INTERPOLATE INTERPOLATE + #endif + #ifndef E2_INTERPOLATE + #define E2_INTERPOLATE INTERPOLATE + #endif + #ifndef E3_INTERPOLATE + #define E3_INTERPOLATE INTERPOLATE + #endif + #ifndef E4_INTERPOLATE + #define E4_INTERPOLATE INTERPOLATE + #endif + #ifndef E5_INTERPOLATE + #define E5_INTERPOLATE INTERPOLATE + #endif + #ifndef E6_INTERPOLATE + #define E6_INTERPOLATE INTERPOLATE + #endif + #ifndef E7_INTERPOLATE + #define E7_INTERPOLATE INTERPOLATE + #endif + #ifndef X_SLAVE_ADDRESS + #define X_SLAVE_ADDRESS 0 + #endif + #ifndef Y_SLAVE_ADDRESS + #define Y_SLAVE_ADDRESS 0 + #endif + #ifndef Z_SLAVE_ADDRESS + #define Z_SLAVE_ADDRESS 0 + #endif + #ifndef I_SLAVE_ADDRESS + #define I_SLAVE_ADDRESS 0 + #endif + #ifndef J_SLAVE_ADDRESS + #define J_SLAVE_ADDRESS 0 + #endif + #ifndef K_SLAVE_ADDRESS + #define K_SLAVE_ADDRESS 0 + #endif + #ifndef X2_SLAVE_ADDRESS + #define X2_SLAVE_ADDRESS 0 + #endif + #ifndef Y2_SLAVE_ADDRESS + #define Y2_SLAVE_ADDRESS 0 + #endif + #ifndef Z2_SLAVE_ADDRESS + #define Z2_SLAVE_ADDRESS 0 + #endif + #ifndef Z3_SLAVE_ADDRESS + #define Z3_SLAVE_ADDRESS 0 + #endif + #ifndef Z4_SLAVE_ADDRESS + #define Z4_SLAVE_ADDRESS 0 + #endif + #ifndef E0_SLAVE_ADDRESS + #define E0_SLAVE_ADDRESS 0 + #endif + #ifndef E1_SLAVE_ADDRESS + #define E1_SLAVE_ADDRESS 0 + #endif + #ifndef E2_SLAVE_ADDRESS + #define E2_SLAVE_ADDRESS 0 + #endif + #ifndef E3_SLAVE_ADDRESS + #define E3_SLAVE_ADDRESS 0 + #endif + #ifndef E4_SLAVE_ADDRESS + #define E4_SLAVE_ADDRESS 0 + #endif + #ifndef E5_SLAVE_ADDRESS + #define E5_SLAVE_ADDRESS 0 + #endif + #ifndef E6_SLAVE_ADDRESS + #define E6_SLAVE_ADDRESS 0 + #endif + #ifndef E7_SLAVE_ADDRESS + #define E7_SLAVE_ADDRESS 0 #endif #endif @@ -1623,12 +2372,116 @@ #define HAS_TMC_SW_SERIAL 1 #endif +#if !USE_SENSORLESS + #undef SENSORLESS_BACKOFF_MM +#endif + +// +// Set USING_HW_SERIALn flags for used Serial Ports +// + +// Flag the indexed hardware serial ports in use +#define CONF_SERIAL_IS(N) ( (defined(SERIAL_PORT) && SERIAL_PORT == N) \ + || (defined(SERIAL_PORT_2) && SERIAL_PORT_2 == N) \ + || (defined(SERIAL_PORT_3) && SERIAL_PORT_3 == N) \ + || (defined(MMU2_SERIAL_PORT) && MMU2_SERIAL_PORT == N) \ + || (defined(LCD_SERIAL_PORT) && LCD_SERIAL_PORT == N) ) + +// Flag the named hardware serial ports in use +#define TMC_UART_IS(A,N) (defined(A##_HARDWARE_SERIAL) && (CAT(HW_,A##_HARDWARE_SERIAL) == HW_Serial##N || CAT(HW_,A##_HARDWARE_SERIAL) == HW_MSerial##N)) +#define ANY_SERIAL_IS(N) ( CONF_SERIAL_IS(N) \ + || TMC_UART_IS(X, N) || TMC_UART_IS(Y , N) || TMC_UART_IS(Z , N) \ + || TMC_UART_IS(X2, N) || TMC_UART_IS(Y2, N) || TMC_UART_IS(Z2, N) || TMC_UART_IS(Z3, N) || TMC_UART_IS(Z4, N) \ + || TMC_UART_IS(E0, N) || TMC_UART_IS(E1, N) || TMC_UART_IS(E2, N) || TMC_UART_IS(E3, N) || TMC_UART_IS(E4, N) ) + +#define HW_Serial 501 +#define HW_Serial0 502 +#define HW_Serial1 503 +#define HW_Serial2 504 +#define HW_Serial3 505 +#define HW_Serial4 506 +#define HW_Serial5 507 +#define HW_Serial6 508 +#define HW_MSerial0 509 +#define HW_MSerial1 510 +#define HW_MSerial2 511 +#define HW_MSerial3 512 +#define HW_MSerial4 513 +#define HW_MSerial5 514 +#define HW_MSerial6 515 +#define HW_MSerial7 516 +#define HW_MSerial8 517 +#define HW_MSerial9 518 +#define HW_MSerial10 519 + +#if CONF_SERIAL_IS(-1) + #define USING_HW_SERIALUSB 1 +#endif +#if ANY_SERIAL_IS(0) + #define USING_HW_SERIAL0 1 +#endif +#if ANY_SERIAL_IS(1) + #define USING_HW_SERIAL1 1 +#endif +#if ANY_SERIAL_IS(2) + #define USING_HW_SERIAL2 1 +#endif +#if ANY_SERIAL_IS(3) + #define USING_HW_SERIAL3 1 +#endif +#if ANY_SERIAL_IS(4) + #define USING_HW_SERIAL4 1 +#endif +#if ANY_SERIAL_IS(5) + #define USING_HW_SERIAL5 1 +#endif +#if ANY_SERIAL_IS(6) + #define USING_HW_SERIAL6 1 +#endif +#if ANY_SERIAL_IS(7) + #define USING_HW_SERIAL7 1 +#endif +#if ANY_SERIAL_IS(8) + #define USING_HW_SERIAL8 1 +#endif +#if ANY_SERIAL_IS(9) + #define USING_HW_SERIAL9 1 +#endif +#if ANY_SERIAL_IS(10) + #define USING_HW_SERIAL10 1 +#endif + +#undef HW_Serial +#undef HW_Serial0 +#undef HW_Serial1 +#undef HW_Serial2 +#undef HW_Serial3 +#undef HW_Serial4 +#undef HW_Serial5 +#undef HW_Serial6 +#undef HW_MSerial0 +#undef HW_MSerial1 +#undef HW_MSerial2 +#undef HW_MSerial3 +#undef HW_MSerial4 +#undef HW_MSerial5 +#undef HW_MSerial6 +#undef HW_MSerial7 +#undef HW_MSerial8 +#undef HW_MSerial9 +#undef HW_MSerial10 + +#undef _SERIAL_ID +#undef _TMC_UART_IS +#undef TMC_UART_IS +#undef ANY_SERIAL_IS + // // Endstops and bed probe // // Is an endstop plug used for extra Z endstops or the probe? -#define IS_PROBE_PIN(A,M) (HAS_CUSTOM_PROBE_PIN && Z_MIN_PROBE_PIN == A##_##M##_PIN) +#define IS_PROBE_PIN(A,M) (USES_Z_MIN_PROBE_PIN && Z_MIN_PROBE_PIN == A##_##M##_PIN) #define IS_X2_ENDSTOP(A,M) (ENABLED(X_DUAL_ENDSTOPS) && X2_USE_ENDSTOP == _##A##M##_) #define IS_Y2_ENDSTOP(A,M) (ENABLED(Y_DUAL_ENDSTOPS) && Y2_USE_ENDSTOP == _##A##M##_) #define IS_Z2_ENDSTOP(A,M) (ENABLED(Z_MULTI_ENDSTOPS) && Z2_USE_ENDSTOP == _##A##M##_) @@ -1654,14 +2507,23 @@ #if _HAS_STOP(Z,MAX) #define HAS_Z_MAX 1 #endif -#if _HAS_STOP(X,STOP) - #define HAS_X_STOP 1 +#if _HAS_STOP(I,MIN) + #define HAS_I_MIN 1 #endif -#if _HAS_STOP(Y,STOP) - #define HAS_Y_STOP 1 +#if _HAS_STOP(I,MAX) + #define HAS_I_MAX 1 #endif -#if _HAS_STOP(Z,STOP) - #define HAS_Z_STOP 1 +#if _HAS_STOP(J,MIN) + #define HAS_J_MIN 1 +#endif +#if _HAS_STOP(J,MAX) + #define HAS_J_MAX 1 +#endif +#if _HAS_STOP(K,MIN) + #define HAS_K_MIN 1 +#endif +#if _HAS_STOP(K,MAX) + #define HAS_K_MAX 1 #endif #if PIN_EXISTS(X2_MIN) #define HAS_X2_MIN 1 @@ -1693,14 +2555,23 @@ #if PIN_EXISTS(Z4_MAX) #define HAS_Z4_MAX 1 #endif -#if HAS_CUSTOM_PROBE_PIN && PIN_EXISTS(Z_MIN_PROBE) + +#if HAS_BED_PROBE && PIN_EXISTS(Z_MIN_PROBE) #define HAS_Z_MIN_PROBE_PIN 1 #endif +#undef _HAS_STOP +#undef IS_PROBE_PIN +#undef IS_X2_ENDSTOP +#undef IS_Y2_ENDSTOP +#undef IS_Z2_ENDSTOP +#undef IS_Z3_ENDSTOP +#undef IS_Z4_ENDSTOP + // // ADC Temp Sensors (Thermistor or Thermocouple with amplifier ADC interface) // -#define HAS_ADC_TEST(P) (PIN_EXISTS(TEMP_##P) && TEMP_SENSOR_##P != 0 && DISABLED(HEATER_##P##_USES_MAX6675)) +#define HAS_ADC_TEST(P) (PIN_EXISTS(TEMP_##P) && TEMP_SENSOR_##P != 0 && NONE(TEMP_SENSOR_##P##_IS_MAX_TC, TEMP_SENSOR_##P##_IS_DUMMY)) #if HAS_ADC_TEST(0) #define HAS_TEMP_ADC_0 1 #endif @@ -1734,13 +2605,32 @@ #if HAS_ADC_TEST(CHAMBER) #define HAS_TEMP_ADC_CHAMBER 1 #endif +#if HAS_ADC_TEST(COOLER) + #define HAS_TEMP_ADC_COOLER 1 +#endif +#if HAS_ADC_TEST(REDUNDANT) + #define HAS_TEMP_ADC_REDUNDANT 1 +#endif -#if HAS_HOTEND && EITHER(HAS_TEMP_ADC_0, HEATER_0_USES_MAX6675) +#define HAS_TEMP(N) ANY(HAS_TEMP_ADC_##N, TEMP_SENSOR_##N##_IS_MAX_TC, TEMP_SENSOR_##N##_IS_DUMMY) +#if HAS_HOTEND && HAS_TEMP(0) #define HAS_TEMP_HOTEND 1 #endif -#define HAS_TEMP_BED HAS_TEMP_ADC_BED -#define HAS_TEMP_PROBE HAS_TEMP_ADC_PROBE -#define HAS_TEMP_CHAMBER HAS_TEMP_ADC_CHAMBER +#if HAS_TEMP(BED) + #define HAS_TEMP_BED 1 +#endif +#if HAS_TEMP(PROBE) + #define HAS_TEMP_PROBE 1 +#endif +#if HAS_TEMP(CHAMBER) + #define HAS_TEMP_CHAMBER 1 +#endif +#if HAS_TEMP(COOLER) + #define HAS_TEMP_COOLER 1 +#endif +#if HAS_TEMP(REDUNDANT) + #define HAS_TEMP_REDUNDANT 1 +#endif #if ENABLED(JOYSTICK) #if PIN_EXISTS(JOY_X) @@ -1793,27 +2683,40 @@ #define BED_OVERSHOOT 10 #endif #define BED_MAX_TARGET (BED_MAXTEMP - (BED_OVERSHOOT)) +#else + #undef PIDTEMPBED +#endif + +#if HAS_TEMP_COOLER && PIN_EXISTS(COOLER) + #define HAS_COOLER 1 + #ifndef COOLER_OVERSHOOT + #define COOLER_OVERSHOOT 2 + #endif + #define COOLER_MIN_TARGET (COOLER_MINTEMP + (COOLER_OVERSHOOT)) + #define COOLER_MAX_TARGET (COOLER_MAXTEMP - (COOLER_OVERSHOOT)) #endif + #if HAS_HEATED_BED || HAS_TEMP_CHAMBER #define BED_OR_CHAMBER 1 #endif -#if HAS_TEMP_HOTEND || BED_OR_CHAMBER || HAS_TEMP_PROBE +#if HAS_TEMP_HOTEND || BED_OR_CHAMBER || HAS_TEMP_PROBE || HAS_TEMP_COOLER #define HAS_TEMP_SENSOR 1 #endif + #if HAS_TEMP_CHAMBER && PIN_EXISTS(HEATER_CHAMBER) #define HAS_HEATED_CHAMBER 1 + #ifndef CHAMBER_OVERSHOOT + #define CHAMBER_OVERSHOOT 10 + #endif + #define CHAMBER_MAX_TARGET (CHAMBER_MAXTEMP - (CHAMBER_OVERSHOOT)) +#else + #undef PIDTEMPCHAMBER #endif // PID heating -#if !HAS_HEATED_BED - #undef PIDTEMPBED -#endif -#if EITHER(PIDTEMP, PIDTEMPBED) +#if ANY(PIDTEMP, PIDTEMPBED, PIDTEMPCHAMBER) #define HAS_PID_HEATING 1 #endif -#if BOTH(PIDTEMP, PIDTEMPBED) - #define HAS_PID_FOR_BOTH 1 -#endif // Thermal protection #if BOTH(HAS_HEATED_BED, THERMAL_PROTECTION_BED) @@ -1828,9 +2731,13 @@ #if BOTH(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 + #define WATCH_COOLER 1 +#endif #if (ENABLED(THERMAL_PROTECTION_HOTENDS) || !EXTRUDERS) \ && (ENABLED(THERMAL_PROTECTION_BED) || !HAS_HEATED_BED) \ - && (ENABLED(THERMAL_PROTECTION_CHAMBER) || !HAS_HEATED_CHAMBER) + && (ENABLED(THERMAL_PROTECTION_CHAMBER) || !HAS_HEATED_CHAMBER) \ + && (ENABLED(THERMAL_PROTECTION_COOLER) || !HAS_COOLER) #define THERMALLY_SAFE 1 #endif @@ -1862,8 +2769,11 @@ #if HAS_TEMP_CHAMBER && PIN_EXISTS(CHAMBER_AUTO_FAN) #define HAS_AUTO_CHAMBER_FAN 1 #endif +#if HAS_TEMP_COOLER && PIN_EXISTS(COOLER_AUTO_FAN) + #define HAS_AUTO_COOLER_FAN 1 +#endif -#if ANY(HAS_AUTO_FAN_0, HAS_AUTO_FAN_1, HAS_AUTO_FAN_2, HAS_AUTO_FAN_3, HAS_AUTO_FAN_4, HAS_AUTO_FAN_5, HAS_AUTO_FAN_6, HAS_AUTO_FAN_7, HAS_AUTO_CHAMBER_FAN) +#if ANY(HAS_AUTO_FAN_0, HAS_AUTO_FAN_1, HAS_AUTO_FAN_2, HAS_AUTO_FAN_3, HAS_AUTO_FAN_4, HAS_AUTO_FAN_5, HAS_AUTO_FAN_6, HAS_AUTO_FAN_7, HAS_AUTO_CHAMBER_FAN, HAS_AUTO_COOLER_FAN) #define HAS_AUTO_FAN 1 #endif #define _FANOVERLAP(A,B) (A##_AUTO_FAN_PIN == E##B##_AUTO_FAN_PIN) @@ -1874,7 +2784,7 @@ #if !HAS_TEMP_SENSOR #undef AUTO_REPORT_TEMPERATURES #endif -#if EITHER(AUTO_REPORT_TEMPERATURES, AUTO_REPORT_SD_STATUS) +#if ANY(AUTO_REPORT_TEMPERATURES, AUTO_REPORT_SD_STATUS, AUTO_REPORT_POSITION) #define HAS_AUTO_REPORTING 1 #endif @@ -1935,6 +2845,77 @@ #define BED_OR_CHAMBER_OR_FAN 1 #endif +/** + * Up to 3 PWM fans + */ +#ifndef FAN_INVERTING + #define FAN_INVERTING false +#endif + +#if HAS_FAN7 + #define FAN_COUNT 8 +#elif HAS_FAN6 + #define FAN_COUNT 7 +#elif HAS_FAN5 + #define FAN_COUNT 6 +#elif HAS_FAN4 + #define FAN_COUNT 5 +#elif HAS_FAN3 + #define FAN_COUNT 4 +#elif HAS_FAN2 + #define FAN_COUNT 3 +#elif HAS_FAN1 + #define FAN_COUNT 2 +#elif HAS_FAN0 + #define FAN_COUNT 1 +#else + #define FAN_COUNT 0 +#endif + +#if FAN_COUNT > 0 + #define HAS_FAN 1 +#endif + +/** + * Part Cooling fan multipliexer + */ +#if PIN_EXISTS(FANMUX0) + #define HAS_FANMUX 1 +#endif + +/** + * MIN/MAX fan PWM scaling + */ +#ifndef FAN_OFF_PWM + #define FAN_OFF_PWM 0 +#endif +#ifndef FAN_MIN_PWM + #if FAN_OFF_PWM > 0 + #define FAN_MIN_PWM (FAN_OFF_PWM + 1) + #else + #define FAN_MIN_PWM 0 + #endif +#endif +#ifndef FAN_MAX_PWM + #define FAN_MAX_PWM 255 +#endif +#if FAN_MIN_PWM < 0 || FAN_MIN_PWM > 255 + #error "FAN_MIN_PWM must be a value from 0 to 255." +#elif FAN_MAX_PWM < 0 || FAN_MAX_PWM > 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 + +/** + * FAST PWM FAN Settings + */ +#if ENABLED(FAST_PWM_FAN) && !defined(FAST_PWM_FAN_FREQUENCY) + #define FAST_PWM_FAN_FREQUENCY ((F_CPU) / (2 * 255 * 1)) // Fan frequency default +#endif + // Servos #if PIN_EXISTS(SERVO0) && NUM_SERVOS > 0 #define HAS_SERVO_0 1 @@ -1951,6 +2932,9 @@ #if NUM_SERVOS > 0 #define HAS_SERVOS 1 #endif +#if HAS_SERVOS && defined(PAUSE_SERVO_OUTPUT) && defined(RESUME_SERVO_OUTPUT) + #define HAS_PAUSE_SERVO_OUTPUT 1 +#endif // Sensors #if PIN_EXISTS(FILWIDTH) @@ -1958,12 +2942,22 @@ #endif // User Interface -#if PIN_EXISTS(HOME) - #define HAS_HOME 1 +#if ENABLED(FREEZE_FEATURE) + #if !PIN_EXISTS(FREEZE) && PIN_EXISTS(KILL) + #define FREEZE_PIN KILL_PIN + #endif + #if PIN_EXISTS(FREEZE) + #define HAS_FREEZE_PIN 1 + #endif +#else + #undef FREEZE_PIN #endif -#if PIN_EXISTS(KILL) +#if PIN_EXISTS(KILL) && TERN1(FREEZE_FEATURE, KILL_PIN != FREEZE_PIN) #define HAS_KILL 1 #endif +#if PIN_EXISTS(HOME) + #define HAS_HOME 1 +#endif #if PIN_EXISTS(SUICIDE) #define HAS_SUICIDE 1 #endif @@ -1978,7 +2972,10 @@ #if PIN_EXISTS(DIGIPOTSS) #define HAS_MOTOR_CURRENT_SPI 1 #endif -#if ANY_PIN(MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y, MOTOR_CURRENT_PWM_XY, MOTOR_CURRENT_PWM_Z, MOTOR_CURRENT_PWM_E) +#if HAS_EXTRUDERS && PIN_EXISTS(MOTOR_CURRENT_PWM_E) + #define HAS_MOTOR_CURRENT_PWM_E 1 +#endif +#if HAS_MOTOR_CURRENT_PWM_E || ANY_PIN(MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y, MOTOR_CURRENT_PWM_XY, MOTOR_CURRENT_PWM_Z) #define HAS_MOTOR_CURRENT_PWM 1 #endif @@ -1988,7 +2985,7 @@ #if ANY(HAS_E0_MS_PINS, HAS_E1_MS_PINS, HAS_E2_MS_PINS, HAS_E3_MS_PINS, HAS_E4_MS_PINS, HAS_E5_MS_PINS, HAS_E6_MS_PINS, HAS_E7_MS_PINS) #define HAS_SOME_E_MS_PINS 1 #endif -#if ANY(HAS_X_MS_PINS, HAS_X2_MS_PINS, HAS_Y_MS_PINS, HAS_Y2_MS_PINS, HAS_SOME_Z_MS_PINS, HAS_SOME_E_MS_PINS) +#if ANY(HAS_X_MS_PINS, HAS_X2_MS_PINS, HAS_Y_MS_PINS, HAS_Y2_MS_PINS, HAS_SOME_Z_MS_PINS, HAS_I_MS_PINS, HAS_J_MS_PINS, HAS_K_MS_PINS, HAS_SOME_E_MS_PINS) #define HAS_MICROSTEPS 1 #endif @@ -2144,6 +3141,9 @@ * Heated chamber requires settings */ #if HAS_HEATED_CHAMBER + #ifndef MIN_CHAMBER_POWER + #define MIN_CHAMBER_POWER 0 + #endif #ifndef MAX_CHAMBER_POWER #define MAX_CHAMBER_POWER 255 #endif @@ -2153,12 +3153,27 @@ #define WRITE_HEATER_CHAMBER(v) WRITE(HEATER_CHAMBER_PIN, (v) ^ HEATER_CHAMBER_INVERTING) #endif -#if HAS_HOTEND || HAS_HEATED_BED || HAS_HEATED_CHAMBER +/** + * Laser Cooling requires settings + */ +#if HAS_COOLER + #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) +#endif + +#if HAS_HOTEND || HAS_HEATED_BED || HAS_HEATED_CHAMBER || HAS_COOLER #define HAS_TEMPERATURE 1 #endif #if HAS_TEMPERATURE && EITHER(HAS_LCD_MENU, DWIN_CREALITY_LCD) - #ifdef PREHEAT_5_LABEL + #ifdef PREHEAT_6_LABEL + #define PREHEAT_COUNT 6 + #elif defined(PREHEAT_5_LABEL) #define PREHEAT_COUNT 5 #elif defined(PREHEAT_4_LABEL) #define PREHEAT_COUNT 4 @@ -2171,76 +3186,8 @@ #endif #endif -/** - * Up to 3 PWM fans - */ -#ifndef FAN_INVERTING - #define FAN_INVERTING false -#endif - -#if HAS_FAN7 - #define FAN_COUNT 8 -#elif HAS_FAN6 - #define FAN_COUNT 7 -#elif HAS_FAN5 - #define FAN_COUNT 6 -#elif HAS_FAN4 - #define FAN_COUNT 5 -#elif HAS_FAN3 - #define FAN_COUNT 4 -#elif HAS_FAN2 - #define FAN_COUNT 3 -#elif HAS_FAN1 - #define FAN_COUNT 2 -#elif HAS_FAN0 - #define FAN_COUNT 1 -#else - #define FAN_COUNT 0 -#endif - -#if FAN_COUNT > 0 - #define HAS_FAN 1 - #define WRITE_FAN(n, v) WRITE(FAN##n##_PIN, (v) ^ FAN_INVERTING) -#endif - -/** - * Part Cooling fan multipliexer - */ -#if PIN_EXISTS(FANMUX0) - #define HAS_FANMUX 1 -#endif - -/** - * MIN/MAX fan PWM scaling - */ -#ifndef FAN_OFF_PWM - #define FAN_OFF_PWM 0 -#endif -#ifndef FAN_MIN_PWM - #if FAN_OFF_PWM > 0 - #define FAN_MIN_PWM (FAN_OFF_PWM + 1) - #else - #define FAN_MIN_PWM 0 - #endif -#endif -#ifndef FAN_MAX_PWM - #define FAN_MAX_PWM 255 -#endif -#if FAN_MIN_PWM < 0 || FAN_MIN_PWM > 255 - #error "FAN_MIN_PWM must be a value from 0 to 255." -#elif FAN_MAX_PWM < 0 || FAN_MAX_PWM > 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 - -/** - * FAST PWM FAN Settings - */ -#if ENABLED(FAST_PWM_FAN) && !defined(FAST_PWM_FAN_FREQUENCY) - #define FAST_PWM_FAN_FREQUENCY ((F_CPU) / (2 * 255 * 1)) // Fan frequency default +#if !PREHEAT_COUNT + #undef PREHEAT_SHORTCUT_MENU_ITEM #endif /** @@ -2267,18 +3214,15 @@ #ifndef Z_PROBE_OFFSET_RANGE_MAX #define Z_PROBE_OFFSET_RANGE_MAX 20 #endif - #ifndef XY_PROBE_SPEED - #ifdef HOMING_FEEDRATE_XY - #define XY_PROBE_SPEED HOMING_FEEDRATE_XY - #else - #define XY_PROBE_SPEED 4000 - #endif + #ifndef XY_PROBE_FEEDRATE + #define XY_PROBE_FEEDRATE ((homing_feedrate_mm_m.x + homing_feedrate_mm_m.y) / 2) #endif #ifndef NOZZLE_TO_PROBE_OFFSET #define NOZZLE_TO_PROBE_OFFSET { 0, 0, 0 } #endif #else #undef NOZZLE_TO_PROBE_OFFSET + #undef PROBING_STEPPERS_OFF #endif /** @@ -2321,21 +3265,36 @@ /** * Heater, Fan, and Probe interactions */ -#if FAN_COUNT == 0 - #undef PROBING_FANS_OFF +#if !HAS_FAN #undef ADAPTIVE_FAN_SLOWING #undef NO_FAN_SLOWING_IN_PID_TUNING #endif - -#if HAS_BED_PROBE && (EITHER(PROBING_HEATERS_OFF, PROBING_FANS_OFF) || DELAY_BEFORE_PROBING > 0) - #define QUIET_PROBING 1 +#if !BOTH(HAS_BED_PROBE, HAS_FAN) + #undef PROBING_FANS_OFF +#endif +#if !BOTH(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) #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) + #define HAS_QUIET_PROBING 1 +#endif -#if ENABLED(ADVANCED_PAUSE_FEATURE) && !defined(FILAMENT_CHANGE_SLOW_LOAD_LENGTH) - #define FILAMENT_CHANGE_SLOW_LOAD_LENGTH 0 +/** + * Advanced Pause - Filament Change + */ +#if ENABLED(ADVANCED_PAUSE_FEATURE) + #if EITHER(HAS_LCD_MENU, EXTENSIBLE_UI) || BOTH(EMERGENCY_PARSER, HOST_PROMPT_SUPPORT) + #define M600_PURGE_MORE_RESUMABLE 1 + #endif + #ifndef FILAMENT_CHANGE_SLOW_LOAD_LENGTH + #define FILAMENT_CHANGE_SLOW_LOAD_LENGTH 0 + #endif #endif #if HAS_MULTI_EXTRUDER && !defined(TOOLCHANGE_FS_EXTRA_PRIME) @@ -2402,6 +3361,10 @@ #endif #endif +#ifndef DEFAULT_LEVELING_FADE_HEIGHT + #define DEFAULT_LEVELING_FADE_HEIGHT 0.0 +#endif + #if ENABLED(SEGMENT_LEVELED_MOVES) && !defined(LEVELED_SEGMENT_LENGTH) #define LEVELED_SEGMENT_LENGTH 5 #endif @@ -2457,11 +3420,11 @@ /** * Buzzer/Speaker */ -#if PIN_EXISTS(BEEPER) || ANY(LCD_USE_I2C_BUZZER, PCA9632_BUZZER) +#if PIN_EXISTS(BEEPER) + #define USE_BEEPER 1 +#endif +#if USE_BEEPER || ANY(LCD_USE_I2C_BUZZER, PCA9632_BUZZER) #define HAS_BUZZER 1 - #if PIN_EXISTS(BEEPER) - #define USE_BEEPER 1 - #endif #endif #if ENABLED(LCD_USE_I2C_BUZZER) @@ -2480,8 +3443,12 @@ #endif #endif -#if HAS_BUZZER && LCD_FEEDBACK_FREQUENCY_DURATION_MS && LCD_FEEDBACK_FREQUENCY_HZ - #define HAS_CHIRP 1 +#if HAS_BUZZER + #if LCD_FEEDBACK_FREQUENCY_DURATION_MS && LCD_FEEDBACK_FREQUENCY_HZ + #define HAS_CHIRP 1 + #endif +#else + #undef SOUND_MENU_ITEM // No buzzer menu item without a buzzer #endif /** @@ -2489,10 +3456,10 @@ */ #if HAS_MARLINUI_U8GLIB #ifndef DOGLCD_SCK - #define DOGLCD_SCK SCK_PIN + #define DOGLCD_SCK SD_SCK_PIN #endif #ifndef DOGLCD_MOSI - #define DOGLCD_MOSI MOSI_PIN + #define DOGLCD_MOSI SD_MOSI_PIN #endif #endif @@ -2512,9 +3479,9 @@ #define Z_CLEARANCE_BETWEEN_PROBES Z_HOMING_HEIGHT #endif #if Z_CLEARANCE_BETWEEN_PROBES > Z_HOMING_HEIGHT - #define MANUAL_PROBE_HEIGHT Z_CLEARANCE_BETWEEN_PROBES + #define Z_CLEARANCE_BETWEEN_MANUAL_PROBES Z_CLEARANCE_BETWEEN_PROBES #else - #define MANUAL_PROBE_HEIGHT Z_HOMING_HEIGHT + #define Z_CLEARANCE_BETWEEN_MANUAL_PROBES Z_HOMING_HEIGHT #endif #ifndef Z_CLEARANCE_MULTI_PROBE #define Z_CLEARANCE_MULTI_PROBE Z_CLEARANCE_BETWEEN_PROBES @@ -2524,6 +3491,16 @@ #endif #endif +// Define a starting height for measuring manual probe points +#ifndef MANUAL_PROBE_START_Z + #if EITHER(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) + #define MANUAL_PROBE_START_Z Z_CLEARANCE_BETWEEN_PROBES + #endif +#endif + #ifndef __SAM3X8E__ //todo: hal: broken hal encapsulation #undef UI_VOLTAGE_LEVEL #undef RADDS_DISPLAY @@ -2542,14 +3519,19 @@ #endif #endif -// LCD timeout to status screen default is 15s -#ifndef LCD_TIMEOUT_TO_STATUS - #define LCD_TIMEOUT_TO_STATUS 15000 +#if HAS_LCD_MENU + // LCD timeout to status screen default is 15s + #ifndef LCD_TIMEOUT_TO_STATUS + #define LCD_TIMEOUT_TO_STATUS 15000 + #endif + #if LCD_TIMEOUT_TO_STATUS + #define SCREENS_CAN_TIME_OUT 1 + #endif #endif // Add commands that need sub-codes to this list #if ANY(G38_PROBE_TARGET, CNC_COORDINATE_SYSTEMS, POWER_LOSS_RECOVERY) - #define USE_GCODE_SUBCODES + #define USE_GCODE_SUBCODES 1 #endif // Parking Extruder @@ -2578,7 +3560,7 @@ // Force SDCARD_SORT_ALPHA to be enabled for Graphical LCD on LPC1768 // on boards where SD card and LCD display share the same SPI bus // because of a bug in the shared SPI implementation. (See #8122) -#if defined(TARGET_LPC1768) && ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) && (SCK_PIN == LCD_PINS_D4) +#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 @@ -2603,6 +3585,11 @@ #endif #endif +// Fallback SPI Speed for SD +#if ENABLED(SDSUPPORT) && !defined(SD_SPI_SPEED) + #define SD_SPI_SPEED SPI_FULL_SPEED +#endif + // Defined here to catch the above defines #if ENABLED(SDCARD_SORT_ALPHA) && (FOLDER_SORTING || ENABLED(SDSORT_GCODE)) #define HAS_FOLDER_SORTING 1 @@ -2614,14 +3601,14 @@ #if HAS_MARLINUI_U8GLIB #define LCD_WIDTH 21 #else - #define LCD_WIDTH TERN(ULTIPANEL, 20, 16) + #define LCD_WIDTH TERN(IS_ULTIPANEL, 20, 16) #endif #endif #ifndef LCD_HEIGHT #if HAS_MARLINUI_U8GLIB #define LCD_HEIGHT 5 #else - #define LCD_HEIGHT TERN(ULTIPANEL, 4, 2) + #define LCD_HEIGHT TERN(IS_ULTIPANEL, 4, 2) #endif #endif #endif @@ -2630,8 +3617,6 @@ #define HAS_ROTARY_ENCODER 1 #endif -#if !NUM_SERIAL - #undef BAUD_RATE_GCODE -#elif NUM_SERIAL > 1 - #define HAS_MULTI_SERIAL 1 +#if PIN_EXISTS(SAFE_POWER) && DISABLED(DISABLE_DRIVER_SAFE_POWER_PROTECT) + #define HAS_DRIVER_SAFE_POWER_PROTECT 1 #endif diff --git a/Marlin/src/inc/MarlinConfig.h b/Marlin/src/inc/MarlinConfig.h index 2eafa2b4171f..8fdb4b9baeae 100644 --- a/Marlin/src/inc/MarlinConfig.h +++ b/Marlin/src/inc/MarlinConfig.h @@ -55,3 +55,5 @@ #include "../core/serial.h" #endif + +#include "../core/multi_language.h" diff --git a/Marlin/src/inc/MarlinConfigPre.h b/Marlin/src/inc/MarlinConfigPre.h index dfa0adba1bd7..c090b7e37bc4 100644 --- a/Marlin/src/inc/MarlinConfigPre.h +++ b/Marlin/src/inc/MarlinConfigPre.h @@ -34,8 +34,8 @@ #include "../HAL/platforms.h" #endif -#include "../core/boards.h" #include "../core/macros.h" +#include "../core/boards.h" #include "../../Configuration.h" #ifdef CUSTOM_VERSION_FILE diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 2cffde0907f7..ebbfa1748c89 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -34,6 +34,10 @@ #error "Marlin requires C++11 support (gcc >= 4.7, Arduino IDE >= 1.6.8). Please upgrade your toolchain." #endif +// Strings for sanity check messages +#define _LINEAR_AXES_STR LINEAR_AXIS_GANG("X ", "Y ", "Z ", "I ", "J ", "K ") +#define _LOGICAL_AXES_STR LOGICAL_AXIS_GANG("E ", "X ", "Y ", "Z ", "I ", "J ", "K ") + // Make sure macros aren't borked #define TEST1 #define TEST2 1 @@ -60,18 +64,23 @@ #undef TEST4 /** - * We try our best to include sanity checks for all changed configuration - * directives because users have a tendency to use outdated config files with - * the bleeding-edge source code, but sometimes this is not enough. This check - * forces a minimum config file revision. Otherwise Marlin will not build. + * This is to alert you about non-matching versions of config files. + * + * You can edit the version tag in your old config files and try the build again. + * The checks below will alert you about options that need to be changed, but they won't + * tell you about new options that you might find useful. So it's recommended to transfer + * your settings to new Configuration files matching your Marlin version as soon as possible. */ #define HEXIFY(H) _CAT(0x,H) #if !defined(CONFIGURATION_H_VERSION) || HEXIFY(CONFIGURATION_H_VERSION) < HEXIFY(REQUIRED_CONFIGURATION_H_VERSION) - #error "You are using an old Configuration.h file, update it before building Marlin." + #error "Your Configuration.h file is for an old version of Marlin. Downgrade Marlin or upgrade your Configuration.h." +#elif HEXIFY(CONFIGURATION_H_VERSION) > HEXIFY(REQUIRED_CONFIGURATION_H_VERSION) + #error "Your Configuration.h file is for a newer version of Marlin. Upgrade Marlin or downgrade your Configuration.h." #endif - #if !defined(CONFIGURATION_ADV_H_VERSION) || HEXIFY(CONFIGURATION_ADV_H_VERSION) < HEXIFY(REQUIRED_CONFIGURATION_ADV_H_VERSION) - #error "You are using an old Configuration_adv.h file, update it before building Marlin." + #error "Your Configuration_adv.h file is for an old version of Marlin. Downgrade Marlin or upgrade your Configuration_adv.h." +#elif HEXIFY(CONFIGURATION_ADV_H_VERSION) > HEXIFY(REQUIRED_CONFIGURATION_ADV_H_VERSION) + #error "Your Configuration_adv.h file is for a newer version of Marlin. Upgrade Marlin or downgrade your Configuration_adv.h." #endif #undef HEXIFY @@ -79,9 +88,9 @@ * Warnings for old configurations */ #ifndef MOTHERBOARD - #error "MOTHERBOARD is required. Please update your configuration." + #error "MOTHERBOARD is required." #elif !defined(X_BED_SIZE) || !defined(Y_BED_SIZE) - #error "X_BED_SIZE and Y_BED_SIZE are now required! Please update your configuration." + #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)) @@ -93,211 +102,219 @@ #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). Please update your configuration." + #error "SDCARDDETECTINVERTED is now SD_DETECT_STATE (HIGH)." #elif defined(SD_DETECT_INVERTED) - #error "SD_DETECT_INVERTED is now SD_DETECT_STATE (HIGH). Please update your configuration." + #error "SD_DETECT_INVERTED is now SD_DETECT_STATE (HIGH)." #elif defined(BTENABLED) - #error "BTENABLED is now BLUETOOTH. Please update your configuration." + #error "BTENABLED is now BLUETOOTH." #elif defined(CUSTOM_MENDEL_NAME) - #error "CUSTOM_MENDEL_NAME is now CUSTOM_MACHINE_NAME. Please update your configuration." + #error "CUSTOM_MENDEL_NAME is now CUSTOM_MACHINE_NAME." #elif defined(HAS_AUTOMATIC_VERSIONING) - #error "HAS_AUTOMATIC_VERSIONING is now CUSTOM_VERSION_FILE. Please update your configuration." + #error "HAS_AUTOMATIC_VERSIONING is now CUSTOM_VERSION_FILE." #elif defined(USE_AUTOMATIC_VERSIONING) - #error "USE_AUTOMATIC_VERSIONING is now CUSTOM_VERSION_FILE. Please update your configuration." + #error "USE_AUTOMATIC_VERSIONING is now CUSTOM_VERSION_FILE." #elif defined(SDSLOW) - #error "SDSLOW deprecated. Set SPI_SPEED to SPI_HALF_SPEED instead." + #error "SDSLOW deprecated. Set SD_SPI_SPEED to SPI_HALF_SPEED instead." #elif defined(SDEXTRASLOW) - #error "SDEXTRASLOW deprecated. Set SPI_SPEED to SPI_QUARTER_SPEED instead." + #error "SDEXTRASLOW deprecated. Set SD_SPI_SPEED to SPI_QUARTER_SPEED instead." #elif defined(FILAMENT_SENSOR) - #error "FILAMENT_SENSOR is now FILAMENT_WIDTH_SENSOR. Please update your configuration." + #error "FILAMENT_SENSOR is now FILAMENT_WIDTH_SENSOR." #elif defined(ENDSTOPPULLUP_FIL_RUNOUT) - #error "ENDSTOPPULLUP_FIL_RUNOUT is now FIL_RUNOUT_PULLUP. Please update your configuration." + #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. Please update your configuration." + #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. Remove them from your configuration." + #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. Please update your configuration." + #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 deprecated. Use XY_PROBE_SPEED instead." + #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 deprecated. Use SERVO_DELAY instead." + #error "SERVO_DEACTIVATION_DELAY is now SERVO_DELAY." #elif ENABLED(FILAMENTCHANGEENABLE) - #error "FILAMENTCHANGEENABLE is now ADVANCED_PAUSE_FEATURE. Please update your configuration." + #error "FILAMENTCHANGEENABLE is now ADVANCED_PAUSE_FEATURE." #elif ENABLED(FILAMENT_CHANGE_FEATURE) - #error "FILAMENT_CHANGE_FEATURE is now ADVANCED_PAUSE_FEATURE. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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 deprecated. Set individual rates with HOMING_FEEDRATE_(XY|Z|E) instead." + #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. Are you sure you want to use this option? Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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) in Configuration_adv.h. + #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. Please update your Configuration_adv.h." + #error "MIN_STEPS_PER_SEGMENT must be at least 1." #elif defined(PREVENT_DANGEROUS_EXTRUDE) - #error "PREVENT_DANGEROUS_EXTRUDE is now PREVENT_COLD_EXTRUSION. Please update your configuration." + #error "PREVENT_DANGEROUS_EXTRUDE is now PREVENT_COLD_EXTRUSION." #elif defined(SCARA) - #error "SCARA is now MORGAN_SCARA. Please update your configuration." + #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. Please update your configuration." + #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]. Please update your configuration." + #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]. Please update your configuration." + #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]. Please update your configuration." + #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]. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #error "UBL_MESH_EDIT_ENABLED is now G26_MESH_VALIDATION." #elif defined(UBL_MESH_EDITING) - #error "UBL_MESH_EDITING is now G26_MESH_VALIDATION. Please update your configuration." + #error "UBL_MESH_EDITING is now G26_MESH_VALIDATION." #elif defined(BLTOUCH_HEATERS_OFF) - #error "BLTOUCH_HEATERS_OFF is now PROBING_HEATERS_OFF. Please update your configuration." + #error "BLTOUCH_HEATERS_OFF is now PROBING_HEATERS_OFF." #elif defined(BLTOUCH_V3) - #error "BLTOUCH_V3 is obsolete. Please update your configuration." + #error "BLTOUCH_V3 is obsolete." #elif defined(BLTOUCH_FORCE_OPEN_DRAIN_MODE) - #error "BLTOUCH_FORCE_OPEN_DRAIN_MODE is obsolete. Please update your configuration." + #error "BLTOUCH_FORCE_OPEN_DRAIN_MODE is obsolete." #elif defined(BEEPER) - #error "BEEPER is now BEEPER_PIN. Please update your pins definitions." + #error "BEEPER is now BEEPER_PIN." #elif defined(SDCARDDETECT) - #error "SDCARDDETECT is now SD_DETECT_PIN. Please update your pins definitions." + #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. Please update your pins definitions." + #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. Please update your pins definitions." + #error "LCD_PIN_BL is now LCD_BACKLIGHT_PIN." #elif defined(LCD_PIN_RESET) - #error "LCD_PIN_RESET is now LCD_RESET_PIN. Please update your pins definitions." + #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. Please update your Configuration_adv.h." + #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. Please update your configuration." + #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. Please update your Configuration_adv.h." + #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. Please update your Configuration_adv.h." + #error "CONTROLLERFAN_SPEED is now CONTROLLERFAN_SPEED_ACTIVE." #elif defined(CONTROLLERFAN_SECS) - #error "CONTROLLERFAN_SECS is now CONTROLLERFAN_IDLE_TIME. Please update your Configuration_adv.h." + #error "CONTROLLERFAN_SECS is now CONTROLLERFAN_IDLE_TIME." #elif defined(MIN_RETRACT) - #error "MIN_RETRACT is now MIN_AUTORETRACT and MAX_AUTORETRACT. Please update your Configuration_adv.h." + #error "MIN_RETRACT is now MIN_AUTORETRACT and MAX_AUTORETRACT." #elif defined(ADVANCE) - #error "ADVANCE was removed in Marlin 1.1.6. Please use LIN_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. Check your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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]. Please update your configuration." + #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 from Configuration.h." + #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 from Configuration.h." + #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. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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) @@ -307,255 +324,310 @@ #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. Please update your configuration." + #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. Please update your configurations." + #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. Please update your configuration." + #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. Please update your configuration." + #error "K1 is now PID_K1." #elif defined(PROBE_DOUBLE_TOUCH) - #error "PROBE_DOUBLE_TOUCH is now MULTIPLE_PROBING. Please update your configuration." + #error "PROBE_DOUBLE_TOUCH is now MULTIPLE_PROBING." #elif defined(ANET_KEYPAD_LCD) - #error "ANET_KEYPAD_LCD is now ZONESTAR_LCD. Please update your configuration." + #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). Please update your configuration." + #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. Please update your configuration." + #error "MEASURED_(UPPER|LOWER)_LIMIT is now FILWIDTH_ERROR_MARGIN." #elif defined(HAVE_TMCDRIVER) - #error "HAVE_TMCDRIVER is now [AXIS]_DRIVER_TYPE TMC26X. Please update your Configuration.h." + #error "HAVE_TMCDRIVER is now [AXIS]_DRIVER_TYPE TMC26X." #elif defined(STEALTHCHOP) - #error "STEALTHCHOP is now STEALTHCHOP_(XY|Z|E). Please update your Configuration_adv.h." + #error "STEALTHCHOP is now STEALTHCHOP_(XY|Z|E)." #elif defined(HAVE_TMC26X) - #error "HAVE_TMC26X is now [AXIS]_DRIVER_TYPE TMC26X. Please update your Configuration.h." + #error "HAVE_TMC26X is now [AXIS]_DRIVER_TYPE TMC26X." #elif defined(HAVE_TMC2130) - #error "HAVE_TMC2130 is now [AXIS]_DRIVER_TYPE TMC2130. Please update your Configuration.h." + #error "HAVE_TMC2130 is now [AXIS]_DRIVER_TYPE TMC2130." #elif defined(HAVE_TMC2208) - #error "HAVE_TMC2208 is now [AXIS]_DRIVER_TYPE TMC2208. Please update your Configuration.h." + #error "HAVE_TMC2208 is now [AXIS]_DRIVER_TYPE TMC2208." #elif defined(HAVE_L6470DRIVER) - #error "HAVE_L6470DRIVER is now [AXIS]_DRIVER_TYPE L6470. Please update your Configuration.h." + #error "HAVE_L6470DRIVER is now [AXIS]_DRIVER_TYPE L6470." #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. Please update your Configuration.h." + #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. Please update your Configuration.h." + #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. Please update your Configuration.h." + #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. Please update your Configuration.h." + #error "[AXIS]_IS_TMC2208 is now [AXIS]_DRIVER_TYPE TMC2208." #elif defined(X_IS_L6470) || defined(X2_IS_L6470) || defined(Y_IS_L6470) || defined(Y2_IS_L6470) || defined(Z_IS_L6470) || defined(Z2_IS_L6470) || defined(Z3_IS_L6470) \ || defined(E0_IS_L6470) || defined(E1_IS_L6470) || defined(E2_IS_L6470) || defined(E3_IS_L6470) || defined(E4_IS_L6470) || defined(E5_IS_L6470) || defined(E6_IS_L6470) || defined(E7_IS_L6470) - #error "[AXIS]_IS_L6470 is now [AXIS]_DRIVER_TYPE L6470. Please update your Configuration.h." + #error "[AXIS]_IS_L6470 is now [AXIS]_DRIVER_TYPE L6470." #elif defined(AUTOMATIC_CURRENT_CONTROL) - #error "AUTOMATIC_CURRENT_CONTROL is now MONITOR_DRIVER_STATUS. Please update your configuration." + #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. Please update your configuration." + #error "FILAMENT_CHANGE_LOAD_LENGTH is now FILAMENT_CHANGE_FAST_LOAD_LENGTH." #elif defined(LEVEL_CORNERS_INSET) - #error "LEVEL_CORNERS_INSET is now LEVEL_CORNERS_INSET_LFRB . Please update your Configuration.h." -#elif ENABLED(LEVEL_BED_CORNERS) && !defined(LEVEL_CORNERS_INSET_LFRB) - #error "LEVEL_BED_CORNERS requires LEVEL_CORNERS_INSET_LFRB values. Please update your Configuration.h." + #error "LEVEL_CORNERS_INSET is now LEVEL_CORNERS_INSET_LFRB." #elif defined(BEZIER_JERK_CONTROL) - #error "BEZIER_JERK_CONTROL is now S_CURVE_ACCELERATION. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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]. Please update your configuration." + #error "ENDSTOP_NOISE_FILTER is now ENDSTOP_NOISE_THRESHOLD [2-7]." #elif defined(RETRACT_ZLIFT) - #error "RETRACT_ZLIFT is now RETRACT_ZRAISE. Please update your Configuration_adv.h." + #error "RETRACT_ZLIFT is now RETRACT_ZRAISE." #elif defined(TOOLCHANGE_PARK_ZLIFT) || defined(TOOLCHANGE_UNPARK_ZLIFT) - #error "TOOLCHANGE_PARK_ZLIFT and TOOLCHANGE_UNPARK_ZLIFT are now TOOLCHANGE_ZRAISE. Please update your configuration." + #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. Please update your configuration." + #error "SINGLENOZZLE_TOOLCHANGE_ZRAISE is now TOOLCHANGE_ZRAISE." #elif defined(SINGLENOZZLE_SWAP_LENGTH) - #error "SINGLENOZZLE_SWAP_LENGTH is now TOOLCHANGE_FIL_SWAP_LENGTH. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #error "SINGLENOZZLE_SWAP_PARK is now TOOLCHANGE_PARK." #elif defined(SINGLENOZZLE_TOOLCHANGE_XY) - #error "SINGLENOZZLE_TOOLCHANGE_XY is now TOOLCHANGE_PARK_XY. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #error "PARKING_EXTRUDER_SECURITY_RAISE is now TOOLCHANGE_ZRAISE." #elif defined(SWITCHING_TOOLHEAD_SECURITY_RAISE) - #error "SWITCHING_TOOLHEAD_SECURITY_RAISE is now TOOLCHANGE_ZRAISE. Please update your configuration." + #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. Please update your configuration." + #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. Please update your configuration." + #error "MBL_Z_STEP is now MESH_EDIT_Z_STEP." #elif defined(CHDK) - #error "CHDK is now CHDK_PIN. Please update your Configuration_adv.h." -#elif defined(MAX6675_SS) - #error "MAX6675_SS is now MAX6675_SS_PIN. Please update your configuration and/or pins." -#elif defined(MAX6675_SS2) - #error "MAX6675_SS2 is now MAX6675_SS2_PIN. Please update your configuration and/or pins." + #error "CHDK is now CHDK_PIN." +#elif ANY_PIN( \ + MAX6675_SS, MAX6675_SS2, MAX6675_CS, MAX6675_CS2, \ + MAX31855_SS, MAX31855_SS2, MAX31855_CS, MAX31855_CS2, \ + MAX31865_SS, MAX31865_SS2, MAX31865_CS, MAX31865_CS2) + #warning "MAX*_SS_PIN, MAX*_SS2_PIN, MAX*_CS_PIN, and MAX*_CS2_PIN are deprecated and will be removed in a future version. Please use TEMP_0_CS_PIN/TEMP_1_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 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 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 instead." +#elif ANY_PIN(THERMO_CS1_PIN, THERMO_CS2_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. Please update your Configuration_adv.h." + #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. Please update your Configuration_adv.h and/or pins." + #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. Please update your Configuration_adv.h." + #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. Please update your Configuration_adv.h." + #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. Please update your Configuration_adv.h." + #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. Please update your Configuration_adv.h." + #error "SPINDLE_LASER_ENABLE_INVERT is now SPINDLE_LASER_ACTIVE_STATE." #elif defined(CUTTER_POWER_DISPLAY) - #error "CUTTER_POWER_DISPLAY is now CUTTER_POWER_UNIT. Please update your Configuration_adv.h." + #error "CUTTER_POWER_DISPLAY is now CUTTER_POWER_UNIT." #elif defined(CHAMBER_HEATER_PIN) - #error "CHAMBER_HEATER_PIN is now HEATER_CHAMBER_PIN. Please update your configuration and/or pins." + #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. Please update your configuration." + #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 from Configuration.h." + #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. Please update your configuration." + #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. Please update your configuration." + #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. Please update your Configuration_adv.h." + #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. Please update your Configuration_adv.h." + #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. Please update your Configuration_adv.h." + #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. Please update your configuration." + #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 from Configuration.h." + #error "POWER_SUPPLY is now obsolete. Please remove it." #elif defined(MKS_ROBIN_TFT) - #error "MKS_ROBIN_TFT is now FSMC_GRAPHICAL_TFT. Please update your configuration." + #error "MKS_ROBIN_TFT is now FSMC_GRAPHICAL_TFT." #elif defined(SDPOWER) - #error "SDPOWER is now SDPOWER_PIN. Please update your configuration and/or pins." + #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 from Configuration.h." + #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. Please update your configuration." + #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. Please update your configuration." + #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 from Configuration.h." + #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. Please update your Configuration_adv.h." + #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 from Configuration.h." + #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]. Please update Configuration_adv.h." + #error "BABYSTEP_MULTIPLICATOR is now BABYSTEP_MULTIPLICATOR_[XY|Z]." #elif defined(LULZBOT_TOUCH_UI) - #error "LULZBOT_TOUCH_UI is now TOUCH_UI_FTDI_EVE. Please update your configuration." + #error "LULZBOT_TOUCH_UI is now TOUCH_UI_FTDI_EVE." #elif defined(PS_DEFAULT_OFF) - #error "PS_DEFAULT_OFF is now PSU_DEFAULT_OFF. Please update your configuration." + #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. Please update Configuration_adv.h." + #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. Please update Configuration_adv.h." + #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 from Configuration_adv.h." + #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). Please update your configuration." + #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. Please update your configuration." + #error "DGUS_SERIAL_PORT is now LCD_SERIAL_PORT." #elif defined(DGUS_BAUDRATE) - #error "DGUS_BAUDRATE is now LCD_BAUDRATE. Please update your configuration." + #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. Please update your configuration." -#elif defined(DGUS_SERIAL_PORT) - #error "DGUS_SERIAL_PORT is now LCD_SERIAL_PORT. Please update your configuration." + #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. Please update your configuration." + #error "ANYCUBIC_LCD_SERIAL_PORT is now LCD_SERIAL_PORT." #elif defined(INTERNAL_SERIAL_PORT) - #error "INTERNAL_SERIAL_PORT is now MMU2_SERIAL_PORT. Please update your configuration." -#elif defined(X_DUAL_ENDSTOPS_ADJUSTMENT) - #error "X_DUAL_ENDSTOPS_ADJUSTMENT is now X2_ENDSTOP_ADJUSTMENT. Please update Configuration_adv.h." -#elif defined(Y_DUAL_ENDSTOPS_ADJUSTMENT) - #error "Y_DUAL_ENDSTOPS_ADJUSTMENT is now Y2_ENDSTOP_ADJUSTMENT. Please update Configuration_adv.h." -#elif defined(Z_DUAL_ENDSTOPS_ADJUSTMENT) - #error "Z_DUAL_ENDSTOPS_ADJUSTMENT is now Z2_ENDSTOP_ADJUSTMENT. Please update Configuration_adv.h." + #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. Please update Configuration_adv.h." + #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. Please update Configuration_adv.h." + #error "Z_QUAD_ENDSTOPS_ADJUSTMENT[234] is now Z[234]_ENDSTOP_ADJUSTMENT." #elif defined(Z_DUAL_STEPPER_DRIVERS) - #error "Z_DUAL_STEPPER_DRIVERS is now NUM_Z_STEPPER_DRIVERS with a value of 2. Please update Configuration_adv.h." + #error "Z_DUAL_STEPPER_DRIVERS is now NUM_Z_STEPPER_DRIVERS with a value of 2." #elif defined(Z_TRIPLE_STEPPER_DRIVERS) - #error "Z_TRIPLE_STEPPER_DRIVERS is now NUM_Z_STEPPER_DRIVERS with a value of 3. Please update Configuration_adv.h." + #error "Z_TRIPLE_STEPPER_DRIVERS is now NUM_Z_STEPPER_DRIVERS with a value of 3." #elif defined(Z_QUAD_STEPPER_DRIVERS) - #error "Z_QUAD_STEPPER_DRIVERS is now NUM_Z_STEPPER_DRIVERS with a value of 4. Please update Configuration_adv.h." -#elif defined(Z_DUAL_ENDSTOPS) - #error "Z_DUAL_ENDSTOPS is now Z_MULTI_ENDSTOPS. Please update Configuration_adv.h." -#elif defined(Z_TRIPLE_ENDSTOPS) - #error "Z_TRIPLE_ENDSTOPS is now Z_MULTI_ENDSTOPS. Please update Configuration_adv.h." -#elif defined(Z_QUAD_ENDSTOPS) - #error "Z_QUAD_ENDSTOPS is now Z_MULTI_ENDSTOPS. Please update Configuration_adv.h." + #error "Z_QUAD_STEPPER_DRIVERS is now NUM_Z_STEPPER_DRIVERS with a value of 4." +#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. Please update Configuration_adv.h." + #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. Make sure your pins are up to date." + #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. Make sure your pins are up to date." + #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. Please update Configuration_adv.h." + #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. Please update Configuration_adv.h." + #error "[XYZ]_HOME_BUMP_MM is now HOMING_BUMP_MM." #elif defined(DIGIPOT_I2C) - #error "DIGIPOT_I2C is now DIGIPOT_MCP4451 (or DIGIPOT_MCP4018). Please update Configuration_adv.h." + #error "DIGIPOT_I2C is now DIGIPOT_MCP4451 (or DIGIPOT_MCP4018)." #elif defined(TOUCH_BUTTONS) - #error "TOUCH_BUTTONS is now TOUCH_SCREEN. Please update your Configuration.h." -#elif defined(LCD_FULL_PIXEL_HEIGHT) - #error "LCD_FULL_PIXEL_HEIGHT is deprecated and should be removed. Please update your Configuration.h." -#elif defined(LCD_FULL_PIXEL_WIDTH) - #error "LCD_FULL_PIXEL_WIDTH is deprecated and should be removed. Please update your Configuration.h." + #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. Please update your Configuration.h." + #error "FSMC_UPSCALE is now GRAPHICAL_TFT_UPSCALE." #elif defined(ANYCUBIC_TFT_MODEL) - #error "ANYCUBIC_TFT_MODEL is now ANYCUBIC_LCD_I3MEGA. Please update your Configuration.h." + #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. Please update your Configuration.h." + #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. Please update your Configuration.h." + #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. Please update your Configuration.h." + #error "FIL_RUNOUT_INVERTING true is now FIL_RUNOUT_STATE HIGH." #else - #error "FIL_RUNOUT_INVERTING false is now FIL_RUNOUT_STATE LOW. Please update your Configuration.h." - #endif -#endif + #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(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" +#endif + +constexpr float arm[] = AXIS_RELATIVE_MODES; +static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _LOGICAL_AXES_STR "elements."); /** * Probe temp compensation requirements */ + #if ENABLED(PROBE_TEMP_COMPENSATION) #if defined(PTC_PARK_POS_X) || defined(PTC_PARK_POS_Y) || defined(PTC_PARK_POS_Z) - #error "PTC_PARK_POS_[XYZ] is now PTC_PARK_POS (array). Please update Configuration_adv.h." + #error "PTC_PARK_POS_[XYZ] is now PTC_PARK_POS (array)." #elif !defined(PTC_PARK_POS) #error "PROBE_TEMP_COMPENSATION requires PTC_PARK_POS." #elif defined(PTC_PROBE_POS_X) || defined(PTC_PROBE_POS_Y) - #error "PTC_PROBE_POS_[XY] is now PTC_PROBE_POS (array). Please update Configuration_adv.h." + #error "PTC_PROBE_POS_[XY] is now PTC_PROBE_POS (array)." #elif !defined(PTC_PROBE_POS) #error "PROBE_TEMP_COMPENSATION requires PTC_PROBE_POS." #endif + + #ifdef PTC_SAMPLE_START + constexpr auto _ptc_sample_start = PTC_SAMPLE_START; + constexpr decltype(_ptc_sample_start) _test_ptc_sample_start = 12.3f; + static_assert(_test_ptc_sample_start != 12.3f, "PTC_SAMPLE_START must be a whole number."); + #endif + #ifdef PTC_SAMPLE_RES + constexpr auto _ptc_sample_res = PTC_SAMPLE_RES; + constexpr decltype(_ptc_sample_res) _test_ptc_sample_res = 12.3f; + static_assert(_test_ptc_sample_res != 12.3f, "PTC_SAMPLE_RES must be a whole number."); + #endif + #ifdef BTC_SAMPLE_START + constexpr auto _btc_sample_start = BTC_SAMPLE_START; + constexpr decltype(_btc_sample_start) _test_btc_sample_start = 12.3f; + static_assert(_test_btc_sample_start != 12.3f, "BTC_SAMPLE_START must be a whole number."); + #endif + #ifdef BTC_SAMPLE_RES + constexpr auto _btc_sample_res = BTC_SAMPLE_RES; + constexpr decltype(_btc_sample_res) _test_btc_sample_res = 12.3f; + static_assert(_test_btc_sample_res != 12.3f, "BTC_SAMPLE_RES must be a whole number."); + #endif + #ifdef BTC_PROBE_TEMP + constexpr auto _btc_probe_temp = BTC_PROBE_TEMP; + constexpr decltype(_btc_probe_temp) _test_btc_probe_temp = 12.3f; + static_assert(_test_btc_probe_temp != 12.3f, "BTC_PROBE_TEMP must be a whole number."); + #endif #endif /** @@ -582,7 +654,20 @@ /** * Serial */ -#if !IS_AT90USB +#ifndef SERIAL_PORT + #error "SERIAL_PORT must be defined." +#elif defined(SERIAL_PORT_2) && SERIAL_PORT_2 == SERIAL_PORT + #error "SERIAL_PORT_2 cannot be the same as SERIAL_PORT." +#elif defined(SERIAL_PORT_3) + #ifndef SERIAL_PORT_2 + #error "Use SERIAL_PORT_2 before using SERIAL_PORT_3" + #elif SERIAL_PORT_3 == SERIAL_PORT + #error "SERIAL_PORT_3 cannot be the same as SERIAL_PORT." + #elif SERIAL_PORT_3 == SERIAL_PORT_2 + #error "SERIAL_PORT_3 cannot be the same as SERIAL_PORT_2." + #endif +#endif +#if !(defined(__AVR__) && defined(USBCON)) #if ENABLED(SERIAL_XON_XOFF) && RX_BUFFER_SIZE < 1024 #error "SERIAL_XON_XOFF requires RX_BUFFER_SIZE >= 1024 for reliable transfers without drops." #elif RX_BUFFER_SIZE && (RX_BUFFER_SIZE < 2 || !IS_POWER_OF_2(RX_BUFFER_SIZE)) @@ -594,12 +679,6 @@ #error "SERIAL_XON_XOFF and SERIAL_STATS_* features not supported on USB-native AVR devices." #endif -#ifndef SERIAL_PORT - #error "SERIAL_PORT must be defined in Configuration.h" -#elif defined(SERIAL_PORT_2) && SERIAL_PORT_2 == SERIAL_PORT - #error "SERIAL_PORT_2 cannot be the same as SERIAL_PORT. Please update your configuration." -#endif - /** * Multiple Stepper Drivers Per Axis */ @@ -614,14 +693,18 @@ #if ENABLED(Y_DUAL_STEPPER_DRIVERS) && !GOOD_AXIS_PINS(Y) #error "Y_DUAL_STEPPER_DRIVERS requires Y2 pins to be defined." -#elif !WITHIN(NUM_Z_STEPPER_DRIVERS, 1, 4) - #error "NUM_Z_STEPPER_DRIVERS must be an integer from 1 to 4." -#elif NUM_Z_STEPPER_DRIVERS == 2 && !GOOD_AXIS_PINS(Z2) - #error "If NUM_Z_STEPPER_DRIVERS is 2, you must define stepper pins for Z2." -#elif NUM_Z_STEPPER_DRIVERS == 3 && !(GOOD_AXIS_PINS(Z2) && GOOD_AXIS_PINS(Z3)) - #error "If NUM_Z_STEPPER_DRIVERS is 3, you must define stepper pins for Z2 and Z3." -#elif NUM_Z_STEPPER_DRIVERS == 4 && !(GOOD_AXIS_PINS(Z2) && GOOD_AXIS_PINS(Z3) && GOOD_AXIS_PINS(Z4)) - #error "If NUM_Z_STEPPER_DRIVERS is 4, you must define stepper pins for Z2, Z3, and Z4." +#endif + +#if HAS_Z_AXIS + #if !WITHIN(NUM_Z_STEPPER_DRIVERS, 1, 4) + #error "NUM_Z_STEPPER_DRIVERS must be an integer from 1 to 4." + #elif NUM_Z_STEPPER_DRIVERS == 2 && !GOOD_AXIS_PINS(Z2) + #error "If NUM_Z_STEPPER_DRIVERS is 2, you must define stepper pins for Z2." + #elif NUM_Z_STEPPER_DRIVERS == 3 && !(GOOD_AXIS_PINS(Z2) && GOOD_AXIS_PINS(Z3)) + #error "If NUM_Z_STEPPER_DRIVERS is 3, you must define stepper pins for Z2 and Z3." + #elif NUM_Z_STEPPER_DRIVERS == 4 && !(GOOD_AXIS_PINS(Z2) && GOOD_AXIS_PINS(Z3) && GOOD_AXIS_PINS(Z4)) + #error "If NUM_Z_STEPPER_DRIVERS is 4, you must define stepper pins for Z2, Z3, and Z4." + #endif #endif /** @@ -674,6 +757,12 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "Enable only one of ENDSTOPPULLUP_Y_MIN or ENDSTOPPULLDOWN_Y_MIN." #elif BOTH(ENDSTOPPULLUP_ZMIN, ENDSTOPPULLDOWN_ZMIN) #error "Enable only one of ENDSTOPPULLUP_Z_MIN or ENDSTOPPULLDOWN_Z_MIN." +#elif BOTH(ENDSTOPPULLUP_IMIN, ENDSTOPPULLDOWN_IMIN) + #error "Enable only one of ENDSTOPPULLUP_I_MIN or ENDSTOPPULLDOWN_I_MIN." +#elif BOTH(ENDSTOPPULLUP_JMIN, ENDSTOPPULLDOWN_JMIN) + #error "Enable only one of ENDSTOPPULLUP_J_MIN or ENDSTOPPULLDOWN_J_MIN." +#elif BOTH(ENDSTOPPULLUP_KMIN, ENDSTOPPULLDOWN_KMIN) + #error "Enable only one of ENDSTOPPULLUP_K_MIN or ENDSTOPPULLDOWN_K_MIN." #endif /** @@ -702,8 +791,14 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #elif PROGRESS_MSG_EXPIRE < 0 #error "PROGRESS_MSG_EXPIRE must be greater than or equal to 0." #endif -#elif ENABLED(LCD_SET_PROGRESS_MANUALLY) && NONE(HAS_MARLINUI_U8GLIB, HAS_GRAPHICAL_TFT, HAS_MARLINUI_HD44780, EXTENSIBLE_UI) - #error "LCD_SET_PROGRESS_MANUALLY requires LCD_PROGRESS_BAR, Character LCD, Graphical LCD, TFT, or EXTENSIBLE_UI." +#elif ENABLED(LCD_SET_PROGRESS_MANUALLY) + #if NONE(HAS_MARLINUI_U8GLIB, HAS_GRAPHICAL_TFT, HAS_MARLINUI_HD44780, EXTENSIBLE_UI) + #error "LCD_SET_PROGRESS_MANUALLY requires LCD_PROGRESS_BAR, Character LCD, Graphical LCD, TFT, or EXTENSIBLE_UI." + #endif +#endif + +#if ENABLED(USE_M73_REMAINING_TIME) && DISABLED(LCD_SET_PROGRESS_MANUALLY) + #error "USE_M73_REMAINING_TIME requires LCD_SET_PROGRESS_MANUALLY" #endif #if !HAS_LCD_MENU && ENABLED(SD_REPRINT_LAST_SELECTED_FILE) @@ -716,7 +811,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #if ENABLED(SHOW_CUSTOM_BOOTSCREEN) && NONE(HAS_MARLINUI_U8GLIB, TOUCH_UI_FTDI_EVE) #error "SHOW_CUSTOM_BOOTSCREEN requires Graphical LCD or TOUCH_UI_FTDI_EVE." #elif ENABLED(CUSTOM_STATUS_SCREEN_IMAGE) && !HAS_MARLINUI_U8GLIB - #error "CUSTOM_STATUS_SCREEN_IMAGE requires a Graphical LCD." + #error "CUSTOM_STATUS_SCREEN_IMAGE requires a 128x64 DOGM B/W Graphical LCD." #endif /** @@ -726,6 +821,13 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "LIGHTWEIGHT_UI requires a U8GLIB_ST7920-based display." #endif +/** + * SD Card Settings + */ +#if ALL(SDSUPPORT, ELB_FULL_GRAPHIC_CONTROLLER, HAS_LCD_MENU) && PIN_EXISTS(SD_DETECT) && SD_DETECT_STATE != HIGH && (SD_CONNECTION_IS(LCD) || !defined(SDCARD_CONNECTION)) + #error "SD_DETECT_STATE must be set HIGH for SD on the ELB_FULL_GRAPHIC_CONTROLLER." +#endif + /** * SD File Sorting */ @@ -799,8 +901,6 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #if ENABLED(BABYSTEP_XY) static_assert(BABYSTEP_MULTIPLICATOR_XY <= 0.25f, "BABYSTEP_MULTIPLICATOR_XY must be less than or equal to 0.25mm."); #endif - #elif ENABLED(BABYSTEP_DISPLAY_TOTAL) && ANY(TFT_320x240, TFT_320x240_SPI, TFT_480x320, TFT_480x320_SPI) - #error "New Color UI (TFT_320x240, TFT_320x240_SPI, TFT_480x320, TFT_480x320_SPI) does not support BABYSTEP_DISPLAY_TOTAL yet." #endif #endif @@ -810,20 +910,40 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #if HAS_FILAMENT_SENSOR #if !PIN_EXISTS(FIL_RUNOUT) #error "FILAMENT_RUNOUT_SENSOR requires FIL_RUNOUT_PIN." - #elif NUM_RUNOUT_SENSORS > E_STEPPERS - #error "NUM_RUNOUT_SENSORS cannot exceed the number of E steppers." - #elif NUM_RUNOUT_SENSORS > 1 && !PIN_EXISTS(FIL_RUNOUT2) - #error "FILAMENT_RUNOUT_SENSOR with NUM_RUNOUT_SENSORS > 1 requires FIL_RUNOUT2_PIN." - #elif NUM_RUNOUT_SENSORS > 2 && !PIN_EXISTS(FIL_RUNOUT3) - #error "FILAMENT_RUNOUT_SENSOR with NUM_RUNOUT_SENSORS > 2 requires FIL_RUNOUT3_PIN." - #elif NUM_RUNOUT_SENSORS > 3 && !PIN_EXISTS(FIL_RUNOUT4) - #error "FILAMENT_RUNOUT_SENSOR with NUM_RUNOUT_SENSORS > 3 requires FIL_RUNOUT4_PIN." - #elif NUM_RUNOUT_SENSORS > 4 && !PIN_EXISTS(FIL_RUNOUT5) - #error "FILAMENT_RUNOUT_SENSOR with NUM_RUNOUT_SENSORS > 4 requires FIL_RUNOUT5_PIN." - #elif NUM_RUNOUT_SENSORS > 5 && !PIN_EXISTS(FIL_RUNOUT6) - #error "FILAMENT_RUNOUT_SENSOR with NUM_RUNOUT_SENSORS > 5 requires FIL_RUNOUT6_PIN." - #elif NONE(SDSUPPORT, PRINTJOB_TIMER_AUTOSTART) - #error "FILAMENT_RUNOUT_SENSOR requires SDSUPPORT or PRINTJOB_TIMER_AUTOSTART." + #elif HAS_PRUSA_MMU2 && NUM_RUNOUT_SENSORS != 1 + #error "NUM_RUNOUT_SENSORS must be 1 with MMU2 / MMU2S." + #elif NUM_RUNOUT_SENSORS != 1 && NUM_RUNOUT_SENSORS != E_STEPPERS + #error "NUM_RUNOUT_SENSORS must be either 1 or number of E steppers." + #elif NUM_RUNOUT_SENSORS >= 8 && !PIN_EXISTS(FIL_RUNOUT8) + #error "FIL_RUNOUT8_PIN is required with NUM_RUNOUT_SENSORS >= 8." + #elif NUM_RUNOUT_SENSORS >= 7 && !PIN_EXISTS(FIL_RUNOUT7) + #error "FIL_RUNOUT7_PIN is required with NUM_RUNOUT_SENSORS >= 7." + #elif NUM_RUNOUT_SENSORS >= 6 && !PIN_EXISTS(FIL_RUNOUT6) + #error "FIL_RUNOUT6_PIN is required with NUM_RUNOUT_SENSORS >= 6." + #elif NUM_RUNOUT_SENSORS >= 5 && !PIN_EXISTS(FIL_RUNOUT5) + #error "FIL_RUNOUT5_PIN is required with NUM_RUNOUT_SENSORS >= 5." + #elif NUM_RUNOUT_SENSORS >= 4 && !PIN_EXISTS(FIL_RUNOUT4) + #error "FIL_RUNOUT4_PIN is required with NUM_RUNOUT_SENSORS >= 4." + #elif NUM_RUNOUT_SENSORS >= 3 && !PIN_EXISTS(FIL_RUNOUT3) + #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) + #error "You can't enable FIL_RUNOUT1_PULLUP and FIL_RUNOUT1_PULLDOWN at the same time." + #elif BOTH(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) + #error "You can't enable FIL_RUNOUT3_PULLUP and FIL_RUNOUT3_PULLDOWN at the same time." + #elif BOTH(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) + #error "You can't enable FIL_RUNOUT5_PULLUP and FIL_RUNOUT5_PULLDOWN at the same time." + #elif BOTH(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) + #error "You can't enable FIL_RUNOUT7_PULLUP and FIL_RUNOUT7_PULLDOWN at the same time." + #elif BOTH(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) @@ -840,10 +960,10 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #elif DISABLED(NOZZLE_PARK_FEATURE) #error "ADVANCED_PAUSE_FEATURE requires NOZZLE_PARK_FEATURE." #elif !defined(FILAMENT_UNLOAD_PURGE_FEEDRATE) - #error "ADVANCED_PAUSE_FEATURE requires FILAMENT_UNLOAD_PURGE_FEEDRATE. Please add it to Configuration_adv.h." + #error "ADVANCED_PAUSE_FEATURE requires FILAMENT_UNLOAD_PURGE_FEEDRATE." #elif ENABLED(EXTRUDER_RUNOUT_PREVENT) #error "EXTRUDER_RUNOUT_PREVENT is incompatible with ADVANCED_PAUSE_FEATURE." - #elif ENABLED(PARK_HEAD_ON_PAUSE) && NONE(SDSUPPORT, NEWPANEL, EMERGENCY_PARSER) + #elif ENABLED(PARK_HEAD_ON_PAUSE) && NONE(SDSUPPORT, IS_NEWPANEL, EMERGENCY_PARSER) #error "PARK_HEAD_ON_PAUSE requires SDSUPPORT, EMERGENCY_PARSER, or an LCD controller." #elif ENABLED(HOME_BEFORE_FILAMENT_CHANGE) && DISABLED(PAUSE_PARK_NO_STEPPER_TIMEOUT) #error "HOME_BEFORE_FILAMENT_CHANGE requires PAUSE_PARK_NO_STEPPER_TIMEOUT." @@ -865,6 +985,13 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement 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)."); #endif +/** + * Instant Freeze + */ +#if ENABLED(FREEZE_FEATURE) && !PIN_EXISTS(FREEZE) + #error "FREEZE_FEATURE requires a FREEZE_PIN to be defined." +#endif + /** * Individual axis homing is useless for DELTAS */ @@ -872,52 +999,96 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "INDIVIDUAL_AXIS_HOMING_MENU is incompatible with DELTA kinematics." #endif +/** + * Sanity checking for all Průša MMU + */ +#ifdef SNMM + #error "SNMM is obsolete. Define MMU_MODEL as PRUSA_MMU1 instead." +#elif ENABLED(MK2_MULTIPLEXER) + #error "MK2_MULTIPLEXER is obsolete. Define MMU_MODEL as PRUSA_MMU1 instead." +#elif ENABLED(PRUSA_MMU2) + #error "PRUSA_MMU2 is obsolete. Define MMU_MODEL as PRUSA_MMU2 instead." +#elif ENABLED(PRUSA_MMU2_S_MODE) + #error "PRUSA_MMU2_S_MODE is obsolete. Define MMU_MODEL as PRUSA_MMU2S instead." +#elif ENABLED(SMUFF_EMU_MMU2) + #error "SMUFF_EMU_MMU2 is obsolete. Define MMU_MODEL as EXTENDABLE_EMU_MMU2 instead." +#elif ENABLED(SMUFF_EMU_MMU2S) + #error "SMUFF_EMU_MMU2S is obsolete. Define MMU_MODEL as EXTENDABLE_EMU_MMU2S instead." +#endif + +/** + * Multi-Material-Unit 2 / EXTENDABLE_EMU_MMU2 requirements + */ +#if HAS_PRUSA_MMU2 + #if !HAS_EXTENDABLE_MMU && EXTRUDERS != 5 + #undef SINGLENOZZLE + #error "PRUSA_MMU2(S) requires exactly 5 EXTRUDERS. Please update your Configuration." + #elif HAS_EXTENDABLE_MMU && EXTRUDERS > 15 + #error "EXTRUDERS is too large for MMU(S) emulation mode. The maximum value is 15." + #elif DISABLED(NOZZLE_PARK_FEATURE) + #error "PRUSA_MMU2(S) requires NOZZLE_PARK_FEATURE. Enable it to continue." + #elif HAS_PRUSA_MMU2S && DISABLED(FILAMENT_RUNOUT_SENSOR) + #error "PRUSA_MMU2S requires FILAMENT_RUNOUT_SENSOR. Enable it to continue." + #elif ENABLED(MMU_EXTRUDER_SENSOR) && DISABLED(FILAMENT_RUNOUT_SENSOR) + #error "MMU_EXTRUDER_SENSOR requires FILAMENT_RUNOUT_SENSOR. Enable it to continue." + #elif ENABLED(MMU_EXTRUDER_SENSOR) && !HAS_LCD_MENU + #error "MMU_EXTRUDER_SENSOR requires an LCD supporting MarlinUI to be enabled." + #elif DISABLED(ADVANCED_PAUSE_FEATURE) + static_assert(nullptr == strstr(MMU2_FILAMENT_RUNOUT_SCRIPT, "M600"), "ADVANCED_PAUSE_FEATURE is required to use M600 with PRUSA_MMU2(S) / HAS_EXTENDABLE_MMU(S)."); + #endif +#endif + /** * Options only for EXTRUDERS > 1 */ #if HAS_MULTI_EXTRUDER - #if EXTRUDERS > 8 - #error "Marlin supports a maximum of 8 EXTRUDERS." + #if HAS_EXTENDABLE_MMU + #define MAX_EXTRUDERS 15 + #else + #define MAX_EXTRUDERS 8 #endif + static_assert(EXTRUDERS <= MAX_EXTRUDERS, "Marlin supports a maximum of " STRINGIFY(MAX_EXTRUDERS) " EXTRUDERS."); + #undef MAX_EXTRUDERS #if ENABLED(HEATERS_PARALLEL) #error "EXTRUDERS must be 1 with HEATERS_PARALLEL." #endif + #if ENABLED(STATUS_HOTEND_INVERTED) && NONE(STATUS_HOTEND_NUMBERLESS, STATUS_HOTEND_ANIM) + #error "With multiple hotends STATUS_HOTEND_INVERTED requires STATUS_HOTEND_ANIM or STATUS_HOTEND_NUMBERLESS." + #endif + #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) #ifndef TOOLCHANGE_FS_LENGTH - #error "TOOLCHANGE_FILAMENT_SWAP requires TOOLCHANGE_FS_LENGTH. Please update your Configuration_adv.h." + #error "TOOLCHANGE_FILAMENT_SWAP requires TOOLCHANGE_FS_LENGTH." #elif !defined(TOOLCHANGE_FS_RETRACT_SPEED) - #error "TOOLCHANGE_FILAMENT_SWAP requires TOOLCHANGE_FS_RETRACT_SPEED. Please update your Configuration_adv.h." + #error "TOOLCHANGE_FILAMENT_SWAP requires TOOLCHANGE_FS_RETRACT_SPEED." #elif !defined(TOOLCHANGE_FS_PRIME_SPEED) - #error "TOOLCHANGE_FILAMENT_SWAP requires TOOLCHANGE_FS_PRIME_SPEED. Please update your Configuration_adv.h." + #error "TOOLCHANGE_FILAMENT_SWAP requires TOOLCHANGE_FS_PRIME_SPEED." #endif #endif #if ENABLED(TOOLCHANGE_PARK) #ifndef TOOLCHANGE_PARK_XY - #error "TOOLCHANGE_PARK requires TOOLCHANGE_PARK_XY. Please update your Configuration." + #error "TOOLCHANGE_PARK requires TOOLCHANGE_PARK_XY." #elif !defined(TOOLCHANGE_PARK_XY_FEEDRATE) - #error "TOOLCHANGE_PARK requires TOOLCHANGE_PARK_XY_FEEDRATE. Please update your Configuration." + #error "TOOLCHANGE_PARK requires TOOLCHANGE_PARK_XY_FEEDRATE." #endif #endif #ifndef TOOLCHANGE_ZRAISE - #error "TOOLCHANGE_ZRAISE required for EXTRUDERS > 1. Please update your Configuration_adv.h." + #error "TOOLCHANGE_ZRAISE required for EXTRUDERS > 1." #endif -#elif ENABLED(MK2_MULTIPLEXER) - #error "MK2_MULTIPLEXER requires 2 or more EXTRUDERS." +#elif HAS_PRUSA_MMU1 || HAS_EXTENDABLE_MMU + + #error "Multi-Material-Unit requires 2 or more EXTRUDERS." + #elif ENABLED(SINGLENOZZLE) + #error "SINGLENOZZLE requires 2 or more EXTRUDERS." -#endif -/** - * Sanity checking for the Průša MK2 Multiplexer - */ -#ifdef SNMM - #error "SNMM is now MK2_MULTIPLEXER. Please update your configuration." #endif /** @@ -1007,6 +1178,21 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_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." + #endif +#endif + +/** + * Dual E Steppers requirements + */ +#if ENABLED(E_DUAL_STEPPER_DRIVERS) + #if EXTRUDERS > 1 + #error "E_DUAL_STEPPER_DRIVERS can only be used with EXTRUDERS set to 1." + #elif ENABLED(MIXING_EXTRUDER) + #error "E_DUAL_STEPPER_DRIVERS is incompatible with MIXING_EXTRUDER." + #elif ENABLED(SWITCHING_EXTRUDER) + #error "E_DUAL_STEPPER_DRIVERS is incompatible with SWITCHING_EXTRUDER." #endif #endif @@ -1020,21 +1206,18 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS ); #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." + #elif !HAS_JUNCTION_DEVIATION && defined(DEFAULT_EJERK) + static_assert(DEFAULT_EJERK >= 10, "It is strongly recommended to set DEFAULT_EJERK >= 10 when using LIN_ADVANCE."); #endif #endif /** * Special tool-changing options */ -#if 1 < 0 \ - + ENABLED(SINGLENOZZLE) \ - + ENABLED(DUAL_X_CARRIAGE) \ - + ENABLED(PARKING_EXTRUDER) \ - + ENABLED(MAGNETIC_PARKING_EXTRUDER) \ - + ENABLED(SWITCHING_TOOLHEAD) \ - + ENABLED(MAGNETIC_SWITCHING_TOOLHEAD) \ - + ENABLED(ELECTROMAGNETIC_SWITCHING_TOOLHEAD) - #error "Please select only one of SINGLENOZZLE, DUAL_X_CARRIAGE, PARKING_EXTRUDER, SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD, or ELECTROMAGNETIC_SWITCHING_TOOLHEAD." +#if MANY(SINGLENOZZLE, DUAL_X_CARRIAGE, PARKING_EXTRUDER, MAGNETIC_PARKING_EXTRUDER, SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD, ELECTROMAGNETIC_SWITCHING_TOOLHEAD) + #error "Please select only one of SINGLENOZZLE, DUAL_X_CARRIAGE, PARKING_EXTRUDER, MAGNETIC_PARKING_EXTRUDER, SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD, or ELECTROMAGNETIC_SWITCHING_TOOLHEAD." #endif /** @@ -1088,23 +1271,28 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif /** - * (Electro)magnetic Switching Toolhead requirements + * Magnetic / Electromagnetic Switching Toolhead requirements */ #if EITHER(MAGNETIC_SWITCHING_TOOLHEAD, ELECTROMAGNETIC_SWITCHING_TOOLHEAD) #ifndef SWITCHING_TOOLHEAD_Y_POS - #error "(ELECTRO)MAGNETIC_SWITCHING_TOOLHEAD requires SWITCHING_TOOLHEAD_Y_POS" + #error "(ELECTRO)?MAGNETIC_SWITCHING_TOOLHEAD requires SWITCHING_TOOLHEAD_Y_POS" #elif !defined(SWITCHING_TOOLHEAD_X_POS) - #error "(ELECTRO)MAGNETIC_SWITCHING_TOOLHEAD requires SWITCHING_TOOLHEAD_X_POS" - #elif !defined(SWITCHING_TOOLHEAD_Z_HOP) - #error "(ELECTRO)MAGNETIC_SWITCHING_TOOLHEAD requires SWITCHING_TOOLHEAD_Z_HOP." + #error "(ELECTRO)?MAGNETIC_SWITCHING_TOOLHEAD requires SWITCHING_TOOLHEAD_X_POS" #elif !defined(SWITCHING_TOOLHEAD_Y_CLEAR) - #error "(ELECTRO)MAGNETIC_SWITCHING_TOOLHEAD requires SWITCHING_TOOLHEAD_Y_CLEAR." - #elif ENABLED(ELECTROMAGNETIC_SWITCHING_TOOLHEAD) - #if ENABLED(EXT_SOLENOID) - #error "(ELECTRO)MAGNETIC_SWITCHING_TOOLHEAD and EXT_SOLENOID are incompatible. (Pins are used twice.)" - #elif !PIN_EXISTS(SOL0) - #error "(ELECTRO)MAGNETIC_SWITCHING_TOOLHEAD requires SOL0_PIN." - #endif + #error "(ELECTRO)?MAGNETIC_SWITCHING_TOOLHEAD requires SWITCHING_TOOLHEAD_Y_CLEAR." + #endif +#endif + +/** + * Electromagnetic Switching Toolhead requirements + */ +#if ENABLED(ELECTROMAGNETIC_SWITCHING_TOOLHEAD) + #if ENABLED(EXT_SOLENOID) + #error "ELECTROMAGNETIC_SWITCHING_TOOLHEAD and EXT_SOLENOID are incompatible. (Pins are used twice.)" + #elif !PIN_EXISTS(SOL0) + #error "ELECTROMAGNETIC_SWITCHING_TOOLHEAD requires SOL0_PIN." + #elif !defined(SWITCHING_TOOLHEAD_Z_HOP) + #error "ELECTROMAGNETIC_SWITCHING_TOOLHEAD requires SWITCHING_TOOLHEAD_Z_HOP." #endif #endif @@ -1154,6 +1342,78 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "To use BED_LIMIT_SWITCHING you must disable PIDTEMPBED." #endif +/** + * Synchronous M106/M107 checks + */ +#if ENABLED(LASER_SYNCHRONOUS_M106_M107) + #if FAN_KICKSTART_TIME + #error "FAN_KICKSTART_TIME must be 0 with LASER_SYNCHRONOUS_M106_M107 (because the laser will always come on at FULL power)." + #elif FAN_MIN_PWM + #error "FAN_MIN_PWM must be 0 with LASER_SYNCHRONOUS_M106_M107 (otherwise the laser will never turn OFF)." + #endif +#endif + +/** + * Chamber Heating Options - PID vs Limit Switching + */ +#if BOTH(PIDTEMPCHAMBER, CHAMBER_LIMIT_SWITCHING) + #error "To use CHAMBER_LIMIT_SWITCHING you must disable PIDTEMPCHAMBER." +#endif + +/** + * Features that require a min/max/specific LINEAR_AXES + */ +#if HAS_LEVELING && !HAS_Z_AXIS + #error "Leveling in Marlin requires three or more axes, with Z as the vertical axis." +#elif ENABLED(CNC_WORKSPACE_PLANES) && !HAS_Z_AXIS + #error "CNC_WORKSPACE_PLANES currently requires LINEAR_AXES >= 3" +#elif ENABLED(DIRECT_STEPPING) && LINEAR_AXES > XYZ + #error "DIRECT_STEPPING currently requires LINEAR_AXES 3" +#elif ENABLED(FOAMCUTTER_XYUV) && LINEAR_AXES < 5 + #error "FOAMCUTTER_XYUV requires LINEAR_AXES >= 5." +#endif + +/** + * Allow only extra axis codes that do not conflict with G-code parameter names + */ +#if LINEAR_AXES >= 4 + #if AXIS4_NAME != 'A' && AXIS4_NAME != 'B' && AXIS4_NAME != 'C' && AXIS4_NAME != 'U' && AXIS4_NAME != 'V' && AXIS4_NAME != 'W' + #error "AXIS4_NAME can only be one of 'A', 'B', 'C', 'U', 'V', or 'W'." + #elif !defined(I_MIN_POS) || !defined(I_MAX_POS) + #error "I_MIN_POS and I_MAX_POS are required with LINEAR_AXES >= 4." + #elif !defined(I_HOME_DIR) + #error "I_HOME_DIR is required with LINEAR_AXES >= 4." + #elif HAS_I_ENABLE && !defined(I_ENABLE_ON) + #error "I_ENABLE_ON is required for your I driver with LINEAR_AXES >= 4." + #endif +#endif +#if LINEAR_AXES >= 5 + #if AXIS5_NAME == AXIS4_NAME || AXIS5_NAME == AXIS6_NAME + #error "AXIS5_NAME must be different from AXIS4_NAME and AXIS6_NAME" + #elif AXIS5_NAME != 'A' && AXIS5_NAME != 'B' && AXIS5_NAME != 'C' && AXIS5_NAME != 'U' && AXIS5_NAME != 'V' && AXIS5_NAME != 'W' + #error "AXIS5_NAME can only be one of 'A', 'B', 'C', 'U', 'V', or 'W'." + #elif !defined(J_MIN_POS) || !defined(J_MAX_POS) + #error "J_MIN_POS and J_MAX_POS are required with LINEAR_AXES >= 5." + #elif !defined(J_HOME_DIR) + #error "J_HOME_DIR is required with LINEAR_AXES >= 5." + #elif HAS_J_ENABLE && !defined(J_ENABLE_ON) + #error "J_ENABLE_ON is required for your J driver with LINEAR_AXES >= 5." + #endif +#endif +#if LINEAR_AXES >= 6 + #if AXIS6_NAME == AXIS5_NAME || AXIS6_NAME == AXIS4_NAME + #error "AXIS6_NAME must be different from AXIS5_NAME and AXIS4_NAME." + #elif AXIS6_NAME != 'A' && AXIS6_NAME != 'B' && AXIS6_NAME != 'C' && AXIS6_NAME != 'U' && AXIS6_NAME != 'V' && AXIS6_NAME != 'W' + #error "AXIS6_NAME can only be one of 'A', 'B', 'C', 'U', 'V', or 'W'." + #elif !defined(K_MIN_POS) || !defined(K_MAX_POS) + #error "K_MIN_POS and K_MAX_POS are required with LINEAR_AXES >= 6." + #elif !defined(K_HOME_DIR) + #error "K_HOME_DIR is required with LINEAR_AXES >= 6." + #elif HAS_K_ENABLE && !defined(K_ENABLE_ON) + #error "K_ENABLE_ON is required for your K driver with LINEAR_AXES >= 6." + #endif +#endif + /** * Kinematics */ @@ -1161,17 +1421,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS /** * Allow only one kinematic type to be defined */ -#if 1 < 0 \ - + ENABLED(DELTA) \ - + ENABLED(MORGAN_SCARA) \ - + ENABLED(COREXY) \ - + ENABLED(COREXZ) \ - + ENABLED(COREYZ) \ - + ENABLED(COREYX) \ - + ENABLED(COREZX) \ - + ENABLED(COREZY) \ - + ENABLED(MARKFORGED_XY) - #error "Please enable only one of DELTA, MORGAN_SCARA, COREXY, COREYX, COREXZ, COREZX, COREYZ, COREZY, or MARKFORGED_XY." +#if MANY(DELTA, MORGAN_SCARA, MP_SCARA, AXEL_TPARA, COREXY, COREXZ, COREYZ, COREYX, COREZX, COREZY, MARKFORGED_XY, FOAMCUTTER_XYUV) + #error "Please enable only one of DELTA, MORGAN_SCARA, MP_SCARA, AXEL_TPARA, COREXY, COREXZ, COREYZ, COREYX, COREZX, COREZY, MARKFORGED_XY, or FOAMCUTTER_XYUV." #endif /** @@ -1186,10 +1437,10 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "DELTA_AUTO_CALIBRATION requires a probe or LCD Controller." #elif ENABLED(DELTA_CALIBRATION_MENU) && !HAS_LCD_MENU #error "DELTA_CALIBRATION_MENU requires an LCD Controller." - #elif ABL_GRID - #if (GRID_MAX_POINTS_X & 1) == 0 || (GRID_MAX_POINTS_Y & 1) == 0 + #elif ABL_USES_GRID + #if ((GRID_MAX_POINTS_X) & 1) == 0 || ((GRID_MAX_POINTS_Y) & 1) == 0 #error "DELTA requires GRID_MAX_POINTS_X and GRID_MAX_POINTS_Y to be odd numbers." - #elif GRID_MAX_POINTS_X < 3 + #elif (GRID_MAX_POINTS_X) < 3 #error "DELTA requires GRID_MAX_POINTS_X and GRID_MAX_POINTS_Y to be 3 or higher." #endif #endif @@ -1210,18 +1461,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS * Allow only one probe option to be defined */ #if 1 < 0 \ - + ENABLED(PROBE_MANUALLY) \ - + ENABLED(FIX_MOUNTED_PROBE) \ - + ENABLED(NOZZLE_AS_PROBE) \ - + (HAS_Z_SERVO_PROBE && DISABLED(BLTOUCH)) \ - + ENABLED(BLTOUCH) && DISABLED(CREALITY_TOUCH) \ - + ENABLED(CREALITY_TOUCH) \ - + ENABLED(TOUCH_MI_PROBE) \ - + ENABLED(SOLENOID_PROBE) \ - + ENABLED(Z_PROBE_ALLEN_KEY) \ - + ENABLED(Z_PROBE_SLED) \ - + ENABLED(RACK_AND_PINION_PROBE) \ - + ENABLED(SENSORLESS_PROBING) + + (DISABLED(BLTOUCH) && HAS_Z_SERVO_PROBE) \ + + COUNT_ENABLED(PROBE_MANUALLY, BLTOUCH, FIX_MOUNTED_PROBE, NOZZLE_AS_PROBE, TOUCH_MI_PROBE, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, RACK_AND_PINION_PROBE, SENSORLESS_PROBING) #error "Please enable only one probe option: PROBE_MANUALLY, SENSORLESS_PROBING, BLTOUCH, FIX_MOUNTED_PROBE, NOZZLE_AS_PROBE, TOUCH_MI_PROBE, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, or Z Servo." #endif @@ -1241,7 +1482,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #if ENABLED(EXT_SOLENOID) #error "SOLENOID_PROBE is incompatible with EXT_SOLENOID." #elif !HAS_SOLENOID_1 - #error "SOLENOID_PROBE requires SOL1_PIN. It can be added to your Configuration.h." + #error "SOLENOID_PROBE requires SOL1_PIN." #endif #endif @@ -1318,25 +1559,26 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "Z_MIN_PROBE_PIN must be defined if Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN is not enabled." #endif + /** + * Check for improper NOZZLE_TO_PROBE_OFFSET + */ + constexpr xyz_pos_t sanity_nozzle_to_probe_offset = NOZZLE_TO_PROBE_OFFSET; #if ENABLED(NOZZLE_AS_PROBE) - constexpr float sanity_nozzle_to_probe_offset[] = NOZZLE_TO_PROBE_OFFSET; - static_assert(sanity_nozzle_to_probe_offset[0] == 0.0 && sanity_nozzle_to_probe_offset[1] == 0.0, - "NOZZLE_AS_PROBE requires the X,Y offsets in NOZZLE_TO_PROBE_OFFSET to be 0,0."); - #endif - - #if DISABLED(NOZZLE_AS_PROBE) - static_assert(PROBING_MARGIN >= 0, "PROBING_MARGIN must be >= 0."); - static_assert(PROBING_MARGIN_BACK >= 0, "PROBING_MARGIN_BACK must be >= 0."); + static_assert(sanity_nozzle_to_probe_offset.x == 0 && sanity_nozzle_to_probe_offset.y == 0, + "NOZZLE_AS_PROBE requires the XY offsets in NOZZLE_TO_PROBE_OFFSET to both be 0."); + #else + static_assert(PROBING_MARGIN >= 0, "PROBING_MARGIN must be >= 0."); + static_assert(PROBING_MARGIN_BACK >= 0, "PROBING_MARGIN_BACK must be >= 0."); static_assert(PROBING_MARGIN_FRONT >= 0, "PROBING_MARGIN_FRONT must be >= 0."); - static_assert(PROBING_MARGIN_LEFT >= 0, "PROBING_MARGIN_LEFT must be >= 0."); + static_assert(PROBING_MARGIN_LEFT >= 0, "PROBING_MARGIN_LEFT must be >= 0."); static_assert(PROBING_MARGIN_RIGHT >= 0, "PROBING_MARGIN_RIGHT must be >= 0."); #endif #define _MARGIN(A) TERN(IS_SCARA, SCARA_PRINTABLE_RADIUS, TERN(DELTA, DELTA_PRINTABLE_RADIUS, ((A##_BED_SIZE) / 2))) - static_assert(PROBING_MARGIN < _MARGIN(X), "PROBING_MARGIN is too large."); - static_assert(PROBING_MARGIN_BACK < _MARGIN(Y), "PROBING_MARGIN_BACK is too large."); + static_assert(PROBING_MARGIN < _MARGIN(X), "PROBING_MARGIN is too large."); + static_assert(PROBING_MARGIN_BACK < _MARGIN(Y), "PROBING_MARGIN_BACK is too large."); static_assert(PROBING_MARGIN_FRONT < _MARGIN(Y), "PROBING_MARGIN_FRONT is too large."); - static_assert(PROBING_MARGIN_LEFT < _MARGIN(X), "PROBING_MARGIN_LEFT is too large."); + static_assert(PROBING_MARGIN_LEFT < _MARGIN(X), "PROBING_MARGIN_LEFT is too large."); static_assert(PROBING_MARGIN_RIGHT < _MARGIN(X), "PROBING_MARGIN_RIGHT is too large."); #undef _MARGIN @@ -1373,6 +1615,14 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "Z_SAFE_HOMING is recommended when homing with a probe. Enable it or comment out this line to continue." #endif + #if ENABLED(PROBE_ACTIVATION_SWITCH) + #ifndef PROBE_ACTIVATION_SWITCH_STATE + #error "PROBE_ACTIVATION_SWITCH_STATE is required for PROBE_ACTIVATION_SWITCH." + #elif !PIN_EXISTS(PROBE_ACTIVATION_SWITCH) + #error "A PROBE_ACTIVATION_SWITCH_PIN is required for PROBE_ACTIVATION_SWITCH." + #endif + #endif + #else /** @@ -1388,15 +1638,22 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif +#if ENABLED(LEVEL_BED_CORNERS) + #ifndef LEVEL_CORNERS_INSET_LFRB + #error "LEVEL_BED_CORNERS requires LEVEL_CORNERS_INSET_LFRB values." + #elif ENABLED(LEVEL_CORNERS_USE_PROBE) + #if !HAS_BED_PROBE + #error "LEVEL_CORNERS_USE_PROBE requires a real probe." + #elif ENABLED(SENSORLESS_PROBING) + #error "LEVEL_CORNERS_USE_PROBE is incompatible with SENSORLESS_PROBING." + #endif + #endif +#endif + /** * Allow only one bed leveling option to be defined */ -#if 1 < 0 \ - + ENABLED(AUTO_BED_LEVELING_LINEAR) \ - + ENABLED(AUTO_BED_LEVELING_3POINT) \ - + ENABLED(AUTO_BED_LEVELING_BILINEAR) \ - + ENABLED(AUTO_BED_LEVELING_UBL) \ - + ENABLED(MESH_BED_LEVELING) +#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." #endif @@ -1410,17 +1667,12 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS * Unified Bed Leveling */ - // Hide PROBE_MANUALLY from the rest of the code - #undef PROBE_MANUALLY - #if IS_SCARA #error "AUTO_BED_LEVELING_UBL does not yet support SCARA printers." #elif DISABLED(EEPROM_SETTINGS) - #error "AUTO_BED_LEVELING_UBL requires EEPROM_SETTINGS. Please update your configuration." + #error "AUTO_BED_LEVELING_UBL requires EEPROM_SETTINGS." #elif !WITHIN(GRID_MAX_POINTS_X, 3, 15) || !WITHIN(GRID_MAX_POINTS_Y, 3, 15) #error "GRID_MAX_POINTS_[XY] must be a whole number between 3 and 15." - #elif !defined(RESTORE_LEVELING_AFTER_G28) - #error "AUTO_BED_LEVELING_UBL used to enable RESTORE_LEVELING_AFTER_G28. To keep this behavior enable RESTORE_LEVELING_AFTER_G28. Otherwise define it as 'false'." #endif #elif HAS_ABL_NOT_UBL @@ -1438,27 +1690,25 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #elif ENABLED(MESH_BED_LEVELING) - // Hide PROBE_MANUALLY from the rest of the code - #undef PROBE_MANUALLY - - /** - * Mesh Bed Leveling - */ - + // Mesh Bed Leveling #if ENABLED(DELTA) #error "MESH_BED_LEVELING is not compatible with DELTA printers." - #elif GRID_MAX_POINTS_X > 9 || GRID_MAX_POINTS_Y > 9 + #elif (GRID_MAX_POINTS_X) > 9 || (GRID_MAX_POINTS_Y) > 9 #error "GRID_MAX_POINTS_X and GRID_MAX_POINTS_Y must be less than 10 for MBL." #endif #endif +#if ALL(HAS_LEVELING, RESTORE_LEVELING_AFTER_G28, ENABLE_LEVELING_AFTER_G28) + #error "Only enable RESTORE_LEVELING_AFTER_G28 or ENABLE_LEVELING_AFTER_G28, but not both." +#endif + #if HAS_MESH && HAS_CLASSIC_JERK static_assert(DEFAULT_ZJERK > 0.1, "Low DEFAULT_ZJERK values are incompatible with mesh-based leveling."); #endif #if ENABLED(G26_MESH_VALIDATION) - #if !EXTRUDERS + #if !HAS_EXTRUDERS #error "G26_MESH_VALIDATION requires at least one extruder." #elif !HAS_MESH #error "G26_MESH_VALIDATION requires MESH_BED_LEVELING, AUTO_BED_LEVELING_BILINEAR, or AUTO_BED_LEVELING_UBL." @@ -1469,12 +1719,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "MESH_EDIT_GFX_OVERLAY requires AUTO_BED_LEVELING_UBL and a Graphical LCD." #endif -#if ENABLED(G29_RETRY_AND_RECOVER) - #if ENABLED(AUTO_BED_LEVELING_UBL) - #error "G29_RETRY_AND_RECOVER is not compatible with UBL." - #elif ENABLED(MESH_BED_LEVELING) - #error "G29_RETRY_AND_RECOVER is not compatible with MESH_BED_LEVELING." - #endif +#if ENABLED(G29_RETRY_AND_RECOVER) && NONE(AUTO_BED_LEVELING_3POINT, AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_BILINEAR) + #error "G29_RETRY_AND_RECOVER requires AUTO_BED_LEVELING_3POINT, LINEAR, or BILINEAR." #endif /** @@ -1485,17 +1731,69 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "LCD_BED_LEVELING requires a programmable LCD controller." #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." #endif #endif +#if BOTH(PREHEAT_BEFORE_PROBING, PREHEAT_BEFORE_LEVELING) + #error "Disable PREHEAT_BEFORE_LEVELING when using PREHEAT_BEFORE_PROBING." +#endif + /** - * Homing + * Homing checks */ -constexpr float hbm[] = HOMING_BUMP_MM; -static_assert(COUNT(hbm) == XYZ, "HOMING_BUMP_MM requires X, Y, and Z elements."); -static_assert(hbm[X_AXIS] >= 0, "HOMING_BUMP_MM.X must be greater than or equal to 0."); -static_assert(hbm[Y_AXIS] >= 0, "HOMING_BUMP_MM.Y must be greater than or equal to 0."); -static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal to 0."); +#ifndef HOMING_BUMP_MM + #error "Required setting HOMING_BUMP_MM is missing!" +#elif !defined(HOMING_BUMP_DIVISOR) + #error "Required setting HOMING_BUMP_DIVISOR is missing!" +#else + constexpr float hbm[] = HOMING_BUMP_MM, hbd[] = HOMING_BUMP_DIVISOR; + static_assert(COUNT(hbm) == LINEAR_AXES, "HOMING_BUMP_MM must have " _LINEAR_AXES_STR "elements (and no others)."); + LINEAR_AXIS_CODE( + static_assert(hbm[X_AXIS] >= 0, "HOMING_BUMP_MM.X must be greater than or equal to 0."), + static_assert(hbm[Y_AXIS] >= 0, "HOMING_BUMP_MM.Y must be greater than or equal to 0."), + static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal to 0."), + static_assert(hbm[I_AXIS] >= 0, "HOMING_BUMP_MM.I must be greater than or equal to 0."), + static_assert(hbm[J_AXIS] >= 0, "HOMING_BUMP_MM.J must be greater than or equal to 0."), + static_assert(hbm[K_AXIS] >= 0, "HOMING_BUMP_MM.K must be greater than or equal to 0.") + ); + static_assert(COUNT(hbd) == LINEAR_AXES, "HOMING_BUMP_DIVISOR must have " _LINEAR_AXES_STR "elements (and no others)."); + LINEAR_AXIS_CODE( + static_assert(hbd[X_AXIS] >= 1, "HOMING_BUMP_DIVISOR.X must be greater than or equal to 1."), + static_assert(hbd[Y_AXIS] >= 1, "HOMING_BUMP_DIVISOR.Y must be greater than or equal to 1."), + static_assert(hbd[Z_AXIS] >= 1, "HOMING_BUMP_DIVISOR.Z must be greater than or equal to 1."), + static_assert(hbd[I_AXIS] >= 1, "HOMING_BUMP_DIVISOR.I must be greater than or equal to 1."), + static_assert(hbd[J_AXIS] >= 1, "HOMING_BUMP_DIVISOR.J must be greater than or equal to 1."), + static_assert(hbd[K_AXIS] >= 1, "HOMING_BUMP_DIVISOR.K must be greater than or equal to 1.") + ); +#endif + +#ifdef HOMING_BACKOFF_POST_MM + constexpr float hbp[] = HOMING_BACKOFF_POST_MM; + static_assert(COUNT(hbp) == LINEAR_AXES, "HOMING_BACKOFF_POST_MM must have " _LINEAR_AXES_STR "elements (and no others)."); + LINEAR_AXIS_CODE( + static_assert(hbp[X_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.X must be greater than or equal to 0."), + static_assert(hbp[Y_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.Y must be greater than or equal to 0."), + static_assert(hbp[Z_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.Z must be greater than or equal to 0."), + static_assert(hbp[I_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.I must be greater than or equal to 0."), + static_assert(hbp[J_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.J must be greater than or equal to 0."), + static_assert(hbp[K_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.K must be greater than or equal to 0.") + ); +#endif + +#ifdef SENSORLESS_BACKOFF_MM + constexpr float sbm[] = SENSORLESS_BACKOFF_MM; + static_assert(COUNT(sbm) == LINEAR_AXES, "SENSORLESS_BACKOFF_MM must have " _LINEAR_AXES_STR "elements (and no others)."); + LINEAR_AXIS_CODE( + static_assert(sbm[X_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.X must be greater than or equal to 0."), + static_assert(sbm[Y_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.Y must be greater than or equal to 0."), + static_assert(sbm[Z_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.Z must be greater than or equal to 0."), + static_assert(sbm[I_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.I must be greater than or equal to 0."), + static_assert(sbm[J_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.J must be greater than or equal to 0."), + static_assert(sbm[K_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.K must be greater than or equal to 0.") + ); +#endif #if ENABLED(CODEPENDENT_XY_HOMING) #if ENABLED(QUICK_HOME) @@ -1516,9 +1814,9 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal /** * Make sure DISABLE_[XYZ] compatible with selected homing options */ -#if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z) +#if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z, DISABLE_I, DISABLE_J, DISABLE_K) #if EITHER(HOME_AFTER_DEACTIVATE, Z_SAFE_HOMING) - #error "DISABLE_[XYZ] is not compatible with HOME_AFTER_DEACTIVATE or Z_SAFE_HOMING." + #error "DISABLE_[XYZIJK] is not compatible with HOME_AFTER_DEACTIVATE or Z_SAFE_HOMING." #endif #endif @@ -1558,8 +1856,8 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal /** * ULTIPANEL encoder */ -#if ENABLED(ULTIPANEL) && NONE(NEWPANEL, SR_LCD_2W_NL) && !defined(SHIFT_CLK) - #error "ULTIPANEL requires some kind of encoder." +#if IS_ULTIPANEL && NONE(IS_NEWPANEL, SR_LCD_2W_NL) && !PIN_EXISTS(SHIFT_CLK) + #error "ULTIPANEL controllers require some kind of encoder." #endif #if ENCODER_PULSES_PER_STEP < 0 @@ -1581,8 +1879,8 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal * Allen Key * Deploying the Allen Key probe uses big moves in z direction. Too dangerous for an unhomed z-axis. */ -#if ENABLED(Z_PROBE_ALLEN_KEY) && (Z_HOME_DIR < 0) && ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) - #error "You can't home to a z min endstop with a Z_PROBE_ALLEN_KEY." +#if ALL(Z_HOME_TO_MIN, Z_PROBE_ALLEN_KEY, Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) + #error "You can't home to a Z min endstop with a Z_PROBE_ALLEN_KEY." #endif /** @@ -1599,7 +1897,7 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #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_DIR != -1 || X2_HOME_DIR != 1 + #elif X_HOME_TO_MAX || X2_HOME_TO_MIN #error "DUAL_X_CARRIAGE requires X_HOME_DIR -1 and X2_HOME_DIR 1." #endif #endif @@ -1641,12 +1939,20 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #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)) "."); + #endif +#endif + /** * Case Light requirements */ -#if ENABLED(CASE_LIGHT_ENABLE) +#if NEED_CASE_LIGHT_PIN #if !PIN_EXISTS(CASE_LIGHT) - #error "CASE_LIGHT_ENABLE requires CASE_LIGHT_PIN to be defined." + #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." #endif @@ -1655,48 +1961,147 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal /** * Required custom thermistor settings */ -#if ENABLED(HEATER_0_USER_THERMISTOR) && !(defined(HOTEND0_PULLUP_RESISTOR_OHMS) && defined(HOTEND0_RESISTANCE_25C_OHMS) && defined(HOTEND0_BETA)) +#if TEMP_SENSOR_0_IS_CUSTOM && !(defined(HOTEND0_PULLUP_RESISTOR_OHMS) && defined(HOTEND0_RESISTANCE_25C_OHMS) && defined(HOTEND0_BETA)) #error "TEMP_SENSOR_0 1000 requires HOTEND0_PULLUP_RESISTOR_OHMS, HOTEND0_RESISTANCE_25C_OHMS and HOTEND0_BETA in Configuration_adv.h." -#elif ENABLED(HEATER_1_USER_THERMISTOR) && !(defined(HOTEND1_PULLUP_RESISTOR_OHMS) && defined(HOTEND1_RESISTANCE_25C_OHMS) && defined(HOTEND1_BETA)) +#elif TEMP_SENSOR_1_IS_CUSTOM && !(defined(HOTEND1_PULLUP_RESISTOR_OHMS) && defined(HOTEND1_RESISTANCE_25C_OHMS) && defined(HOTEND1_BETA)) #error "TEMP_SENSOR_1 1000 requires HOTEND1_PULLUP_RESISTOR_OHMS, HOTEND1_RESISTANCE_25C_OHMS and HOTEND1_BETA in Configuration_adv.h." -#elif ENABLED(HEATER_2_USER_THERMISTOR) && !(defined(HOTEND2_PULLUP_RESISTOR_OHMS) && defined(HOTEND2_RESISTANCE_25C_OHMS) && defined(HOTEND2_BETA)) +#elif TEMP_SENSOR_2_IS_CUSTOM && !(defined(HOTEND2_PULLUP_RESISTOR_OHMS) && defined(HOTEND2_RESISTANCE_25C_OHMS) && defined(HOTEND2_BETA)) #error "TEMP_SENSOR_2 1000 requires HOTEND2_PULLUP_RESISTOR_OHMS, HOTEND2_RESISTANCE_25C_OHMS and HOTEND2_BETA in Configuration_adv.h." -#elif ENABLED(HEATER_3_USER_THERMISTOR) && !(defined(HOTEND3_PULLUP_RESISTOR_OHMS) && defined(HOTEND3_RESISTANCE_25C_OHMS) && defined(HOTEND3_BETA)) +#elif TEMP_SENSOR_3_IS_CUSTOM && !(defined(HOTEND3_PULLUP_RESISTOR_OHMS) && defined(HOTEND3_RESISTANCE_25C_OHMS) && defined(HOTEND3_BETA)) #error "TEMP_SENSOR_3 1000 requires HOTEND3_PULLUP_RESISTOR_OHMS, HOTEND3_RESISTANCE_25C_OHMS and HOTEND3_BETA in Configuration_adv.h." -#elif ENABLED(HEATER_4_USER_THERMISTOR) && !(defined(HOTEND4_PULLUP_RESISTOR_OHMS) && defined(HOTEND4_RESISTANCE_25C_OHMS) && defined(HOTEND4_BETA)) +#elif TEMP_SENSOR_4_IS_CUSTOM && !(defined(HOTEND4_PULLUP_RESISTOR_OHMS) && defined(HOTEND4_RESISTANCE_25C_OHMS) && defined(HOTEND4_BETA)) #error "TEMP_SENSOR_4 1000 requires HOTEND4_PULLUP_RESISTOR_OHMS, HOTEND4_RESISTANCE_25C_OHMS and HOTEND4_BETA in Configuration_adv.h." -#elif ENABLED(HEATER_5_USER_THERMISTOR) && !(defined(HOTEND5_PULLUP_RESISTOR_OHMS) && defined(HOTEND5_RESISTANCE_25C_OHMS) && defined(HOTEND5_BETA)) +#elif TEMP_SENSOR_5_IS_CUSTOM && !(defined(HOTEND5_PULLUP_RESISTOR_OHMS) && defined(HOTEND5_RESISTANCE_25C_OHMS) && defined(HOTEND5_BETA)) #error "TEMP_SENSOR_5 1000 requires HOTEND5_PULLUP_RESISTOR_OHMS, HOTEND5_RESISTANCE_25C_OHMS and HOTEND5_BETA in Configuration_adv.h." -#elif ENABLED(HEATER_6_USER_THERMISTOR) && !(defined(HOTEND6_PULLUP_RESISTOR_OHMS) && defined(HOTEND6_RESISTANCE_25C_OHMS) && defined(HOTEND6_BETA)) +#elif TEMP_SENSOR_6_IS_CUSTOM && !(defined(HOTEND6_PULLUP_RESISTOR_OHMS) && defined(HOTEND6_RESISTANCE_25C_OHMS) && defined(HOTEND6_BETA)) #error "TEMP_SENSOR_6 1000 requires HOTEND6_PULLUP_RESISTOR_OHMS, HOTEND6_RESISTANCE_25C_OHMS and HOTEND6_BETA in Configuration_adv.h." -#elif ENABLED(HEATER_7_USER_THERMISTOR) && !(defined(HOTEND7_PULLUP_RESISTOR_OHMS) && defined(HOTEND7_RESISTANCE_25C_OHMS) && defined(HOTEND7_BETA)) +#elif TEMP_SENSOR_7_IS_CUSTOM && !(defined(HOTEND7_PULLUP_RESISTOR_OHMS) && defined(HOTEND7_RESISTANCE_25C_OHMS) && defined(HOTEND7_BETA)) #error "TEMP_SENSOR_7 1000 requires HOTEND7_PULLUP_RESISTOR_OHMS, HOTEND7_RESISTANCE_25C_OHMS and HOTEND7_BETA in Configuration_adv.h." -#elif ENABLED(HEATER_BED_USER_THERMISTOR) && !(defined(BED_PULLUP_RESISTOR_OHMS) && defined(BED_RESISTANCE_25C_OHMS) && defined(BED_BETA)) +#elif TEMP_SENSOR_BED_IS_CUSTOM && !(defined(BED_PULLUP_RESISTOR_OHMS) && defined(BED_RESISTANCE_25C_OHMS) && defined(BED_BETA)) #error "TEMP_SENSOR_BED 1000 requires BED_PULLUP_RESISTOR_OHMS, BED_RESISTANCE_25C_OHMS and BED_BETA in Configuration_adv.h." -#elif ENABLED(HEATER_CHAMBER_USER_THERMISTOR) && !(defined(CHAMBER_PULLUP_RESISTOR_OHMS) && defined(CHAMBER_RESISTANCE_25C_OHMS) && defined(CHAMBER_BETA)) +#elif TEMP_SENSOR_CHAMBER_IS_CUSTOM && !(defined(CHAMBER_PULLUP_RESISTOR_OHMS) && defined(CHAMBER_RESISTANCE_25C_OHMS) && defined(CHAMBER_BETA)) #error "TEMP_SENSOR_CHAMBER 1000 requires CHAMBER_PULLUP_RESISTOR_OHMS, CHAMBER_RESISTANCE_25C_OHMS and CHAMBER_BETA in Configuration_adv.h." +#elif TEMP_SENSOR_PROBE_IS_CUSTOM && !(defined(PROBE_PULLUP_RESISTOR_OHMS) && defined(PROBE_RESISTANCE_25C_OHMS) && defined(PROBE_BETA)) + #error "TEMP_SENSOR_PROBE 1000 requires PROBE_PULLUP_RESISTOR_OHMS, PROBE_RESISTANCE_25C_OHMS and PROBE_BETA in Configuration_adv.h." +#elif TEMP_SENSOR_REDUNDANT_IS_CUSTOM && !(defined(REDUNDANT_PULLUP_RESISTOR_OHMS) && defined(REDUNDANT_RESISTANCE_25C_OHMS) && defined(REDUNDANT_BETA)) + #error "TEMP_SENSOR_REDUNDANT 1000 requires REDUNDANT_PULLUP_RESISTOR_OHMS, REDUNDANT_RESISTANCE_25C_OHMS and REDUNDANT_BETA in Configuration_adv.h." +#endif + +/** + * Required MAX31865 settings + */ +#if TEMP_SENSOR_0_IS_MAX31865 || (TEMP_SENSOR_REDUNDANT_IS_MAX31865 && TEMP_SENSOR_REDUNDANT_SOURCE == 0) + #if !defined(MAX31865_SENSOR_WIRES_0) || !WITHIN(MAX31865_SENSOR_WIRES_0, 2, 4) + #error "MAX31865_SENSOR_WIRES_0 must be defined as an integer between 2 and 4." + #elif !defined(MAX31865_SENSOR_OHMS_0) || !defined(MAX31865_CALIBRATION_OHMS_0) + #error "MAX31865_SENSOR_OHMS_0 and MAX31865_CALIBRATION_OHMS_0 must be set if TEMP_SENSOR_0/TEMP_SENSOR_REDUNDANT is MAX31865." + #endif +#endif +#if TEMP_SENSOR_1_IS_MAX31865 || (TEMP_SENSOR_REDUNDANT_IS_MAX31865 && TEMP_SENSOR_REDUNDANT_SOURCE == 1) + #if !defined(MAX31865_SENSOR_WIRES_1) || !WITHIN(MAX31865_SENSOR_WIRES_1, 2, 4) + #error "MAX31865_SENSOR_WIRES_1 must be defined as an integer between 2 and 4." + #elif !defined(MAX31865_SENSOR_OHMS_1) || !defined(MAX31865_CALIBRATION_OHMS_1) + #error "MAX31865_SENSOR_OHMS_1 and MAX31865_CALIBRATION_OHMS_1 must be set if TEMP_SENSOR_1/TEMP_SENSOR_REDUNDANT is MAX31865." + #endif +#endif + +/** + * Redundant temperature sensor config + */ +#if HAS_TEMP_REDUNDANT + #if !defined(TEMP_SENSOR_REDUNDANT_SOURCE) + #error "TEMP_SENSOR_REDUNDANT requires TEMP_SENSOR_REDUNDANT_SOURCE." + #elif !defined(TEMP_SENSOR_REDUNDANT_TARGET) + #error "TEMP_SENSOR_REDUNDANT requires TEMP_SENSOR_REDUNDANT_TARGET." + #elif TEMP_SENSOR_REDUNDANT_SOURCE == TEMP_SENSOR_REDUNDANT_TARGET + #error "TEMP_SENSOR_REDUNDANT_SOURCE can't be the same as TEMP_SENSOR_REDUNDANT_TARGET." + #elif TEMP_SENSOR_REDUNDANT_SOURCE < -5 || TEMP_SENSOR_REDUNDANT_SOURCE > 7 + #error "TEMP_SENSOR_REDUNDANT_SOURCE must be between -5 and 7." + #elif TEMP_SENSOR_REDUNDANT_TARGET < -5 || TEMP_SENSOR_REDUNDANT_TARGET > 7 + #error "TEMP_SENSOR_REDUNDANT_TARGET must be between -5 and 7." + #elif TEMP_SENSOR_REDUNDANT_SOURCE == -3 + #error "TEMP_SENSOR_REDUNDANT_SOURCE can't be -3 (not used)." + #elif TEMP_SENSOR_REDUNDANT_TARGET == -3 + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be -3 (not used)." + #elif HAS_MULTI_HOTEND && TEMP_SENSOR_REDUNDANT_SOURCE < HOTENDS + #error "TEMP_SENSOR_REDUNDANT_SOURCE must be after the last TEMP_SENSOR used with a hotend; you can't use a sensor in the middle of two hotends." + #endif + + #if TEMP_SENSOR_REDUNDANT_SOURCE == 0 && HAS_HOTEND + #error "TEMP_SENSOR_REDUNDANT_SOURCE can not be 0 if a hotend is used. E0 always uses TEMP_SENSOR_0." + #elif TEMP_SENSOR_REDUNDANT_SOURCE == -5 && HAS_TEMP_COOLER + #error "TEMP_SENSOR_REDUNDANT_SOURCE can't be Cooler (-5): TEMP_SENSOR_COOLER has already defined the sensor." + #elif TEMP_SENSOR_REDUNDANT_SOURCE == -4 && HAS_TEMP_PROBE + #error "TEMP_SENSOR_REDUNDANT_SOURCE can't be Probe (-4): TEMP_SENSOR_PROBE has already defined the sensor." + #elif TEMP_SENSOR_REDUNDANT_SOURCE == -2 && HAS_TEMP_CHAMBER + #error "TEMP_SENSOR_REDUNDANT_SOURCE can't be Chamber (-2): TEMP_SENSOR_CHAMBER has already defined the sensor." + #elif TEMP_SENSOR_REDUNDANT_SOURCE == -1 && HAS_TEMP_BED + #error "TEMP_SENSOR_REDUNDANT_SOURCE can't be Bed (-1): TEMP_SENSOR_BED has already defined the sensor." + #endif + + #if TEMP_SENSOR_REDUNDANT_TARGET == 0 && !PIN_EXISTS(TEMP_0) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E0 (0): requires TEMP_0_PIN" + #elif TEMP_SENSOR_REDUNDANT_TARGET == 1 && !PIN_EXISTS(TEMP_1) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E1 (1): requires TEMP_1_PIN" + #elif TEMP_SENSOR_REDUNDANT_TARGET == 2 && !PIN_EXISTS(TEMP_2) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E2 (2): requires TEMP_2_PIN" + #elif TEMP_SENSOR_REDUNDANT_TARGET == 3 && !PIN_EXISTS(TEMP_3) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E3 (3): requires TEMP_3_PIN" + #elif TEMP_SENSOR_REDUNDANT_TARGET == 4 && !PIN_EXISTS(TEMP_4) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E4 (4): requires TEMP_4_PIN" + #elif TEMP_SENSOR_REDUNDANT_TARGET == 5 && !PIN_EXISTS(TEMP_5) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E5 (5): requires TEMP_5_PIN" + #elif TEMP_SENSOR_REDUNDANT_TARGET == 6 && !PIN_EXISTS(TEMP_6) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E6 (6): requires TEMP_6_PIN" + #elif TEMP_SENSOR_REDUNDANT_TARGET == 7 && !PIN_EXISTS(TEMP_7) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E7 (7): requires TEMP_7_PIN" + #elif TEMP_SENSOR_REDUNDANT_TARGET == -1 && !PIN_EXISTS(TEMP_BED) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be Bed (-1): requires TEMP_BED_PIN" + #elif TEMP_SENSOR_REDUNDANT_TARGET == -2 && !PIN_EXISTS(TEMP_CHAMBER) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be Chamber (-2): requires TEMP_CHAMBER_PIN" + #elif TEMP_SENSOR_REDUNDANT_TARGET == -4 && !PIN_EXISTS(TEMP_PROBE) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be Probe (-4): requires TEMP_PROBE_PIN" + #elif TEMP_SENSOR_REDUNDANT_TARGET == -5 && !PIN_EXISTS(TEMP_COOLER) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be Cooler (-5): requires TEMP_COOLER_PIN" + #endif + + #if TEMP_SENSOR_REDUNDANT_IS_MAX_TC && REDUNDANT_TEMP_MATCH(SOURCE, E0) && !PIN_EXISTS(TEMP_0_CS) + #error "TEMP_SENSOR_REDUNDANT MAX Thermocouple with TEMP_SENSOR_REDUNDANT_SOURCE E0 requires TEMP_0_CS_PIN." + #elif TEMP_SENSOR_REDUNDANT_IS_MAX_TC && REDUNDANT_TEMP_MATCH(SOURCE, E1) && !PIN_EXISTS(TEMP_1_CS) + #error "TEMP_SENSOR_REDUNDANT MAX Thermocouple with TEMP_SENSOR_REDUNDANT_SOURCE E1 requires TEMP_1_CS_PIN." + #endif +#endif + +/** + * Test Sensor & Heater pin combos. + * Pins and Sensor IDs must be set for each heater + */ +#if !ANY_PIN(TEMP_0, TEMP_0_CS) + #error "TEMP_0_PIN or TEMP_0_CS_PIN not defined for this board." +#elif !HAS_HEATER_0 && EXTRUDERS + #error "HEATER_0_PIN not defined for this board." +#elif TEMP_SENSOR_0_IS_MAX_TC && !PIN_EXISTS(TEMP_0_CS) + #error "TEMP_SENSOR_0 MAX thermocouple requires TEMP_0_CS_PIN." +#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 + #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 -/** - * A Sensor ID has to be set for each heater - */ - #if HAS_MULTI_HOTEND - #if ENABLED(HEATER_1_USES_MAX6675) && !PIN_EXISTS(MAX6675_SS2) - #error "MAX6675_SS2_PIN (required for TEMP_SENSOR_1) not defined for this board." + #if TEMP_SENSOR_1_IS_MAX_TC && !PIN_EXISTS(TEMP_1_CS) + #error "TEMP_SENSOR_1 MAX thermocouple requires TEMP_1_CS_PIN." #elif TEMP_SENSOR_1 == 0 #error "TEMP_SENSOR_1 is required with 2 or more HOTENDS." - #elif !ANY_PIN(TEMP_1, MAX6675_SS2) - #error "TEMP_1_PIN not defined for this board." - #elif ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - #error "HOTENDS must be 1 with TEMP_SENSOR_1_AS_REDUNDANT." + #elif !ANY_PIN(TEMP_1, TEMP_1_CS) && !TEMP_SENSOR_1_IS_DUMMY + #error "TEMP_1_PIN or TEMP_1_CS_PIN not defined for this board." #endif #if HOTENDS > 2 #if TEMP_SENSOR_2 == 0 #error "TEMP_SENSOR_2 is required with 3 or more HOTENDS." #elif !HAS_HEATER_2 #error "HEATER_2_PIN not defined for this board." - #elif !PIN_EXISTS(TEMP_2) + #elif !PIN_EXISTS(TEMP_2) && !TEMP_SENSOR_2_IS_DUMMY #error "TEMP_2_PIN not defined for this board." #endif #if HOTENDS > 3 @@ -1704,7 +2109,7 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #error "TEMP_SENSOR_3 is required with 4 or more HOTENDS." #elif !HAS_HEATER_3 #error "HEATER_3_PIN not defined for this board." - #elif !PIN_EXISTS(TEMP_3) + #elif !PIN_EXISTS(TEMP_3) && !TEMP_SENSOR_3_IS_DUMMY #error "TEMP_3_PIN not defined for this board." #endif #if HOTENDS > 4 @@ -1712,7 +2117,7 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #error "TEMP_SENSOR_4 is required with 5 or more HOTENDS." #elif !HAS_HEATER_4 #error "HEATER_4_PIN not defined for this board." - #elif !PIN_EXISTS(TEMP_4) + #elif !PIN_EXISTS(TEMP_4) && !TEMP_SENSOR_4_IS_DUMMY #error "TEMP_4_PIN not defined for this board." #endif #if HOTENDS > 5 @@ -1720,7 +2125,7 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #error "TEMP_SENSOR_5 is required with 6 HOTENDS." #elif !HAS_HEATER_5 #error "HEATER_5_PIN not defined for this board." - #elif !PIN_EXISTS(TEMP_5) + #elif !PIN_EXISTS(TEMP_5) && !TEMP_SENSOR_5_IS_DUMMY #error "TEMP_5_PIN not defined for this board." #endif #if HOTENDS > 6 @@ -1728,7 +2133,7 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #error "TEMP_SENSOR_6 is required with 6 HOTENDS." #elif !HAS_HEATER_6 #error "HEATER_6_PIN not defined for this board." - #elif !PIN_EXISTS(TEMP_6) + #elif !PIN_EXISTS(TEMP_6) && !TEMP_SENSOR_6_IS_DUMMY #error "TEMP_6_PIN not defined for this board." #endif #if HOTENDS > 7 @@ -1736,7 +2141,7 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #error "TEMP_SENSOR_7 is required with 7 HOTENDS." #elif !HAS_HEATER_7 #error "HEATER_7_PIN not defined for this board." - #elif !PIN_EXISTS(TEMP_7) + #elif !PIN_EXISTS(TEMP_7) && !TEMP_SENSOR_7_IS_DUMMY #error "TEMP_7_PIN not defined for this board." #endif #elif TEMP_SENSOR_7 != 0 @@ -1787,7 +2192,7 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #elif TEMP_SENSOR_7 != 0 #error "TEMP_SENSOR_7 shouldn't be set with only 2 HOTENDS." #endif -#elif TEMP_SENSOR_1 != 0 && DISABLED(TEMP_SENSOR_1_AS_REDUNDANT) +#elif TEMP_SENSOR_1 != 0 #error "TEMP_SENSOR_1 shouldn't be set with only 1 HOTEND." #elif TEMP_SENSOR_2 != 0 #error "TEMP_SENSOR_2 shouldn't be set with only 1 HOTEND." @@ -1801,25 +2206,50 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #error "TEMP_SENSOR_6 shouldn't be set with only 1 HOTEND." #elif TEMP_SENSOR_7 != 0 #error "TEMP_SENSOR_7 shouldn't be set with only 1 HOTEND." -#endif +#endif // HAS_MULTI_HOTEND +/** + * Pins must be set for temp sensors, with some other feature requirements. + */ #if TEMP_SENSOR_CHAMBER && !PIN_EXISTS(TEMP_CHAMBER) - #error "TEMP_SENSOR_CHAMBER requires TEMP_CHAMBER_PIN. Please add it to your configuration." + #error "TEMP_SENSOR_CHAMBER requires TEMP_CHAMBER_PIN." +#endif + +#if TEMP_SENSOR_COOLER + #if !PIN_EXISTS(TEMP_COOLER) + #error "TEMP_SENSOR_COOLER requires TEMP_COOLER_PIN." + #elif DISABLED(LASER_FEATURE) + #error "TEMP_SENSOR_COOLER requires LASER_FEATURE." + #endif +#endif + +#if TEMP_SENSOR_PROBE + #if !PIN_EXISTS(TEMP_PROBE) + #error "TEMP_SENSOR_PROBE requires TEMP_PROBE_PIN." + #elif !HAS_TEMP_ADC_PROBE + #error "TEMP_PROBE_PIN must be an ADC pin." + #elif DISABLED(FIX_MOUNTED_PROBE) + #error "TEMP_SENSOR_PROBE shouldn't be set without FIX_MOUNTED_PROBE." + #endif +#endif + +#if ENABLED(LASER_COOLANT_FLOW_METER) && !(PIN_EXISTS(FLOWMETER) && ENABLED(LASER_FEATURE)) + #error "LASER_COOLANT_FLOW_METER requires FLOWMETER_PIN and LASER_FEATURE." #endif #if ENABLED(CHAMBER_FAN) && !(defined(CHAMBER_FAN_MODE) && WITHIN(CHAMBER_FAN_MODE, 0, 2)) - #error "CHAMBER_FAN_MODE must be between 0 and 2. Please update your Configuration_adv.h." + #error "CHAMBER_FAN_MODE must be between 0 and 2." #endif #if ENABLED(CHAMBER_VENT) #ifndef CHAMBER_VENT_SERVO_NR - #error "CHAMBER_VENT_SERVO_NR is required for CHAMBER SERVO. Update your Configuration_adv.h." + #error "CHAMBER_VENT_SERVO_NR is required for CHAMBER SERVO." #elif !NUM_SERVOS #error "NUM_SERVOS is required for a Heated Chamber vent servo (CHAMBER_VENT_SERVO_NR)." #elif CHAMBER_VENT_SERVO_NR >= NUM_SERVOS #error "CHAMBER_VENT_SERVO_NR must be smaller than NUM_SERVOS." #elif HAS_Z_SERVO_PROBE && CHAMBER_VENT_SERVO_NR == Z_PROBE_SERVO_NR - #error "CHAMBER SERVO is already used by BLTOUCH. Please change." + #error "CHAMBER SERVO is already used by BLTOUCH." #elif CHAMBER_VENT_SERVO_NR == 0 && !PIN_EXISTS(SERVO0) #error "SERVO0_PIN must be defined for your Heated Chamber vent servo." #elif CHAMBER_VENT_SERVO_NR == 1 && !PIN_EXISTS(SERVO1) @@ -1831,48 +2261,6 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #endif #endif -#if TEMP_SENSOR_PROBE - #if !PIN_EXISTS(TEMP_PROBE) - #error "TEMP_SENSOR_PROBE requires TEMP_PROBE_PIN. Please add it to your configuration." - #elif !HAS_TEMP_ADC_PROBE - #error "TEMP_PROBE_PIN must be an ADC pin." - #elif !ENABLED(FIX_MOUNTED_PROBE) - #error "TEMP_SENSOR_PROBE shouldn't be set without FIX_MOUNTED_PROBE." - #endif -#endif - -#if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) && TEMP_SENSOR_1 == 0 - #error "TEMP_SENSOR_1 is required with TEMP_SENSOR_1_AS_REDUNDANT." -#endif - -#if ENABLED(MAX6675_IS_MAX31865) && (!defined(MAX31865_SENSOR_OHMS) || !defined(MAX31865_CALIBRATION_OHMS)) - #error "MAX31865_SENSOR_OHMS and MAX31865_CALIBRATION_OHMS must be set in Configuration.h when using a MAX31865 temperature sensor." -#endif - -/** - * Test Heater, Temp Sensor, and Extruder Pins - */ -#if !HAS_HEATER_0 && EXTRUDERS - #error "HEATER_0_PIN not defined for this board." -#elif !ANY_PIN(TEMP_0, MAX6675_SS) - #error "TEMP_0_PIN not defined for this board." -#elif ((defined(__AVR_ATmega644P__) || defined(__AVR_ATmega1284P__)) && !PINS_EXIST(E0_STEP, E0_DIR)) - #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." -#endif - -// Pins are required for heaters -#if ENABLED(HEATER_0_USES_MAX6675) && !PIN_EXISTS(MAX6675_SS) - #error "MAX6675_SS_PIN (required for TEMP_SENSOR_0) not defined for this board." -#elif HAS_HOTEND && !HAS_TEMP_HOTEND - #error "TEMP_0_PIN (required for TEMP_SENSOR_0) not defined for this board." -#elif EITHER(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 - /** * Temperature status LEDs */ @@ -1890,7 +2278,7 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal /** * LED Backlight Timeout */ -#if defined(LED_BACKLIGHT_TIMEOUT) && !(ENABLED(PSU_CONTROL) && EITHER(FYSETC_MINI_12864_2_0, FYSETC_MINI_12864_2_1)) +#if defined(LED_BACKLIGHT_TIMEOUT) && !(ENABLED(PSU_CONTROL) && ANY(FYSETC_MINI_12864_2_0, FYSETC_MINI_12864_2_1, FYSETC_242_OLED_12864)) #error "LED_BACKLIGHT_TIMEOUT requires a FYSETC Mini Panel and a Power Switch." #endif @@ -1898,64 +2286,72 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal * Basic multi hotend duplication mode */ #if ENABLED(MULTI_NOZZLE_DUPLICATION) - #if HOTENDS < 2 - #error "MULTI_NOZZLE_DUPLICATION requires 2 or more hotends." + #if ENABLED(SINGLENOZZLE) + #error "MULTI_NOZZLE_DUPLICATION is incompatible with SINGLENOZZLE." #elif ENABLED(DUAL_X_CARRIAGE) #error "MULTI_NOZZLE_DUPLICATION is incompatible with DUAL_X_CARRIAGE." - #elif ENABLED(SINGLENOZZLE) - #error "MULTI_NOZZLE_DUPLICATION is incompatible with SINGLENOZZLE." #elif ENABLED(MIXING_EXTRUDER) #error "MULTI_NOZZLE_DUPLICATION is incompatible with MIXING_EXTRUDER." #elif ENABLED(SWITCHING_EXTRUDER) #error "MULTI_NOZZLE_DUPLICATION is incompatible with SWITCHING_EXTRUDER." + #elif HOTENDS < 2 + #error "MULTI_NOZZLE_DUPLICATION requires 2 or more hotends." #endif #endif /** * Test Extruder Stepper Pins */ -#if DISABLED(MK2_MULTIPLEXER) // MK2_MULTIPLEXER uses E0 stepper only - #if E_STEPPERS - #if !(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." +#if HAS_EXTRUDERS + #if ((defined(__AVR_ATmega644P__) || defined(__AVR_ATmega1284P__)) && !PINS_EXIST(E0_STEP, E0_DIR)) + #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." + #endif +#endif + +#if E_STEPPERS + #if !(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." + #endif + #if E_STEPPERS > 1 + #if !(PINS_EXIST(E1_STEP, E1_DIR) && HAS_E1_ENABLE) + #error "E1_STEP_PIN, E1_DIR_PIN, or E1_ENABLE_PIN not defined for this board." #endif - #if E_STEPPERS > 1 - #if !(PINS_EXIST(E1_STEP, E1_DIR) && HAS_E1_ENABLE) - #error "E1_STEP_PIN, E1_DIR_PIN, or E1_ENABLE_PIN not defined for this board." + #if E_STEPPERS > 2 + #if !(PINS_EXIST(E2_STEP, E2_DIR) && HAS_E2_ENABLE) + #error "E2_STEP_PIN, E2_DIR_PIN, or E2_ENABLE_PIN not defined for this board." #endif - #if E_STEPPERS > 2 - #if !(PINS_EXIST(E2_STEP, E2_DIR) && HAS_E2_ENABLE) - #error "E2_STEP_PIN, E2_DIR_PIN, or E2_ENABLE_PIN not defined for this board." + #if E_STEPPERS > 3 + #if !(PINS_EXIST(E3_STEP, E3_DIR) && HAS_E3_ENABLE) + #error "E3_STEP_PIN, E3_DIR_PIN, or E3_ENABLE_PIN not defined for this board." #endif - #if E_STEPPERS > 3 - #if !(PINS_EXIST(E3_STEP, E3_DIR) && HAS_E3_ENABLE) - #error "E3_STEP_PIN, E3_DIR_PIN, or E3_ENABLE_PIN not defined for this board." + #if E_STEPPERS > 4 + #if !(PINS_EXIST(E4_STEP, E4_DIR) && HAS_E4_ENABLE) + #error "E4_STEP_PIN, E4_DIR_PIN, or E4_ENABLE_PIN not defined for this board." #endif - #if E_STEPPERS > 4 - #if !(PINS_EXIST(E4_STEP, E4_DIR) && HAS_E4_ENABLE) - #error "E4_STEP_PIN, E4_DIR_PIN, or E4_ENABLE_PIN not defined for this board." + #if E_STEPPERS > 5 + #if !(PINS_EXIST(E5_STEP, E5_DIR) && HAS_E5_ENABLE) + #error "E5_STEP_PIN, E5_DIR_PIN, or E5_ENABLE_PIN not defined for this board." #endif - #if E_STEPPERS > 5 - #if !(PINS_EXIST(E5_STEP, E5_DIR) && HAS_E5_ENABLE) - #error "E5_STEP_PIN, E5_DIR_PIN, or E5_ENABLE_PIN not defined for this board." + #if E_STEPPERS > 6 + #if !(PINS_EXIST(E6_STEP, E6_DIR) && HAS_E6_ENABLE) + #error "E6_STEP_PIN, E6_DIR_PIN, or E6_ENABLE_PIN not defined for this board." #endif - #if E_STEPPERS > 6 - #if !(PINS_EXIST(E6_STEP, E6_DIR) && HAS_E6_ENABLE) - #error "E6_STEP_PIN, E6_DIR_PIN, or E6_ENABLE_PIN not defined for this board." + #if E_STEPPERS > 7 + #if !(PINS_EXIST(E7_STEP, E7_DIR) && HAS_E7_ENABLE) + #error "E7_STEP_PIN, E7_DIR_PIN, or E7_ENABLE_PIN not defined for this board." #endif - #if E_STEPPERS > 7 - #if !(PINS_EXIST(E7_STEP, E7_DIR) && HAS_E7_ENABLE) - #error "E7_STEP_PIN, E7_DIR_PIN, or E7_ENABLE_PIN not defined for this board." - #endif - #endif // E_STEPPERS > 7 - #endif // E_STEPPERS > 6 - #endif // E_STEPPERS > 5 - #endif // E_STEPPERS > 4 - #endif // E_STEPPERS > 3 - #endif // E_STEPPERS > 2 - #endif // E_STEPPERS > 1 - #endif // E_STEPPERS -#endif + #endif // E_STEPPERS > 7 + #endif // E_STEPPERS > 6 + #endif // E_STEPPERS > 5 + #endif // E_STEPPERS > 4 + #endif // E_STEPPERS > 3 + #endif // E_STEPPERS > 2 + #endif // E_STEPPERS > 1 +#endif // E_STEPPERS /** * Endstop Tests @@ -1964,142 +2360,94 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #define _PLUG_UNUSED_TEST(A,P) (DISABLED(USE_##P##MIN_PLUG, USE_##P##MAX_PLUG) \ && !(ENABLED(A##_DUAL_ENDSTOPS) && WITHIN(A##2_USE_ENDSTOP, _##P##MAX_, _##P##MIN_)) \ && !(ENABLED(A##_MULTI_ENDSTOPS) && WITHIN(A##2_USE_ENDSTOP, _##P##MAX_, _##P##MIN_)) ) -#define _AXIS_PLUG_UNUSED_TEST(A) (_PLUG_UNUSED_TEST(A,X) && _PLUG_UNUSED_TEST(A,Y) && _PLUG_UNUSED_TEST(A,Z)) - -// At least 3 endstop plugs must be used -#if _AXIS_PLUG_UNUSED_TEST(X) - #error "You must enable USE_XMIN_PLUG or USE_XMAX_PLUG." -#endif -#if _AXIS_PLUG_UNUSED_TEST(Y) - #error "You must enable USE_YMIN_PLUG or USE_YMAX_PLUG." -#endif -#if _AXIS_PLUG_UNUSED_TEST(Z) - #error "You must enable USE_ZMIN_PLUG or USE_ZMAX_PLUG." -#endif +#define _AXIS_PLUG_UNUSED_TEST(A) (1 LINEAR_AXIS_GANG(&& _PLUG_UNUSED_TEST(A,X), && _PLUG_UNUSED_TEST(A,Y), && _PLUG_UNUSED_TEST(A,Z), && _PLUG_UNUSED_TEST(A,I), && _PLUG_UNUSED_TEST(A,J), && _PLUG_UNUSED_TEST(A,K) ) ) + +// A machine with endstops must have a minimum of 3 +#if HAS_ENDSTOPS + #if _AXIS_PLUG_UNUSED_TEST(X) + #error "You must enable USE_XMIN_PLUG or USE_XMAX_PLUG." + #endif + #if _AXIS_PLUG_UNUSED_TEST(Y) + #error "You must enable USE_YMIN_PLUG or USE_YMAX_PLUG." + #endif + #if _AXIS_PLUG_UNUSED_TEST(Z) + #error "You must enable USE_ZMIN_PLUG or USE_ZMAX_PLUG." + #endif + #if LINEAR_AXES >= 4 && _AXIS_PLUG_UNUSED_TEST(I) + #error "You must enable USE_IMIN_PLUG or USE_IMAX_PLUG." + #endif + #if LINEAR_AXES >= 5 && _AXIS_PLUG_UNUSED_TEST(J) + #error "You must enable USE_JMIN_PLUG or USE_JMAX_PLUG." + #endif + #if LINEAR_AXES >= 6 && _AXIS_PLUG_UNUSED_TEST(K) + #error "You must enable USE_KMIN_PLUG or USE_KMAX_PLUG." + #endif + + // Delta and Cartesian use 3 homing endstops + #if NONE(IS_SCARA, SPI_ENDSTOPS) + #if X_HOME_TO_MIN && DISABLED(USE_XMIN_PLUG) + #error "Enable USE_XMIN_PLUG when homing X to MIN." + #elif X_HOME_TO_MAX && DISABLED(USE_XMAX_PLUG) + #error "Enable USE_XMAX_PLUG when homing X to MAX." + #elif Y_HOME_TO_MIN && DISABLED(USE_YMIN_PLUG) + #error "Enable USE_YMIN_PLUG when homing Y to MIN." + #elif Y_HOME_TO_MAX && DISABLED(USE_YMAX_PLUG) + #error "Enable USE_YMAX_PLUG when homing Y to MAX." + #elif LINEAR_AXES >= 4 && I_HOME_TO_MIN && DISABLED(USE_IMIN_PLUG) + #error "Enable USE_IMIN_PLUG when homing I to MIN." + #elif LINEAR_AXES >= 4 && I_HOME_TO_MAX && DISABLED(USE_IMAX_PLUG) + #error "Enable USE_IMAX_PLUG when homing I to MAX." + #elif LINEAR_AXES >= 5 && J_HOME_TO_MIN && DISABLED(USE_JMIN_PLUG) + #error "Enable USE_JMIN_PLUG when homing J to MIN." + #elif LINEAR_AXES >= 5 && J_HOME_TO_MAX && DISABLED(USE_JMAX_PLUG) + #error "Enable USE_JMAX_PLUG when homing J to MAX." + #elif LINEAR_AXES >= 6 && K_HOME_TO_MIN && DISABLED(USE_KMIN_PLUG) + #error "Enable USE_KMIN_PLUG when homing K to MIN." + #elif LINEAR_AXES >= 6 && K_HOME_TO_MAX && DISABLED(USE_KMAX_PLUG) + #error "Enable USE_KMAX_PLUG when homing K to MAX." + #endif + #endif -// Delta and Cartesian use 3 homing endstops -#if !IS_SCARA - #if X_HOME_DIR < 0 && DISABLED(USE_XMIN_PLUG) - #error "Enable USE_XMIN_PLUG when homing X to MIN." - #elif X_HOME_DIR > 0 && DISABLED(USE_XMAX_PLUG) - #error "Enable USE_XMAX_PLUG when homing X to MAX." - #elif Y_HOME_DIR < 0 && DISABLED(USE_YMIN_PLUG) - #error "Enable USE_YMIN_PLUG when homing Y to MIN." - #elif Y_HOME_DIR > 0 && DISABLED(USE_YMAX_PLUG) - #error "Enable USE_YMAX_PLUG when homing Y to MAX." + // Z homing direction and plug usage flags + #if Z_HOME_TO_MIN && NONE(USE_ZMIN_PLUG, HOMING_Z_WITH_PROBE) + #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) + #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 -// Z homing direction and plug usage flags -#if Z_HOME_DIR < 0 && NONE(USE_ZMIN_PLUG, HOMING_Z_WITH_PROBE) - #error "Enable USE_ZMIN_PLUG when homing Z to MIN." -#elif Z_HOME_DIR > 0 && ENABLED(USE_PROBE_FOR_Z_HOMING) - #error "Z_HOME_DIR must be -1 when homing Z with the probe." -#elif Z_HOME_DIR > 0 && DISABLED(USE_ZMAX_PLUG) - #error "Enable USE_ZMAX_PLUG when homing Z to MAX." +#if BOTH(HOME_Z_FIRST, USE_PROBE_FOR_Z_HOMING) + #error "HOME_Z_FIRST can't be used when homing Z with a probe." #endif // Dual/multiple endstops requirements #if ENABLED(X_DUAL_ENDSTOPS) - #if !X2_USE_ENDSTOP - #error "You must set X2_USE_ENDSTOP with X_DUAL_ENDSTOPS." - #elif X2_USE_ENDSTOP == _XMIN_ && DISABLED(USE_XMIN_PLUG) - #error "USE_XMIN_PLUG is required when X2_USE_ENDSTOP is _XMIN_." - #elif X2_USE_ENDSTOP == _XMAX_ && DISABLED(USE_XMAX_PLUG) - #error "USE_XMAX_PLUG is required when X2_USE_ENDSTOP is _XMAX_." - #elif X2_USE_ENDSTOP == _YMIN_ && DISABLED(USE_YMIN_PLUG) - #error "USE_YMIN_PLUG is required when X2_USE_ENDSTOP is _YMIN_." - #elif X2_USE_ENDSTOP == _YMAX_ && DISABLED(USE_YMAX_PLUG) - #error "USE_YMAX_PLUG is required when X2_USE_ENDSTOP is _YMAX_." - #elif X2_USE_ENDSTOP == _ZMIN_ && DISABLED(USE_ZMIN_PLUG) - #error "USE_ZMIN_PLUG is required when X2_USE_ENDSTOP is _ZMIN_." - #elif X2_USE_ENDSTOP == _ZMAX_ && DISABLED(USE_ZMAX_PLUG) - #error "USE_ZMAX_PLUG is required when X2_USE_ENDSTOP is _ZMAX_." - #elif !HAS_X2_MIN && !HAS_X2_MAX - #error "X2_USE_ENDSTOP has been assigned to a nonexistent endstop!" - #elif ENABLED(DELTA) + #if ENABLED(DELTA) #error "X_DUAL_ENDSTOPS is not compatible with DELTA." + #elif !X2_USE_ENDSTOP + #error "X2_USE_ENDSTOP must be set with X_DUAL_ENDSTOPS." #endif #endif #if ENABLED(Y_DUAL_ENDSTOPS) - #if !Y2_USE_ENDSTOP - #error "You must set Y2_USE_ENDSTOP with Y_DUAL_ENDSTOPS." - #elif Y2_USE_ENDSTOP == _XMIN_ && DISABLED(USE_XMIN_PLUG) - #error "USE_XMIN_PLUG is required when Y2_USE_ENDSTOP is _XMIN_." - #elif Y2_USE_ENDSTOP == _XMAX_ && DISABLED(USE_XMAX_PLUG) - #error "USE_XMAX_PLUG is required when Y2_USE_ENDSTOP is _XMAX_." - #elif Y2_USE_ENDSTOP == _YMIN_ && DISABLED(USE_YMIN_PLUG) - #error "USE_YMIN_PLUG is required when Y2_USE_ENDSTOP is _YMIN_." - #elif Y2_USE_ENDSTOP == _YMAX_ && DISABLED(USE_YMAX_PLUG) - #error "USE_YMAX_PLUG is required when Y2_USE_ENDSTOP is _YMAX_." - #elif Y2_USE_ENDSTOP == _ZMIN_ && DISABLED(USE_ZMIN_PLUG) - #error "USE_ZMIN_PLUG is required when Y2_USE_ENDSTOP is _ZMIN_." - #elif Y2_USE_ENDSTOP == _ZMAX_ && DISABLED(USE_ZMAX_PLUG) - #error "USE_ZMAX_PLUG is required when Y2_USE_ENDSTOP is _ZMAX_." - #elif !HAS_Y2_MIN && !HAS_Y2_MAX - #error "Y2_USE_ENDSTOP has been assigned to a nonexistent endstop!" - #elif ENABLED(DELTA) + #if ENABLED(DELTA) #error "Y_DUAL_ENDSTOPS is not compatible with DELTA." + #elif !Y2_USE_ENDSTOP + #error "Y2_USE_ENDSTOP must be set with Y_DUAL_ENDSTOPS." #endif #endif - #if ENABLED(Z_MULTI_ENDSTOPS) - #if !Z2_USE_ENDSTOP - #error "You must set Z2_USE_ENDSTOP with Z_MULTI_ENDSTOPS when NUM_Z_STEPPER_DRIVERS >= 2." - #elif Z2_USE_ENDSTOP == _XMIN_ && DISABLED(USE_XMIN_PLUG) - #error "USE_XMIN_PLUG is required when Z2_USE_ENDSTOP is _XMIN_." - #elif Z2_USE_ENDSTOP == _XMAX_ && DISABLED(USE_XMAX_PLUG) - #error "USE_XMAX_PLUG is required when Z2_USE_ENDSTOP is _XMAX_." - #elif Z2_USE_ENDSTOP == _YMIN_ && DISABLED(USE_YMIN_PLUG) - #error "USE_YMIN_PLUG is required when Z2_USE_ENDSTOP is _YMIN_." - #elif Z2_USE_ENDSTOP == _YMAX_ && DISABLED(USE_YMAX_PLUG) - #error "USE_YMAX_PLUG is required when Z2_USE_ENDSTOP is _YMAX_." - #elif Z2_USE_ENDSTOP == _ZMIN_ && DISABLED(USE_ZMIN_PLUG) - #error "USE_ZMIN_PLUG is required when Z2_USE_ENDSTOP is _ZMIN_." - #elif Z2_USE_ENDSTOP == _ZMAX_ && DISABLED(USE_ZMAX_PLUG) - #error "USE_ZMAX_PLUG is required when Z2_USE_ENDSTOP is _ZMAX_." - #elif !HAS_Z2_MIN && !HAS_Z2_MAX - #error "Z2_USE_ENDSTOP has been assigned to a nonexistent endstop!" - #elif ENABLED(DELTA) + #if ENABLED(DELTA) #error "Z_MULTI_ENDSTOPS is not compatible with DELTA." - #endif - #if NUM_Z_STEPPER_DRIVERS >= 3 - #if !Z3_USE_ENDSTOP - #error "You must set Z3_USE_ENDSTOP with Z_MULTI_ENDSTOPS when NUM_Z_STEPPER_DRIVERS >= 3." - #elif Z3_USE_ENDSTOP == _XMIN_ && DISABLED(USE_XMIN_PLUG) - #error "USE_XMIN_PLUG is required when Z3_USE_ENDSTOP is _XMIN_." - #elif Z3_USE_ENDSTOP == _XMAX_ && DISABLED(USE_XMAX_PLUG) - #error "USE_XMAX_PLUG is required when Z3_USE_ENDSTOP is _XMAX_." - #elif Z3_USE_ENDSTOP == _YMIN_ && DISABLED(USE_YMIN_PLUG) - #error "USE_YMIN_PLUG is required when Z3_USE_ENDSTOP is _YMIN_." - #elif Z3_USE_ENDSTOP == _YMAX_ && DISABLED(USE_YMAX_PLUG) - #error "USE_YMAX_PLUG is required when Z3_USE_ENDSTOP is _YMAX_." - #elif Z3_USE_ENDSTOP == _ZMIN_ && DISABLED(USE_ZMIN_PLUG) - #error "USE_ZMIN_PLUG is required when Z3_USE_ENDSTOP is _ZMIN_." - #elif Z3_USE_ENDSTOP == _ZMAX_ && DISABLED(USE_ZMAX_PLUG) - #error "USE_ZMAX_PLUG is required when Z3_USE_ENDSTOP is _ZMAX_." - #elif !HAS_Z3_MIN && !HAS_Z3_MAX - #error "Z3_USE_ENDSTOP has been assigned to a nonexistent endstop!" - #endif - #endif - #if NUM_Z_STEPPER_DRIVERS >= 4 - #if !Z4_USE_ENDSTOP - #error "You must set Z4_USE_ENDSTOP with Z_MULTI_ENDSTOPS when NUM_Z_STEPPER_DRIVERS >= 4." - #elif Z4_USE_ENDSTOP == _XMIN_ && DISABLED(USE_XMIN_PLUG) - #error "USE_XMIN_PLUG is required when Z4_USE_ENDSTOP is _XMIN_." - #elif Z4_USE_ENDSTOP == _XMAX_ && DISABLED(USE_XMAX_PLUG) - #error "USE_XMAX_PLUG is required when Z4_USE_ENDSTOP is _XMAX_." - #elif Z4_USE_ENDSTOP == _YMIN_ && DISABLED(USE_YMIN_PLUG) - #error "USE_YMIN_PLUG is required when Z4_USE_ENDSTOP is _YMIN_." - #elif Z4_USE_ENDSTOP == _YMAX_ && DISABLED(USE_YMAX_PLUG) - #error "USE_YMAX_PLUG is required when Z4_USE_ENDSTOP is _YMAX_." - #elif Z4_USE_ENDSTOP == _ZMIN_ && DISABLED(USE_ZMIN_PLUG) - #error "USE_ZMIN_PLUG is required when Z4_USE_ENDSTOP is _ZMIN_." - #elif Z4_USE_ENDSTOP == _ZMAX_ && DISABLED(USE_ZMAX_PLUG) - #error "USE_ZMAX_PLUG is required when Z4_USE_ENDSTOP is _ZMAX_." - #elif !HAS_Z4_MIN && !HAS_Z4_MAX - #error "Z4_USE_ENDSTOP has been assigned to a nonexistent endstop!" - #endif + #elif !Z2_USE_ENDSTOP + #error "Z2_USE_ENDSTOP must be set with Z_MULTI_ENDSTOPS." + #elif !Z3_USE_ENDSTOP && NUM_Z_STEPPER_DRIVERS >= 3 + #error "Z3_USE_ENDSTOP must be set with Z_MULTI_ENDSTOPS and NUM_Z_STEPPER_DRIVERS >= 3." + #elif !Z4_USE_ENDSTOP && NUM_Z_STEPPER_DRIVERS >= 4 + #error "Z4_USE_ENDSTOP must be set with Z_MULTI_ENDSTOPS and NUM_Z_STEPPER_DRIVERS >= 4." #endif #endif @@ -2110,10 +2458,20 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal /** * Emergency Command Parser */ -#if BOTH(IS_AT90USB, EMERGENCY_PARSER) +#if ENABLED(EMERGENCY_PARSER) && defined(__AVR__) && defined(USBCON) #error "EMERGENCY_PARSER does not work on boards with AT90USB processors (USBCON)." #endif +/** + * Software Reset options + */ +#if ENABLED(SOFT_RESET_VIA_SERIAL) && DISABLED(EMERGENCY_PARSER) + #error "EMERGENCY_PARSER is required to activate SOFT_RESET_VIA_SERIAL." +#endif +#if ENABLED(SOFT_RESET_ON_KILL) && !BUTTON_EXISTS(ENC) + #error "An encoder button is required or SOFT_RESET_ON_KILL will reset the printer without notice!" +#endif + /** * I2C bus */ @@ -2233,109 +2591,166 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #endif #endif +#if ENABLED(SD_IGNORE_AT_STARTUP) + #if ENABLED(POWER_LOSS_RECOVERY) + #error "SD_IGNORE_AT_STARTUP is incompatible with POWER_LOSS_RECOVERY." + #elif ENABLED(SDCARD_EEPROM_EMULATION) + #error "SD_IGNORE_AT_STARTUP is incompatible with SDCARD_EEPROM_EMULATION." + #endif +#endif + /** * Make sure only one display is enabled */ #if 1 < 0 \ - + (ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) && DISABLED(IS_RRD_SC)) \ - + (ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) && DISABLED(IS_RRD_FG_SC)) \ - + (ENABLED(ULTRA_LCD) && DISABLED(IS_ULTRA_LCD)) \ + + ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) \ + + ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) \ + (ENABLED(U8GLIB_SSD1306) && DISABLED(IS_U8GLIB_SSD1306)) \ + (ENABLED(MINIPANEL) && NONE(MKS_MINI_12864, ENDER2_STOCKDISPLAY)) \ - + (ENABLED(MKS_MINI_12864) && DISABLED(MKS_LCD12864)) \ + + (ENABLED(MKS_MINI_12864) && NONE(MKS_LCD12864A, MKS_LCD12864B)) \ + (ENABLED(EXTENSIBLE_UI) && DISABLED(IS_EXTUI)) \ - + (ENABLED(ULTIPANEL) && DISABLED(IS_ULTIPANEL)) \ - + ENABLED(RADDS_DISPLAY) \ - + ENABLED(ULTIMAKERCONTROLLER) \ - + ENABLED(PANEL_ONE) \ + + (DISABLED(IS_LEGACY_TFT) && ENABLED(TFT_GENERIC)) \ + + (ENABLED(IS_LEGACY_TFT) && COUNT_ENABLED(TFT_320x240, TFT_320x240_SPI, TFT_480x320, TFT_480x320_SPI)) \ + + COUNT_ENABLED(ANYCUBIC_LCD_I3MEGA, ANYCUBIC_LCD_CHIRON, ANYCUBIC_TFT35) \ + + COUNT_ENABLED(DGUS_LCD_UI_ORIGIN, DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_HIPRECY, DGUS_LCD_UI_MKS) \ + + COUNT_ENABLED(ENDER2_STOCKDISPLAY, CR10_STOCKDISPLAY, DWIN_CREALITY_LCD) \ + + COUNT_ENABLED(FYSETC_MINI_12864_X_X, FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0, FYSETC_MINI_12864_2_1, FYSETC_GENERIC_12864_1_1) \ + + COUNT_ENABLED(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) \ + + COUNT_ENABLED(TFTGLCD_PANEL_SPI, TFTGLCD_PANEL_I2C) \ + + COUNT_ENABLED(VIKI2, miniVIKI) \ + + COUNT_ENABLED(ZONESTAR_12864LCD, ZONESTAR_12864OLED, ZONESTAR_12864OLED_SSD1306) \ + + COUNT_ENABLED(ANET_FULL_GRAPHICS_LCD, ANET_FULL_GRAPHICS_LCD_ALT_WIRING) \ + + ENABLED(AZSMZ_12864) \ + + ENABLED(BQ_LCD_SMART_CONTROLLER) \ + + ENABLED(CARTESIO_UI) \ + + ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) \ + + ENABLED(FF_INTERFACEBOARD) \ + + ENABLED(FYSETC_242_OLED_12864) \ + ENABLED(G3D_PANEL) \ - + ENABLED(RIGIDBOT_PANEL) \ - + ENABLED(MAKEBOARD_MINI_2_LINE_DISPLAY_1602) \ - + ENABLED(ZONESTAR_LCD) \ - + ENABLED(RA_CONTROL_PANEL) \ - + ENABLED(LCD_SAINSMART_I2C_1602) \ - + ENABLED(LCD_SAINSMART_I2C_2004) \ - + ENABLED(LCM1602) \ + + ENABLED(LCD_FOR_MELZI) \ + ENABLED(LCD_I2C_PANELOLU2) \ + ENABLED(LCD_I2C_VIKI) \ - + ENABLED(SAV_3DLCD) \ - + ENABLED(FF_INTERFACEBOARD) \ - + ENABLED(REPRAPWORLD_GRAPHICAL_LCD) \ - + ENABLED(VIKI2) \ - + ENABLED(miniVIKI) \ + + ENABLED(LCM1602) \ + + ENABLED(LONGER_LK_TFT28) \ + + ENABLED(MAKEBOARD_MINI_2_LINE_DISPLAY_1602) \ + ENABLED(MAKRPANEL) \ - + ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) \ - + ENABLED(BQ_LCD_SMART_CONTROLLER) \ - + ENABLED(CARTESIO_UI) \ - + ENABLED(LCD_FOR_MELZI) \ - + ENABLED(ULTI_CONTROLLER) \ - + ENABLED(MKS_LCD12864) \ - + ENABLED(ENDER2_STOCKDISPLAY) \ - + ENABLED(FYSETC_MINI_12864_X_X) \ - + ENABLED(FYSETC_MINI_12864_1_2) \ - + ENABLED(FYSETC_MINI_12864_2_0) \ - + ENABLED(FYSETC_MINI_12864_2_1) \ - + ENABLED(FYSETC_GENERIC_12864_1_1) \ - + ENABLED(CR10_STOCKDISPLAY) \ - + ENABLED(DWIN_CREALITY_LCD) \ - + ENABLED(ANET_FULL_GRAPHICS_LCD) \ - + ENABLED(AZSMZ_12864) \ - + ENABLED(SILVER_GATE_GLCD_CONTROLLER) \ - + ENABLED(SAV_3DGLCD) \ + + ENABLED(MALYAN_LCD) \ + + ENABLED(NEXTION_TFT) \ + + ENABLED(MKS_LCD12864A) \ + + ENABLED(MKS_LCD12864B) \ + ENABLED(OLED_PANEL_TINYBOY2) \ - + ENABLED(MKS_12864OLED) \ - + ENABLED(MKS_12864OLED_SSD1306) \ - + ENABLED(ZONESTAR_12864LCD) \ - + ENABLED(ZONESTAR_12864OLED) \ - + ENABLED(ZONESTAR_12864OLED_SSD1306) \ - + ENABLED(U8GLIB_SH1106_EINSTART) \ + ENABLED(OVERLORD_OLED) \ - + ENABLED(FYSETC_242_OLED_12864) \ - + ENABLED(DGUS_LCD_UI_ORIGIN) \ - + ENABLED(DGUS_LCD_UI_FYSETC) \ - + ENABLED(DGUS_LCD_UI_HIPRECY) \ - + ENABLED(MALYAN_LCD) \ + + ENABLED(PANEL_ONE) \ + + ENABLED(RA_CONTROL_PANEL) \ + + ENABLED(RADDS_DISPLAY) \ + + ENABLED(REPRAPWORLD_GRAPHICAL_LCD) \ + + ENABLED(RIGIDBOT_PANEL) \ + + ENABLED(SAV_3DGLCD) \ + + ENABLED(SAV_3DLCD) \ + + ENABLED(SILVER_GATE_GLCD_CONTROLLER) \ + + ENABLED(TFT_TRONXY_X5SA) \ + ENABLED(TOUCH_UI_FTDI_EVE) \ - + ENABLED(TFT_320x240) \ - + ENABLED(TFT_320x240_SPI) \ - + ENABLED(FSMC_GRAPHICAL_TFT) \ - + ENABLED(TFT_LVGL_UI_FSMC) \ - + ENABLED(TFT_LVGL_UI_SPI) \ - + ENABLED(ANYCUBIC_LCD_I3MEGA) \ - + ENABLED(ANYCUBIC_LCD_CHIRON) \ - + ENABLED(TFTGLCD_PANEL_SPI) \ - + ENABLED(TFTGLCD_PANEL_I2C) + + ENABLED(U8GLIB_SH1106_EINSTART) \ + + ENABLED(ULTI_CONTROLLER) \ + + ENABLED(ULTIMAKERCONTROLLER) \ + + ENABLED(ULTIPANEL) \ + + ENABLED(ULTRA_LCD) \ + + ENABLED(YHCB2004) \ + + ENABLED(ZONESTAR_LCD) \ + + ENABLED(K3D_FULL_GRAPHIC_SMART_CONTROLLER) \ + + ENABLED(K3D_242_OLED_CONTROLLER) #error "Please select only one LCD controller option." #endif -#undef IS_RRD_SC -#undef IS_RRD_FG_SC -#undef IS_ULTRA_LCD #undef IS_U8GLIB_SSD1306 -#undef IS_RRW_KEYPAD #undef IS_EXTUI -#undef IS_ULTIPANEL +#undef IS_LEGACY_TFT + +#if ANY(TFT_GENERIC, MKS_TS35_V2_0, MKS_ROBIN_TFT24, MKS_ROBIN_TFT28, MKS_ROBIN_TFT32, MKS_ROBIN_TFT35, MKS_ROBIN_TFT43, MKS_ROBIN_TFT_V1_1R, TFT_TRONXY_X5SA, ANYCUBIC_TFT35, ANYCUBIC_TFT35, LONGER_LK_TFT28, ANET_ET4_TFT28, ANET_ET5_TFT35, BIQU_BX_TFT70) + #if NONE(TFT_COLOR_UI, TFT_CLASSIC_UI, TFT_LVGL_UI) + #error "TFT_COLOR_UI, TFT_CLASSIC_UI, TFT_LVGL_UI is required for your TFT. Please enable one." + #elif 1 < ENABLED(TFT_COLOR_UI) + ENABLED(TFT_CLASSIC_UI) + ENABLED(TFT_LVGL_UI) + #error "Please select only one of TFT_COLOR_UI, TFT_CLASSIC_UI, or TFT_LVGL_UI." + #endif +#elif ANY(TFT_COLOR_UI, TFT_CLASSIC_UI, TFT_LVGL_UI) + #error "TFT_(COLOR|CLASSIC|LVGL)_UI requires a TFT display to be enabled." +#endif + +#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 1 < ENABLED(LCD_SCREEN_ROT_0) + ENABLED(LCD_SCREEN_ROT_90) + ENABLED(LCD_SCREEN_ROT_180) + ENABLED(LCD_SCREEN_ROT_270) +#if BOTH(TFT_INTERFACE_FSMC, TFT_INTERFACE_SPI) + #error "Please enable only one of TFT_INTERFACE_SPI or TFT_INTERFACE_SPI." +#endif + +#if MANY(LCD_SCREEN_ROT_0, LCD_SCREEN_ROT_90, LCD_SCREEN_ROT_180, LCD_SCREEN_ROT_270) #error "Please enable only one LCD_SCREEN_ROT_* option: 0, 90, 180, or 270." #endif +#if MANY(TFT_RES_320x240, TFT_RES_480x272, TFT_RES_480x320, TFT_RES_1024x600) + #error "Please select only one of TFT_RES_320x240, TFT_RES_480x272, TFT_RES_480x320, or TFT_RES_1024x600." +#endif + +#if HAS_TFT_LVGL_UI && DISABLED(TFT_RES_480x320) + #error "(FMSC|SPI)TFT_LVGL_UI requires TFT_RES_480x320." +#endif + +#if defined(GRAPHICAL_TFT_UPSCALE) && !WITHIN(GRAPHICAL_TFT_UPSCALE, 2, 4) + #error "GRAPHICAL_TFT_UPSCALE must be 2, 3, or 4." +#endif + +#if BOTH(CHIRON_TFT_STANDARD, CHIRON_TFT_NEW) + #error "Please select only one of CHIRON_TFT_STANDARD or CHIRON_TFT_NEW." +#endif + +/** + * Some boards forbid the use of -1 Native USB + */ +#if ENABLED(BOARD_NO_NATIVE_USB) + #undef BOARD_NO_NATIVE_USB + #if SERIAL_PORT == -1 + #error "SERIAL_PORT is set to -1, but the MOTHERBOARD has no native USB support. Set SERIAL_PORT to a valid value for your board." + #elif SERIAL_PORT_2 == -1 + #error "SERIAL_PORT_2 is set to -1, but the MOTHERBOARD has no native USB support. Set SERIAL_PORT_2 to a valid value for your board." + #elif MMU2_SERIAL_PORT == -1 + #error "MMU2_SERIAL_PORT is set to -1, but the MOTHERBOARD has no native USB support. Set MMU2_SERIAL_PORT to a valid value for your board." + #elif LCD_SERIAL_PORT == -1 + #error "LCD_SERIAL_PORT is set to -1, but the MOTHERBOARD has no native USB support. Set LCD_SERIAL_PORT to a valid value for your board." + #endif +#endif + +/** + * MMU2 require a dedicated serial port + */ +#ifdef MMU2_SERIAL_PORT + #if MMU2_SERIAL_PORT == SERIAL_PORT + #error "MMU2_SERIAL_PORT cannot be the same as SERIAL_PORT." + #elif defined(SERIAL_PORT_2) && MMU2_SERIAL_PORT == SERIAL_PORT_2 + #error "MMU2_SERIAL_PORT cannot be the same as SERIAL_PORT_2." + #elif defined(LCD_SERIAL_PORT) && MMU2_SERIAL_PORT == LCD_SERIAL_PORT + #error "MMU2_SERIAL_PORT cannot be the same as LCD_SERIAL_PORT." + #endif +#endif + /** * Serial displays require a dedicated serial port */ #ifdef LCD_SERIAL_PORT #if LCD_SERIAL_PORT == SERIAL_PORT - #error "LCD_SERIAL_PORT cannot be the same as SERIAL_PORT. Please update your configuration." + #error "LCD_SERIAL_PORT cannot be the same as SERIAL_PORT." #elif defined(SERIAL_PORT_2) && LCD_SERIAL_PORT == SERIAL_PORT_2 - #error "LCD_SERIAL_PORT cannot be the same as SERIAL_PORT_2. Please update your configuration." + #error "LCD_SERIAL_PORT cannot be the same as SERIAL_PORT_2." #endif #else #if HAS_DGUS_LCD - #error "The DGUS LCD requires LCD_SERIAL_PORT to be defined in Configuration.h" + #error "The DGUS LCD requires LCD_SERIAL_PORT to be defined." #elif EITHER(ANYCUBIC_LCD_I3MEGA, ANYCUBIC_LCD_CHIRON) - #error "The ANYCUBIC LCD requires LCD_SERIAL_PORT to be defined in Configuration.h" + #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 in Configuration.h" + #error "MALYAN_LCD requires LCD_SERIAL_PORT to be defined." #endif #endif @@ -2384,6 +2799,12 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #error "An SPI driven TMC driver on E6 requires E6_CS_PIN." #elif INVALID_TMC_SPI(E7) #error "An SPI driven TMC driver on E7 requires E7_CS_PIN." +#elif INVALID_TMC_SPI(I) + #error "An SPI driven TMC on I requires I_CS_PIN." +#elif INVALID_TMC_SPI(J) + #error "An SPI driven TMC on J requires J_CS_PIN." +#elif INVALID_TMC_SPI(K) + #error "An SPI driven TMC on K requires K_CS_PIN." #endif #undef INVALID_TMC_SPI @@ -2423,6 +2844,12 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #error "TMC2208 or TMC2209 on E6 requires E6_HARDWARE_SERIAL or E6_SERIAL_(RX|TX)_PIN." #elif INVALID_TMC_UART(E7) #error "TMC2208 or TMC2209 on E7 requires E7_HARDWARE_SERIAL or E7_SERIAL_(RX|TX)_PIN." +#elif LINEAR_AXES >= 4 && INVALID_TMC_UART(I) + #error "TMC2208 or TMC2209 on I requires I_HARDWARE_SERIAL or I_SERIAL_(RX|TX)_PIN." +#elif LINEAR_AXES >= 5 && INVALID_TMC_UART(J) + #error "TMC2208 or TMC2209 on J requires J_HARDWARE_SERIAL or J_SERIAL_(RX|TX)_PIN." +#elif LINEAR_AXES >= 6 && INVALID_TMC_UART(K) + #error "TMC2208 or TMC2209 on K requires K_HARDWARE_SERIAL or K_SERIAL_(RX|TX)_PIN." #endif #undef INVALID_TMC_UART @@ -2446,6 +2873,12 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal INVALID_TMC_ADDRESS(Z3); #elif AXIS_DRIVER_TYPE_Z4(TMC2209) INVALID_TMC_ADDRESS(Z4); +#elif AXIS_DRIVER_TYPE_I(TMC2209) + INVALID_TMC_ADDRESS(I); +#elif AXIS_DRIVER_TYPE_J(TMC2209) + INVALID_TMC_ADDRESS(J); +#elif AXIS_DRIVER_TYPE_K(TMC2209) + INVALID_TMC_ADDRESS(K); #elif AXIS_DRIVER_TYPE_E0(TMC2209) INVALID_TMC_ADDRESS(E0); #elif AXIS_DRIVER_TYPE_E1(TMC2209) @@ -2501,6 +2934,12 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal INVALID_TMC_MS(E6) #elif !TMC_MICROSTEP_IS_VALID(E7) INVALID_TMC_MS(E7) +#elif LINEAR_AXES >= 4 && !TMC_MICROSTEP_IS_VALID(I) + INVALID_TMC_MS(I) +#elif LINEAR_AXES >= 5 && !TMC_MICROSTEP_IS_VALID(J) + INVALID_TMC_MS(J) +#elif LINEAR_AXES >= 6 && !TMC_MICROSTEP_IS_VALID(K) + INVALID_TMC_MS(K) #endif #undef INVALID_TMC_MS #undef TMC_MICROSTEP_IS_VALID @@ -2521,57 +2960,120 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #define X_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(X,TMC2209) #define Y_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(Y,TMC2209) #define Z_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(Z,TMC2209) - - #if ENABLED(DELTA) && !BOTH(STEALTHCHOP_XY, STEALTHCHOP_Z) - #error "SENSORLESS_HOMING on DELTA currently requires STEALTHCHOP_XY and STEALTHCHOP_Z." - #elif X_SENSORLESS && X_HOME_DIR < 0 && NONE(ONBOARD_ENDSTOPPULLUPS, ENDSTOPPULLUPS, ENDSTOPPULLUP_XMIN) - #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_XMIN (or ENDSTOPPULLUPS) when homing to X_MIN." - #elif X_SENSORLESS && X_HOME_DIR > 0 && NONE(ONBOARD_ENDSTOPPULLUPS, ENDSTOPPULLUPS, ENDSTOPPULLUP_XMAX) - #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_XMAX (or ENDSTOPPULLUPS) when homing to X_MAX." - #elif Y_SENSORLESS && Y_HOME_DIR < 0 && NONE(ONBOARD_ENDSTOPPULLUPS, ENDSTOPPULLUPS, ENDSTOPPULLUP_YMIN) - #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_YMIN (or ENDSTOPPULLUPS) when homing to Y_MIN." - #elif Y_SENSORLESS && Y_HOME_DIR > 0 && NONE(ONBOARD_ENDSTOPPULLUPS, ENDSTOPPULLUPS, ENDSTOPPULLUP_YMAX) - #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_YMAX (or ENDSTOPPULLUPS) when homing to Y_MAX." - #elif Z_SENSORLESS && Z_HOME_DIR < 0 && NONE(ONBOARD_ENDSTOPPULLUPS, ENDSTOPPULLUPS, ENDSTOPPULLUP_ZMIN) - #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_ZMIN (or ENDSTOPPULLUPS) when homing to Z_MIN." - #elif Z_SENSORLESS && Z_HOME_DIR > 0 && NONE(ONBOARD_ENDSTOPPULLUPS, ENDSTOPPULLUPS, ENDSTOPPULLUP_ZMAX) - #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_ZMAX (or ENDSTOPPULLUPS) when homing to Z_MAX." - #elif X_SENSORLESS && X_HOME_DIR < 0 && X_MIN_ENDSTOP_INVERTING != X_ENDSTOP_INVERTING - #if X_ENDSTOP_INVERTING - #error "SENSORLESS_HOMING requires X_MIN_ENDSTOP_INVERTING = true when homing to X_MIN." - #else - #error "SENSORLESS_HOMING requires X_MIN_ENDSTOP_INVERTING = false when homing TMC2209 to X_MIN." + #if LINEAR_AXES >= 4 + #define I_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(I,TMC2209) + #endif + #if LINEAR_AXES >= 5 + #define J_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(J,TMC2209) + #endif + #if LINEAR_AXES >= 6 + #define K_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(K,TMC2209) + #endif + + #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." + #elif X_SENSORLESS && X_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_XMAX) + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_XMAX (or ENDSTOPPULLUPS) when homing to X_MAX." + #elif Y_SENSORLESS && Y_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_YMIN) + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_YMIN (or ENDSTOPPULLUPS) when homing to Y_MIN." + #elif Y_SENSORLESS && Y_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_YMAX) + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_YMAX (or ENDSTOPPULLUPS) when homing to Y_MAX." + #elif Z_SENSORLESS && Z_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_ZMIN) + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_ZMIN (or ENDSTOPPULLUPS) when homing to Z_MIN." + #elif Z_SENSORLESS && Z_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_ZMAX) + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_ZMAX (or ENDSTOPPULLUPS) when homing to Z_MAX." + #elif LINEAR_AXES >= 4 && I_SENSORLESS && I_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_IMAX) + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_IMAX (or ENDSTOPPULLUPS) when homing to I_MAX." + #elif LINEAR_AXES >= 5 && J_SENSORLESS && J_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_JMAX) + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_JMAX (or ENDSTOPPULLUPS) when homing to J_MAX." + #elif LINEAR_AXES >= 6 && K_SENSORLESS && K_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_KMAX) + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_KMAX (or ENDSTOPPULLUPS) when homing to K_MAX." #endif - #elif X_SENSORLESS && X_HOME_DIR > 0 && X_MAX_ENDSTOP_INVERTING != X_ENDSTOP_INVERTING - #if X_ENDSTOP_INVERTING - #error "SENSORLESS_HOMING requires X_MAX_ENDSTOP_INVERTING = true when homing to X_MAX." - #else - #error "SENSORLESS_HOMING requires X_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to X_MAX." - #endif - #elif Y_SENSORLESS && Y_HOME_DIR < 0 && Y_MIN_ENDSTOP_INVERTING != Y_ENDSTOP_INVERTING - #if Y_ENDSTOP_INVERTING - #error "SENSORLESS_HOMING requires Y_MIN_ENDSTOP_INVERTING = true when homing to Y_MIN." - #else - #error "SENSORLESS_HOMING requires Y_MIN_ENDSTOP_INVERTING = false when homing TMC2209 to Y_MIN." - #endif - #elif Y_SENSORLESS && Y_HOME_DIR > 0 && Y_MAX_ENDSTOP_INVERTING != Y_ENDSTOP_INVERTING - #if Y_ENDSTOP_INVERTING - #error "SENSORLESS_HOMING requires Y_MAX_ENDSTOP_INVERTING = true when homing to Y_MAX." - #else - #error "SENSORLESS_HOMING requires Y_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to Y_MAX." - #endif - #elif Z_SENSORLESS && Z_HOME_DIR < 0 && Z_MIN_ENDSTOP_INVERTING != Z_ENDSTOP_INVERTING - #if Z_ENDSTOP_INVERTING - #error "SENSORLESS_HOMING requires Z_MIN_ENDSTOP_INVERTING = true when homing to Z_MIN." - #else - #error "SENSORLESS_HOMING requires Z_MIN_ENDSTOP_INVERTING = false when homing TMC2209 to Z_MIN." + #endif + + #if ENABLED(SPI_ENDSTOPS) + #if ENABLED(QUICK_HOME) + #warning "SPI_ENDSTOPS may be unreliable with QUICK_HOME. Adjust back-offs for better results." #endif - #elif Z_SENSORLESS && Z_HOME_DIR > 0 && Z_MAX_ENDSTOP_INVERTING != Z_ENDSTOP_INVERTING - #if Z_ENDSTOP_INVERTING - #error "SENSORLESS_HOMING requires Z_MAX_ENDSTOP_INVERTING = true when homing to Z_MAX." - #else - #error "SENSORLESS_HOMING requires Z_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to Z_MAX." + #else + #if X_SENSORLESS && X_HOME_TO_MIN && X_MIN_ENDSTOP_INVERTING != X_ENDSTOP_INVERTING + #if X_ENDSTOP_INVERTING + #error "SENSORLESS_HOMING requires X_MIN_ENDSTOP_INVERTING = true when homing to X_MIN." + #else + #error "SENSORLESS_HOMING requires X_MIN_ENDSTOP_INVERTING = false when homing TMC2209 to X_MIN." + #endif + #elif X_SENSORLESS && X_HOME_TO_MAX && X_MAX_ENDSTOP_INVERTING != X_ENDSTOP_INVERTING + #if X_ENDSTOP_INVERTING + #error "SENSORLESS_HOMING requires X_MAX_ENDSTOP_INVERTING = true when homing to X_MAX." + #else + #error "SENSORLESS_HOMING requires X_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to X_MAX." + #endif + #elif Y_SENSORLESS && Y_HOME_TO_MIN && Y_MIN_ENDSTOP_INVERTING != Y_ENDSTOP_INVERTING + #if Y_ENDSTOP_INVERTING + #error "SENSORLESS_HOMING requires Y_MIN_ENDSTOP_INVERTING = true when homing to Y_MIN." + #else + #error "SENSORLESS_HOMING requires Y_MIN_ENDSTOP_INVERTING = false when homing TMC2209 to Y_MIN." + #endif + #elif Y_SENSORLESS && Y_HOME_TO_MAX && Y_MAX_ENDSTOP_INVERTING != Y_ENDSTOP_INVERTING + #if Y_ENDSTOP_INVERTING + #error "SENSORLESS_HOMING requires Y_MAX_ENDSTOP_INVERTING = true when homing to Y_MAX." + #else + #error "SENSORLESS_HOMING requires Y_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to Y_MAX." + #endif + #elif Z_SENSORLESS && Z_HOME_TO_MIN && Z_MIN_ENDSTOP_INVERTING != Z_ENDSTOP_INVERTING + #if Z_ENDSTOP_INVERTING + #error "SENSORLESS_HOMING requires Z_MIN_ENDSTOP_INVERTING = true when homing to Z_MIN." + #else + #error "SENSORLESS_HOMING requires Z_MIN_ENDSTOP_INVERTING = false when homing TMC2209 to Z_MIN." + #endif + #elif Z_SENSORLESS && Z_HOME_TO_MAX && Z_MAX_ENDSTOP_INVERTING != Z_ENDSTOP_INVERTING + #if Z_ENDSTOP_INVERTING + #error "SENSORLESS_HOMING requires Z_MAX_ENDSTOP_INVERTING = true when homing to Z_MAX." + #else + #error "SENSORLESS_HOMING requires Z_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to Z_MAX." + #endif + #elif LINEAR_AXES >= 4 && I_SENSORLESS && I_HOME_TO_MIN && I_MIN_ENDSTOP_INVERTING != I_ENDSTOP_INVERTING + #if I_ENDSTOP_INVERTING + #error "SENSORLESS_HOMING requires I_MIN_ENDSTOP_INVERTING = true when homing to I_MIN." + #else + #error "SENSORLESS_HOMING requires I_MIN_ENDSTOP_INVERTING = false when homing TMC2209 to I_MIN." + #endif + #elif LINEAR_AXES >= 4 && I_SENSORLESS && I_HOME_TO_MAX && I_MAX_ENDSTOP_INVERTING != I_ENDSTOP_INVERTING + #if I_ENDSTOP_INVERTING + #error "SENSORLESS_HOMING requires I_MAX_ENDSTOP_INVERTING = true when homing to I_MAX." + #else + #error "SENSORLESS_HOMING requires I_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to I_MAX." + #endif + #elif LINEAR_AXES >= 5 && J_SENSORLESS && J_HOME_TO_MIN && J_MIN_ENDSTOP_INVERTING != J_ENDSTOP_INVERTING + #if J_ENDSTOP_INVERTING + #error "SENSORLESS_HOMING requires J_MIN_ENDSTOP_INVERTING = true when homing to J_MIN." + #else + #error "SENSORLESS_HOMING requires J_MIN_ENDSTOP_INVERTING = false when homing TMC2209 to J_MIN." + #endif + #elif LINEAR_AXES >= 5 && J_SENSORLESS && J_HOME_TO_MAX && J_MAX_ENDSTOP_INVERTING != J_ENDSTOP_INVERTING + #if J_ENDSTOP_INVERTING + #error "SENSORLESS_HOMING requires J_MAX_ENDSTOP_INVERTING = true when homing to J_MAX." + #else + #error "SENSORLESS_HOMING requires J_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to J_MAX." + #endif + #elif LINEAR_AXES >= 6 && K_SENSORLESS && K_HOME_TO_MIN && K_MIN_ENDSTOP_INVERTING != K_ENDSTOP_INVERTING + #if K_ENDSTOP_INVERTING + #error "SENSORLESS_HOMING requires K_MIN_ENDSTOP_INVERTING = true when homing to K_MIN." + #else + #error "SENSORLESS_HOMING requires K_MIN_ENDSTOP_INVERTING = false when homing TMC2209 to K_MIN." + #endif + #elif LINEAR_AXES >= 6 && K_SENSORLESS && K_HOME_TO_MAX && K_MAX_ENDSTOP_INVERTING != K_ENDSTOP_INVERTING + #if K_ENDSTOP_INVERTING + #error "SENSORLESS_HOMING requires K_MAX_ENDSTOP_INVERTING = true when homing to K_MAX." + #else + #error "SENSORLESS_HOMING requires K_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to K_MAX." + #endif #endif + #endif + + #if ENABLED(DELTA) && !BOTH(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." #elif !(X_SENSORLESS || Y_SENSORLESS || Z_SENSORLESS) @@ -2581,12 +3083,19 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #undef X_ENDSTOP_INVERTING #undef Y_ENDSTOP_INVERTING #undef Z_ENDSTOP_INVERTING + #undef I_ENDSTOP_INVERTING + #undef J_ENDSTOP_INVERTING + #undef K_ENDSTOP_INVERTING #endif // Sensorless probing requirements #if ENABLED(SENSORLESS_PROBING) #if ENABLED(DELTA) && !(X_SENSORLESS && Y_SENSORLESS && Z_SENSORLESS) #error "SENSORLESS_PROBING for DELTA requires TMC stepper drivers with StallGuard on X, Y, and Z axes." + #elif ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) + #error "SENSORLESS_PROBING cannot be used with Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN." + #elif ENABLED(USE_PROBE_FOR_Z_HOMING) + #error "SENSORLESS_PROBING cannot be used with USE_PROBE_FOR_Z_HOMING." #elif !Z_SENSORLESS #error "SENSORLESS_PROBING requires a TMC stepper driver with StallGuard on Z." #endif @@ -2639,6 +3148,12 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #define CS_COMPARE Z2_CS_PIN #elif IN_CHAIN(Z3) #define CS_COMPARE Z3_CS_PIN + #elif IN_CHAIN(I) + #define CS_COMPARE I_CS_PIN + #elif IN_CHAIN(J) + #define CS_COMPARE J_CS_PIN + #elif IN_CHAIN(K) + #define CS_COMPARE K_CS_PIN #elif IN_CHAIN(E0) #define CS_COMPARE E0_CS_PIN #elif IN_CHAIN(E1) @@ -2658,6 +3173,7 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #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(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 @@ -2668,13 +3184,20 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #endif #undef IN_CHAIN +/** + * L64XX requirement + */ +#if HAS_L64XX && LINEAR_AXES >= 4 + #error "L64XX requires LINEAR_AXES 3. Homing with L64XX is not yet implemented for LINEAR_AXES > 3." +#endif + /** * Digipot requirement */ #if HAS_MOTOR_CURRENT_I2C #if BOTH(DIGIPOT_MCP4018, DIGIPOT_MCP4451) #error "Enable only one of DIGIPOT_MCP4018 or DIGIPOT_MCP4451." - #elif !MB(MKS_SBASE) \ +#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)) #error "DIGIPOT_MCP4018/4451 requires DIGIPOTS_I2C_SDA_* pins to be defined." #endif @@ -2685,36 +3208,48 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal */ constexpr float sanity_arr_1[] = DEFAULT_AXIS_STEPS_PER_UNIT, sanity_arr_2[] = DEFAULT_MAX_FEEDRATE, - sanity_arr_3[] = DEFAULT_MAX_ACCELERATION; + sanity_arr_3[] = DEFAULT_MAX_ACCELERATION, + sanity_arr_7[] = HOMING_FEEDRATE_MM_M; #define _ARR_TEST(N,I) (sanity_arr_##N[_MIN(I,int(COUNT(sanity_arr_##N))-1)] > 0) +#if HAS_MULTI_EXTRUDER + #define _EXTRA_NOTE " (Did you forget to enable DISTINCT_E_FACTORS?)" +#else + #define _EXTRA_NOTE " (Should be " STRINGIFY(LINEAR_AXES) "+" STRINGIFY(E_STEPPERS) ")" +#endif -static_assert(COUNT(sanity_arr_1) >= XYZE, "DEFAULT_AXIS_STEPS_PER_UNIT requires X, Y, Z and E elements."); -static_assert(COUNT(sanity_arr_1) <= XYZE_N, "DEFAULT_AXIS_STEPS_PER_UNIT has too many elements. (Did you forget to enable DISTINCT_E_FACTORS?)"); +static_assert(COUNT(sanity_arr_1) >= LOGICAL_AXES, "DEFAULT_AXIS_STEPS_PER_UNIT requires " _LOGICAL_AXES_STR "elements."); +static_assert(COUNT(sanity_arr_1) <= DISTINCT_AXES, "DEFAULT_AXIS_STEPS_PER_UNIT has too many elements." _EXTRA_NOTE); static_assert( _ARR_TEST(1,0) && _ARR_TEST(1,1) && _ARR_TEST(1,2) && _ARR_TEST(1,3) && _ARR_TEST(1,4) && _ARR_TEST(1,5) && _ARR_TEST(1,6) && _ARR_TEST(1,7) && _ARR_TEST(1,8), "DEFAULT_AXIS_STEPS_PER_UNIT values must be positive."); -static_assert(COUNT(sanity_arr_2) >= XYZE, "DEFAULT_MAX_FEEDRATE requires X, Y, Z and E elements."); -static_assert(COUNT(sanity_arr_2) <= XYZE_N, "DEFAULT_MAX_FEEDRATE has too many elements. (Did you forget to enable DISTINCT_E_FACTORS?)"); +static_assert(COUNT(sanity_arr_2) >= LOGICAL_AXES, "DEFAULT_MAX_FEEDRATE requires " _LOGICAL_AXES_STR "elements."); +static_assert(COUNT(sanity_arr_2) <= DISTINCT_AXES, "DEFAULT_MAX_FEEDRATE has too many elements." _EXTRA_NOTE); static_assert( _ARR_TEST(2,0) && _ARR_TEST(2,1) && _ARR_TEST(2,2) && _ARR_TEST(2,3) && _ARR_TEST(2,4) && _ARR_TEST(2,5) && _ARR_TEST(2,6) && _ARR_TEST(2,7) && _ARR_TEST(2,8), "DEFAULT_MAX_FEEDRATE values must be positive."); -static_assert(COUNT(sanity_arr_3) >= XYZE, "DEFAULT_MAX_ACCELERATION requires X, Y, Z and E elements."); -static_assert(COUNT(sanity_arr_3) <= XYZE_N, "DEFAULT_MAX_ACCELERATION has too many elements. (Did you forget to enable DISTINCT_E_FACTORS?)"); +static_assert(COUNT(sanity_arr_3) >= LOGICAL_AXES, "DEFAULT_MAX_ACCELERATION requires " _LOGICAL_AXES_STR "elements."); +static_assert(COUNT(sanity_arr_3) <= DISTINCT_AXES, "DEFAULT_MAX_ACCELERATION has too many elements." _EXTRA_NOTE); static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) && _ARR_TEST(3,3) && _ARR_TEST(3,4) && _ARR_TEST(3,5) && _ARR_TEST(3,6) && _ARR_TEST(3,7) && _ARR_TEST(3,8), "DEFAULT_MAX_ACCELERATION values must be positive."); +static_assert(COUNT(sanity_arr_7) == LINEAR_AXES, "HOMING_FEEDRATE_MM_M requires " _LINEAR_AXES_STR "elements (and no others)."); +static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) + && _ARR_TEST(3,3) && _ARR_TEST(3,4) && _ARR_TEST(3,5) + && _ARR_TEST(3,6) && _ARR_TEST(3,7) && _ARR_TEST(3,8), + "HOMING_FEEDRATE_MM_M values must be positive."); + #if ENABLED(LIMITED_MAX_ACCEL_EDITING) #ifdef MAX_ACCEL_EDIT_VALUES constexpr float sanity_arr_4[] = MAX_ACCEL_EDIT_VALUES; - static_assert(COUNT(sanity_arr_4) >= XYZE, "MAX_ACCEL_EDIT_VALUES requires X, Y, Z and E elements."); - static_assert(COUNT(sanity_arr_4) <= XYZE, "MAX_ACCEL_EDIT_VALUES has too many elements. X, Y, Z and E elements only."); + static_assert(COUNT(sanity_arr_4) >= LOGICAL_AXES, "MAX_ACCEL_EDIT_VALUES requires " _LOGICAL_AXES_STR "elements."); + static_assert(COUNT(sanity_arr_4) <= LOGICAL_AXES, "MAX_ACCEL_EDIT_VALUES has too many elements. " _LOGICAL_AXES_STR "elements only."); static_assert( _ARR_TEST(4,0) && _ARR_TEST(4,1) && _ARR_TEST(4,2) && _ARR_TEST(4,3) && _ARR_TEST(4,4) && _ARR_TEST(4,5) && _ARR_TEST(4,6) && _ARR_TEST(4,7) && _ARR_TEST(4,8), @@ -2725,8 +3260,8 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #if ENABLED(LIMITED_MAX_FR_EDITING) #ifdef MAX_FEEDRATE_EDIT_VALUES constexpr float sanity_arr_5[] = MAX_FEEDRATE_EDIT_VALUES; - static_assert(COUNT(sanity_arr_5) >= XYZE, "MAX_FEEDRATE_EDIT_VALUES requires X, Y, Z and E elements."); - static_assert(COUNT(sanity_arr_5) <= XYZE, "MAX_FEEDRATE_EDIT_VALUES has too many elements. X, Y, Z and E elements only."); + static_assert(COUNT(sanity_arr_5) >= LOGICAL_AXES, "MAX_FEEDRATE_EDIT_VALUES requires " _LOGICAL_AXES_STR "elements."); + static_assert(COUNT(sanity_arr_5) <= LOGICAL_AXES, "MAX_FEEDRATE_EDIT_VALUES has too many elements. " _LOGICAL_AXES_STR "elements only."); static_assert( _ARR_TEST(5,0) && _ARR_TEST(5,1) && _ARR_TEST(5,2) && _ARR_TEST(5,3) && _ARR_TEST(5,4) && _ARR_TEST(5,5) && _ARR_TEST(5,6) && _ARR_TEST(5,7) && _ARR_TEST(5,8), @@ -2737,8 +3272,8 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #if ENABLED(LIMITED_JERK_EDITING) #ifdef MAX_JERK_EDIT_VALUES constexpr float sanity_arr_6[] = MAX_JERK_EDIT_VALUES; - static_assert(COUNT(sanity_arr_6) >= XYZE, "MAX_JERK_EDIT_VALUES requires X, Y, Z and E elements."); - static_assert(COUNT(sanity_arr_6) <= XYZE, "MAX_JERK_EDIT_VALUES has too many elements. X, Y, Z and E elements only."); + static_assert(COUNT(sanity_arr_6) >= LOGICAL_AXES, "MAX_JERK_EDIT_VALUES requires " _LOGICAL_AXES_STR "elements."); + static_assert(COUNT(sanity_arr_6) <= LOGICAL_AXES, "MAX_JERK_EDIT_VALUES has too many elements. " _LOGICAL_AXES_STR "elements only."); static_assert( _ARR_TEST(6,0) && _ARR_TEST(6,1) && _ARR_TEST(6,2) && _ARR_TEST(6,3) && _ARR_TEST(6,4) && _ARR_TEST(6,5) && _ARR_TEST(6,6) && _ARR_TEST(6,7) && _ARR_TEST(6,8), @@ -2747,6 +3282,7 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #endif #undef _ARR_TEST +#undef _EXTRA_NOTE #if BOTH(CNC_COORDINATE_SYSTEMS, NO_WORKSPACE_OFFSETS) #error "CNC_COORDINATE_SYSTEMS is incompatible with NO_WORKSPACE_OFFSETS." @@ -2754,9 +3290,11 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #if !BLOCK_BUFFER_SIZE || !IS_POWER_OF_2(BLOCK_BUFFER_SIZE) #error "BLOCK_BUFFER_SIZE must be a power of 2." +#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 -#if ENABLED(LED_CONTROL_MENU) && DISABLED(ULTIPANEL) +#if ENABLED(LED_CONTROL_MENU) && !IS_ULTIPANEL #error "LED_CONTROL_MENU requires an LCD controller." #endif @@ -2778,8 +3316,18 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #endif #endif -#if ENABLED(BACKUP_POWER_SUPPLY) && !PIN_EXISTS(POWER_LOSS) - #error "BACKUP_POWER_SUPPLY requires a POWER_LOSS_PIN." +#if ENABLED(POWER_LOSS_RECOVERY) + #if ENABLED(BACKUP_POWER_SUPPLY) && !PIN_EXISTS(POWER_LOSS) + #error "BACKUP_POWER_SUPPLY requires a POWER_LOSS_PIN." + #elif BOTH(POWER_LOSS_RECOVER_ZHOME, Z_SAFE_HOMING) + #error "POWER_LOSS_RECOVER_ZHOME cannot be used with Z_SAFE_HOMING." + #elif BOTH(POWER_LOSS_PULLUP, POWER_LOSS_PULLDOWN) + #error "You can't enable POWER_LOSS_PULLUP and POWER_LOSS_PULLDOWN at the same time." + #elif ENABLED(POWER_LOSS_RECOVER_ZHOME) && Z_HOME_TO_MAX + #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) + #error "POWER_LOSS_RECOVER_ZHOME requires POWER_LOSS_ZHOME_POS for a Cartesian that homes to ZMIN." + #endif #endif #if ENABLED(Z_STEPPER_AUTO_ALIGN) @@ -2787,8 +3335,11 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #error "Z_STEPPER_AUTO_ALIGN requires NUM_Z_STEPPER_DRIVERS greater than 1." #elif !HAS_BED_PROBE #error "Z_STEPPER_AUTO_ALIGN requires a Z-bed probe." - #elif ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) && NUM_Z_STEPPER_DRIVERS < 3 - #error "Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS requires NUM_Z_STEPPER_DRIVERS to be 3 or 4." + #elif ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) + static_assert(WITHIN(Z_STEPPER_ALIGN_AMP, 0.5, 2.0), "Z_STEPPER_ALIGN_AMP must be between 0.5 and 2.0."); + #if NUM_Z_STEPPER_DRIVERS < 3 + #error "Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS requires NUM_Z_STEPPER_DRIVERS to be 3 or 4." + #endif #endif #endif @@ -2801,6 +3352,10 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #error "MECHANICAL_GANTRY_CALIBRATION Requires GANTRY_CALIBRATION_EXTRA_HEIGHT to be set." #elif !defined(GANTRY_CALIBRATION_FEEDRATE) #error "MECHANICAL_GANTRY_CALIBRATION Requires GANTRY_CALIBRATION_FEEDRATE to be set." + #elif ENABLED(Z_MULTI_ENDSTOPS) + #error "Sorry! MECHANICAL_GANTRY_CALIBRATION cannot be used with Z_MULTI_ENDSTOPS." + #elif ENABLED(Z_STEPPER_AUTO_ALIGN) + #error "Sorry! MECHANICAL_GANTRY_CALIBRATION cannot be used with Z_STEPPER_AUTO_ALIGN." #endif #if defined(GANTRY_CALIBRATION_SAFE_POSITION) && !defined(GANTRY_CALIBRATION_XY_PARK_FEEDRATE) #error "GANTRY_CALIBRATION_SAFE_POSITION Requires GANTRY_CALIBRATION_XY_PARK_FEEDRATE to be set." @@ -2812,13 +3367,17 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #endif #if ENABLED(PRINTCOUNTER) && DISABLED(EEPROM_SETTINGS) - #error "PRINTCOUNTER requires EEPROM_SETTINGS. Please update your Configuration." + #error "PRINTCOUNTER requires EEPROM_SETTINGS." #endif -#if ENABLED(USB_FLASH_DRIVE_SUPPORT) && !PINS_EXIST(USB_CS, USB_INTR) +#if ENABLED(USB_FLASH_DRIVE_SUPPORT) && !PINS_EXIST(USB_CS, USB_INTR) && DISABLED(USE_OTG_USB_HOST) #error "USB_CS_PIN and USB_INTR_PIN are required for USB_FLASH_DRIVE_SUPPORT." #endif +#if ENABLED(USE_OTG_USB_HOST) && !defined(HAS_OTG_USB_HOST_SUPPORT) + #error "The current board does not support USE_OTG_USB_HOST." +#endif + #if ENABLED(SD_FIRMWARE_UPDATE) && !defined(__AVR_ATmega2560__) #error "SD_FIRMWARE_UPDATE requires an ATmega2560-based (Arduino Mega) board." #endif @@ -2827,109 +3386,6 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #error "GCODE_MACROS_SLOTS must be a number from 1 to 10." #endif -#if ENABLED(CUSTOM_USER_MENUS) - #ifdef USER_GCODE_1 - constexpr char _chr1 = USER_GCODE_1[strlen(USER_GCODE_1) - 1]; - static_assert(_chr1 != '\n' && _chr1 != '\r', "USER_GCODE_1 cannot have a newline at the end. Please remove it."); - #endif - #ifdef USER_GCODE_2 - constexpr char _chr2 = USER_GCODE_2[strlen(USER_GCODE_2) - 1]; - static_assert(_chr2 != '\n' && _chr2 != '\r', "USER_GCODE_2 cannot have a newline at the end. Please remove it."); - #endif - #ifdef USER_GCODE_3 - constexpr char _chr3 = USER_GCODE_3[strlen(USER_GCODE_3) - 1]; - static_assert(_chr3 != '\n' && _chr3 != '\r', "USER_GCODE_3 cannot have a newline at the end. Please remove it."); - #endif - #ifdef USER_GCODE_4 - constexpr char _chr4 = USER_GCODE_4[strlen(USER_GCODE_4) - 1]; - static_assert(_chr4 != '\n' && _chr4 != '\r', "USER_GCODE_4 cannot have a newline at the end. Please remove it."); - #endif - #ifdef USER_GCODE_5 - constexpr char _chr5 = USER_GCODE_5[strlen(USER_GCODE_5) - 1]; - static_assert(_chr5 != '\n' && _chr5 != '\r', "USER_GCODE_5 cannot have a newline at the end. Please remove it."); - #endif - #ifdef USER_GCODE_6 - constexpr char _chr6 = USER_GCODE_6[strlen(USER_GCODE_6) - 1]; - static_assert(_chr6 != '\n' && _chr6 != '\r', "USER_GCODE_6 cannot have a newline at the end. Please remove it."); - #endif - #ifdef USER_GCODE_7 - constexpr char _chr7 = USER_GCODE_7[strlen(USER_GCODE_7) - 1]; - static_assert(_chr7 != '\n' && _chr7 != '\r', "USER_GCODE_7 cannot have a newline at the end. Please remove it."); - #endif - #ifdef USER_GCODE_8 - constexpr char _chr8 = USER_GCODE_8[strlen(USER_GCODE_8) - 1]; - static_assert(_chr8 != '\n' && _chr8 != '\r', "USER_GCODE_8 cannot have a newline at the end. Please remove it."); - #endif - #ifdef USER_GCODE_9 - constexpr char _chr9 = USER_GCODE_9[strlen(USER_GCODE_9) - 1]; - static_assert(_chr9 != '\n' && _chr9 != '\r', "USER_GCODE_9 cannot have a newline at the end. Please remove it."); - #endif - #ifdef USER_GCODE_10 - constexpr char _chr10 = USER_GCODE_10[strlen(USER_GCODE_10) - 1]; - static_assert(_chr10 != '\n' && _chr10 != '\r', "USER_GCODE_10 cannot have a newline at the end. Please remove it."); - #endif - #ifdef USER_GCODE_11 - constexpr char _chr11 = USER_GCODE_11[strlen(USER_GCODE_11) - 1]; - static_assert(_chr11 != '\n' && _chr11 != '\r', "USER_GCODE_11 cannot have a newline at the end. Please remove it."); - #endif - #ifdef USER_GCODE_12 - constexpr char _chr12 = USER_GCODE_12[strlen(USER_GCODE_12) - 1]; - static_assert(_chr12 != '\n' && _chr12 != '\r', "USER_GCODE_12 cannot have a newline at the end. Please remove it."); - #endif - #ifdef USER_GCODE_13 - constexpr char _chr13 = USER_GCODE_13[strlen(USER_GCODE_13) - 1]; - static_assert(_chr13 != '\n' && _chr13 != '\r', "USER_GCODE_13 cannot have a newline at the end. Please remove it."); - #endif - #ifdef USER_GCODE_14 - constexpr char _chr14 = USER_GCODE_14[strlen(USER_GCODE_14) - 1]; - static_assert(_chr14 != '\n' && _chr14 != '\r', "USER_GCODE_14 cannot have a newline at the end. Please remove it."); - #endif - #ifdef USER_GCODE_15 - constexpr char _chr15 = USER_GCODE_15[strlen(USER_GCODE_15) - 1]; - static_assert(_chr15 != '\n' && _chr15 != '\r', "USER_GCODE_15 cannot have a newline at the end. Please remove it."); - #endif - #ifdef USER_GCODE_16 - constexpr char _chr16 = USER_GCODE_16[strlen(USER_GCODE_16) - 1]; - static_assert(_chr16 != '\n' && _chr16 != '\r', "USER_GCODE_16 cannot have a newline at the end. Please remove it."); - #endif - #ifdef USER_GCODE_17 - constexpr char _chr17 = USER_GCODE_17[strlen(USER_GCODE_17) - 1]; - static_assert(_chr17 != '\n' && _chr17 != '\r', "USER_GCODE_17 cannot have a newline at the end. Please remove it."); - #endif - #ifdef USER_GCODE_18 - constexpr char _chr18 = USER_GCODE_18[strlen(USER_GCODE_18) - 1]; - static_assert(_chr18 != '\n' && _chr18 != '\r', "USER_GCODE_18 cannot have a newline at the end. Please remove it."); - #endif - #ifdef USER_GCODE_19 - constexpr char _chr19 = USER_GCODE_19[strlen(USER_GCODE_19) - 1]; - static_assert(_chr19 != '\n' && _chr19 != '\r', "USER_GCODE_19 cannot have a newline at the end. Please remove it."); - #endif - #ifdef USER_GCODE_20 - constexpr char _chr20 = USER_GCODE_20[strlen(USER_GCODE_20) - 1]; - static_assert(_chr20 != '\n' && _chr20 != '\r', "USER_GCODE_20 cannot have a newline at the end. Please remove it."); - #endif - #ifdef USER_GCODE_21 - constexpr char _chr21 = USER_GCODE_21[strlen(USER_GCODE_21) - 1]; - static_assert(_chr21 != '\n' && _chr21 != '\r', "USER_GCODE_21 cannot have a newline at the end. Please remove it."); - #endif - #ifdef USER_GCODE_22 - constexpr char _chr22 = USER_GCODE_22[strlen(USER_GCODE_22) - 1]; - static_assert(_chr22 != '\n' && _chr22 != '\r', "USER_GCODE_22 cannot have a newline at the end. Please remove it."); - #endif - #ifdef USER_GCODE_23 - constexpr char _chr23 = USER_GCODE_23[strlen(USER_GCODE_23) - 1]; - static_assert(_chr23 != '\n' && _chr23 != '\r', "USER_GCODE_23 cannot have a newline at the end. Please remove it."); - #endif - #ifdef USER_GCODE_24 - constexpr char _chr24 = USER_GCODE_24[strlen(USER_GCODE_24) - 1]; - static_assert(_chr24 != '\n' && _chr24 != '\r', "USER_GCODE_24 cannot have a newline at the end. Please remove it."); - #endif - #ifdef USER_GCODE_25 - constexpr char _chr25 = USER_GCODE_25[strlen(USER_GCODE_25) - 1]; - static_assert(_chr25 != '\n' && _chr25 != '\r', "USER_GCODE_25 cannot have a newline at the end. Please remove it."); - #endif -#endif - #if ENABLED(BACKLASH_COMPENSATION) #ifndef BACKLASH_DISTANCE_MM #error "BACKLASH_COMPENSATION requires BACKLASH_DISTANCE_MM." @@ -2941,8 +3397,10 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) "BACKLASH_COMPENSATION can only apply to " STRINGIFY(NORMAL_AXIS) " on a MarkForged system."); #elif IS_CORE constexpr float backlash_arr[] = BACKLASH_DISTANCE_MM; - static_assert(!backlash_arr[CORE_AXIS_1] && !backlash_arr[CORE_AXIS_2], + #ifndef CORE_BACKLASH + static_assert(!backlash_arr[CORE_AXIS_1] && !backlash_arr[CORE_AXIS_2], "BACKLASH_COMPENSATION can only apply to " STRINGIFY(NORMAL_AXIS) " with your CORE system."); + #endif #endif #endif @@ -2957,33 +3415,16 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #if (PIN_EXISTS(CHDK) + PIN_EXISTS(PHOTOGRAPH) + defined(PHOTO_SWITCH_POSITION)) > 1 #error "Please define only one of CHDK_PIN, PHOTOGRAPH_PIN, or PHOTO_SWITCH_POSITION." #elif defined(PHOTO_SWITCH_POSITION) && !defined(PHOTO_POSITION) - #error "PHOTO_SWITCH_POSITION requires PHOTO_POSITION. Please update your Configuration_adv.h." + #error "PHOTO_SWITCH_POSITION requires PHOTO_POSITION." #elif PIN_EXISTS(CHDK) && defined(CHDK_DELAY) - #error "CHDK_DELAY has been replaced by PHOTO_SWITCH_MS. Please update your Configuration_adv.h." + #error "CHDK_DELAY has been replaced by PHOTO_SWITCH_MS." #elif PIN_EXISTS(CHDK) && !defined(PHOTO_SWITCH_MS) - #error "PHOTO_SWITCH_MS is required with CHDK_PIN. Please update your Configuration_adv.h." + #error "PHOTO_SWITCH_MS is required with CHDK_PIN." #elif defined(PHOTO_RETRACT_MM) static_assert(PHOTO_RETRACT_MM + 0 >= 0, "PHOTO_RETRACT_MM must be >= 0."); #endif #endif -/** - * Průša MMU2 requirements - */ -#if ENABLED(PRUSA_MMU2) - #if EXTRUDERS != 5 - #error "PRUSA_MMU2 requires EXTRUDERS = 5." - #elif DISABLED(NOZZLE_PARK_FEATURE) - #error "PRUSA_MMU2 requires NOZZLE_PARK_FEATURE. Enable it to continue." - #elif EITHER(PRUSA_MMU2_S_MODE, MMU_EXTRUDER_SENSOR) && DISABLED(FILAMENT_RUNOUT_SENSOR) - #error "PRUSA_MMU2_S_MODE or MMU_EXTRUDER_SENSOR requires FILAMENT_RUNOUT_SENSOR. Enable it to continue." - #elif BOTH(PRUSA_MMU2_S_MODE, MMU_EXTRUDER_SENSOR) - #error "Enable only one of PRUSA_MMU2_S_MODE or MMU_EXTRUDER_SENSOR." - #elif DISABLED(ADVANCED_PAUSE_FEATURE) - static_assert(nullptr == strstr(MMU2_FILAMENT_RUNOUT_SCRIPT, "M600"), "ADVANCED_PAUSE_FEATURE is required to use M600 with PRUSA_MMU2."); - #endif -#endif - /** * Advanced PRINTCOUNTER settings */ @@ -3016,23 +3457,23 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #error "PSU_CONTROL requires PSU_ACTIVE_STATE to be defined as 'HIGH' or 'LOW'." #elif !PIN_EXISTS(PS_ON) #error "PSU_CONTROL requires PS_ON_PIN." + #elif POWER_OFF_DELAY < 0 + #error "POWER_OFF_DELAY must be a positive value." #endif -#elif ENABLED(AUTO_POWER_CONTROL) - #error "AUTO_POWER_CONTROL requires PSU_CONTROL." #endif #if HAS_CUTTER #ifndef CUTTER_POWER_UNIT - #error "CUTTER_POWER_UNIT is required with a spindle or laser. Please update your Configuration_adv.h." - #elif !CUTTER_UNIT_IS(PWM255) && !CUTTER_UNIT_IS(PERCENT) && !CUTTER_UNIT_IS(RPM) - #error "CUTTER_POWER_UNIT must be PWM255, PERCENT, or RPM. Please update your Configuration_adv.h." + #error "CUTTER_POWER_UNIT is required with a spindle or laser." + #elif !CUTTER_UNIT_IS(PWM255) && !CUTTER_UNIT_IS(PERCENT) && !CUTTER_UNIT_IS(RPM) && !CUTTER_UNIT_IS(SERVO) + #error "CUTTER_POWER_UNIT must be PWM255, PERCENT, RPM, or SERVO." #endif #if ENABLED(LASER_POWER_INLINE) #if ENABLED(SPINDLE_CHANGE_DIR) #error "SPINDLE_CHANGE_DIR and LASER_POWER_INLINE are incompatible." #elif ENABLED(LASER_MOVE_G0_OFF) && DISABLED(LASER_MOVE_POWER) - #error "LASER_MOVE_G0_OFF requires LASER_MOVE_POWER. Please update your Configuration_adv.h." + #error "LASER_MOVE_G0_OFF requires LASER_MOVE_POWER." #endif #if ENABLED(LASER_POWER_INLINE_TRAPEZOID) #if DISABLED(SPINDLE_LASER_PWM) @@ -3064,8 +3505,8 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #define _PIN_CONFLICT(P) (PIN_EXISTS(P) && P##_PIN == SPINDLE_LASER_PWM_PIN) #if BOTH(SPINDLE_FEATURE, LASER_FEATURE) #error "Enable only one of SPINDLE_FEATURE or LASER_FEATURE." - #elif !PIN_EXISTS(SPINDLE_LASER_ENA) - #error "(SPINDLE|LASER)_FEATURE requires SPINDLE_LASER_ENA_PIN." + #elif !PIN_EXISTS(SPINDLE_LASER_ENA) && DISABLED(SPINDLE_SERVO) + #error "(SPINDLE|LASER)_FEATURE requires SPINDLE_LASER_ENA_PIN or SPINDLE_SERVO to control the power." #elif ENABLED(SPINDLE_CHANGE_DIR) && !PIN_EXISTS(SPINDLE_DIR) #error "SPINDLE_DIR_PIN is required for SPINDLE_CHANGE_DIR." #elif ENABLED(SPINDLE_LASER_PWM) @@ -3130,10 +3571,14 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #undef _PIN_CONFLICT #endif -#if !HAS_MARLINUI_U8GLIB - #if ENABLED(PRINT_PROGRESS_SHOW_DECIMALS) - #error "PRINT_PROGRESS_SHOW_DECIMALS currently requires a Graphical LCD." - #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." +#endif + +#if NONE(HAS_MARLINUI_U8GLIB, EXTENSIBLE_UI) && ENABLED(PRINT_PROGRESS_SHOW_DECIMALS) + #error "PRINT_PROGRESS_SHOW_DECIMALS currently requires a Graphical LCD." #endif #if HAS_ADC_BUTTONS && defined(ADC_BUTTON_DEBOUNCE_DELAY) && ADC_BUTTON_DEBOUNCE_DELAY < 16 @@ -3154,28 +3599,11 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #endif /** - * Stepper Chunk support + * Touch Screen Calibration */ -#if BOTH(DIRECT_STEPPING, LIN_ADVANCE) - #error "DIRECT_STEPPING is incompatible with LIN_ADVANCE. Enable in external planner if possible." -#endif - -/** - * Touch Buttons - */ -#if ENABLED(TOUCH_SCREEN) - #ifndef XPT2046_X_CALIBRATION - #error "XPT2046_X_CALIBRATION must be defined with TOUCH_SCREEN." - #endif - #ifndef XPT2046_Y_CALIBRATION - #error "XPT2046_Y_CALIBRATION must be defined with TOUCH_SCREEN." - #endif - #ifndef XPT2046_X_OFFSET - #error "XPT2046_X_OFFSET must be defined with TOUCH_SCREEN." - #endif - #ifndef XPT2046_Y_OFFSET - #error "XPT2046_Y_OFFSET must be defined with TOUCH_SCREEN." - #endif +#if ENABLED(TFT_TOUCH_DEVICE_XPT2046) && DISABLED(TOUCH_SCREEN_CALIBRATION) \ + && (!defined(TOUCH_CALIBRATION_X) || !defined(TOUCH_CALIBRATION_Y) || !defined(TOUCH_OFFSET_X) || !defined(TOUCH_OFFSET_Y)) + #error "TOUCH_CALIBRATION_[XY] and TOUCH_OFFSET_[XY] are required for resistive touch screens with TOUCH_SCREEN_CALIBRATION disabled." #endif /** @@ -3196,5 +3624,113 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #endif #endif +/** + * Sanity Check for MEATPACK and BINARY_FILE_TRANSFER Features + */ +#if BOTH(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) + #error "SLIM_LCD_MENUS disables \"Advanced Settings > Probe Offsets > PROBE_OFFSET_WIZARD.\"" +#endif + +/** + * Sanity check for unique start and stop values in NOZZLE_CLEAN_FEATURE + */ +#if ENABLED(NOZZLE_CLEAN_FEATURE) + constexpr xyz_pos_t start_xyz[8] = NOZZLE_CLEAN_START_POINT, + end_xyz[8] = NOZZLE_CLEAN_END_POINT; + #define _CLEAN_ASSERT(N) static_assert(N >= HOTENDS || end_xyz[N].x != start_xyz[N].x || TERN(NOZZLE_CLEAN_NO_Y, false, end_xyz[N].y != start_xyz[N].y), \ + "NOZZLE_CLEAN Start and End must be made different on HOTEND " STRINGIFY(N)) + _CLEAN_ASSERT(0); _CLEAN_ASSERT(1); + _CLEAN_ASSERT(2); _CLEAN_ASSERT(3); + _CLEAN_ASSERT(4); _CLEAN_ASSERT(5); + _CLEAN_ASSERT(6); _CLEAN_ASSERT(7); + #undef _CLEAN_ASSERT +#endif + +/** + * Sanity check for MIXING_EXTRUDER & DISTINCT_E_FACTORS these are not compatible + */ +#if BOTH(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 + +/** + * Sanity check for valid stepper driver types + */ +#define _BAD_DRIVER(A) (defined(A##_DRIVER_TYPE) && !_DRIVER_ID(A##_DRIVER_TYPE)) +#if _BAD_DRIVER(X) + #error "X_DRIVER_TYPE is not recognized." +#endif +#if _BAD_DRIVER(Y) + #error "Y_DRIVER_TYPE is not recognized." +#endif +#if _BAD_DRIVER(Z) + #error "Z_DRIVER_TYPE is not recognized." +#endif +#if LINEAR_AXES >= 4 + #if _BAD_DRIVER(I) + #error "I_DRIVER_TYPE is not recognized." + #endif +#endif +#if LINEAR_AXES >= 5 + #if _BAD_DRIVER(J) + #error "J_DRIVER_TYPE is not recognized." + #endif +#endif +#if LINEAR_AXES >= 6 + #if _BAD_DRIVER(K) + #error "K_DRIVER_TYPE is not recognized." + #endif +#endif + +#if _BAD_DRIVER(X2) + #error "X2_DRIVER_TYPE is not recognized." +#endif +#if _BAD_DRIVER(Y2) + #error "Y2_DRIVER_TYPE is not recognized." +#endif +#if _BAD_DRIVER(Z2) + #error "Z2_DRIVER_TYPE is not recognized." +#endif +#if _BAD_DRIVER(Z3) + #error "Z3_DRIVER_TYPE is not recognized." +#endif +#if _BAD_DRIVER(Z4) + #error "Z4_DRIVER_TYPE is not recognized." +#endif +#if _BAD_DRIVER(E0) + #error "E0_DRIVER_TYPE is not recognized." +#endif +#if _BAD_DRIVER(E1) + #error "E1_DRIVER_TYPE is not recognized." +#endif +#if _BAD_DRIVER(E2) + #error "E2_DRIVER_TYPE is not recognized." +#endif +#if _BAD_DRIVER(E3) + #error "E3_DRIVER_TYPE is not recognized." +#endif +#if _BAD_DRIVER(E4) + #error "E4_DRIVER_TYPE is not recognized." +#endif +#if _BAD_DRIVER(E5) + #error "E5_DRIVER_TYPE is not recognized." +#endif +#if _BAD_DRIVER(E6) + #error "E6_DRIVER_TYPE is not recognized." +#endif +#if _BAD_DRIVER(E7) + #error "E7_DRIVER_TYPE is not recognized." +#endif +#undef _BAD_DRIVER + // Misc. Cleanup #undef _TEST_PWM +#undef _LINEAR_AXES_STR +#undef _LOGICAL_AXES_STR diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 00ca940662e9..47faf32aad68 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -25,7 +25,7 @@ * Release version. Leave the Marlin version or apply a custom scheme. */ #ifndef SHORT_BUILD_VERSION - #define SHORT_BUILD_VERSION "2.0.7.2" + #define SHORT_BUILD_VERSION "2.0.9.1" #endif /** @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-10-15" + #define STRING_DISTRIBUTION_DATE "2021-06-27" #endif /** @@ -52,7 +52,7 @@ * to alert users to major changes. */ -#define MARLIN_HEX_VERSION 020007 +#define MARLIN_HEX_VERSION 02000901 #ifndef REQUIRED_CONFIGURATION_H_VERSION #define REQUIRED_CONFIGURATION_H_VERSION MARLIN_HEX_VERSION #endif @@ -82,7 +82,7 @@ * providing the source code to your customers.) */ #ifndef SOURCE_CODE_URL - #define SOURCE_CODE_URL "https://github.com/MarlinFirmware/Marlin" + #define SOURCE_CODE_URL "github.com/MarlinFirmware/Marlin" #endif /** @@ -97,7 +97,7 @@ * documentation about a specific Marlin release. Displayed in the Info Menu. */ #ifndef WEBSITE_URL - #define WEBSITE_URL "https://marlinfw.org" + #define WEBSITE_URL "marlinfw.org" #endif /** diff --git a/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp b/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp index aa3c3c04a123..8aca19b0cd9e 100644 --- a/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp +++ b/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp @@ -16,10 +16,10 @@ #if HAS_MARLINUI_HD44780 -#include "../ultralcd.h" +#include "../marlinui.h" #include "../../MarlinCore.h" -#include "ultralcd_HD44780.h" +#include "marlinui_HD44780.h" #include diff --git a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp new file mode 100644 index 000000000000..f4d765e2d303 --- /dev/null +++ b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp @@ -0,0 +1,1588 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../inc/MarlinConfigPre.h" + +#if HAS_MARLINUI_HD44780 + +/** + * marlinui_HD44780.cpp + * + * LCD display implementations for Hitachi HD44780. + * These are the most common LCD character displays. + */ + +#include "marlinui_HD44780.h" +#include "../marlinui.h" +#include "../../libs/numtostr.h" + +#include "../../sd/cardreader.h" +#include "../../module/temperature.h" +#include "../../module/printcounter.h" +#include "../../module/planner.h" +#include "../../module/motion.h" + +#if DISABLED(LCD_PROGRESS_BAR) && BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) + #include "../../feature/filwidth.h" + #include "../../gcode/parser.h" +#endif + +#if EITHER(HAS_COOLER, LASER_COOLANT_FLOW_METER) + #include "../../feature/cooler.h" +#endif + +#if ENABLED(I2C_AMMETER) + #include "../../feature/ammeter.h" +#endif + +#if ENABLED(AUTO_BED_LEVELING_UBL) + #include "../../feature/bedlevel/bedlevel.h" +#endif + +// +// Create LCD instance and chipset-specific information +// + +#if ENABLED(LCD_I2C_TYPE_PCF8575) + + 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) + + LCD_CLASS lcd(LCD_I2C_ADDRESS OPTARG(DETECT_I2C_LCD_DEVICE, 1)); + +#elif ENABLED(LCD_I2C_TYPE_PCA8574) + + LCD_CLASS lcd(LCD_I2C_ADDRESS, LCD_WIDTH, LCD_HEIGHT); + +#elif ENABLED(SR_LCD_2W_NL) + + // 2 wire Non-latching LCD SR from: + // https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/schematics#!shiftregister-connection + + LCD_CLASS lcd(SR_DATA_PIN, SR_CLK_PIN + #if PIN_EXISTS(SR_STROBE) + , SR_STROBE_PIN + #endif + ); + +#elif ENABLED(SR_LCD_3W_NL) + + // NewLiquidCrystal was not working + // https://github.com/mikeshub/SailfishLCD + // uses the code directly from Sailfish + + LCD_CLASS lcd(SR_STROBE_PIN, SR_DATA_PIN, SR_CLK_PIN); + +#elif ENABLED(LCM1602) + + LCD_CLASS lcd(0x27, 2, 1, 0, 4, 5, 6, 7, 3, POSITIVE); + +#elif ENABLED(YHCB2004) + + LCD_CLASS lcd(YHCB2004_CLK, 20, 4, YHCB2004_MOSI, YHCB2004_MISO); // 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); + +#endif + +static void createChar_P(const char c, const byte * const ptr) { + byte temp[8]; + LOOP_L_N(i, 8) + temp[i] = pgm_read_byte(&ptr[i]); + lcd.createChar(c, temp); +} + +#if ENABLED(LCD_PROGRESS_BAR) + #define LCD_STR_PROGRESS "\x03\x04\x05" +#endif + +#if ENABLED(LCD_USE_I2C_BUZZER) + void MarlinUI::buzz(const long duration, const uint16_t freq) { + if (!buzzer_enabled) return; + lcd.buzz(duration, freq); + } +#endif + +void MarlinUI::set_custom_characters(const HD44780CharSet screen_charset/*=CHARSET_INFO*/) { + #if NONE(LCD_PROGRESS_BAR, SHOW_BOOTSCREEN) + UNUSED(screen_charset); + #endif + + // CHARSET_BOOT + #if ENABLED(SHOW_BOOTSCREEN) + const static PROGMEM byte corner[4][8] = { { + B00000, + B00000, + B00000, + B00000, + B00001, + B00010, + B00100, + B00100 + }, { + B00000, + B00000, + B00000, + B11100, + B11100, + B01100, + B00100, + B00100 + }, { + B00100, + B00010, + B00001, + B00000, + B00000, + B00000, + B00000, + B00000 + }, { + B00100, + B01000, + B10000, + B00000, + B00000, + B00000, + B00000, + B00000 + } }; + #endif // SHOW_BOOTSCREEN + + // CHARSET_INFO + const static PROGMEM byte bedTemp[8] = { + B00000, + B11111, + B10101, + B10001, + B10101, + B11111, + B00000, + B00000 + }; + + const static PROGMEM byte degree[8] = { + B01100, + B10010, + B10010, + B01100, + B00000, + B00000, + B00000, + B00000 + }; + + const static PROGMEM byte thermometer[8] = { + B00100, + B01010, + B01010, + B01010, + B01010, + B10001, + B10001, + B01110 + }; + + const static PROGMEM byte uplevel[8] = { + B00100, + B01110, + B11111, + B00100, + B11100, + B00000, + B00000, + B00000 + }; + + const static PROGMEM byte feedrate[8] = { + #if LCD_INFO_SCREEN_STYLE == 1 + B00000, + B00100, + B10010, + B01001, + B10010, + B00100, + B00000, + B00000 + #else + B11100, + B10000, + B11000, + B10111, + B00101, + B00110, + B00101, + B00000 + #endif + }; + + const static PROGMEM byte clock[8] = { + B00000, + B01110, + B10011, + B10101, + B10001, + B01110, + B00000, + B00000 + }; + + #if ENABLED(LCD_PROGRESS_BAR) + + // CHARSET_INFO + const static PROGMEM byte progress[3][8] = { { + B00000, + B10000, + B10000, + B10000, + B10000, + B10000, + B10000, + B00000 + }, { + B00000, + B10100, + B10100, + B10100, + B10100, + B10100, + B10100, + B00000 + }, { + B00000, + B10101, + B10101, + B10101, + B10101, + B10101, + B10101, + B00000 + } }; + + #endif // LCD_PROGRESS_BAR + + #if BOTH(SDSUPPORT, HAS_LCD_MENU) + + // CHARSET_MENU + const static PROGMEM byte refresh[8] = { + B00000, + B00110, + B11001, + B11000, + B00011, + B10011, + B01100, + B00000, + }; + const static PROGMEM byte folder[8] = { + B00000, + B11100, + B11111, + B10001, + B10001, + B11111, + B00000, + B00000 + }; + + #endif // SDSUPPORT + + #if ENABLED(SHOW_BOOTSCREEN) + // Set boot screen corner characters + if (screen_charset == CHARSET_BOOT) { + for (uint8_t i = 4; i--;) + createChar_P(i, corner[i]); + } + else + #endif + { // Info Screen uses 5 special characters + createChar_P(LCD_STR_BEDTEMP[0], bedTemp); + createChar_P(LCD_STR_DEGREE[0], degree); + createChar_P(LCD_STR_THERMOMETER[0], thermometer); + createChar_P(LCD_STR_FEEDRATE[0], feedrate); + createChar_P(LCD_STR_CLOCK[0], clock); + + #if ENABLED(LCD_PROGRESS_BAR) + if (screen_charset == CHARSET_INFO) { // 3 Progress bar characters for info screen + for (int16_t i = 3; i--;) + createChar_P(LCD_STR_PROGRESS[i], progress[i]); + } + else + #endif + { + createChar_P(LCD_STR_UPLEVEL[0], uplevel); + #if BOTH(SDSUPPORT, HAS_LCD_MENU) + // SD Card sub-menu special characters + createChar_P(LCD_STR_REFRESH[0], refresh); + createChar_P(LCD_STR_FOLDER[0], folder); + #endif + } + } + +} + +void MarlinUI::init_lcd() { + + #if ENABLED(LCD_I2C_TYPE_PCF8575) + lcd.begin(LCD_WIDTH, LCD_HEIGHT); + #ifdef LCD_I2C_PIN_BL + lcd.setBacklightPin(LCD_I2C_PIN_BL, POSITIVE); + lcd.setBacklight(HIGH); + #endif + + #elif ENABLED(LCD_I2C_TYPE_MCP23017) + lcd.setMCPType(LTI_TYPE_MCP23017); + lcd.begin(LCD_WIDTH, LCD_HEIGHT); + update_indicators(); + + #elif ENABLED(LCD_I2C_TYPE_MCP23008) + lcd.setMCPType(LTI_TYPE_MCP23008); + lcd.begin(LCD_WIDTH, LCD_HEIGHT); + + #elif ENABLED(LCD_I2C_TYPE_PCA8574) + lcd.init(); + lcd.backlight(); + + #else + lcd.begin(LCD_WIDTH, LCD_HEIGHT); + #endif + + set_custom_characters(on_status_screen() ? CHARSET_INFO : CHARSET_MENU); + + lcd.clear(); +} + +bool MarlinUI::detected() { + return TERN1(DETECT_I2C_LCD_DEVICE, lcd.LcdDetected() == 1); +} + +#if HAS_SLOW_BUTTONS + uint8_t MarlinUI::read_slow_buttons() { + #if ENABLED(LCD_I2C_TYPE_MCP23017) + // Reading these buttons is too slow for interrupt context + // so they are read during LCD update in the main loop. + uint8_t slow_bits = lcd.readButtons() + #if !BUTTON_EXISTS(ENC) + << B_I2C_BTN_OFFSET + #endif + ; + #if ENABLED(LCD_I2C_VIKI) + if ((slow_bits & (B_MI | B_RI)) && PENDING(millis(), next_button_update_ms)) // LCD clicked + slow_bits &= ~(B_MI | B_RI); // Disable LCD clicked buttons if screen is updated + #endif + return slow_bits; + #endif // LCD_I2C_TYPE_MCP23017 + } +#endif + +void MarlinUI::clear_lcd() { lcd.clear(); } + +#if ENABLED(SHOW_BOOTSCREEN) + + void lcd_erase_line(const lcd_uint_t line) { + lcd_moveto(0, line); + for (uint8_t i = LCD_WIDTH + 1; --i;) + lcd_put_wchar(' '); + } + + // Scroll the PSTR 'text' in a 'len' wide field for 'time' milliseconds at position col,line + void lcd_scroll(const lcd_uint_t col, const lcd_uint_t line, PGM_P const text, const uint8_t len, const int16_t time) { + uint8_t slen = utf8_strlen_P(text); + if (slen < len) { + lcd_put_u8str_max_P(col, line, text, len); + for (; slen < len; ++slen) lcd_put_wchar(' '); + safe_delay(time); + } + else { + PGM_P p = text; + int dly = time / _MAX(slen, 1); + LOOP_LE_N(i, slen) { + + // Print the text at the correct place + lcd_put_u8str_max_P(col, line, p, len); + + // Fill with spaces + for (uint8_t ix = slen - i; ix < len; ++ix) lcd_put_wchar(' '); + + // Delay + safe_delay(dly); + + // Advance to the next UTF8 valid position + p++; + while (!START_OF_UTF8_CHAR(pgm_read_byte(p))) p++; + } + } + } + + static void logo_lines(PGM_P const extra) { + int16_t indent = (LCD_WIDTH - 8 - utf8_strlen_P(extra)) / 2; + lcd_put_wchar(indent, 0, '\x00'); lcd_put_u8str_P(PSTR( "------" )); lcd_put_wchar('\x01'); + lcd_put_u8str_P(indent, 1, PSTR("|Marlin|")); lcd_put_u8str_P(extra); + lcd_put_wchar(indent, 2, '\x02'); lcd_put_u8str_P(PSTR( "------" )); lcd_put_wchar('\x03'); + } + + void MarlinUI::show_bootscreen() { + set_custom_characters(CHARSET_BOOT); + lcd.clear(); + + #define LCD_EXTRA_SPACE (LCD_WIDTH-8) + + #define CENTER_OR_SCROLL(STRING,DELAY) \ + lcd_erase_line(3); \ + if (utf8_strlen(STRING) <= LCD_WIDTH) { \ + lcd_put_u8str_P((LCD_WIDTH - utf8_strlen_P(PSTR(STRING))) / 2, 3, PSTR(STRING)); \ + safe_delay(DELAY); \ + } \ + else { \ + lcd_scroll(0, 3, PSTR(STRING), LCD_WIDTH, DELAY); \ + } + + // + // Show the Marlin logo with splash line 1 + // + if (LCD_EXTRA_SPACE >= utf8_strlen(SHORT_BUILD_VERSION) + 1) { + // + // Show the Marlin logo, splash line1, and splash line 2 + // + logo_lines(PSTR(" " SHORT_BUILD_VERSION)); + CENTER_OR_SCROLL(MARLIN_WEBSITE_URL, 2000); + } + else { + // + // Show the Marlin logo and short build version + // After a delay show the website URL + // + logo_lines(NUL_STR); + CENTER_OR_SCROLL(SHORT_BUILD_VERSION, 1500); + CENTER_OR_SCROLL(MARLIN_WEBSITE_URL, 1500); + #ifdef STRING_SPLASH_LINE3 + CENTER_OR_SCROLL(STRING_SPLASH_LINE3, 1500); + #endif + } + } + + void MarlinUI::bootscreen_completion(const millis_t) { + lcd.clear(); + safe_delay(100); + set_custom_characters(CHARSET_INFO); + lcd.clear(); + } + +#endif // SHOW_BOOTSCREEN + +void MarlinUI::draw_kill_screen() { + lcd_put_u8str(0, 0, status_message); + lcd_uint_t y = 2; + #if LCD_HEIGHT >= 4 + lcd_put_u8str_P(0, y++, GET_TEXT(MSG_HALTED)); + #endif + lcd_put_u8str_P(0, y, GET_TEXT(MSG_PLEASE_RESET)); +} + +// +// Before homing, blink '123' <-> '???'. +// Homed but unknown... '123' <-> ' '. +// Homed and known, display constantly. +// +FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const bool blink) { + lcd_put_wchar('X' + uint8_t(axis)); + if (blink) + lcd_put_u8str(value); + else if (axis_should_home(axis)) + while (const char c = *value++) lcd_put_wchar(c <= '.' ? c : '?'); + else if (NONE(HOME_AFTER_DEACTIVATE, DISABLE_REDUCED_ACCURACY_WARNING) && !axis_is_trusted(axis)) + lcd_put_u8str_P(axis == Z_AXIS ? PSTR(" ") : PSTR(" ")); + else + lcd_put_u8str(value); +} + + +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 celsius_t t1 = (isBed ? thermalManager.wholeDegBed() : thermalManager.wholeDegHotend(heater_id)), + t2 = (isBed ? thermalManager.degTargetBed() : thermalManager.degTargetHotend(heater_id)); + #else + const celsius_t t1 = thermalManager.wholeDegHotend(heater_id), t2 = thermalManager.degTargetHotend(heater_id); + #endif + + if (prefix >= 0) lcd_put_wchar(prefix); + + lcd_put_u8str(t1 < 0 ? "err" : i16tostr3rj(t1)); + lcd_put_wchar('/'); + + #if !HEATER_IDLE_HANDLER + UNUSED(blink); + #else + if (!blink && thermalManager.heater_idle[thermalManager.idle_index_for_id(heater_id)].timed_out) { + lcd_put_wchar(' '); + if (t2 >= 10) lcd_put_wchar(' '); + if (t2 >= 100) lcd_put_wchar(' '); + } + else + #endif + lcd_put_u8str(i16tostr3left(t2)); + + if (prefix >= 0) { + lcd_put_wchar(LCD_STR_DEGREE[0]); + lcd_put_wchar(' '); + if (t2 < 10) lcd_put_wchar(' '); + } +} + +#if HAS_COOLER +FORCE_INLINE void _draw_cooler_status(const char prefix, const bool blink) { + const celsius_t t2 = thermalManager.degTargetCooler(); + + if (prefix >= 0) lcd_put_wchar(prefix); + + lcd_put_u8str(i16tostr3rj(thermalManager.wholeDegCooler())); + lcd_put_wchar('/'); + + #if !HEATER_IDLE_HANDLER + UNUSED(blink); + #else + if (!blink && thermalManager.heater_idle[thermalManager.idle_index_for_id(heater_id)].timed_out) { + lcd_put_wchar(' '); + if (t2 >= 10) lcd_put_wchar(' '); + if (t2 >= 100) lcd_put_wchar(' '); + } + else + #endif + lcd_put_u8str(i16tostr3left(t2)); + + if (prefix >= 0) { + lcd_put_wchar(LCD_STR_DEGREE[0]); + lcd_put_wchar(' '); + if (t2 < 10) lcd_put_wchar(' '); + } +} +#endif + +#if ENABLED(LASER_COOLANT_FLOW_METER) + FORCE_INLINE void _draw_flowmeter_status() { + lcd_put_u8str("~"); + lcd_put_u8str(ftostr11ns(cooler.flowrate)); + lcd_put_wchar('L'); + } +#endif + +#if ENABLED(I2C_AMMETER) + FORCE_INLINE void _draw_ammeter_status() { + lcd_put_u8str(" "); + ammeter.read(); + if (ammeter.current <= 0.999f) { + lcd_put_u8str(ui16tostr3rj(uint16_t(ammeter.current * 1000 + 0.5f))); + lcd_put_u8str("mA"); + } + else { + lcd_put_u8str(ftostr12ns(ammeter.current)); + lcd_put_wchar('A'); + } + } +#endif + +FORCE_INLINE void _draw_bed_status(const bool blink) { + _draw_heater_status(H_BED, TERN0(HAS_LEVELING, blink && planner.leveling_active) ? '_' : LCD_STR_BEDTEMP[0], blink); +} + +#if HAS_PRINT_PROGRESS + + FORCE_INLINE void _draw_print_progress() { + const uint8_t progress = ui.get_progress_percent(); + lcd_put_u8str_P(PSTR(TERN(SDSUPPORT, "SD", "P:"))); + if (progress) + lcd_put_u8str(ui8tostr3rj(progress)); + else + lcd_put_u8str_P(PSTR("---")); + lcd_put_wchar('%'); + } + +#endif + +#if ENABLED(LCD_PROGRESS_BAR) + + void MarlinUI::draw_progress_bar(const uint8_t percent) { + const int16_t tix = int16_t(percent * (LCD_WIDTH) * 3) / 100, + cel = tix / 3, + rem = tix % 3; + uint8_t i = LCD_WIDTH; + char msg[LCD_WIDTH + 1], b = ' '; + msg[LCD_WIDTH] = '\0'; + while (i--) { + if (i == cel - 1) + b = LCD_STR_PROGRESS[2]; + else if (i == cel && rem != 0) + b = LCD_STR_PROGRESS[rem - 1]; + msg[i] = b; + } + lcd_put_u8str(msg); + } + +#endif // LCD_PROGRESS_BAR + +void MarlinUI::draw_status_message(const bool blink) { + + lcd_moveto(0, LCD_HEIGHT - 1); + + #if ENABLED(LCD_PROGRESS_BAR) + + // Draw the progress bar if the message has shown long enough + // or if there is no message set. + if (ELAPSED(millis(), progress_bar_ms + PROGRESS_BAR_MSG_TIME) || !has_status()) { + const uint8_t progress = get_progress_percent(); + if (progress > 2) return draw_progress_bar(progress); + } + + #elif BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) + + // Alternate Status message and Filament display + if (ELAPSED(millis(), next_filament_display)) { + lcd_put_u8str_P(PSTR("Dia ")); + lcd_put_u8str(ftostr12ns(filwidth.measured_mm)); + lcd_put_u8str_P(PSTR(" V")); + lcd_put_u8str(i16tostr3rj(planner.volumetric_percent(parser.volumetric_enabled))); + lcd_put_wchar('%'); + return; + } + + #endif // FILAMENT_LCD_DISPLAY && SDSUPPORT + + #if ENABLED(STATUS_MESSAGE_SCROLLING) + static bool last_blink = false; + + // Get the UTF8 character count of the string + uint8_t slen = utf8_strlen(status_message); + + // If the string fits into the LCD, just print it and do not scroll it + if (slen <= LCD_WIDTH) { + + // The string isn't scrolling and may not fill the screen + lcd_put_u8str(status_message); + + // Fill the rest with spaces + while (slen < LCD_WIDTH) { lcd_put_wchar(' '); ++slen; } + } + else { + // String is larger than the available space in screen. + + // Get a pointer to the next valid UTF8 character + // and the string remaining length + uint8_t rlen; + const char *stat = status_and_len(rlen); + lcd_put_u8str_max(stat, LCD_WIDTH); // The string leaves space + + // If the remaining string doesn't completely fill the screen + if (rlen < LCD_WIDTH) { + uint8_t chars = LCD_WIDTH - rlen; // Amount of space left in characters + lcd_put_wchar(' '); // Always at 1+ spaces left, draw a space + if (--chars) { // Draw a second space if there's room + lcd_put_wchar(' '); + if (--chars) { // Draw a third space if there's room + lcd_put_wchar(' '); + if (--chars) + lcd_put_u8str_max(status_message, chars); // Print a second copy of the message + } + } + } + if (last_blink != blink) { + last_blink = blink; + advance_status_scroll(); + } + } + #else + UNUSED(blink); + + // Get the UTF8 character count of the string + uint8_t slen = utf8_strlen(status_message); + + // Just print the string to the LCD + lcd_put_u8str_max(status_message, LCD_WIDTH); + + // Fill the rest with spaces if there are missing spaces + while (slen < LCD_WIDTH) { + lcd_put_wchar(' '); + ++slen; + } + #endif +} + +/** + * LCD_INFO_SCREEN_STYLE 0 : Classic Status Screen + * + * 16x2 |000/000 B000/000| + * |0123456789012345| + * + * 16x4 |000/000 B000/000| + * |SD---% Z 000.00| + * |F---% T--:--| + * |0123456789012345| + * + * 20x2 |T000/000° B000/000° | + * |01234567890123456789| + * + * 20x4 |T000/000° B000/000° | + * |X 000 Y 000 Z000.000| + * |F---% SD---% T--:--| + * |01234567890123456789| + * + * LCD_INFO_SCREEN_STYLE 1 : Průša-style Status Screen + * + * |T000/000° Z 000.00 | + * |B000/000° F---% | + * |SD---% T--:-- | + * |01234567890123456789| + * + * |T000/000° Z 000.00 | + * |T000/000° F---% | + * |B000/000° SD---% | + * |01234567890123456789| + */ + +inline uint8_t draw_elapsed_or_remaining_time(uint8_t timepos, const bool blink) { + char buffer[14]; + + #if ENABLED(SHOW_REMAINING_TIME) + const bool show_remain = TERN1(ROTATE_PROGRESS_DISPLAY, blink) && printingIsActive(); + if (show_remain) { + #if ENABLED(USE_M73_REMAINING_TIME) + duration_t remaining = ui.get_remaining_time(); + #else + uint8_t progress = ui.get_progress_percent(); + uint32_t elapsed = print_job_timer.duration(); + duration_t remaining = (progress > 0) ? ((elapsed * 25600 / progress) >> 8) - elapsed : 0; + #endif + timepos -= remaining.toDigital(buffer); + lcd_put_wchar(timepos, 2, 'R'); + } + #else + constexpr bool show_remain = false; + #endif + + if (!show_remain) { + duration_t elapsed = print_job_timer.duration(); + timepos -= elapsed.toDigital(buffer); + lcd_put_wchar(timepos, 2, LCD_STR_CLOCK[0]); + } + lcd_put_u8str(buffer); + return timepos; +} + +void MarlinUI::draw_status_screen() { + + const bool blink = get_blink(); + lcd_moveto(0, 0); + + #if LCD_INFO_SCREEN_STYLE == 0 + + // ========== Line 1 ========== + + #if LCD_WIDTH < 20 + + // + // Hotend 0 Temperature + // + #if HAS_HOTEND + _draw_heater_status(H_E0, -1, blink); + + // + // Hotend 1 or Bed Temperature + // + #if HAS_MULTI_HOTEND + lcd_moveto(8, 0); + _draw_heater_status(H_E1, LCD_STR_THERMOMETER[0], blink); + #elif HAS_HEATED_BED + lcd_moveto(8, 0); + _draw_bed_status(blink); + #endif + #endif + + #else // LCD_WIDTH >= 20 + + // + // Hotend 0 Temperature + // + #if HAS_HOTEND + _draw_heater_status(H_E0, LCD_STR_THERMOMETER[0], blink); + + // + // Hotend 1 or Bed Temperature + // + #if HAS_MULTI_HOTEND + lcd_moveto(10, 0); + _draw_heater_status(H_E1, LCD_STR_THERMOMETER[0], blink); + #elif HAS_HEATED_BED + lcd_moveto(10, 0); + _draw_bed_status(blink); + #endif + #endif + + TERN_(HAS_COOLER, _draw_cooler_status('*', blink)); + TERN_(LASER_COOLANT_FLOW_METER, _draw_flowmeter_status()); + TERN_(I2C_AMMETER, _draw_ammeter_status()); + + #endif // LCD_WIDTH >= 20 + + // ========== Line 2 ========== + + #if LCD_HEIGHT > 2 + + #if LCD_WIDTH < 20 + + #if HAS_PRINT_PROGRESS + lcd_moveto(0, 2); + _draw_print_progress(); + #endif + + #else // LCD_WIDTH >= 20 + + lcd_moveto(0, 1); + + // If the first line has two extruder temps, + // show more temperatures on the next line + + #if HOTENDS > 2 || (HAS_MULTI_HOTEND && HAS_HEATED_BED) + + #if HOTENDS > 2 + _draw_heater_status(H_E2, LCD_STR_THERMOMETER[0], blink); + lcd_moveto(10, 1); + #endif + + _draw_bed_status(blink); + + #else // HOTENDS <= 2 && (HOTENDS <= 1 || !HAS_HEATED_BED) + + #if HAS_DUAL_MIXING + + // Two-component mix / gradient instead of XY + + char mixer_messages[12]; + const char *mix_label; + #if ENABLED(GRADIENT_MIX) + if (mixer.gradient.enabled) { + mixer.update_mix_from_gradient(); + mix_label = "Gr"; + } + else + #endif + { + mixer.update_mix_from_vtool(); + mix_label = "Mx"; + } + sprintf_P(mixer_messages, PSTR("%s %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()); + + if (show_e_total) { + #if ENABLED(LCD_SHOW_E_TOTAL) + char tmp[20]; + const uint8_t escale = e_move_accumulator >= 100000.0f ? 10 : 1; // After 100m switch to cm + sprintf_P(tmp, PSTR("E %ld%cm "), uint32_t(_MAX(e_move_accumulator, 0.0f)) / escale, escale == 10 ? 'c' : 'm'); // 1234567mm + lcd_put_u8str(tmp); + #endif + } + else { + const xy_pos_t lpos = current_position.asLogical(); + _draw_axis_value(X_AXIS, ftostr4sign(lpos.x), blink); + lcd_put_wchar(' '); + _draw_axis_value(Y_AXIS, ftostr4sign(lpos.y), blink); + } + + #endif // !HAS_DUAL_MIXING + + #endif // HOTENDS <= 2 && (HOTENDS <= 1 || !HAS_HEATED_BED) + + #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_wchar(planner.leveling_active || blink ? '_' : ' '); + #endif + + #endif // LCD_HEIGHT > 2 + + // ========== Line 3 ========== + + #if LCD_HEIGHT > 3 + + lcd_put_wchar(0, 2, LCD_STR_FEEDRATE[0]); + lcd_put_u8str(i16tostr3rj(feedrate_percentage)); + lcd_put_wchar('%'); + + const uint8_t timepos = draw_elapsed_or_remaining_time(LCD_WIDTH - 1, blink); + + #if LCD_WIDTH >= 20 + lcd_moveto(timepos - 7, 2); + #if HAS_PRINT_PROGRESS + _draw_print_progress(); + #else + char c; + uint16_t per; + #if HAS_FAN0 + if (true + #if EXTRUDERS && ENABLED(ADAPTIVE_FAN_SLOWING) + && (blink || thermalManager.fan_speed_scaler[0] < 128) + #endif + ) { + uint16_t spd = thermalManager.fan_speed[0]; + if (blink) c = 'F'; + #if ENABLED(ADAPTIVE_FAN_SLOWING) + else { c = '*'; spd = thermalManager.scaledFanSpeed(0, spd); } + #endif + per = thermalManager.pwmToPercent(spd); + } + else + #endif + { + #if HAS_EXTRUDERS + c = 'E'; + per = planner.flow_percentage[0]; + #endif + } + lcd_put_wchar(c); + lcd_put_u8str(i16tostr3rj(per)); + lcd_put_wchar('%'); + #endif + #endif + + #endif // LCD_HEIGHT > 3 + + #elif LCD_INFO_SCREEN_STYLE == 1 + + // ========== Line 1 ========== + + // + // Hotend 0 Temperature + // + _draw_heater_status(H_E0, LCD_STR_THERMOMETER[0], blink); + + // + // Z Coordinate + // + lcd_moveto(LCD_WIDTH - 9, 0); + _draw_axis_value(Z_AXIS, ftostr52sp(LOGICAL_Z_POSITION(current_position.z)), blink); + + #if HAS_LEVELING && (HAS_MULTI_HOTEND || !HAS_HEATED_BED) + lcd_put_wchar(LCD_WIDTH - 1, 0, planner.leveling_active || blink ? '_' : ' '); + #endif + + // ========== Line 2 ========== + + // + // Hotend 1 or Bed Temperature + // + lcd_moveto(0, 1); + #if HAS_MULTI_HOTEND + _draw_heater_status(H_E1, LCD_STR_THERMOMETER[0], blink); + #elif HAS_HEATED_BED + _draw_bed_status(blink); + #endif + + lcd_put_wchar(LCD_WIDTH - 9, 1, LCD_STR_FEEDRATE[0]); + lcd_put_u8str(i16tostr3rj(feedrate_percentage)); + lcd_put_wchar('%'); + + // ========== Line 3 ========== + + // + // SD Percent, Hotend 2, or Bed + // + lcd_moveto(0, 2); + #if HOTENDS > 2 + _draw_heater_status(H_E2, LCD_STR_THERMOMETER[0], blink); + #elif HAS_MULTI_HOTEND && HAS_HEATED_BED + _draw_bed_status(blink); + #elif HAS_PRINT_PROGRESS + #define DREW_PRINT_PROGRESS 1 + _draw_print_progress(); + #endif + + // + // Elapsed Time or SD Percent + // + lcd_moveto(LCD_WIDTH - 9, 2); + + #if HAS_PRINT_PROGRESS && !DREW_PRINT_PROGRESS + + _draw_print_progress(); + + #else + + (void)draw_elapsed_or_remaining_time(LCD_WIDTH - 4, blink); + + #endif + + #endif // LCD_INFO_SCREEN_STYLE 1 + + // ========= Last Line ======== + + // + // Status Message (which may be a Progress Bar or Filament display) + // + draw_status_message(blink); +} + +#if HAS_LCD_MENU + + #include "../menu/menu.h" + + #if ENABLED(ADVANCED_PAUSE_FEATURE) + + void MarlinUI::draw_hotend_status(const uint8_t row, const uint8_t extruder) { + if (row < LCD_HEIGHT) { + lcd_moveto(LCD_WIDTH - 9, row); + _draw_heater_status((heater_id_t)extruder, LCD_STR_THERMOMETER[0], get_blink()); + } + } + + #endif // ADVANCED_PAUSE_FEATURE + + // Draw a static item with no left-right margin required. Centered by default. + void MenuItem_static::draw(const uint8_t row, PGM_P const pstr, const uint8_t style/*=SS_DEFAULT*/, const char * const vstr/*=nullptr*/) { + int8_t n = LCD_WIDTH; + lcd_moveto(0, row); + const int8_t plen = pstr ? utf8_strlen_P(pstr) : 0, + vlen = vstr ? utf8_strlen(vstr) : 0; + if (style & SS_CENTER) { + int8_t pad = (LCD_WIDTH - plen - vlen) / 2; + while (--pad >= 0) { lcd_put_wchar(' '); n--; } + } + if (plen) n = lcd_put_u8str_ind_P(pstr, itemIndex, itemString, n); + if (vlen) n -= lcd_put_u8str_max(vstr, n); + for (; n > 0; --n) lcd_put_wchar(' '); + } + + // Draw a generic menu item with pre_char (if selected) and post_char + void MenuItemBase::_draw(const bool sel, const uint8_t row, PGM_P const pstr, const char pre_char, const char post_char) { + lcd_put_wchar(0, row, sel ? pre_char : ' '); + uint8_t n = lcd_put_u8str_ind_P(pstr, itemIndex, itemString, LCD_WIDTH - 2); + for (; n; --n) lcd_put_wchar(' '); + lcd_put_wchar(post_char); + } + + // Draw a menu item with a (potentially) editable value + void MenuEditItemBase::draw(const bool sel, const uint8_t row, PGM_P const pstr, const char * const inStr, const bool pgm) { + const uint8_t vlen = inStr ? (pgm ? utf8_strlen_P(inStr) : utf8_strlen(inStr)) : 0; + lcd_put_wchar(0, row, sel ? LCD_STR_ARROW_RIGHT[0] : ' '); + uint8_t n = lcd_put_u8str_ind_P(pstr, itemIndex, itemString, LCD_WIDTH - 2 - vlen); + if (vlen) { + lcd_put_wchar(':'); + for (; n; --n) lcd_put_wchar(' '); + if (pgm) lcd_put_u8str_P(inStr); else lcd_put_u8str(inStr); + } + } + + // Low-level draw_edit_screen can be used to draw an edit screen from anyplace + void MenuEditItemBase::draw_edit_screen(PGM_P const pstr, const char * const value/*=nullptr*/) { + ui.encoder_direction_normal(); + uint8_t n = lcd_put_u8str_ind_P(0, 1, pstr, itemIndex, itemString, LCD_WIDTH - 1); + if (value) { + lcd_put_wchar(':'); n--; + const uint8_t len = utf8_strlen(value) + 1; // Plus one for a leading space + const lcd_uint_t valrow = n < len ? 2 : 1; // Value on the next row if it won't fit + lcd_put_wchar(LCD_WIDTH - len, valrow, ' '); // Right-justified, padded, leading space + lcd_put_u8str(value); + } + } + + // The Select Screen presents a prompt and two "buttons" + void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const bool yesno, PGM_P const pref, const char * const string/*=nullptr*/, PGM_P const suff/*=nullptr*/) { + ui.draw_select_screen_prompt(pref, string, suff); + SETCURSOR(0, LCD_HEIGHT - 1); + lcd_put_wchar(yesno ? ' ' : '['); lcd_put_u8str_P(no); lcd_put_wchar(yesno ? ' ' : ']'); + SETCURSOR_RJ(utf8_strlen_P(yes) + 2, LCD_HEIGHT - 1); + lcd_put_wchar(yesno ? '[' : ' '); lcd_put_u8str_P(yes); lcd_put_wchar(yesno ? ']' : ' '); + } + + #if ENABLED(SDSUPPORT) + + void MenuItem_sdbase::draw(const bool sel, const uint8_t row, PGM_P const, CardReader &theCard, const bool isDir) { + lcd_put_wchar(0, row, sel ? LCD_STR_ARROW_RIGHT[0] : ' '); + constexpr uint8_t maxlen = LCD_WIDTH - 2; + uint8_t n = maxlen - lcd_put_u8str_max(ui.scrolled_filename(theCard, maxlen, row, sel), maxlen); + for (; n; --n) lcd_put_wchar(' '); + lcd_put_wchar(isDir ? LCD_STR_FOLDER[0] : ' '); + } + + #endif + + #if ENABLED(LCD_HAS_STATUS_INDICATORS) + + void MarlinUI::update_indicators() { + // Set the LEDS - referred to as backlights by the LiquidTWI2 library + static uint8_t ledsprev = 0; + uint8_t leds = 0; + + if (TERN0(HAS_HEATED_BED, thermalManager.degTargetBed() > 0)) leds |= LED_A; + if (TERN0(HAS_HOTEND, thermalManager.degTargetHotend(0) > 0)) leds |= LED_B; + + #if HAS_FAN + if ( TERN0(HAS_FAN0, thermalManager.fan_speed[0]) + || TERN0(HAS_FAN1, thermalManager.fan_speed[1]) + || TERN0(HAS_FAN2, thermalManager.fan_speed[2]) + || TERN0(HAS_FAN3, thermalManager.fan_speed[3]) + || TERN0(HAS_FAN4, thermalManager.fan_speed[4]) + || TERN0(HAS_FAN5, thermalManager.fan_speed[5]) + || TERN0(HAS_FAN6, thermalManager.fan_speed[6]) + || TERN0(HAS_FAN7, thermalManager.fan_speed[7]) + ) leds |= LED_C; + #endif // HAS_FAN + + if (TERN0(HAS_MULTI_HOTEND, thermalManager.degTargetHotend(1) > 0)) leds |= LED_C; + + if (leds != ledsprev) { + lcd.setBacklight(leds); + ledsprev = leds; + } + } + + #endif // LCD_HAS_STATUS_INDICATORS + + #if ENABLED(AUTO_BED_LEVELING_UBL) + + #define HD44780_CHAR_WIDTH 5 + #define HD44780_CHAR_HEIGHT 8 + #define MESH_MAP_COLS 7 + #define MESH_MAP_ROWS 4 + + #define CHAR_LINE_TOP 0 + #define CHAR_LINE_BOT 1 + #define CHAR_EDGE_L 2 + #define CHAR_EDGE_R 3 + #define CHAR_UL_UL 4 + #define CHAR_LR_UL 5 + #define CHAR_UL_LR 6 + #define CHAR_LR_LR 7 + + #define TOP_LEFT _BV(0) + #define TOP_RIGHT _BV(1) + #define LOWER_LEFT _BV(2) + #define LOWER_RIGHT _BV(3) + + /** + * Possible map screens: + * + * 16x2 |X000.00 Y000.00| + * |(00,00) Z00.000| + * + * 20x2 | X:000.00 Y:000.00 | + * | (00,00) Z:00.000 | + * + * 16x4 |+-------+(00,00)| + * || |X000.00| + * || |Y000.00| + * |+-------+Z00.000| + * + * 20x4 | +-------+ (00,00) | + * | | | X:000.00| + * | | | Y:000.00| + * | +-------+ Z:00.000| + */ + + typedef struct { + uint8_t custom_char_bits[HD44780_CHAR_HEIGHT]; + } custom_char; + + typedef struct { + lcd_uint_t column, row, + x_pixel_offset, y_pixel_offset; + uint8_t x_pixel_mask; + } coordinate; + + void add_edges_to_custom_char(custom_char &custom, const coordinate &ul, const coordinate &lr, const coordinate &brc, const uint8_t cell_location); + FORCE_INLINE static void clear_custom_char(custom_char * const cc) { ZERO(cc->custom_char_bits); } + + coordinate pixel_location(int16_t x, int16_t y) { + coordinate ret_val; + int16_t xp, yp, r, c; + + x++; y++; // +1 because lines on the left and top + + c = x / (HD44780_CHAR_WIDTH); + r = y / (HD44780_CHAR_HEIGHT); + + ret_val.column = c; + ret_val.row = r; + + xp = x - c * (HD44780_CHAR_WIDTH); // Get the pixel offsets into the character cell + xp = HD44780_CHAR_WIDTH - 1 - xp; // Column within relevant character cell (0 on the right) + yp = y - r * (HD44780_CHAR_HEIGHT); + + ret_val.x_pixel_mask = _BV(xp); + ret_val.x_pixel_offset = xp; + ret_val.y_pixel_offset = yp; + return ret_val; + } + + inline coordinate pixel_location(const lcd_uint_t x, const lcd_uint_t y) { return pixel_location((int16_t)x, (int16_t)y); } + + void prep_and_put_map_char(custom_char &chrdata, const coordinate &ul, const coordinate &lr, const coordinate &brc, const uint8_t cl, const char c, const lcd_uint_t x, const lcd_uint_t y) { + add_edges_to_custom_char(chrdata, ul, lr, brc, cl); + lcd.createChar(c, (uint8_t*)&chrdata); + lcd_put_wchar(x, y, c); + } + + void MarlinUI::ubl_plot(const uint8_t x_plot, const uint8_t y_plot) { + + #if LCD_WIDTH >= 20 + #define _LCD_W_POS 12 + #define _PLOT_X 1 + #define _MAP_X 3 + #define _LABEL(C,X,Y) lcd_put_u8str_P(X, Y, C) + #define _XLABEL(X,Y) _LABEL(X_LBL,X,Y) + #define _YLABEL(X,Y) _LABEL(Y_LBL,X,Y) + #define _ZLABEL(X,Y) _LABEL(Z_LBL,X,Y) + #else + #define _LCD_W_POS 8 + #define _PLOT_X 0 + #define _MAP_X 1 + #define _LABEL(X,Y,C) lcd_put_wchar(X, Y, C) + #define _XLABEL(X,Y) _LABEL('X',X,Y) + #define _YLABEL(X,Y) _LABEL('Y',X,Y) + #define _ZLABEL(X,Y) _LABEL('Z',X,Y) + #endif + + #if LCD_HEIGHT <= 3 // 16x2 or 20x2 display + + /** + * Show X and Y positions + */ + _XLABEL(_PLOT_X, 0); + lcd_put_u8str(ftostr52(LOGICAL_X_POSITION(ubl.mesh_index_to_xpos(x_plot)))); + _YLABEL(_LCD_W_POS, 0); + lcd_put_u8str(ftostr52(LOGICAL_Y_POSITION(ubl.mesh_index_to_ypos(y_plot)))); + + lcd_moveto(_PLOT_X, 0); + + #else // 16x4 or 20x4 display + + coordinate upper_left, lower_right, bottom_right_corner; + custom_char new_char; + uint8_t i, n, n_rows, n_cols; + lcd_uint_t j, k, l, m, bottom_line, right_edge, + x_map_pixels, y_map_pixels, + pixels_per_x_mesh_pnt, pixels_per_y_mesh_pnt, + suppress_x_offset = 0, suppress_y_offset = 0; + + const uint8_t y_plot_inv = (GRID_MAX_POINTS_Y) - 1 - y_plot; + + upper_left.column = 0; + upper_left.row = 0; + lower_right.column = 0; + lower_right.row = 0; + + clear_lcd(); + + x_map_pixels = (HD44780_CHAR_WIDTH) * (MESH_MAP_COLS) - 2; // Minus 2 because we are drawing a box around the map + y_map_pixels = (HD44780_CHAR_HEIGHT) * (MESH_MAP_ROWS) - 2; + + pixels_per_x_mesh_pnt = x_map_pixels / (GRID_MAX_POINTS_X); + pixels_per_y_mesh_pnt = y_map_pixels / (GRID_MAX_POINTS_Y); + + if (pixels_per_x_mesh_pnt >= HD44780_CHAR_WIDTH) { // There are only 2 custom characters available, so the X + pixels_per_x_mesh_pnt = HD44780_CHAR_WIDTH; // Size of the mesh point needs to fit within them independent + suppress_x_offset = 1; // Of where the starting pixel is located. + } + + if (pixels_per_y_mesh_pnt >= HD44780_CHAR_HEIGHT) { // There are only 2 custom characters available, so the Y + pixels_per_y_mesh_pnt = HD44780_CHAR_HEIGHT; // Size of the mesh point needs to fit within them independent + suppress_y_offset = 1; // Of where the starting pixel is located. + } + + x_map_pixels = pixels_per_x_mesh_pnt * (GRID_MAX_POINTS_X); // Now we have the right number of pixels to make both + y_map_pixels = pixels_per_y_mesh_pnt * (GRID_MAX_POINTS_Y); // Directions fit nicely + + right_edge = pixels_per_x_mesh_pnt * (GRID_MAX_POINTS_X) + 1; // Find location of right edge within the character cell + bottom_line = pixels_per_y_mesh_pnt * (GRID_MAX_POINTS_Y) + 1; // Find location of bottom line within the character cell + + n_rows = bottom_line / (HD44780_CHAR_HEIGHT) + 1; + n_cols = right_edge / (HD44780_CHAR_WIDTH) + 1; + + for (i = 0; i < n_cols; i++) { + lcd_put_wchar(i, 0, CHAR_LINE_TOP); // Box Top line + lcd_put_wchar(i, n_rows - 1, CHAR_LINE_BOT); // Box Bottom line + } + + for (j = 0; j < n_rows; j++) { + lcd_put_wchar(0, j, CHAR_EDGE_L); // Box Left edge + lcd_put_wchar(n_cols - 1, j, CHAR_EDGE_R); // Box Right edge + } + + /** + * If the entire 4th row is not in use, do not put vertical bars all the way down to the bottom of the display + */ + + k = pixels_per_y_mesh_pnt * (GRID_MAX_POINTS_Y) + 2; + l = (HD44780_CHAR_HEIGHT) * n_rows; + if (l > k && l - k >= (HD44780_CHAR_HEIGHT) / 2) { + lcd_put_wchar(0, n_rows - 1, ' '); // Box Left edge + lcd_put_wchar(n_cols - 1, n_rows - 1, ' '); // Box Right edge + } + + clear_custom_char(&new_char); + new_char.custom_char_bits[0] = 0b11111U; // Char #0 is used for the box top line + lcd.createChar(CHAR_LINE_TOP, (uint8_t*)&new_char); + + clear_custom_char(&new_char); + k = (GRID_MAX_POINTS_Y) * pixels_per_y_mesh_pnt + 1; // Row of pixels for the bottom box line + l = k % (HD44780_CHAR_HEIGHT); // Row within relevant character cell + new_char.custom_char_bits[l] = 0b11111U; // Char #1 is used for the box bottom line + lcd.createChar(CHAR_LINE_BOT, (uint8_t*)&new_char); + + clear_custom_char(&new_char); + for (j = 0; j < HD44780_CHAR_HEIGHT; j++) + new_char.custom_char_bits[j] = 0b10000U; // Char #2 is used for the box left edge + lcd.createChar(CHAR_EDGE_L, (uint8_t*)&new_char); + + clear_custom_char(&new_char); + m = (GRID_MAX_POINTS_X) * pixels_per_x_mesh_pnt + 1; // Column of pixels for the right box line + n = m % (HD44780_CHAR_WIDTH); // Column within relevant character cell + i = HD44780_CHAR_WIDTH - 1 - n; // Column within relevant character cell (0 on the right) + for (j = 0; j < HD44780_CHAR_HEIGHT; j++) + new_char.custom_char_bits[j] = (uint8_t)_BV(i); // Char #3 is used for the box right edge + lcd.createChar(CHAR_EDGE_R, (uint8_t*)&new_char); + + i = x_plot * pixels_per_x_mesh_pnt - suppress_x_offset; + j = y_plot_inv * pixels_per_y_mesh_pnt - suppress_y_offset; + upper_left = pixel_location(i, j); + + k = (x_plot + 1) * pixels_per_x_mesh_pnt - 1 - suppress_x_offset; + l = (y_plot_inv + 1) * pixels_per_y_mesh_pnt - 1 - suppress_y_offset; + lower_right = pixel_location(k, l); + + bottom_right_corner = pixel_location(x_map_pixels, y_map_pixels); + + /** + * First, handle the simple case where everything is within a single character cell. + * If part of the Mesh Plot is outside of this character cell, we will follow up + * and deal with that next. + */ + + clear_custom_char(&new_char); + const lcd_uint_t ypix = _MIN(upper_left.y_pixel_offset + pixels_per_y_mesh_pnt, HD44780_CHAR_HEIGHT); + for (j = upper_left.y_pixel_offset; j < ypix; j++) { + i = upper_left.x_pixel_mask; + for (k = 0; k < pixels_per_x_mesh_pnt; k++) { + new_char.custom_char_bits[j] |= i; + i >>= 1; + } + } + + prep_and_put_map_char(new_char, upper_left, lower_right, bottom_right_corner, TOP_LEFT, CHAR_UL_UL, upper_left.column, upper_left.row); + + /** + * Next, check for two side by side character cells being used to display the Mesh Point + * If found... do the right hand character cell next. + */ + if (upper_left.column == lower_right.column - 1) { + l = upper_left.x_pixel_offset; + clear_custom_char(&new_char); + for (j = upper_left.y_pixel_offset; j < ypix; j++) { + i = _BV(HD44780_CHAR_WIDTH - 1); // Fill in the left side of the right character cell + for (k = 0; k < pixels_per_x_mesh_pnt - 1 - l; k++) { + new_char.custom_char_bits[j] |= i; + i >>= 1; + } + } + prep_and_put_map_char(new_char, upper_left, lower_right, bottom_right_corner, TOP_RIGHT, CHAR_LR_UL, lower_right.column, upper_left.row); + } + + /** + * Next, check for two character cells stacked on top of each other being used to display the Mesh Point + */ + if (upper_left.row == lower_right.row - 1) { + l = HD44780_CHAR_HEIGHT - upper_left.y_pixel_offset; // Number of pixel rows in top character cell + k = pixels_per_y_mesh_pnt - l; // Number of pixel rows in bottom character cell + clear_custom_char(&new_char); + for (j = 0; j < k; j++) { + i = upper_left.x_pixel_mask; + for (m = 0; m < pixels_per_x_mesh_pnt; m++) { // Fill in the top side of the bottom character cell + new_char.custom_char_bits[j] |= i; + if (!(i >>= 1)) break; + } + } + prep_and_put_map_char(new_char, upper_left, lower_right, bottom_right_corner, LOWER_LEFT, CHAR_UL_LR, upper_left.column, lower_right.row); + } + + /** + * Next, check for four character cells being used to display the Mesh Point. If that is + * what is here, we work to fill in the character cell that is down one and to the right one + * from the upper_left character cell. + */ + + if (upper_left.column == lower_right.column - 1 && upper_left.row == lower_right.row - 1) { + l = HD44780_CHAR_HEIGHT - upper_left.y_pixel_offset; // Number of pixel rows in top character cell + k = pixels_per_y_mesh_pnt - l; // Number of pixel rows in bottom character cell + clear_custom_char(&new_char); + for (j = 0; j < k; j++) { + l = upper_left.x_pixel_offset; + i = _BV(HD44780_CHAR_WIDTH - 1); // Fill in the left side of the right character cell + for (m = 0; m < pixels_per_x_mesh_pnt - 1 - l; m++) { // Fill in the top side of the bottom character cell + new_char.custom_char_bits[j] |= i; + i >>= 1; + } + } + prep_and_put_map_char(new_char, upper_left, lower_right, bottom_right_corner, LOWER_RIGHT, CHAR_LR_LR, lower_right.column, lower_right.row); + } + + #endif + + /** + * Print plot position + */ + lcd_put_wchar(_LCD_W_POS, 0, '('); + lcd_put_u8str(ui8tostr3rj(x_plot)); + lcd_put_wchar(','); + lcd_put_u8str(ui8tostr3rj(y_plot)); + lcd_put_wchar(')'); + + #if LCD_HEIGHT <= 3 // 16x2 or 20x2 display + + /** + * Print Z values + */ + _ZLABEL(_LCD_W_POS, 1); + if (!isnan(ubl.z_values[x_plot][y_plot])) + lcd_put_u8str(ftostr43sign(ubl.z_values[x_plot][y_plot])); + else + lcd_put_u8str_P(PSTR(" -----")); + + #else // 16x4 or 20x4 display + + /** + * Show all values at right of screen + */ + _XLABEL(_LCD_W_POS, 1); + lcd_put_u8str(ftostr52(LOGICAL_X_POSITION(ubl.mesh_index_to_xpos(x_plot)))); + _YLABEL(_LCD_W_POS, 2); + lcd_put_u8str(ftostr52(LOGICAL_Y_POSITION(ubl.mesh_index_to_ypos(y_plot)))); + + /** + * Show the location value + */ + _ZLABEL(_LCD_W_POS, 3); + if (!isnan(ubl.z_values[x_plot][y_plot])) + lcd_put_u8str(ftostr43sign(ubl.z_values[x_plot][y_plot])); + else + lcd_put_u8str_P(PSTR(" -----")); + + #endif // LCD_HEIGHT > 3 + } + + void add_edges_to_custom_char(custom_char &custom, const coordinate &ul, const coordinate &lr, const coordinate &brc, const uint8_t cell_location) { + uint8_t i, k; + int16_t n_rows = lr.row - ul.row + 1, + n_cols = lr.column - ul.column + 1; + + /** + * Check if Top line of box needs to be filled in + */ + + if (ul.row == 0 && (cell_location & (TOP_LEFT|TOP_RIGHT))) { // Only fill in the top line for the top character cells + + if (n_cols == 1) { + if (ul.column != brc.column) + custom.custom_char_bits[0] = 0xFF; // Single column in middle + else + for (i = brc.x_pixel_offset; i < HD44780_CHAR_WIDTH; i++) // Single column on right side + SBI(custom.custom_char_bits[0], i); + } + else if ((cell_location & TOP_LEFT) || lr.column != brc.column) // Multiple column in the middle or with right cell in middle + custom.custom_char_bits[0] = 0xFF; + else + for (i = brc.x_pixel_offset; i < HD44780_CHAR_WIDTH; i++) + SBI(custom.custom_char_bits[0], i); + } + + /** + * Check if left line of box needs to be filled in + */ + if (cell_location & (TOP_LEFT|LOWER_LEFT)) { + if (ul.column == 0) { // Left column of characters on LCD Display + k = ul.row == brc.row ? brc.y_pixel_offset : HD44780_CHAR_HEIGHT; // If it isn't the last row... do the full character cell + for (i = 0; i < k; i++) + SBI(custom.custom_char_bits[i], HD44780_CHAR_WIDTH - 1); + } + } + + /** + * Check if bottom line of box needs to be filled in + */ + + // Single row of mesh plot cells + if (n_rows == 1 /* && (cell_location & (TOP_LEFT|TOP_RIGHT)) */ && ul.row == brc.row) { + if (n_cols == 1) // Single row, single column case + k = ul.column == brc.column ? brc.x_pixel_mask : 0x01; + else if (cell_location & TOP_RIGHT) // Single row, multiple column case + k = lr.column == brc.column ? brc.x_pixel_mask : 0x01; + else // Single row, left of multiple columns + k = 0x01; + while (k < _BV(HD44780_CHAR_WIDTH)) { + custom.custom_char_bits[brc.y_pixel_offset] |= k; + k <<= 1; + } + } + + // Double row of characters on LCD Display + // And this is a bottom custom character + if (n_rows == 2 && (cell_location & (LOWER_LEFT|LOWER_RIGHT)) && lr.row == brc.row) { + if (n_cols == 1) // Double row, single column case + k = ul.column == brc.column ? brc.x_pixel_mask : 0x01; + else if (cell_location & LOWER_RIGHT) // Double row, multiple column case + k = lr.column == brc.column ? brc.x_pixel_mask : 0x01; + else // Double row, left of multiple columns + k = 0x01; + while (k < _BV(HD44780_CHAR_WIDTH)) { + custom.custom_char_bits[brc.y_pixel_offset] |= k; + k <<= 1; + } + } + + /** + * Check if right line of box needs to be filled in + */ + + // Nothing to do if the lower right part of the mesh pnt isn't in the same column as the box line + if (lr.column == brc.column) { + // This mesh point is in the same character cell as the right box line + if (ul.column == brc.column || (cell_location & (TOP_RIGHT|LOWER_RIGHT))) { + // If not the last row... do the full character cell + k = ul.row == brc.row ? brc.y_pixel_offset : HD44780_CHAR_HEIGHT; + for (i = 0; i < k; i++) custom.custom_char_bits[i] |= brc.x_pixel_mask; + } + } + } + + #endif // AUTO_BED_LEVELING_UBL + +#endif // HAS_LCD_MENU + +#endif // HAS_MARLINUI_HD44780 diff --git a/Marlin/src/lcd/HD44780/marlinui_HD44780.h b/Marlin/src/lcd/HD44780/marlinui_HD44780.h new file mode 100644 index 000000000000..62c0c7620220 --- /dev/null +++ b/Marlin/src/lcd/HD44780/marlinui_HD44780.h @@ -0,0 +1,107 @@ +/** + * 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 + +/** + * Hitachi HD44780 display defines and headers + */ + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(LCD_I2C_TYPE_PCF8575) + + // NOTE: These are register-mapped pins on the PCF8575 controller, not Arduino pins. + #define LCD_I2C_PIN_BL 3 + #define LCD_I2C_PIN_EN 2 + #define LCD_I2C_PIN_RW 1 + #define LCD_I2C_PIN_RS 0 + #define LCD_I2C_PIN_D4 4 + #define LCD_I2C_PIN_D5 5 + #define LCD_I2C_PIN_D6 6 + #define LCD_I2C_PIN_D7 7 + + #include + #include + #include + #define LCD_CLASS LiquidCrystal_I2C + +#elif ENABLED(LCD_I2C_TYPE_MCP23017) + + // For the LED indicators (which may be mapped to different events in update_indicators()) + #define LCD_HAS_STATUS_INDICATORS + #define LED_A 0x04 //100 + #define LED_B 0x02 //010 + #define LED_C 0x01 //001 + + #include + #include + #define LCD_CLASS LiquidTWI2 + +#elif ENABLED(LCD_I2C_TYPE_MCP23008) + + #include + #include + #define LCD_CLASS LiquidTWI2 + +#elif ENABLED(LCD_I2C_TYPE_PCA8574) + + #include + #define LCD_CLASS LiquidCrystal_I2C + +#elif ENABLED(SR_LCD_2W_NL) + + // 2 wire Non-latching LCD SR from: + // https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/schematics#!shiftregister-connection + #include + #include + #define LCD_CLASS LiquidCrystal_SR + +#elif ENABLED(SR_LCD_3W_NL) + + // NewLiquidCrystal didn't work, so this uses + // https://github.com/mikeshub/SailfishLCD + + #include + #define LCD_CLASS LiquidCrystalSerial + +#elif ENABLED(LCM1602) + + #include + #include + #include + #define LCD_CLASS LiquidCrystal_I2C + +#elif ENABLED(YHCB2004) + + #include + #define LCD_CLASS LiquidCrystal_AIP31068_SPI + +#else + + // Standard directly connected LCD implementations + #include + #define LCD_CLASS LiquidCrystal + +#endif + +#include "../fontutils.h" +#include "../lcdprint.h" diff --git a/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp b/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp deleted file mode 100644 index e6cc22746571..000000000000 --- a/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp +++ /dev/null @@ -1,1520 +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 . - * - */ - -#include "../../inc/MarlinConfigPre.h" - -#if HAS_MARLINUI_HD44780 - -/** - * ultralcd_HD44780.cpp - * - * LCD display implementations for Hitachi HD44780. - * These are the most common LCD character displays. - */ - -#include "ultralcd_HD44780.h" -#include "../ultralcd.h" -#include "../../libs/numtostr.h" - -#include "../../sd/cardreader.h" -#include "../../module/temperature.h" -#include "../../module/printcounter.h" -#include "../../module/planner.h" -#include "../../module/motion.h" - -#if DISABLED(LCD_PROGRESS_BAR) && BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) - #include "../../feature/filwidth.h" - #include "../../gcode/parser.h" -#endif - -#if ENABLED(AUTO_BED_LEVELING_UBL) - #include "../../feature/bedlevel/bedlevel.h" -#endif - -// -// Create LCD instance and chipset-specific information -// - -#if ENABLED(LCD_I2C_TYPE_PCF8575) - - 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) - - LCD_CLASS lcd(LCD_I2C_ADDRESS - #ifdef DETECT_DEVICE - , 1 - #endif - ); - -#elif ENABLED(LCD_I2C_TYPE_PCA8574) - - LCD_CLASS lcd(LCD_I2C_ADDRESS, LCD_WIDTH, LCD_HEIGHT); - -#elif ENABLED(SR_LCD_2W_NL) - - // 2 wire Non-latching LCD SR from: - // https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/schematics#!shiftregister-connection - - LCD_CLASS lcd(SR_DATA_PIN, SR_CLK_PIN - #if PIN_EXISTS(SR_STROBE) - , SR_STROBE_PIN - #endif - ); - -#elif ENABLED(SR_LCD_3W_NL) - - // NewLiquidCrystal was not working - // https://github.com/mikeshub/SailfishLCD - // uses the code directly from Sailfish - - LCD_CLASS lcd(SR_STROBE_PIN, SR_DATA_PIN, SR_CLK_PIN); - -#elif ENABLED(LCM1602) - - LCD_CLASS lcd(0x27, 2, 1, 0, 4, 5, 6, 7, 3, POSITIVE); - -#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); - -#endif - -static void createChar_P(const char c, const byte * const ptr) { - byte temp[8]; - LOOP_L_N(i, 8) - temp[i] = pgm_read_byte(&ptr[i]); - lcd.createChar(c, temp); -} - -#if ENABLED(LCD_PROGRESS_BAR) - #define LCD_STR_PROGRESS "\x03\x04\x05" -#endif - -#if ENABLED(LCD_USE_I2C_BUZZER) - void MarlinUI::buzz(const long duration, const uint16_t freq) { - lcd.buzz(duration, freq); - } -#endif - -void MarlinUI::set_custom_characters(const HD44780CharSet screen_charset/*=CHARSET_INFO*/) { - #if NONE(LCD_PROGRESS_BAR, SHOW_BOOTSCREEN) - UNUSED(screen_charset); - #endif - - // CHARSET_BOOT - #if ENABLED(SHOW_BOOTSCREEN) - const static PROGMEM byte corner[4][8] = { { - B00000, - B00000, - B00000, - B00000, - B00001, - B00010, - B00100, - B00100 - }, { - B00000, - B00000, - B00000, - B11100, - B11100, - B01100, - B00100, - B00100 - }, { - B00100, - B00010, - B00001, - B00000, - B00000, - B00000, - B00000, - B00000 - }, { - B00100, - B01000, - B10000, - B00000, - B00000, - B00000, - B00000, - B00000 - } }; - #endif // SHOW_BOOTSCREEN - - // CHARSET_INFO - const static PROGMEM byte bedTemp[8] = { - B00000, - B11111, - B10101, - B10001, - B10101, - B11111, - B00000, - B00000 - }; - - const static PROGMEM byte degree[8] = { - B01100, - B10010, - B10010, - B01100, - B00000, - B00000, - B00000, - B00000 - }; - - const static PROGMEM byte thermometer[8] = { - B00100, - B01010, - B01010, - B01010, - B01010, - B10001, - B10001, - B01110 - }; - - const static PROGMEM byte uplevel[8] = { - B00100, - B01110, - B11111, - B00100, - B11100, - B00000, - B00000, - B00000 - }; - - const static PROGMEM byte feedrate[8] = { - #if LCD_INFO_SCREEN_STYLE == 1 - B00000, - B00100, - B10010, - B01001, - B10010, - B00100, - B00000, - B00000 - #else - B11100, - B10000, - B11000, - B10111, - B00101, - B00110, - B00101, - B00000 - #endif - }; - - const static PROGMEM byte clock[8] = { - B00000, - B01110, - B10011, - B10101, - B10001, - B01110, - B00000, - B00000 - }; - - #if ENABLED(LCD_PROGRESS_BAR) - - // CHARSET_INFO - const static PROGMEM byte progress[3][8] = { { - B00000, - B10000, - B10000, - B10000, - B10000, - B10000, - B10000, - B00000 - }, { - B00000, - B10100, - B10100, - B10100, - B10100, - B10100, - B10100, - B00000 - }, { - B00000, - B10101, - B10101, - B10101, - B10101, - B10101, - B10101, - B00000 - } }; - - #endif // LCD_PROGRESS_BAR - - #if BOTH(SDSUPPORT, HAS_LCD_MENU) - - // CHARSET_MENU - const static PROGMEM byte refresh[8] = { - B00000, - B00110, - B11001, - B11000, - B00011, - B10011, - B01100, - B00000, - }; - const static PROGMEM byte folder[8] = { - B00000, - B11100, - B11111, - B10001, - B10001, - B11111, - B00000, - B00000 - }; - - #endif // SDSUPPORT - - #if ENABLED(SHOW_BOOTSCREEN) - // Set boot screen corner characters - if (screen_charset == CHARSET_BOOT) { - for (uint8_t i = 4; i--;) - createChar_P(i, corner[i]); - } - else - #endif - { // Info Screen uses 5 special characters - createChar_P(LCD_STR_BEDTEMP[0], bedTemp); - createChar_P(LCD_STR_DEGREE[0], degree); - createChar_P(LCD_STR_THERMOMETER[0], thermometer); - createChar_P(LCD_STR_FEEDRATE[0], feedrate); - createChar_P(LCD_STR_CLOCK[0], clock); - - #if ENABLED(LCD_PROGRESS_BAR) - if (screen_charset == CHARSET_INFO) { // 3 Progress bar characters for info screen - for (int16_t i = 3; i--;) - createChar_P(LCD_STR_PROGRESS[i], progress[i]); - } - else - #endif - { - createChar_P(LCD_STR_UPLEVEL[0], uplevel); - #if BOTH(SDSUPPORT, HAS_LCD_MENU) - // SD Card sub-menu special characters - createChar_P(LCD_STR_REFRESH[0], refresh); - createChar_P(LCD_STR_FOLDER[0], folder); - #endif - } - } - -} - -void MarlinUI::init_lcd() { - - #if ENABLED(LCD_I2C_TYPE_PCF8575) - lcd.begin(LCD_WIDTH, LCD_HEIGHT); - #ifdef LCD_I2C_PIN_BL - lcd.setBacklightPin(LCD_I2C_PIN_BL, POSITIVE); - lcd.setBacklight(HIGH); - #endif - - #elif ENABLED(LCD_I2C_TYPE_MCP23017) - lcd.setMCPType(LTI_TYPE_MCP23017); - lcd.begin(LCD_WIDTH, LCD_HEIGHT); - update_indicators(); - - #elif ENABLED(LCD_I2C_TYPE_MCP23008) - lcd.setMCPType(LTI_TYPE_MCP23008); - lcd.begin(LCD_WIDTH, LCD_HEIGHT); - - #elif ENABLED(LCD_I2C_TYPE_PCA8574) - lcd.init(); - lcd.backlight(); - - #else - lcd.begin(LCD_WIDTH, LCD_HEIGHT); - #endif - - set_custom_characters(on_status_screen() ? CHARSET_INFO : CHARSET_MENU); - - lcd.clear(); -} - -bool MarlinUI::detected() { - return (true - #if EITHER(LCD_I2C_TYPE_MCP23017, LCD_I2C_TYPE_MCP23008) && defined(DETECT_DEVICE) - && lcd.LcdDetected() == 1 - #endif - ); -} - -#if HAS_SLOW_BUTTONS - uint8_t MarlinUI::read_slow_buttons() { - #if ENABLED(LCD_I2C_TYPE_MCP23017) - // Reading these buttons is too slow for interrupt context - // so they are read during LCD update in the main loop. - uint8_t slow_bits = lcd.readButtons() - #if !BUTTON_EXISTS(ENC) - << B_I2C_BTN_OFFSET - #endif - ; - #if ENABLED(LCD_I2C_VIKI) - if ((slow_bits & (B_MI | B_RI)) && PENDING(millis(), next_button_update_ms)) // LCD clicked - slow_bits &= ~(B_MI | B_RI); // Disable LCD clicked buttons if screen is updated - #endif - return slow_bits; - #endif // LCD_I2C_TYPE_MCP23017 - } -#endif - -void MarlinUI::clear_lcd() { lcd.clear(); } - -#if ENABLED(SHOW_BOOTSCREEN) - - void lcd_erase_line(const lcd_uint_t line) { - lcd_moveto(0, line); - for (uint8_t i = LCD_WIDTH + 1; --i;) - lcd_put_wchar(' '); - } - - // Scroll the PSTR 'text' in a 'len' wide field for 'time' milliseconds at position col,line - void lcd_scroll(const lcd_uint_t col, const lcd_uint_t line, PGM_P const text, const uint8_t len, const int16_t time) { - uint8_t slen = utf8_strlen_P(text); - if (slen < len) { - lcd_put_u8str_max_P(col, line, text, len); - for (; slen < len; ++slen) lcd_put_wchar(' '); - safe_delay(time); - } - else { - PGM_P p = text; - int dly = time / _MAX(slen, 1); - LOOP_LE_N(i, slen) { - - // Print the text at the correct place - lcd_put_u8str_max_P(col, line, p, len); - - // Fill with spaces - for (uint8_t ix = slen - i; ix < len; ++ix) lcd_put_wchar(' '); - - // Delay - safe_delay(dly); - - // Advance to the next UTF8 valid position - p++; - while (!START_OF_UTF8_CHAR(pgm_read_byte(p))) p++; - } - } - } - - static void logo_lines(PGM_P const extra) { - int16_t indent = (LCD_WIDTH - 8 - utf8_strlen_P(extra)) / 2; - lcd_put_wchar(indent, 0, '\x00'); lcd_put_u8str_P(PSTR( "------" )); lcd_put_wchar('\x01'); - lcd_put_u8str_P(indent, 1, PSTR("|Marlin|")); lcd_put_u8str_P(extra); - lcd_put_wchar(indent, 2, '\x02'); lcd_put_u8str_P(PSTR( "------" )); lcd_put_wchar('\x03'); - } - - void MarlinUI::show_bootscreen() { - set_custom_characters(CHARSET_BOOT); - lcd.clear(); - - #define LCD_EXTRA_SPACE (LCD_WIDTH-8) - - #define CENTER_OR_SCROLL(STRING,DELAY) \ - lcd_erase_line(3); \ - if (utf8_strlen(STRING) <= LCD_WIDTH) { \ - lcd_put_u8str_P((LCD_WIDTH - utf8_strlen_P(PSTR(STRING))) / 2, 3, PSTR(STRING)); \ - safe_delay(DELAY); \ - } \ - else { \ - lcd_scroll(0, 3, PSTR(STRING), LCD_WIDTH, DELAY); \ - } - - // - // Show the Marlin logo with splash line 1 - // - if (LCD_EXTRA_SPACE >= utf8_strlen(SHORT_BUILD_VERSION) + 1) { - // - // Show the Marlin logo, splash line1, and splash line 2 - // - logo_lines(PSTR(" " SHORT_BUILD_VERSION)); - CENTER_OR_SCROLL(MARLIN_WEBSITE_URL, 2000); - } - else { - // - // Show the Marlin logo and short build version - // After a delay show the website URL - // - extern const char NUL_STR[]; - logo_lines(NUL_STR); - CENTER_OR_SCROLL(SHORT_BUILD_VERSION, 1500); - CENTER_OR_SCROLL(MARLIN_WEBSITE_URL, 1500); - #ifdef STRING_SPLASH_LINE3 - CENTER_OR_SCROLL(STRING_SPLASH_LINE3, 1500); - #endif - } - - lcd.clear(); - safe_delay(100); - set_custom_characters(CHARSET_INFO); - lcd.clear(); - } - -#endif // SHOW_BOOTSCREEN - -void MarlinUI::draw_kill_screen() { - lcd_put_u8str(0, 0, status_message); - lcd_uint_t y = 2; - #if LCD_HEIGHT >= 4 - lcd_put_u8str_P(0, y++, GET_TEXT(MSG_HALTED)); - #endif - lcd_put_u8str_P(0, y, GET_TEXT(MSG_PLEASE_RESET)); -} - -// -// Before homing, blink '123' <-> '???'. -// Homed but unknown... '123' <-> ' '. -// Homed and known, display constantly. -// -FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const bool blink) { - lcd_put_wchar('X' + uint8_t(axis)); - if (blink) - lcd_put_u8str(value); - else { - if (!TEST(axis_homed, axis)) - while (const char c = *value++) lcd_put_wchar(c <= '.' ? c : '?'); - else { - #if NONE(HOME_AFTER_DEACTIVATE, DISABLE_REDUCED_ACCURACY_WARNING) - if (!TEST(axis_known_position, axis)) - lcd_put_u8str_P(axis == Z_AXIS ? PSTR(" ") : PSTR(" ")); - else - #endif - lcd_put_u8str(value); - } - } -} - -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 float t1 = (isBed ? thermalManager.degBed() : thermalManager.degHotend(heater_id)), - t2 = (isBed ? thermalManager.degTargetBed() : thermalManager.degTargetHotend(heater_id)); - #else - const float t1 = thermalManager.degHotend(heater_id), t2 = thermalManager.degTargetHotend(heater_id); - #endif - - if (prefix >= 0) lcd_put_wchar(prefix); - - lcd_put_u8str(i16tostr3rj(t1 + 0.5)); - lcd_put_wchar('/'); - - #if !HEATER_IDLE_HANDLER - UNUSED(blink); - #else - if (!blink && thermalManager.heater_idle[thermalManager.idle_index_for_id(heater_id)].timed_out) { - lcd_put_wchar(' '); - if (t2 >= 10) lcd_put_wchar(' '); - if (t2 >= 100) lcd_put_wchar(' '); - } - else - #endif - lcd_put_u8str(i16tostr3left(t2 + 0.5)); - - if (prefix >= 0) { - lcd_put_wchar(LCD_STR_DEGREE[0]); - lcd_put_wchar(' '); - if (t2 < 10) lcd_put_wchar(' '); - } -} - -FORCE_INLINE void _draw_bed_status(const bool blink) { - _draw_heater_status(H_BED, TERN0(HAS_LEVELING, blink && planner.leveling_active) ? '_' : LCD_STR_BEDTEMP[0], blink); -} - -#if HAS_PRINT_PROGRESS - - FORCE_INLINE void _draw_print_progress() { - const uint8_t progress = ui.get_progress_percent(); - lcd_put_u8str_P(PSTR(TERN(SDSUPPORT, "SD", "P:"))); - if (progress) - lcd_put_u8str(ui8tostr3rj(progress)); - else - lcd_put_u8str_P(PSTR("---")); - lcd_put_wchar('%'); - } - -#endif - -#if ENABLED(LCD_PROGRESS_BAR) - - void MarlinUI::draw_progress_bar(const uint8_t percent) { - const int16_t tix = (int16_t)(percent * (LCD_WIDTH) * 3) / 100, - cel = tix / 3, - rem = tix % 3; - uint8_t i = LCD_WIDTH; - char msg[LCD_WIDTH + 1], b = ' '; - msg[LCD_WIDTH] = '\0'; - while (i--) { - if (i == cel - 1) - b = LCD_STR_PROGRESS[2]; - else if (i == cel && rem != 0) - b = LCD_STR_PROGRESS[rem - 1]; - msg[i] = b; - } - lcd_put_u8str(msg); - } - -#endif // LCD_PROGRESS_BAR - -void MarlinUI::draw_status_message(const bool blink) { - - lcd_moveto(0, LCD_HEIGHT - 1); - - #if ENABLED(LCD_PROGRESS_BAR) - - // Draw the progress bar if the message has shown long enough - // or if there is no message set. - if (ELAPSED(millis(), progress_bar_ms + PROGRESS_BAR_MSG_TIME) || !has_status()) { - const uint8_t progress = get_progress_percent(); - if (progress > 2) return draw_progress_bar(progress); - } - - #elif BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) - - // Alternate Status message and Filament display - if (ELAPSED(millis(), next_filament_display)) { - lcd_put_u8str_P(PSTR("Dia ")); - lcd_put_u8str(ftostr12ns(filwidth.measured_mm)); - lcd_put_u8str_P(PSTR(" V")); - lcd_put_u8str(i16tostr3rj(planner.volumetric_percent(parser.volumetric_enabled))); - lcd_put_wchar('%'); - return; - } - - #endif // FILAMENT_LCD_DISPLAY && SDSUPPORT - - #if ENABLED(STATUS_MESSAGE_SCROLLING) - static bool last_blink = false; - - // Get the UTF8 character count of the string - uint8_t slen = utf8_strlen(status_message); - - // If the string fits into the LCD, just print it and do not scroll it - if (slen <= LCD_WIDTH) { - - // The string isn't scrolling and may not fill the screen - lcd_put_u8str(status_message); - - // Fill the rest with spaces - while (slen < LCD_WIDTH) { lcd_put_wchar(' '); ++slen; } - } - else { - // String is larger than the available space in screen. - - // Get a pointer to the next valid UTF8 character - // and the string remaining length - uint8_t rlen; - const char *stat = status_and_len(rlen); - lcd_put_u8str_max(stat, LCD_WIDTH); // The string leaves space - - // If the remaining string doesn't completely fill the screen - if (rlen < LCD_WIDTH) { - lcd_put_wchar('.'); // Always at 1+ spaces left, draw a dot - uint8_t chars = LCD_WIDTH - rlen; // Amount of space left in characters - if (--chars) { // Draw a second dot if there's space - lcd_put_wchar('.'); - if (--chars) - lcd_put_u8str_max(status_message, chars); // Print a second copy of the message - } - } - if (last_blink != blink) { - last_blink = blink; - advance_status_scroll(); - } - } - #else - UNUSED(blink); - - // Get the UTF8 character count of the string - uint8_t slen = utf8_strlen(status_message); - - // Just print the string to the LCD - lcd_put_u8str_max(status_message, LCD_WIDTH); - - // Fill the rest with spaces if there are missing spaces - while (slen < LCD_WIDTH) { - lcd_put_wchar(' '); - ++slen; - } - #endif -} - -/** - * LCD_INFO_SCREEN_STYLE 0 : Classic Status Screen - * - * 16x2 |000/000 B000/000| - * |0123456789012345| - * - * 16x4 |000/000 B000/000| - * |SD---% Z 000.00| - * |F---% T--:--| - * |0123456789012345| - * - * 20x2 |T000/000° B000/000° | - * |01234567890123456789| - * - * 20x4 |T000/000° B000/000° | - * |X 000 Y 000 Z000.000| - * |F---% SD---% T--:--| - * |01234567890123456789| - * - * LCD_INFO_SCREEN_STYLE 1 : Průša-style Status Screen - * - * |T000/000° Z 000.00 | - * |B000/000° F---% | - * |SD---% T--:-- | - * |01234567890123456789| - * - * |T000/000° Z 000.00 | - * |T000/000° F---% | - * |B000/000° SD---% | - * |01234567890123456789| - */ - -void MarlinUI::draw_status_screen() { - - const bool blink = get_blink(); - lcd_moveto(0, 0); - - #if LCD_INFO_SCREEN_STYLE == 0 - - // ========== Line 1 ========== - - #if LCD_WIDTH < 20 - - // - // Hotend 0 Temperature - // - _draw_heater_status(H_E0, -1, blink); - - // - // Hotend 1 or Bed Temperature - // - #if HAS_MULTI_HOTEND - lcd_moveto(8, 0); - _draw_heater_status(H_E1, LCD_STR_THERMOMETER[0], blink); - #elif HAS_HEATED_BED - lcd_moveto(8, 0); - _draw_bed_status(blink); - #endif - - #else // LCD_WIDTH >= 20 - - // - // Hotend 0 Temperature - // - _draw_heater_status(H_E0, LCD_STR_THERMOMETER[0], blink); - - // - // Hotend 1 or Bed Temperature - // - #if HAS_MULTI_HOTEND - lcd_moveto(10, 0); - _draw_heater_status(H_E1, LCD_STR_THERMOMETER[0], blink); - #elif HAS_HEATED_BED - lcd_moveto(10, 0); - _draw_bed_status(blink); - #endif - - #endif // LCD_WIDTH >= 20 - - // ========== Line 2 ========== - - #if LCD_HEIGHT > 2 - - #if LCD_WIDTH < 20 - - #if HAS_PRINT_PROGRESS - lcd_moveto(0, 2); - _draw_print_progress(); - #endif - - #else // LCD_WIDTH >= 20 - - lcd_moveto(0, 1); - - // If the first line has two extruder temps, - // show more temperatures on the next line - - #if HOTENDS > 2 || (HAS_MULTI_HOTEND && HAS_HEATED_BED) - - #if HOTENDS > 2 - _draw_heater_status(H_E2, LCD_STR_THERMOMETER[0], blink); - lcd_moveto(10, 1); - #endif - - _draw_bed_status(blink); - - #else // HOTENDS <= 2 && (HOTENDS <= 1 || !HAS_HEATED_BED) - - #if HAS_DUAL_MIXING - - // Two-component mix / gradient instead of XY - - char mixer_messages[12]; - const char *mix_label; - #if ENABLED(GRADIENT_MIX) - if (mixer.gradient.enabled) { - mixer.update_mix_from_gradient(); - mix_label = "Gr"; - } - else - #endif - { - mixer.update_mix_from_vtool(); - mix_label = "Mx"; - } - sprintf_P(mixer_messages, PSTR("%s %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() || marlin_state == MF_SD_COMPLETE); - - if (show_e_total) { - #if ENABLED(LCD_SHOW_E_TOTAL) - char tmp[20]; - const uint8_t escale = e_move_accumulator >= 100000.0f ? 10 : 1; // After 100m switch to cm - sprintf_P(tmp, PSTR("E %ld%cm "), uint32_t(_MAX(e_move_accumulator, 0.0f)) / escale, escale == 10 ? 'c' : 'm'); // 1234567mm - lcd_put_u8str(tmp); - #endif - } - else { - const xy_pos_t lpos = current_position.asLogical(); - _draw_axis_value(X_AXIS, ftostr4sign(lpos.x), blink); - lcd_put_wchar(' '); - _draw_axis_value(Y_AXIS, ftostr4sign(lpos.y), blink); - } - - #endif // !HAS_DUAL_MIXING - - #endif // HOTENDS <= 2 && (HOTENDS <= 1 || !HAS_HEATED_BED) - - #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_wchar(planner.leveling_active || blink ? '_' : ' '); - #endif - - #endif // LCD_HEIGHT > 2 - - // ========== Line 3 ========== - - #if LCD_HEIGHT > 3 - - lcd_put_wchar(0, 2, LCD_STR_FEEDRATE[0]); - lcd_put_u8str(i16tostr3rj(feedrate_percentage)); - lcd_put_wchar('%'); - - char buffer[14]; - uint8_t timepos = 0; - #if ENABLED(SHOW_REMAINING_TIME) - const bool show_remain = TERN1(ROTATE_PROGRESS_DISPLAY, blink) && (printingIsActive() || marlin_state == MF_SD_COMPLETE); - if (show_remain) { - #if ENABLED(USE_M73_REMAINING_TIME) - duration_t remaining = get_remaining_time(); - #else - uint8_t progress = get_progress_percent(); - uint32_t elapsed = print_job_timer.duration(); - duration_t remaining = (progress > 0) ? ((elapsed * 25600 / progress) >> 8) - elapsed : 0; - #endif - const uint8_t len = remaining.toDigital(buffer); - timepos = LCD_WIDTH - 1 - len; - lcd_put_wchar(timepos, 2, 'R'); - } - #else - constexpr bool show_remain = false; - #endif - - if (!show_remain) { - duration_t elapsed = print_job_timer.duration(); - const uint8_t len = elapsed.toDigital(buffer); - timepos = LCD_WIDTH - 1 - len; - lcd_put_wchar(timepos, 2, LCD_STR_CLOCK[0]); - } - lcd_put_u8str(buffer); - - #if LCD_WIDTH >= 20 - lcd_moveto(timepos - 7, 2); - #if HAS_PRINT_PROGRESS - _draw_print_progress(); - #else - char c; - uint16_t per; - #if HAS_FAN0 - if (true - #if EXTRUDERS && ENABLED(ADAPTIVE_FAN_SLOWING) - && (blink || thermalManager.fan_speed_scaler[0] < 128) - #endif - ) { - uint16_t spd = thermalManager.fan_speed[0]; - if (blink) c = 'F'; - #if ENABLED(ADAPTIVE_FAN_SLOWING) - else { c = '*'; spd = thermalManager.scaledFanSpeed(0, spd); } - #endif - per = thermalManager.fanPercent(spd); - } - else - #endif - { - #if EXTRUDERS - c = 'E'; - per = planner.flow_percentage[0]; - #endif - } - lcd_put_wchar(c); - lcd_put_u8str(i16tostr3rj(per)); - lcd_put_wchar('%'); - #endif - #endif - - #endif // LCD_HEIGHT > 3 - - #elif LCD_INFO_SCREEN_STYLE == 1 - - // ========== Line 1 ========== - - // - // Hotend 0 Temperature - // - _draw_heater_status(H_E0, LCD_STR_THERMOMETER[0], blink); - - // - // Z Coordinate - // - lcd_moveto(LCD_WIDTH - 9, 0); - _draw_axis_value(Z_AXIS, ftostr52sp(LOGICAL_Z_POSITION(current_position.z)), blink); - - #if HAS_LEVELING && (HAS_MULTI_HOTEND || !HAS_HEATED_BED) - lcd_put_wchar(LCD_WIDTH - 1, 0, planner.leveling_active || blink ? '_' : ' '); - #endif - - // ========== Line 2 ========== - - // - // Hotend 1 or Bed Temperature - // - lcd_moveto(0, 1); - #if HAS_MULTI_HOTEND - _draw_heater_status(H_E1, LCD_STR_THERMOMETER[0], blink); - #elif HAS_HEATED_BED - _draw_bed_status(blink); - #endif - - lcd_put_wchar(LCD_WIDTH - 9, 1, LCD_STR_FEEDRATE[0]); - lcd_put_u8str(i16tostr3rj(feedrate_percentage)); - lcd_put_wchar('%'); - - // ========== Line 3 ========== - - // - // SD Percent, Hotend 2, or Bed - // - lcd_moveto(0, 2); - #if HOTENDS > 2 - _draw_heater_status(H_E2, LCD_STR_THERMOMETER[0], blink); - #elif HAS_MULTI_HOTEND && HAS_HEATED_BED - _draw_bed_status(blink); - #elif HAS_PRINT_PROGRESS - #define DREW_PRINT_PROGRESS - _draw_print_progress(); - #endif - - // - // Elapsed Time or SD Percent - // - lcd_moveto(LCD_WIDTH - 9, 2); - #if HAS_PRINT_PROGRESS && !defined(DREW_PRINT_PROGRESS) - _draw_print_progress(); - #else - duration_t elapsed = print_job_timer.duration(); - char buffer[14]; - (void)elapsed.toDigital(buffer); - lcd_put_wchar(LCD_STR_CLOCK[0]); - lcd_put_u8str(buffer); - #endif - - #endif // LCD_INFO_SCREEN_STYLE 1 - - // ========= Last Line ======== - - // - // Status Message (which may be a Progress Bar or Filament display) - // - draw_status_message(blink); -} - -#if HAS_LCD_MENU - - #include "../menu/menu.h" - - #if ENABLED(ADVANCED_PAUSE_FEATURE) - - void MarlinUI::draw_hotend_status(const uint8_t row, const uint8_t extruder) { - if (row < LCD_HEIGHT) { - lcd_moveto(LCD_WIDTH - 9, row); - _draw_heater_status((heater_id_t)extruder, LCD_STR_THERMOMETER[0], get_blink()); - } - } - - #endif // ADVANCED_PAUSE_FEATURE - - // Draw a static item with no left-right margin required. Centered by default. - void MenuItem_static::draw(const uint8_t row, PGM_P const pstr, const uint8_t style/*=SS_DEFAULT*/, const char * const vstr/*=nullptr*/) { - int8_t n = LCD_WIDTH; - lcd_moveto(0, row); - const int8_t plen = pstr ? utf8_strlen_P(pstr) : 0, - vlen = vstr ? utf8_strlen(vstr) : 0; - if (style & SS_CENTER) { - int8_t pad = (LCD_WIDTH - plen - vlen) / 2; - while (--pad >= 0) { lcd_put_wchar(' '); n--; } - } - if (plen) n = lcd_put_u8str_ind_P(pstr, itemIndex, itemString, n); - if (vlen) n -= lcd_put_u8str_max(vstr, n); - for (; n > 0; --n) lcd_put_wchar(' '); - } - - // Draw a generic menu item with pre_char (if selected) and post_char - void MenuItemBase::_draw(const bool sel, const uint8_t row, PGM_P const pstr, const char pre_char, const char post_char) { - lcd_put_wchar(0, row, sel ? pre_char : ' '); - uint8_t n = lcd_put_u8str_ind_P(pstr, itemIndex, itemString, LCD_WIDTH - 2); - for (; n; --n) lcd_put_wchar(' '); - lcd_put_wchar(post_char); - } - - // Draw a menu item with a (potentially) editable value - void MenuEditItemBase::draw(const bool sel, const uint8_t row, PGM_P const pstr, const char* const inStr, const bool pgm) { - const uint8_t vlen = inStr ? (pgm ? utf8_strlen_P(inStr) : utf8_strlen(inStr)) : 0; - lcd_put_wchar(0, row, sel ? LCD_STR_ARROW_RIGHT[0] : ' '); - uint8_t n = lcd_put_u8str_ind_P(pstr, itemIndex, itemString, LCD_WIDTH - 2 - vlen); - if (vlen) { - lcd_put_wchar(':'); - for (; n; --n) lcd_put_wchar(' '); - if (pgm) lcd_put_u8str_P(inStr); else lcd_put_u8str(inStr); - } - } - - // Low-level draw_edit_screen can be used to draw an edit screen from anyplace - void MenuEditItemBase::draw_edit_screen(PGM_P const pstr, const char* const value/*=nullptr*/) { - ui.encoder_direction_normal(); - uint8_t n = lcd_put_u8str_ind_P(0, 1, pstr, itemIndex, itemString, LCD_WIDTH - 1); - if (value != nullptr) { - lcd_put_wchar(':'); n--; - const uint8_t len = utf8_strlen(value) + 1; // Plus one for a leading space - const lcd_uint_t valrow = n < len ? 2 : 1; // Value on the next row if it won't fit - lcd_put_wchar(LCD_WIDTH - len, valrow, ' '); // Right-justified, padded, leading space - lcd_put_u8str(value); - } - } - - // The Select Screen presents a prompt and two "buttons" - void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const bool yesno, PGM_P const pref, const char * const string/*=nullptr*/, PGM_P const suff/*=nullptr*/) { - ui.draw_select_screen_prompt(pref, string, suff); - SETCURSOR(0, LCD_HEIGHT - 1); - lcd_put_wchar(yesno ? ' ' : '['); lcd_put_u8str_P(no); lcd_put_wchar(yesno ? ' ' : ']'); - SETCURSOR_RJ(utf8_strlen_P(yes) + 2, LCD_HEIGHT - 1); - lcd_put_wchar(yesno ? '[' : ' '); lcd_put_u8str_P(yes); lcd_put_wchar(yesno ? ']' : ' '); - } - - #if ENABLED(SDSUPPORT) - - void MenuItem_sdbase::draw(const bool sel, const uint8_t row, PGM_P const, CardReader &theCard, const bool isDir) { - lcd_put_wchar(0, row, sel ? LCD_STR_ARROW_RIGHT[0] : ' '); - constexpr uint8_t maxlen = LCD_WIDTH - 2; - uint8_t n = maxlen - lcd_put_u8str_max(ui.scrolled_filename(theCard, maxlen, row, sel), maxlen); - for (; n; --n) lcd_put_wchar(' '); - lcd_put_wchar(isDir ? LCD_STR_FOLDER[0] : ' '); - } - - #endif - - #if ENABLED(LCD_HAS_STATUS_INDICATORS) - - void MarlinUI::update_indicators() { - // Set the LEDS - referred to as backlights by the LiquidTWI2 library - static uint8_t ledsprev = 0; - uint8_t leds = 0; - - if (TERN0(HAS_HEATED_BED, thermalManager.degTargetBed() > 0)) leds |= LED_A; - if (TERN0(HAS_HOTEND, thermalManager.degTargetHotend(0) > 0)) leds |= LED_B; - - #if HAS_FAN - if ( TERN0(HAS_FAN0, thermalManager.fan_speed[0]) - || TERN0(HAS_FAN1, thermalManager.fan_speed[1]) - || TERN0(HAS_FAN2, thermalManager.fan_speed[2]) - || TERN0(HAS_FAN3, thermalManager.fan_speed[3]) - || TERN0(HAS_FAN4, thermalManager.fan_speed[4]) - || TERN0(HAS_FAN5, thermalManager.fan_speed[5]) - || TERN0(HAS_FAN6, thermalManager.fan_speed[6]) - || TERN0(HAS_FAN7, thermalManager.fan_speed[7]) - ) leds |= LED_C; - #endif // HAS_FAN - - if (TERN0(HAS_MULTI_HOTEND, thermalManager.degTargetHotend(1) > 0)) leds |= LED_C; - - if (leds != ledsprev) { - lcd.setBacklight(leds); - ledsprev = leds; - } - } - - #endif // LCD_HAS_STATUS_INDICATORS - - #if ENABLED(AUTO_BED_LEVELING_UBL) - - #define HD44780_CHAR_WIDTH 5 - #define HD44780_CHAR_HEIGHT 8 - #define MESH_MAP_COLS 7 - #define MESH_MAP_ROWS 4 - - #define CHAR_LINE_TOP 0 - #define CHAR_LINE_BOT 1 - #define CHAR_EDGE_L 2 - #define CHAR_EDGE_R 3 - #define CHAR_UL_UL 4 - #define CHAR_LR_UL 5 - #define CHAR_UL_LR 6 - #define CHAR_LR_LR 7 - - #define TOP_LEFT _BV(0) - #define TOP_RIGHT _BV(1) - #define LOWER_LEFT _BV(2) - #define LOWER_RIGHT _BV(3) - - /** - * Possible map screens: - * - * 16x2 |X000.00 Y000.00| - * |(00,00) Z00.000| - * - * 20x2 | X:000.00 Y:000.00 | - * | (00,00) Z:00.000 | - * - * 16x4 |+-------+(00,00)| - * || |X000.00| - * || |Y000.00| - * |+-------+Z00.000| - * - * 20x4 | +-------+ (00,00) | - * | | | X:000.00| - * | | | Y:000.00| - * | +-------+ Z:00.000| - */ - - typedef struct { - uint8_t custom_char_bits[HD44780_CHAR_HEIGHT]; - } custom_char; - - typedef struct { - lcd_uint_t column, row, - x_pixel_offset, y_pixel_offset; - uint8_t x_pixel_mask; - } coordinate; - - void add_edges_to_custom_char(custom_char &custom, const coordinate &ul, const coordinate &lr, const coordinate &brc, const uint8_t cell_location); - FORCE_INLINE static void clear_custom_char(custom_char * const cc) { ZERO(cc->custom_char_bits); } - - coordinate pixel_location(int16_t x, int16_t y) { - coordinate ret_val; - int16_t xp, yp, r, c; - - x++; y++; // +1 because lines on the left and top - - c = x / (HD44780_CHAR_WIDTH); - r = y / (HD44780_CHAR_HEIGHT); - - ret_val.column = c; - ret_val.row = r; - - xp = x - c * (HD44780_CHAR_WIDTH); // Get the pixel offsets into the character cell - xp = HD44780_CHAR_WIDTH - 1 - xp; // Column within relevant character cell (0 on the right) - yp = y - r * (HD44780_CHAR_HEIGHT); - - ret_val.x_pixel_mask = _BV(xp); - ret_val.x_pixel_offset = xp; - ret_val.y_pixel_offset = yp; - return ret_val; - } - - inline coordinate pixel_location(const lcd_uint_t x, const lcd_uint_t y) { return pixel_location((int16_t)x, (int16_t)y); } - - void prep_and_put_map_char(custom_char &chrdata, const coordinate &ul, const coordinate &lr, const coordinate &brc, const uint8_t cl, const char c, const lcd_uint_t x, const lcd_uint_t y) { - add_edges_to_custom_char(chrdata, ul, lr, brc, cl); - lcd.createChar(c, (uint8_t*)&chrdata); - lcd_put_wchar(x, y, c); - } - - void MarlinUI::ubl_plot(const uint8_t x_plot, const uint8_t y_plot) { - - #if LCD_WIDTH >= 20 - #define _LCD_W_POS 12 - #define _PLOT_X 1 - #define _MAP_X 3 - #define _LABEL(C,X,Y) lcd_put_u8str_P(X, Y, C) - #define _XLABEL(X,Y) _LABEL(X_LBL,X,Y) - #define _YLABEL(X,Y) _LABEL(Y_LBL,X,Y) - #define _ZLABEL(X,Y) _LABEL(Z_LBL,X,Y) - #else - #define _LCD_W_POS 8 - #define _PLOT_X 0 - #define _MAP_X 1 - #define _LABEL(X,Y,C) lcd_put_wchar(X, Y, C) - #define _XLABEL(X,Y) _LABEL('X',X,Y) - #define _YLABEL(X,Y) _LABEL('Y',X,Y) - #define _ZLABEL(X,Y) _LABEL('Z',X,Y) - #endif - - #if LCD_HEIGHT <= 3 // 16x2 or 20x2 display - - /** - * Show X and Y positions - */ - _XLABEL(_PLOT_X, 0); - lcd_put_u8str(ftostr52(LOGICAL_X_POSITION(ubl.mesh_index_to_xpos(x_plot)))); - _YLABEL(_LCD_W_POS, 0); - lcd_put_u8str(ftostr52(LOGICAL_Y_POSITION(ubl.mesh_index_to_ypos(y_plot)))); - - lcd_moveto(_PLOT_X, 0); - - #else // 16x4 or 20x4 display - - coordinate upper_left, lower_right, bottom_right_corner; - custom_char new_char; - uint8_t i, n, n_rows, n_cols; - lcd_uint_t j, k, l, m, bottom_line, right_edge, - x_map_pixels, y_map_pixels, - pixels_per_x_mesh_pnt, pixels_per_y_mesh_pnt, - suppress_x_offset = 0, suppress_y_offset = 0; - - const uint8_t y_plot_inv = (GRID_MAX_POINTS_Y - 1) - y_plot; - - upper_left.column = 0; - upper_left.row = 0; - lower_right.column = 0; - lower_right.row = 0; - - clear_lcd(); - - x_map_pixels = (HD44780_CHAR_WIDTH) * (MESH_MAP_COLS) - 2; // Minus 2 because we are drawing a box around the map - y_map_pixels = (HD44780_CHAR_HEIGHT) * (MESH_MAP_ROWS) - 2; - - pixels_per_x_mesh_pnt = x_map_pixels / (GRID_MAX_POINTS_X); - pixels_per_y_mesh_pnt = y_map_pixels / (GRID_MAX_POINTS_Y); - - if (pixels_per_x_mesh_pnt >= HD44780_CHAR_WIDTH) { // There are only 2 custom characters available, so the X - pixels_per_x_mesh_pnt = HD44780_CHAR_WIDTH; // Size of the mesh point needs to fit within them independent - suppress_x_offset = 1; // Of where the starting pixel is located. - } - - if (pixels_per_y_mesh_pnt >= HD44780_CHAR_HEIGHT) { // There are only 2 custom characters available, so the Y - pixels_per_y_mesh_pnt = HD44780_CHAR_HEIGHT; // Size of the mesh point needs to fit within them independent - suppress_y_offset = 1; // Of where the starting pixel is located. - } - - x_map_pixels = pixels_per_x_mesh_pnt * (GRID_MAX_POINTS_X); // Now we have the right number of pixels to make both - y_map_pixels = pixels_per_y_mesh_pnt * (GRID_MAX_POINTS_Y); // Directions fit nicely - - right_edge = pixels_per_x_mesh_pnt * (GRID_MAX_POINTS_X) + 1; // Find location of right edge within the character cell - bottom_line = pixels_per_y_mesh_pnt * (GRID_MAX_POINTS_Y) + 1; // Find location of bottome line within the character cell - - n_rows = bottom_line / (HD44780_CHAR_HEIGHT) + 1; - n_cols = right_edge / (HD44780_CHAR_WIDTH) + 1; - - for (i = 0; i < n_cols; i++) { - lcd_put_wchar(i, 0, CHAR_LINE_TOP); // Box Top line - lcd_put_wchar(i, n_rows - 1, CHAR_LINE_BOT); // Box Bottom line - } - - for (j = 0; j < n_rows; j++) { - lcd_put_wchar(0, j, CHAR_EDGE_L); // Box Left edge - lcd_put_wchar(n_cols - 1, j, CHAR_EDGE_R); // Box Right edge - } - - /** - * If the entire 4th row is not in use, do not put vertical bars all the way down to the bottom of the display - */ - - k = pixels_per_y_mesh_pnt * (GRID_MAX_POINTS_Y) + 2; - l = (HD44780_CHAR_HEIGHT) * n_rows; - if (l > k && l - k >= (HD44780_CHAR_HEIGHT) / 2) { - lcd_put_wchar(0, n_rows - 1, ' '); // Box Left edge - lcd_put_wchar(n_cols - 1, n_rows - 1, ' '); // Box Right edge - } - - clear_custom_char(&new_char); - new_char.custom_char_bits[0] = 0b11111U; // Char #0 is used for the box top line - lcd.createChar(CHAR_LINE_TOP, (uint8_t*)&new_char); - - clear_custom_char(&new_char); - k = (GRID_MAX_POINTS_Y) * pixels_per_y_mesh_pnt + 1; // Row of pixels for the bottom box line - l = k % (HD44780_CHAR_HEIGHT); // Row within relevant character cell - new_char.custom_char_bits[l] = 0b11111U; // Char #1 is used for the box bottom line - lcd.createChar(CHAR_LINE_BOT, (uint8_t*)&new_char); - - clear_custom_char(&new_char); - for (j = 0; j < HD44780_CHAR_HEIGHT; j++) - new_char.custom_char_bits[j] = 0b10000U; // Char #2 is used for the box left edge - lcd.createChar(CHAR_EDGE_L, (uint8_t*)&new_char); - - clear_custom_char(&new_char); - m = (GRID_MAX_POINTS_X) * pixels_per_x_mesh_pnt + 1; // Column of pixels for the right box line - n = m % (HD44780_CHAR_WIDTH); // Column within relevant character cell - i = HD44780_CHAR_WIDTH - 1 - n; // Column within relevant character cell (0 on the right) - for (j = 0; j < HD44780_CHAR_HEIGHT; j++) - new_char.custom_char_bits[j] = (uint8_t)_BV(i); // Char #3 is used for the box right edge - lcd.createChar(CHAR_EDGE_R, (uint8_t*)&new_char); - - i = x_plot * pixels_per_x_mesh_pnt - suppress_x_offset; - j = y_plot_inv * pixels_per_y_mesh_pnt - suppress_y_offset; - upper_left = pixel_location(i, j); - - k = (x_plot + 1) * pixels_per_x_mesh_pnt - 1 - suppress_x_offset; - l = (y_plot_inv + 1) * pixels_per_y_mesh_pnt - 1 - suppress_y_offset; - lower_right = pixel_location(k, l); - - bottom_right_corner = pixel_location(x_map_pixels, y_map_pixels); - - /** - * First, handle the simple case where everything is within a single character cell. - * If part of the Mesh Plot is outside of this character cell, we will follow up - * and deal with that next. - */ - - clear_custom_char(&new_char); - const lcd_uint_t ypix = _MIN(upper_left.y_pixel_offset + pixels_per_y_mesh_pnt, HD44780_CHAR_HEIGHT); - for (j = upper_left.y_pixel_offset; j < ypix; j++) { - i = upper_left.x_pixel_mask; - for (k = 0; k < pixels_per_x_mesh_pnt; k++) { - new_char.custom_char_bits[j] |= i; - i >>= 1; - } - } - - prep_and_put_map_char(new_char, upper_left, lower_right, bottom_right_corner, TOP_LEFT, CHAR_UL_UL, upper_left.column, upper_left.row); - - /** - * Next, check for two side by side character cells being used to display the Mesh Point - * If found... do the right hand character cell next. - */ - if (upper_left.column == lower_right.column - 1) { - l = upper_left.x_pixel_offset; - clear_custom_char(&new_char); - for (j = upper_left.y_pixel_offset; j < ypix; j++) { - i = _BV(HD44780_CHAR_WIDTH - 1); // Fill in the left side of the right character cell - for (k = 0; k < pixels_per_x_mesh_pnt - 1 - l; k++) { - new_char.custom_char_bits[j] |= i; - i >>= 1; - } - } - prep_and_put_map_char(new_char, upper_left, lower_right, bottom_right_corner, TOP_RIGHT, CHAR_LR_UL, lower_right.column, upper_left.row); - } - - /** - * Next, check for two character cells stacked on top of each other being used to display the Mesh Point - */ - if (upper_left.row == lower_right.row - 1) { - l = HD44780_CHAR_HEIGHT - upper_left.y_pixel_offset; // Number of pixel rows in top character cell - k = pixels_per_y_mesh_pnt - l; // Number of pixel rows in bottom character cell - clear_custom_char(&new_char); - for (j = 0; j < k; j++) { - i = upper_left.x_pixel_mask; - for (m = 0; m < pixels_per_x_mesh_pnt; m++) { // Fill in the top side of the bottom character cell - new_char.custom_char_bits[j] |= i; - if (!(i >>= 1)) break; - } - } - prep_and_put_map_char(new_char, upper_left, lower_right, bottom_right_corner, LOWER_LEFT, CHAR_UL_LR, upper_left.column, lower_right.row); - } - - /** - * Next, check for four character cells being used to display the Mesh Point. If that is - * what is here, we work to fill in the character cell that is down one and to the right one - * from the upper_left character cell. - */ - - if (upper_left.column == lower_right.column - 1 && upper_left.row == lower_right.row - 1) { - l = HD44780_CHAR_HEIGHT - upper_left.y_pixel_offset; // Number of pixel rows in top character cell - k = pixels_per_y_mesh_pnt - l; // Number of pixel rows in bottom character cell - clear_custom_char(&new_char); - for (j = 0; j < k; j++) { - l = upper_left.x_pixel_offset; - i = _BV(HD44780_CHAR_WIDTH - 1); // Fill in the left side of the right character cell - for (m = 0; m < pixels_per_x_mesh_pnt - 1 - l; m++) { // Fill in the top side of the bottom character cell - new_char.custom_char_bits[j] |= i; - i >>= 1; - } - } - prep_and_put_map_char(new_char, upper_left, lower_right, bottom_right_corner, LOWER_RIGHT, CHAR_LR_LR, lower_right.column, lower_right.row); - } - - #endif - - /** - * Print plot position - */ - lcd_put_wchar(_LCD_W_POS, 0, '('); - lcd_put_u8str(ui8tostr3rj(x_plot)); - lcd_put_wchar(','); - lcd_put_u8str(ui8tostr3rj(y_plot)); - lcd_put_wchar(')'); - - #if LCD_HEIGHT <= 3 // 16x2 or 20x2 display - - /** - * Print Z values - */ - _ZLABEL(_LCD_W_POS, 1); - if (!isnan(ubl.z_values[x_plot][y_plot])) - lcd_put_u8str(ftostr43sign(ubl.z_values[x_plot][y_plot])); - else - lcd_put_u8str_P(PSTR(" -----")); - - #else // 16x4 or 20x4 display - - /** - * Show all values at right of screen - */ - _XLABEL(_LCD_W_POS, 1); - lcd_put_u8str(ftostr52(LOGICAL_X_POSITION(ubl.mesh_index_to_xpos(x_plot)))); - _YLABEL(_LCD_W_POS, 2); - lcd_put_u8str(ftostr52(LOGICAL_Y_POSITION(ubl.mesh_index_to_ypos(y_plot)))); - - /** - * Show the location value - */ - _ZLABEL(_LCD_W_POS, 3); - if (!isnan(ubl.z_values[x_plot][y_plot])) - lcd_put_u8str(ftostr43sign(ubl.z_values[x_plot][y_plot])); - else - lcd_put_u8str_P(PSTR(" -----")); - - #endif // LCD_HEIGHT > 3 - } - - void add_edges_to_custom_char(custom_char &custom, const coordinate &ul, const coordinate &lr, const coordinate &brc, const uint8_t cell_location) { - uint8_t i, k; - int16_t n_rows = lr.row - ul.row + 1, - n_cols = lr.column - ul.column + 1; - - /** - * Check if Top line of box needs to be filled in - */ - - if (ul.row == 0 && (cell_location & (TOP_LEFT|TOP_RIGHT))) { // Only fill in the top line for the top character cells - - if (n_cols == 1) { - if (ul.column != brc.column) - custom.custom_char_bits[0] = 0xFF; // Single column in middle - else - for (i = brc.x_pixel_offset; i < HD44780_CHAR_WIDTH; i++) // Single column on right side - SBI(custom.custom_char_bits[0], i); - } - else if ((cell_location & TOP_LEFT) || lr.column != brc.column) // Multiple column in the middle or with right cell in middle - custom.custom_char_bits[0] = 0xFF; - else - for (i = brc.x_pixel_offset; i < HD44780_CHAR_WIDTH; i++) - SBI(custom.custom_char_bits[0], i); - } - - /** - * Check if left line of box needs to be filled in - */ - if (cell_location & (TOP_LEFT|LOWER_LEFT)) { - if (ul.column == 0) { // Left column of characters on LCD Display - k = ul.row == brc.row ? brc.y_pixel_offset : HD44780_CHAR_HEIGHT; // If it isn't the last row... do the full character cell - for (i = 0; i < k; i++) - SBI(custom.custom_char_bits[i], HD44780_CHAR_WIDTH - 1); - } - } - - /** - * Check if bottom line of box needs to be filled in - */ - - // Single row of mesh plot cells - if (n_rows == 1 /* && (cell_location & (TOP_LEFT|TOP_RIGHT)) */ && ul.row == brc.row) { - if (n_cols == 1) // Single row, single column case - k = ul.column == brc.column ? brc.x_pixel_mask : 0x01; - else if (cell_location & TOP_RIGHT) // Single row, multiple column case - k = lr.column == brc.column ? brc.x_pixel_mask : 0x01; - else // Single row, left of multiple columns - k = 0x01; - while (k < _BV(HD44780_CHAR_WIDTH)) { - custom.custom_char_bits[brc.y_pixel_offset] |= k; - k <<= 1; - } - } - - // Double row of characters on LCD Display - // And this is a bottom custom character - if (n_rows == 2 && (cell_location & (LOWER_LEFT|LOWER_RIGHT)) && lr.row == brc.row) { - if (n_cols == 1) // Double row, single column case - k = ul.column == brc.column ? brc.x_pixel_mask : 0x01; - else if (cell_location & LOWER_RIGHT) // Double row, multiple column case - k = lr.column == brc.column ? brc.x_pixel_mask : 0x01; - else // Double row, left of multiple columns - k = 0x01; - while (k < _BV(HD44780_CHAR_WIDTH)) { - custom.custom_char_bits[brc.y_pixel_offset] |= k; - k <<= 1; - } - } - - /** - * Check if right line of box needs to be filled in - */ - - // Nothing to do if the lower right part of the mesh pnt isn't in the same column as the box line - if (lr.column == brc.column) { - // This mesh point is in the same character cell as the right box line - if (ul.column == brc.column || (cell_location & (TOP_RIGHT|LOWER_RIGHT))) { - // If not the last row... do the full character cell - k = ul.row == brc.row ? brc.y_pixel_offset : HD44780_CHAR_HEIGHT; - for (i = 0; i < k; i++) custom.custom_char_bits[i] |= brc.x_pixel_mask; - } - } - } - - #endif // AUTO_BED_LEVELING_UBL - -#endif // HAS_LCD_MENU - -#endif // HAS_MARLINUI_HD44780 diff --git a/Marlin/src/lcd/HD44780/ultralcd_HD44780.h b/Marlin/src/lcd/HD44780/ultralcd_HD44780.h deleted file mode 100644 index 604d26a029b4..000000000000 --- a/Marlin/src/lcd/HD44780/ultralcd_HD44780.h +++ /dev/null @@ -1,102 +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 - -/** - * Hitachi HD44780 display defines and headers - */ - -#include "../../inc/MarlinConfig.h" - -#if ENABLED(LCD_I2C_TYPE_PCF8575) - - // NOTE: These are register-mapped pins on the PCF8575 controller, not Arduino pins. - #define LCD_I2C_PIN_BL 3 - #define LCD_I2C_PIN_EN 2 - #define LCD_I2C_PIN_RW 1 - #define LCD_I2C_PIN_RS 0 - #define LCD_I2C_PIN_D4 4 - #define LCD_I2C_PIN_D5 5 - #define LCD_I2C_PIN_D6 6 - #define LCD_I2C_PIN_D7 7 - - #include - #include - #include - #define LCD_CLASS LiquidCrystal_I2C - -#elif ENABLED(LCD_I2C_TYPE_MCP23017) - - // For the LED indicators (which may be mapped to different events in update_indicators()) - #define LCD_HAS_STATUS_INDICATORS - #define LED_A 0x04 //100 - #define LED_B 0x02 //010 - #define LED_C 0x01 //001 - - #include - #include - #define LCD_CLASS LiquidTWI2 - -#elif ENABLED(LCD_I2C_TYPE_MCP23008) - - #include - #include - #define LCD_CLASS LiquidTWI2 - -#elif ENABLED(LCD_I2C_TYPE_PCA8574) - - #include - #define LCD_CLASS LiquidCrystal_I2C - -#elif ENABLED(SR_LCD_2W_NL) - - // 2 wire Non-latching LCD SR from: - // https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/schematics#!shiftregister-connection - #include - #include - #define LCD_CLASS LiquidCrystal_SR - -#elif ENABLED(SR_LCD_3W_NL) - - // NewLiquidCrystal didn't work, so this uses - // https://github.com/mikeshub/SailfishLCD - - #include - #define LCD_CLASS LiquidCrystalSerial - -#elif ENABLED(LCM1602) - - #include - #include - #include - #define LCD_CLASS LiquidCrystal_I2C - -#else - - // Standard directly connected LCD implementations - #include - #define LCD_CLASS LiquidCrystal - -#endif - -#include "../fontutils.h" -#include "../lcdprint.h" diff --git a/Marlin/src/lcd/TFTGLCD/lcdprint_TFTGLCD.cpp b/Marlin/src/lcd/TFTGLCD/lcdprint_TFTGLCD.cpp index 51681a800953..dddab1f259f5 100644 --- a/Marlin/src/lcd/TFTGLCD/lcdprint_TFTGLCD.cpp +++ b/Marlin/src/lcd/TFTGLCD/lcdprint_TFTGLCD.cpp @@ -37,11 +37,11 @@ #if IS_TFTGLCD_PANEL -#include "../ultralcd.h" +#include "../marlinui.h" #include "../../MarlinCore.h" #include "../../libs/numtostr.h" -#include "ultralcd_TFTGLCD.h" +#include "marlinui_TFTGLCD.h" #include diff --git a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp new file mode 100644 index 000000000000..712e76e86f21 --- /dev/null +++ b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp @@ -0,0 +1,1092 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../inc/MarlinConfigPre.h" + +#if IS_TFTGLCD_PANEL + +/** + * marlinui_TFTGLCD.cpp + * + * Implementation of the LCD display routines for a TFT GLCD displays with external controller. + * This display looks like a REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER but has good text font + * and supports color output. + */ + +#if NONE(__AVR__, TARGET_LPC1768, STM32F1, STM32F4xx) + #warning "Selected platform not yet tested. Please contribute your good pin mappings." +#endif + +#if ENABLED(TFTGLCD_PANEL_SPI) + #include +#else + #include +#endif + +#include "marlinui_TFTGLCD.h" +#include "../marlinui.h" +#include "../../libs/numtostr.h" + +#include "../../sd/cardreader.h" +#include "../../module/temperature.h" +#include "../../module/printcounter.h" +#include "../../module/planner.h" +#include "../../module/motion.h" + +#if DISABLED(LCD_PROGRESS_BAR) && BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) + #include "../../feature/filwidth.h" + #include "../../gcode/parser.h" +#endif + +#if EITHER(HAS_COOLER, LASER_COOLANT_FLOW_METER) + #include "../../feature/cooler.h" +#endif + +#if ENABLED(I2C_AMMETER) + #include "../../feature/ammeter.h" +#endif + +#if HAS_CUTTER + #include "../../feature/spindle_laser.h" +#endif + +#if ENABLED(AUTO_BED_LEVELING_UBL) + #include "../../feature/bedlevel/bedlevel.h" +#endif + +TFTGLCD lcd; + +#define ICON_LOGO B00000001 +#define ICON_TEMP1 B00000010 // Hotend 1 +#define ICON_TEMP2 B00000100 // Hotend 2 +#define ICON_TEMP3 B00001000 // Hotend 3 +#define ICON_BED B00010000 +#define ICON_FAN B00100000 +#define ICON_HOT B01000000 // When any T > 50deg +#define PIC_MASK 0x7F + +// LEDs not used, for compatibility with Smoothieware +#define LED_HOTEND_ON B00000001 +#define LED_BED_ON B00000010 +#define LED_FAN_ON B00000100 +#define LED_HOT B00001000 +#define LED_MASK 0x0F + +#define FBSIZE (LCD_WIDTH * LCD_HEIGHT + 2) +#define MIDDLE_Y ((LCD_HEIGHT - 1) / 2) + +// Markers for change line colors +#define COLOR_EDIT '#' +#define COLOR_ERROR '!' + +#ifdef CONVERT_TO_EXT_ASCII //use standard pseudographic symbols in ASCII table + #define LR 179 //vertical line + #define TRC 191 //top right corner + #define BLC 192 //bottom left corner + #define GL 196 //horizontal line + #define BRC 217 //bottom right corner, should be replaced to 12 for some languages + #define TLC 218 //top left corner, should be replaced to 13 for some languages +#else //next symbols must be present in panel font + #define LR 8 //equal to 179 + #define TRC 9 //equal to 191 + #define BLC 10 //equal to 192 + #define GL 11 //equal to 196 + #define BRC 12 //equal to 217 + #define TLC 13 //equal to 218 +#endif + +#define Marlin 0x01 + +enum Commands { // based on Smoothieware commands + GET_SPI_DATA = 0, + READ_BUTTONS, // read buttons + READ_ENCODER, // read encoder + LCD_WRITE, // write all screen to LCD + BUZZER, // beep buzzer + CONTRAST, // set contrast (brightnes) + // Other commands... 0xE0 thru 0xFF + GET_LCD_ROW = 0xE0, // for detect panel + GET_LCD_COL, // reserved for compatibility with Smoothieware, not used + LCD_PUT, // write one line to LCD + CLR_SCREEN, + INIT_SCREEN = 0xFE // clear panel buffer +}; + +static unsigned char framebuffer[FBSIZE]; +static unsigned char *fb; +static uint8_t cour_line; +static uint8_t picBits, ledBits, hotBits; +static uint8_t PanelDetected = 0; + +// Different platforms use different SPI methods +#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) + #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) + #define SPI_SEND_ONE(V) SPI.write(V); + #define SPI_SEND_TWO(V) SPI.write16(V); +#endif + +#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) + #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) +#endif + +// Constructor +TFTGLCD::TFTGLCD() {} + +// Clear local buffer +void TFTGLCD::clear_buffer() { + memset(&framebuffer[0], ' ', FBSIZE - 2); + framebuffer[FBSIZE - 1] = framebuffer[FBSIZE - 2] = 0; + picBits = ledBits = 0; +} + +// Clear panel's screen +void TFTGLCD::clr_screen() { + if (!PanelDetected) return; + #if ENABLED(TFTGLCD_PANEL_SPI) + WRITE(TFTGLCD_CS, LOW); + SPI_SEND_ONE(CLR_SCREEN); + WRITE(TFTGLCD_CS, HIGH); + #else + Wire.beginTransmission((uint8_t)LCD_I2C_ADDRESS); //set I2C device address + Wire.write(CLR_SCREEN); + Wire.endTransmission(); //transmit data + #endif +} + +// Set new text cursor position +void TFTGLCD::setCursor(uint8_t col, uint8_t row) { + fb = &framebuffer[0] + col + row * LCD_WIDTH; + cour_line = row; +} + +// Send char to buffer +void TFTGLCD::write(char c) { + *fb++ = c; +} + +// Send text line to buffer +void TFTGLCD::print(const char *line) { + while (*line) *fb++ = *line++; +} + +// For menu +void TFTGLCD::print_line() { + if (!PanelDetected) return; + #if ENABLED(TFTGLCD_PANEL_SPI) + WRITE(TFTGLCD_CS, LOW); + SPI_SEND_ONE(LCD_PUT); + SPI_SEND_ONE(cour_line); + SPI_SEND_SOME(framebuffer, LCD_WIDTH, cour_line * LCD_WIDTH); + WRITE(TFTGLCD_CS, HIGH); + #else + Wire.beginTransmission((uint8_t)LCD_I2C_ADDRESS); //set I2C device address + Wire.write(LCD_PUT); + Wire.write(cour_line); + Wire.write(&framebuffer[cour_line * LCD_WIDTH], LCD_WIDTH); //transfer 1 line to txBuffer + Wire.endTransmission(); //transmit data + safe_delay(1); + #endif +} + +void TFTGLCD::print_screen() { + if (!PanelDetected) return; + framebuffer[FBSIZE - 2] = picBits & PIC_MASK; + framebuffer[FBSIZE - 1] = ledBits; + #if ENABLED(TFTGLCD_PANEL_SPI) + // Send all framebuffer to panel + WRITE(TFTGLCD_CS, LOW); + SPI_SEND_ONE(LCD_WRITE); + SPI_SEND_SOME(framebuffer, FBSIZE, 0); + WRITE(TFTGLCD_CS, HIGH); + #else + uint8_t r; + // Send framebuffer to panel by line + Wire.beginTransmission((uint8_t)LCD_I2C_ADDRESS); + // First line + Wire.write(LCD_WRITE); + Wire.write(&framebuffer[0], LCD_WIDTH); + Wire.endTransmission(); + for (r = 1; r < (LCD_HEIGHT - 1); r++) { + Wire.beginTransmission((uint8_t)LCD_I2C_ADDRESS); + Wire.write(&framebuffer[r * LCD_WIDTH], LCD_WIDTH); + Wire.endTransmission(); + } + // Last line + Wire.beginTransmission((uint8_t)LCD_I2C_ADDRESS); + Wire.write(&framebuffer[r * LCD_WIDTH], LCD_WIDTH); + Wire.write(&framebuffer[FBSIZE - 2], 2); + Wire.endTransmission(); + #endif +} + +void TFTGLCD::setContrast(uint16_t contrast) { + if (!PanelDetected) return; + #if ENABLED(TFTGLCD_PANEL_SPI) + WRITE(TFTGLCD_CS, LOW); + SPI_SEND_ONE(CONTRAST); + SPI_SEND_ONE((uint8_t)contrast); + WRITE(TFTGLCD_CS, HIGH); + #else + Wire.beginTransmission((uint8_t)LCD_I2C_ADDRESS); + Wire.write(CONTRAST); + Wire.write((uint8_t)contrast); + Wire.endTransmission(); + #endif +} + +extern volatile int8_t encoderDiff; + +// Read buttons and encoder states +uint8_t MarlinUI::read_slow_buttons(void) { + if (!PanelDetected) return 0; + #if ENABLED(TFTGLCD_PANEL_SPI) + uint8_t b = 0; + WRITE(TFTGLCD_CS, LOW); + SPI_SEND_ONE(READ_ENCODER); + #ifndef STM32F4xx + WRITE(TFTGLCD_CS, LOW); // for delay + #endif + encoderDiff += SPI_SEND_ONE(READ_BUTTONS); + #ifndef STM32F4xx + WRITE(TFTGLCD_CS, LOW); // for delay + WRITE(TFTGLCD_CS, LOW); + #endif + b = SPI_SEND_ONE(GET_SPI_DATA); + WRITE(TFTGLCD_CS, HIGH); + return b; + #else + Wire.beginTransmission((uint8_t)LCD_I2C_ADDRESS); + Wire.write(READ_ENCODER); + Wire.endTransmission(); + #ifdef __AVR__ + 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) + Wire.requestFrom(LCD_I2C_ADDRESS, 2); + #endif + encoderDiff += Wire.read(); + return Wire.read(); //buttons + #endif +} + +// Duration in ms, freq in Hz +void MarlinUI::buzz(const long duration, const uint16_t freq) { + if (!PanelDetected) return; + if (!buzzer_enabled) return; + #if ENABLED(TFTGLCD_PANEL_SPI) + WRITE(TFTGLCD_CS, LOW); + SPI_SEND_ONE(BUZZER); + SPI_SEND_TWO((uint16_t)duration); + SPI_SEND_TWO(freq); + WRITE(TFTGLCD_CS, HIGH); + #else + Wire.beginTransmission((uint8_t)LCD_I2C_ADDRESS); + Wire.write(BUZZER); + Wire.write((uint8_t)(duration >> 8)); + Wire.write((uint8_t)duration); + Wire.write((uint8_t)(freq >> 8)); + Wire.write((uint8_t)freq); + Wire.endTransmission(); + #endif +} + +void MarlinUI::init_lcd() { + uint8_t t; + lcd.clear_buffer(); + t = 0; + #if ENABLED(TFTGLCD_PANEL_SPI) + // SPI speed must be less 10MHz + SET_OUTPUT(TFTGLCD_CS); + WRITE(TFTGLCD_CS, HIGH); + spiInit(TERN(__STM32F1__, SPI_QUARTER_SPEED, SPI_FULL_SPEED)); + WRITE(TFTGLCD_CS, LOW); + SPI_SEND_ONE(GET_LCD_ROW); + t = SPI_SEND_ONE(GET_SPI_DATA); + #else + #ifdef TARGET_LPC1768 + Wire.begin(); //init twi/I2C + #else + Wire.begin((uint8_t)LCD_I2C_ADDRESS); //init twi/I2C + #endif + Wire.beginTransmission((uint8_t)LCD_I2C_ADDRESS); + Wire.write((uint8_t)GET_LCD_ROW); // put command to buffer + Wire.endTransmission(); // send buffer + #ifdef __AVR__ + Wire.requestFrom((uint8_t)LCD_I2C_ADDRESS, 1, 0, 0, 1); + #elif ANY(STM32F1, STM32F4xx, TARGET_LPC1768) + Wire.requestFrom(LCD_I2C_ADDRESS, 1); + #endif + t = (uint8_t)Wire.read(); + #endif + + if (t == LCD_HEIGHT) { + PanelDetected = 1; + #if ENABLED(TFTGLCD_PANEL_SPI) + SPI_SEND_ONE(INIT_SCREEN); + SPI_SEND_ONE(Marlin); + WRITE(TFTGLCD_CS, HIGH); + #else + Wire.beginTransmission((uint8_t)LCD_I2C_ADDRESS); + Wire.write((uint8_t)INIT_SCREEN); + Wire.write(Marlin); + Wire.endTransmission(); + #endif + } + else + PanelDetected = 0; + safe_delay(100); +} + +bool MarlinUI::detected() { + return PanelDetected; +} + +void MarlinUI::clear_lcd() { + if (!PanelDetected) return; + lcd.clr_screen(); + lcd.clear_buffer(); +} + +int16_t MarlinUI::contrast; // Initialized by settings.load() + +void MarlinUI::set_contrast(const int16_t value) { + contrast = constrain(value, LCD_CONTRAST_MIN, LCD_CONTRAST_MAX); + lcd.setContrast(contrast); +} + +static void center_text_P(PGM_P pstart, uint8_t y) { + uint8_t len = utf8_strlen_P(pstart); + if (len < LCD_WIDTH) + lcd.setCursor((LCD_WIDTH - len) / 2, y); + else + lcd.setCursor(0, y); + lcd_put_u8str_P(pstart); +} + +#if ENABLED(SHOW_BOOTSCREEN) + + void MarlinUI::show_bootscreen() { + if (!PanelDetected) return; + // + // Show the Marlin logo, splash line1, and splash line 2 + // + uint8_t indent = (LCD_WIDTH - 8) / 2; + // symbols 217 (bottom right corner) and 218 (top left corner) are using for letters in some languages + // and they should be moved to beginning ASCII table as special symbols + lcd.setCursor(indent, 0); lcd.write(TLC); lcd_put_u8str_P(PSTR("------")); lcd.write(TRC); + lcd.setCursor(indent, 1); lcd.write(LR); lcd_put_u8str_P(PSTR("Marlin")); lcd.write(LR); + lcd.setCursor(indent, 2); lcd.write(BLC); lcd_put_u8str_P(PSTR("------")); lcd.write(BRC); + center_text_P(PSTR(SHORT_BUILD_VERSION), 3); + center_text_P(PSTR(MARLIN_WEBSITE_URL), 4); + picBits = ICON_LOGO; + lcd.print_screen(); + } + + void MarlinUI::bootscreen_completion(const millis_t sofar) { + if ((BOOTSCREEN_TIMEOUT) > sofar) safe_delay((BOOTSCREEN_TIMEOUT) - sofar); + } + +#endif // SHOW_BOOTSCREEN + +void MarlinUI::draw_kill_screen() { + if (!PanelDetected) return; + lcd.clear_buffer(); + lcd.setCursor(0, 3); lcd.write(COLOR_ERROR); + lcd.setCursor((LCD_WIDTH - utf8_strlen(status_message)) / 2 + 1, 3); + lcd_put_u8str(status_message); + center_text_P(GET_TEXT(MSG_HALTED), 5); + center_text_P(GET_TEXT(MSG_PLEASE_RESET), 6); + lcd.print_screen(); +} + +// +// Before homing, blink '123' <-> '???'. +// Homed but unknown... '123' <-> ' '. +// Homed and known, display constantly. +// +FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const bool blink) { + lcd.write('X' + uint8_t(axis)); + if (blink) + lcd.print(value); + else if (axis_should_home(axis)) + while (const char c = *value++) lcd.write(c <= '.' ? c : '?'); + else if (NONE(HOME_AFTER_DEACTIVATE, DISABLE_REDUCED_ACCURACY_WARNING) && !axis_is_trusted(axis)) + lcd_put_u8str_P(axis == Z_AXIS ? PSTR(" ") : PSTR(" ")); + else + lcd_put_u8str(value); +} + +#if HAS_HOTEND || HAS_HEATED_BED + + FORCE_INLINE void _draw_heater_status(const heater_id_t heater_id, const char *prefix, const bool blink) { + uint8_t pic_hot_bits; + #if HAS_HEATED_BED + const bool isBed = heater_id < 0; + const celsius_t t1 = (isBed ? thermalManager.wholeDegBed() : thermalManager.wholeDegHotend(heater_id)), + t2 = (isBed ? thermalManager.degTargetBed() : thermalManager.degTargetHotend(heater_id)); + #else + const celsius_t t1 = thermalManager.wholeDegHotend(heater_id), t2 = thermalManager.degTargetHotend(heater_id); + #endif + + #if HOTENDS < 2 + if (heater_id == H_E0) { + lcd.setCursor(2, 5); lcd.print(prefix); //HE + lcd.setCursor(1, 6); lcd.print(i16tostr3rj(t1)); + lcd.setCursor(1, 7); + } + else { + lcd.setCursor(6, 5); lcd.print(prefix); //BED + lcd.setCursor(6, 6); lcd.print(i16tostr3rj(t1)); + lcd.setCursor(6, 7); + } + #else + if (heater_id > H_BED) { + lcd.setCursor(heater_id * 4, 5); lcd.print(prefix); // HE1 or HE2 or HE3 + lcd.setCursor(heater_id * 4, 6); lcd.print(i16tostr3rj(t1)); + lcd.setCursor(heater_id * 4, 7); + } + else { + lcd.setCursor(13, 5); lcd.print(prefix); //BED + lcd.setCursor(13, 6); lcd.print(i16tostr3rj(t1)); + lcd.setCursor(13, 7); + } + #endif // HOTENDS <= 1 + + #if !HEATER_IDLE_HANDLER + UNUSED(blink); + #else + if (!blink && thermalManager.heater_idle[thermalManager.idle_index_for_id(heater_id)].timed_out) { + lcd.write(' '); + if (t2 >= 10) lcd.write(' '); + if (t2 >= 100) lcd.write(' '); + } + else + #endif // !HEATER_IDLE_HANDLER + lcd.print(i16tostr3rj(t2)); + + switch (heater_id) { + case H_BED: pic_hot_bits = ICON_BED; break; + case H_E0: pic_hot_bits = ICON_TEMP1; break; + case H_E1: pic_hot_bits = ICON_TEMP2; break; + case H_E2: pic_hot_bits = ICON_TEMP3; + default: break; + } + + if (t2) picBits |= pic_hot_bits; + else picBits &= ~pic_hot_bits; + + if (t1 > 50) hotBits |= pic_hot_bits; + else hotBits &= ~pic_hot_bits; + + if (hotBits) picBits |= ICON_HOT; + else picBits &= ~ICON_HOT; + } + +#endif // HAS_HOTEND || HAS_HEATED_BED + +#if HAS_COOLER + + FORCE_INLINE void _draw_cooler_status(const bool blink) { + const celsius_t t2 = thermalManager.degTargetCooler(); + + lcd.setCursor(0, 5); lcd_put_u8str_P(PSTR("COOL")); + lcd.setCursor(1, 6); lcd_put_u8str(i16tostr3rj(thermalManager.wholeDegCooler())); + lcd.setCursor(1, 7); + + #if !HEATER_IDLE_HANDLER + UNUSED(blink); + #else + if (!blink && thermalManager.heater_idle[thermalManager.idle_index_for_id(heater_id)].timed_out) { + lcd_put_wchar(' '); + if (t2 >= 10) lcd_put_wchar(' '); + if (t2 >= 100) lcd_put_wchar(' '); + } + else + #endif + lcd_put_u8str(i16tostr3left(t2)); + + lcd_put_wchar(' '); + if (t2 < 10) lcd_put_wchar(' '); + + if (t2) picBits |= ICON_TEMP1; + else picBits &= ~ICON_TEMP1; + } + +#endif // HAS_COOLER + +#if ENABLED(LASER_COOLANT_FLOW_METER) + + FORCE_INLINE void _draw_flowmeter_status() { + lcd.setCursor(5, 5); lcd_put_u8str_P(PSTR("FLOW")); + lcd.setCursor(7, 6); lcd_put_wchar('L'); + lcd.setCursor(6, 7); lcd_put_u8str(ftostr11ns(cooler.flowrate)); + + if (cooler.flowrate) picBits |= ICON_FAN; + else picBits &= ~ICON_FAN; + } + +#endif + +#if ENABLED(I2C_AMMETER) + + FORCE_INLINE void _draw_ammeter_status() { + lcd.setCursor(10, 5); lcd_put_u8str_P(PSTR("ILAZ")); + ammeter.read(); + lcd.setCursor(11, 6); + if (ammeter.current <= 0.999f) + { + lcd_put_u8str("mA"); + lcd.setCursor(10, 7); + lcd_put_wchar(' '); lcd_put_u8str(ui16tostr3rj(uint16_t(ammeter.current * 1000 + 0.5f))); + } + else { + lcd_put_u8str(" A"); + lcd.setCursor(10, 7); + lcd_put_u8str(ftostr12ns(ammeter.current)); + } + + if (ammeter.current) picBits |= ICON_BED; + else picBits &= ~ICON_BED; + } + +#endif // I2C_AMMETER + +#if HAS_CUTTER + + FORCE_INLINE void _draw_cutter_status() { + lcd.setCursor(15, 5); lcd_put_u8str_P(PSTR("CUTT")); + #if CUTTER_UNIT_IS(RPM) + lcd.setCursor(16, 6); lcd_put_u8str_P(PSTR("RPM")); + lcd.setCursor(15, 7); lcd_put_u8str(ftostr31ns(float(cutter.unitPower) / 1000)); + lcd_put_wchar('K'); + #elif CUTTER_UNIT_IS(PERCENT) + lcd.setCursor(17, 6); lcd_put_wchar('%'); + lcd.setCursor(18, 7); lcd_put_u8str(cutter_power2str(cutter.unitPower)); + #else + lcd.setCursor(17, 7); lcd_put_u8str(cutter_power2str(cutter.unitPower)); + #endif + + if (cutter.unitPower) picBits |= ICON_HOT; + else picBits &= ~ICON_HOT; + } + +#endif // HAS_CUTTER + +#if HAS_PRINT_PROGRESS + + FORCE_INLINE void _draw_print_progress() { + if (!PanelDetected) return; + const uint8_t progress = ui._get_progress(); + #if ENABLED(SDSUPPORT) + lcd_put_u8str_P(PSTR("SD")); + #elif ENABLED(LCD_SET_PROGRESS_MANUALLY) + lcd_put_u8str_P(PSTR("P:")); + #endif + if (progress) + lcd.print(ui8tostr3rj(progress)); + else + lcd_put_u8str_P(PSTR("---")); + lcd.write('%'); + } + +#endif // HAS_PRINT_PROGRESS + +#if ENABLED(LCD_PROGRESS_BAR) + + void MarlinUI::draw_progress_bar(const uint8_t percent) { + if (!PanelDetected) return; + if (fb == &framebuffer[0] + LCD_WIDTH * 2) { // For status screen + lcd.write('%'); lcd.write(percent); + } + else { // For progress bar test + lcd.setCursor(LCD_WIDTH / 2 - 2, MIDDLE_Y); + lcd.print(i16tostr3rj(percent)); lcd.write('%'); + lcd.print_line(); + lcd.setCursor(0, MIDDLE_Y + 1); + lcd.write('%'); lcd.write(percent); + lcd.print_line(); + } + } + +#endif // LCD_PROGRESS_BAR + +void MarlinUI::draw_status_message(const bool blink) { + if (!PanelDetected) return; + lcd.setCursor(0, 3); + #if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) + + // Alternate Status message and Filament display + if (ELAPSED(millis(), next_filament_display)) { + lcd_put_u8str_P(PSTR("Dia ")); + lcd.print(ftostr12ns(filament_width_meas)); + lcd_put_u8str_P(PSTR(" V")); + lcd.print(i16tostr3rj(100.0 * ( + parser.volumetric_enabled + ? planner.volumetric_area_nominal / planner.volumetric_multiplier[FILAMENT_SENSOR_EXTRUDER_NUM] + : planner.volumetric_multiplier[FILAMENT_SENSOR_EXTRUDER_NUM] + ) + )); + lcd.write('%'); + return; + } + + #endif // FILAMENT_LCD_DISPLAY && SDSUPPORT + + // Get the UTF8 character count of the string + uint8_t slen = utf8_strlen(status_message); + + #if ENABLED(STATUS_MESSAGE_SCROLLING) + + static bool last_blink = false; + + // If the string fits into the LCD, just print it and do not scroll it + if (slen <= LCD_WIDTH) { + + // The string isn't scrolling and may not fill the screen + lcd_put_u8str(status_message); + + // Fill the rest with spaces + while (slen < LCD_WIDTH) { lcd.write(' '); ++slen; } + } + else { + // String is larger than the available space in screen. + + // Get a pointer to the next valid UTF8 character + // and the string remaining length + uint8_t rlen; + const char *stat = status_and_len(rlen); + lcd_put_u8str_max(stat, LCD_WIDTH); // The string leaves space + + // If the remaining string doesn't completely fill the screen + if (rlen < LCD_WIDTH) { + uint8_t chars = LCD_WIDTH - rlen; // Amount of space left in characters + lcd.write(' '); // Always at 1+ spaces left, draw a space + if (--chars) { // Draw a second space if there's room + lcd.write(' '); + if (--chars) { // Draw a third space if there's room + lcd.write(' '); + if (--chars) + lcd_put_u8str_max(status_message, chars); // Print a second copy of the message + } + } + } + if (last_blink != blink) { + last_blink = blink; + advance_status_scroll(); + } + } + + #else + + UNUSED(blink); + + // Just print the string to the LCD + lcd_put_u8str_max(status_message, LCD_WIDTH); + + // Fill the rest with spaces if there are missing spaces + while (slen < LCD_WIDTH) { + lcd.write(' '); + ++slen; + } + + #endif +} + +/** +Possible status screens: + +Equal to 20x10 text LCD + +|X 000 Y 000 Z 000.00| +|FR100% SD100% C--:--| +| Progress bar line | +|Status message | +| | +| HE BED FAN | +| ttc ttc % | ttc - current temperature +| tts tts %%% | tts - set temperature, %%% - percent for FAN +| ICO ICO ICO ICO | ICO - icon 48x48, placed in 2 text lines +| ICO ICO ICO ICO | ICO + +or + +|X 000 Y 000 Z 000.00| +|FR100% SD100% C--:--| +| Progress bar line | +|Status message | +| | +|HE1 HE2 HE3 BED ICO| +|ttc ttc ttc ttc ICO| +|tts tts tts tts %%%| +|ICO ICO ICO ICO ICO| +|ICO ICO ICO ICO ICO| + +or + +|X 000 Y 000 Z 000.00| +|FR100% SD100% C--:--| +| Progress bar line | +|Status message | +| | +|COOL FLOW ILAZ CUTT | +| ttc L mA RPM | +| tts f.f aaa rr.rK| +| ICO ICO ICO ICO | +| ICO ICO ICO ICO | + +or + +Equal to 24x10 text LCD + +|X 000 Y 000 Z 000.00 | +|FR100% SD100% C--:--| +| Progress bar line | +|Status message | +| | +|HE1 HE2 HE3 BED FAN | +|ttc ttc ttc ttc % | +|tts tts tts tts %%% | +|ICO ICO ICO ICO ICO ICO| +|ICO ICO ICO ICO ICO ICO| +*/ + +void MarlinUI::draw_status_screen() { + if (!PanelDetected) return; + + const bool blink = get_blink(); + + lcd.clear_buffer(); + + // + // Line 1 - XYZ coordinates + // + + lcd.setCursor(0, 0); + const xyz_pos_t lpos = current_position.asLogical(); + _draw_axis_value(X_AXIS, ftostr4sign(lpos.x), blink); lcd.write(' '); + _draw_axis_value(Y_AXIS, ftostr4sign(lpos.y), blink); lcd.write(' '); + _draw_axis_value(Z_AXIS, ftostr52sp(lpos.z), blink); + + #if HAS_LEVELING && !HAS_HEATED_BED + lcd.write(planner.leveling_active || blink ? '_' : ' '); + #endif + + // + // Line 2 - feedrate, , time + // + + lcd.setCursor(0, 1); + lcd_put_u8str_P(PSTR("FR")); lcd.print(i16tostr3rj(feedrate_percentage)); lcd.write('%'); + + #if BOTH(SDSUPPORT, HAS_PRINT_PROGRESS) + lcd.setCursor(LCD_WIDTH / 2 - 3, 1); + _draw_print_progress(); + #endif + + char buffer[10]; + duration_t elapsed = print_job_timer.duration(); + uint8_t len = elapsed.toDigital(buffer); + + lcd.setCursor((LCD_WIDTH - 1) - len, 1); + lcd.write(LCD_STR_CLOCK[0]); lcd.print(buffer); + + // + // Line 3 - progressbar + // + + lcd.setCursor(0, 2); + #if ENABLED(LCD_PROGRESS_BAR) + draw_progress_bar(_get_progress()); + #else + lcd.write('%'); lcd.write(0); + #endif + + // + // Line 4 - Status Message (which may be a Filament display) + // + + draw_status_message(blink); + + // + // Line 5 + // + + #if HOTENDS <= 1 || (HOTENDS <= 2 && !HAS_HEATED_BED) + #if DUAL_MIXING_EXTRUDER + lcd.setCursor(0, 4); + // Two-component mix / gradient instead of XY + char mixer_messages[12]; + const char *mix_label; + #if ENABLED(GRADIENT_MIX) + if (mixer.gradient.enabled) { + mixer.update_mix_from_gradient(); + mix_label = "Gr"; + } + else + #endif + { + mixer.update_mix_from_vtool(); + mix_label = "Mx"; + } + sprintf_P(mixer_messages, PSTR("%s %d;%d%% "), mix_label, int(mixer.mix[0]), int(mixer.mix[1])); + lcd_put_u8str(mixer_messages); + #endif + #endif + + // + // Line 6..8 Temperatures, FAN for printer or Cooler, Flowmetter, Ampermeter, Cutter for laser/spindle + // + + #if HAS_HOTEND + + #if HOTENDS < 2 + _draw_heater_status(H_E0, "HE", blink); // Hotend Temperature + #else + _draw_heater_status(H_E0, "HE1", blink); // Hotend 1 Temperature + _draw_heater_status(H_E1, "HE2", blink); // Hotend 2 Temperature + #if HOTENDS > 2 + _draw_heater_status(H_E2, "HE3", blink); // Hotend 3 Temperature + #endif + #endif + + #if HAS_HEATED_BED + #if HAS_LEVELING + _draw_heater_status(H_BED, (planner.leveling_active && blink ? "___" : "BED"), blink); + #else + _draw_heater_status(H_BED, "BED", blink); + #endif + #endif + + #if HAS_FAN + uint16_t spd = thermalManager.fan_speed[0]; + #if ENABLED(ADAPTIVE_FAN_SLOWING) + if (!blink) spd = thermalManager.scaledFanSpeed(0, spd); + #endif + uint16_t per = thermalManager.pwmToPercent(spd); + + #if HOTENDS < 2 + #define FANX 11 + #else + #define FANX 17 + #endif + lcd.setCursor(FANX, 5); lcd_put_u8str_P(PSTR("FAN")); + lcd.setCursor(FANX + 1, 6); lcd.write('%'); + lcd.setCursor(FANX, 7); + lcd.print(i16tostr3rj(per)); + + if (TERN0(HAS_FAN0, thermalManager.fan_speed[0]) || TERN0(HAS_FAN1, thermalManager.fan_speed[1]) || TERN0(HAS_FAN2, thermalManager.fan_speed[2])) + picBits |= ICON_FAN; + else + picBits &= ~ICON_FAN; + + #endif // HAS_FAN + + #else + + TERN_(HAS_COOLER, _draw_cooler_status(blink)); + TERN_(LASER_COOLANT_FLOW_METER, _draw_flowmeter_status()); + TERN_(I2C_AMMETER, _draw_ammeter_status()); + TERN_(HAS_CUTTER, _draw_cutter_status()); + + #endif + + // + // Line 9, 10 - icons + // + lcd.print_screen(); +} + +#if HAS_LCD_MENU + + #include "../menu/menu.h" + + #if ENABLED(ADVANCED_PAUSE_FEATURE) + + void MarlinUI::draw_hotend_status(const uint8_t row, const uint8_t extruder) { + if (!PanelDetected) return; + lcd.setCursor((LCD_WIDTH - 14) / 2, row + 1); + lcd.write(LCD_STR_THERMOMETER[0]); lcd_put_u8str_P(PSTR(" E")); lcd.write('1' + extruder); lcd.write(' '); + lcd.print(i16tostr3rj(thermalManager.wholeDegHotend(extruder))); lcd.write(LCD_STR_DEGREE[0]); lcd.write('/'); + lcd.print(i16tostr3rj(thermalManager.degTargetHotend(extruder))); lcd.write(LCD_STR_DEGREE[0]); + lcd.print_line(); + } + + #endif + + // Draw a static item with no left-right margin required. Centered by default. + void MenuItem_static::draw(const uint8_t row, PGM_P const pstr, const uint8_t style/*=SS_DEFAULT*/, const char * const valstr/*=nullptr*/) { + if (!PanelDetected) return; + uint8_t n = LCD_WIDTH; + lcd.setCursor(0, row); + if ((style & SS_CENTER) && !valstr) { + int8_t pad = (LCD_WIDTH - utf8_strlen_P(pstr)) / 2; + while (--pad >= 0) { lcd.write(' '); n--; } + } + n = lcd_put_u8str_ind_P(pstr, itemIndex, itemString, n); + if (valstr) n -= lcd_put_u8str_max(valstr, n); + for (; n; --n) lcd.write(' '); + lcd.print_line(); + } + + // Draw a generic menu item with pre_char (if selected) and post_char + void MenuItemBase::_draw(const bool sel, const uint8_t row, PGM_P const pstr, const char pre_char, const char post_char) { + if (!PanelDetected) return; + lcd.setCursor(0, row); + lcd.write(sel ? pre_char : ' '); + uint8_t n = lcd_put_u8str_ind_P(pstr, itemIndex, itemString, LCD_WIDTH - 2); + for (; n; --n) lcd.write(' '); + lcd.write(post_char); + lcd.print_line(); + } + + // Draw a menu item with a (potentially) editable value + void MenuEditItemBase::draw(const bool sel, const uint8_t row, PGM_P const pstr, const char * const data, const bool pgm) { + if (!PanelDetected) return; + const uint8_t vlen = data ? (pgm ? utf8_strlen_P(data) : utf8_strlen(data)) : 0; + lcd.setCursor(0, row); + lcd.write(sel ? LCD_STR_ARROW_RIGHT[0] : ' '); + uint8_t n = lcd_put_u8str_ind_P(pstr, itemIndex, itemString, LCD_WIDTH - 2 - vlen); + if (vlen) { + lcd.write(':'); + for (; n; --n) lcd.write(' '); + if (pgm) lcd_put_u8str_P(data); else lcd_put_u8str(data); + } + lcd.print_line(); + } + + // Low-level draw_edit_screen can be used to draw an edit screen from anyplace + // This line moves to the last line of the screen for UBL plot screen on the panel side + void MenuEditItemBase::draw_edit_screen(PGM_P const pstr, const char * const value/*=nullptr*/) { + if (!PanelDetected) return; + ui.encoder_direction_normal(); + const uint8_t y = TERN0(AUTO_BED_LEVELING_UBL, ui.external_control) ? LCD_HEIGHT - 1 : MIDDLE_Y; + lcd.setCursor(0, y); + lcd.write(COLOR_EDIT); + lcd_put_u8str_P(pstr); + if (value) { + lcd.write(':'); + lcd.setCursor((LCD_WIDTH - 1) - (utf8_strlen(value) + 1), y); // Right-justified, padded by spaces + lcd.write(' '); // Overwrite char if value gets shorter + lcd.print(value); + lcd.write(' '); + lcd.print_line(); + } + } + + // The Select Screen presents a prompt and two "buttons" + void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const bool yesno, PGM_P const pref, const char * const string, PGM_P const suff) { + if (!PanelDetected) return; + ui.draw_select_screen_prompt(pref, string, suff); + lcd.setCursor(0, MIDDLE_Y); + lcd.write(COLOR_EDIT); + lcd.write(yesno ? ' ' : '['); lcd_put_u8str_P(no); lcd.write(yesno ? ' ' : ']'); + lcd.setCursor(LCD_WIDTH - utf8_strlen_P(yes) - 3, MIDDLE_Y); + lcd.write(yesno ? '[' : ' '); lcd_put_u8str_P(yes); lcd.write(yesno ? ']' : ' '); + lcd.print_line(); + } + + #if ENABLED(SDSUPPORT) + + void MenuItem_sdbase::draw(const bool sel, const uint8_t row, PGM_P const, CardReader &theCard, const bool isDir) { + if (!PanelDetected) return; + lcd.setCursor(0, row); + lcd.write(sel ? LCD_STR_ARROW_RIGHT[0] : ' '); + constexpr uint8_t maxlen = LCD_WIDTH - 2; + uint8_t n = maxlen - lcd_put_u8str_max(ui.scrolled_filename(theCard, maxlen, row, sel), maxlen); + for (; n; --n) lcd.write(' '); + lcd.write(isDir ? LCD_STR_FOLDER[0] : ' '); + lcd.print_line(); + } + + #endif // SDSUPPORT + + #if ENABLED(LCD_HAS_STATUS_INDICATORS) + + void MarlinUI::update_indicators() {} + + #endif // LCD_HAS_STATUS_INDICATORS + + #if ENABLED(AUTO_BED_LEVELING_UBL) + /** + * Map screen: + * |/---------\ (00,00) | + * || . . . . | X:000.00| + * || . . . . | Y:000.00| + * || . . . . | Z:00.000| + * || . . . . | | + * || . . . . | | + * || . . . . | | + * |+---------/ | + * | | + * |____________________| + */ + void MarlinUI::ubl_plot(const uint8_t x_plot, const uint8_t y_plot) { + if (!PanelDetected) return; + + #define _LCD_W_POS 12 + + lcd.clear_buffer(); + + //print only top left corner. All frame with grid points will be printed by panel + lcd.setCursor(0, 0); + *fb++ = TLC; //top left corner - marker for plot parameters + *fb = (GRID_MAX_POINTS_X << 4) + GRID_MAX_POINTS_Y; //set mesh size + + // Print plot position + lcd.setCursor(_LCD_W_POS, 0); + *fb++ = '('; lcd.print(i16tostr3left(x_plot)); + *fb++ = ','; lcd.print(i16tostr3left(y_plot)); *fb = ')'; + + // Show all values + lcd.setCursor(_LCD_W_POS, 1); lcd_put_u8str_P(PSTR("X:")); + lcd.print(ftostr52(LOGICAL_X_POSITION(pgm_read_float(&ubl._mesh_index_to_xpos[x_plot])))); + lcd.setCursor(_LCD_W_POS, 2); lcd_put_u8str_P(PSTR("Y:")); + lcd.print(ftostr52(LOGICAL_Y_POSITION(pgm_read_float(&ubl._mesh_index_to_ypos[y_plot])))); + + // Show the location value + lcd.setCursor(_LCD_W_POS, 3); lcd_put_u8str_P(PSTR("Z:")); + + if (!isnan(ubl.z_values[x_plot][y_plot])) + lcd.print(ftostr43sign(ubl.z_values[x_plot][y_plot])); + else + lcd_put_u8str_P(PSTR(" -----")); + + center_text_P(GET_TEXT(MSG_UBL_FINE_TUNE_MESH), 8); + + lcd.print_screen(); + } + + #endif // AUTO_BED_LEVELING_UBL + +#endif // HAS_LCD_MENU + +#endif // IS_TFTGLCD_PANEL diff --git a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.h b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.h new file mode 100644 index 000000000000..c399b907e460 --- /dev/null +++ b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.h @@ -0,0 +1,72 @@ +/** + * 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 + +/** + * Implementation of the LCD display routines for a TFT GLCD displays with external controller. + */ + +#include "../../inc/MarlinConfig.h" + +#if IS_TFTGLCD_PANEL + +#include "../../libs/duration_t.h" + +//////////////////////////////////// +// Set up button and encode mappings for each panel (into 'buttons' variable) +// +// This is just to map common functions (across different panels) onto the same +// macro name. The mapping is independent of whether the button is directly connected or +// via a shift/i2c register. + +//////////////////////////////////// +// Create LCD class instance and chipset-specific information +class TFTGLCD { + private: + public: + TFTGLCD(); + void clear_buffer(); + void clr_screen(); + void setCursor(uint8_t col, uint8_t row); + void write(char c); + void print(const char *line); + void print_line(); + void print_screen(); + void redraw_screen(); + void setContrast(uint16_t contrast); +}; + +extern TFTGLCD lcd; + +#include "../fontutils.h" +#include "../lcdprint.h" + +// Use panel encoder - free old encoder pins +#undef BTN_EN1 +#undef BTN_EN2 +#undef BTN_ENC + +#ifndef EN_C + #define EN_C 4 // for click +#endif + +#endif // IS_TFTGLCD_PANEL diff --git a/Marlin/src/lcd/TFTGLCD/ultralcd_TFTGLCD.cpp b/Marlin/src/lcd/TFTGLCD/ultralcd_TFTGLCD.cpp deleted file mode 100644 index b5789091dc2f..000000000000 --- a/Marlin/src/lcd/TFTGLCD/ultralcd_TFTGLCD.cpp +++ /dev/null @@ -1,963 +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 . - * - */ - -#include "../../inc/MarlinConfigPre.h" - -#if IS_TFTGLCD_PANEL - -/** - * ultralcd_TFTGLCD.cpp - * - * Implementation of the LCD display routines for a TFT GLCD displays with external controller. - * This display looks as a REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER but has good text font - * and supports color output. - */ - -#if NONE(__AVR__, TARGET_LPC1768, __STM32F1__, STM32F4xx) - #warning "Selected platform not yet tested. Please contribute your good pin mappings." -#endif - -#if ENABLED(TFTGLCD_PANEL_SPI) - #include -#else - #include -#endif - -#include "ultralcd_TFTGLCD.h" -#include "../ultralcd.h" -#include "../../libs/numtostr.h" - -#include "../../sd/cardreader.h" -#include "../../module/temperature.h" -#include "../../module/printcounter.h" -#include "../../module/planner.h" -#include "../../module/motion.h" - -#if DISABLED(LCD_PROGRESS_BAR) && BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) - #include "../../feature/filwidth.h" - #include "../../gcode/parser.h" -#endif - -#if ENABLED(AUTO_BED_LEVELING_UBL) - #include "../../feature/bedlevel/bedlevel.h" -#endif - -TFTGLCD lcd; - -#define ICON_LOGO B00000001 -#define ICON_TEMP1 B00000010 //hotend 1 -#define ICON_TEMP2 B00000100 //hotend 2 -#define ICON_TEMP3 B00001000 //hotend 3 -#define ICON_BED B00010000 -#define ICON_FAN B00100000 -#define ICON_HOT B01000000 //when any T > 50deg -#define PIC_MASK 0x7F - -// LEDs not used, for compatibility with Smoothieware -#define LED_HOTEND_ON B00000001 -#define LED_BED_ON B00000010 -#define LED_FAN_ON B00000100 -#define LED_HOT B00001000 -#define LED_MASK 0x0F - -#define FBSIZE (LCD_WIDTH * LCD_HEIGHT + 2) -#define MIDDLE_Y ((LCD_HEIGHT - 1) / 2) - -// Markers for change line colors -#define COLOR_EDIT '#' -#define COLOR_ERROR '!' - -#ifdef CONVERT_TO_EXT_ASCII //use standart pseudographic symbols in ASCII table - #define LR 179 //vertical line - #define TRC 191 //top right corner - #define BLC 192 //bottom left corner - #define GL 196 //horizontal line - #define BRC 217 //bottom right corner, should be replaced to 12 for some languages - #define TLC 218 //top left corner, should be replaced to 13 for some languages -#else //next symbols must be present in panel font - #define LR 8 //equal to 179 - #define TRC 9 //equal to 191 - #define BLC 10 //equal to 192 - #define GL 11 //equal to 196 - #define BRC 12 //equal to 217 - #define TLC 13 //equal to 218 -#endif - -#define Marlin 0x01 - -enum Commands { // based on Smoothieware commands - GET_SPI_DATA = 0, - READ_BUTTONS, // read buttons - READ_ENCODER, // read encoder - LCD_WRITE, // write all screen to LCD - BUZZER, // beep buzzer - CONTRAST, // set contrast (brightnes) - // Other commands... 0xE0 thru 0xFF - GET_LCD_ROW = 0xE0, // for detect panel - GET_LCD_COL, // reserved for compatibility with Smoothieware, not used - LCD_PUT, // write one line to LCD - CLR_SCREEN, - INIT_SCREEN = 0xFE // clear panel buffer -}; - -static unsigned char framebuffer[FBSIZE]; -static unsigned char *fb; -static uint8_t cour_line; -static uint8_t picBits, ledBits, hotBits; -static uint8_t PanelDetected = 0; - -// Different platforms use different SPI methods -#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 defined(STM32F4xx) - #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) - #define SPI_SEND_ONE(V) SPI.write(V); - #define SPI_SEND_TWO(V) SPI.write16(V); -#endif - -#if ANY(__AVR__, ARDUINO_ARCH_SAM, __SAMD51__, __MK20DX256__, __MK64FX512__) - #define SPI_SEND_SOME(V,L,Z) SPI.transfer(&V[Z], L); -#elif defined(STM32F4xx) - #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) -#endif - -// Constructor -TFTGLCD::TFTGLCD() {} - -// Clear local buffer -void TFTGLCD::clear_buffer() { - memset(&framebuffer[0], ' ', FBSIZE - 2); - framebuffer[FBSIZE - 1] = framebuffer[FBSIZE - 2] = 0; - picBits = ledBits = 0; -} - -// Clear panel's screen -void TFTGLCD::clr_screen() { - if (!PanelDetected) return; - #if ENABLED(TFTGLCD_PANEL_SPI) - WRITE(TFTGLCD_CS, LOW); - SPI_SEND_ONE(CLR_SCREEN); - WRITE(TFTGLCD_CS, HIGH); - #else - Wire.beginTransmission((uint8_t)LCD_I2C_ADDRESS); //set I2C device address - Wire.write(CLR_SCREEN); - Wire.endTransmission(); //transmit data - #endif -} - -// Set new text cursor position -void TFTGLCD::setCursor(uint8_t col, uint8_t row) { - fb = &framebuffer[0] + col + row * LCD_WIDTH; - cour_line = row; -} - -// Send char to buffer -void TFTGLCD::write(char c) { - *fb++ = c; -} - -// Send text line to buffer -void TFTGLCD::print(const char *line) { - while (*line) *fb++ = *line++; -} - -// For menu -void TFTGLCD::print_line() { - if (!PanelDetected) return; - #if ENABLED(TFTGLCD_PANEL_SPI) - WRITE(TFTGLCD_CS, LOW); - SPI_SEND_ONE(LCD_PUT); - SPI_SEND_ONE(cour_line); - SPI_SEND_SOME(framebuffer, LCD_WIDTH, cour_line * LCD_WIDTH); - WRITE(TFTGLCD_CS, HIGH); - #else - Wire.beginTransmission((uint8_t)LCD_I2C_ADDRESS); //set I2C device address - Wire.write(LCD_PUT); - Wire.write(cour_line); - Wire.write(&framebuffer[cour_line * LCD_WIDTH], LCD_WIDTH); //transfer 1 line to txBuffer - Wire.endTransmission(); //transmit data - safe_delay(1); - #endif -} - -void TFTGLCD::print_screen(){ - if (!PanelDetected) return; - framebuffer[FBSIZE - 2] = picBits & PIC_MASK; - framebuffer[FBSIZE - 1] = ledBits; - #if ENABLED(TFTGLCD_PANEL_SPI) - // Send all framebuffer to panel - WRITE(TFTGLCD_CS, LOW); - SPI_SEND_ONE(LCD_WRITE); - SPI_SEND_SOME(framebuffer, FBSIZE, 0); - WRITE(TFTGLCD_CS, HIGH); - #else - uint8_t r; - // Send framebuffer to panel by line - Wire.beginTransmission((uint8_t)LCD_I2C_ADDRESS); - // First line - Wire.write(LCD_WRITE); - Wire.write(&framebuffer[0], LCD_WIDTH); - Wire.endTransmission(); - for (r = 1; r < (LCD_HEIGHT - 1); r++) { - Wire.beginTransmission((uint8_t)LCD_I2C_ADDRESS); - Wire.write(&framebuffer[r * LCD_WIDTH], LCD_WIDTH); - Wire.endTransmission(); - } - // Last line - Wire.beginTransmission((uint8_t)LCD_I2C_ADDRESS); - Wire.write(&framebuffer[r * LCD_WIDTH], LCD_WIDTH); - Wire.write(&framebuffer[FBSIZE - 2], 2); - Wire.endTransmission(); - #endif -} - -void TFTGLCD::setContrast(uint16_t contrast) { - if (!PanelDetected) return; - #if ENABLED(TFTGLCD_PANEL_SPI) - WRITE(TFTGLCD_CS, LOW); - SPI_SEND_ONE(CONTRAST); - SPI_SEND_ONE((uint8_t)contrast); - WRITE(TFTGLCD_CS, HIGH); - #else - Wire.beginTransmission((uint8_t)LCD_I2C_ADDRESS); - Wire.write(CONTRAST); - Wire.write((uint8_t)contrast); - Wire.endTransmission(); - #endif -} - -extern volatile int8_t encoderDiff; - -// Read buttons and encoder states -uint8_t MarlinUI::read_slow_buttons(void) { - if (!PanelDetected) return 0; - #if ENABLED(TFTGLCD_PANEL_SPI) - uint8_t b = 0; - WRITE(TFTGLCD_CS, LOW); - SPI_SEND_ONE(READ_ENCODER); - #ifndef STM32F4xx - WRITE(TFTGLCD_CS, LOW); // for delay - #endif - encoderDiff += SPI_SEND_ONE(READ_BUTTONS); - #ifndef STM32F4xx - WRITE(TFTGLCD_CS, LOW); // for delay - WRITE(TFTGLCD_CS, LOW); - #endif - b = SPI_SEND_ONE(GET_SPI_DATA); - WRITE(TFTGLCD_CS, HIGH); - return b; - #else - Wire.beginTransmission((uint8_t)LCD_I2C_ADDRESS); - Wire.write(READ_ENCODER); - Wire.endTransmission(); - #ifdef __AVR__ - 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) - Wire.requestFrom(LCD_I2C_ADDRESS, 2); - #endif - encoderDiff += Wire.read(); - return Wire.read(); //buttons - #endif -} - -// Duration in ms, freq in Hz -void MarlinUI::buzz(const long duration, const uint16_t freq) { - if (!PanelDetected) return; - #if ENABLED(TFTGLCD_PANEL_SPI) - WRITE(TFTGLCD_CS, LOW); - SPI_SEND_ONE(BUZZER); - SPI_SEND_TWO((uint16_t)duration); - SPI_SEND_TWO(freq); - WRITE(TFTGLCD_CS, HIGH); - #else - Wire.beginTransmission((uint8_t)LCD_I2C_ADDRESS); - Wire.write(BUZZER); - Wire.write((uint8_t)(duration >> 8)); - Wire.write((uint8_t)duration); - Wire.write((uint8_t)(freq >> 8)); - Wire.write((uint8_t)freq); - Wire.endTransmission(); - #endif -} - -void MarlinUI::init_lcd() { - uint8_t t; - lcd.clear_buffer(); - t = 0; - #if ENABLED(TFTGLCD_PANEL_SPI) - // SPI speed must be less 10MHz - _SET_OUTPUT(TFTGLCD_CS); - WRITE(TFTGLCD_CS, HIGH); - spiInit(TERN(__STM32F1__, SPI_QUARTER_SPEED, SPI_FULL_SPEED)); - WRITE(TFTGLCD_CS, LOW); - SPI_SEND_ONE(GET_LCD_ROW); - t = SPI_SEND_ONE(GET_SPI_DATA); - #else - #ifdef TARGET_LPC1768 - Wire.begin(); //init twi/I2C - #else - Wire.begin((uint8_t)LCD_I2C_ADDRESS); //init twi/I2C - #endif - Wire.beginTransmission((uint8_t)LCD_I2C_ADDRESS); - Wire.write((uint8_t)GET_LCD_ROW); // put command to buffer - Wire.endTransmission(); // send buffer - #ifdef __AVR__ - Wire.requestFrom((uint8_t)LCD_I2C_ADDRESS, 1, 0, 0, 1); - #elif ANY(__STM32F1__, STM32F4xx, TARGET_LPC1768) - Wire.requestFrom(LCD_I2C_ADDRESS, 1); - #endif - t = (uint8_t)Wire.read(); - #endif - - if (t == LCD_HEIGHT) { - PanelDetected = 1; - #if ENABLED(TFTGLCD_PANEL_SPI) - SPI_SEND_ONE(INIT_SCREEN); - SPI_SEND_ONE(Marlin); - WRITE(TFTGLCD_CS, HIGH); - #else - Wire.beginTransmission((uint8_t)LCD_I2C_ADDRESS); - Wire.write((uint8_t)INIT_SCREEN); - Wire.write(Marlin); - Wire.endTransmission(); - #endif - } - else - PanelDetected = 0; - safe_delay(100); -} - -bool MarlinUI::detected() { - return PanelDetected; -} - -void MarlinUI::clear_lcd() { - if (!PanelDetected) return; - lcd.clr_screen(); - lcd.clear_buffer(); -} - -int16_t MarlinUI::contrast; // Initialized by settings.load() - -void MarlinUI::set_contrast(const int16_t value) { - contrast = constrain(value, LCD_CONTRAST_MIN, LCD_CONTRAST_MAX); - lcd.setContrast(contrast); -} - -static void center_text_P(PGM_P pstart, uint8_t y) { - uint8_t len = utf8_strlen_P(pstart); - if (len < LCD_WIDTH) - lcd.setCursor((LCD_WIDTH - len) / 2, y); - else - lcd.setCursor(0, y); - lcd_put_u8str_P(pstart); -} - -#if ENABLED(SHOW_BOOTSCREEN) - - void MarlinUI::show_bootscreen() { - if (!PanelDetected) return; - // - // Show the Marlin logo, splash line1, and splash line 2 - // - uint8_t indent = (LCD_WIDTH - 8) / 2; - // symbols 217 (bottom right corner) and 218 (top left corner) are using for letters in some languages - // and they should be moved to begining ASCII table as spetial symbols - lcd.setCursor(indent, 0); lcd.write(TLC); lcd_put_u8str_P(PSTR("------")); lcd.write(TRC); - lcd.setCursor(indent, 1); lcd.write(LR); lcd_put_u8str_P(PSTR("Marlin")); lcd.write(LR); - lcd.setCursor(indent, 2); lcd.write(BLC); lcd_put_u8str_P(PSTR("------")); lcd.write(BRC); - center_text_P(PSTR(SHORT_BUILD_VERSION), 3); - center_text_P(PSTR(MARLIN_WEBSITE_URL), 4); - picBits = ICON_LOGO; - lcd.print_screen(); - safe_delay(1500); - } - -#endif // SHOW_BOOTSCREEN - -void MarlinUI::draw_kill_screen() { - if (!PanelDetected) return; - lcd.clear_buffer(); - lcd.setCursor(0, 3); lcd.write(COLOR_ERROR); - lcd.setCursor((LCD_WIDTH - utf8_strlen(status_message)) / 2 + 1, 3); - lcd_put_u8str(status_message); - center_text_P(GET_TEXT(MSG_HALTED), 5); - center_text_P(GET_TEXT(MSG_PLEASE_RESET), 6); - lcd.print_screen(); -} - -// -// Before homing, blink '123' <-> '???'. -// Homed but unknown... '123' <-> ' '. -// Homed and known, display constantly. -// -FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const bool blink) { - lcd.write('X' + uint8_t(axis)); - if (blink) - lcd.print(value); - else { - if (!TEST(axis_homed, axis)) - while (const char c = *value++) lcd.write(c <= '.' ? c : '?'); - else { - #if NONE(HOME_AFTER_DEACTIVATE, DISABLE_REDUCED_ACCURACY_WARNING) - if (!TEST(axis_known_position, axis)) - lcd_put_u8str_P(axis == Z_AXIS ? PSTR(" ") : PSTR(" ")); - else - #endif - lcd_put_u8str(value); - } - } -} - -FORCE_INLINE void _draw_heater_status(const heater_id_t heater_id, const char *prefix, const bool blink) { - uint8_t pic_hot_bits; - #if HAS_HEATED_BED - const bool isBed = heater_id < 0; - const float t1 = (isBed ? thermalManager.degBed() : thermalManager.degHotend(heater_id)); - const float t2 = (isBed ? thermalManager.degTargetBed() : thermalManager.degTargetHotend(heater_id)); - #else - const float t1 = thermalManager.degHotend(heater_id); - const float t2 = thermalManager.degTargetHotend(heater_id); - #endif - - #if HOTENDS < 2 - if (heater_id == H_E0) { - lcd.setCursor(2, 5); lcd.print(prefix); //HE - lcd.setCursor(1, 6); lcd.print(i16tostr3rj(t1 + 0.5)); - lcd.setCursor(1, 7); - } - else { - lcd.setCursor(6, 5); lcd.print(prefix); //BED - lcd.setCursor(6, 6); lcd.print(i16tostr3rj(t1 + 0.5)); - lcd.setCursor(6, 7); - } - #else - if (heater_id > H_BED) { - lcd.setCursor(heater_id * 4, 5); lcd.print(prefix); //HE1 or HE2 or HE3 - lcd.setCursor(heater_id * 4, 6); lcd.print(i16tostr3rj(t1 + 0.5)); - lcd.setCursor(heater_id * 4, 7); - } - else { - lcd.setCursor(13, 5); lcd.print(prefix); //BED - lcd.setCursor(13, 6); lcd.print(i16tostr3rj(t1 + 0.5)); - lcd.setCursor(13, 7); - } - #endif // HOTENDS <= 1 - - #if !HEATER_IDLE_HANDLER - UNUSED(blink); - #else - if (!blink && thermalManager.heater_idle[thermalManager.idle_index_for_id(heater_id)].timed_out) { - lcd.write(' '); - if (t2 >= 10) lcd.write(' '); - if (t2 >= 100) lcd.write(' '); - } - else - #endif // !HEATER_IDLE_HANDLER - lcd.print(i16tostr3rj(t2 + 0.5)); - - switch (heater_id) { - case H_BED: pic_hot_bits = ICON_BED; break; - case H_E0: pic_hot_bits = ICON_TEMP1; break; - case H_E1: pic_hot_bits = ICON_TEMP2; break; - case H_E2: pic_hot_bits = ICON_TEMP3; - default: break; - } - - if (t2) picBits |= pic_hot_bits; - else picBits &= ~pic_hot_bits; - - if (t1 > 50) hotBits |= pic_hot_bits; - else hotBits &= ~pic_hot_bits; - - if (hotBits) picBits |= ICON_HOT; - else picBits &= ~ICON_HOT; -} - -#if HAS_PRINT_PROGRESS - - FORCE_INLINE void _draw_print_progress() { - if (!PanelDetected) return; - const uint8_t progress = ui._get_progress(); - #if ENABLED(SDSUPPORT) - lcd_put_u8str_P(PSTR("SD")); - #elif ENABLED(LCD_SET_PROGRESS_MANUALLY) - lcd_put_u8str_P(PSTR("P:")); - #endif - if (progress) - lcd.print(ui8tostr3rj(progress)); - else - lcd_put_u8str_P(PSTR("---")); - lcd.write('%'); - } - -#endif // HAS_PRINT_PROGRESS - -#if ENABLED(LCD_PROGRESS_BAR) - - void MarlinUI::draw_progress_bar(const uint8_t percent) { - if (!PanelDetected) return; - if (fb == &framebuffer[0] + LCD_WIDTH * 2) { // For status screen - lcd.write('%'); lcd.write(percent); - } - else { // For progress bar test - lcd.setCursor(LCD_WIDTH / 2 - 2, MIDDLE_Y); - lcd.print(i16tostr3rj(percent)); lcd.write('%'); - lcd.print_line(); - lcd.setCursor(0, MIDDLE_Y + 1); - lcd.write('%'); lcd.write(percent); - lcd.print_line(); - } - } - -#endif - -void MarlinUI::draw_status_message(const bool blink) { - if (!PanelDetected) return; - lcd.setCursor(0, 3); - #if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) - - // Alternate Status message and Filament display - if (ELAPSED(millis(), next_filament_display)) { - lcd_put_u8str_P(PSTR("Dia ")); - lcd.print(ftostr12ns(filament_width_meas)); - lcd_put_u8str_P(PSTR(" V")); - lcd.print(i16tostr3rj(100.0 * ( - parser.volumetric_enabled - ? planner.volumetric_area_nominal / planner.volumetric_multiplier[FILAMENT_SENSOR_EXTRUDER_NUM] - : planner.volumetric_multiplier[FILAMENT_SENSOR_EXTRUDER_NUM] - ) - )); - lcd.write('%'); - return; - } - - #endif // FILAMENT_LCD_DISPLAY && SDSUPPORT - - // Get the UTF8 character count of the string - uint8_t slen = utf8_strlen(status_message); - - #if ENABLED(STATUS_MESSAGE_SCROLLING) - - static bool last_blink = false; - - // If the string fits into the LCD, just print it and do not scroll it - if (slen <= LCD_WIDTH) { - - // The string isn't scrolling and may not fill the screen - lcd_put_u8str(status_message); - - // Fill the rest with spaces - while (slen < LCD_WIDTH) { lcd.write(' '); ++slen; } - } - else { - // String is larger than the available space in screen. - - // Get a pointer to the next valid UTF8 character - // and the string remaining length - uint8_t rlen; - const char *stat = status_and_len(rlen); - lcd_put_u8str_max(stat, LCD_WIDTH); // The string leaves space - - // If the remaining string doesn't completely fill the screen - if (rlen < LCD_WIDTH) { - lcd.write('.'); // Always at 1+ spaces left, draw a dot - uint8_t chars = LCD_WIDTH - rlen; // Amount of space left in characters - if (--chars) { // Draw a second dot if there's space - lcd.write('.'); - if (--chars) - lcd_put_u8str_max(status_message, chars); // Print a second copy of the message - } - } - if (last_blink != blink) { - last_blink = blink; - advance_status_scroll(); - } - } - - #else - - UNUSED(blink); - - // Just print the string to the LCD - lcd_put_u8str_max(status_message, LCD_WIDTH); - - // Fill the rest with spaces if there are missing spaces - while (slen < LCD_WIDTH) { - lcd.write(' '); - ++slen; - } - - #endif -} - -/** -Possible status screens: - -Equal to 20x10 text LCD - -|X 000 Y 000 Z 000.00| -|FR100% SD100% C--:--| -| Progress bar line | -|Status message | -| | -| HE BED FAN | -| ttc ttc % | ttc - current temperature -| tts tts %%% | tts - setted temperature, %%% - percent for FAN -| ICO ICO ICO ICO | ICO - icon 48x48, placed in 2 text lines -| ICO ICO ICO ICO | ICO / - -or - -|X 000 Y 000 Z 000.00| -|FR100% SD100% C--:--| -| Progress bar line | -|Status message | -| | -|HE1 HE2 HE3 BED ICO| -|ttc ttc ttc ttc ICO| -|tts tts tts tts %%%| -|ICO ICO ICO ICO ICO| -|ICO ICO ICO ICO ICO| - -or - -Equal to 24x10 text LCD - -|X 000 Y 000 Z 000.00 | -|FR100% SD100% C--:--| -| Progress bar line | -|Status message | -| | -|HE1 HE2 HE3 BED FAN | -|ttc ttc ttc ttc % | -|tts tts tts tts %%% | -|ICO ICO ICO ICO ICO ICO| -|ICO ICO ICO ICO ICO ICO| -*/ - -void MarlinUI::draw_status_screen() { - if (!PanelDetected) return; - - const bool blink = get_blink(); - - lcd.clear_buffer(); - - // - // Line 1 - XYZ coordinates - // - - lcd.setCursor(0, 0); - _draw_axis_value(X_AXIS, ftostr4sign(LOGICAL_X_POSITION(current_position[X_AXIS])), blink); lcd.write(' '); - _draw_axis_value(Y_AXIS, ftostr4sign(LOGICAL_Y_POSITION(current_position[Y_AXIS])), blink); lcd.write(' '); - _draw_axis_value(Z_AXIS, ftostr52sp(LOGICAL_Z_POSITION(current_position[Z_AXIS])), blink); - - #if HAS_LEVELING && !HAS_HEATED_BED - lcd.write(planner.leveling_active || blink ? '_' : ' '); - #endif - - // - // Line 2 - feedrate, , time - // - - lcd.setCursor(0, 1); - lcd_put_u8str_P(PSTR("FR")); lcd.print(i16tostr3rj(feedrate_percentage)); lcd.write('%'); - - #if BOTH(SDSUPPORT, HAS_PRINT_PROGRESS) - lcd.setCursor(LCD_WIDTH / 2 - 3, 1); - _draw_print_progress(); - #endif - - char buffer[10]; - duration_t elapsed = print_job_timer.duration(); - uint8_t len = elapsed.toDigital(buffer); - - lcd.setCursor((LCD_WIDTH - 1) - len, 1); - lcd.write(0x07); lcd.print(buffer); // LCD_CLOCK_CHAR - - // - // Line 3 - progressbar - // - - lcd.setCursor(0, 2); - #if ENABLED(LCD_PROGRESS_BAR) - draw_progress_bar(_get_progress()); - #else - lcd.write('%'); lcd.write(0); - #endif - - // - // Line 4 - Status Message (which may be a Filament display) - // - - draw_status_message(blink); - - // - // Line 5 - // - - #if HOTENDS <= 1 || (HOTENDS <= 2 && !HAS_HEATED_BED) - #if DUAL_MIXING_EXTRUDER - lcd.setCursor(0, 4); - // Two-component mix / gradient instead of XY - char mixer_messages[12]; - const char *mix_label; - #if ENABLED(GRADIENT_MIX) - if (mixer.gradient.enabled) { - mixer.update_mix_from_gradient(); - mix_label = "Gr"; - } - else - #endif - { - mixer.update_mix_from_vtool(); - mix_label = "Mx"; - } - sprintf_P(mixer_messages, PSTR("%s %d;%d%% "), mix_label, int(mixer.mix[0]), int(mixer.mix[1])); - lcd_put_u8str(mixer_messages); - #endif - #endif - - // - // Line 6..8 Temperatures, FAN - // - - #if HOTENDS < 2 - _draw_heater_status(H_E0, "HE", blink); // Hotend Temperature - #else - _draw_heater_status(H_E0, "HE1", blink); // Hotend 1 Temperature - _draw_heater_status(H_E1, "HE2", blink); // Hotend 2 Temperature - #if HOTENDS > 2 - _draw_heater_status(H_E2, "HE3", blink); // Hotend 3 Temperature - #endif - #endif // HOTENDS <= 1 - - #if HAS_HEATED_BED - #if HAS_LEVELING - _draw_heater_status(H_BED, (planner.leveling_active && blink ? "___" : "BED"), blink); - #else - _draw_heater_status(H_BED, "BED", blink); - #endif - #endif // HAS_HEATED_BED - - #if FAN_COUNT > 0 - uint16_t spd = thermalManager.fan_speed[0]; - - #if ENABLED(ADAPTIVE_FAN_SLOWING) - if (!blink) spd = thermalManager.scaledFanSpeed(0, spd); - #endif - - uint16_t per = thermalManager.fanPercent(spd); - #if HOTENDS < 2 - #define FANX 11 - #else - #define FANX 17 - #endif - lcd.setCursor(FANX, 5); lcd_put_u8str_P(PSTR("FAN")); - lcd.setCursor(FANX + 1, 6); lcd.write('%'); - lcd.setCursor(FANX, 7); - lcd.print(i16tostr3rj(per)); - - if (TERN0(HAS_FAN0, thermalManager.fan_speed[0]) || TERN0(HAS_FAN1, thermalManager.fan_speed[1]) || TERN0(HAS_FAN2, thermalManager.fan_speed[2])) - picBits |= ICON_FAN; - else - picBits &= ~ICON_FAN; - - #endif // FAN_COUNT > 0 - - // - // Line 9, 10 - icons - // - lcd.print_screen(); -} - -#if HAS_LCD_MENU - - #include "../menu/menu.h" - - #if ENABLED(ADVANCED_PAUSE_FEATURE) - - void MarlinUI::draw_hotend_status(const uint8_t row, const uint8_t extruder) { - if (!PanelDetected) return; - lcd.setCursor((LCD_WIDTH - 14) / 2, row + 1); - lcd.write(0x02); lcd_put_u8str_P(" E"); lcd.write('1' + extruder); lcd.write(' '); - lcd.print(i16tostr3rj(thermalManager.degHotend(extruder))); lcd.write(0x01); lcd.write('/'); - lcd.print(i16tostr3rj(thermalManager.degTargetHotend(extruder))); lcd.write(0x01); - lcd.print_line(); - } - - #endif // ADVANCED_PAUSE_FEATURE - - // Draw a static item with no left-right margin required. Centered by default. - void MenuItem_static::draw(const uint8_t row, PGM_P const pstr, const uint8_t style/*=SS_DEFAULT*/, const char * const valstr/*=nullptr*/) { - if (!PanelDetected) return; - uint8_t n = LCD_WIDTH; - lcd.setCursor(0, row); - if ((style & SS_CENTER) && !valstr) { - int8_t pad = (LCD_WIDTH - utf8_strlen_P(pstr)) / 2; - while (--pad >= 0) { lcd.write(' '); n--; } - } - n = lcd_put_u8str_ind_P(pstr, itemIndex, itemString, n); - if (valstr) n -= lcd_put_u8str_max(valstr, n); - for (; n; --n) lcd.write(' '); - lcd.print_line(); - } - - // Draw a generic menu item with pre_char (if selected) and post_char - void MenuItemBase::_draw(const bool sel, const uint8_t row, PGM_P const pstr, const char pre_char, const char post_char) { - if (!PanelDetected) return; - lcd.setCursor(0, row); - lcd.write(sel ? pre_char : ' '); - uint8_t n = lcd_put_u8str_ind_P(pstr, itemIndex, itemString, LCD_WIDTH - 2); - for (; n; --n) lcd.write(' '); - lcd.write(post_char); - lcd.print_line(); - } - - // Draw a menu item with a (potentially) editable value - void MenuEditItemBase::draw(const bool sel, const uint8_t row, PGM_P const pstr, const char* const data, const bool pgm) { - if (!PanelDetected) return; - const uint8_t vlen = data ? (pgm ? utf8_strlen_P(data) : utf8_strlen(data)) : 0; - lcd.setCursor(0, row); - lcd.write(sel ? LCD_STR_ARROW_RIGHT[0] : ' '); - uint8_t n = lcd_put_u8str_ind_P(pstr, itemIndex, itemString, LCD_WIDTH - 2 - vlen); - if (vlen) { - lcd.write(':'); - for (; n; --n) lcd.write(' '); - if (pgm) lcd_put_u8str_P(data); else lcd_put_u8str(data); - } - lcd.print_line(); - } - - // Low-level draw_edit_screen can be used to draw an edit screen from anyplace - // This line moves to the last line of the screen for UBL plot screen on the panel side - void MenuEditItemBase::draw_edit_screen(PGM_P const pstr, const char* const value/*=nullptr*/) { - if (!PanelDetected) return; - ui.encoder_direction_normal(); - lcd.setCursor(0, MIDDLE_Y); - lcd.write(COLOR_EDIT); - lcd_put_u8str_P(pstr); - if (value != nullptr) { - lcd.write(':'); - lcd.setCursor((LCD_WIDTH - 1) - (utf8_strlen(value) + 1), MIDDLE_Y); // Right-justified, padded by spaces - lcd.write(' '); // Overwrite char if value gets shorter - lcd.print(value); - lcd.write(' '); - lcd.print_line(); - } - } - - // The Select Screen presents a prompt and two "buttons" - void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const bool yesno, PGM_P const pref, const char * const string, PGM_P const suff) { - if (!PanelDetected) return; - ui.draw_select_screen_prompt(pref, string, suff); - lcd.setCursor(0, MIDDLE_Y); - lcd.write(COLOR_EDIT); - lcd.write(yesno ? ' ' : '['); lcd_put_u8str_P(no); lcd.write(yesno ? ' ' : ']'); - lcd.setCursor(LCD_WIDTH - utf8_strlen_P(yes) - 3, MIDDLE_Y); - lcd.write(yesno ? '[' : ' '); lcd_put_u8str_P(yes); lcd.write(yesno ? ']' : ' '); - lcd.print_line(); - } - - #if ENABLED(SDSUPPORT) - - void MenuItem_sdbase::draw(const bool sel, const uint8_t row, PGM_P const, CardReader &theCard, const bool isDir) { - if (!PanelDetected) return; - lcd.setCursor(0, row); - lcd.write(sel ? LCD_STR_ARROW_RIGHT[0] : ' '); - constexpr uint8_t maxlen = LCD_WIDTH - 2; - uint8_t n = maxlen - lcd_put_u8str_max(ui.scrolled_filename(theCard, maxlen, row, sel), maxlen); - for (; n; --n) lcd.write(' '); - lcd.write(isDir ? LCD_STR_FOLDER[0] : ' '); - lcd.print_line(); - } - - #endif // SDSUPPORT - - #if ENABLED(LCD_HAS_STATUS_INDICATORS) - - void MarlinUI::update_indicators() {} - - #endif // LCD_HAS_STATUS_INDICATORS - - #if ENABLED(AUTO_BED_LEVELING_UBL) - /** - * Map screen: - * |/---------\ (00,00) | - * || . . . . | X:000.00| - * || . . . . | Y:000.00| - * || . . . . | Z:00.000| - * || . . . . | | - * || . . . . | | - * || . . . . | | - * |+---------/ | - * | | - * |____________________| - */ - void MarlinUI::ubl_plot(const uint8_t x_plot, const uint8_t y_plot) { - if (!PanelDetected) return; - - #define _LCD_W_POS 12 - - lcd.clear_buffer(); - - //print only top left corner. All frame with grid points will be printed by panel - lcd.setCursor(0, 0); - *fb++ = TLC; //top left corner - marker for plot parameters - *fb = (GRID_MAX_POINTS_X << 4) + GRID_MAX_POINTS_Y; //set mesh size - - // Print plot position - lcd.setCursor(_LCD_W_POS, 0); - *fb++ = '('; lcd.print(i16tostr3left(x_plot)); - *fb++ = ','; lcd.print(i16tostr3left(y_plot)); *fb = ')'; - - // Show all values - lcd.setCursor(_LCD_W_POS, 1); lcd_put_u8str_P(PSTR("X:")); - lcd.print(ftostr52(LOGICAL_X_POSITION(pgm_read_float(&ubl._mesh_index_to_xpos[x_plot])))); - lcd.setCursor(_LCD_W_POS, 2); lcd_put_u8str_P(PSTR("Y:")); - lcd.print(ftostr52(LOGICAL_Y_POSITION(pgm_read_float(&ubl._mesh_index_to_ypos[y_plot])))); - - // Show the location value - lcd.setCursor(_LCD_W_POS, 3); lcd_put_u8str_P(PSTR("Z:")); - - if (!isnan(ubl.z_values[x_plot][y_plot])) - lcd.print(ftostr43sign(ubl.z_values[x_plot][y_plot])); - else - lcd_put_u8str_P(PSTR(" -----")); - - center_text_P(GET_TEXT(MSG_UBL_FINE_TUNE_MESH), 8); - - lcd.print_screen(); - } - - #endif // AUTO_BED_LEVELING_UBL - -#endif // HAS_LCD_MENU - -#endif // IS_TFTGLCD_PANEL diff --git a/Marlin/src/lcd/TFTGLCD/ultralcd_TFTGLCD.h b/Marlin/src/lcd/TFTGLCD/ultralcd_TFTGLCD.h deleted file mode 100644 index eedcc4afa073..000000000000 --- a/Marlin/src/lcd/TFTGLCD/ultralcd_TFTGLCD.h +++ /dev/null @@ -1,75 +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 - -/** - * Implementation of the LCD display routines for a TFT GLCD displays with external controller. - */ - -#include "../../inc/MarlinConfig.h" - -#if IS_TFTGLCD_PANEL - -#include "../../libs/duration_t.h" - -//////////////////////////////////// -// Set up button and encode mappings for each panel (into 'buttons' variable) -// -// This is just to map common functions (across different panels) onto the same -// macro name. The mapping is independent of whether the button is directly connected or -// via a shift/i2c register. - -//////////////////////////////////// -// Create LCD class instance and chipset-specific information -class TFTGLCD { - private: - public: - TFTGLCD(); - void clear_buffer(); - void clr_screen(); - void setCursor(uint8_t col, uint8_t row); - void write(char c); - void print(const char *line); - void print_line(); - void print_screen(); - void redraw_screen(); - void setContrast(uint16_t contrast); -}; - -extern TFTGLCD lcd; - -#include "../fontutils.h" -#include "../lcdprint.h" - -// Use panel encoder - free old encoder pins -#undef BTN_EN1 -#undef BTN_EN2 -#undef BTN_ENC -#define BTN_EN1 -1 -#define BTN_EN2 -1 -#define BTN_ENC -1 - -#ifndef EN_C - #define EN_C 4 //for click -#endif - -#endif // IS_TFTGLCD_PANEL diff --git a/Marlin/src/lcd/buttons.h b/Marlin/src/lcd/buttons.h new file mode 100644 index 000000000000..f39cb0a9aa03 --- /dev/null +++ b/Marlin/src/lcd/buttons.h @@ -0,0 +1,224 @@ +/** + * 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 + +#include "../inc/MarlinConfig.h" + +#if ((!HAS_ADC_BUTTONS && IS_NEWPANEL) || BUTTONS_EXIST(EN1, EN2)) && !IS_TFTGLCD_PANEL + #define HAS_ENCODER_WHEEL 1 +#endif +#if HAS_ENCODER_WHEEL || ANY_BUTTON(ENC, BACK, UP, DWN, LFT, RT) + #define HAS_DIGITAL_BUTTONS 1 +#endif +#if !HAS_ADC_BUTTONS && (IS_RRW_KEYPAD || (HAS_WIRED_LCD && !IS_NEWPANEL)) + #define HAS_SHIFT_ENCODER 1 +#endif + +// I2C buttons must be read in the main thread +#if ANY(LCD_I2C_VIKI, LCD_I2C_PANELOLU2, IS_TFTGLCD_PANEL) + #define HAS_SLOW_BUTTONS 1 +#endif + +#if HAS_ENCODER_WHEEL + #define ENCODER_PHASE_0 0 + #define ENCODER_PHASE_1 2 + #define ENCODER_PHASE_2 3 + #define ENCODER_PHASE_3 1 +#endif + +#if IS_RRW_KEYPAD + #define BTN_OFFSET 0 // Bit offset into buttons for shift register values + + #define BLEN_KEYPAD_F3 0 + #define BLEN_KEYPAD_F2 1 + #define BLEN_KEYPAD_F1 2 + #define BLEN_KEYPAD_DOWN 3 + #define BLEN_KEYPAD_RIGHT 4 + #define BLEN_KEYPAD_MIDDLE 5 + #define BLEN_KEYPAD_UP 6 + #define BLEN_KEYPAD_LEFT 7 + + #define EN_KEYPAD_F1 _BV(BTN_OFFSET + BLEN_KEYPAD_F1) + #define EN_KEYPAD_F2 _BV(BTN_OFFSET + BLEN_KEYPAD_F2) + #define EN_KEYPAD_F3 _BV(BTN_OFFSET + BLEN_KEYPAD_F3) + #define EN_KEYPAD_DOWN _BV(BTN_OFFSET + BLEN_KEYPAD_DOWN) + #define EN_KEYPAD_RIGHT _BV(BTN_OFFSET + BLEN_KEYPAD_RIGHT) + #define EN_KEYPAD_MIDDLE _BV(BTN_OFFSET + BLEN_KEYPAD_MIDDLE) + #define EN_KEYPAD_UP _BV(BTN_OFFSET + BLEN_KEYPAD_UP) + #define EN_KEYPAD_LEFT _BV(BTN_OFFSET + BLEN_KEYPAD_LEFT) + + #define RRK(B) (keypad_buttons & (B)) + + #ifdef EN_C + #define BUTTON_CLICK() ((buttons & EN_C) || RRK(EN_KEYPAD_MIDDLE)) + #else + #define BUTTON_CLICK() RRK(EN_KEYPAD_MIDDLE) + #endif +#endif + +#if EITHER(HAS_DIGITAL_BUTTONS, DWIN_CREALITY_LCD) + // Wheel spin pins where BA is 00, 10, 11, 01 (1 bit always changes) + #define BLEN_A 0 + #define BLEN_B 1 + + #define EN_A _BV(BLEN_A) + #define EN_B _BV(BLEN_B) + + #define _BUTTON_PRESSED(BN) !READ(BTN_##BN) + + #if BUTTON_EXISTS(ENC) || HAS_TOUCH_BUTTONS + #define BLEN_C 2 + #define EN_C _BV(BLEN_C) + #endif + + #if ENABLED(LCD_I2C_VIKI) + #include + #define B_I2C_BTN_OFFSET 3 // (the first three bit positions reserved for EN_A, EN_B, EN_C) + + // button and encoder bit positions within 'buttons' + #define B_LE (BUTTON_LEFT << B_I2C_BTN_OFFSET) // The remaining normalized buttons are all read via I2C + #define B_UP (BUTTON_UP << B_I2C_BTN_OFFSET) + #define B_MI (BUTTON_SELECT << B_I2C_BTN_OFFSET) + #define B_DW (BUTTON_DOWN << B_I2C_BTN_OFFSET) + #define B_RI (BUTTON_RIGHT << B_I2C_BTN_OFFSET) + + #if BUTTON_EXISTS(ENC) // The pause/stop/restart button is connected to BTN_ENC when used + #define B_ST (EN_C) // Map the pause/stop/resume button into its normalized functional name + #define BUTTON_CLICK() (buttons & (B_MI|B_RI|B_ST)) // Pause/stop also acts as click until a proper pause/stop is implemented. + #else + #define BUTTON_CLICK() (buttons & (B_MI|B_RI)) + #endif + + // I2C buttons take too long to read inside an interrupt context and so we read them during lcd_update + + #elif ENABLED(LCD_I2C_PANELOLU2) + #if !BUTTON_EXISTS(ENC) // Use I2C if not directly connected to a pin + #define B_I2C_BTN_OFFSET 3 // (the first three bit positions reserved for EN_A, EN_B, EN_C) + + #define B_MI (PANELOLU2_ENCODER_C << B_I2C_BTN_OFFSET) // requires LiquidTWI2 library v1.2.3 or later + + #define BUTTON_CLICK() (buttons & B_MI) + #endif + #endif +#else + #undef BUTTON_EXISTS + #define BUTTON_EXISTS(...) false + + // Dummy button, never pressed + #define _BUTTON_PRESSED(BN) false + + // Shift register bits correspond to buttons: + #define BL_LE 7 // Left + #define BL_UP 6 // Up + #define BL_MI 5 // Middle + #define BL_DW 4 // Down + #define BL_RI 3 // Right + #define BL_ST 2 // Red Button + #define B_LE _BV(BL_LE) + #define B_UP _BV(BL_UP) + #define B_MI _BV(BL_MI) + #define B_DW _BV(BL_DW) + #define B_RI _BV(BL_RI) + #define B_ST _BV(BL_ST) + + #ifndef BUTTON_CLICK + #define BUTTON_CLICK() (buttons & (B_MI|B_ST)) + #endif +#endif + +#ifndef EN_A + #define EN_A 0 +#endif +#ifndef EN_B + #define EN_B 0 +#endif +#ifndef EN_C + #define EN_C 0 +#endif +#if BUTTON_EXISTS(BACK) || EITHER(HAS_TOUCH_BUTTONS, IS_TFTGLCD_PANEL) + #define BLEN_D 3 + #define EN_D _BV(BLEN_D) +#else + #define EN_D 0 +#endif + +#define BUTTON_PRESSED(BN) (_BUTTON_PRESSED_##BN) + +#if BUTTON_EXISTS(EN1) + #define _BUTTON_PRESSED_EN1 _BUTTON_PRESSED(EN1) +#else + #define _BUTTON_PRESSED_EN1 false +#endif +#if BUTTON_EXISTS(EN2) + #define _BUTTON_PRESSED_EN2 _BUTTON_PRESSED(EN2) +#else + #define _BUTTON_PRESSED_EN2 false +#endif +#if BUTTON_EXISTS(ENC_EN) + #define _BUTTON_PRESSED_ENC_EN _BUTTON_PRESSED(ENC_EN) +#else + #define _BUTTON_PRESSED_ENC_EN false +#endif +#if BUTTON_EXISTS(ENC) + #define _BUTTON_PRESSED_ENC _BUTTON_PRESSED(ENC) +#else + #define _BUTTON_PRESSED_ENC false +#endif +#if BUTTON_EXISTS(UP) + #define _BUTTON_PRESSED_UP _BUTTON_PRESSED(UP) +#else + #define _BUTTON_PRESSED_UP false +#endif +#if BUTTON_EXISTS(DWN) + #define _BUTTON_PRESSED_DWN _BUTTON_PRESSED(DWN) +#else + #define _BUTTON_PRESSED_DWN false +#endif +#if BUTTON_EXISTS(LFT) + #define _BUTTON_PRESSED_LFT _BUTTON_PRESSED(LFT) +#else + #define _BUTTON_PRESSED_LFT false +#endif +#if BUTTON_EXISTS(RT) + #define _BUTTON_PRESSED_RT _BUTTON_PRESSED(RT) +#else + #define _BUTTON_PRESSED_RT false +#endif +#if BUTTON_EXISTS(BACK) + #define _BUTTON_PRESSED_BACK _BUTTON_PRESSED(BACK) +#else + #define _BUTTON_PRESSED_BACK false +#endif + +#ifndef BUTTON_CLICK + #if EN_C > 0 + #define BUTTON_CLICK() (buttons & EN_C) + #else + #define BUTTON_CLICK() false + #endif +#endif + +#if EN_D > 0 + #define LCD_BACK_CLICKED() (buttons & EN_D) +#else + #define LCD_BACK_CLICKED() false +#endif diff --git a/Marlin/src/lcd/dogm/HAL_LCD_class_defines.h b/Marlin/src/lcd/dogm/HAL_LCD_class_defines.h index 1511c6993323..28ca26134e16 100644 --- a/Marlin/src/lcd/dogm/HAL_LCD_class_defines.h +++ b/Marlin/src/lcd/dogm/HAL_LCD_class_defines.h @@ -30,12 +30,15 @@ extern u8g_dev_t u8g_dev_st7565_64128n_HAL_2x_hw_spi; class U8GLIB_64128N_2X_HAL : public U8GLIB { public: - U8GLIB_64128N_2X_HAL(pin_t sck, pin_t mosi, pin_t cs, pin_t a0, pin_t reset = U8G_PIN_NONE) - : U8GLIB(&u8g_dev_st7565_64128n_HAL_2x_sw_spi, (uint8_t)sck, (uint8_t)mosi, (uint8_t)cs, (uint8_t)a0, (uint8_t)reset) - { } - U8GLIB_64128N_2X_HAL(pin_t cs, pin_t a0, pin_t reset = U8G_PIN_NONE) - : U8GLIB(&u8g_dev_st7565_64128n_HAL_2x_hw_spi, (uint8_t)cs, (uint8_t)a0, (uint8_t)reset) - { } + 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::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) { + U8GLIB::init(&u8g_dev_st7565_64128n_HAL_2x_hw_spi, (uint8_t)cs, (uint8_t)a0, (uint8_t)reset); + } }; extern u8g_dev_t u8g_dev_st7920_128x64_HAL_4x_sw_spi; @@ -43,12 +46,15 @@ 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(pin_t sck, pin_t mosi, pin_t cs, pin_t reset = U8G_PIN_NONE) - : U8GLIB(&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 - { } - U8GLIB_ST7920_128X64_4X_HAL(pin_t cs, pin_t reset = U8G_PIN_NONE) - : U8GLIB(&u8g_dev_st7920_128x64_HAL_4x_hw_spi, (uint8_t)cs, U8G_PIN_NONE, (uint8_t)reset) // a0 = U8G_PIN_NONE - { } + 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::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) { + U8GLIB::init(&u8g_dev_st7920_128x64_HAL_4x_hw_spi, (uint8_t)cs, U8G_PIN_NONE, (uint8_t)reset); // a0 = U8G_PIN_NONE + } }; // @@ -59,27 +65,29 @@ extern u8g_dev_t u8g_dev_st7920_128x64_rrd_sw_spi; class U8GLIB_ST7920_128X64_RRD : public U8GLIB { public: - U8GLIB_ST7920_128X64_RRD(pin_t sck, pin_t mosi, pin_t cs, pin_t reset = U8G_PIN_NONE) - : U8GLIB(&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 - { } + 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::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 + } }; extern u8g_dev_t u8g_dev_sh1106_128x64_2x_i2c_2_wire; class U8GLIB_SH1106_128X64_2X_I2C_2_WIRE : public U8GLIB { public: - U8GLIB_SH1106_128X64_2X_I2C_2_WIRE(uint8_t options = U8G_I2C_OPT_NONE) - : U8GLIB(&u8g_dev_sh1106_128x64_2x_i2c_2_wire, options) - { } + U8GLIB_SH1106_128X64_2X_I2C_2_WIRE() : U8GLIB() { } + U8GLIB_SH1106_128X64_2X_I2C_2_WIRE(uint8_t options) { init(options); } + void init(uint8_t options = U8G_I2C_OPT_NONE) { U8GLIB::init(&u8g_dev_sh1106_128x64_2x_i2c_2_wire, options); } }; extern u8g_dev_t u8g_dev_ssd1306_128x64_2x_i2c_2_wire; class U8GLIB_SSD1306_128X64_2X_I2C_2_WIRE : public U8GLIB { public: - U8GLIB_SSD1306_128X64_2X_I2C_2_WIRE(uint8_t options = U8G_I2C_OPT_NONE) - : U8GLIB(&u8g_dev_ssd1306_128x64_2x_i2c_2_wire, options) - { } + U8GLIB_SSD1306_128X64_2X_I2C_2_WIRE() : U8GLIB() { } + U8GLIB_SSD1306_128X64_2X_I2C_2_WIRE(uint8_t options) { init(options); } + void init(uint8_t options = U8G_I2C_OPT_NONE) { U8GLIB::init(&u8g_dev_ssd1306_128x64_2x_i2c_2_wire, options); } }; // @@ -90,9 +98,9 @@ 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(uint8_t cs, uint8_t rs, uint8_t reset = U8G_PIN_NONE) - : U8GLIB(&u8g_dev_tft_320x240_upscale_from_128x64, cs, rs, reset) - { } + 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); } }; @@ -100,10 +108,29 @@ extern u8g_dev_t u8g_dev_uc1701_mini12864_HAL_2x_sw_spi, u8g_dev_uc1701_mini1286 class U8GLIB_MINI12864_2X_HAL : public U8GLIB { public: - U8GLIB_MINI12864_2X_HAL(uint8_t sck, uint8_t mosi, uint8_t cs, uint8_t a0, uint8_t reset = U8G_PIN_NONE) - : U8GLIB(&u8g_dev_uc1701_mini12864_HAL_2x_sw_spi, sck, mosi, cs, a0, reset) - { } - U8GLIB_MINI12864_2X_HAL(uint8_t cs, uint8_t a0, uint8_t reset = U8G_PIN_NONE) - : U8GLIB(&u8g_dev_uc1701_mini12864_HAL_2x_hw_spi, cs, a0, reset) - { } + 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::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) { + U8GLIB::init(&u8g_dev_uc1701_mini12864_HAL_2x_hw_spi, cs, a0, reset); + } +}; + +extern u8g_dev_t u8g_dev_ssd1309_sw_spi; +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::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) { + 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 da7d4f6f1ec0..a30dd4ca17f3 100644 --- a/Marlin/src/lcd/dogm/HAL_LCD_com_defines.h +++ b/Marlin/src/lcd/dogm/HAL_LCD_com_defines.h @@ -23,7 +23,7 @@ // Use this file to select the com driver for device drivers that are NOT in the U8G library -#include +#include #ifndef U8G_HAL_LINKS // Defined by LPC1768/9 environments in platform.ini @@ -52,7 +52,9 @@ #elif defined(ARDUINO_ARCH_STM32) + uint8_t u8g_com_std_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); uint8_t u8g_com_stm32duino_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); + #define U8G_COM_HAL_SW_SPI_FN u8g_com_std_sw_spi_fn #define U8G_COM_HAL_HW_SPI_FN u8g_com_stm32duino_hw_spi_fn #elif defined(__AVR__) @@ -95,6 +97,11 @@ #define U8G_COM_ST7920_HAL_HW_SPI u8g_com_HAL_LPC1768_ST7920_hw_spi_fn #define U8G_COM_SSD_I2C_HAL u8g_com_HAL_LPC1768_ssd_hw_i2c_fn +#elif defined(__PLAT_NATIVE_SIM__) + uint8_t u8g_com_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); + uint8_t u8g_com_ST7920_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); + #define U8G_COM_HAL_SW_SPI_FN u8g_com_sw_spi_fn + #define U8G_COM_ST7920_HAL_SW_SPI u8g_com_ST7920_sw_spi_fn #endif #ifndef U8G_COM_HAL_SW_SPI_FN @@ -112,7 +119,7 @@ #ifndef U8G_COM_SSD_I2C_HAL #define U8G_COM_SSD_I2C_HAL u8g_com_null_fn #endif -#if EITHER(FSMC_GRAPHICAL_TFT, SPI_GRAPHICAL_TFT) +#if HAS_FSMC_GRAPHICAL_TFT || HAS_SPI_GRAPHICAL_TFT uint8_t u8g_com_hal_tft_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); #define U8G_COM_HAL_TFT_FN u8g_com_hal_tft_fn #else diff --git a/Marlin/src/lcd/dogm/dogm_Bootscreen.h b/Marlin/src/lcd/dogm/dogm_Bootscreen.h index c9001119d9d4..42408614715e 100644 --- a/Marlin/src/lcd/dogm/dogm_Bootscreen.h +++ b/Marlin/src/lcd/dogm/dogm_Bootscreen.h @@ -32,8 +32,20 @@ #if ENABLED(SHOW_CUSTOM_BOOTSCREEN) + typedef struct { + const unsigned char *bitmap; + const unsigned short duration; + } boot_frame_t; + #include "../../../_Bootscreen.h" + #if ENABLED(CUSTOM_BOOTSCREEN_ANIMATED) && DISABLED(CUSTOM_BOOTSCREEN_ANIMATED_FRAME_TIME) && !defined(CUSTOM_BOOTSCREEN_FRAME_TIME) + #define CUSTOM_BOOTSCREEN_FRAME_TIME 500 // (ms) + #endif + + #ifndef CUSTOM_BOOTSCREEN_BMPWIDTH + #define CUSTOM_BOOTSCREEN_BMPWIDTH 128 + #endif #ifndef CUSTOM_BOOTSCREEN_BMP_BYTEWIDTH #define CUSTOM_BOOTSCREEN_BMP_BYTEWIDTH CEILING(CUSTOM_BOOTSCREEN_BMPWIDTH, 8) #endif @@ -41,6 +53,13 @@ #define CUSTOM_BOOTSCREEN_BMPHEIGHT (sizeof(custom_start_bmp) / (CUSTOM_BOOTSCREEN_BMP_BYTEWIDTH)) #endif + #ifndef CUSTOM_BOOTSCREEN_Y + #if ENABLED(CUSTOM_BOOTSCREEN_BOTTOM_JUSTIFY) + #define CUSTOM_BOOTSCREEN_Y (LCD_PIXEL_HEIGHT - (CUSTOM_BOOTSCREEN_BMPHEIGHT)) + #else + #define CUSTOM_BOOTSCREEN_Y ((LCD_PIXEL_HEIGHT - (CUSTOM_BOOTSCREEN_BMPHEIGHT)) / 2) + #endif + #endif #endif #if ENABLED(BOOT_MARLIN_LOGO_SMALL) diff --git a/Marlin/src/lcd/dogm/dogm_Statusscreen.h b/Marlin/src/lcd/dogm/dogm_Statusscreen.h index c6ad566cffaf..dfbf7b429111 100644 --- a/Marlin/src/lcd/dogm/dogm_Statusscreen.h +++ b/Marlin/src/lcd/dogm/dogm_Statusscreen.h @@ -29,7 +29,7 @@ */ #include "../../inc/MarlinConfig.h" -#include "ultralcd_DOGM.h" +#include "marlinui_DOGM.h" #define BW(N) ((N + 7) / 8) @@ -57,805 +57,84 @@ // Default Status Screen Heater or Hotends bitmaps // #if !STATUS_HEATERS_WIDTH && !STATUS_HOTEND1_WIDTH - #if ENABLED(STATUS_COMBINE_HEATERS) - - #undef STATUS_HOTEND_ANIM - #undef STATUS_BED_ANIM - #define STATUS_HEATERS_XSPACE 24 - - // - // Status Screen Combined Heater bitmaps - // - #if HAS_HEATED_BED && HOTENDS <= 4 - - #if HOTENDS == 0 - - #define STATUS_HEATERS_WIDTH 96 - - const unsigned char status_heaters_bmp[] PROGMEM = { - B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000100,B00010000,B01000000, - B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000010,B00001000,B00100000, - B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000010,B00001000,B00100000, - B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000100,B00010000,B01000000, - B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00001000,B00100000,B10000000, - B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00010000,B01000001,B00000000, - B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00010000,B01000001,B00000000, - B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00001000,B00100000,B10000000, - B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000100,B00010000,B01000000, - B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000, - B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00011111,B11111111,B11111000, - B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00011111,B11111111,B11111000 - }; - - #elif HOTENDS == 1 - - #define STATUS_HEATERS_WIDTH 96 - - const unsigned char status_heaters_bmp[] PROGMEM = { - B00011111,B11100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000100,B00010000,B01000000, - B00111111,B11110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000010,B00001000,B00100000, - B00111111,B11110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000010,B00001000,B00100000, - B00111111,B11110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000100,B00010000,B01000000, - B00011111,B11100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00001000,B00100000,B10000000, - B00011111,B11100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00010000,B01000001,B00000000, - B00111111,B11110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00010000,B01000001,B00000000, - B00111111,B11110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00001000,B00100000,B10000000, - B00111111,B11110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000100,B00010000,B01000000, - B00001111,B11000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000, - B00000111,B10000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00011111,B11111111,B11111000, - B00000011,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00011111,B11111111,B11111000 - }; - - #elif HOTENDS == 2 - - #define STATUS_HEATERS_WIDTH 96 - - const unsigned char status_heaters_bmp[] PROGMEM = { - B00011111,B11100000,B00000000,B00011111,B11100000,B00000000,B00000000,B00000000,B00000000,B00000100,B00010000,B01000000, - B00111110,B11110000,B00000000,B00111100,B11110000,B00000000,B00000000,B00000000,B00000000,B00000010,B00001000,B00100000, - B00111100,B11110000,B00000000,B00111011,B01110000,B00000000,B00000000,B00000000,B00000000,B00000010,B00001000,B00100000, - B00111010,B11110000,B00000000,B00111111,B01110000,B00000000,B00000000,B00000000,B00000000,B00000100,B00010000,B01000000, - B00011110,B11100000,B00000000,B00011110,B11100000,B00000000,B00000000,B00000000,B00000000,B00001000,B00100000,B10000000, - B00011110,B11100000,B00000000,B00011101,B11100000,B00000000,B00000000,B00000000,B00000000,B00010000,B01000001,B00000000, - B00111110,B11110000,B00000000,B00111011,B11110000,B00000000,B00000000,B00000000,B00000000,B00010000,B01000001,B00000000, - B00111110,B11110000,B00000000,B00111000,B01110000,B00000000,B00000000,B00000000,B00000000,B00001000,B00100000,B10000000, - B00111111,B11110000,B00000000,B00111111,B11110000,B00000000,B00000000,B00000000,B00000000,B00000100,B00010000,B01000000, - B00001111,B11000000,B00000000,B00001111,B11000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000, - B00000111,B10000000,B00000000,B00000111,B10000000,B00000000,B00000000,B00000000,B00000000,B00011111,B11111111,B11111000, - B00000011,B00000000,B00000000,B00000011,B00000000,B00000000,B00000000,B00000000,B00000000,B00011111,B11111111,B11111000 - }; - - #elif HOTENDS == 3 - - #define STATUS_HEATERS_WIDTH 96 - - const unsigned char status_heaters_bmp[] PROGMEM = { - B00011111,B11100000,B00000000,B00011111,B11100000,B00000000,B00011111,B11100000,B00000000,B00000100,B00010000,B01000000, - B00111110,B11110000,B00000000,B00111100,B11110000,B00000000,B00111100,B11110000,B00000000,B00000010,B00001000,B00100000, - B00111100,B11110000,B00000000,B00111011,B01110000,B00000000,B00111011,B01110000,B00000000,B00000010,B00001000,B00100000, - B00111010,B11110000,B00000000,B00111111,B01110000,B00000000,B00111111,B01110000,B00000000,B00000100,B00010000,B01000000, - B00011110,B11100000,B00000000,B00011110,B11100000,B00000000,B00011100,B11100000,B00000000,B00001000,B00100000,B10000000, - B00011110,B11100000,B00000000,B00011101,B11100000,B00000000,B00011111,B01100000,B00000000,B00010000,B01000001,B00000000, - B00111110,B11110000,B00000000,B00111011,B11110000,B00000000,B00111011,B01110000,B00000000,B00010000,B01000001,B00000000, - B00111110,B11110000,B00000000,B00111000,B01110000,B00000000,B00111100,B11110000,B00000000,B00001000,B00100000,B10000000, - B00111111,B11110000,B00000000,B00111111,B11110000,B00000000,B00111111,B11110000,B00000000,B00000100,B00010000,B01000000, - B00001111,B11000000,B00000000,B00001111,B11000000,B00000000,B00001111,B11000000,B00000000,B00000000,B00000000,B00000000, - B00000111,B10000000,B00000000,B00000111,B10000000,B00000000,B00000111,B10000000,B00000000,B00011111,B11111111,B11111000, - B00000011,B00000000,B00000000,B00000011,B00000000,B00000000,B00000011,B00000000,B00000000,B00011111,B11111111,B11111000 - }; - - #else // HOTENDS > 3 - - #define STATUS_HEATERS_WIDTH 120 - - const unsigned char status_heaters_bmp[] PROGMEM = { - B00011111,B11100000,B00000000,B00011111,B11100000,B00000000,B00011111,B11100000,B00000000,B00011111,B11100000,B00000000,B00000100,B00010000,B01000000, - B00111110,B11110000,B00000000,B00111100,B11110000,B00000000,B00111100,B11110000,B00000000,B00111011,B01110000,B00000000,B00000010,B00001000,B00100000, - B00111100,B11110000,B00000000,B00111011,B01110000,B00000000,B00111011,B01110000,B00000000,B00111011,B01110000,B00000000,B00000010,B00001000,B00100000, - B00111010,B11110000,B00000000,B00111111,B01110000,B00000000,B00111111,B01110000,B00000000,B00111011,B01110000,B00000000,B00000100,B00010000,B01000000, - B00011110,B11100000,B00000000,B00011110,B11100000,B00000000,B00011100,B11100000,B00000000,B00011011,B01100000,B00000000,B00001000,B00100000,B10000000, - B00011110,B11100000,B00000000,B00011101,B11100000,B00000000,B00011111,B01100000,B00000000,B00011000,B00100000,B00000000,B00010000,B01000001,B00000000, - B00111110,B11110000,B00000000,B00111011,B11110000,B00000000,B00111011,B01110000,B00000000,B00111111,B01110000,B00000000,B00010000,B01000001,B00000000, - B00111110,B11110000,B00000000,B00111000,B01110000,B00000000,B00111100,B11110000,B00000000,B00111111,B01110000,B00000000,B00001000,B00100000,B10000000, - B00111111,B11110000,B00000000,B00111111,B11110000,B00000000,B00111111,B11110000,B00000000,B00111111,B11110000,B00000000,B00000100,B00010000,B01000000, - B00001111,B11000000,B00000000,B00001111,B11000000,B00000000,B00001111,B11000000,B00000000,B00001111,B11000000,B00000000,B00000000,B00000000,B00000000, - B00000111,B10000000,B00000000,B00000111,B10000000,B00000000,B00000111,B10000000,B00000000,B00000111,B10000000,B00000000,B00011111,B11111111,B11111000, - B00000011,B00000000,B00000000,B00000011,B00000000,B00000000,B00000011,B00000000,B00000000,B00000011,B00000000,B00000000,B00011111,B11111111,B11111000 - }; - - #endif // HOTENDS - - #define STATUS_BED_TEXT_X (STATUS_HEATERS_WIDTH - 10) - - #else // !HAS_HEATED_BED || HOTENDS > 3 - - #if HOTENDS == 0 - - #define STATUS_HEATERS_WIDTH 0 - - #elif HOTENDS == 1 - - #define STATUS_HEATERS_WIDTH 12 - - const unsigned char status_heaters_bmp[] PROGMEM = { - B00011111,B11100000, - B00111111,B11110000, - B00111111,B11110000, - B00111111,B11110000, - B00011111,B11100000, - B00011111,B11100000, - B00111111,B11110000, - B00111111,B11110000, - B00111111,B11110000, - B00001111,B11000000, - B00000111,B10000000, - B00000011,B00000000 - }; - - #elif HOTENDS == 2 - - #define STATUS_HEATERS_WIDTH 36 - - const unsigned char status_heaters_bmp[] PROGMEM = { - B00011111,B11100000,B00000000,B00011111,B11100000, - B00111110,B11110000,B00000000,B00111100,B11110000, - B00111100,B11110000,B00000000,B00111011,B01110000, - B00111010,B11110000,B00000000,B00111111,B01110000, - B00011110,B11100000,B00000000,B00011110,B11100000, - B00011110,B11100000,B00000000,B00011101,B11100000, - B00111110,B11110000,B00000000,B00111011,B11110000, - B00111110,B11110000,B00000000,B00111000,B01110000, - B00111111,B11110000,B00000000,B00111111,B11110000, - B00001111,B11000000,B00000000,B00001111,B11000000, - B00000111,B10000000,B00000000,B00000111,B10000000, - B00000011,B00000000,B00000000,B00000011,B00000000 - }; - - #elif HOTENDS == 3 - - #define STATUS_HEATERS_WIDTH 60 - - const unsigned char status_heaters_bmp[] PROGMEM = { - B00011111,B11100000,B00000000,B00011111,B11100000,B00000000,B00011111,B11100000, - B00111110,B11110000,B00000000,B00111100,B11110000,B00000000,B00111100,B11110000, - B00111100,B11110000,B00000000,B00111011,B01110000,B00000000,B00111011,B01110000, - B00111010,B11110000,B00000000,B00111111,B01110000,B00000000,B00111111,B01110000, - B00011110,B11100000,B00000000,B00011110,B11100000,B00000000,B00011100,B11100000, - B00011110,B11100000,B00000000,B00011101,B11100000,B00000000,B00011111,B01100000, - B00111110,B11110000,B00000000,B00111011,B11110000,B00000000,B00111011,B01110000, - B00111110,B11110000,B00000000,B00111000,B01110000,B00000000,B00111100,B11110000, - B00111111,B11110000,B00000000,B00111111,B11110000,B00000000,B00111111,B11110000, - B00001111,B11000000,B00000000,B00001111,B11000000,B00000000,B00001111,B11000000, - B00000111,B10000000,B00000000,B00000111,B10000000,B00000000,B00000111,B10000000, - B00000011,B00000000,B00000000,B00000011,B00000000,B00000000,B00000011,B00000000 - }; - - #elif HOTENDS == 4 - - #define STATUS_HEATERS_WIDTH 84 - - const unsigned char status_heaters_bmp[] PROGMEM = { - B00011111,B11100000,B00000000,B00011111,B11100000,B00000000,B00011111,B11100000,B00000000,B00011111,B11100000, - B00111110,B11110000,B00000000,B00111100,B11110000,B00000000,B00111100,B11110000,B00000000,B00111011,B01110000, - B00111100,B11110000,B00000000,B00111011,B01110000,B00000000,B00111011,B01110000,B00000000,B00111011,B01110000, - B00111010,B11110000,B00000000,B00111111,B01110000,B00000000,B00111111,B01110000,B00000000,B00111011,B01110000, - B00011110,B11100000,B00000000,B00011110,B11100000,B00000000,B00011100,B11100000,B00000000,B00011011,B01100000, - B00011110,B11100000,B00000000,B00011101,B11100000,B00000000,B00011111,B01100000,B00000000,B00011000,B00100000, - B00111110,B11110000,B00000000,B00111011,B11110000,B00000000,B00111011,B01110000,B00000000,B00111111,B01110000, - B00111110,B11110000,B00000000,B00111000,B01110000,B00000000,B00111100,B11110000,B00000000,B00111111,B01110000, - B00111111,B11110000,B00000000,B00111111,B11110000,B00000000,B00111111,B11110000,B00000000,B00111111,B11110000, - B00001111,B11000000,B00000000,B00001111,B11000000,B00000000,B00001111,B11000000,B00000000,B00001111,B11000000, - B00000111,B10000000,B00000000,B00000111,B10000000,B00000000,B00000111,B10000000,B00000000,B00000111,B10000000, - B00000011,B00000000,B00000000,B00000011,B00000000,B00000000,B00000011,B00000000,B00000000,B00000011,B00000000 - }; - - #else // HOTENDS > 4 - - #define STATUS_HEATERS_WIDTH 108 - - const unsigned char status_heaters_bmp[] PROGMEM = { - B00011111,B11100000,B00000000,B00011111,B11100000,B00000000,B00011111,B11100000,B00000000,B00011111,B11100000,B00000000,B00011111,B11100000, - B00111110,B11110000,B00000000,B00111100,B11110000,B00000000,B00111100,B11110000,B00000000,B00111011,B01110000,B00000000,B00111000,B01110000, - B00111100,B11110000,B00000000,B00111011,B01110000,B00000000,B00111011,B01110000,B00000000,B00111011,B01110000,B00000000,B00111011,B11110000, - B00111010,B11110000,B00000000,B00111111,B01110000,B00000000,B00111111,B01110000,B00000000,B00111011,B01110000,B00000000,B00111000,B11110000, - B00011110,B11100000,B00000000,B00011110,B11100000,B00000000,B00011100,B11100000,B00000000,B00011011,B01100000,B00000000,B00011111,B01100000, - B00011110,B11100000,B00000000,B00011101,B11100000,B00000000,B00011111,B01100000,B00000000,B00011000,B00100000,B00000000,B00011111,B01100000, - B00111110,B11110000,B00000000,B00111011,B11110000,B00000000,B00111011,B01110000,B00000000,B00111111,B01110000,B00000000,B00111011,B01110000, - B00111110,B11110000,B00000000,B00111000,B01110000,B00000000,B00111100,B11110000,B00000000,B00111111,B01110000,B00000000,B00111100,B11110000, - B00111111,B11110000,B00000000,B00111111,B11110000,B00000000,B00111111,B11110000,B00000000,B00111111,B11110000,B00000000,B00111111,B11110000, - B00001111,B11000000,B00000000,B00001111,B11000000,B00000000,B00001111,B11000000,B00000000,B00001111,B11000000,B00000000,B00001111,B11000000, - B00000111,B10000000,B00000000,B00000111,B10000000,B00000000,B00000111,B10000000,B00000000,B00000111,B10000000,B00000000,B00000111,B10000000, - B00000011,B00000000,B00000000,B00000011,B00000000,B00000000,B00000011,B00000000,B00000000,B00000011,B00000000,B00000000,B00000011,B00000000 - }; - - #endif // HOTENDS - - #endif // !HAS_HEATED_BED || HOTENDS > 3 - - #else // !STATUS_COMBINE_HEATERS - - // - // Status Screen Hotends bitmaps - // + #include "status/combined.h" + #else #if HAS_HOTEND - - #define STATUS_HOTEND1_WIDTH 16 - - #define MAX_HOTEND_BITMAPS 5 - #if HOTENDS > MAX_HOTEND_BITMAPS - #define STATUS_HOTEND_BITMAPS MAX_HOTEND_BITMAPS - #else - #define STATUS_HOTEND_BITMAPS HOTENDS - #endif - - #if HOTENDS == 1 || ENABLED(STATUS_HOTEND_NUMBERLESS) - - const unsigned char status_hotend_a_bmp[] PROGMEM = { - B00011111,B11100000, - B00111111,B11110000, - B00111111,B11110000, - B00111111,B11110000, - B00011111,B11100000, - B00011111,B11100000, - B00111111,B11110000, - B00111111,B11110000, - B00111111,B11110000, - B00001111,B11000000, - B00000111,B10000000, - B00000011,B00000000 - }; - - #ifdef STATUS_HOTEND_ANIM - - const unsigned char status_hotend_b_bmp[] PROGMEM = { - B00011111,B11100000, - B00100000,B00010000, - B00100000,B00010000, - B00100000,B00010000, - B00010000,B00100000, - B00010000,B00100000, - B00100000,B00010000, - B00100000,B00010000, - B00110000,B00110000, - B00001000,B01000000, - B00000100,B10000000, - B00000011,B00000000 - }; - - #endif - - #elif HOTENDS >= 2 - - #ifdef STATUS_HOTEND_ANIM - - const unsigned char status_hotend1_a_bmp[] PROGMEM = { - B00011111,B11100000, - B00111111,B11110000, - B00111110,B11110000, - B00111100,B11110000, - B00011010,B11100000, - B00011110,B11100000, - B00111110,B11110000, - B00111110,B11110000, - B00111110,B11110000, - B00001111,B11000000, - B00000111,B10000000, - B00000011,B00000000 - }; - - const unsigned char status_hotend1_b_bmp[] PROGMEM = { - B00011111,B11100000, - B00100000,B00010000, - B00100001,B00010000, - B00100011,B00010000, - B00010101,B00100000, - B00010001,B00100000, - B00100001,B00010000, - B00100001,B00010000, - B00110001,B00110000, - B00001000,B01000000, - B00000100,B10000000, - B00000011,B00000000 - }; - - const unsigned char status_hotend2_a_bmp[] PROGMEM = { - B00011111,B11100000, - B00111111,B11110000, - B00111100,B11110000, - B00111011,B01110000, - B00011111,B01100000, - B00011110,B11100000, - B00111101,B11110000, - B00111011,B11110000, - B00111000,B01110000, - B00001111,B11000000, - B00000111,B10000000, - B00000011,B00000000 - }; - - const unsigned char status_hotend2_b_bmp[] PROGMEM = { - B00011111,B11100000, - B00100000,B00010000, - B00100011,B00010000, - B00100100,B10010000, - B00010000,B10100000, - B00010001,B00100000, - B00100010,B00010000, - B00100100,B00010000, - B00110111,B10110000, - B00001000,B01000000, - B00000100,B10000000, - B00000011,B00000000 - }; - - #else - - const unsigned char status_hotend1_a_bmp[] PROGMEM = { - B00011111,B11100000, - B00111110,B11110000, - B00111100,B11110000, - B00111010,B11110000, - B00011110,B11100000, - B00011110,B11100000, - B00111110,B11110000, - B00111110,B11110000, - B00111111,B11110000, - B00001111,B11000000, - B00000111,B10000000, - B00000011,B00000000 - }; - - const unsigned char status_hotend2_a_bmp[] PROGMEM = { - B00011111,B11100000, - B00111100,B11110000, - B00111011,B01110000, - B00111111,B01110000, - B00011110,B11100000, - B00011101,B11100000, - B00111011,B11110000, - B00111000,B01110000, - B00111111,B11110000, - B00001111,B11000000, - B00000111,B10000000, - B00000011,B00000000 - }; - - #endif - - #if STATUS_HOTEND_BITMAPS >= 3 - - #ifdef STATUS_HOTEND_ANIM - - const unsigned char status_hotend3_a_bmp[] PROGMEM = { - B00011111,B11100000, - B00111111,B11110000, - B00111100,B11110000, - B00111011,B01110000, - B00011111,B01100000, - B00011100,B11100000, - B00111111,B01110000, - B00111011,B01110000, - B00111100,B11110000, - B00001111,B11000000, - B00000111,B10000000, - B00000011,B00000000 - }; - - const unsigned char status_hotend3_b_bmp[] PROGMEM = { - B00011111,B11100000, - B00100000,B00010000, - B00100011,B00010000, - B00100100,B10010000, - B00010000,B10100000, - B00010011,B00100000, - B00100000,B10010000, - B00100100,B10010000, - B00110011,B00110000, - B00001000,B01000000, - B00000100,B10000000, - B00000011,B00000000 - }; - - #else - - const unsigned char status_hotend3_a_bmp[] PROGMEM = { - B00011111,B11100000, - B00111100,B11110000, - B00111011,B01110000, - B00111111,B01110000, - B00011100,B11100000, - B00011111,B01100000, - B00111011,B01110000, - B00111100,B11110000, - B00111111,B11110000, - B00001111,B11000000, - B00000111,B10000000, - B00000011,B00000000 - }; - - #endif - - #endif - - #if STATUS_HOTEND_BITMAPS >= 4 - - #ifdef STATUS_HOTEND_ANIM - - const unsigned char status_hotend4_a_bmp[] PROGMEM = { - B00011111,B11100000, - B00111111,B11110000, - B00111011,B01110000, - B00111011,B01110000, - B00011011,B01100000, - B00011011,B01100000, - B00111000,B00110000, - B00111111,B01110000, - B00111111,B01110000, - B00001111,B11000000, - B00000111,B10000000, - B00000011,B00000000 - }; - - const unsigned char status_hotend4_b_bmp[] PROGMEM = { - B00011111,B11100000, - B00100000,B00010000, - B00100100,B10010000, - B00100100,B10010000, - B00010100,B10100000, - B00010100,B10100000, - B00100111,B11010000, - B00100000,B10010000, - B00110000,B10110000, - B00001000,B01000000, - B00000100,B10000000, - B00000011,B00000000 - }; - - #else - - const unsigned char status_hotend4_a_bmp[] PROGMEM = { - B00011111,B11100000, - B00111011,B01110000, - B00111011,B01110000, - B00111011,B01110000, - B00011011,B01100000, - B00011000,B00100000, - B00111111,B01110000, - B00111111,B01110000, - B00111111,B11110000, - B00001111,B11000000, - B00000111,B10000000, - B00000011,B00000000 - }; - - #endif - - #endif - - #if STATUS_HOTEND_BITMAPS >= 5 - - #ifdef STATUS_HOTEND_ANIM - - const unsigned char status_hotend5_a_bmp[] PROGMEM = { - B00011111,B11100000, - B00111111,B11110000, - B00111000,B01110000, - B00111011,B11110000, - B00011000,B11100000, - B00011111,B01100000, - B00111111,B01110000, - B00111011,B01110000, - B00111100,B11110000, - B00001111,B11000000, - B00000111,B10000000, - B00000011,B00000000 - }; - - const unsigned char status_hotend5_b_bmp[] PROGMEM = { - B00011111,B11100000, - B00100000,B00010000, - B00100111,B10010000, - B00100100,B00010000, - B00010111,B00100000, - B00010000,B10100000, - B00100000,B10010000, - B00100100,B10010000, - B00110011,B00110000, - B00001000,B01000000, - B00000100,B10000000, - B00000011,B00000000 - }; - - #else - - const unsigned char status_hotend5_a_bmp[] PROGMEM = { - B00011111,B11100000, - B00111000,B01110000, - B00111011,B11110000, - B00111000,B11110000, - B00011111,B01100000, - B00011111,B01100000, - B00111011,B01110000, - B00111100,B11110000, - B00111111,B11110000, - B00001111,B11000000, - B00000111,B10000000, - B00000011,B00000000 - }; - - #endif - - #endif - - #endif - + #include "status/hotend.h" #else #define STATUS_HEATERS_HEIGHT 20 #endif - #endif +#endif -#endif // !STATUS_HEATERS_WIDTH && !STATUS_HOTEND1_WIDTH - -// LASER / SPINDLE +// +// Laser / Spindle +// #if !STATUS_CUTTER_WIDTH && HAS_CUTTER - #define STATUS_CUTTER_WIDTH 24 - #define STATUS_CUTTER_X 80 - #if ENABLED(LASER_FEATURE) - #ifdef STATUS_CUTTER_ANIM - const unsigned char status_cutter_on_bmp[] PROGMEM = { - B00000000,B00100100,B00000000, - B00000000,B01100110,B00000000, - B00000000,B11000011,B00000000, - B00000001,B10011001,B10000000, - B00000011,B00100100,B11000000, - B00000000,B01000010,B00000000, - B00000000,B01000010,B00000000, - B00000011,B00100100,B11000000, - B00000001,B10011001,B10000000, - B00000000,B11000011,B00000000, - B00000000,B01100110,B00000000, - B00000000,B00100100,B00000000 - }; - const unsigned char status_cutter_bmp[] PROGMEM = { - B00000000,B00100100,B00000000, - B00000000,B01100110,B00000000, - B00000000,B00000000,B00000000, - B00000001,B00000000,B10000000, - B00000011,B00000000,B11000000, - B00000000,B00011000,B00000000, - B00000000,B00011000,B00000000, - B00000011,B00000000,B11000000, - B00000001,B00000000,B10000000, - B00000000,B00000000,B00000000, - B00000000,B01100110,B00000000, - B00000000,B00100100,B00000000 - }; - #else - const unsigned char status_cutter_bmp[] PROGMEM = { - B00000000,B00100100,B00000000, - B00000000,B01100110,B00000000, - B00000000,B11000011,B00000000, - B00000001,B10000001,B10000000, - B00000011,B00000000,B11000000, - B00000000,B00000000,B00000000, - B00000000,B00000000,B00000000, - B00000011,B00000000,B11000000, - B00000001,B10000001,B10000000, - B00000000,B11000011,B00000000, - B00000000,B01100110,B00000000, - B00000000,B00100100,B00000000 - }; - #endif - #else - #ifdef STATUS_CUTTER_ANIM - const unsigned char status_cutter_on_bmp[] PROGMEM = { - B00000001,B11111110,B10000000, - B00000000,B11000000,B00000000, - B00000001,B10000000,B10000000, - B00000001,B00000000,B10000000, - B00000001,B11111100,B10000000, - B00000000,B11100000,B00000000, - B00000001,B11000000,B10000000, - B00000000,B10000001,B00000000, - B00000000,B01111010,B00000000, - B00000000,B00110100,B00000000, - B00000000,B00011000,B00000000, - B00000000,B00000000,B00000000 - }; - const unsigned char status_cutter_bmp[] PROGMEM = { - B00000001,B11111110,B10000000, - B00000000,B11000000,B00000000, - B00000001,B10000000,B10000000, - B00000001,B00000000,B10000000, - B00000001,B11111100,B10000000, - B00000000,B11100000,B00000000, - B00000001,B11000000,B10000000, - B00000000,B10000001,B00000000, - B00000000,B01111010,B00000000, - B00000000,B00110100,B00000000, - B00000000,B00011000,B00000000, - B00000000,B00000000,B00000000 - }; - #else - const unsigned char status_cutter_bmp[] PROGMEM = { - B00000001,B11000010,B10000000, - B00000001,B00011100,B10000000, - B00000000,B11100001,B00000000, - B00000001,B00001110,B10000000, - B00000001,B01110000,B10000000, - B00000000,B10000111,B10000000, - B00000001,B00111111,B10000000, - B00000000,B11111111,B00000000, - B00000000,B01111110,B00000000, - B00000000,B00111100,B00000000, - B00000000,B00011000,B00000000, - B00000000,B00000000,B00000000 - }; - #endif + #include "status/cutter.h" +#endif +#ifndef STATUS_CUTTER_WIDTH + #define STATUS_CUTTER_WIDTH 0 +#endif + #ifndef STATUS_CUTTER_BYTEWIDTH + #define STATUS_CUTTER_BYTEWIDTH BW(STATUS_CUTTER_WIDTH) #endif -#endif // LASER / SPINDLE // -// Default Status Screen Bed bitmaps +// Laser cooler // -#if !STATUS_BED_WIDTH && HAS_HEATED_BED && DISABLED(STATUS_COMBINE_HEATERS) - - #if ENABLED(STATUS_ALT_BED_BITMAP) - - #define STATUS_BED_ANIM - #define STATUS_BED_WIDTH 24 - #ifndef STATUS_BED_X - #define STATUS_BED_X (LCD_PIXEL_WIDTH - (STATUS_BED_BYTEWIDTH + STATUS_CHAMBER_BYTEWIDTH + STATUS_FAN_BYTEWIDTH) * 8) - #endif - #define STATUS_BED_TEXT_X (STATUS_BED_X + 11) - - const unsigned char status_bed_bmp[] PROGMEM = { - B11111111,B11111111,B11000000, - B01000000,B00000000,B00100000, - B00100000,B00000000,B00010000, - B00010000,B00000000,B00001000, - B00001000,B00000000,B00000100, - B00000100,B00000000,B00000010, - B00000011,B11111111,B11111111 - }; - - const unsigned char status_bed_on_bmp[] PROGMEM = { - B00000010,B00100010,B00000000, - B00000100,B01000100,B00000000, - B00000100,B01000100,B00000000, - B00000010,B00100010,B00000000, - B00000001,B00010001,B00000000, - B11111111,B11111111,B11000000, - B01000000,B10001000,B10100000, - B00100001,B00010001,B00010000, - B00010010,B00100010,B00001000, - B00001000,B00000000,B00000100, - B00000100,B00000000,B00000010, - B00000011,B11111111,B11111111 - }; - - #else - - #define STATUS_BED_WIDTH 21 - #ifndef STATUS_BED_X - #define STATUS_BED_X (LCD_PIXEL_WIDTH - (STATUS_BED_BYTEWIDTH + STATUS_CHAMBER_BYTEWIDTH + STATUS_FAN_BYTEWIDTH) * 8) - #endif - - #ifdef STATUS_BED_ANIM - - const unsigned char status_bed_bmp[] PROGMEM = { - B00011111,B11111111,B11111000, - B00011111,B11111111,B11111000 - }; - - const unsigned char status_bed_on_bmp[] PROGMEM = { - B00000100,B00010000,B01000000, - B00000010,B00001000,B00100000, - B00000010,B00001000,B00100000, - B00000100,B00010000,B01000000, - B00001000,B00100000,B10000000, - B00010000,B01000001,B00000000, - B00010000,B01000001,B00000000, - B00001000,B00100000,B10000000, - B00000100,B00010000,B01000000, - B00000000,B00000000,B00000000, - B00011111,B11111111,B11111000, - B00011111,B11111111,B11111000 - }; - - #else - - const unsigned char status_bed_bmp[] PROGMEM = { - B00000100,B00010000,B01000000, - B00000010,B00001000,B00100000, - B00000010,B00001000,B00100000, - B00000100,B00010000,B01000000, - B00001000,B00100000,B10000000, - B00010000,B01000001,B00000000, - B00010000,B01000001,B00000000, - B00001000,B00100000,B10000000, - B00000100,B00010000,B01000000, - B00000000,B00000000,B00000000, - B00011111,B11111111,B11111000, - B00011111,B11111111,B11111000 - }; +#if !STATUS_COOLER_WIDTH && HAS_COOLER + #include "status/cooler.h" +#endif +#ifndef STATUS_COOLER_WIDTH + #define STATUS_COOLER_WIDTH 0 +#endif +#ifndef STATUS_COOLER_BYTEWIDTH + #define STATUS_COOLER_BYTEWIDTH BW(STATUS_COOLER_WIDTH) +#endif - #endif +// +// Laser Flowmeter +// +#if !STATUS_FLOWMETER_WIDTH && ENABLED(LASER_COOLANT_FLOW_METER) + #include "status/cooler.h" +#endif +#ifndef STATUS_FLOWMETER_WIDTH + #define STATUS_FLOWMETER_WIDTH 0 +#endif +#ifndef STATUS_FLOWMETER_BYTEWIDTH + #define STATUS_FLOWMETER_BYTEWIDTH BW(STATUS_FLOWMETER_WIDTH) +#endif +// +// Laser Ammeter +// +#if ENABLED(I2C_AMMETER) + #if !STATUS_AMMETER_WIDTH + #include "status/ammeter.h" + #endif + #ifndef STATUS_AMMETER_WIDTH + #define STATUS_AMMETER_WIDTH 0 #endif #endif +// +// Bed +// +#if !STATUS_BED_WIDTH && HAS_HEATED_BED && DISABLED(STATUS_COMBINE_HEATERS) + #include "status/bed.h" +#endif #ifndef STATUS_BED_WIDTH #define STATUS_BED_WIDTH 0 #endif +// +// Chamber +// #if !STATUS_CHAMBER_WIDTH && HAS_TEMP_CHAMBER && ((HOTENDS <= 4 && !HAS_HEATED_BED) || (HOTENDS <= 3 && HAS_HEATED_BED)) - #define STATUS_CHAMBER_WIDTH 21 - #if STATUS_HEATERS_WIDTH - #if ENABLED(STATUS_COMBINE_HEATERS) - #define STATUS_CHAMBER_X (LCD_PIXEL_WIDTH - 2 - (STATUS_CHAMBER_BYTEWIDTH) * 8) - #elif HAS_FAN0 && HAS_HEATED_BED && HOTENDS <= 2 - #define STATUS_CHAMBER_X (LCD_PIXEL_WIDTH - 2 - (STATUS_HEATERS_BYTEWIDTH - STATUS_CHAMBER_BYTEWIDTH) * 8) - #elif HAS_FAN0 && !HAS_HEATED_BED - #define STATUS_CHAMBER_X (LCD_PIXEL_WIDTH - (STATUS_CHAMBER_BYTEWIDTH + STATUS_FAN_BYTEWIDTH) * 8) - #else - #define STATUS_CHAMBER_X (LCD_PIXEL_WIDTH - (STATUS_CHAMBER_BYTEWIDTH) * 8) - #endif - #endif - - #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 - }; - 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 - }; - - #else - - const unsigned char status_chamber_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 - }; - - #endif + #include "status/chamber.h" #endif - #ifndef STATUS_CHAMBER_WIDTH #define STATUS_CHAMBER_WIDTH 0 #endif @@ -881,427 +160,7 @@ // Provide default Fan Bitmaps // #if !STATUS_FAN_WIDTH && STATUS_FAN_FRAMES > 0 - - // Provide a fan animation if none exists - - #if STATUS_FAN_FRAMES <= 2 - - #define STATUS_FAN_Y 2 - #define STATUS_FAN_WIDTH 20 - - #if ENABLED(STATUS_ALT_FAN_BITMAP) - - const unsigned char status_fan0_bmp[] PROGMEM = { - B00000001,B11111110,B00000000, - B00000110,B00000001,B10000000, - B00001000,B11111100,B01000000, - B00010000,B11111100,B00100000, - B00010000,B01111000,B00100000, - B00100000,B00110000,B00010000, - B00101100,B00000000,B11010000, - B00101110,B00110001,B11010000, - B00101111,B01111011,B11010000, - B00101111,B01111011,B11010000, - B00101110,B00110001,B11010000, - B00101100,B00000000,B11010000, - B00100000,B00110000,B00010000, - B00010000,B01111000,B00100000, - B00010000,B11111100,B00100000, - B00001000,B11111100,B01000000, - B00000110,B00000001,B10000000, - B00000001,B11111110,B00000000 - }; - - #if STATUS_FAN_FRAMES == 2 - const unsigned char status_fan1_bmp[] PROGMEM = { - B00000001,B11111110,B00000000, - B00000110,B00000001,B10000000, - B00001001,B10000110,B01000000, - B00010011,B10000111,B00100000, - B00010111,B10000111,B10100000, - B00101111,B10000111,B11010000, - B00101111,B00000011,B11010000, - B00100000,B00110000,B00010000, - B00100000,B01111000,B00010000, - B00100000,B01111000,B00010000, - B00100000,B00110000,B00010000, - B00101111,B00000011,B11010000, - B00101111,B10000111,B11010000, - B00010111,B10000111,B10100000, - B00010011,B10000111,B00100000, - B00001001,B10000110,B01000000, - B00000110,B00000001,B10000000, - B00000001,B11111110,B00000000 - }; - #endif - - #else // !STATUS_ALT_FAN_BITMAP - - const unsigned char status_fan0_bmp[] PROGMEM = { - B00111111,B11111111,B11110000, - B00111000,B00000000,B01110000, - B00110000,B11111100,B00110000, - B00100000,B11111100,B00010000, - B00100000,B01111000,B00010000, - B00100000,B00110000,B00010000, - B00101100,B00000000,B11010000, - B00101110,B00110001,B11010000, - B00101111,B01111011,B11010000, - B00101111,B01111011,B11010000, - B00101110,B00110001,B11010000, - B00101100,B00000000,B11010000, - B00100000,B00110000,B00010000, - B00100000,B01111000,B00010000, - B00100000,B11111100,B00010000, - B00110000,B11111100,B00110000, - B00111000,B00000000,B01110000, - B00111111,B11111111,B11110000 - }; - - #if STATUS_FAN_FRAMES == 2 - const unsigned char status_fan1_bmp[] PROGMEM = { - B00111111,B11111111,B11110000, - B00111000,B00000000,B01110000, - B00110001,B10000110,B00110000, - B00100011,B10000111,B00010000, - B00100111,B10000111,B10010000, - B00101111,B10000111,B11010000, - B00101111,B00000011,B11010000, - B00100000,B00110000,B00010000, - B00100000,B01111000,B00010000, - B00100000,B01111000,B00010000, - B00100000,B00110000,B00010000, - B00101111,B00000011,B11010000, - B00101111,B10000111,B11010000, - B00100111,B10000111,B10010000, - B00100011,B10000111,B00010000, - B00110001,B10000110,B00110000, - B00111000,B00000000,B01110000, - B00111111,B11111111,B11110000 - }; - #endif - - #endif // !STATUS_ALT_FAN_BITMAP - - #elif STATUS_FAN_FRAMES == 3 - - #define STATUS_FAN_WIDTH 20 - - #if ENABLED(STATUS_ALT_FAN_BITMAP) - - const unsigned char status_fan0_bmp[] PROGMEM = { - B00000001,B11111111,B00000000, - B00000110,B00000000,B11000000, - B00001001,B00000001,B00100000, - B00010111,B10000011,B11010000, - B00010111,B10000011,B11010000, - B00101111,B11000111,B11101000, - B00100111,B11000111,B11001000, - B00100001,B11111111,B00001000, - B00100000,B01111100,B00001000, - B00100000,B01111100,B00001000, - B00100000,B01111100,B00001000, - B00100001,B11111111,B00001000, - B00100111,B11000111,B11001000, - B00101111,B11000111,B11101000, - B00010111,B10000011,B11010000, - B00010111,B10000011,B11010000, - B00001001,B00000001,B00100000, - B00000110,B00000000,B11000000, - B00000001,B11111111,B00000000 - }; - const unsigned char status_fan1_bmp[] PROGMEM = { - B00000001,B11111111,B00000000, - B00000110,B00110000,B11000000, - B00001001,B11110000,B00100000, - B00010001,B11110000,B00010000, - B00010000,B11110000,B00010000, - B00100000,B11110000,B01101000, - B00100000,B00110001,B11101000, - B00100000,B00111001,B11101000, - B00100000,B01111111,B11111000, - B00111111,B11111111,B11111000, - B00111111,B11111100,B00001000, - B00101111,B00111000,B00001000, - B00101110,B00011000,B00001000, - B00101100,B00011110,B00001000, - B00010000,B00011110,B00010000, - B00010000,B00011111,B00010000, - B00001000,B00011111,B00100000, - B00000110,B00011000,B11000000, - B00000001,B11111111,B00000000 - }; - const unsigned char status_fan2_bmp[] PROGMEM = { - B00000001,B11111111,B00000000, - B00000110,B00011000,B11000000, - B00001000,B00011111,B00100000, - B00010000,B00011111,B10010000, - B00010100,B00011111,B00010000, - B00101110,B00011110,B00001000, - B00101111,B00011100,B00001000, - B00101111,B10111000,B00001000, - B00111111,B11111100,B00001000, - B00111111,B11111111,B11111000, - B00100000,B01111111,B11111000, - B00100000,B00111011,B11101000, - B00100000,B01110001,B11101000, - B00100000,B11110000,B11101000, - B00010001,B11110000,B01010000, - B00010011,B11110000,B00010000, - B00001001,B11110000,B00100000, - B00000110,B00110000,B11000000, - B00000001,B11111111,B00000000 - }; - - #else // !STATUS_ALT_FAN_BITMAP - - const unsigned char status_fan0_bmp[] PROGMEM = { - B00111111,B11111111,B11111000, - B00111110,B00000000,B11111000, - B00111001,B00000001,B00111000, - B00110111,B10000011,B11011000, - B00110111,B10000011,B11011000, - B00101111,B11000111,B11101000, - B00100111,B11000111,B11001000, - B00100001,B11111111,B00001000, - B00100000,B01111100,B00001000, - B00100000,B01111100,B00001000, - B00100000,B01111100,B00001000, - B00100001,B11111111,B00001000, - B00100111,B11000111,B11001000, - B00101111,B11000111,B11101000, - B00110111,B10000011,B11011000, - B00110111,B10000011,B11011000, - B00111001,B00000001,B00111000, - B00111110,B00000000,B11111000, - B00111111,B11111111,B11111000 - }; - const unsigned char status_fan1_bmp[] PROGMEM = { - B00111111,B11111111,B11111000, - B00111110,B00110000,B11111000, - B00111001,B11110000,B00111000, - B00110001,B11110000,B00011000, - B00110000,B11110000,B00011000, - B00100000,B11110000,B01101000, - B00100000,B00110001,B11101000, - B00100000,B00111001,B11101000, - B00100000,B01111111,B11111000, - B00111111,B11111111,B11111000, - B00111111,B11111100,B00001000, - B00101111,B00111000,B00001000, - B00101110,B00011000,B00001000, - B00101100,B00011110,B00001000, - B00110000,B00011110,B00011000, - B00110000,B00011111,B00011000, - B00111000,B00011111,B00111000, - B00111110,B00011000,B11111000, - B00111111,B11111111,B11111000 - }; - const unsigned char status_fan2_bmp[] PROGMEM = { - B00111111,B11111111,B11111000, - B00111110,B00011000,B11111000, - B00111000,B00011111,B00111000, - B00110000,B00011111,B10011000, - B00110100,B00011111,B00011000, - B00101110,B00011110,B00001000, - B00101111,B00011100,B00001000, - B00101111,B10111000,B00001000, - B00111111,B11111100,B00001000, - B00111111,B11111111,B11111000, - B00100000,B01111111,B11111000, - B00100000,B00111011,B11101000, - B00100000,B01110001,B11101000, - B00100000,B11110000,B11101000, - B00110001,B11110000,B01011000, - B00110011,B11110000,B00011000, - B00111001,B11110000,B00111000, - B00111110,B00110000,B11111000, - B00111111,B11111111,B11111000 - }; - - #endif // !STATUS_ALT_FAN_BITMAP - - #elif STATUS_FAN_FRAMES == 4 - - #define STATUS_FAN_WIDTH 20 - - #if ENABLED(STATUS_ALT_FAN_BITMAP) - - const unsigned char status_fan0_bmp[] PROGMEM = { - B00000001,B11111111,B00000000, - B00000110,B00000000,B11000000, - B00001000,B00111111,B00100000, - B00010000,B01111110,B00010000, - B00010000,B01111100,B00010000, - B00101000,B01111100,B00001000, - B00101100,B00111000,B00001000, - B00101111,B00111001,B11001000, - B00101111,B11111111,B11101000, - B00101111,B11000111,B11101000, - B00101111,B11111111,B11101000, - B00100111,B00111001,B11101000, - B00100000,B00111000,B01101000, - B00100000,B01111100,B00101000, - B00010000,B01111100,B00010000, - B00010000,B11111100,B00010000, - B00001001,B11111000,B00100000, - B00000110,B00000000,B11000000, - B00000001,B11111111,B00000000 - }; - const unsigned char status_fan1_bmp[] PROGMEM = { - B00000001,B11111111,B00000000, - B00000110,B00000000,B11000000, - B00001000,B00001111,B00100000, - B00010100,B00011111,B11010000, - B00010110,B00011111,B10010000, - B00101111,B00011111,B00001000, - B00101111,B10011110,B00001000, - B00101111,B11111100,B00001000, - B00101111,B11011100,B00001000, - B00100111,B11101111,B11001000, - B00100000,B01110111,B11101000, - B00100000,B01111111,B11101000, - B00100000,B11110011,B11101000, - B00100001,B11110001,B11101000, - B00010011,B11110000,B11010000, - B00010111,B11110000,B01010000, - B00001001,B11100000,B00100000, - B00000110,B00000000,B11000000, - B00000001,B11111111,B00000000 - }; - const unsigned char status_fan2_bmp[] PROGMEM = { - B00000001,B11111111,B00000000, - B00000110,B10000000,B11000000, - B00001001,B10000000,B00100000, - B00010111,B10000001,B11010000, - B00010111,B11000011,B11010000, - B00100111,B11000111,B11101000, - B00100011,B11000111,B11111000, - B00100001,B11111111,B10001000, - B00100000,B01101100,B00001000, - B00100000,B01101100,B00001000, - B00100000,B01101100,B00001000, - B00100011,B11111111,B00001000, - B00111111,B11000111,B10001000, - B00101111,B11000111,B11001000, - B00010111,B10000111,B11010000, - B00010111,B00000011,B11010000, - B00001000,B00000011,B00100000, - B00000110,B00000010,B11000000, - B00000001,B11111111,B00000000 - }; - const unsigned char status_fan3_bmp[] PROGMEM = { - B00000001,B11111111,B00000000, - B00000110,B00000000,B11000000, - B00001001,B11110000,B00100000, - B00010001,B11100000,B00010000, - B00010001,B11100000,B00010000, - B00100001,B11100001,B11101000, - B00100000,B11110011,B11101000, - B00100000,B01111111,B11101000, - B00100000,B01110111,B11101000, - B00101000,B11101110,B00101000, - B00101111,B11011100,B00001000, - B00101111,B11111100,B00001000, - B00101111,B10011110,B00001000, - B00101111,B00001111,B00001000, - B00010000,B00001111,B00010000, - B00010000,B00001111,B00010000, - B00001000,B00011111,B00100000, - B00000110,B00000000,B11000000, - B00000001,B11111111,B00000000 - }; - - #else // !STATUS_ALT_FAN_BITMAP - - const unsigned char status_fan0_bmp[] PROGMEM = { - B00111111,B11111111,B11111000, - B00111110,B00000000,B11111000, - B00111000,B00111111,B00111000, - B00110000,B01111110,B00011000, - B00110000,B01111100,B00011000, - B00101000,B01111100,B00001000, - B00101100,B00111000,B00001000, - B00101111,B00111001,B11001000, - B00101111,B11111111,B11101000, - B00101111,B11000111,B11101000, - B00101111,B11111111,B11101000, - B00100111,B00111001,B11101000, - B00100000,B00111000,B01101000, - B00100000,B01111100,B00101000, - B00110000,B01111100,B00011000, - B00110000,B11111100,B00011000, - B00111001,B11111000,B00111000, - B00111110,B00000000,B11111000, - B00111111,B11111111,B11111000 - }; - const unsigned char status_fan1_bmp[] PROGMEM = { - B00111111,B11111111,B11111000, - B00111110,B00000000,B11111000, - B00111000,B00001111,B00111000, - B00110100,B00011111,B11011000, - B00110110,B00011111,B10011000, - B00101111,B00011111,B00001000, - B00101111,B10011110,B00001000, - B00101111,B11111100,B00001000, - B00101111,B11011100,B00001000, - B00100111,B11101111,B11001000, - B00100000,B01110111,B11101000, - B00100000,B01111111,B11101000, - B00100000,B11110011,B11101000, - B00100001,B11110001,B11101000, - B00110011,B11110000,B11011000, - B00110111,B11110000,B01011000, - B00111001,B11100000,B00111000, - B00111110,B00000000,B11111000, - B00111111,B11111111,B11111000 - }; - const unsigned char status_fan2_bmp[] PROGMEM = { - B00111111,B11111111,B11111000, - B00111110,B10000000,B11111000, - B00111001,B10000000,B00111000, - B00110111,B10000001,B11011000, - B00110111,B11000011,B11011000, - B00100111,B11000111,B11101000, - B00100011,B11000111,B11111000, - B00100001,B11111111,B10001000, - B00100000,B01101100,B00001000, - B00100000,B01101100,B00001000, - B00100000,B01101100,B00001000, - B00100011,B11111111,B00001000, - B00111111,B11000111,B10001000, - B00101111,B11000111,B11001000, - B00110111,B10000111,B11011000, - B00110111,B00000011,B11011000, - B00111000,B00000011,B00111000, - B00111110,B00000010,B11111000, - B00111111,B11111111,B11111000 - }; - const unsigned char status_fan3_bmp[] PROGMEM = { - B00111111,B11111111,B11111000, - B00111110,B00000000,B11111000, - B00111001,B11110000,B00111000, - B00110001,B11100000,B00011000, - B00110001,B11100000,B00011000, - B00100001,B11100001,B11101000, - B00100000,B11110011,B11101000, - B00100000,B01111111,B11101000, - B00100000,B01110111,B11101000, - B00101000,B11101110,B00101000, - B00101111,B11011100,B00001000, - B00101111,B11111100,B00001000, - B00101111,B10011110,B00001000, - B00101111,B00001111,B00001000, - B00110000,B00001111,B00011000, - B00110000,B00001111,B00011000, - B00111000,B00011111,B00111000, - B00111110,B00000000,B11111000, - B00111111,B11111111,B11111000 - }; - - #endif // !STATUS_ALT_FAN_BITMAP - - #endif + #include "status/fan.h" #else #undef STATUS_FAN_FRAMES #define STATUS_FAN_WIDTH 0 @@ -1325,7 +184,6 @@ #endif #if ENABLED(CUSTOM_STATUS_SCREEN_IMAGE) - // // Disable the logo bitmap if insufficient space // @@ -1341,7 +199,7 @@ #undef STATUS_LOGO_WIDTH #endif - #if !defined(STATUS_HEATERS_X) && ((HAS_MULTI_HOTEND && STATUS_LOGO_WIDTH && BED_OR_CHAMBER_OR_FAN) || (HOTENDS >= 3 && !BED_OR_CHAMBER_OR_FAN)) + #if !defined(STATUS_HEATERS_X) && ((HAS_HOTEND && STATUS_LOGO_WIDTH && BED_OR_CHAMBER_OR_FAN) || (HOTENDS >= 3 && !BED_OR_CHAMBER_OR_FAN)) #define _STATUS_HEATERS_X(H,S,N) ((LCD_PIXEL_WIDTH - (H * (S + N)) - (_EXTRA_WIDTH) + (STATUS_LOGO_WIDTH)) / 2) #if STATUS_HOTEND1_WIDTH #if HOTENDS > 2 @@ -1353,7 +211,6 @@ #define STATUS_HEATERS_X _STATUS_HEATERS_X(1, STATUS_HEATERS_WIDTH, 4) #endif #endif - #endif // @@ -1367,14 +224,18 @@ #endif #if STATUS_LOGO_WIDTH #ifndef STATUS_LOGO_X - #define STATUS_LOGO_X 0 - #endif - #ifndef STATUS_LOGO_Y - #define STATUS_LOGO_Y _MIN(0U, (20 - (STATUS_LOGO_HEIGHT)) / 2) + #ifdef STATUS_HEATERS_X + #define STATUS_LOGO_X ((STATUS_HEATERS_X - (STATUS_LOGO_WIDTH) - 1) / 2) + #else + #define STATUS_LOGO_X 0 + #endif #endif #ifndef STATUS_LOGO_HEIGHT #define STATUS_LOGO_HEIGHT (sizeof(status_logo_bmp) / (STATUS_LOGO_BYTEWIDTH)) #endif + #ifndef STATUS_LOGO_Y + #define STATUS_LOGO_Y _MAX(0U, (28U - _MIN(28U, STATUS_LOGO_HEIGHT)) / 2U) + #endif static_assert( sizeof(status_logo_bmp) == (STATUS_LOGO_BYTEWIDTH) * (STATUS_LOGO_HEIGHT), "Status logo bitmap (status_logo_bmp) dimensions don't match data." @@ -1430,7 +291,9 @@ #define STATUS_HOTEND8_WIDTH STATUS_HOTEND7_WIDTH #endif - constexpr uint8_t status_hotend_width[HOTENDS] = ARRAY_N(HOTENDS, STATUS_HOTEND1_WIDTH, STATUS_HOTEND2_WIDTH, STATUS_HOTEND3_WIDTH, STATUS_HOTEND4_WIDTH, STATUS_HOTEND5_WIDTH, STATUS_HOTEND6_WIDTH, STATUS_HOTEND7_WIDTH, STATUS_HOTEND8_WIDTH); + #define _SHNAME(N,T) STATUS_HOTEND##N##_##T, + + constexpr uint8_t status_hotend_width[HOTENDS] = { REPEAT2_S(1, INCREMENT(HOTENDS), _SHNAME, WIDTH) }; #define STATUS_HOTEND_WIDTH(N) status_hotend_width[N] #ifndef STATUS_HOTEND1_BYTEWIDTH @@ -1458,7 +321,7 @@ #define STATUS_HOTEND8_BYTEWIDTH BW(STATUS_HOTEND8_WIDTH) #endif - constexpr uint8_t status_hotend_bytewidth[HOTENDS] = ARRAY_N(HOTENDS, STATUS_HOTEND1_BYTEWIDTH, STATUS_HOTEND2_BYTEWIDTH, STATUS_HOTEND3_BYTEWIDTH, STATUS_HOTEND4_BYTEWIDTH, STATUS_HOTEND5_BYTEWIDTH, STATUS_HOTEND6_BYTEWIDTH, STATUS_HOTEND7_BYTEWIDTH, STATUS_HOTEND8_BYTEWIDTH); + constexpr uint8_t status_hotend_bytewidth[HOTENDS] = { REPEAT2_S(1, INCREMENT(HOTENDS), _SHNAME, BYTEWIDTH) }; #define STATUS_HOTEND_BYTEWIDTH(N) status_hotend_bytewidth[N] #ifndef STATUS_HOTEND1_X @@ -1488,7 +351,7 @@ #define STATUS_HOTEND8_X STATUS_HOTEND7_X + STATUS_HEATERS_XSPACE #endif - constexpr uint8_t status_hotend_x[HOTENDS] = ARRAY_N(HOTENDS, STATUS_HOTEND1_X, STATUS_HOTEND2_X, STATUS_HOTEND3_X, STATUS_HOTEND4_X, STATUS_HOTEND5_X, STATUS_HOTEND6_X, STATUS_HOTEND7_X, STATUS_HOTEND8_X); + constexpr uint8_t status_hotend_x[HOTENDS] = { REPEAT2_S(1, INCREMENT(HOTENDS), _SHNAME, X) }; #define STATUS_HOTEND_X(N) status_hotend_x[N] #elif HAS_MULTI_HOTEND #define STATUS_HOTEND_X(N) ((N) ? STATUS_HOTEND2_X : STATUS_HOTEND1_X) @@ -1519,13 +382,15 @@ #ifndef STATUS_HOTEND8_TEXT_X #define STATUS_HOTEND8_TEXT_X STATUS_HOTEND7_TEXT_X + STATUS_HEATERS_XSPACE #endif - constexpr uint8_t status_hotend_text_x[] = ARRAY_N(HOTENDS, STATUS_HOTEND1_TEXT_X, STATUS_HOTEND2_TEXT_X, STATUS_HOTEND3_TEXT_X, STATUS_HOTEND4_TEXT_X, STATUS_HOTEND5_TEXT_X, STATUS_HOTEND6_TEXT_X, STATUS_HOTEND7_TEXT_X, STATUS_HOTEND8_TEXT_X); + constexpr uint8_t status_hotend_text_x[HOTENDS] = { REPEAT2_S(1, INCREMENT(HOTENDS), _SHNAME, TEXT_X) }; #define STATUS_HOTEND_TEXT_X(N) status_hotend_text_x[N] #else #define STATUS_HOTEND_TEXT_X(N) (STATUS_HOTEND1_X + 6 + (N) * (STATUS_HEATERS_XSPACE)) #endif #endif + #undef _SHNAME + #if STATUS_HOTEND_BITMAPS > 1 && DISABLED(STATUS_HOTEND_NUMBERLESS) #define TEST_BITMAP_OFF status_hotend1_a_bmp #define TEST_BITMAP_ON status_hotend1_b_bmp @@ -1595,46 +460,45 @@ // // Cutter Bitmap Properties // -#ifndef STATUS_CUTTER_BYTEWIDTH - #define STATUS_CUTTER_BYTEWIDTH BW(STATUS_CUTTER_WIDTH) -#endif -#if STATUS_CUTTER_WIDTH +#if HAS_CUTTER + #if STATUS_CUTTER_WIDTH - #ifndef STATUS_CUTTER_X - #define STATUS_CUTTER_X (LCD_PIXEL_WIDTH - (STATUS_CUTTER_BYTEWIDTH + STATUS_CUTTER_BYTEWIDTH) * 8) - #endif + #ifndef STATUS_CUTTER_X + #define STATUS_CUTTER_X (LCD_PIXEL_WIDTH - (STATUS_CUTTER_BYTEWIDTH + STATUS_CUTTER_BYTEWIDTH) * 8) + #endif - #ifndef STATUS_CUTTER_HEIGHT - #ifdef STATUS_CUTTER_ANIM - #define STATUS_CUTTER_HEIGHT(S) ((S) ? sizeof(status_cutter_on_bmp) / (STATUS_CUTTER_BYTEWIDTH) : sizeof(status_cutter_bmp) / (STATUS_CUTTER_BYTEWIDTH)) - #else - #define STATUS_CUTTER_HEIGHT(S) (sizeof(status_cutter_bmp) / (STATUS_CUTTER_BYTEWIDTH)) + #ifndef STATUS_CUTTER_HEIGHT + #ifdef STATUS_CUTTER_ANIM + #define STATUS_CUTTER_HEIGHT(S) ((S) ? sizeof(status_cutter_on_bmp) / (STATUS_CUTTER_BYTEWIDTH) : sizeof(status_cutter_bmp) / (STATUS_CUTTER_BYTEWIDTH)) + #else + #define STATUS_CUTTER_HEIGHT(S) (sizeof(status_cutter_bmp) / (STATUS_CUTTER_BYTEWIDTH)) + #endif #endif - #endif - #ifndef STATUS_CUTTER_Y - #define STATUS_CUTTER_Y(S) 4 - #endif + #ifndef STATUS_CUTTER_Y + #define STATUS_CUTTER_Y(S) 4 + #endif - #ifndef STATUS_CUTTER_TEXT_X - #define STATUS_CUTTER_TEXT_X (STATUS_CUTTER_X -1) - #endif + #ifndef STATUS_CUTTER_TEXT_X + #define STATUS_CUTTER_TEXT_X (STATUS_CUTTER_X -1) + #endif - #ifndef STATUS_CUTTER_TEXT_Y - #define STATUS_CUTTER_TEXT_Y 28 - #endif + #ifndef STATUS_CUTTER_TEXT_Y + #define STATUS_CUTTER_TEXT_Y 28 + #endif - static_assert( - sizeof(status_cutter_bmp) == (STATUS_CUTTER_BYTEWIDTH) * (STATUS_CUTTER_HEIGHT(0)), - "Status cutter bitmap (status_cutter_bmp) dimensions don't match data." - ); - #ifdef STATUS_CUTTER_ANIM static_assert( - sizeof(status_cutter_on_bmp) == (STATUS_CUTTER_BYTEWIDTH) * (STATUS_CUTTER_HEIGHT(1)), - "Status cutter bitmap (status_cutter_on_bmp) dimensions don't match data." + sizeof(status_cutter_bmp) == (STATUS_CUTTER_BYTEWIDTH) * (STATUS_CUTTER_HEIGHT(0)), + "Status cutter bitmap (status_cutter_bmp) dimensions don't match data." ); - #endif + #ifdef STATUS_CUTTER_ANIM + static_assert( + sizeof(status_cutter_on_bmp) == (STATUS_CUTTER_BYTEWIDTH) * (STATUS_CUTTER_HEIGHT(1)), + "Status cutter bitmap (status_cutter_on_bmp) dimensions don't match data." + ); + #endif + #endif #endif // @@ -1678,6 +542,102 @@ #endif +// +// Cooler Bitmap Properties +// +#if HAS_COOLER + #if STATUS_COOLER_WIDTH + + #ifndef STATUS_COOLER_X + #define STATUS_COOLER_X (LCD_PIXEL_WIDTH - (STATUS_COOLER_BYTEWIDTH + STATUS_FAN_BYTEWIDTH + STATUS_CUTTER_BYTEWIDTH) * 8) + #endif + + #ifndef STATUS_COOLER_HEIGHT + #define STATUS_COOLER_HEIGHT(S) (sizeof(status_cooler_bmp1) / (STATUS_COOLER_BYTEWIDTH)) + #endif + + #ifndef STATUS_COOLER_Y + #define STATUS_COOLER_Y(S) (18 - STATUS_COOLER_HEIGHT(S)) + #endif + + #ifndef STATUS_COOLER_TEXT_X + #define STATUS_COOLER_TEXT_X (STATUS_COOLER_X + 12) + #endif + + static_assert( + sizeof(status_cooler_bmp1) == (STATUS_COOLER_BYTEWIDTH) * (STATUS_COOLER_HEIGHT(0)), + "Status cooler bitmap (status_cooler_bmp1) dimensions don't match data." + ); + #ifdef STATUS_COOLER_ANIM + static_assert( + sizeof(status_cooler_bmp2) == (STATUS_COOLER_BYTEWIDTH) * (STATUS_COOLER_HEIGHT(1)), + "Status cooler bitmap (status_cooler_bmp2) dimensions don't match data." + ); + #endif + + #endif +#endif + +// +// Flowmeter Bitmap Properties +// +#if ENABLED(LASER_COOLANT_FLOW_METER) + #if STATUS_FLOWMETER_WIDTH + + #ifndef STATUS_FLOWMETER_X + #define STATUS_FLOWMETER_X (LCD_PIXEL_WIDTH - (STATUS_FLOWMETER_BYTEWIDTH + STATUS_FAN_BYTEWIDTH + STATUS_CUTTER_BYTEWIDTH + STATUS_COOLER_BYTEWIDTH) * 8) + #endif + + #ifndef STATUS_FLOWMETER_HEIGHT + #define STATUS_FLOWMETER_HEIGHT(S) (sizeof(status_flowmeter_bmp1) / (STATUS_FLOWMETER_BYTEWIDTH)) + #endif + + #ifndef STATUS_FLOWMETER_Y + #define STATUS_FLOWMETER_Y(S) (20 - STATUS_FLOWMETER_HEIGHT(S)) + #endif + + #ifndef STATUS_FLOWMETER_TEXT_X + #define STATUS_FLOWMETER_TEXT_X (STATUS_FLOWMETER_X + 12) + #endif + + static_assert( + sizeof(status_flowmeter_bmp1) == (STATUS_FLOWMETER_BYTEWIDTH) * STATUS_FLOWMETER_HEIGHT(0), + "Status flowmeter bitmap (status_flowmeter_bmp1) dimensions don't match data." + ); + #ifdef STATUS_COOLER_ANIM + static_assert( + sizeof(status_flowmeter_bmp2) == (STATUS_FLOWMETER_BYTEWIDTH) * STATUS_FLOWMETER_HEIGHT(1), + "Status flowmeter bitmap (status_flowmeter_bmp2) dimensions don't match data." + ); + #endif + #endif +#endif + +// +// I2C Laser Ammeter +// +#if ENABLED(I2C_AMMETER) && STATUS_AMMETER_WIDTH + #ifndef STATUS_AMMETER_BYTEWIDTH + #define STATUS_AMMETER_BYTEWIDTH BW(STATUS_AMMETER_WIDTH) + #endif + #ifndef STATUS_AMMETER_X + #define STATUS_AMMETER_X (LCD_PIXEL_WIDTH - (STATUS_AMMETER_BYTEWIDTH + STATUS_FLOWMETER_BYTEWIDTH + STATUS_FAN_BYTEWIDTH + STATUS_CUTTER_BYTEWIDTH + STATUS_COOLER_BYTEWIDTH) * 8) + #endif + #ifndef STATUS_AMMETER_HEIGHT + #define STATUS_AMMETER_HEIGHT(S) (sizeof(status_ammeter_bmp_mA) / (STATUS_AMMETER_BYTEWIDTH)) + #endif + #ifndef STATUS_AMMETER_Y + #define STATUS_AMMETER_Y(S) (18 - STATUS_AMMETER_HEIGHT(S)) + #endif + #ifndef STATUS_AMMETER_TEXT_X + #define STATUS_AMMETER_TEXT_X (STATUS_AMMETER_X + 7) + #endif + static_assert( + sizeof(status_ammeter_bmp_mA) == (STATUS_AMMETER_BYTEWIDTH) * STATUS_AMMETER_HEIGHT(0), + "Status ammeter bitmap (status_ammeter_bmp_mA) dimensions don't match data." + ); +#endif + // // Bed Bitmap Properties // @@ -1765,6 +725,16 @@ #if HAS_CUTTER && !DO_DRAW_BED #define DO_DRAW_CUTTER 1 #endif +#if HAS_COOLER + #define DO_DRAW_COOLER 1 +#endif +#if ENABLED(LASER_COOLANT_FLOW_METER) + #define DO_DRAW_FLOWMETER 1 +#endif +#if ENABLED(I2C_AMMETER) + #define DO_DRAW_AMMETER 1 +#endif + #if HAS_TEMP_CHAMBER && STATUS_CHAMBER_WIDTH && HOTENDS <= 4 #define DO_DRAW_CHAMBER 1 #endif @@ -1783,6 +753,12 @@ #if BOTH(DO_DRAW_CUTTER, STATUS_CUTTER_ANIM) #define ANIM_CUTTER 1 #endif +#if BOTH(DO_DRAW_COOLER, STATUS_COOLER_ANIM) + #define ANIM_COOLER 1 +#endif +#if BOTH(DO_DRAW_FLOWMETER, STATUS_FLOWMETER_ANIM) + #define ANIM_FLOWMETER 1 +#endif #if ANIM_HOTEND || ANIM_BED || ANIM_CHAMBER || ANIM_CUTTER #define ANIM_HBCC 1 #endif diff --git a/Marlin/src/lcd/dogm/fontdata/fontdata_6x9_marlin.h b/Marlin/src/lcd/dogm/fontdata/fontdata_6x9_marlin.h index cd9cb3cdc968..524ff18778dc 100644 --- a/Marlin/src/lcd/dogm/fontdata/fontdata_6x9_marlin.h +++ b/Marlin/src/lcd/dogm/fontdata/fontdata_6x9_marlin.h @@ -32,7 +32,7 @@ X Font ascent = 6 descent=-2 Max Font ascent = 7 descent=-2 */ -#include +#include const u8g_fntpgm_uint8_t u8g_font_6x9[2434] U8G_FONT_SECTION(".progmem.u8g_font_6x9") = { 0x00,0x06,0x09,0x00,0xFE,0x06,0x02,0x0F,0x03,0x84,0x01,0xFF,0xFE,0x07,0xFE,0x06, 0xFE,0x05,0x07,0x07,0x00,0x00,0x00,0x40,0xF0,0xC8,0x88,0x98,0x78,0x10,0x05,0x07, diff --git a/Marlin/src/lcd/dogm/fontdata/fontdata_ISO10646_1.h b/Marlin/src/lcd/dogm/fontdata/fontdata_ISO10646_1.h index b4b615da4d0f..0a7ece860177 100644 --- a/Marlin/src/lcd/dogm/fontdata/fontdata_ISO10646_1.h +++ b/Marlin/src/lcd/dogm/fontdata/fontdata_ISO10646_1.h @@ -16,7 +16,7 @@ * along with this program. If not, see . * */ -#include +#include #if defined(__AVR__) && ENABLED(NOT_EXTENDED_ISO10646_1_5X7) // reduced font (only symbols 1 - 127) - saves about 1278 bytes of FLASH diff --git a/Marlin/src/lcd/dogm/fontdata/langdata.h b/Marlin/src/lcd/dogm/fontdata/langdata.h new file mode 100644 index 000000000000..746a3bd0b451 --- /dev/null +++ b/Marlin/src/lcd/dogm/fontdata/langdata.h @@ -0,0 +1,23 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include + +#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_an.h b/Marlin/src/lcd/dogm/fontdata/langdata_an.h index ffda82764fa2..fb0fdcf893f5 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_an.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_an.h @@ -3,7 +3,8 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; +#include "langdata.h" + +static const uxg_fontinfo_t g_fontinfo_an[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_bg.h b/Marlin/src/lcd/dogm/fontdata/langdata_bg.h index c506f879335b..20cd7b9ed74d 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_bg.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_bg.h @@ -3,7 +3,9 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once + +#include "langdata.h" const u8g_fntpgm_uint8_t fontpage_8_144_149[96] U8G_FONT_SECTION("fontpage_8_144_149") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x90,0x95,0x00,0x07,0xFF,0x00, @@ -64,14 +66,13 @@ const u8g_fntpgm_uint8_t fontpage_8_206_207[39] U8G_FONT_SECTION("fontpage_8_206 0x00,0x05,0x05,0x05,0x06,0x00,0x00,0x90,0xA8,0xE8,0xA8,0x90,0x04,0x05,0x05,0x06, 0x01,0x00,0x70,0x90,0x70,0x50,0x90}; -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(8, 144, 149, fontpage_8_144_149), // 'А' -- 'Е' - FONTDATA_ITEM(8, 151, 152, fontpage_8_151_152), // 'З' -- 'И' - FONTDATA_ITEM(8, 154, 164, fontpage_8_154_164), // 'К' -- 'Ф' - FONTDATA_ITEM(8, 166, 166, fontpage_8_166_166), // 'Ц' -- 'Ц' - FONTDATA_ITEM(8, 175, 195, fontpage_8_175_195), // 'Я' -- 'у' - FONTDATA_ITEM(8, 197, 200, fontpage_8_197_200), // 'х' -- 'ш' - FONTDATA_ITEM(8, 202, 202, fontpage_8_202_202), // 'ъ' -- 'ъ' - FONTDATA_ITEM(8, 206, 207, fontpage_8_206_207), // 'ю' -- 'я' +static const uxg_fontinfo_t g_fontinfo_bg[] PROGMEM = { + FONTDATA_ITEM(8, 144, 149, fontpage_8_144_149), // 'А' -- 'Е' + FONTDATA_ITEM(8, 151, 152, fontpage_8_151_152), // 'З' -- 'И' + FONTDATA_ITEM(8, 154, 164, fontpage_8_154_164), // 'К' -- 'Ф' + FONTDATA_ITEM(8, 166, 166, fontpage_8_166_166), // 'Ц' -- 'Ц' + FONTDATA_ITEM(8, 175, 195, fontpage_8_175_195), // 'Я' -- 'у' + FONTDATA_ITEM(8, 197, 200, fontpage_8_197_200), // 'х' -- 'ш' + FONTDATA_ITEM(8, 202, 202, fontpage_8_202_202), // 'ъ' -- 'ъ' + FONTDATA_ITEM(8, 206, 207, fontpage_8_206_207), // 'ю' -- 'я' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_ca.h b/Marlin/src/lcd/dogm/fontdata/langdata_ca.h index ffda82764fa2..deac3678b56e 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_ca.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_ca.h @@ -3,7 +3,8 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; +#include "langdata.h" + +static const uxg_fontinfo_t g_fontinfo_ca[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_cz.h b/Marlin/src/lcd/dogm/fontdata/langdata_cz.h index 754459d9af2a..39f03f3a97d7 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_cz.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_cz.h @@ -3,7 +3,9 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once + +#include "langdata.h" const u8g_fntpgm_uint8_t fontpage_2_140_141[47] U8G_FONT_SECTION("fontpage_2_140_141") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x8C,0x8D,0x00,0x0A,0x00,0x00, @@ -40,15 +42,14 @@ const u8g_fntpgm_uint8_t fontpage_2_253_254[47] U8G_FONT_SECTION("fontpage_2_253 0x00,0x05,0x0A,0x0A,0x06,0x00,0x00,0x50,0x20,0x00,0xF8,0x08,0x10,0x20,0x40,0x80, 0xF8,0x05,0x08,0x08,0x06,0x00,0x00,0x50,0x20,0x00,0xF8,0x10,0x20,0x40,0xF8}; -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(2, 140, 141, fontpage_2_140_141), // 'Č' -- 'č' - FONTDATA_ITEM(2, 143, 143, fontpage_2_143_143), // 'ď' -- 'ď' - FONTDATA_ITEM(2, 154, 155, fontpage_2_154_155), // 'Ě' -- 'ě' - FONTDATA_ITEM(2, 200, 200, fontpage_2_200_200), // 'ň' -- 'ň' - FONTDATA_ITEM(2, 216, 217, fontpage_2_216_217), // 'Ř' -- 'ř' - FONTDATA_ITEM(2, 224, 225, fontpage_2_224_225), // 'Š' -- 'š' - FONTDATA_ITEM(2, 229, 229, fontpage_2_229_229), // 'ť' -- 'ť' - FONTDATA_ITEM(2, 239, 239, fontpage_2_239_239), // 'ů' -- 'ů' - FONTDATA_ITEM(2, 253, 254, fontpage_2_253_254), // 'Ž' -- 'ž' +static const uxg_fontinfo_t g_fontinfo_cz[] PROGMEM = { + FONTDATA_ITEM(2, 140, 141, fontpage_2_140_141), // 'Č' -- 'č' + FONTDATA_ITEM(2, 143, 143, fontpage_2_143_143), // 'ď' -- 'ď' + FONTDATA_ITEM(2, 154, 155, fontpage_2_154_155), // 'Ě' -- 'ě' + FONTDATA_ITEM(2, 200, 200, fontpage_2_200_200), // 'ň' -- 'ň' + FONTDATA_ITEM(2, 216, 217, fontpage_2_216_217), // 'Ř' -- 'ř' + FONTDATA_ITEM(2, 224, 225, fontpage_2_224_225), // 'Š' -- 'š' + FONTDATA_ITEM(2, 229, 229, fontpage_2_229_229), // 'ť' -- 'ť' + FONTDATA_ITEM(2, 239, 239, fontpage_2_239_239), // 'ů' -- 'ů' + FONTDATA_ITEM(2, 253, 254, fontpage_2_253_254), // 'Ž' -- 'ž' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_da.h b/Marlin/src/lcd/dogm/fontdata/langdata_da.h index ffda82764fa2..ad8df9a42976 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_da.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_da.h @@ -3,7 +3,8 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; +#include "langdata.h" + +static const uxg_fontinfo_t g_fontinfo_da[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_de.h b/Marlin/src/lcd/dogm/fontdata/langdata_de.h index ffda82764fa2..44230fa302b3 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_de.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_de.h @@ -3,7 +3,8 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; +#include "langdata.h" + +static const uxg_fontinfo_t g_fontinfo_de[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_el.h b/Marlin/src/lcd/dogm/fontdata/langdata_el.h index 4b545f228436..6fefab9c61a1 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_el.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_el.h @@ -3,7 +3,9 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once + +#include "langdata.h" const u8g_fntpgm_uint8_t fontpage_7_136_136[33] U8G_FONT_SECTION("fontpage_7_136_136") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x88,0x88,0x00,0x0A,0x00,0x00, @@ -75,16 +77,15 @@ const u8g_fntpgm_uint8_t fontpage_64_166_166[24] U8G_FONT_SECTION("fontpage_64_1 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0xA6,0xA6,0x00,0x01,0x00,0x00, 0x00,0x05,0x01,0x01,0x06,0x00,0x00,0xA8}; -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(7, 136, 136, fontpage_7_136_136), // 'Έ' -- 'Έ' - FONTDATA_ITEM(7, 145, 157, fontpage_7_145_157), // 'Α' -- 'Ν' - FONTDATA_ITEM(7, 159, 161, fontpage_7_159_161), // 'Ο' -- 'Ρ' - FONTDATA_ITEM(7, 163, 167, fontpage_7_163_167), // 'Σ' -- 'Χ' - FONTDATA_ITEM(7, 172, 175, fontpage_7_172_175), // 'ά' -- 'ί' - FONTDATA_ITEM(7, 177, 181, fontpage_7_177_181), // 'α' -- 'ε' - FONTDATA_ITEM(7, 183, 199, fontpage_7_183_199), // 'η' -- 'χ' - FONTDATA_ITEM(7, 201, 201, fontpage_7_201_201), // 'ω' -- 'ω' - FONTDATA_ITEM(7, 204, 206, fontpage_7_204_206), // 'ό' -- 'ώ' - FONTDATA_ITEM(64, 166, 166, fontpage_64_166_166), // '…' -- '…' +static const uxg_fontinfo_t g_fontinfo_el[] PROGMEM = { + FONTDATA_ITEM(7, 136, 136, fontpage_7_136_136), // 'Έ' -- 'Έ' + FONTDATA_ITEM(7, 145, 157, fontpage_7_145_157), // 'Α' -- 'Ν' + FONTDATA_ITEM(7, 159, 161, fontpage_7_159_161), // 'Ο' -- 'Ρ' + FONTDATA_ITEM(7, 163, 167, fontpage_7_163_167), // 'Σ' -- 'Χ' + FONTDATA_ITEM(7, 172, 175, fontpage_7_172_175), // 'ά' -- 'ί' + FONTDATA_ITEM(7, 177, 181, fontpage_7_177_181), // 'α' -- 'ε' + FONTDATA_ITEM(7, 183, 199, fontpage_7_183_199), // 'η' -- 'χ' + FONTDATA_ITEM(7, 201, 201, fontpage_7_201_201), // 'ω' -- 'ω' + FONTDATA_ITEM(7, 204, 206, fontpage_7_204_206), // 'ό' -- 'ώ' + FONTDATA_ITEM(64, 166, 166, fontpage_64_166_166), // '…' -- '…' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_el_gr.h b/Marlin/src/lcd/dogm/fontdata/langdata_el_gr.h index 4b545f228436..8d7cba861530 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_el_gr.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_el_gr.h @@ -3,7 +3,9 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once + +#include "langdata.h" const u8g_fntpgm_uint8_t fontpage_7_136_136[33] U8G_FONT_SECTION("fontpage_7_136_136") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x88,0x88,0x00,0x0A,0x00,0x00, @@ -75,16 +77,15 @@ const u8g_fntpgm_uint8_t fontpage_64_166_166[24] U8G_FONT_SECTION("fontpage_64_1 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0xA6,0xA6,0x00,0x01,0x00,0x00, 0x00,0x05,0x01,0x01,0x06,0x00,0x00,0xA8}; -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(7, 136, 136, fontpage_7_136_136), // 'Έ' -- 'Έ' - FONTDATA_ITEM(7, 145, 157, fontpage_7_145_157), // 'Α' -- 'Ν' - FONTDATA_ITEM(7, 159, 161, fontpage_7_159_161), // 'Ο' -- 'Ρ' - FONTDATA_ITEM(7, 163, 167, fontpage_7_163_167), // 'Σ' -- 'Χ' - FONTDATA_ITEM(7, 172, 175, fontpage_7_172_175), // 'ά' -- 'ί' - FONTDATA_ITEM(7, 177, 181, fontpage_7_177_181), // 'α' -- 'ε' - FONTDATA_ITEM(7, 183, 199, fontpage_7_183_199), // 'η' -- 'χ' - FONTDATA_ITEM(7, 201, 201, fontpage_7_201_201), // 'ω' -- 'ω' - FONTDATA_ITEM(7, 204, 206, fontpage_7_204_206), // 'ό' -- 'ώ' - FONTDATA_ITEM(64, 166, 166, fontpage_64_166_166), // '…' -- '…' +static const uxg_fontinfo_t g_fontinfo_el_gr[] PROGMEM = { + FONTDATA_ITEM(7, 136, 136, fontpage_7_136_136), // 'Έ' -- 'Έ' + FONTDATA_ITEM(7, 145, 157, fontpage_7_145_157), // 'Α' -- 'Ν' + FONTDATA_ITEM(7, 159, 161, fontpage_7_159_161), // 'Ο' -- 'Ρ' + FONTDATA_ITEM(7, 163, 167, fontpage_7_163_167), // 'Σ' -- 'Χ' + FONTDATA_ITEM(7, 172, 175, fontpage_7_172_175), // 'ά' -- 'ί' + FONTDATA_ITEM(7, 177, 181, fontpage_7_177_181), // 'α' -- 'ε' + FONTDATA_ITEM(7, 183, 199, fontpage_7_183_199), // 'η' -- 'χ' + FONTDATA_ITEM(7, 201, 201, fontpage_7_201_201), // 'ω' -- 'ω' + FONTDATA_ITEM(7, 204, 206, fontpage_7_204_206), // 'ό' -- 'ώ' + FONTDATA_ITEM(64, 166, 166, fontpage_64_166_166), // '…' -- '…' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_en.h b/Marlin/src/lcd/dogm/fontdata/langdata_en.h index ffda82764fa2..a69161b5620f 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_en.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_en.h @@ -3,7 +3,8 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; +#include "langdata.h" + +static const uxg_fontinfo_t g_fontinfo_en[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_es.h b/Marlin/src/lcd/dogm/fontdata/langdata_es.h index ffda82764fa2..a8ddb44ce896 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_es.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_es.h @@ -3,7 +3,8 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; +#include "langdata.h" + +static const uxg_fontinfo_t g_fontinfo_es[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_eu.h b/Marlin/src/lcd/dogm/fontdata/langdata_eu.h index ffda82764fa2..3fdc0253bc80 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_eu.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_eu.h @@ -3,7 +3,8 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; +#include "langdata.h" + +static const uxg_fontinfo_t g_fontinfo_eu[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_fi.h b/Marlin/src/lcd/dogm/fontdata/langdata_fi.h index ffda82764fa2..25e192753756 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_fi.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_fi.h @@ -3,7 +3,8 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; +#include "langdata.h" + +static const uxg_fontinfo_t g_fontinfo_fi[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_fr.h b/Marlin/src/lcd/dogm/fontdata/langdata_fr.h index ffda82764fa2..a3cc160c97ce 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_fr.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_fr.h @@ -3,7 +3,8 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; +#include "langdata.h" + +static const uxg_fontinfo_t g_fontinfo_fr[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_gl.h b/Marlin/src/lcd/dogm/fontdata/langdata_gl.h index ffda82764fa2..2f93d05dbe20 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_gl.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_gl.h @@ -3,7 +3,8 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; +#include "langdata.h" + +static const uxg_fontinfo_t g_fontinfo_gl[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_hr.h b/Marlin/src/lcd/dogm/fontdata/langdata_hr.h index cdb2cc7d1ade..b5e4d544cca2 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_hr.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_hr.h @@ -3,7 +3,9 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once + +#include "langdata.h" const u8g_fntpgm_uint8_t fontpage_2_135_135[31] U8G_FONT_SECTION("fontpage_2_135_135") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x87,0x87,0x00,0x08,0x00,0x00, @@ -22,11 +24,10 @@ const u8g_fntpgm_uint8_t fontpage_2_254_254[31] U8G_FONT_SECTION("fontpage_2_254 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0xFE,0xFE,0x00,0x08,0x00,0x00, 0x00,0x05,0x08,0x08,0x06,0x00,0x00,0x50,0x20,0x00,0xF8,0x10,0x20,0x40,0xF8}; -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(2, 135, 135, fontpage_2_135_135), // 'ć' -- 'ć' - FONTDATA_ITEM(2, 140, 141, fontpage_2_140_141), // 'Č' -- 'č' - FONTDATA_ITEM(2, 145, 145, fontpage_2_145_145), // 'đ' -- 'đ' - FONTDATA_ITEM(2, 225, 225, fontpage_2_225_225), // 'š' -- 'š' - FONTDATA_ITEM(2, 254, 254, fontpage_2_254_254), // 'ž' -- 'ž' +static const uxg_fontinfo_t g_fontinfo_hr[] PROGMEM = { + FONTDATA_ITEM(2, 135, 135, fontpage_2_135_135), // 'ć' -- 'ć' + FONTDATA_ITEM(2, 140, 141, fontpage_2_140_141), // 'Č' -- 'č' + FONTDATA_ITEM(2, 145, 145, fontpage_2_145_145), // 'đ' -- 'đ' + FONTDATA_ITEM(2, 225, 225, fontpage_2_225_225), // 'š' -- 'š' + FONTDATA_ITEM(2, 254, 254, fontpage_2_254_254), // 'ž' -- 'ž' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_hu.h b/Marlin/src/lcd/dogm/fontdata/langdata_hu.h index 8c15a3890ab0..450662a8c9d1 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_hu.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_hu.h @@ -3,13 +3,14 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once + +#include "langdata.h" const u8g_fntpgm_uint8_t fontpage_2_241_241[31] U8G_FONT_SECTION("fontpage_2_241_241") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0xF1,0xF1,0x00,0x08,0x00,0x00, 0x00,0x05,0x08,0x08,0x06,0x00,0x00,0x48,0x90,0x00,0x88,0x88,0x88,0x88,0x70}; -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(2, 241, 241, fontpage_2_241_241), // 'ű' -- 'ű' +static const uxg_fontinfo_t g_fontinfo_hu[] PROGMEM = { + FONTDATA_ITEM(2, 241, 241, fontpage_2_241_241), // 'ű' -- 'ű' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_it.h b/Marlin/src/lcd/dogm/fontdata/langdata_it.h index ffda82764fa2..1a41a794fa52 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_it.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_it.h @@ -3,7 +3,8 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; +#include "langdata.h" + +static const uxg_fontinfo_t g_fontinfo_it[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_jp_kana.h b/Marlin/src/lcd/dogm/fontdata/langdata_jp_kana.h index 01316d4c1311..dc483b7d2b59 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_jp_kana.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_jp_kana.h @@ -3,7 +3,9 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once + +#include "langdata.h" const u8g_fntpgm_uint8_t fontpage_97_161_164[65] U8G_FONT_SECTION("fontpage_97_161_164") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0xA1,0xA4,0x00,0x07,0x00,0x00, @@ -94,18 +96,17 @@ const u8g_fntpgm_uint8_t fontpage_97_252_252[25] U8G_FONT_SECTION("fontpage_97_2 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0xFC,0xFC,0x00,0x05,0x00,0x00, 0x00,0x05,0x02,0x02,0x06,0x00,0x03,0x80,0x78}; -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(97, 161, 164, fontpage_97_161_164), // 'ァ' -- 'イ' - FONTDATA_ITEM(97, 166, 166, fontpage_97_166_166), // 'ウ' -- 'ウ' - FONTDATA_ITEM(97, 168, 168, fontpage_97_168_168), // 'エ' -- 'エ' - FONTDATA_ITEM(97, 170, 187, fontpage_97_170_187), // 'オ' -- 'セ' - FONTDATA_ITEM(97, 189, 193, fontpage_97_189_193), // 'ソ' -- 'チ' - FONTDATA_ITEM(97, 195, 211, fontpage_97_195_211), // 'ッ' -- 'ビ' - FONTDATA_ITEM(97, 213, 217, fontpage_97_213_217), // 'フ' -- 'ベ' - FONTDATA_ITEM(97, 219, 220, fontpage_97_219_220), // 'ホ' -- 'ボ' - FONTDATA_ITEM(97, 222, 223, fontpage_97_222_223), // 'マ' -- 'ミ' - FONTDATA_ITEM(97, 225, 237, fontpage_97_225_237), // 'メ' -- 'ロ' - FONTDATA_ITEM(97, 242, 243, fontpage_97_242_243), // 'ヲ' -- 'ン' - FONTDATA_ITEM(97, 252, 252, fontpage_97_252_252), // 'ー' -- 'ー' +static const uxg_fontinfo_t g_fontinfo_jp_kana[] PROGMEM = { + FONTDATA_ITEM(97, 161, 164, fontpage_97_161_164), // 'ァ' -- 'イ' + FONTDATA_ITEM(97, 166, 166, fontpage_97_166_166), // 'ウ' -- 'ウ' + FONTDATA_ITEM(97, 168, 168, fontpage_97_168_168), // 'エ' -- 'エ' + FONTDATA_ITEM(97, 170, 187, fontpage_97_170_187), // 'オ' -- 'セ' + FONTDATA_ITEM(97, 189, 193, fontpage_97_189_193), // 'ソ' -- 'チ' + FONTDATA_ITEM(97, 195, 211, fontpage_97_195_211), // 'ッ' -- 'ビ' + FONTDATA_ITEM(97, 213, 217, fontpage_97_213_217), // 'フ' -- 'ベ' + FONTDATA_ITEM(97, 219, 220, fontpage_97_219_220), // 'ホ' -- 'ボ' + FONTDATA_ITEM(97, 222, 223, fontpage_97_222_223), // 'マ' -- 'ミ' + FONTDATA_ITEM(97, 225, 237, fontpage_97_225_237), // 'メ' -- 'ロ' + FONTDATA_ITEM(97, 242, 243, fontpage_97_242_243), // 'ヲ' -- 'ン' + FONTDATA_ITEM(97, 252, 252, fontpage_97_252_252), // 'ー' -- 'ー' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_ko_KR.h b/Marlin/src/lcd/dogm/fontdata/langdata_ko_KR.h index 6b48434a6f58..31cc0bca36b7 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_ko_KR.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_ko_KR.h @@ -3,7 +3,9 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once + +#include "langdata.h" const u8g_fntpgm_uint8_t fontpage_344_240_240[34] U8G_FONT_SECTION("fontpage_344_240_240") = { 0x00,0x0B,0x0D,0x00,0xFD,0x00,0x00,0x00,0x00,0x00,0xF0,0xF0,0x00,0x09,0xFE,0x00, @@ -436,112 +438,111 @@ const u8g_fntpgm_uint8_t fontpage_431_136_136[34] U8G_FONT_SECTION("fontpage_431 0x00,0x08,0x0B,0x0B,0x0A,0x01,0xFE,0x71,0x01,0xFD,0x01,0x71,0x49,0x89,0x49,0x71, 0x01,0x01}; -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(344, 240, 240, fontpage_344_240_240), // '거' -- '거' - FONTDATA_ITEM(345, 224, 224, fontpage_345_224_224), // '고' -- '고' - FONTDATA_ITEM(347, 248, 248, fontpage_347_248_248), // '그' -- '그' - FONTDATA_ITEM(348, 137, 137, fontpage_348_137_137), // '급' -- '급' - FONTDATA_ITEM(348, 176, 176, fontpage_348_176_176), // '기' -- '기' - FONTDATA_ITEM(348, 197, 197, fontpage_348_197_197), // '깅' -- '깅' - FONTDATA_ITEM(352, 196, 196, fontpage_352_196_196), // '끄' -- '끄' - FONTDATA_ITEM(353, 180, 180, fontpage_353_180_180), // '내' -- '내' - FONTDATA_ITEM(354, 248, 248, fontpage_354_248_248), // '노' -- '노' - FONTDATA_ITEM(356, 132, 132, fontpage_356_132_132), // '누' -- '누' - FONTDATA_ITEM(356, 244, 244, fontpage_356_244_244), // '뉴' -- '뉴' - FONTDATA_ITEM(357, 200, 200, fontpage_357_200_200), // '니' -- '니' - FONTDATA_ITEM(357, 228, 228, fontpage_357_228_228), // '다' -- '다' - FONTDATA_ITEM(357, 249, 249, fontpage_357_249_249), // '당' -- '당' - FONTDATA_ITEM(359, 196, 196, fontpage_359_196_196), // '도' -- '도' - FONTDATA_ITEM(359, 204, 204, fontpage_359_204_204), // '돌' -- '돌' - FONTDATA_ITEM(359, 217, 217, fontpage_359_217_217), // '동' -- '동' - FONTDATA_ITEM(360, 152, 152, fontpage_360_152_152), // '되' -- '되' - FONTDATA_ITEM(360, 156, 156, fontpage_360_156_156), // '된' -- '된' - FONTDATA_ITEM(360, 168, 168, fontpage_360_168_168), // '됨' -- '됨' - FONTDATA_ITEM(361, 164, 164, fontpage_361_164_164), // '뒤' -- '뒤' - FONTDATA_ITEM(361, 220, 220, fontpage_361_220_220), // '드' -- '드' - FONTDATA_ITEM(362, 148, 148, fontpage_362_148_148), // '디' -- '디' - FONTDATA_ITEM(366, 252, 252, fontpage_366_252_252), // '라' -- '라' - FONTDATA_ITEM(367, 236, 236, fontpage_367_236_236), // '러' -- '러' - FONTDATA_ITEM(368, 136, 136, fontpage_368_136_136), // '레' -- '레' - FONTDATA_ITEM(368, 165, 165, fontpage_368_165_165), // '력' -- '력' - FONTDATA_ITEM(368, 220, 220, fontpage_368_220_220), // '로' -- '로' - FONTDATA_ITEM(369, 204, 204, fontpage_369_204_204), // '료' -- '료' - FONTDATA_ITEM(370, 244, 244, fontpage_370_244_244), // '르' -- '르' - FONTDATA_ITEM(371, 172, 172, fontpage_371_172_172), // '리' -- '리' - FONTDATA_ITEM(371, 176, 176, fontpage_371_176_176), // '린' -- '린' - FONTDATA_ITEM(371, 189, 189, fontpage_371_189_189), // '립' -- '립' - FONTDATA_ITEM(371, 193, 193, fontpage_371_193_193), // '링' -- '링' - FONTDATA_ITEM(372, 200, 200, fontpage_372_200_200), // '멈' -- '멈' - FONTDATA_ITEM(372, 212, 212, fontpage_372_212_212), // '메' -- '메' - FONTDATA_ITEM(372, 244, 244, fontpage_372_244_244), // '면' -- '면' - FONTDATA_ITEM(373, 168, 168, fontpage_373_168_168), // '모' -- '모' - FONTDATA_ITEM(373, 187, 187, fontpage_373_187_187), // '못' -- '못' - FONTDATA_ITEM(375, 248, 248, fontpage_375_248_248), // '미' -- '미' - FONTDATA_ITEM(376, 128, 128, fontpage_376_128_128), // '밀' -- '밀' - FONTDATA_ITEM(376, 148, 148, fontpage_376_148_148), // '바' -- '바' - FONTDATA_ITEM(377, 132, 132, fontpage_377_132_132), // '버' -- '버' - FONTDATA_ITEM(377, 160, 160, fontpage_377_160_160), // '베' -- '베' - FONTDATA_ITEM(377, 168, 168, fontpage_377_168_168), // '벨' -- '벨' - FONTDATA_ITEM(377, 248, 248, fontpage_377_248_248), // '본' -- '본' - FONTDATA_ITEM(380, 196, 196, fontpage_380_196_196), // '비' -- '비' - FONTDATA_ITEM(385, 172, 172, fontpage_385_172_172), // '사' -- '사' - FONTDATA_ITEM(385, 189, 189, fontpage_385_189_189), // '삽' -- '삽' - FONTDATA_ITEM(385, 200, 200, fontpage_385_200_200), // '새' -- '새' - FONTDATA_ITEM(386, 164, 164, fontpage_386_164_164), // '설' -- '설' - FONTDATA_ITEM(387, 140, 141, fontpage_387_140_141), // '소' -- '속' - FONTDATA_ITEM(389, 164, 164, fontpage_389_164_164), // '스' -- '스' - FONTDATA_ITEM(389, 172, 172, fontpage_389_172_172), // '슬' -- '슬' - FONTDATA_ITEM(389, 220, 221, fontpage_389_220_221), // '시' -- '식' - FONTDATA_ITEM(395, 180, 180, fontpage_395_180_180), // '어' -- '어' - FONTDATA_ITEM(395, 198, 198, fontpage_395_198_198), // '없' -- '없' - FONTDATA_ITEM(395, 209, 209, fontpage_395_209_209), // '엑' -- '엑' - FONTDATA_ITEM(395, 212, 212, fontpage_395_212_212), // '엔' -- '엔' - FONTDATA_ITEM(395, 244, 244, fontpage_395_244_244), // '열' -- '열' - FONTDATA_ITEM(396, 136, 136, fontpage_396_136_136), // '예' -- '예' - FONTDATA_ITEM(396, 164, 164, fontpage_396_164_164), // '오' -- '오' - FONTDATA_ITEM(396, 168, 168, fontpage_396_168_168), // '온' -- '온' - FONTDATA_ITEM(396, 196, 196, fontpage_396_196_196), // '완' -- '완' - FONTDATA_ITEM(397, 208, 208, fontpage_397_208_208), // '원' -- '원' - FONTDATA_ITEM(398, 132, 132, fontpage_398_132_132), // '위' -- '위' - FONTDATA_ITEM(398, 188, 188, fontpage_398_188_188), // '으' -- '으' - FONTDATA_ITEM(398, 204, 204, fontpage_398_204_204), // '음' -- '음' - FONTDATA_ITEM(398, 244, 244, fontpage_398_244_244), // '이' -- '이' - FONTDATA_ITEM(398, 252, 253, fontpage_398_252_253), // '일' -- '읽' - FONTDATA_ITEM(399, 133, 133, fontpage_399_133_133), // '입' -- '입' - FONTDATA_ITEM(399, 144, 145, fontpage_399_144_145), // '자' -- '작' - FONTDATA_ITEM(399, 152, 152, fontpage_399_152_152), // '잘' -- '잘' - FONTDATA_ITEM(399, 165, 165, fontpage_399_165_165), // '장' -- '장' - FONTDATA_ITEM(399, 172, 172, fontpage_399_172_172), // '재' -- '재' - FONTDATA_ITEM(400, 128, 128, fontpage_400_128_128), // '저' -- '저' - FONTDATA_ITEM(400, 132, 132, fontpage_400_132_132), // '전' -- '전' - FONTDATA_ITEM(400, 149, 149, fontpage_400_149_149), // '정' -- '정' - FONTDATA_ITEM(400, 156, 156, fontpage_400_156_156), // '제' -- '제' - FONTDATA_ITEM(401, 253, 253, fontpage_401_253_253), // '죽' -- '죽' - FONTDATA_ITEM(402, 128, 128, fontpage_402_128_128), // '준' -- '준' - FONTDATA_ITEM(402, 145, 145, fontpage_402_145_145), // '중' -- '중' - FONTDATA_ITEM(403, 144, 144, fontpage_403_144_144), // '즐' -- '즐' - FONTDATA_ITEM(403, 192, 192, fontpage_403_192_192), // '지' -- '지' - FONTDATA_ITEM(409, 152, 152, fontpage_409_152_152), // '처' -- '처' - FONTDATA_ITEM(410, 136, 136, fontpage_410_136_136), // '초' -- '초' - FONTDATA_ITEM(411, 149, 149, fontpage_411_149_149), // '축' -- '축' - FONTDATA_ITEM(411, 156, 156, fontpage_411_156_156), // '출' -- '출' - FONTDATA_ITEM(411, 164, 164, fontpage_411_164_164), // '춤' -- '춤' - FONTDATA_ITEM(411, 232, 232, fontpage_411_232_232), // '취' -- '취' - FONTDATA_ITEM(412, 216, 216, fontpage_412_216_216), // '치' -- '치' - FONTDATA_ITEM(412, 232, 232, fontpage_412_232_232), // '침' -- '침' - FONTDATA_ITEM(412, 244, 244, fontpage_412_244_244), // '카' -- '카' - FONTDATA_ITEM(414, 156, 156, fontpage_414_156_156), // '켜' -- '켜' - FONTDATA_ITEM(417, 209, 209, fontpage_417_209_209), // '탑' -- '탑' - FONTDATA_ITEM(418, 176, 176, fontpage_418_176_176), // '터' -- '터' - FONTDATA_ITEM(418, 204, 204, fontpage_418_204_204), // '테' -- '테' - FONTDATA_ITEM(419, 160, 160, fontpage_419_160_160), // '토' -- '토' - FONTDATA_ITEM(421, 184, 184, fontpage_421_184_184), // '트' -- '트' - FONTDATA_ITEM(423, 156, 156, fontpage_423_156_156), // '펜' -- '펜' - FONTDATA_ITEM(426, 132, 132, fontpage_426_132_132), // '프' -- '프' - FONTDATA_ITEM(426, 216, 216, fontpage_426_216_216), // '하' -- '하' - FONTDATA_ITEM(426, 233, 233, fontpage_426_233_233), // '합' -- '합' - FONTDATA_ITEM(428, 200, 200, fontpage_428_200_200), // '홈' -- '홈' - FONTDATA_ITEM(428, 212, 212, fontpage_428_212_212), // '화' -- '화' - FONTDATA_ITEM(431, 136, 136, fontpage_431_136_136), // '히' -- '히' +static const uxg_fontinfo_t g_fontinfo_ko_KR[] PROGMEM = { + FONTDATA_ITEM(344, 240, 240, fontpage_344_240_240), // '거' -- '거' + FONTDATA_ITEM(345, 224, 224, fontpage_345_224_224), // '고' -- '고' + FONTDATA_ITEM(347, 248, 248, fontpage_347_248_248), // '그' -- '그' + FONTDATA_ITEM(348, 137, 137, fontpage_348_137_137), // '급' -- '급' + FONTDATA_ITEM(348, 176, 176, fontpage_348_176_176), // '기' -- '기' + FONTDATA_ITEM(348, 197, 197, fontpage_348_197_197), // '깅' -- '깅' + FONTDATA_ITEM(352, 196, 196, fontpage_352_196_196), // '끄' -- '끄' + FONTDATA_ITEM(353, 180, 180, fontpage_353_180_180), // '내' -- '내' + FONTDATA_ITEM(354, 248, 248, fontpage_354_248_248), // '노' -- '노' + FONTDATA_ITEM(356, 132, 132, fontpage_356_132_132), // '누' -- '누' + FONTDATA_ITEM(356, 244, 244, fontpage_356_244_244), // '뉴' -- '뉴' + FONTDATA_ITEM(357, 200, 200, fontpage_357_200_200), // '니' -- '니' + FONTDATA_ITEM(357, 228, 228, fontpage_357_228_228), // '다' -- '다' + FONTDATA_ITEM(357, 249, 249, fontpage_357_249_249), // '당' -- '당' + FONTDATA_ITEM(359, 196, 196, fontpage_359_196_196), // '도' -- '도' + FONTDATA_ITEM(359, 204, 204, fontpage_359_204_204), // '돌' -- '돌' + FONTDATA_ITEM(359, 217, 217, fontpage_359_217_217), // '동' -- '동' + FONTDATA_ITEM(360, 152, 152, fontpage_360_152_152), // '되' -- '되' + FONTDATA_ITEM(360, 156, 156, fontpage_360_156_156), // '된' -- '된' + FONTDATA_ITEM(360, 168, 168, fontpage_360_168_168), // '됨' -- '됨' + FONTDATA_ITEM(361, 164, 164, fontpage_361_164_164), // '뒤' -- '뒤' + FONTDATA_ITEM(361, 220, 220, fontpage_361_220_220), // '드' -- '드' + FONTDATA_ITEM(362, 148, 148, fontpage_362_148_148), // '디' -- '디' + FONTDATA_ITEM(366, 252, 252, fontpage_366_252_252), // '라' -- '라' + FONTDATA_ITEM(367, 236, 236, fontpage_367_236_236), // '러' -- '러' + FONTDATA_ITEM(368, 136, 136, fontpage_368_136_136), // '레' -- '레' + FONTDATA_ITEM(368, 165, 165, fontpage_368_165_165), // '력' -- '력' + FONTDATA_ITEM(368, 220, 220, fontpage_368_220_220), // '로' -- '로' + FONTDATA_ITEM(369, 204, 204, fontpage_369_204_204), // '료' -- '료' + FONTDATA_ITEM(370, 244, 244, fontpage_370_244_244), // '르' -- '르' + FONTDATA_ITEM(371, 172, 172, fontpage_371_172_172), // '리' -- '리' + FONTDATA_ITEM(371, 176, 176, fontpage_371_176_176), // '린' -- '린' + FONTDATA_ITEM(371, 189, 189, fontpage_371_189_189), // '립' -- '립' + FONTDATA_ITEM(371, 193, 193, fontpage_371_193_193), // '링' -- '링' + FONTDATA_ITEM(372, 200, 200, fontpage_372_200_200), // '멈' -- '멈' + FONTDATA_ITEM(372, 212, 212, fontpage_372_212_212), // '메' -- '메' + FONTDATA_ITEM(372, 244, 244, fontpage_372_244_244), // '면' -- '면' + FONTDATA_ITEM(373, 168, 168, fontpage_373_168_168), // '모' -- '모' + FONTDATA_ITEM(373, 187, 187, fontpage_373_187_187), // '못' -- '못' + FONTDATA_ITEM(375, 248, 248, fontpage_375_248_248), // '미' -- '미' + FONTDATA_ITEM(376, 128, 128, fontpage_376_128_128), // '밀' -- '밀' + FONTDATA_ITEM(376, 148, 148, fontpage_376_148_148), // '바' -- '바' + FONTDATA_ITEM(377, 132, 132, fontpage_377_132_132), // '버' -- '버' + FONTDATA_ITEM(377, 160, 160, fontpage_377_160_160), // '베' -- '베' + FONTDATA_ITEM(377, 168, 168, fontpage_377_168_168), // '벨' -- '벨' + FONTDATA_ITEM(377, 248, 248, fontpage_377_248_248), // '본' -- '본' + FONTDATA_ITEM(380, 196, 196, fontpage_380_196_196), // '비' -- '비' + FONTDATA_ITEM(385, 172, 172, fontpage_385_172_172), // '사' -- '사' + FONTDATA_ITEM(385, 189, 189, fontpage_385_189_189), // '삽' -- '삽' + FONTDATA_ITEM(385, 200, 200, fontpage_385_200_200), // '새' -- '새' + FONTDATA_ITEM(386, 164, 164, fontpage_386_164_164), // '설' -- '설' + FONTDATA_ITEM(387, 140, 141, fontpage_387_140_141), // '소' -- '속' + FONTDATA_ITEM(389, 164, 164, fontpage_389_164_164), // '스' -- '스' + FONTDATA_ITEM(389, 172, 172, fontpage_389_172_172), // '슬' -- '슬' + FONTDATA_ITEM(389, 220, 221, fontpage_389_220_221), // '시' -- '식' + FONTDATA_ITEM(395, 180, 180, fontpage_395_180_180), // '어' -- '어' + FONTDATA_ITEM(395, 198, 198, fontpage_395_198_198), // '없' -- '없' + FONTDATA_ITEM(395, 209, 209, fontpage_395_209_209), // '엑' -- '엑' + FONTDATA_ITEM(395, 212, 212, fontpage_395_212_212), // '엔' -- '엔' + FONTDATA_ITEM(395, 244, 244, fontpage_395_244_244), // '열' -- '열' + FONTDATA_ITEM(396, 136, 136, fontpage_396_136_136), // '예' -- '예' + FONTDATA_ITEM(396, 164, 164, fontpage_396_164_164), // '오' -- '오' + FONTDATA_ITEM(396, 168, 168, fontpage_396_168_168), // '온' -- '온' + FONTDATA_ITEM(396, 196, 196, fontpage_396_196_196), // '완' -- '완' + FONTDATA_ITEM(397, 208, 208, fontpage_397_208_208), // '원' -- '원' + FONTDATA_ITEM(398, 132, 132, fontpage_398_132_132), // '위' -- '위' + FONTDATA_ITEM(398, 188, 188, fontpage_398_188_188), // '으' -- '으' + FONTDATA_ITEM(398, 204, 204, fontpage_398_204_204), // '음' -- '음' + FONTDATA_ITEM(398, 244, 244, fontpage_398_244_244), // '이' -- '이' + FONTDATA_ITEM(398, 252, 253, fontpage_398_252_253), // '일' -- '읽' + FONTDATA_ITEM(399, 133, 133, fontpage_399_133_133), // '입' -- '입' + FONTDATA_ITEM(399, 144, 145, fontpage_399_144_145), // '자' -- '작' + FONTDATA_ITEM(399, 152, 152, fontpage_399_152_152), // '잘' -- '잘' + FONTDATA_ITEM(399, 165, 165, fontpage_399_165_165), // '장' -- '장' + FONTDATA_ITEM(399, 172, 172, fontpage_399_172_172), // '재' -- '재' + FONTDATA_ITEM(400, 128, 128, fontpage_400_128_128), // '저' -- '저' + FONTDATA_ITEM(400, 132, 132, fontpage_400_132_132), // '전' -- '전' + FONTDATA_ITEM(400, 149, 149, fontpage_400_149_149), // '정' -- '정' + FONTDATA_ITEM(400, 156, 156, fontpage_400_156_156), // '제' -- '제' + FONTDATA_ITEM(401, 253, 253, fontpage_401_253_253), // '죽' -- '죽' + FONTDATA_ITEM(402, 128, 128, fontpage_402_128_128), // '준' -- '준' + FONTDATA_ITEM(402, 145, 145, fontpage_402_145_145), // '중' -- '중' + FONTDATA_ITEM(403, 144, 144, fontpage_403_144_144), // '즐' -- '즐' + FONTDATA_ITEM(403, 192, 192, fontpage_403_192_192), // '지' -- '지' + FONTDATA_ITEM(409, 152, 152, fontpage_409_152_152), // '처' -- '처' + FONTDATA_ITEM(410, 136, 136, fontpage_410_136_136), // '초' -- '초' + FONTDATA_ITEM(411, 149, 149, fontpage_411_149_149), // '축' -- '축' + FONTDATA_ITEM(411, 156, 156, fontpage_411_156_156), // '출' -- '출' + FONTDATA_ITEM(411, 164, 164, fontpage_411_164_164), // '춤' -- '춤' + FONTDATA_ITEM(411, 232, 232, fontpage_411_232_232), // '취' -- '취' + FONTDATA_ITEM(412, 216, 216, fontpage_412_216_216), // '치' -- '치' + FONTDATA_ITEM(412, 232, 232, fontpage_412_232_232), // '침' -- '침' + FONTDATA_ITEM(412, 244, 244, fontpage_412_244_244), // '카' -- '카' + FONTDATA_ITEM(414, 156, 156, fontpage_414_156_156), // '켜' -- '켜' + FONTDATA_ITEM(417, 209, 209, fontpage_417_209_209), // '탑' -- '탑' + FONTDATA_ITEM(418, 176, 176, fontpage_418_176_176), // '터' -- '터' + FONTDATA_ITEM(418, 204, 204, fontpage_418_204_204), // '테' -- '테' + FONTDATA_ITEM(419, 160, 160, fontpage_419_160_160), // '토' -- '토' + FONTDATA_ITEM(421, 184, 184, fontpage_421_184_184), // '트' -- '트' + FONTDATA_ITEM(423, 156, 156, fontpage_423_156_156), // '펜' -- '펜' + FONTDATA_ITEM(426, 132, 132, fontpage_426_132_132), // '프' -- '프' + FONTDATA_ITEM(426, 216, 216, fontpage_426_216_216), // '하' -- '하' + FONTDATA_ITEM(426, 233, 233, fontpage_426_233_233), // '합' -- '합' + FONTDATA_ITEM(428, 200, 200, fontpage_428_200_200), // '홈' -- '홈' + FONTDATA_ITEM(428, 212, 212, fontpage_428_212_212), // '화' -- '화' + FONTDATA_ITEM(431, 136, 136, fontpage_431_136_136), // '히' -- '히' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_nl.h b/Marlin/src/lcd/dogm/fontdata/langdata_nl.h index ffda82764fa2..e76eff334820 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_nl.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_nl.h @@ -3,7 +3,8 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; +#include "langdata.h" + +static const uxg_fontinfo_t g_fontinfo_nl[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_pl.h b/Marlin/src/lcd/dogm/fontdata/langdata_pl.h index 926f07529537..e89a6c159a4e 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_pl.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_pl.h @@ -3,7 +3,9 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once + +#include "langdata.h" const u8g_fntpgm_uint8_t fontpage_2_132_133[45] U8G_FONT_SECTION("fontpage_2_132_133") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x84,0x85,0x00,0x07,0xFE,0x00, @@ -29,12 +31,11 @@ const u8g_fntpgm_uint8_t fontpage_2_252_252[30] U8G_FONT_SECTION("fontpage_2_252 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0xFC,0xFC,0x00,0x07,0x00,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0x20,0x00,0xF8,0x10,0x20,0x40,0xF8}; -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(2, 132, 133, fontpage_2_132_133), // 'Ą' -- 'ą' - FONTDATA_ITEM(2, 135, 135, fontpage_2_135_135), // 'ć' -- 'ć' - FONTDATA_ITEM(2, 153, 153, fontpage_2_153_153), // 'ę' -- 'ę' - FONTDATA_ITEM(2, 193, 196, fontpage_2_193_196), // 'Ł' -- 'ń' - FONTDATA_ITEM(2, 218, 219, fontpage_2_218_219), // 'Ś' -- 'ś' - FONTDATA_ITEM(2, 252, 252, fontpage_2_252_252), // 'ż' -- 'ż' +static const uxg_fontinfo_t g_fontinfo_pl[] PROGMEM = { + FONTDATA_ITEM(2, 132, 133, fontpage_2_132_133), // 'Ą' -- 'ą' + FONTDATA_ITEM(2, 135, 135, fontpage_2_135_135), // 'ć' -- 'ć' + FONTDATA_ITEM(2, 153, 153, fontpage_2_153_153), // 'ę' -- 'ę' + FONTDATA_ITEM(2, 193, 196, fontpage_2_193_196), // 'Ł' -- 'ń' + FONTDATA_ITEM(2, 218, 219, fontpage_2_218_219), // 'Ś' -- 'ś' + FONTDATA_ITEM(2, 252, 252, fontpage_2_252_252), // 'ż' -- 'ż' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_pt.h b/Marlin/src/lcd/dogm/fontdata/langdata_pt.h index ffda82764fa2..61f857e587b6 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_pt.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_pt.h @@ -3,7 +3,8 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; +#include "langdata.h" + +static const uxg_fontinfo_t g_fontinfo_pt[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_pt_br.h b/Marlin/src/lcd/dogm/fontdata/langdata_pt_br.h index ffda82764fa2..b0ed5ad5cffc 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_pt_br.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_pt_br.h @@ -3,7 +3,8 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; +#include "langdata.h" + +static const uxg_fontinfo_t g_fontinfo_pt_br[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_ro.h b/Marlin/src/lcd/dogm/fontdata/langdata_ro.h index ffda82764fa2..6be486355314 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_ro.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_ro.h @@ -3,7 +3,8 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; +#include "langdata.h" + +static const uxg_fontinfo_t g_fontinfo_ro[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_ru.h b/Marlin/src/lcd/dogm/fontdata/langdata_ru.h index 4edd6e74e304..3f857a1b3f22 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_ru.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_ru.h @@ -3,7 +3,9 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once + +#include "langdata.h" const u8g_fntpgm_uint8_t fontpage_8_144_168[348] U8G_FONT_SECTION("fontpage_8_144_168") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x90,0xA8,0x00,0x0A,0xFE,0x00, @@ -64,10 +66,9 @@ const u8g_fntpgm_uint8_t fontpage_8_209_209[30] U8G_FONT_SECTION("fontpage_8_209 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0xD1,0xD1,0x00,0x07,0x00,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0x50,0x00,0x70,0x88,0xF0,0x80,0x70}; -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(8, 144, 168, fontpage_8_144_168), // 'А' -- 'Ш' - FONTDATA_ITEM(8, 171, 173, fontpage_8_171_173), // 'Ы' -- 'Э' - FONTDATA_ITEM(8, 175, 207, fontpage_8_175_207), // 'Я' -- 'я' - FONTDATA_ITEM(8, 209, 209, fontpage_8_209_209), // 'ё' -- 'ё' +static const uxg_fontinfo_t g_fontinfo_ru[] PROGMEM = { + FONTDATA_ITEM(8, 144, 168, fontpage_8_144_168), // 'А' -- 'Ш' + FONTDATA_ITEM(8, 171, 173, fontpage_8_171_173), // 'Ы' -- 'Э' + FONTDATA_ITEM(8, 175, 207, fontpage_8_175_207), // 'Я' -- 'я' + FONTDATA_ITEM(8, 209, 209, fontpage_8_209_209), // 'ё' -- 'ё' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_sk.h b/Marlin/src/lcd/dogm/fontdata/langdata_sk.h index d2e7ec2c56db..4580ce5b7b82 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_sk.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_sk.h @@ -3,7 +3,9 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once + +#include "langdata.h" const u8g_fntpgm_uint8_t fontpage_2_140_143[79] U8G_FONT_SECTION("fontpage_2_140_143") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x8C,0x8F,0x00,0x0A,0x00,0x00, @@ -15,9 +17,10 @@ const u8g_fntpgm_uint8_t fontpage_2_186_186[33] U8G_FONT_SECTION("fontpage_2_186 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0xBA,0xBA,0x00,0x0A,0x00,0x00, 0x00,0x03,0x0A,0x0A,0x06,0x01,0x00,0x20,0x40,0x00,0xC0,0x40,0x40,0x40,0x40,0x40, 0xE0}; -const u8g_fntpgm_uint8_t fontpage_2_190_190[33] U8G_FONT_SECTION("fontpage_2_190_190") = { - 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0xBE,0xBE,0x00,0x0A,0x00,0x00, - 0x00,0x03,0x0A,0x0A,0x06,0x01,0x00,0xA0,0x40,0x00,0xC0,0x40,0x40,0x40,0x40,0x40, +const u8g_fntpgm_uint8_t fontpage_2_189_190[49] U8G_FONT_SECTION("fontpage_2_189_190") = { + 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0xBD,0xBE,0x00,0x0A,0x00,0x00, + 0x00,0x05,0x0A,0x0A,0x06,0x00,0x00,0x50,0x20,0x00,0x80,0x80,0x80,0x80,0x80,0x80, + 0xF8,0x03,0x0A,0x0A,0x06,0x01,0x00,0xA0,0x40,0x00,0xC0,0x40,0x40,0x40,0x40,0x40, 0xE0}; const u8g_fntpgm_uint8_t fontpage_2_199_200[47] U8G_FONT_SECTION("fontpage_2_199_200") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0xC7,0xC8,0x00,0x0A,0x00,0x00, @@ -36,13 +39,12 @@ const u8g_fntpgm_uint8_t fontpage_2_253_254[47] U8G_FONT_SECTION("fontpage_2_253 0x00,0x05,0x0A,0x0A,0x06,0x00,0x00,0x50,0x20,0x00,0xF8,0x08,0x10,0x20,0x40,0x80, 0xF8,0x05,0x08,0x08,0x06,0x00,0x00,0x50,0x20,0x00,0xF8,0x10,0x20,0x40,0xF8}; -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(2, 140, 143, fontpage_2_140_143), // 'Č' -- 'ď' - FONTDATA_ITEM(2, 186, 186, fontpage_2_186_186), // 'ĺ' -- 'ĺ' - FONTDATA_ITEM(2, 190, 190, fontpage_2_190_190), // 'ľ' -- 'ľ' - FONTDATA_ITEM(2, 199, 200, fontpage_2_199_200), // 'Ň' -- 'ň' - FONTDATA_ITEM(2, 224, 225, fontpage_2_224_225), // 'Š' -- 'š' - FONTDATA_ITEM(2, 229, 229, fontpage_2_229_229), // 'ť' -- 'ť' - FONTDATA_ITEM(2, 253, 254, fontpage_2_253_254), // 'Ž' -- 'ž' +static const uxg_fontinfo_t g_fontinfo_sk[] PROGMEM = { + FONTDATA_ITEM(2, 140, 143, fontpage_2_140_143), // 'Č' -- 'ď' + FONTDATA_ITEM(2, 186, 186, fontpage_2_186_186), // 'ĺ' -- 'ĺ' + FONTDATA_ITEM(2, 189, 190, fontpage_2_189_190), // 'Ľ' -- 'ľ' + FONTDATA_ITEM(2, 199, 200, fontpage_2_199_200), // 'Ň' -- 'ň' + FONTDATA_ITEM(2, 224, 225, fontpage_2_224_225), // 'Š' -- 'š' + FONTDATA_ITEM(2, 229, 229, fontpage_2_229_229), // 'ť' -- 'ť' + FONTDATA_ITEM(2, 253, 254, fontpage_2_253_254), // 'Ž' -- 'ž' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_test.h b/Marlin/src/lcd/dogm/fontdata/langdata_test.h index c397d8b4b95b..da76a3104156 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_test.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_test.h @@ -3,7 +3,9 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once + +#include "langdata.h" const u8g_fntpgm_uint8_t fontpage_8_128_255[1677] U8G_FONT_SECTION("fontpage_8_128_255") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x80,0xFF,0x00,0x0A,0xFE,0x00, @@ -223,9 +225,8 @@ const u8g_fntpgm_uint8_t fontpage_97_193_255[822] U8G_FONT_SECTION("fontpage_97_ 0x06,0x00,0x02,0x28,0x28,0x00,0x80,0x60,0x10,0x08,0x05,0x06,0x06,0x06,0x00,0x00, 0xF8,0x08,0x08,0x08,0x08,0x08}; -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(8, 128, 255, fontpage_8_128_255), // 'Ѐ' -- 'ѿ' - FONTDATA_ITEM(97, 129, 191, fontpage_97_129_191), // 'め' -- 'タ' - FONTDATA_ITEM(97, 193, 255, fontpage_97_193_255), // 'チ' -- 'ヿ' +static const uxg_fontinfo_t g_fontinfo_test[] PROGMEM = { + FONTDATA_ITEM(8, 128, 255, fontpage_8_128_255), // 'Ѐ' -- 'ѿ' + FONTDATA_ITEM(97, 129, 191, fontpage_97_129_191), // 'め' -- 'タ' + FONTDATA_ITEM(97, 193, 255, fontpage_97_193_255), // 'チ' -- 'ヿ' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_tr.h b/Marlin/src/lcd/dogm/fontdata/langdata_tr.h index a4068e10d092..0ac02435a5dd 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_tr.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_tr.h @@ -3,7 +3,9 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once + +#include "langdata.h" const u8g_fntpgm_uint8_t fontpage_2_158_159[49] U8G_FONT_SECTION("fontpage_2_158_159") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x9E,0x9F,0x00,0x0A,0xFE,0x00, @@ -19,9 +21,8 @@ const u8g_fntpgm_uint8_t fontpage_2_222_223[45] U8G_FONT_SECTION("fontpage_2_222 0x00,0x05,0x09,0x09,0x06,0x00,0xFE,0x70,0x88,0x80,0x70,0x08,0x88,0x70,0x10,0x60, 0x05,0x07,0x07,0x06,0x00,0xFE,0x78,0x80,0x70,0x08,0xF0,0x10,0x60}; -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(2, 158, 159, fontpage_2_158_159), // 'Ğ' -- 'ğ' - FONTDATA_ITEM(2, 176, 177, fontpage_2_176_177), // 'İ' -- 'ı' - FONTDATA_ITEM(2, 222, 223, fontpage_2_222_223), // 'Ş' -- 'ş' +static const uxg_fontinfo_t g_fontinfo_tr[] PROGMEM = { + FONTDATA_ITEM(2, 158, 159, fontpage_2_158_159), // 'Ğ' -- 'ğ' + FONTDATA_ITEM(2, 176, 177, fontpage_2_176_177), // 'İ' -- 'ı' + FONTDATA_ITEM(2, 222, 223, fontpage_2_222_223), // 'Ş' -- 'ş' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_uk.h b/Marlin/src/lcd/dogm/fontdata/langdata_uk.h index 47ec93992fc2..b25e2f6db4e3 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_uk.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_uk.h @@ -3,7 +3,9 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once + +#include "langdata.h" const u8g_fntpgm_uint8_t fontpage_8_134_134[30] U8G_FONT_SECTION("fontpage_8_134_134") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x86,0x86,0x00,0x07,0x00,0x00, @@ -72,14 +74,13 @@ const u8g_fntpgm_uint8_t fontpage_8_214_215[41] U8G_FONT_SECTION("fontpage_8_214 0x00,0x03,0x06,0x06,0x06,0x01,0x00,0x40,0x00,0xC0,0x40,0x40,0xE0,0x03,0x06,0x06, 0x06,0x01,0x00,0xA0,0x00,0xC0,0x40,0x40,0xE0}; -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(8, 134, 134, fontpage_8_134_134), // 'І' -- 'І' - FONTDATA_ITEM(8, 144, 169, fontpage_8_144_169), // 'А' -- 'Щ' - FONTDATA_ITEM(8, 172, 172, fontpage_8_172_172), // 'Ь' -- 'Ь' - FONTDATA_ITEM(8, 175, 201, fontpage_8_175_201), // 'Я' -- 'щ' - FONTDATA_ITEM(8, 204, 204, fontpage_8_204_204), // 'ь' -- 'ь' - FONTDATA_ITEM(8, 206, 207, fontpage_8_206_207), // 'ю' -- 'я' - FONTDATA_ITEM(8, 212, 212, fontpage_8_212_212), // 'є' -- 'є' - FONTDATA_ITEM(8, 214, 215, fontpage_8_214_215), // 'і' -- 'ї' +static const uxg_fontinfo_t g_fontinfo_uk[] PROGMEM = { + FONTDATA_ITEM(8, 134, 134, fontpage_8_134_134), // 'І' -- 'І' + FONTDATA_ITEM(8, 144, 169, fontpage_8_144_169), // 'А' -- 'Щ' + FONTDATA_ITEM(8, 172, 172, fontpage_8_172_172), // 'Ь' -- 'Ь' + FONTDATA_ITEM(8, 175, 201, fontpage_8_175_201), // 'Я' -- 'щ' + FONTDATA_ITEM(8, 204, 204, fontpage_8_204_204), // 'ь' -- 'ь' + FONTDATA_ITEM(8, 206, 207, fontpage_8_206_207), // 'ю' -- 'я' + FONTDATA_ITEM(8, 212, 212, fontpage_8_212_212), // 'є' -- 'є' + FONTDATA_ITEM(8, 214, 215, fontpage_8_214_215), // 'і' -- 'ї' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_vi.h b/Marlin/src/lcd/dogm/fontdata/langdata_vi.h index a8a0c5c121e6..303c4c66d637 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_vi.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_vi.h @@ -3,7 +3,9 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once + +#include "langdata.h" 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, @@ -177,51 +179,50 @@ const u8g_fntpgm_uint8_t fontpage_61_241_241[32] U8G_FONT_SECTION("fontpage_61_2 0x00,0x06,0x09,0x09,0x07,0x00,0xFE,0x0C,0x04,0x88,0x88,0x88,0x88,0x70,0x00,0x20 }; -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(2, 131, 131, fontpage_2_131_131), // 'ă' -- 'ă' - FONTDATA_ITEM(2, 144, 145, fontpage_2_144_145), // 'Đ' -- 'đ' - FONTDATA_ITEM(2, 169, 169, fontpage_2_169_169), // 'ĩ' -- 'ĩ' - FONTDATA_ITEM(3, 161, 161, fontpage_3_161_161), // 'ơ' -- 'ơ' - FONTDATA_ITEM(3, 175, 176, fontpage_3_175_176), // 'Ư' -- 'ư' - FONTDATA_ITEM(6, 131, 131, fontpage_6_131_131), // '̃' -- '̃' - FONTDATA_ITEM(6, 137, 137, fontpage_6_137_137), // '̉' -- '̉' - FONTDATA_ITEM(6, 163, 163, fontpage_6_163_163), // '̣' -- '̣' - FONTDATA_ITEM(6, 192, 193, fontpage_6_192_193), // '̀' -- '́' - FONTDATA_ITEM(61, 161, 161, fontpage_61_161_161), // 'ạ' -- 'ạ' - FONTDATA_ITEM(61, 163, 163, fontpage_61_163_163), // 'ả' -- 'ả' - FONTDATA_ITEM(61, 165, 165, fontpage_61_165_165), // 'ấ' -- 'ấ' - FONTDATA_ITEM(61, 167, 167, fontpage_61_167_167), // 'ầ' -- 'ầ' - FONTDATA_ITEM(61, 169, 169, fontpage_61_169_169), // 'ẩ' -- 'ẩ' - FONTDATA_ITEM(61, 173, 173, fontpage_61_173_173), // 'ậ' -- 'ậ' - FONTDATA_ITEM(61, 175, 175, fontpage_61_175_175), // 'ắ' -- 'ắ' - FONTDATA_ITEM(61, 177, 177, fontpage_61_177_177), // 'ằ' -- 'ằ' - FONTDATA_ITEM(61, 179, 179, fontpage_61_179_179), // 'ẳ' -- 'ẳ' - FONTDATA_ITEM(61, 181, 181, fontpage_61_181_181), // 'ẵ' -- 'ẵ' - FONTDATA_ITEM(61, 183, 183, fontpage_61_183_183), // 'ặ' -- 'ặ' - FONTDATA_ITEM(61, 191, 191, fontpage_61_191_191), // 'ế' -- 'ế' - FONTDATA_ITEM(61, 193, 193, fontpage_61_193_193), // 'ề' -- 'ề' - FONTDATA_ITEM(61, 195, 195, fontpage_61_195_195), // 'ể' -- 'ể' - FONTDATA_ITEM(61, 199, 199, fontpage_61_199_199), // 'ệ' -- 'ệ' - FONTDATA_ITEM(61, 201, 201, fontpage_61_201_201), // 'ỉ' -- 'ỉ' - FONTDATA_ITEM(61, 203, 203, fontpage_61_203_203), // 'ị' -- 'ị' - FONTDATA_ITEM(61, 205, 205, fontpage_61_205_205), // 'ọ' -- 'ọ' - FONTDATA_ITEM(61, 207, 207, fontpage_61_207_207), // 'ỏ' -- 'ỏ' - FONTDATA_ITEM(61, 209, 209, fontpage_61_209_209), // 'ố' -- 'ố' - FONTDATA_ITEM(61, 211, 211, fontpage_61_211_211), // 'ồ' -- 'ồ' - FONTDATA_ITEM(61, 213, 213, fontpage_61_213_213), // 'ổ' -- 'ổ' - FONTDATA_ITEM(61, 215, 215, fontpage_61_215_215), // 'ỗ' -- 'ỗ' - FONTDATA_ITEM(61, 217, 217, fontpage_61_217_217), // 'ộ' -- 'ộ' - FONTDATA_ITEM(61, 219, 219, fontpage_61_219_219), // 'ớ' -- 'ớ' - FONTDATA_ITEM(61, 221, 221, fontpage_61_221_221), // 'ờ' -- 'ờ' - FONTDATA_ITEM(61, 223, 223, fontpage_61_223_223), // 'ở' -- 'ở' - FONTDATA_ITEM(61, 225, 225, fontpage_61_225_225), // 'ỡ' -- 'ỡ' - FONTDATA_ITEM(61, 227, 227, fontpage_61_227_227), // 'ợ' -- 'ợ' - FONTDATA_ITEM(61, 229, 229, fontpage_61_229_229), // 'ụ' -- 'ụ' - FONTDATA_ITEM(61, 231, 231, fontpage_61_231_231), // 'ủ' -- 'ủ' - FONTDATA_ITEM(61, 233, 233, fontpage_61_233_233), // 'ứ' -- 'ứ' - FONTDATA_ITEM(61, 235, 235, fontpage_61_235_235), // 'ừ' -- 'ừ' - FONTDATA_ITEM(61, 237, 237, fontpage_61_237_237), // 'ử' -- 'ử' - FONTDATA_ITEM(61, 239, 239, fontpage_61_239_239), // 'ữ' -- 'ữ' - FONTDATA_ITEM(61, 241, 241, fontpage_61_241_241), // 'ự' -- 'ự' +static const uxg_fontinfo_t g_fontinfo_vi[] PROGMEM = { + FONTDATA_ITEM(2, 131, 131, fontpage_2_131_131), // 'ă' -- 'ă' + FONTDATA_ITEM(2, 144, 145, fontpage_2_144_145), // 'Đ' -- 'đ' + FONTDATA_ITEM(2, 169, 169, fontpage_2_169_169), // 'ĩ' -- 'ĩ' + FONTDATA_ITEM(3, 161, 161, fontpage_3_161_161), // 'ơ' -- 'ơ' + FONTDATA_ITEM(3, 175, 176, fontpage_3_175_176), // 'Ư' -- 'ư' + FONTDATA_ITEM(6, 131, 131, fontpage_6_131_131), // '̃' -- '̃' + FONTDATA_ITEM(6, 137, 137, fontpage_6_137_137), // '̉' -- '̉' + FONTDATA_ITEM(6, 163, 163, fontpage_6_163_163), // '̣' -- '̣' + FONTDATA_ITEM(6, 192, 193, fontpage_6_192_193), // '̀' -- '́' + FONTDATA_ITEM(61, 161, 161, fontpage_61_161_161), // 'ạ' -- 'ạ' + FONTDATA_ITEM(61, 163, 163, fontpage_61_163_163), // 'ả' -- 'ả' + FONTDATA_ITEM(61, 165, 165, fontpage_61_165_165), // 'ấ' -- 'ấ' + FONTDATA_ITEM(61, 167, 167, fontpage_61_167_167), // 'ầ' -- 'ầ' + FONTDATA_ITEM(61, 169, 169, fontpage_61_169_169), // 'ẩ' -- 'ẩ' + FONTDATA_ITEM(61, 173, 173, fontpage_61_173_173), // 'ậ' -- 'ậ' + FONTDATA_ITEM(61, 175, 175, fontpage_61_175_175), // 'ắ' -- 'ắ' + FONTDATA_ITEM(61, 177, 177, fontpage_61_177_177), // 'ằ' -- 'ằ' + FONTDATA_ITEM(61, 179, 179, fontpage_61_179_179), // 'ẳ' -- 'ẳ' + FONTDATA_ITEM(61, 181, 181, fontpage_61_181_181), // 'ẵ' -- 'ẵ' + FONTDATA_ITEM(61, 183, 183, fontpage_61_183_183), // 'ặ' -- 'ặ' + FONTDATA_ITEM(61, 191, 191, fontpage_61_191_191), // 'ế' -- 'ế' + FONTDATA_ITEM(61, 193, 193, fontpage_61_193_193), // 'ề' -- 'ề' + FONTDATA_ITEM(61, 195, 195, fontpage_61_195_195), // 'ể' -- 'ể' + FONTDATA_ITEM(61, 199, 199, fontpage_61_199_199), // 'ệ' -- 'ệ' + FONTDATA_ITEM(61, 201, 201, fontpage_61_201_201), // 'ỉ' -- 'ỉ' + FONTDATA_ITEM(61, 203, 203, fontpage_61_203_203), // 'ị' -- 'ị' + FONTDATA_ITEM(61, 205, 205, fontpage_61_205_205), // 'ọ' -- 'ọ' + FONTDATA_ITEM(61, 207, 207, fontpage_61_207_207), // 'ỏ' -- 'ỏ' + FONTDATA_ITEM(61, 209, 209, fontpage_61_209_209), // 'ố' -- 'ố' + FONTDATA_ITEM(61, 211, 211, fontpage_61_211_211), // 'ồ' -- 'ồ' + FONTDATA_ITEM(61, 213, 213, fontpage_61_213_213), // 'ổ' -- 'ổ' + FONTDATA_ITEM(61, 215, 215, fontpage_61_215_215), // 'ỗ' -- 'ỗ' + FONTDATA_ITEM(61, 217, 217, fontpage_61_217_217), // 'ộ' -- 'ộ' + FONTDATA_ITEM(61, 219, 219, fontpage_61_219_219), // 'ớ' -- 'ớ' + FONTDATA_ITEM(61, 221, 221, fontpage_61_221_221), // 'ờ' -- 'ờ' + FONTDATA_ITEM(61, 223, 223, fontpage_61_223_223), // 'ở' -- 'ở' + FONTDATA_ITEM(61, 225, 225, fontpage_61_225_225), // 'ỡ' -- 'ỡ' + FONTDATA_ITEM(61, 227, 227, fontpage_61_227_227), // 'ợ' -- 'ợ' + FONTDATA_ITEM(61, 229, 229, fontpage_61_229_229), // 'ụ' -- 'ụ' + FONTDATA_ITEM(61, 231, 231, fontpage_61_231_231), // 'ủ' -- 'ủ' + FONTDATA_ITEM(61, 233, 233, fontpage_61_233_233), // 'ứ' -- 'ứ' + FONTDATA_ITEM(61, 235, 235, fontpage_61_235_235), // 'ừ' -- 'ừ' + FONTDATA_ITEM(61, 237, 237, fontpage_61_237_237), // 'ử' -- 'ử' + FONTDATA_ITEM(61, 239, 239, fontpage_61_239_239), // 'ữ' -- 'ữ' + FONTDATA_ITEM(61, 241, 241, fontpage_61_241_241), // 'ự' -- 'ự' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_zh_CN.h b/Marlin/src/lcd/dogm/fontdata/langdata_zh_CN.h index 491d480a0150..664fa5f4bfe9 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_zh_CN.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_zh_CN.h @@ -3,7 +3,9 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once + +#include "langdata.h" const u8g_fntpgm_uint8_t fontpage_64_157_157[26] U8G_FONT_SECTION("fontpage_64_157_157") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x9D,0x9D,0x00,0x07,0x00,0x00, @@ -1462,362 +1464,361 @@ const u8g_fntpgm_uint8_t fontpage_510_154_154[30] U8G_FONT_SECTION("fontpage_510 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x9A,0x9A,0x00,0x08,0x00,0x00, 0x00,0x02,0x07,0x07,0x0C,0x06,0x01,0xC0,0xC0,0x00,0x00,0x00,0xC0,0xC0}; -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(64, 157, 157, fontpage_64_157_157), // '”' -- '”' - FONTDATA_ITEM(69, 191, 191, fontpage_69_191_191), // '⊿' -- '⊿' - FONTDATA_ITEM(156, 128, 128, fontpage_156_128_128), // '一' -- '一' - FONTDATA_ITEM(156, 137, 139, fontpage_156_137_139), // '三' -- '下' - FONTDATA_ITEM(156, 141, 141, fontpage_156_141_141), // '不' -- '不' - FONTDATA_ITEM(156, 147, 147, fontpage_156_147_147), // '专' -- '专' - FONTDATA_ITEM(156, 157, 157, fontpage_156_157_157), // '丝' -- '丝' - FONTDATA_ITEM(156, 170, 170, fontpage_156_170_170), // '个' -- '个' - FONTDATA_ITEM(156, 173, 173, fontpage_156_173_173), // '中' -- '中' - FONTDATA_ITEM(156, 186, 187, fontpage_156_186_187), // '为' -- '主' - FONTDATA_ITEM(156, 201, 201, fontpage_156_201_201), // '义' -- '义' - FONTDATA_ITEM(156, 203, 203, fontpage_156_203_203), // '之' -- '之' - FONTDATA_ITEM(157, 134, 134, fontpage_157_134_134), // '了' -- '了' - FONTDATA_ITEM(157, 140, 140, fontpage_157_140_140), // '二' -- '二' - FONTDATA_ITEM(157, 142, 142, fontpage_157_142_142), // '于' -- '于' - FONTDATA_ITEM(157, 164, 164, fontpage_157_164_164), // '交' -- '交' - FONTDATA_ITEM(157, 174, 174, fontpage_157_174_174), // '亮' -- '亮' - FONTDATA_ITEM(157, 206, 206, fontpage_157_206_206), // '从' -- '从' - FONTDATA_ITEM(157, 228, 229, fontpage_157_228_229), // '令' -- '以' - FONTDATA_ITEM(157, 246, 246, fontpage_157_246_246), // '件' -- '件' - FONTDATA_ITEM(157, 253, 253, fontpage_157_253_253), // '份' -- '份' - FONTDATA_ITEM(158, 145, 145, fontpage_158_145_145), // '休' -- '休' - FONTDATA_ITEM(158, 160, 160, fontpage_158_160_160), // '传' -- '传' - FONTDATA_ITEM(158, 205, 206, fontpage_158_205_206), // '位' -- '低' - FONTDATA_ITEM(158, 211, 211, fontpage_158_211_211), // '体' -- '体' - FONTDATA_ITEM(158, 217, 217, fontpage_158_217_217), // '余' -- '余' - FONTDATA_ITEM(158, 220, 220, fontpage_158_220_220), // '作' -- '作' - FONTDATA_ITEM(158, 255, 255, fontpage_158_255_255), // '使' -- '使' - FONTDATA_ITEM(159, 155, 155, fontpage_159_155_155), // '供' -- '供' - FONTDATA_ITEM(159, 181, 181, fontpage_159_181_181), // '侵' -- '侵' - FONTDATA_ITEM(159, 221, 221, fontpage_159_221_221), // '保' -- '保' - FONTDATA_ITEM(159, 225, 225, fontpage_159_225_225), // '信' -- '信' - FONTDATA_ITEM(160, 188, 188, fontpage_160_188_188), // '值' -- '值' - FONTDATA_ITEM(160, 190, 190, fontpage_160_190_190), // '倾' -- '倾' - FONTDATA_ITEM(160, 207, 207, fontpage_160_207_207), // '偏' -- '偏' - FONTDATA_ITEM(160, 220, 220, fontpage_160_220_220), // '停' -- '停' - FONTDATA_ITEM(161, 168, 168, fontpage_161_168_168), // '储' -- '储' - FONTDATA_ITEM(161, 207, 207, fontpage_161_207_207), // '像' -- '像' - FONTDATA_ITEM(162, 197, 197, fontpage_162_197_197), // '充' -- '充' - FONTDATA_ITEM(162, 200, 201, fontpage_162_200_201), // '先' -- '光' - FONTDATA_ITEM(162, 229, 229, fontpage_162_229_229), // '入' -- '入' - FONTDATA_ITEM(162, 232, 232, fontpage_162_232_232), // '全' -- '全' - FONTDATA_ITEM(162, 241, 241, fontpage_162_241_241), // '共' -- '共' - FONTDATA_ITEM(162, 243, 243, fontpage_162_243_243), // '关' -- '关' - FONTDATA_ITEM(162, 247, 247, fontpage_162_247_247), // '具' -- '具' - FONTDATA_ITEM(163, 151, 151, fontpage_163_151_151), // '冗' -- '冗' - FONTDATA_ITEM(163, 183, 183, fontpage_163_183_183), // '冷' -- '冷' - FONTDATA_ITEM(163, 198, 198, fontpage_163_198_198), // '准' -- '准' - FONTDATA_ITEM(163, 250, 251, fontpage_163_250_251), // '出' -- '击' - FONTDATA_ITEM(164, 134, 135, fontpage_164_134_135), // '分' -- '切' - FONTDATA_ITEM(164, 155, 155, fontpage_164_155_155), // '创' -- '创' - FONTDATA_ITEM(164, 157, 157, fontpage_164_157_157), // '初' -- '初' - FONTDATA_ITEM(164, 171, 171, fontpage_164_171_171), // '别' -- '别' - FONTDATA_ITEM(164, 176, 176, fontpage_164_176_176), // '到' -- '到' - FONTDATA_ITEM(164, 182, 183, fontpage_164_182_183), // '制' -- '刷' - FONTDATA_ITEM(164, 242, 242, fontpage_164_242_242), // '割' -- '割' - FONTDATA_ITEM(165, 155, 155, fontpage_165_155_155), // '力' -- '力' - FONTDATA_ITEM(165, 159, 160, fontpage_165_159_160), // '功' -- '加' - FONTDATA_ITEM(165, 168, 168, fontpage_165_168_168), // '动' -- '动' - FONTDATA_ITEM(166, 150, 150, fontpage_166_150_150), // '化' -- '化' - FONTDATA_ITEM(166, 199, 199, fontpage_166_199_199), // '升' -- '升' - FONTDATA_ITEM(166, 202, 202, fontpage_166_202_202), // '半' -- '半' - FONTDATA_ITEM(166, 207, 207, fontpage_166_207_207), // '协' -- '协' - FONTDATA_ITEM(166, 213, 213, fontpage_166_213_213), // '单' -- '单' - FONTDATA_ITEM(166, 225, 225, fontpage_166_225_225), // '卡' -- '卡' - FONTDATA_ITEM(166, 240, 241, fontpage_166_240_241), // '印' -- '危' - FONTDATA_ITEM(166, 244, 244, fontpage_166_244_244), // '却' -- '却' - FONTDATA_ITEM(166, 248, 248, fontpage_166_248_248), // '卸' -- '卸' - FONTDATA_ITEM(167, 139, 139, fontpage_167_139_139), // '压' -- '压' - FONTDATA_ITEM(167, 159, 159, fontpage_167_159_159), // '原' -- '原' - FONTDATA_ITEM(167, 204, 205, fontpage_167_204_205), // '双' -- '反' - FONTDATA_ITEM(167, 214, 214, fontpage_167_214_214), // '取' -- '取' - FONTDATA_ITEM(167, 216, 216, fontpage_167_216_216), // '变' -- '变' - FONTDATA_ITEM(167, 240, 240, fontpage_167_240_240), // '台' -- '台' - FONTDATA_ITEM(168, 131, 131, fontpage_168_131_131), // '吃' -- '吃' - FONTDATA_ITEM(168, 136, 136, fontpage_168_136_136), // '合' -- '合' - FONTDATA_ITEM(168, 141, 142, fontpage_168_141_142), // '名' -- '后' - FONTDATA_ITEM(168, 145, 145, fontpage_168_145_145), // '向' -- '向' - FONTDATA_ITEM(168, 166, 166, fontpage_168_166_166), // '否' -- '否' - FONTDATA_ITEM(168, 175, 175, fontpage_168_175_175), // '启' -- '启' - FONTDATA_ITEM(168, 202, 202, fontpage_168_202_202), // '告' -- '告' - FONTDATA_ITEM(168, 232, 232, fontpage_168_232_232), // '周' -- '周' - FONTDATA_ITEM(168, 253, 253, fontpage_168_253_253), // '命' -- '命' - FONTDATA_ITEM(169, 140, 140, fontpage_169_140_140), // '和' -- '和' - FONTDATA_ITEM(169, 205, 205, fontpage_169_205_205), // '响' -- '响' - FONTDATA_ITEM(171, 183, 183, fontpage_171_183_183), // '喷' -- '喷' - FONTDATA_ITEM(172, 180, 180, fontpage_172_180_180), // '嘴' -- '嘴' - FONTDATA_ITEM(172, 232, 232, fontpage_172_232_232), // '器' -- '器' - FONTDATA_ITEM(172, 244, 244, fontpage_172_244_244), // '噴' -- '噴' - FONTDATA_ITEM(173, 222, 222, fontpage_173_222_222), // '回' -- '回' - FONTDATA_ITEM(173, 224, 224, fontpage_173_224_224), // '因' -- '因' - FONTDATA_ITEM(173, 250, 250, fontpage_173_250_250), // '固' -- '固' - FONTDATA_ITEM(173, 254, 254, fontpage_173_254_254), // '图' -- '图' - FONTDATA_ITEM(174, 168, 168, fontpage_174_168_168), // '在' -- '在' - FONTDATA_ITEM(174, 207, 207, fontpage_174_207_207), // '坏' -- '坏' - FONTDATA_ITEM(174, 215, 215, fontpage_174_215_215), // '块' -- '块' - FONTDATA_ITEM(175, 139, 139, fontpage_175_139_139), // '型' -- '型' - FONTDATA_ITEM(175, 171, 171, fontpage_175_171_171), // '垫' -- '垫' - FONTDATA_ITEM(176, 235, 235, fontpage_176_235_235), // '填' -- '填' - FONTDATA_ITEM(177, 243, 243, fontpage_177_243_243), // '壳' -- '壳' - FONTDATA_ITEM(178, 135, 135, fontpage_178_135_135), // '备' -- '备' - FONTDATA_ITEM(178, 141, 141, fontpage_178_141_141), // '复' -- '复' - FONTDATA_ITEM(178, 150, 150, fontpage_178_150_150), // '外' -- '外' - FONTDATA_ITEM(178, 154, 154, fontpage_178_154_154), // '多' -- '多' - FONTDATA_ITEM(178, 167, 167, fontpage_178_167_167), // '大' -- '大' - FONTDATA_ITEM(178, 169, 170, fontpage_178_169_170), // '天' -- '太' - FONTDATA_ITEM(178, 177, 177, fontpage_178_177_177), // '失' -- '失' - FONTDATA_ITEM(178, 180, 180, fontpage_178_180_180), // '头' -- '头' - FONTDATA_ITEM(178, 253, 253, fontpage_178_253_253), // '好' -- '好' - FONTDATA_ITEM(179, 203, 203, fontpage_179_203_203), // '始' -- '始' - FONTDATA_ITEM(182, 208, 208, fontpage_182_208_208), // '子' -- '子' - FONTDATA_ITEM(182, 216, 216, fontpage_182_216_216), // '存' -- '存' - FONTDATA_ITEM(183, 137, 137, fontpage_183_137_137), // '安' -- '安' - FONTDATA_ITEM(183, 140, 140, fontpage_183_140_140), // '完' -- '完' - FONTDATA_ITEM(183, 154, 154, fontpage_183_154_154), // '定' -- '定' - FONTDATA_ITEM(183, 162, 162, fontpage_183_162_162), // '客' -- '客' - FONTDATA_ITEM(183, 171, 171, fontpage_183_171_171), // '宫' -- '宫' - FONTDATA_ITEM(183, 249, 249, fontpage_183_249_249), // '对' -- '对' - FONTDATA_ITEM(184, 134, 134, fontpage_184_134_134), // '将' -- '将' - FONTDATA_ITEM(184, 143, 143, fontpage_184_143_143), // '小' -- '小' - FONTDATA_ITEM(184, 177, 177, fontpage_184_177_177), // '就' -- '就' - FONTDATA_ITEM(184, 207, 207, fontpage_184_207_207), // '屏' -- '屏' - FONTDATA_ITEM(187, 229, 229, fontpage_187_229_229), // '工' -- '工' - FONTDATA_ITEM(187, 238, 238, fontpage_187_238_238), // '差' -- '差' - FONTDATA_ITEM(187, 242, 242, fontpage_187_242_242), // '已' -- '已' - FONTDATA_ITEM(188, 243, 243, fontpage_188_243_243), // '平' -- '平' - FONTDATA_ITEM(188, 246, 246, fontpage_188_246_246), // '并' -- '并' - FONTDATA_ITEM(189, 138, 138, fontpage_189_138_138), // '床' -- '床' - FONTDATA_ITEM(189, 148, 148, fontpage_189_148_148), // '应' -- '应' - FONTDATA_ITEM(189, 159, 159, fontpage_189_159_159), // '废' -- '废' - FONTDATA_ITEM(189, 166, 166, fontpage_189_166_166), // '度' -- '度' - FONTDATA_ITEM(190, 128, 128, fontpage_190_128_128), // '开' -- '开' - FONTDATA_ITEM(190, 131, 131, fontpage_190_131_131), // '弃' -- '弃' - FONTDATA_ITEM(190, 143, 143, fontpage_190_143_143), // '式' -- '式' - FONTDATA_ITEM(190, 149, 149, fontpage_190_149_149), // '引' -- '引' - FONTDATA_ITEM(190, 185, 185, fontpage_190_185_185), // '弹' -- '弹' - FONTDATA_ITEM(190, 210, 210, fontpage_190_210_210), // '归' -- '归' - FONTDATA_ITEM(191, 132, 133, fontpage_191_132_133), // '径' -- '待' - FONTDATA_ITEM(191, 170, 170, fontpage_191_170_170), // '循' -- '循' - FONTDATA_ITEM(191, 174, 174, fontpage_191_174_174), // '微' -- '微' - FONTDATA_ITEM(191, 195, 195, fontpage_191_195_195), // '心' -- '心' - FONTDATA_ITEM(191, 253, 253, fontpage_191_253_253), // '忽' -- '忽' - FONTDATA_ITEM(192, 167, 167, fontpage_192_167_167), // '性' -- '性' - FONTDATA_ITEM(192, 187, 187, fontpage_192_187_187), // '总' -- '总' - FONTDATA_ITEM(192, 226, 226, fontpage_192_226_226), // '恢' -- '恢' - FONTDATA_ITEM(192, 239, 239, fontpage_192_239_239), // '息' -- '息' - FONTDATA_ITEM(194, 159, 159, fontpage_194_159_159), // '感' -- '感' - FONTDATA_ITEM(196, 143, 144, fontpage_196_143_144), // '戏' -- '成' - FONTDATA_ITEM(196, 183, 183, fontpage_196_183_183), // '户' -- '户' - FONTDATA_ITEM(196, 192, 192, fontpage_196_192_192), // '所' -- '所' - FONTDATA_ITEM(196, 199, 199, fontpage_196_199_199), // '扇' -- '扇' - FONTDATA_ITEM(196, 203, 203, fontpage_196_203_203), // '手' -- '手' - FONTDATA_ITEM(196, 211, 211, fontpage_196_211_211), // '打' -- '打' - FONTDATA_ITEM(196, 231, 231, fontpage_196_231_231), // '执' -- '执' - FONTDATA_ITEM(196, 249, 249, fontpage_196_249_249), // '批' -- '批' - FONTDATA_ITEM(197, 150, 150, fontpage_197_150_150), // '抖' -- '抖' - FONTDATA_ITEM(197, 165, 165, fontpage_197_165_165), // '报' -- '报' - FONTDATA_ITEM(197, 172, 172, fontpage_197_172_172), // '抬' -- '抬' - FONTDATA_ITEM(197, 189, 189, fontpage_197_189_189), // '抽' -- '抽' - FONTDATA_ITEM(197, 212, 212, fontpage_197_212_212), // '拔' -- '拔' - FONTDATA_ITEM(197, 233, 233, fontpage_197_233_233), // '择' -- '择' - FONTDATA_ITEM(198, 137, 137, fontpage_198_137_137), // '按' -- '按' - FONTDATA_ITEM(198, 161, 161, fontpage_198_161_161), // '挡' -- '挡' - FONTDATA_ITEM(198, 164, 164, fontpage_198_164_164), // '挤' -- '挤' - FONTDATA_ITEM(198, 223, 223, fontpage_198_223_223), // '损' -- '损' - FONTDATA_ITEM(198, 226, 226, fontpage_198_226_226), // '换' -- '换' - FONTDATA_ITEM(199, 137, 137, fontpage_199_137_137), // '掉' -- '掉' - FONTDATA_ITEM(199, 162, 162, fontpage_199_162_162), // '探' -- '探' - FONTDATA_ITEM(199, 165, 165, fontpage_199_165_165), // '接' -- '接' - FONTDATA_ITEM(199, 167, 167, fontpage_199_167_167), // '控' -- '控' - FONTDATA_ITEM(199, 208, 208, fontpage_199_208_208), // '提' -- '提' - FONTDATA_ITEM(199, 210, 210, fontpage_199_210_210), // '插' -- '插' - FONTDATA_ITEM(202, 182, 182, fontpage_202_182_182), // '收' -- '收' - FONTDATA_ITEM(202, 190, 190, fontpage_202_190_190), // '放' -- '放' - FONTDATA_ITEM(202, 240, 240, fontpage_202_240_240), // '数' -- '数' - FONTDATA_ITEM(202, 242, 242, fontpage_202_242_242), // '敲' -- '敲' - FONTDATA_ITEM(202, 244, 244, fontpage_202_244_244), // '整' -- '整' - FONTDATA_ITEM(203, 135, 135, fontpage_203_135_135), // '文' -- '文' - FONTDATA_ITEM(203, 153, 153, fontpage_203_153_153), // '料' -- '料' - FONTDATA_ITEM(203, 156, 156, fontpage_203_156_156), // '斜' -- '斜' - FONTDATA_ITEM(203, 173, 173, fontpage_203_173_173), // '断' -- '断' - FONTDATA_ITEM(203, 176, 176, fontpage_203_176_176), // '新' -- '新' - FONTDATA_ITEM(203, 185, 185, fontpage_203_185_185), // '方' -- '方' - FONTDATA_ITEM(203, 224, 224, fontpage_203_224_224), // '无' -- '无' - FONTDATA_ITEM(203, 246, 246, fontpage_203_246_246), // '时' -- '时' - FONTDATA_ITEM(204, 142, 142, fontpage_204_142_142), // '明' -- '明' - FONTDATA_ITEM(204, 175, 175, fontpage_204_175_175), // '是' -- '是' - FONTDATA_ITEM(205, 130, 130, fontpage_205_130_130), // '暂' -- '暂' - FONTDATA_ITEM(205, 171, 171, fontpage_205_171_171), // '暫' -- '暫' - FONTDATA_ITEM(205, 244, 244, fontpage_205_244_244), // '更' -- '更' - FONTDATA_ITEM(206, 128, 128, fontpage_206_128_128), // '最' -- '最' - FONTDATA_ITEM(206, 137, 137, fontpage_206_137_137), // '有' -- '有' - FONTDATA_ITEM(206, 159, 159, fontpage_206_159_159), // '期' -- '期' - FONTDATA_ITEM(206, 186, 186, fontpage_206_186_186), // '机' -- '机' - FONTDATA_ITEM(206, 192, 192, fontpage_206_192_192), // '杀' -- '杀' - FONTDATA_ITEM(206, 223, 223, fontpage_206_223_223), // '束' -- '束' - FONTDATA_ITEM(206, 225, 225, fontpage_206_225_225), // '条' -- '条' - FONTDATA_ITEM(206, 229, 229, fontpage_206_229_229), // '来' -- '来' - FONTDATA_ITEM(206, 255, 255, fontpage_206_255_255), // '板' -- '板' - FONTDATA_ITEM(207, 151, 151, fontpage_207_151_151), // '林' -- '林' - FONTDATA_ITEM(207, 241, 241, fontpage_207_241_241), // '柱' -- '柱' - FONTDATA_ITEM(208, 161, 161, fontpage_208_161_161), // '校' -- '校' - FONTDATA_ITEM(208, 188, 188, fontpage_208_188_188), // '格' -- '格' - FONTDATA_ITEM(209, 175, 175, fontpage_209_175_175), // '梯' -- '梯' - FONTDATA_ITEM(209, 192, 192, fontpage_209_192_192), // '检' -- '检' - FONTDATA_ITEM(211, 253, 253, fontpage_211_253_253), // '槽' -- '槽' - FONTDATA_ITEM(212, 161, 161, fontpage_212_161_161), // '模' -- '模' - FONTDATA_ITEM(212, 217, 217, fontpage_212_217_217), // '橙' -- '橙' - FONTDATA_ITEM(214, 226, 227, fontpage_214_226_227), // '止' -- '正' - FONTDATA_ITEM(214, 229, 229, fontpage_214_229_229), // '步' -- '步' - FONTDATA_ITEM(215, 212, 212, fontpage_215_212_212), // '比' -- '比' - FONTDATA_ITEM(217, 161, 161, fontpage_217_161_161), // '没' -- '没' - FONTDATA_ITEM(217, 226, 226, fontpage_217_226_226), // '波' -- '波' - FONTDATA_ITEM(217, 232, 232, fontpage_217_232_232), // '注' -- '注' - FONTDATA_ITEM(218, 151, 151, fontpage_218_151_151), // '洗' -- '洗' - FONTDATA_ITEM(218, 187, 187, fontpage_218_187_187), // '活' -- '活' - FONTDATA_ITEM(218, 193, 193, fontpage_218_193_193), // '流' -- '流' - FONTDATA_ITEM(218, 203, 203, fontpage_218_203_203), // '测' -- '测' - FONTDATA_ITEM(219, 136, 136, fontpage_219_136_136), // '消' -- '消' - FONTDATA_ITEM(219, 225, 225, fontpage_219_225_225), // '淡' -- '淡' - FONTDATA_ITEM(219, 247, 247, fontpage_219_247_247), // '混' -- '混' - FONTDATA_ITEM(220, 133, 133, fontpage_220_133_133), // '清' -- '清' - FONTDATA_ITEM(220, 169, 169, fontpage_220_169_169), // '温' -- '温' - FONTDATA_ITEM(220, 184, 184, fontpage_220_184_184), // '游' -- '游' - FONTDATA_ITEM(221, 144, 144, fontpage_221_144_144), // '源' -- '源' - FONTDATA_ITEM(221, 162, 162, fontpage_221_162_162), // '溢' -- '溢' - FONTDATA_ITEM(221, 209, 209, fontpage_221_209_209), // '滑' -- '滑' - FONTDATA_ITEM(222, 143, 143, fontpage_222_143_143), // '漏' -- '漏' - FONTDATA_ITEM(223, 192, 192, fontpage_223_192_192), // '激' -- '激' - FONTDATA_ITEM(224, 239, 239, fontpage_224_239_239), // '灯' -- '灯' - FONTDATA_ITEM(225, 185, 185, fontpage_225_185_185), // '点' -- '点' - FONTDATA_ITEM(225, 237, 237, fontpage_225_237_237), // '热' -- '热' - FONTDATA_ITEM(228, 199, 199, fontpage_228_199_199), // '片' -- '片' - FONTDATA_ITEM(228, 233, 233, fontpage_228_233_233), // '物' -- '物' - FONTDATA_ITEM(228, 249, 249, fontpage_228_249_249), // '特' -- '特' - FONTDATA_ITEM(231, 135, 135, fontpage_231_135_135), // '率' -- '率' - FONTDATA_ITEM(231, 175, 175, fontpage_231_175_175), // '环' -- '环' - FONTDATA_ITEM(234, 168, 168, fontpage_234_168_168), // '用' -- '用' - FONTDATA_ITEM(234, 181, 181, fontpage_234_181_181), // '电' -- '电' - FONTDATA_ITEM(234, 229, 229, fontpage_234_229_229), // '略' -- '略' - FONTDATA_ITEM(236, 253, 253, fontpage_236_253_253), // '白' -- '白' - FONTDATA_ITEM(237, 132, 132, fontpage_237_132_132), // '的' -- '的' - FONTDATA_ITEM(237, 209, 209, fontpage_237_209_209), // '监' -- '监' - FONTDATA_ITEM(237, 244, 244, fontpage_237_244_244), // '直' -- '直' - FONTDATA_ITEM(238, 129, 129, fontpage_238_129_129), // '省' -- '省' - FONTDATA_ITEM(238, 160, 160, fontpage_238_160_160), // '眠' -- '眠' - FONTDATA_ITEM(240, 238, 238, fontpage_240_238_238), // '确' -- '确' - FONTDATA_ITEM(243, 187, 187, fontpage_243_187_187), // '离' -- '离' - FONTDATA_ITEM(243, 251, 251, fontpage_243_251_251), // '移' -- '移' - FONTDATA_ITEM(244, 250, 250, fontpage_244_250_250), // '空' -- '空' - FONTDATA_ITEM(245, 239, 239, fontpage_245_239_239), // '端' -- '端' - FONTDATA_ITEM(246, 172, 172, fontpage_246_172_172), // '第' -- '第' - FONTDATA_ITEM(246, 201, 201, fontpage_246_201_201), // '等' -- '等' - FONTDATA_ITEM(247, 128, 128, fontpage_247_128_128), // '简' -- '简' - FONTDATA_ITEM(247, 177, 177, fontpage_247_177_177), // '箱' -- '箱' - FONTDATA_ITEM(248, 251, 251, fontpage_248_251_251), // '类' -- '类' - FONTDATA_ITEM(250, 162, 162, fontpage_250_162_162), // '索' -- '索' - FONTDATA_ITEM(250, 171, 171, fontpage_250_171_171), // '紫' -- '紫' - FONTDATA_ITEM(253, 162, 162, fontpage_253_162_162), // '红' -- '红' - FONTDATA_ITEM(253, 167, 167, fontpage_253_167_167), // '级' -- '级' - FONTDATA_ITEM(253, 191, 191, fontpage_253_191_191), // '线' -- '线' - FONTDATA_ITEM(253, 198, 198, fontpage_253_198_198), // '细' -- '细' - FONTDATA_ITEM(253, 200, 200, fontpage_253_200_200), // '终' -- '终' - FONTDATA_ITEM(253, 211, 211, fontpage_253_211_211), // '结' -- '结' - FONTDATA_ITEM(253, 217, 217, fontpage_253_217_217), // '给' -- '给' - FONTDATA_ITEM(253, 223, 223, fontpage_253_223_223), // '统' -- '统' - FONTDATA_ITEM(253, 231, 231, fontpage_253_231_231), // '继' -- '继' - FONTDATA_ITEM(253, 234, 234, fontpage_253_234_234), // '绪' -- '绪' - FONTDATA_ITEM(253, 237, 237, fontpage_253_237_237), // '续' -- '续' - FONTDATA_ITEM(253, 255, 255, fontpage_253_255_255), // '绿' -- '绿' - FONTDATA_ITEM(254, 150, 150, fontpage_254_150_150), // '编' -- '编' - FONTDATA_ITEM(254, 186, 186, fontpage_254_186_186), // '缺' -- '缺' - FONTDATA_ITEM(254, 209, 209, fontpage_254_209_209), // '网' -- '网' - FONTDATA_ITEM(254, 238, 238, fontpage_254_238_238), // '置' -- '置' - FONTDATA_ITEM(254, 242, 242, fontpage_254_242_242), // '署' -- '署' - FONTDATA_ITEM(256, 133, 133, fontpage_256_133_133), // '者' -- '者' - FONTDATA_ITEM(256, 234, 234, fontpage_256_234_234), // '聪' -- '聪' - FONTDATA_ITEM(257, 253, 253, fontpage_257_253_253), // '能' -- '能' - FONTDATA_ITEM(259, 234, 234, fontpage_259_234_234), // '自' -- '自' - FONTDATA_ITEM(259, 243, 243, fontpage_259_243_243), // '至' -- '至' - FONTDATA_ITEM(263, 220, 220, fontpage_263_220_220), // '菜' -- '菜' - FONTDATA_ITEM(265, 221, 221, fontpage_265_221_221), // '蓝' -- '蓝' - FONTDATA_ITEM(269, 199, 199, fontpage_269_199_199), // '蛇' -- '蛇' - FONTDATA_ITEM(272, 204, 204, fontpage_272_204_204), // '行' -- '行' - FONTDATA_ITEM(273, 171, 171, fontpage_273_171_171), // '被' -- '被' - FONTDATA_ITEM(273, 197, 197, fontpage_273_197_197), // '装' -- '装' - FONTDATA_ITEM(275, 129, 129, fontpage_275_129_129), // '要' -- '要' - FONTDATA_ITEM(275, 210, 210, fontpage_275_210_210), // '角' -- '角' - FONTDATA_ITEM(279, 161, 161, fontpage_279_161_161), // '计' -- '计' - FONTDATA_ITEM(279, 174, 174, fontpage_279_174_174), // '议' -- '议' - FONTDATA_ITEM(279, 190, 190, fontpage_279_190_190), // '设' -- '设' - FONTDATA_ITEM(279, 213, 213, fontpage_279_213_213), // '试' -- '试' - FONTDATA_ITEM(279, 239, 239, fontpage_279_239_239), // '误' -- '误' - FONTDATA_ITEM(279, 247, 247, fontpage_279_247_247), // '请' -- '请' - FONTDATA_ITEM(279, 251, 251, fontpage_279_251_251), // '读' -- '读' - FONTDATA_ITEM(280, 131, 131, fontpage_280_131_131), // '调' -- '调' - FONTDATA_ITEM(282, 165, 165, fontpage_282_165_165), // '败' -- '败' - FONTDATA_ITEM(282, 170, 170, fontpage_282_170_170), // '贪' -- '贪' - FONTDATA_ITEM(282, 247, 247, fontpage_282_247_247), // '起' -- '起' - FONTDATA_ITEM(283, 133, 133, fontpage_283_133_133), // '超' -- '超' - FONTDATA_ITEM(283, 221, 221, fontpage_283_221_221), // '距' -- '距' - FONTDATA_ITEM(286, 236, 236, fontpage_286_236_236), // '转' -- '转' - FONTDATA_ITEM(286, 239, 239, fontpage_286_239_239), // '软' -- '软' - FONTDATA_ITEM(286, 244, 244, fontpage_286_244_244), // '轴' -- '轴' - FONTDATA_ITEM(286, 253, 253, fontpage_286_253_253), // '载' -- '载' - FONTDATA_ITEM(287, 145, 145, fontpage_287_145_145), // '辑' -- '辑' - FONTDATA_ITEM(287, 147, 147, fontpage_287_147_147), // '输' -- '输' - FONTDATA_ITEM(287, 185, 185, fontpage_287_185_185), // '边' -- '边' - FONTDATA_ITEM(287, 193, 193, fontpage_287_193_193), // '迁' -- '迁' - FONTDATA_ITEM(287, 208, 209, fontpage_287_208_209), // '运' -- '近' - FONTDATA_ITEM(287, 212, 212, fontpage_287_212_212), // '返' -- '返' - FONTDATA_ITEM(287, 216, 216, fontpage_287_216_216), // '还' -- '还' - FONTDATA_ITEM(287, 219, 219, fontpage_287_219_219), // '进' -- '进' - FONTDATA_ITEM(287, 222, 222, fontpage_287_222_222), // '连' -- '连' - FONTDATA_ITEM(287, 247, 247, fontpage_287_247_247), // '迷' -- '迷' - FONTDATA_ITEM(288, 128, 128, fontpage_288_128_128), // '退' -- '退' - FONTDATA_ITEM(288, 137, 137, fontpage_288_137_137), // '选' -- '选' - FONTDATA_ITEM(288, 159, 159, fontpage_288_159_159), // '速' -- '速' - FONTDATA_ITEM(289, 232, 232, fontpage_289_232_232), // '部' -- '部' - FONTDATA_ITEM(290, 205, 205, fontpage_290_205_205), // '配' -- '配' - FONTDATA_ITEM(291, 202, 202, fontpage_291_202_202), // '释' -- '释' - FONTDATA_ITEM(291, 205, 205, fontpage_291_205_205), // '重' -- '重' - FONTDATA_ITEM(291, 207, 207, fontpage_291_207_207), // '量' -- '量' - FONTDATA_ITEM(297, 136, 136, fontpage_297_136_136), // '针' -- '针' - FONTDATA_ITEM(297, 174, 174, fontpage_297_174_174), // '钮' -- '钮' - FONTDATA_ITEM(298, 153, 153, fontpage_298_153_153), // '错' -- '错' - FONTDATA_ITEM(298, 220, 220, fontpage_298_220_220), // '镜' -- '镜' - FONTDATA_ITEM(298, 255, 255, fontpage_298_255_255), // '长' -- '长' - FONTDATA_ITEM(299, 237, 237, fontpage_299_237_237), // '闭' -- '闭' - FONTDATA_ITEM(299, 242, 242, fontpage_299_242_242), // '闲' -- '闲' - FONTDATA_ITEM(299, 244, 244, fontpage_299_244_244), // '间' -- '间' - FONTDATA_ITEM(300, 136, 136, fontpage_300_136_136), // '阈' -- '阈' - FONTDATA_ITEM(300, 205, 205, fontpage_300_205_205), // '降' -- '降' - FONTDATA_ITEM(300, 208, 208, fontpage_300_208_208), // '限' -- '限' - FONTDATA_ITEM(300, 228, 228, fontpage_300_228_228), // '除' -- '除' - FONTDATA_ITEM(300, 233, 233, fontpage_300_233_233), // '险' -- '险' - FONTDATA_ITEM(301, 246, 246, fontpage_301_246_246), // '零' -- '零' - FONTDATA_ITEM(302, 128, 128, fontpage_302_128_128), // '需' -- '需' - FONTDATA_ITEM(302, 210, 210, fontpage_302_210_210), // '青' -- '青' - FONTDATA_ITEM(302, 222, 222, fontpage_302_222_222), // '非' -- '非' - FONTDATA_ITEM(302, 224, 224, fontpage_302_224_224), // '靠' -- '靠' - FONTDATA_ITEM(302, 226, 226, fontpage_302_226_226), // '面' -- '面' - FONTDATA_ITEM(304, 245, 245, fontpage_304_245_245), // '页' -- '页' - FONTDATA_ITEM(304, 249, 249, fontpage_304_249_249), // '项' -- '项' - FONTDATA_ITEM(305, 132, 132, fontpage_305_132_132), // '预' -- '预' - FONTDATA_ITEM(305, 145, 145, fontpage_305_145_145), // '频' -- '频' - FONTDATA_ITEM(305, 157, 157, fontpage_305_157_157), // '额' -- '额' - FONTDATA_ITEM(305, 206, 206, fontpage_305_206_206), // '风' -- '风' - FONTDATA_ITEM(306, 241, 241, fontpage_306_241_241), // '饱' -- '饱' - FONTDATA_ITEM(308, 236, 236, fontpage_308_236_236), // '马' -- '马' - FONTDATA_ITEM(308, 241, 241, fontpage_308_241_241), // '驱' -- '驱' - FONTDATA_ITEM(309, 216, 216, fontpage_309_216_216), // '高' -- '高' - FONTDATA_ITEM(317, 196, 196, fontpage_317_196_196), // '黄' -- '黄' - FONTDATA_ITEM(317, 222, 222, fontpage_317_222_222), // '點' -- '點' - FONTDATA_ITEM(318, 208, 208, fontpage_318_208_208), // '齐' -- '齐' - FONTDATA_ITEM(510, 154, 154, fontpage_510_154_154), // ':' -- ':' +static const uxg_fontinfo_t g_fontinfo_zh_CN[] PROGMEM = { + FONTDATA_ITEM(64, 157, 157, fontpage_64_157_157), // '”' -- '”' + FONTDATA_ITEM(69, 191, 191, fontpage_69_191_191), // '⊿' -- '⊿' + FONTDATA_ITEM(156, 128, 128, fontpage_156_128_128), // '一' -- '一' + FONTDATA_ITEM(156, 137, 139, fontpage_156_137_139), // '三' -- '下' + FONTDATA_ITEM(156, 141, 141, fontpage_156_141_141), // '不' -- '不' + FONTDATA_ITEM(156, 147, 147, fontpage_156_147_147), // '专' -- '专' + FONTDATA_ITEM(156, 157, 157, fontpage_156_157_157), // '丝' -- '丝' + FONTDATA_ITEM(156, 170, 170, fontpage_156_170_170), // '个' -- '个' + FONTDATA_ITEM(156, 173, 173, fontpage_156_173_173), // '中' -- '中' + FONTDATA_ITEM(156, 186, 187, fontpage_156_186_187), // '为' -- '主' + FONTDATA_ITEM(156, 201, 201, fontpage_156_201_201), // '义' -- '义' + FONTDATA_ITEM(156, 203, 203, fontpage_156_203_203), // '之' -- '之' + FONTDATA_ITEM(157, 134, 134, fontpage_157_134_134), // '了' -- '了' + FONTDATA_ITEM(157, 140, 140, fontpage_157_140_140), // '二' -- '二' + FONTDATA_ITEM(157, 142, 142, fontpage_157_142_142), // '于' -- '于' + FONTDATA_ITEM(157, 164, 164, fontpage_157_164_164), // '交' -- '交' + FONTDATA_ITEM(157, 174, 174, fontpage_157_174_174), // '亮' -- '亮' + FONTDATA_ITEM(157, 206, 206, fontpage_157_206_206), // '从' -- '从' + FONTDATA_ITEM(157, 228, 229, fontpage_157_228_229), // '令' -- '以' + FONTDATA_ITEM(157, 246, 246, fontpage_157_246_246), // '件' -- '件' + FONTDATA_ITEM(157, 253, 253, fontpage_157_253_253), // '份' -- '份' + FONTDATA_ITEM(158, 145, 145, fontpage_158_145_145), // '休' -- '休' + FONTDATA_ITEM(158, 160, 160, fontpage_158_160_160), // '传' -- '传' + FONTDATA_ITEM(158, 205, 206, fontpage_158_205_206), // '位' -- '低' + FONTDATA_ITEM(158, 211, 211, fontpage_158_211_211), // '体' -- '体' + FONTDATA_ITEM(158, 217, 217, fontpage_158_217_217), // '余' -- '余' + FONTDATA_ITEM(158, 220, 220, fontpage_158_220_220), // '作' -- '作' + FONTDATA_ITEM(158, 255, 255, fontpage_158_255_255), // '使' -- '使' + FONTDATA_ITEM(159, 155, 155, fontpage_159_155_155), // '供' -- '供' + FONTDATA_ITEM(159, 181, 181, fontpage_159_181_181), // '侵' -- '侵' + FONTDATA_ITEM(159, 221, 221, fontpage_159_221_221), // '保' -- '保' + FONTDATA_ITEM(159, 225, 225, fontpage_159_225_225), // '信' -- '信' + FONTDATA_ITEM(160, 188, 188, fontpage_160_188_188), // '值' -- '值' + FONTDATA_ITEM(160, 190, 190, fontpage_160_190_190), // '倾' -- '倾' + FONTDATA_ITEM(160, 207, 207, fontpage_160_207_207), // '偏' -- '偏' + FONTDATA_ITEM(160, 220, 220, fontpage_160_220_220), // '停' -- '停' + FONTDATA_ITEM(161, 168, 168, fontpage_161_168_168), // '储' -- '储' + FONTDATA_ITEM(161, 207, 207, fontpage_161_207_207), // '像' -- '像' + FONTDATA_ITEM(162, 197, 197, fontpage_162_197_197), // '充' -- '充' + FONTDATA_ITEM(162, 200, 201, fontpage_162_200_201), // '先' -- '光' + FONTDATA_ITEM(162, 229, 229, fontpage_162_229_229), // '入' -- '入' + FONTDATA_ITEM(162, 232, 232, fontpage_162_232_232), // '全' -- '全' + FONTDATA_ITEM(162, 241, 241, fontpage_162_241_241), // '共' -- '共' + FONTDATA_ITEM(162, 243, 243, fontpage_162_243_243), // '关' -- '关' + FONTDATA_ITEM(162, 247, 247, fontpage_162_247_247), // '具' -- '具' + FONTDATA_ITEM(163, 151, 151, fontpage_163_151_151), // '冗' -- '冗' + FONTDATA_ITEM(163, 183, 183, fontpage_163_183_183), // '冷' -- '冷' + FONTDATA_ITEM(163, 198, 198, fontpage_163_198_198), // '准' -- '准' + FONTDATA_ITEM(163, 250, 251, fontpage_163_250_251), // '出' -- '击' + FONTDATA_ITEM(164, 134, 135, fontpage_164_134_135), // '分' -- '切' + FONTDATA_ITEM(164, 155, 155, fontpage_164_155_155), // '创' -- '创' + FONTDATA_ITEM(164, 157, 157, fontpage_164_157_157), // '初' -- '初' + FONTDATA_ITEM(164, 171, 171, fontpage_164_171_171), // '别' -- '别' + FONTDATA_ITEM(164, 176, 176, fontpage_164_176_176), // '到' -- '到' + FONTDATA_ITEM(164, 182, 183, fontpage_164_182_183), // '制' -- '刷' + FONTDATA_ITEM(164, 242, 242, fontpage_164_242_242), // '割' -- '割' + FONTDATA_ITEM(165, 155, 155, fontpage_165_155_155), // '力' -- '力' + FONTDATA_ITEM(165, 159, 160, fontpage_165_159_160), // '功' -- '加' + FONTDATA_ITEM(165, 168, 168, fontpage_165_168_168), // '动' -- '动' + FONTDATA_ITEM(166, 150, 150, fontpage_166_150_150), // '化' -- '化' + FONTDATA_ITEM(166, 199, 199, fontpage_166_199_199), // '升' -- '升' + FONTDATA_ITEM(166, 202, 202, fontpage_166_202_202), // '半' -- '半' + FONTDATA_ITEM(166, 207, 207, fontpage_166_207_207), // '协' -- '协' + FONTDATA_ITEM(166, 213, 213, fontpage_166_213_213), // '单' -- '单' + FONTDATA_ITEM(166, 225, 225, fontpage_166_225_225), // '卡' -- '卡' + FONTDATA_ITEM(166, 240, 241, fontpage_166_240_241), // '印' -- '危' + FONTDATA_ITEM(166, 244, 244, fontpage_166_244_244), // '却' -- '却' + FONTDATA_ITEM(166, 248, 248, fontpage_166_248_248), // '卸' -- '卸' + FONTDATA_ITEM(167, 139, 139, fontpage_167_139_139), // '压' -- '压' + FONTDATA_ITEM(167, 159, 159, fontpage_167_159_159), // '原' -- '原' + FONTDATA_ITEM(167, 204, 205, fontpage_167_204_205), // '双' -- '反' + FONTDATA_ITEM(167, 214, 214, fontpage_167_214_214), // '取' -- '取' + FONTDATA_ITEM(167, 216, 216, fontpage_167_216_216), // '变' -- '变' + FONTDATA_ITEM(167, 240, 240, fontpage_167_240_240), // '台' -- '台' + FONTDATA_ITEM(168, 131, 131, fontpage_168_131_131), // '吃' -- '吃' + FONTDATA_ITEM(168, 136, 136, fontpage_168_136_136), // '合' -- '合' + FONTDATA_ITEM(168, 141, 142, fontpage_168_141_142), // '名' -- '后' + FONTDATA_ITEM(168, 145, 145, fontpage_168_145_145), // '向' -- '向' + FONTDATA_ITEM(168, 166, 166, fontpage_168_166_166), // '否' -- '否' + FONTDATA_ITEM(168, 175, 175, fontpage_168_175_175), // '启' -- '启' + FONTDATA_ITEM(168, 202, 202, fontpage_168_202_202), // '告' -- '告' + FONTDATA_ITEM(168, 232, 232, fontpage_168_232_232), // '周' -- '周' + FONTDATA_ITEM(168, 253, 253, fontpage_168_253_253), // '命' -- '命' + FONTDATA_ITEM(169, 140, 140, fontpage_169_140_140), // '和' -- '和' + FONTDATA_ITEM(169, 205, 205, fontpage_169_205_205), // '响' -- '响' + FONTDATA_ITEM(171, 183, 183, fontpage_171_183_183), // '喷' -- '喷' + FONTDATA_ITEM(172, 180, 180, fontpage_172_180_180), // '嘴' -- '嘴' + FONTDATA_ITEM(172, 232, 232, fontpage_172_232_232), // '器' -- '器' + FONTDATA_ITEM(172, 244, 244, fontpage_172_244_244), // '噴' -- '噴' + FONTDATA_ITEM(173, 222, 222, fontpage_173_222_222), // '回' -- '回' + FONTDATA_ITEM(173, 224, 224, fontpage_173_224_224), // '因' -- '因' + FONTDATA_ITEM(173, 250, 250, fontpage_173_250_250), // '固' -- '固' + FONTDATA_ITEM(173, 254, 254, fontpage_173_254_254), // '图' -- '图' + FONTDATA_ITEM(174, 168, 168, fontpage_174_168_168), // '在' -- '在' + FONTDATA_ITEM(174, 207, 207, fontpage_174_207_207), // '坏' -- '坏' + FONTDATA_ITEM(174, 215, 215, fontpage_174_215_215), // '块' -- '块' + FONTDATA_ITEM(175, 139, 139, fontpage_175_139_139), // '型' -- '型' + FONTDATA_ITEM(175, 171, 171, fontpage_175_171_171), // '垫' -- '垫' + FONTDATA_ITEM(176, 235, 235, fontpage_176_235_235), // '填' -- '填' + FONTDATA_ITEM(177, 243, 243, fontpage_177_243_243), // '壳' -- '壳' + FONTDATA_ITEM(178, 135, 135, fontpage_178_135_135), // '备' -- '备' + FONTDATA_ITEM(178, 141, 141, fontpage_178_141_141), // '复' -- '复' + FONTDATA_ITEM(178, 150, 150, fontpage_178_150_150), // '外' -- '外' + FONTDATA_ITEM(178, 154, 154, fontpage_178_154_154), // '多' -- '多' + FONTDATA_ITEM(178, 167, 167, fontpage_178_167_167), // '大' -- '大' + FONTDATA_ITEM(178, 169, 170, fontpage_178_169_170), // '天' -- '太' + FONTDATA_ITEM(178, 177, 177, fontpage_178_177_177), // '失' -- '失' + FONTDATA_ITEM(178, 180, 180, fontpage_178_180_180), // '头' -- '头' + FONTDATA_ITEM(178, 253, 253, fontpage_178_253_253), // '好' -- '好' + FONTDATA_ITEM(179, 203, 203, fontpage_179_203_203), // '始' -- '始' + FONTDATA_ITEM(182, 208, 208, fontpage_182_208_208), // '子' -- '子' + FONTDATA_ITEM(182, 216, 216, fontpage_182_216_216), // '存' -- '存' + FONTDATA_ITEM(183, 137, 137, fontpage_183_137_137), // '安' -- '安' + FONTDATA_ITEM(183, 140, 140, fontpage_183_140_140), // '完' -- '完' + FONTDATA_ITEM(183, 154, 154, fontpage_183_154_154), // '定' -- '定' + FONTDATA_ITEM(183, 162, 162, fontpage_183_162_162), // '客' -- '客' + FONTDATA_ITEM(183, 171, 171, fontpage_183_171_171), // '宫' -- '宫' + FONTDATA_ITEM(183, 249, 249, fontpage_183_249_249), // '对' -- '对' + FONTDATA_ITEM(184, 134, 134, fontpage_184_134_134), // '将' -- '将' + FONTDATA_ITEM(184, 143, 143, fontpage_184_143_143), // '小' -- '小' + FONTDATA_ITEM(184, 177, 177, fontpage_184_177_177), // '就' -- '就' + FONTDATA_ITEM(184, 207, 207, fontpage_184_207_207), // '屏' -- '屏' + FONTDATA_ITEM(187, 229, 229, fontpage_187_229_229), // '工' -- '工' + FONTDATA_ITEM(187, 238, 238, fontpage_187_238_238), // '差' -- '差' + FONTDATA_ITEM(187, 242, 242, fontpage_187_242_242), // '已' -- '已' + FONTDATA_ITEM(188, 243, 243, fontpage_188_243_243), // '平' -- '平' + FONTDATA_ITEM(188, 246, 246, fontpage_188_246_246), // '并' -- '并' + FONTDATA_ITEM(189, 138, 138, fontpage_189_138_138), // '床' -- '床' + FONTDATA_ITEM(189, 148, 148, fontpage_189_148_148), // '应' -- '应' + FONTDATA_ITEM(189, 159, 159, fontpage_189_159_159), // '废' -- '废' + FONTDATA_ITEM(189, 166, 166, fontpage_189_166_166), // '度' -- '度' + FONTDATA_ITEM(190, 128, 128, fontpage_190_128_128), // '开' -- '开' + FONTDATA_ITEM(190, 131, 131, fontpage_190_131_131), // '弃' -- '弃' + FONTDATA_ITEM(190, 143, 143, fontpage_190_143_143), // '式' -- '式' + FONTDATA_ITEM(190, 149, 149, fontpage_190_149_149), // '引' -- '引' + FONTDATA_ITEM(190, 185, 185, fontpage_190_185_185), // '弹' -- '弹' + FONTDATA_ITEM(190, 210, 210, fontpage_190_210_210), // '归' -- '归' + FONTDATA_ITEM(191, 132, 133, fontpage_191_132_133), // '径' -- '待' + FONTDATA_ITEM(191, 170, 170, fontpage_191_170_170), // '循' -- '循' + FONTDATA_ITEM(191, 174, 174, fontpage_191_174_174), // '微' -- '微' + FONTDATA_ITEM(191, 195, 195, fontpage_191_195_195), // '心' -- '心' + FONTDATA_ITEM(191, 253, 253, fontpage_191_253_253), // '忽' -- '忽' + FONTDATA_ITEM(192, 167, 167, fontpage_192_167_167), // '性' -- '性' + FONTDATA_ITEM(192, 187, 187, fontpage_192_187_187), // '总' -- '总' + FONTDATA_ITEM(192, 226, 226, fontpage_192_226_226), // '恢' -- '恢' + FONTDATA_ITEM(192, 239, 239, fontpage_192_239_239), // '息' -- '息' + FONTDATA_ITEM(194, 159, 159, fontpage_194_159_159), // '感' -- '感' + FONTDATA_ITEM(196, 143, 144, fontpage_196_143_144), // '戏' -- '成' + FONTDATA_ITEM(196, 183, 183, fontpage_196_183_183), // '户' -- '户' + FONTDATA_ITEM(196, 192, 192, fontpage_196_192_192), // '所' -- '所' + FONTDATA_ITEM(196, 199, 199, fontpage_196_199_199), // '扇' -- '扇' + FONTDATA_ITEM(196, 203, 203, fontpage_196_203_203), // '手' -- '手' + FONTDATA_ITEM(196, 211, 211, fontpage_196_211_211), // '打' -- '打' + FONTDATA_ITEM(196, 231, 231, fontpage_196_231_231), // '执' -- '执' + FONTDATA_ITEM(196, 249, 249, fontpage_196_249_249), // '批' -- '批' + FONTDATA_ITEM(197, 150, 150, fontpage_197_150_150), // '抖' -- '抖' + FONTDATA_ITEM(197, 165, 165, fontpage_197_165_165), // '报' -- '报' + FONTDATA_ITEM(197, 172, 172, fontpage_197_172_172), // '抬' -- '抬' + FONTDATA_ITEM(197, 189, 189, fontpage_197_189_189), // '抽' -- '抽' + FONTDATA_ITEM(197, 212, 212, fontpage_197_212_212), // '拔' -- '拔' + FONTDATA_ITEM(197, 233, 233, fontpage_197_233_233), // '择' -- '择' + FONTDATA_ITEM(198, 137, 137, fontpage_198_137_137), // '按' -- '按' + FONTDATA_ITEM(198, 161, 161, fontpage_198_161_161), // '挡' -- '挡' + FONTDATA_ITEM(198, 164, 164, fontpage_198_164_164), // '挤' -- '挤' + FONTDATA_ITEM(198, 223, 223, fontpage_198_223_223), // '损' -- '损' + FONTDATA_ITEM(198, 226, 226, fontpage_198_226_226), // '换' -- '换' + FONTDATA_ITEM(199, 137, 137, fontpage_199_137_137), // '掉' -- '掉' + FONTDATA_ITEM(199, 162, 162, fontpage_199_162_162), // '探' -- '探' + FONTDATA_ITEM(199, 165, 165, fontpage_199_165_165), // '接' -- '接' + FONTDATA_ITEM(199, 167, 167, fontpage_199_167_167), // '控' -- '控' + FONTDATA_ITEM(199, 208, 208, fontpage_199_208_208), // '提' -- '提' + FONTDATA_ITEM(199, 210, 210, fontpage_199_210_210), // '插' -- '插' + FONTDATA_ITEM(202, 182, 182, fontpage_202_182_182), // '收' -- '收' + FONTDATA_ITEM(202, 190, 190, fontpage_202_190_190), // '放' -- '放' + FONTDATA_ITEM(202, 240, 240, fontpage_202_240_240), // '数' -- '数' + FONTDATA_ITEM(202, 242, 242, fontpage_202_242_242), // '敲' -- '敲' + FONTDATA_ITEM(202, 244, 244, fontpage_202_244_244), // '整' -- '整' + FONTDATA_ITEM(203, 135, 135, fontpage_203_135_135), // '文' -- '文' + FONTDATA_ITEM(203, 153, 153, fontpage_203_153_153), // '料' -- '料' + FONTDATA_ITEM(203, 156, 156, fontpage_203_156_156), // '斜' -- '斜' + FONTDATA_ITEM(203, 173, 173, fontpage_203_173_173), // '断' -- '断' + FONTDATA_ITEM(203, 176, 176, fontpage_203_176_176), // '新' -- '新' + FONTDATA_ITEM(203, 185, 185, fontpage_203_185_185), // '方' -- '方' + FONTDATA_ITEM(203, 224, 224, fontpage_203_224_224), // '无' -- '无' + FONTDATA_ITEM(203, 246, 246, fontpage_203_246_246), // '时' -- '时' + FONTDATA_ITEM(204, 142, 142, fontpage_204_142_142), // '明' -- '明' + FONTDATA_ITEM(204, 175, 175, fontpage_204_175_175), // '是' -- '是' + FONTDATA_ITEM(205, 130, 130, fontpage_205_130_130), // '暂' -- '暂' + FONTDATA_ITEM(205, 171, 171, fontpage_205_171_171), // '暫' -- '暫' + FONTDATA_ITEM(205, 244, 244, fontpage_205_244_244), // '更' -- '更' + FONTDATA_ITEM(206, 128, 128, fontpage_206_128_128), // '最' -- '最' + FONTDATA_ITEM(206, 137, 137, fontpage_206_137_137), // '有' -- '有' + FONTDATA_ITEM(206, 159, 159, fontpage_206_159_159), // '期' -- '期' + FONTDATA_ITEM(206, 186, 186, fontpage_206_186_186), // '机' -- '机' + FONTDATA_ITEM(206, 192, 192, fontpage_206_192_192), // '杀' -- '杀' + FONTDATA_ITEM(206, 223, 223, fontpage_206_223_223), // '束' -- '束' + FONTDATA_ITEM(206, 225, 225, fontpage_206_225_225), // '条' -- '条' + FONTDATA_ITEM(206, 229, 229, fontpage_206_229_229), // '来' -- '来' + FONTDATA_ITEM(206, 255, 255, fontpage_206_255_255), // '板' -- '板' + FONTDATA_ITEM(207, 151, 151, fontpage_207_151_151), // '林' -- '林' + FONTDATA_ITEM(207, 241, 241, fontpage_207_241_241), // '柱' -- '柱' + FONTDATA_ITEM(208, 161, 161, fontpage_208_161_161), // '校' -- '校' + FONTDATA_ITEM(208, 188, 188, fontpage_208_188_188), // '格' -- '格' + FONTDATA_ITEM(209, 175, 175, fontpage_209_175_175), // '梯' -- '梯' + FONTDATA_ITEM(209, 192, 192, fontpage_209_192_192), // '检' -- '检' + FONTDATA_ITEM(211, 253, 253, fontpage_211_253_253), // '槽' -- '槽' + FONTDATA_ITEM(212, 161, 161, fontpage_212_161_161), // '模' -- '模' + FONTDATA_ITEM(212, 217, 217, fontpage_212_217_217), // '橙' -- '橙' + FONTDATA_ITEM(214, 226, 227, fontpage_214_226_227), // '止' -- '正' + FONTDATA_ITEM(214, 229, 229, fontpage_214_229_229), // '步' -- '步' + FONTDATA_ITEM(215, 212, 212, fontpage_215_212_212), // '比' -- '比' + FONTDATA_ITEM(217, 161, 161, fontpage_217_161_161), // '没' -- '没' + FONTDATA_ITEM(217, 226, 226, fontpage_217_226_226), // '波' -- '波' + FONTDATA_ITEM(217, 232, 232, fontpage_217_232_232), // '注' -- '注' + FONTDATA_ITEM(218, 151, 151, fontpage_218_151_151), // '洗' -- '洗' + FONTDATA_ITEM(218, 187, 187, fontpage_218_187_187), // '活' -- '活' + FONTDATA_ITEM(218, 193, 193, fontpage_218_193_193), // '流' -- '流' + FONTDATA_ITEM(218, 203, 203, fontpage_218_203_203), // '测' -- '测' + FONTDATA_ITEM(219, 136, 136, fontpage_219_136_136), // '消' -- '消' + FONTDATA_ITEM(219, 225, 225, fontpage_219_225_225), // '淡' -- '淡' + FONTDATA_ITEM(219, 247, 247, fontpage_219_247_247), // '混' -- '混' + FONTDATA_ITEM(220, 133, 133, fontpage_220_133_133), // '清' -- '清' + FONTDATA_ITEM(220, 169, 169, fontpage_220_169_169), // '温' -- '温' + FONTDATA_ITEM(220, 184, 184, fontpage_220_184_184), // '游' -- '游' + FONTDATA_ITEM(221, 144, 144, fontpage_221_144_144), // '源' -- '源' + FONTDATA_ITEM(221, 162, 162, fontpage_221_162_162), // '溢' -- '溢' + FONTDATA_ITEM(221, 209, 209, fontpage_221_209_209), // '滑' -- '滑' + FONTDATA_ITEM(222, 143, 143, fontpage_222_143_143), // '漏' -- '漏' + FONTDATA_ITEM(223, 192, 192, fontpage_223_192_192), // '激' -- '激' + FONTDATA_ITEM(224, 239, 239, fontpage_224_239_239), // '灯' -- '灯' + FONTDATA_ITEM(225, 185, 185, fontpage_225_185_185), // '点' -- '点' + FONTDATA_ITEM(225, 237, 237, fontpage_225_237_237), // '热' -- '热' + FONTDATA_ITEM(228, 199, 199, fontpage_228_199_199), // '片' -- '片' + FONTDATA_ITEM(228, 233, 233, fontpage_228_233_233), // '物' -- '物' + FONTDATA_ITEM(228, 249, 249, fontpage_228_249_249), // '特' -- '特' + FONTDATA_ITEM(231, 135, 135, fontpage_231_135_135), // '率' -- '率' + FONTDATA_ITEM(231, 175, 175, fontpage_231_175_175), // '环' -- '环' + FONTDATA_ITEM(234, 168, 168, fontpage_234_168_168), // '用' -- '用' + FONTDATA_ITEM(234, 181, 181, fontpage_234_181_181), // '电' -- '电' + FONTDATA_ITEM(234, 229, 229, fontpage_234_229_229), // '略' -- '略' + FONTDATA_ITEM(236, 253, 253, fontpage_236_253_253), // '白' -- '白' + FONTDATA_ITEM(237, 132, 132, fontpage_237_132_132), // '的' -- '的' + FONTDATA_ITEM(237, 209, 209, fontpage_237_209_209), // '监' -- '监' + FONTDATA_ITEM(237, 244, 244, fontpage_237_244_244), // '直' -- '直' + FONTDATA_ITEM(238, 129, 129, fontpage_238_129_129), // '省' -- '省' + FONTDATA_ITEM(238, 160, 160, fontpage_238_160_160), // '眠' -- '眠' + FONTDATA_ITEM(240, 238, 238, fontpage_240_238_238), // '确' -- '确' + FONTDATA_ITEM(243, 187, 187, fontpage_243_187_187), // '离' -- '离' + FONTDATA_ITEM(243, 251, 251, fontpage_243_251_251), // '移' -- '移' + FONTDATA_ITEM(244, 250, 250, fontpage_244_250_250), // '空' -- '空' + FONTDATA_ITEM(245, 239, 239, fontpage_245_239_239), // '端' -- '端' + FONTDATA_ITEM(246, 172, 172, fontpage_246_172_172), // '第' -- '第' + FONTDATA_ITEM(246, 201, 201, fontpage_246_201_201), // '等' -- '等' + FONTDATA_ITEM(247, 128, 128, fontpage_247_128_128), // '简' -- '简' + FONTDATA_ITEM(247, 177, 177, fontpage_247_177_177), // '箱' -- '箱' + FONTDATA_ITEM(248, 251, 251, fontpage_248_251_251), // '类' -- '类' + FONTDATA_ITEM(250, 162, 162, fontpage_250_162_162), // '索' -- '索' + FONTDATA_ITEM(250, 171, 171, fontpage_250_171_171), // '紫' -- '紫' + FONTDATA_ITEM(253, 162, 162, fontpage_253_162_162), // '红' -- '红' + FONTDATA_ITEM(253, 167, 167, fontpage_253_167_167), // '级' -- '级' + FONTDATA_ITEM(253, 191, 191, fontpage_253_191_191), // '线' -- '线' + FONTDATA_ITEM(253, 198, 198, fontpage_253_198_198), // '细' -- '细' + FONTDATA_ITEM(253, 200, 200, fontpage_253_200_200), // '终' -- '终' + FONTDATA_ITEM(253, 211, 211, fontpage_253_211_211), // '结' -- '结' + FONTDATA_ITEM(253, 217, 217, fontpage_253_217_217), // '给' -- '给' + FONTDATA_ITEM(253, 223, 223, fontpage_253_223_223), // '统' -- '统' + FONTDATA_ITEM(253, 231, 231, fontpage_253_231_231), // '继' -- '继' + FONTDATA_ITEM(253, 234, 234, fontpage_253_234_234), // '绪' -- '绪' + FONTDATA_ITEM(253, 237, 237, fontpage_253_237_237), // '续' -- '续' + FONTDATA_ITEM(253, 255, 255, fontpage_253_255_255), // '绿' -- '绿' + FONTDATA_ITEM(254, 150, 150, fontpage_254_150_150), // '编' -- '编' + FONTDATA_ITEM(254, 186, 186, fontpage_254_186_186), // '缺' -- '缺' + FONTDATA_ITEM(254, 209, 209, fontpage_254_209_209), // '网' -- '网' + FONTDATA_ITEM(254, 238, 238, fontpage_254_238_238), // '置' -- '置' + FONTDATA_ITEM(254, 242, 242, fontpage_254_242_242), // '署' -- '署' + FONTDATA_ITEM(256, 133, 133, fontpage_256_133_133), // '者' -- '者' + FONTDATA_ITEM(256, 234, 234, fontpage_256_234_234), // '聪' -- '聪' + FONTDATA_ITEM(257, 253, 253, fontpage_257_253_253), // '能' -- '能' + FONTDATA_ITEM(259, 234, 234, fontpage_259_234_234), // '自' -- '自' + FONTDATA_ITEM(259, 243, 243, fontpage_259_243_243), // '至' -- '至' + FONTDATA_ITEM(263, 220, 220, fontpage_263_220_220), // '菜' -- '菜' + FONTDATA_ITEM(265, 221, 221, fontpage_265_221_221), // '蓝' -- '蓝' + FONTDATA_ITEM(269, 199, 199, fontpage_269_199_199), // '蛇' -- '蛇' + FONTDATA_ITEM(272, 204, 204, fontpage_272_204_204), // '行' -- '行' + FONTDATA_ITEM(273, 171, 171, fontpage_273_171_171), // '被' -- '被' + FONTDATA_ITEM(273, 197, 197, fontpage_273_197_197), // '装' -- '装' + FONTDATA_ITEM(275, 129, 129, fontpage_275_129_129), // '要' -- '要' + FONTDATA_ITEM(275, 210, 210, fontpage_275_210_210), // '角' -- '角' + FONTDATA_ITEM(279, 161, 161, fontpage_279_161_161), // '计' -- '计' + FONTDATA_ITEM(279, 174, 174, fontpage_279_174_174), // '议' -- '议' + FONTDATA_ITEM(279, 190, 190, fontpage_279_190_190), // '设' -- '设' + FONTDATA_ITEM(279, 213, 213, fontpage_279_213_213), // '试' -- '试' + FONTDATA_ITEM(279, 239, 239, fontpage_279_239_239), // '误' -- '误' + FONTDATA_ITEM(279, 247, 247, fontpage_279_247_247), // '请' -- '请' + FONTDATA_ITEM(279, 251, 251, fontpage_279_251_251), // '读' -- '读' + FONTDATA_ITEM(280, 131, 131, fontpage_280_131_131), // '调' -- '调' + FONTDATA_ITEM(282, 165, 165, fontpage_282_165_165), // '败' -- '败' + FONTDATA_ITEM(282, 170, 170, fontpage_282_170_170), // '贪' -- '贪' + FONTDATA_ITEM(282, 247, 247, fontpage_282_247_247), // '起' -- '起' + FONTDATA_ITEM(283, 133, 133, fontpage_283_133_133), // '超' -- '超' + FONTDATA_ITEM(283, 221, 221, fontpage_283_221_221), // '距' -- '距' + FONTDATA_ITEM(286, 236, 236, fontpage_286_236_236), // '转' -- '转' + FONTDATA_ITEM(286, 239, 239, fontpage_286_239_239), // '软' -- '软' + FONTDATA_ITEM(286, 244, 244, fontpage_286_244_244), // '轴' -- '轴' + FONTDATA_ITEM(286, 253, 253, fontpage_286_253_253), // '载' -- '载' + FONTDATA_ITEM(287, 145, 145, fontpage_287_145_145), // '辑' -- '辑' + FONTDATA_ITEM(287, 147, 147, fontpage_287_147_147), // '输' -- '输' + FONTDATA_ITEM(287, 185, 185, fontpage_287_185_185), // '边' -- '边' + FONTDATA_ITEM(287, 193, 193, fontpage_287_193_193), // '迁' -- '迁' + FONTDATA_ITEM(287, 208, 209, fontpage_287_208_209), // '运' -- '近' + FONTDATA_ITEM(287, 212, 212, fontpage_287_212_212), // '返' -- '返' + FONTDATA_ITEM(287, 216, 216, fontpage_287_216_216), // '还' -- '还' + FONTDATA_ITEM(287, 219, 219, fontpage_287_219_219), // '进' -- '进' + FONTDATA_ITEM(287, 222, 222, fontpage_287_222_222), // '连' -- '连' + FONTDATA_ITEM(287, 247, 247, fontpage_287_247_247), // '迷' -- '迷' + FONTDATA_ITEM(288, 128, 128, fontpage_288_128_128), // '退' -- '退' + FONTDATA_ITEM(288, 137, 137, fontpage_288_137_137), // '选' -- '选' + FONTDATA_ITEM(288, 159, 159, fontpage_288_159_159), // '速' -- '速' + FONTDATA_ITEM(289, 232, 232, fontpage_289_232_232), // '部' -- '部' + FONTDATA_ITEM(290, 205, 205, fontpage_290_205_205), // '配' -- '配' + FONTDATA_ITEM(291, 202, 202, fontpage_291_202_202), // '释' -- '释' + FONTDATA_ITEM(291, 205, 205, fontpage_291_205_205), // '重' -- '重' + FONTDATA_ITEM(291, 207, 207, fontpage_291_207_207), // '量' -- '量' + FONTDATA_ITEM(297, 136, 136, fontpage_297_136_136), // '针' -- '针' + FONTDATA_ITEM(297, 174, 174, fontpage_297_174_174), // '钮' -- '钮' + FONTDATA_ITEM(298, 153, 153, fontpage_298_153_153), // '错' -- '错' + FONTDATA_ITEM(298, 220, 220, fontpage_298_220_220), // '镜' -- '镜' + FONTDATA_ITEM(298, 255, 255, fontpage_298_255_255), // '长' -- '长' + FONTDATA_ITEM(299, 237, 237, fontpage_299_237_237), // '闭' -- '闭' + FONTDATA_ITEM(299, 242, 242, fontpage_299_242_242), // '闲' -- '闲' + FONTDATA_ITEM(299, 244, 244, fontpage_299_244_244), // '间' -- '间' + FONTDATA_ITEM(300, 136, 136, fontpage_300_136_136), // '阈' -- '阈' + FONTDATA_ITEM(300, 205, 205, fontpage_300_205_205), // '降' -- '降' + FONTDATA_ITEM(300, 208, 208, fontpage_300_208_208), // '限' -- '限' + FONTDATA_ITEM(300, 228, 228, fontpage_300_228_228), // '除' -- '除' + FONTDATA_ITEM(300, 233, 233, fontpage_300_233_233), // '险' -- '险' + FONTDATA_ITEM(301, 246, 246, fontpage_301_246_246), // '零' -- '零' + FONTDATA_ITEM(302, 128, 128, fontpage_302_128_128), // '需' -- '需' + FONTDATA_ITEM(302, 210, 210, fontpage_302_210_210), // '青' -- '青' + FONTDATA_ITEM(302, 222, 222, fontpage_302_222_222), // '非' -- '非' + FONTDATA_ITEM(302, 224, 224, fontpage_302_224_224), // '靠' -- '靠' + FONTDATA_ITEM(302, 226, 226, fontpage_302_226_226), // '面' -- '面' + FONTDATA_ITEM(304, 245, 245, fontpage_304_245_245), // '页' -- '页' + FONTDATA_ITEM(304, 249, 249, fontpage_304_249_249), // '项' -- '项' + FONTDATA_ITEM(305, 132, 132, fontpage_305_132_132), // '预' -- '预' + FONTDATA_ITEM(305, 145, 145, fontpage_305_145_145), // '频' -- '频' + FONTDATA_ITEM(305, 157, 157, fontpage_305_157_157), // '额' -- '额' + FONTDATA_ITEM(305, 206, 206, fontpage_305_206_206), // '风' -- '风' + FONTDATA_ITEM(306, 241, 241, fontpage_306_241_241), // '饱' -- '饱' + FONTDATA_ITEM(308, 236, 236, fontpage_308_236_236), // '马' -- '马' + FONTDATA_ITEM(308, 241, 241, fontpage_308_241_241), // '驱' -- '驱' + FONTDATA_ITEM(309, 216, 216, fontpage_309_216_216), // '高' -- '高' + FONTDATA_ITEM(317, 196, 196, fontpage_317_196_196), // '黄' -- '黄' + FONTDATA_ITEM(317, 222, 222, fontpage_317_222_222), // '點' -- '點' + FONTDATA_ITEM(318, 208, 208, fontpage_318_208_208), // '齐' -- '齐' + FONTDATA_ITEM(510, 154, 154, fontpage_510_154_154), // ':' -- ':' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_zh_TW.h b/Marlin/src/lcd/dogm/fontdata/langdata_zh_TW.h index 8eee544ec81b..093629cd16fa 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_zh_TW.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_zh_TW.h @@ -3,7 +3,9 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once + +#include "langdata.h" const u8g_fntpgm_uint8_t fontpage_69_191_191[28] U8G_FONT_SECTION("fontpage_69_191_191") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0xBF,0xBF,0x00,0x05,0x00,0x00, @@ -1217,305 +1219,304 @@ const u8g_fntpgm_uint8_t fontpage_510_154_154[30] U8G_FONT_SECTION("fontpage_510 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x9A,0x9A,0x00,0x08,0x00,0x00, 0x00,0x02,0x07,0x07,0x0C,0x06,0x01,0xC0,0xC0,0x00,0x00,0x00,0xC0,0xC0}; -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(69, 191, 191, fontpage_69_191_191), // '⊿' -- '⊿' - FONTDATA_ITEM(156, 128, 128, fontpage_156_128_128), // '一' -- '一' - FONTDATA_ITEM(156, 137, 139, fontpage_156_137_139), // '三' -- '下' - FONTDATA_ITEM(156, 141, 141, fontpage_156_141_141), // '不' -- '不' - FONTDATA_ITEM(156, 166, 166, fontpage_156_166_166), // '並' -- '並' - FONTDATA_ITEM(156, 173, 173, fontpage_156_173_173), // '中' -- '中' - FONTDATA_ITEM(156, 187, 187, fontpage_156_187_187), // '主' -- '主' - FONTDATA_ITEM(156, 203, 203, fontpage_156_203_203), // '之' -- '之' - FONTDATA_ITEM(157, 164, 164, fontpage_157_164_164), // '交' -- '交' - FONTDATA_ITEM(157, 174, 174, fontpage_157_174_174), // '亮' -- '亮' - FONTDATA_ITEM(157, 228, 228, fontpage_157_228_228), // '令' -- '令' - FONTDATA_ITEM(157, 246, 246, fontpage_157_246_246), // '件' -- '件' - FONTDATA_ITEM(157, 253, 253, fontpage_157_253_253), // '份' -- '份' - FONTDATA_ITEM(158, 145, 145, fontpage_158_145_145), // '休' -- '休' - FONTDATA_ITEM(158, 205, 206, fontpage_158_205_206), // '位' -- '低' - FONTDATA_ITEM(158, 220, 220, fontpage_158_220_220), // '作' -- '作' - FONTDATA_ITEM(159, 155, 155, fontpage_159_155_155), // '供' -- '供' - FONTDATA_ITEM(159, 221, 221, fontpage_159_221_221), // '保' -- '保' - FONTDATA_ITEM(159, 225, 225, fontpage_159_225_225), // '信' -- '信' - FONTDATA_ITEM(160, 139, 139, fontpage_160_139_139), // '個' -- '個' - FONTDATA_ITEM(160, 188, 188, fontpage_160_188_188), // '值' -- '值' - FONTDATA_ITEM(160, 207, 207, fontpage_160_207_207), // '偏' -- '偏' - FONTDATA_ITEM(160, 220, 220, fontpage_160_220_220), // '停' -- '停' - FONTDATA_ITEM(160, 245, 245, fontpage_160_245_245), // '偵' -- '偵' - FONTDATA_ITEM(161, 153, 153, fontpage_161_153_153), // '備' -- '備' - FONTDATA_ITEM(161, 179, 179, fontpage_161_179_179), // '傳' -- '傳' - FONTDATA_ITEM(161, 190, 190, fontpage_161_190_190), // '傾' -- '傾' - FONTDATA_ITEM(162, 178, 178, fontpage_162_178_178), // '儲' -- '儲' - FONTDATA_ITEM(162, 197, 197, fontpage_162_197_197), // '充' -- '充' - FONTDATA_ITEM(162, 200, 201, fontpage_162_200_201), // '先' -- '光' - FONTDATA_ITEM(162, 229, 229, fontpage_162_229_229), // '入' -- '入' - FONTDATA_ITEM(162, 232, 232, fontpage_162_232_232), // '全' -- '全' - FONTDATA_ITEM(162, 241, 241, fontpage_162_241_241), // '共' -- '共' - FONTDATA_ITEM(162, 247, 247, fontpage_162_247_247), // '具' -- '具' - FONTDATA_ITEM(163, 151, 151, fontpage_163_151_151), // '冗' -- '冗' - FONTDATA_ITEM(163, 183, 183, fontpage_163_183_183), // '冷' -- '冷' - FONTDATA_ITEM(163, 198, 198, fontpage_163_198_198), // '准' -- '准' - FONTDATA_ITEM(163, 250, 250, fontpage_163_250_250), // '出' -- '出' - FONTDATA_ITEM(164, 134, 134, fontpage_164_134_134), // '分' -- '分' - FONTDATA_ITEM(164, 151, 151, fontpage_164_151_151), // '列' -- '列' - FONTDATA_ITEM(164, 157, 157, fontpage_164_157_157), // '初' -- '初' - FONTDATA_ITEM(164, 176, 176, fontpage_164_176_176), // '到' -- '到' - FONTDATA_ITEM(164, 182, 183, fontpage_164_182_183), // '制' -- '刷' - FONTDATA_ITEM(164, 245, 245, fontpage_164_245_245), // '創' -- '創' - FONTDATA_ITEM(165, 155, 155, fontpage_165_155_155), // '力' -- '力' - FONTDATA_ITEM(165, 160, 160, fontpage_165_160_160), // '加' -- '加' - FONTDATA_ITEM(165, 213, 213, fontpage_165_213_213), // '動' -- '動' - FONTDATA_ITEM(166, 150, 150, fontpage_166_150_150), // '化' -- '化' - FONTDATA_ITEM(166, 202, 202, fontpage_166_202_202), // '半' -- '半' - FONTDATA_ITEM(166, 212, 212, fontpage_166_212_212), // '協' -- '協' - FONTDATA_ITEM(166, 225, 225, fontpage_166_225_225), // '卡' -- '卡' - FONTDATA_ITEM(166, 240, 240, fontpage_166_240_240), // '印' -- '印' - FONTDATA_ITEM(166, 248, 248, fontpage_166_248_248), // '卸' -- '卸' - FONTDATA_ITEM(166, 251, 251, fontpage_166_251_251), // '卻' -- '卻' - FONTDATA_ITEM(167, 159, 159, fontpage_167_159_159), // '原' -- '原' - FONTDATA_ITEM(167, 205, 205, fontpage_167_205_205), // '反' -- '反' - FONTDATA_ITEM(167, 214, 214, fontpage_167_214_214), // '取' -- '取' - FONTDATA_ITEM(167, 240, 240, fontpage_167_240_240), // '台' -- '台' - FONTDATA_ITEM(168, 136, 136, fontpage_168_136_136), // '合' -- '合' - FONTDATA_ITEM(168, 166, 166, fontpage_168_166_166), // '否' -- '否' - FONTDATA_ITEM(168, 202, 202, fontpage_168_202_202), // '告' -- '告' - FONTDATA_ITEM(168, 253, 253, fontpage_168_253_253), // '命' -- '命' - FONTDATA_ITEM(169, 140, 140, fontpage_169_140_140), // '和' -- '和' - FONTDATA_ITEM(170, 223, 223, fontpage_170_223_223), // '啟' -- '啟' - FONTDATA_ITEM(171, 174, 174, fontpage_171_174_174), // '單' -- '單' - FONTDATA_ITEM(172, 180, 180, fontpage_172_180_180), // '嘴' -- '嘴' - FONTDATA_ITEM(172, 232, 232, fontpage_172_232_232), // '器' -- '器' - FONTDATA_ITEM(172, 244, 244, fontpage_172_244_244), // '噴' -- '噴' - FONTDATA_ITEM(173, 222, 222, fontpage_173_222_222), // '回' -- '回' - FONTDATA_ITEM(173, 224, 224, fontpage_173_224_224), // '因' -- '因' - FONTDATA_ITEM(173, 250, 250, fontpage_173_250_250), // '固' -- '固' - FONTDATA_ITEM(174, 150, 150, fontpage_174_150_150), // '圖' -- '圖' - FONTDATA_ITEM(174, 168, 168, fontpage_174_168_168), // '在' -- '在' - FONTDATA_ITEM(175, 139, 139, fontpage_175_139_139), // '型' -- '型' - FONTDATA_ITEM(175, 247, 247, fontpage_175_247_247), // '執' -- '執' - FONTDATA_ITEM(176, 202, 202, fontpage_176_202_202), // '塊' -- '塊' - FONTDATA_ITEM(176, 235, 235, fontpage_176_235_235), // '填' -- '填' - FONTDATA_ITEM(177, 138, 138, fontpage_177_138_138), // '墊' -- '墊' - FONTDATA_ITEM(178, 150, 150, fontpage_178_150_150), // '外' -- '外' - FONTDATA_ITEM(178, 154, 154, fontpage_178_154_154), // '多' -- '多' - FONTDATA_ITEM(178, 160, 160, fontpage_178_160_160), // '夠' -- '夠' - FONTDATA_ITEM(178, 167, 167, fontpage_178_167_167), // '大' -- '大' - FONTDATA_ITEM(178, 169, 170, fontpage_178_169_170), // '天' -- '太' - FONTDATA_ITEM(178, 177, 177, fontpage_178_177_177), // '失' -- '失' - FONTDATA_ITEM(179, 203, 203, fontpage_179_203_203), // '始' -- '始' - FONTDATA_ITEM(181, 146, 146, fontpage_181_146_146), // '媒' -- '媒' - FONTDATA_ITEM(182, 208, 208, fontpage_182_208_208), // '子' -- '子' - FONTDATA_ITEM(182, 216, 216, fontpage_182_216_216), // '存' -- '存' - FONTDATA_ITEM(183, 137, 137, fontpage_183_137_137), // '安' -- '安' - FONTDATA_ITEM(183, 140, 140, fontpage_183_140_140), // '完' -- '完' - FONTDATA_ITEM(183, 154, 154, fontpage_183_154_154), // '定' -- '定' - FONTDATA_ITEM(183, 162, 162, fontpage_183_162_162), // '客' -- '客' - FONTDATA_ITEM(183, 185, 185, fontpage_183_185_185), // '容' -- '容' - FONTDATA_ITEM(184, 141, 141, fontpage_184_141_141), // '對' -- '對' - FONTDATA_ITEM(184, 143, 143, fontpage_184_143_143), // '小' -- '小' - FONTDATA_ITEM(184, 177, 177, fontpage_184_177_177), // '就' -- '就' - FONTDATA_ITEM(187, 229, 229, fontpage_187_229_229), // '工' -- '工' - FONTDATA_ITEM(187, 238, 238, fontpage_187_238_238), // '差' -- '差' - FONTDATA_ITEM(187, 242, 242, fontpage_187_242_242), // '已' -- '已' - FONTDATA_ITEM(188, 243, 243, fontpage_188_243_243), // '平' -- '平' - FONTDATA_ITEM(189, 138, 138, fontpage_189_138_138), // '床' -- '床' - FONTDATA_ITEM(189, 166, 166, fontpage_189_166_166), // '度' -- '度' - FONTDATA_ITEM(189, 226, 226, fontpage_189_226_226), // '廢' -- '廢' - FONTDATA_ITEM(189, 250, 250, fontpage_189_250_250), // '建' -- '建' - FONTDATA_ITEM(190, 149, 149, fontpage_190_149_149), // '引' -- '引' - FONTDATA_ITEM(191, 133, 133, fontpage_191_133_133), // '待' -- '待' - FONTDATA_ITEM(191, 140, 140, fontpage_191_140_140), // '後' -- '後' - FONTDATA_ITEM(191, 145, 145, fontpage_191_145_145), // '徑' -- '徑' - FONTDATA_ITEM(191, 158, 158, fontpage_191_158_158), // '從' -- '從' - FONTDATA_ITEM(191, 169, 169, fontpage_191_169_169), // '復' -- '復' - FONTDATA_ITEM(191, 174, 174, fontpage_191_174_174), // '微' -- '微' - FONTDATA_ITEM(191, 195, 195, fontpage_191_195_195), // '心' -- '心' - FONTDATA_ITEM(192, 167, 167, fontpage_192_167_167), // '性' -- '性' - FONTDATA_ITEM(192, 226, 226, fontpage_192_226_226), // '恢' -- '恢' - FONTDATA_ITEM(192, 239, 239, fontpage_192_239_239), // '息' -- '息' - FONTDATA_ITEM(195, 182, 182, fontpage_195_182_182), // '憶' -- '憶' - FONTDATA_ITEM(195, 201, 201, fontpage_195_201_201), // '應' -- '應' - FONTDATA_ITEM(196, 144, 144, fontpage_196_144_144), // '成' -- '成' - FONTDATA_ITEM(196, 182, 182, fontpage_196_182_182), // '戶' -- '戶' - FONTDATA_ITEM(196, 192, 192, fontpage_196_192_192), // '所' -- '所' - FONTDATA_ITEM(196, 199, 199, fontpage_196_199_199), // '扇' -- '扇' - FONTDATA_ITEM(196, 203, 203, fontpage_196_203_203), // '手' -- '手' - FONTDATA_ITEM(196, 211, 211, fontpage_196_211_211), // '打' -- '打' - FONTDATA_ITEM(196, 249, 249, fontpage_196_249_249), // '批' -- '批' - FONTDATA_ITEM(197, 150, 150, fontpage_197_150_150), // '抖' -- '抖' - FONTDATA_ITEM(197, 189, 189, fontpage_197_189_189), // '抽' -- '抽' - FONTDATA_ITEM(197, 212, 212, fontpage_197_212_212), // '拔' -- '拔' - FONTDATA_ITEM(198, 137, 137, fontpage_198_137_137), // '按' -- '按' - FONTDATA_ITEM(199, 137, 137, fontpage_199_137_137), // '掉' -- '掉' - FONTDATA_ITEM(199, 162, 162, fontpage_199_162_162), // '探' -- '探' - FONTDATA_ITEM(199, 165, 165, fontpage_199_165_165), // '接' -- '接' - FONTDATA_ITEM(199, 167, 167, fontpage_199_167_167), // '控' -- '控' - FONTDATA_ITEM(199, 208, 208, fontpage_199_208_208), // '提' -- '提' - FONTDATA_ITEM(199, 210, 210, fontpage_199_210_210), // '插' -- '插' - FONTDATA_ITEM(199, 219, 219, fontpage_199_219_219), // '換' -- '換' - FONTDATA_ITEM(201, 199, 199, fontpage_201_199_199), // '擇' -- '擇' - FONTDATA_ITEM(201, 202, 203, fontpage_201_202_203), // '擊' -- '擋' - FONTDATA_ITEM(201, 224, 224, fontpage_201_224_224), // '擠' -- '擠' - FONTDATA_ITEM(202, 182, 182, fontpage_202_182_182), // '收' -- '收' - FONTDATA_ITEM(202, 190, 190, fontpage_202_190_190), // '放' -- '放' - FONTDATA_ITEM(202, 215, 215, fontpage_202_215_215), // '敗' -- '敗' - FONTDATA_ITEM(202, 244, 244, fontpage_202_244_244), // '整' -- '整' - FONTDATA_ITEM(202, 248, 248, fontpage_202_248_248), // '數' -- '數' - FONTDATA_ITEM(203, 153, 153, fontpage_203_153_153), // '料' -- '料' - FONTDATA_ITEM(203, 156, 156, fontpage_203_156_156), // '斜' -- '斜' - FONTDATA_ITEM(203, 176, 176, fontpage_203_176_176), // '新' -- '新' - FONTDATA_ITEM(203, 183, 183, fontpage_203_183_183), // '斷' -- '斷' - FONTDATA_ITEM(203, 188, 188, fontpage_203_188_188), // '於' -- '於' - FONTDATA_ITEM(204, 135, 135, fontpage_204_135_135), // '昇' -- '昇' - FONTDATA_ITEM(204, 142, 142, fontpage_204_142_142), // '明' -- '明' - FONTDATA_ITEM(204, 175, 175, fontpage_204_175_175), // '是' -- '是' - FONTDATA_ITEM(204, 194, 194, fontpage_204_194_194), // '時' -- '時' - FONTDATA_ITEM(205, 171, 171, fontpage_205_171_171), // '暫' -- '暫' - FONTDATA_ITEM(205, 244, 244, fontpage_205_244_244), // '更' -- '更' - FONTDATA_ITEM(206, 128, 128, fontpage_206_128_128), // '最' -- '最' - FONTDATA_ITEM(206, 137, 137, fontpage_206_137_137), // '有' -- '有' - FONTDATA_ITEM(206, 255, 255, fontpage_206_255_255), // '板' -- '板' - FONTDATA_ITEM(207, 241, 241, fontpage_207_241_241), // '柱' -- '柱' - FONTDATA_ITEM(208, 161, 161, fontpage_208_161_161), // '校' -- '校' - FONTDATA_ITEM(208, 188, 188, fontpage_208_188_188), // '格' -- '格' - FONTDATA_ITEM(209, 157, 157, fontpage_209_157_157), // '條' -- '條' - FONTDATA_ITEM(209, 196, 196, fontpage_209_196_196), // '棄' -- '棄' - FONTDATA_ITEM(211, 253, 253, fontpage_211_253_253), // '槽' -- '槽' - FONTDATA_ITEM(212, 217, 217, fontpage_212_217_217), // '橙' -- '橙' - FONTDATA_ITEM(212, 223, 223, fontpage_212_223_223), // '機' -- '機' - FONTDATA_ITEM(213, 162, 162, fontpage_213_162_162), // '檢' -- '檢' - FONTDATA_ITEM(214, 226, 227, fontpage_214_226_227), // '止' -- '正' - FONTDATA_ITEM(214, 229, 229, fontpage_214_229_229), // '步' -- '步' - FONTDATA_ITEM(214, 248, 248, fontpage_214_248_248), // '歸' -- '歸' - FONTDATA_ITEM(215, 188, 188, fontpage_215_188_188), // '殼' -- '殼' - FONTDATA_ITEM(215, 212, 212, fontpage_215_212_212), // '比' -- '比' - FONTDATA_ITEM(217, 146, 146, fontpage_217_146_146), // '沒' -- '沒' - FONTDATA_ITEM(219, 136, 136, fontpage_219_136_136), // '消' -- '消' - FONTDATA_ITEM(219, 225, 225, fontpage_219_225_225), // '淡' -- '淡' - FONTDATA_ITEM(220, 133, 133, fontpage_220_133_133), // '清' -- '清' - FONTDATA_ITEM(220, 172, 172, fontpage_220_172_172), // '測' -- '測' - FONTDATA_ITEM(221, 144, 144, fontpage_221_144_144), // '源' -- '源' - FONTDATA_ITEM(221, 150, 150, fontpage_221_150_150), // '準' -- '準' - FONTDATA_ITEM(221, 171, 171, fontpage_221_171_171), // '溫' -- '溫' - FONTDATA_ITEM(223, 192, 192, fontpage_223_192_192), // '激' -- '激' - FONTDATA_ITEM(226, 161, 161, fontpage_226_161_161), // '無' -- '無' - FONTDATA_ITEM(227, 177, 177, fontpage_227_177_177), // '熱' -- '熱' - FONTDATA_ITEM(227, 200, 200, fontpage_227_200_200), // '燈' -- '燈' - FONTDATA_ITEM(228, 199, 199, fontpage_228_199_199), // '片' -- '片' - FONTDATA_ITEM(228, 233, 233, fontpage_228_233_233), // '物' -- '物' - FONTDATA_ITEM(231, 135, 135, fontpage_231_135_135), // '率' -- '率' - FONTDATA_ITEM(234, 168, 168, fontpage_234_168_168), // '用' -- '用' - FONTDATA_ITEM(234, 204, 204, fontpage_234_204_204), // '界' -- '界' - FONTDATA_ITEM(236, 253, 253, fontpage_236_253_253), // '白' -- '白' - FONTDATA_ITEM(237, 132, 132, fontpage_237_132_132), // '的' -- '的' - FONTDATA_ITEM(237, 227, 227, fontpage_237_227_227), // '監' -- '監' - FONTDATA_ITEM(237, 244, 244, fontpage_237_244_244), // '直' -- '直' - FONTDATA_ITEM(238, 160, 160, fontpage_238_160_160), // '眠' -- '眠' - FONTDATA_ITEM(240, 141, 141, fontpage_240_141_141), // '砍' -- '砍' - FONTDATA_ITEM(241, 186, 186, fontpage_241_186_186), // '確' -- '確' - FONTDATA_ITEM(243, 251, 251, fontpage_243_251_251), // '移' -- '移' - FONTDATA_ITEM(244, 205, 205, fontpage_244_205_205), // '積' -- '積' - FONTDATA_ITEM(245, 239, 239, fontpage_245_239_239), // '端' -- '端' - FONTDATA_ITEM(246, 201, 201, fontpage_246_201_201), // '等' -- '等' - FONTDATA_ITEM(247, 161, 161, fontpage_247_161_161), // '管' -- '管' - FONTDATA_ITEM(247, 177, 177, fontpage_247_177_177), // '箱' -- '箱' - FONTDATA_ITEM(249, 251, 251, fontpage_249_251_251), // '系' -- '系' - FONTDATA_ITEM(250, 133, 133, fontpage_250_133_133), // '紅' -- '紅' - FONTDATA_ITEM(250, 162, 162, fontpage_250_162_162), // '索' -- '索' - FONTDATA_ITEM(250, 171, 171, fontpage_250_171_171), // '紫' -- '紫' - FONTDATA_ITEM(250, 176, 176, fontpage_250_176_176), // '細' -- '細' - FONTDATA_ITEM(250, 194, 194, fontpage_250_194_194), // '終' -- '終' - FONTDATA_ITEM(250, 241, 242, fontpage_250_241_242), // '統' -- '絲' - FONTDATA_ITEM(251, 160, 160, fontpage_251_160_160), // '綠' -- '綠' - FONTDATA_ITEM(251, 178, 178, fontpage_251_178_178), // '網' -- '網' - FONTDATA_ITEM(251, 210, 210, fontpage_251_210_210), // '緒' -- '緒' - FONTDATA_ITEM(251, 218, 218, fontpage_251_218_218), // '線' -- '線' - FONTDATA_ITEM(251, 232, 232, fontpage_251_232_232), // '編' -- '編' - FONTDATA_ITEM(252, 174, 174, fontpage_252_174_174), // '縮' -- '縮' - FONTDATA_ITEM(252, 189, 189, fontpage_252_189_189), // '總' -- '總' - FONTDATA_ITEM(252, 252, 252, fontpage_252_252_252), // '繼' -- '繼' - FONTDATA_ITEM(253, 140, 140, fontpage_253_140_140), // '續' -- '續' - FONTDATA_ITEM(253, 162, 162, fontpage_253_162_162), // '红' -- '红' - FONTDATA_ITEM(254, 238, 238, fontpage_254_238_238), // '置' -- '置' - FONTDATA_ITEM(254, 242, 242, fontpage_254_242_242), // '署' -- '署' - FONTDATA_ITEM(256, 240, 240, fontpage_256_240_240), // '聰' -- '聰' - FONTDATA_ITEM(259, 234, 234, fontpage_259_234_234), // '自' -- '自' - FONTDATA_ITEM(267, 205, 205, fontpage_267_205_205), // '藍' -- '藍' - FONTDATA_ITEM(272, 204, 204, fontpage_272_204_204), // '行' -- '行' - FONTDATA_ITEM(272, 232, 232, fontpage_272_232_232), // '表' -- '表' - FONTDATA_ITEM(273, 171, 171, fontpage_273_171_171), // '被' -- '被' - FONTDATA_ITEM(273, 197, 197, fontpage_273_197_197), // '装' -- '装' - FONTDATA_ITEM(273, 221, 221, fontpage_273_221_221), // '裝' -- '裝' - FONTDATA_ITEM(274, 135, 135, fontpage_274_135_135), // '複' -- '複' - FONTDATA_ITEM(275, 210, 210, fontpage_275_210_210), // '角' -- '角' - FONTDATA_ITEM(276, 136, 136, fontpage_276_136_136), // '計' -- '計' - FONTDATA_ITEM(276, 138, 138, fontpage_276_138_138), // '訊' -- '訊' - FONTDATA_ITEM(276, 152, 152, fontpage_276_152_152), // '記' -- '記' - FONTDATA_ITEM(276, 173, 173, fontpage_276_173_173), // '設' -- '設' - FONTDATA_ITEM(276, 230, 230, fontpage_276_230_230), // '試' -- '試' - FONTDATA_ITEM(277, 141, 141, fontpage_277_141_141), // '認' -- '認' - FONTDATA_ITEM(277, 164, 164, fontpage_277_164_164), // '誤' -- '誤' - FONTDATA_ITEM(277, 191, 191, fontpage_277_191_191), // '調' -- '調' - FONTDATA_ITEM(277, 203, 203, fontpage_277_203_203), // '請' -- '請' - FONTDATA_ITEM(278, 240, 240, fontpage_278_240_240), // '議' -- '議' - FONTDATA_ITEM(279, 128, 128, fontpage_279_128_128), // '讀' -- '讀' - FONTDATA_ITEM(279, 138, 138, fontpage_279_138_138), // '變' -- '變' - FONTDATA_ITEM(281, 199, 199, fontpage_281_199_199), // '資' -- '資' - FONTDATA_ITEM(283, 221, 221, fontpage_283_221_221), // '距' -- '距' - FONTDATA_ITEM(285, 202, 202, fontpage_285_202_202), // '車' -- '車' - FONTDATA_ITEM(285, 223, 223, fontpage_285_223_223), // '軟' -- '軟' - FONTDATA_ITEM(285, 248, 248, fontpage_285_248_248), // '軸' -- '軸' - FONTDATA_ITEM(286, 137, 137, fontpage_286_137_137), // '載' -- '載' - FONTDATA_ITEM(286, 175, 175, fontpage_286_175_175), // '輯' -- '輯' - FONTDATA_ITEM(286, 184, 184, fontpage_286_184_184), // '輸' -- '輸' - FONTDATA_ITEM(286, 201, 201, fontpage_286_201_201), // '轉' -- '轉' - FONTDATA_ITEM(287, 209, 209, fontpage_287_209_209), // '近' -- '近' - FONTDATA_ITEM(287, 212, 212, fontpage_287_212_212), // '返' -- '返' - FONTDATA_ITEM(288, 128, 128, fontpage_288_128_128), // '退' -- '退' - FONTDATA_ITEM(288, 159, 159, fontpage_288_159_159), // '速' -- '速' - FONTDATA_ITEM(288, 163, 163, fontpage_288_163_163), // '連' -- '連' - FONTDATA_ITEM(288, 178, 178, fontpage_288_178_178), // '進' -- '進' - FONTDATA_ITEM(288, 203, 203, fontpage_288_203_203), // '運' -- '運' - FONTDATA_ITEM(288, 212, 212, fontpage_288_212_212), // '達' -- '達' - FONTDATA_ITEM(288, 248, 248, fontpage_288_248_248), // '選' -- '選' - FONTDATA_ITEM(289, 132, 132, fontpage_289_132_132), // '還' -- '還' - FONTDATA_ITEM(289, 138, 138, fontpage_289_138_138), // '邊' -- '邊' - FONTDATA_ITEM(289, 232, 232, fontpage_289_232_232), // '部' -- '部' - FONTDATA_ITEM(291, 203, 203, fontpage_291_203_203), // '釋' -- '釋' - FONTDATA_ITEM(291, 205, 205, fontpage_291_205_205), // '重' -- '重' - FONTDATA_ITEM(291, 207, 207, fontpage_291_207_207), // '量' -- '量' - FONTDATA_ITEM(291, 221, 221, fontpage_291_221_221), // '針' -- '針' - FONTDATA_ITEM(292, 149, 149, fontpage_292_149_149), // '鈕' -- '鈕' - FONTDATA_ITEM(294, 175, 175, fontpage_294_175_175), // '錯' -- '錯' - FONTDATA_ITEM(294, 245, 245, fontpage_294_245_245), // '鍵' -- '鍵' - FONTDATA_ITEM(298, 247, 247, fontpage_298_247_247), // '長' -- '長' - FONTDATA_ITEM(299, 137, 137, fontpage_299_137_137), // '閉' -- '閉' - FONTDATA_ITEM(299, 139, 139, fontpage_299_139_139), // '開' -- '開' - FONTDATA_ITEM(299, 147, 147, fontpage_299_147_147), // '間' -- '間' - FONTDATA_ITEM(299, 220, 220, fontpage_299_220_220), // '關' -- '關' - FONTDATA_ITEM(300, 205, 205, fontpage_300_205_205), // '降' -- '降' - FONTDATA_ITEM(300, 228, 228, fontpage_300_228_228), // '除' -- '除' - FONTDATA_ITEM(301, 142, 142, fontpage_301_142_142), // '階' -- '階' - FONTDATA_ITEM(301, 217, 217, fontpage_301_217_217), // '雙' -- '雙' - FONTDATA_ITEM(301, 226, 226, fontpage_301_226_226), // '離' -- '離' - FONTDATA_ITEM(301, 251, 251, fontpage_301_251_251), // '電' -- '電' - FONTDATA_ITEM(302, 210, 210, fontpage_302_210_210), // '青' -- '青' - FONTDATA_ITEM(302, 222, 222, fontpage_302_222_222), // '非' -- '非' - FONTDATA_ITEM(302, 226, 226, fontpage_302_226_226), // '面' -- '面' - FONTDATA_ITEM(304, 133, 133, fontpage_304_133_133), // '項' -- '項' - FONTDATA_ITEM(304, 144, 144, fontpage_304_144_144), // '預' -- '預' - FONTDATA_ITEM(304, 205, 205, fontpage_304_205_205), // '額' -- '額' - FONTDATA_ITEM(304, 222, 222, fontpage_304_222_222), // '類' -- '類' - FONTDATA_ITEM(305, 168, 168, fontpage_305_168_168), // '風' -- '風' - FONTDATA_ITEM(305, 253, 253, fontpage_305_253_253), // '飽' -- '飽' - FONTDATA_ITEM(306, 152, 152, fontpage_306_152_152), // '餘' -- '餘' - FONTDATA_ITEM(307, 172, 172, fontpage_307_172_172), // '馬' -- '馬' - FONTDATA_ITEM(308, 197, 197, fontpage_308_197_197), // '驅' -- '驅' - FONTDATA_ITEM(309, 212, 212, fontpage_309_212_212), // '體' -- '體' - FONTDATA_ITEM(309, 216, 216, fontpage_309_216_216), // '高' -- '高' - FONTDATA_ITEM(317, 195, 195, fontpage_317_195_195), // '黃' -- '黃' - FONTDATA_ITEM(317, 222, 222, fontpage_317_222_222), // '點' -- '點' - FONTDATA_ITEM(318, 202, 202, fontpage_318_202_202), // '齊' -- '齊' - FONTDATA_ITEM(510, 154, 154, fontpage_510_154_154), // ':' -- ':' +static const uxg_fontinfo_t g_fontinfo_zh_TW[] PROGMEM = { + FONTDATA_ITEM(69, 191, 191, fontpage_69_191_191), // '⊿' -- '⊿' + FONTDATA_ITEM(156, 128, 128, fontpage_156_128_128), // '一' -- '一' + FONTDATA_ITEM(156, 137, 139, fontpage_156_137_139), // '三' -- '下' + FONTDATA_ITEM(156, 141, 141, fontpage_156_141_141), // '不' -- '不' + FONTDATA_ITEM(156, 166, 166, fontpage_156_166_166), // '並' -- '並' + FONTDATA_ITEM(156, 173, 173, fontpage_156_173_173), // '中' -- '中' + FONTDATA_ITEM(156, 187, 187, fontpage_156_187_187), // '主' -- '主' + FONTDATA_ITEM(156, 203, 203, fontpage_156_203_203), // '之' -- '之' + FONTDATA_ITEM(157, 164, 164, fontpage_157_164_164), // '交' -- '交' + FONTDATA_ITEM(157, 174, 174, fontpage_157_174_174), // '亮' -- '亮' + FONTDATA_ITEM(157, 228, 228, fontpage_157_228_228), // '令' -- '令' + FONTDATA_ITEM(157, 246, 246, fontpage_157_246_246), // '件' -- '件' + FONTDATA_ITEM(157, 253, 253, fontpage_157_253_253), // '份' -- '份' + FONTDATA_ITEM(158, 145, 145, fontpage_158_145_145), // '休' -- '休' + FONTDATA_ITEM(158, 205, 206, fontpage_158_205_206), // '位' -- '低' + FONTDATA_ITEM(158, 220, 220, fontpage_158_220_220), // '作' -- '作' + FONTDATA_ITEM(159, 155, 155, fontpage_159_155_155), // '供' -- '供' + FONTDATA_ITEM(159, 221, 221, fontpage_159_221_221), // '保' -- '保' + FONTDATA_ITEM(159, 225, 225, fontpage_159_225_225), // '信' -- '信' + FONTDATA_ITEM(160, 139, 139, fontpage_160_139_139), // '個' -- '個' + FONTDATA_ITEM(160, 188, 188, fontpage_160_188_188), // '值' -- '值' + FONTDATA_ITEM(160, 207, 207, fontpage_160_207_207), // '偏' -- '偏' + FONTDATA_ITEM(160, 220, 220, fontpage_160_220_220), // '停' -- '停' + FONTDATA_ITEM(160, 245, 245, fontpage_160_245_245), // '偵' -- '偵' + FONTDATA_ITEM(161, 153, 153, fontpage_161_153_153), // '備' -- '備' + FONTDATA_ITEM(161, 179, 179, fontpage_161_179_179), // '傳' -- '傳' + FONTDATA_ITEM(161, 190, 190, fontpage_161_190_190), // '傾' -- '傾' + FONTDATA_ITEM(162, 178, 178, fontpage_162_178_178), // '儲' -- '儲' + FONTDATA_ITEM(162, 197, 197, fontpage_162_197_197), // '充' -- '充' + FONTDATA_ITEM(162, 200, 201, fontpage_162_200_201), // '先' -- '光' + FONTDATA_ITEM(162, 229, 229, fontpage_162_229_229), // '入' -- '入' + FONTDATA_ITEM(162, 232, 232, fontpage_162_232_232), // '全' -- '全' + FONTDATA_ITEM(162, 241, 241, fontpage_162_241_241), // '共' -- '共' + FONTDATA_ITEM(162, 247, 247, fontpage_162_247_247), // '具' -- '具' + FONTDATA_ITEM(163, 151, 151, fontpage_163_151_151), // '冗' -- '冗' + FONTDATA_ITEM(163, 183, 183, fontpage_163_183_183), // '冷' -- '冷' + FONTDATA_ITEM(163, 198, 198, fontpage_163_198_198), // '准' -- '准' + FONTDATA_ITEM(163, 250, 250, fontpage_163_250_250), // '出' -- '出' + FONTDATA_ITEM(164, 134, 134, fontpage_164_134_134), // '分' -- '分' + FONTDATA_ITEM(164, 151, 151, fontpage_164_151_151), // '列' -- '列' + FONTDATA_ITEM(164, 157, 157, fontpage_164_157_157), // '初' -- '初' + FONTDATA_ITEM(164, 176, 176, fontpage_164_176_176), // '到' -- '到' + FONTDATA_ITEM(164, 182, 183, fontpage_164_182_183), // '制' -- '刷' + FONTDATA_ITEM(164, 245, 245, fontpage_164_245_245), // '創' -- '創' + FONTDATA_ITEM(165, 155, 155, fontpage_165_155_155), // '力' -- '力' + FONTDATA_ITEM(165, 160, 160, fontpage_165_160_160), // '加' -- '加' + FONTDATA_ITEM(165, 213, 213, fontpage_165_213_213), // '動' -- '動' + FONTDATA_ITEM(166, 150, 150, fontpage_166_150_150), // '化' -- '化' + FONTDATA_ITEM(166, 202, 202, fontpage_166_202_202), // '半' -- '半' + FONTDATA_ITEM(166, 212, 212, fontpage_166_212_212), // '協' -- '協' + FONTDATA_ITEM(166, 225, 225, fontpage_166_225_225), // '卡' -- '卡' + FONTDATA_ITEM(166, 240, 240, fontpage_166_240_240), // '印' -- '印' + FONTDATA_ITEM(166, 248, 248, fontpage_166_248_248), // '卸' -- '卸' + FONTDATA_ITEM(166, 251, 251, fontpage_166_251_251), // '卻' -- '卻' + FONTDATA_ITEM(167, 159, 159, fontpage_167_159_159), // '原' -- '原' + FONTDATA_ITEM(167, 205, 205, fontpage_167_205_205), // '反' -- '反' + FONTDATA_ITEM(167, 214, 214, fontpage_167_214_214), // '取' -- '取' + FONTDATA_ITEM(167, 240, 240, fontpage_167_240_240), // '台' -- '台' + FONTDATA_ITEM(168, 136, 136, fontpage_168_136_136), // '合' -- '合' + FONTDATA_ITEM(168, 166, 166, fontpage_168_166_166), // '否' -- '否' + FONTDATA_ITEM(168, 202, 202, fontpage_168_202_202), // '告' -- '告' + FONTDATA_ITEM(168, 253, 253, fontpage_168_253_253), // '命' -- '命' + FONTDATA_ITEM(169, 140, 140, fontpage_169_140_140), // '和' -- '和' + FONTDATA_ITEM(170, 223, 223, fontpage_170_223_223), // '啟' -- '啟' + FONTDATA_ITEM(171, 174, 174, fontpage_171_174_174), // '單' -- '單' + FONTDATA_ITEM(172, 180, 180, fontpage_172_180_180), // '嘴' -- '嘴' + FONTDATA_ITEM(172, 232, 232, fontpage_172_232_232), // '器' -- '器' + FONTDATA_ITEM(172, 244, 244, fontpage_172_244_244), // '噴' -- '噴' + FONTDATA_ITEM(173, 222, 222, fontpage_173_222_222), // '回' -- '回' + FONTDATA_ITEM(173, 224, 224, fontpage_173_224_224), // '因' -- '因' + FONTDATA_ITEM(173, 250, 250, fontpage_173_250_250), // '固' -- '固' + FONTDATA_ITEM(174, 150, 150, fontpage_174_150_150), // '圖' -- '圖' + FONTDATA_ITEM(174, 168, 168, fontpage_174_168_168), // '在' -- '在' + FONTDATA_ITEM(175, 139, 139, fontpage_175_139_139), // '型' -- '型' + FONTDATA_ITEM(175, 247, 247, fontpage_175_247_247), // '執' -- '執' + FONTDATA_ITEM(176, 202, 202, fontpage_176_202_202), // '塊' -- '塊' + FONTDATA_ITEM(176, 235, 235, fontpage_176_235_235), // '填' -- '填' + FONTDATA_ITEM(177, 138, 138, fontpage_177_138_138), // '墊' -- '墊' + FONTDATA_ITEM(178, 150, 150, fontpage_178_150_150), // '外' -- '外' + FONTDATA_ITEM(178, 154, 154, fontpage_178_154_154), // '多' -- '多' + FONTDATA_ITEM(178, 160, 160, fontpage_178_160_160), // '夠' -- '夠' + FONTDATA_ITEM(178, 167, 167, fontpage_178_167_167), // '大' -- '大' + FONTDATA_ITEM(178, 169, 170, fontpage_178_169_170), // '天' -- '太' + FONTDATA_ITEM(178, 177, 177, fontpage_178_177_177), // '失' -- '失' + FONTDATA_ITEM(179, 203, 203, fontpage_179_203_203), // '始' -- '始' + FONTDATA_ITEM(181, 146, 146, fontpage_181_146_146), // '媒' -- '媒' + FONTDATA_ITEM(182, 208, 208, fontpage_182_208_208), // '子' -- '子' + FONTDATA_ITEM(182, 216, 216, fontpage_182_216_216), // '存' -- '存' + FONTDATA_ITEM(183, 137, 137, fontpage_183_137_137), // '安' -- '安' + FONTDATA_ITEM(183, 140, 140, fontpage_183_140_140), // '完' -- '完' + FONTDATA_ITEM(183, 154, 154, fontpage_183_154_154), // '定' -- '定' + FONTDATA_ITEM(183, 162, 162, fontpage_183_162_162), // '客' -- '客' + FONTDATA_ITEM(183, 185, 185, fontpage_183_185_185), // '容' -- '容' + FONTDATA_ITEM(184, 141, 141, fontpage_184_141_141), // '對' -- '對' + FONTDATA_ITEM(184, 143, 143, fontpage_184_143_143), // '小' -- '小' + FONTDATA_ITEM(184, 177, 177, fontpage_184_177_177), // '就' -- '就' + FONTDATA_ITEM(187, 229, 229, fontpage_187_229_229), // '工' -- '工' + FONTDATA_ITEM(187, 238, 238, fontpage_187_238_238), // '差' -- '差' + FONTDATA_ITEM(187, 242, 242, fontpage_187_242_242), // '已' -- '已' + FONTDATA_ITEM(188, 243, 243, fontpage_188_243_243), // '平' -- '平' + FONTDATA_ITEM(189, 138, 138, fontpage_189_138_138), // '床' -- '床' + FONTDATA_ITEM(189, 166, 166, fontpage_189_166_166), // '度' -- '度' + FONTDATA_ITEM(189, 226, 226, fontpage_189_226_226), // '廢' -- '廢' + FONTDATA_ITEM(189, 250, 250, fontpage_189_250_250), // '建' -- '建' + FONTDATA_ITEM(190, 149, 149, fontpage_190_149_149), // '引' -- '引' + FONTDATA_ITEM(191, 133, 133, fontpage_191_133_133), // '待' -- '待' + FONTDATA_ITEM(191, 140, 140, fontpage_191_140_140), // '後' -- '後' + FONTDATA_ITEM(191, 145, 145, fontpage_191_145_145), // '徑' -- '徑' + FONTDATA_ITEM(191, 158, 158, fontpage_191_158_158), // '從' -- '從' + FONTDATA_ITEM(191, 169, 169, fontpage_191_169_169), // '復' -- '復' + FONTDATA_ITEM(191, 174, 174, fontpage_191_174_174), // '微' -- '微' + FONTDATA_ITEM(191, 195, 195, fontpage_191_195_195), // '心' -- '心' + FONTDATA_ITEM(192, 167, 167, fontpage_192_167_167), // '性' -- '性' + FONTDATA_ITEM(192, 226, 226, fontpage_192_226_226), // '恢' -- '恢' + FONTDATA_ITEM(192, 239, 239, fontpage_192_239_239), // '息' -- '息' + FONTDATA_ITEM(195, 182, 182, fontpage_195_182_182), // '憶' -- '憶' + FONTDATA_ITEM(195, 201, 201, fontpage_195_201_201), // '應' -- '應' + FONTDATA_ITEM(196, 144, 144, fontpage_196_144_144), // '成' -- '成' + FONTDATA_ITEM(196, 182, 182, fontpage_196_182_182), // '戶' -- '戶' + FONTDATA_ITEM(196, 192, 192, fontpage_196_192_192), // '所' -- '所' + FONTDATA_ITEM(196, 199, 199, fontpage_196_199_199), // '扇' -- '扇' + FONTDATA_ITEM(196, 203, 203, fontpage_196_203_203), // '手' -- '手' + FONTDATA_ITEM(196, 211, 211, fontpage_196_211_211), // '打' -- '打' + FONTDATA_ITEM(196, 249, 249, fontpage_196_249_249), // '批' -- '批' + FONTDATA_ITEM(197, 150, 150, fontpage_197_150_150), // '抖' -- '抖' + FONTDATA_ITEM(197, 189, 189, fontpage_197_189_189), // '抽' -- '抽' + FONTDATA_ITEM(197, 212, 212, fontpage_197_212_212), // '拔' -- '拔' + FONTDATA_ITEM(198, 137, 137, fontpage_198_137_137), // '按' -- '按' + FONTDATA_ITEM(199, 137, 137, fontpage_199_137_137), // '掉' -- '掉' + FONTDATA_ITEM(199, 162, 162, fontpage_199_162_162), // '探' -- '探' + FONTDATA_ITEM(199, 165, 165, fontpage_199_165_165), // '接' -- '接' + FONTDATA_ITEM(199, 167, 167, fontpage_199_167_167), // '控' -- '控' + FONTDATA_ITEM(199, 208, 208, fontpage_199_208_208), // '提' -- '提' + FONTDATA_ITEM(199, 210, 210, fontpage_199_210_210), // '插' -- '插' + FONTDATA_ITEM(199, 219, 219, fontpage_199_219_219), // '換' -- '換' + FONTDATA_ITEM(201, 199, 199, fontpage_201_199_199), // '擇' -- '擇' + FONTDATA_ITEM(201, 202, 203, fontpage_201_202_203), // '擊' -- '擋' + FONTDATA_ITEM(201, 224, 224, fontpage_201_224_224), // '擠' -- '擠' + FONTDATA_ITEM(202, 182, 182, fontpage_202_182_182), // '收' -- '收' + FONTDATA_ITEM(202, 190, 190, fontpage_202_190_190), // '放' -- '放' + FONTDATA_ITEM(202, 215, 215, fontpage_202_215_215), // '敗' -- '敗' + FONTDATA_ITEM(202, 244, 244, fontpage_202_244_244), // '整' -- '整' + FONTDATA_ITEM(202, 248, 248, fontpage_202_248_248), // '數' -- '數' + FONTDATA_ITEM(203, 153, 153, fontpage_203_153_153), // '料' -- '料' + FONTDATA_ITEM(203, 156, 156, fontpage_203_156_156), // '斜' -- '斜' + FONTDATA_ITEM(203, 176, 176, fontpage_203_176_176), // '新' -- '新' + FONTDATA_ITEM(203, 183, 183, fontpage_203_183_183), // '斷' -- '斷' + FONTDATA_ITEM(203, 188, 188, fontpage_203_188_188), // '於' -- '於' + FONTDATA_ITEM(204, 135, 135, fontpage_204_135_135), // '昇' -- '昇' + FONTDATA_ITEM(204, 142, 142, fontpage_204_142_142), // '明' -- '明' + FONTDATA_ITEM(204, 175, 175, fontpage_204_175_175), // '是' -- '是' + FONTDATA_ITEM(204, 194, 194, fontpage_204_194_194), // '時' -- '時' + FONTDATA_ITEM(205, 171, 171, fontpage_205_171_171), // '暫' -- '暫' + FONTDATA_ITEM(205, 244, 244, fontpage_205_244_244), // '更' -- '更' + FONTDATA_ITEM(206, 128, 128, fontpage_206_128_128), // '最' -- '最' + FONTDATA_ITEM(206, 137, 137, fontpage_206_137_137), // '有' -- '有' + FONTDATA_ITEM(206, 255, 255, fontpage_206_255_255), // '板' -- '板' + FONTDATA_ITEM(207, 241, 241, fontpage_207_241_241), // '柱' -- '柱' + FONTDATA_ITEM(208, 161, 161, fontpage_208_161_161), // '校' -- '校' + FONTDATA_ITEM(208, 188, 188, fontpage_208_188_188), // '格' -- '格' + FONTDATA_ITEM(209, 157, 157, fontpage_209_157_157), // '條' -- '條' + FONTDATA_ITEM(209, 196, 196, fontpage_209_196_196), // '棄' -- '棄' + FONTDATA_ITEM(211, 253, 253, fontpage_211_253_253), // '槽' -- '槽' + FONTDATA_ITEM(212, 217, 217, fontpage_212_217_217), // '橙' -- '橙' + FONTDATA_ITEM(212, 223, 223, fontpage_212_223_223), // '機' -- '機' + FONTDATA_ITEM(213, 162, 162, fontpage_213_162_162), // '檢' -- '檢' + FONTDATA_ITEM(214, 226, 227, fontpage_214_226_227), // '止' -- '正' + FONTDATA_ITEM(214, 229, 229, fontpage_214_229_229), // '步' -- '步' + FONTDATA_ITEM(214, 248, 248, fontpage_214_248_248), // '歸' -- '歸' + FONTDATA_ITEM(215, 188, 188, fontpage_215_188_188), // '殼' -- '殼' + FONTDATA_ITEM(215, 212, 212, fontpage_215_212_212), // '比' -- '比' + FONTDATA_ITEM(217, 146, 146, fontpage_217_146_146), // '沒' -- '沒' + FONTDATA_ITEM(219, 136, 136, fontpage_219_136_136), // '消' -- '消' + FONTDATA_ITEM(219, 225, 225, fontpage_219_225_225), // '淡' -- '淡' + FONTDATA_ITEM(220, 133, 133, fontpage_220_133_133), // '清' -- '清' + FONTDATA_ITEM(220, 172, 172, fontpage_220_172_172), // '測' -- '測' + FONTDATA_ITEM(221, 144, 144, fontpage_221_144_144), // '源' -- '源' + FONTDATA_ITEM(221, 150, 150, fontpage_221_150_150), // '準' -- '準' + FONTDATA_ITEM(221, 171, 171, fontpage_221_171_171), // '溫' -- '溫' + FONTDATA_ITEM(223, 192, 192, fontpage_223_192_192), // '激' -- '激' + FONTDATA_ITEM(226, 161, 161, fontpage_226_161_161), // '無' -- '無' + FONTDATA_ITEM(227, 177, 177, fontpage_227_177_177), // '熱' -- '熱' + FONTDATA_ITEM(227, 200, 200, fontpage_227_200_200), // '燈' -- '燈' + FONTDATA_ITEM(228, 199, 199, fontpage_228_199_199), // '片' -- '片' + FONTDATA_ITEM(228, 233, 233, fontpage_228_233_233), // '物' -- '物' + FONTDATA_ITEM(231, 135, 135, fontpage_231_135_135), // '率' -- '率' + FONTDATA_ITEM(234, 168, 168, fontpage_234_168_168), // '用' -- '用' + FONTDATA_ITEM(234, 204, 204, fontpage_234_204_204), // '界' -- '界' + FONTDATA_ITEM(236, 253, 253, fontpage_236_253_253), // '白' -- '白' + FONTDATA_ITEM(237, 132, 132, fontpage_237_132_132), // '的' -- '的' + FONTDATA_ITEM(237, 227, 227, fontpage_237_227_227), // '監' -- '監' + FONTDATA_ITEM(237, 244, 244, fontpage_237_244_244), // '直' -- '直' + FONTDATA_ITEM(238, 160, 160, fontpage_238_160_160), // '眠' -- '眠' + FONTDATA_ITEM(240, 141, 141, fontpage_240_141_141), // '砍' -- '砍' + FONTDATA_ITEM(241, 186, 186, fontpage_241_186_186), // '確' -- '確' + FONTDATA_ITEM(243, 251, 251, fontpage_243_251_251), // '移' -- '移' + FONTDATA_ITEM(244, 205, 205, fontpage_244_205_205), // '積' -- '積' + FONTDATA_ITEM(245, 239, 239, fontpage_245_239_239), // '端' -- '端' + FONTDATA_ITEM(246, 201, 201, fontpage_246_201_201), // '等' -- '等' + FONTDATA_ITEM(247, 161, 161, fontpage_247_161_161), // '管' -- '管' + FONTDATA_ITEM(247, 177, 177, fontpage_247_177_177), // '箱' -- '箱' + FONTDATA_ITEM(249, 251, 251, fontpage_249_251_251), // '系' -- '系' + FONTDATA_ITEM(250, 133, 133, fontpage_250_133_133), // '紅' -- '紅' + FONTDATA_ITEM(250, 162, 162, fontpage_250_162_162), // '索' -- '索' + FONTDATA_ITEM(250, 171, 171, fontpage_250_171_171), // '紫' -- '紫' + FONTDATA_ITEM(250, 176, 176, fontpage_250_176_176), // '細' -- '細' + FONTDATA_ITEM(250, 194, 194, fontpage_250_194_194), // '終' -- '終' + FONTDATA_ITEM(250, 241, 242, fontpage_250_241_242), // '統' -- '絲' + FONTDATA_ITEM(251, 160, 160, fontpage_251_160_160), // '綠' -- '綠' + FONTDATA_ITEM(251, 178, 178, fontpage_251_178_178), // '網' -- '網' + FONTDATA_ITEM(251, 210, 210, fontpage_251_210_210), // '緒' -- '緒' + FONTDATA_ITEM(251, 218, 218, fontpage_251_218_218), // '線' -- '線' + FONTDATA_ITEM(251, 232, 232, fontpage_251_232_232), // '編' -- '編' + FONTDATA_ITEM(252, 174, 174, fontpage_252_174_174), // '縮' -- '縮' + FONTDATA_ITEM(252, 189, 189, fontpage_252_189_189), // '總' -- '總' + FONTDATA_ITEM(252, 252, 252, fontpage_252_252_252), // '繼' -- '繼' + FONTDATA_ITEM(253, 140, 140, fontpage_253_140_140), // '續' -- '續' + FONTDATA_ITEM(253, 162, 162, fontpage_253_162_162), // '红' -- '红' + FONTDATA_ITEM(254, 238, 238, fontpage_254_238_238), // '置' -- '置' + FONTDATA_ITEM(254, 242, 242, fontpage_254_242_242), // '署' -- '署' + FONTDATA_ITEM(256, 240, 240, fontpage_256_240_240), // '聰' -- '聰' + FONTDATA_ITEM(259, 234, 234, fontpage_259_234_234), // '自' -- '自' + FONTDATA_ITEM(267, 205, 205, fontpage_267_205_205), // '藍' -- '藍' + FONTDATA_ITEM(272, 204, 204, fontpage_272_204_204), // '行' -- '行' + FONTDATA_ITEM(272, 232, 232, fontpage_272_232_232), // '表' -- '表' + FONTDATA_ITEM(273, 171, 171, fontpage_273_171_171), // '被' -- '被' + FONTDATA_ITEM(273, 197, 197, fontpage_273_197_197), // '装' -- '装' + FONTDATA_ITEM(273, 221, 221, fontpage_273_221_221), // '裝' -- '裝' + FONTDATA_ITEM(274, 135, 135, fontpage_274_135_135), // '複' -- '複' + FONTDATA_ITEM(275, 210, 210, fontpage_275_210_210), // '角' -- '角' + FONTDATA_ITEM(276, 136, 136, fontpage_276_136_136), // '計' -- '計' + FONTDATA_ITEM(276, 138, 138, fontpage_276_138_138), // '訊' -- '訊' + FONTDATA_ITEM(276, 152, 152, fontpage_276_152_152), // '記' -- '記' + FONTDATA_ITEM(276, 173, 173, fontpage_276_173_173), // '設' -- '設' + FONTDATA_ITEM(276, 230, 230, fontpage_276_230_230), // '試' -- '試' + FONTDATA_ITEM(277, 141, 141, fontpage_277_141_141), // '認' -- '認' + FONTDATA_ITEM(277, 164, 164, fontpage_277_164_164), // '誤' -- '誤' + FONTDATA_ITEM(277, 191, 191, fontpage_277_191_191), // '調' -- '調' + FONTDATA_ITEM(277, 203, 203, fontpage_277_203_203), // '請' -- '請' + FONTDATA_ITEM(278, 240, 240, fontpage_278_240_240), // '議' -- '議' + FONTDATA_ITEM(279, 128, 128, fontpage_279_128_128), // '讀' -- '讀' + FONTDATA_ITEM(279, 138, 138, fontpage_279_138_138), // '變' -- '變' + FONTDATA_ITEM(281, 199, 199, fontpage_281_199_199), // '資' -- '資' + FONTDATA_ITEM(283, 221, 221, fontpage_283_221_221), // '距' -- '距' + FONTDATA_ITEM(285, 202, 202, fontpage_285_202_202), // '車' -- '車' + FONTDATA_ITEM(285, 223, 223, fontpage_285_223_223), // '軟' -- '軟' + FONTDATA_ITEM(285, 248, 248, fontpage_285_248_248), // '軸' -- '軸' + FONTDATA_ITEM(286, 137, 137, fontpage_286_137_137), // '載' -- '載' + FONTDATA_ITEM(286, 175, 175, fontpage_286_175_175), // '輯' -- '輯' + FONTDATA_ITEM(286, 184, 184, fontpage_286_184_184), // '輸' -- '輸' + FONTDATA_ITEM(286, 201, 201, fontpage_286_201_201), // '轉' -- '轉' + FONTDATA_ITEM(287, 209, 209, fontpage_287_209_209), // '近' -- '近' + FONTDATA_ITEM(287, 212, 212, fontpage_287_212_212), // '返' -- '返' + FONTDATA_ITEM(288, 128, 128, fontpage_288_128_128), // '退' -- '退' + FONTDATA_ITEM(288, 159, 159, fontpage_288_159_159), // '速' -- '速' + FONTDATA_ITEM(288, 163, 163, fontpage_288_163_163), // '連' -- '連' + FONTDATA_ITEM(288, 178, 178, fontpage_288_178_178), // '進' -- '進' + FONTDATA_ITEM(288, 203, 203, fontpage_288_203_203), // '運' -- '運' + FONTDATA_ITEM(288, 212, 212, fontpage_288_212_212), // '達' -- '達' + FONTDATA_ITEM(288, 248, 248, fontpage_288_248_248), // '選' -- '選' + FONTDATA_ITEM(289, 132, 132, fontpage_289_132_132), // '還' -- '還' + FONTDATA_ITEM(289, 138, 138, fontpage_289_138_138), // '邊' -- '邊' + FONTDATA_ITEM(289, 232, 232, fontpage_289_232_232), // '部' -- '部' + FONTDATA_ITEM(291, 203, 203, fontpage_291_203_203), // '釋' -- '釋' + FONTDATA_ITEM(291, 205, 205, fontpage_291_205_205), // '重' -- '重' + FONTDATA_ITEM(291, 207, 207, fontpage_291_207_207), // '量' -- '量' + FONTDATA_ITEM(291, 221, 221, fontpage_291_221_221), // '針' -- '針' + FONTDATA_ITEM(292, 149, 149, fontpage_292_149_149), // '鈕' -- '鈕' + FONTDATA_ITEM(294, 175, 175, fontpage_294_175_175), // '錯' -- '錯' + FONTDATA_ITEM(294, 245, 245, fontpage_294_245_245), // '鍵' -- '鍵' + FONTDATA_ITEM(298, 247, 247, fontpage_298_247_247), // '長' -- '長' + FONTDATA_ITEM(299, 137, 137, fontpage_299_137_137), // '閉' -- '閉' + FONTDATA_ITEM(299, 139, 139, fontpage_299_139_139), // '開' -- '開' + FONTDATA_ITEM(299, 147, 147, fontpage_299_147_147), // '間' -- '間' + FONTDATA_ITEM(299, 220, 220, fontpage_299_220_220), // '關' -- '關' + FONTDATA_ITEM(300, 205, 205, fontpage_300_205_205), // '降' -- '降' + FONTDATA_ITEM(300, 228, 228, fontpage_300_228_228), // '除' -- '除' + FONTDATA_ITEM(301, 142, 142, fontpage_301_142_142), // '階' -- '階' + FONTDATA_ITEM(301, 217, 217, fontpage_301_217_217), // '雙' -- '雙' + FONTDATA_ITEM(301, 226, 226, fontpage_301_226_226), // '離' -- '離' + FONTDATA_ITEM(301, 251, 251, fontpage_301_251_251), // '電' -- '電' + FONTDATA_ITEM(302, 210, 210, fontpage_302_210_210), // '青' -- '青' + FONTDATA_ITEM(302, 222, 222, fontpage_302_222_222), // '非' -- '非' + FONTDATA_ITEM(302, 226, 226, fontpage_302_226_226), // '面' -- '面' + FONTDATA_ITEM(304, 133, 133, fontpage_304_133_133), // '項' -- '項' + FONTDATA_ITEM(304, 144, 144, fontpage_304_144_144), // '預' -- '預' + FONTDATA_ITEM(304, 205, 205, fontpage_304_205_205), // '額' -- '額' + FONTDATA_ITEM(304, 222, 222, fontpage_304_222_222), // '類' -- '類' + FONTDATA_ITEM(305, 168, 168, fontpage_305_168_168), // '風' -- '風' + FONTDATA_ITEM(305, 253, 253, fontpage_305_253_253), // '飽' -- '飽' + FONTDATA_ITEM(306, 152, 152, fontpage_306_152_152), // '餘' -- '餘' + FONTDATA_ITEM(307, 172, 172, fontpage_307_172_172), // '馬' -- '馬' + FONTDATA_ITEM(308, 197, 197, fontpage_308_197_197), // '驅' -- '驅' + FONTDATA_ITEM(309, 212, 212, fontpage_309_212_212), // '體' -- '體' + FONTDATA_ITEM(309, 216, 216, fontpage_309_216_216), // '高' -- '高' + FONTDATA_ITEM(317, 195, 195, fontpage_317_195_195), // '黃' -- '黃' + FONTDATA_ITEM(317, 222, 222, fontpage_317_222_222), // '點' -- '點' + FONTDATA_ITEM(318, 202, 202, fontpage_318_202_202), // '齊' -- '齊' + FONTDATA_ITEM(510, 154, 154, fontpage_510_154_154), // ':' -- ':' }; diff --git a/Marlin/src/lcd/dogm/lcdprint_u8g.cpp b/Marlin/src/lcd/dogm/lcdprint_u8g.cpp index a6bdb373dd70..a85dc9f97911 100644 --- a/Marlin/src/lcd/dogm/lcdprint_u8g.cpp +++ b/Marlin/src/lcd/dogm/lcdprint_u8g.cpp @@ -11,9 +11,9 @@ #if HAS_MARLINUI_U8GLIB -#include "ultralcd_DOGM.h" +#include "marlinui_DOGM.h" -#include "../ultralcd.h" +#include "../marlinui.h" #include "../../MarlinCore.h" #include "../fontutils.h" diff --git a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp new file mode 100644 index 000000000000..25e943a14d14 --- /dev/null +++ b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp @@ -0,0 +1,750 @@ +/** + * 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 . + * + */ + +/** + * lcd/dogm/marlinui_DOGM.h + * + * Implementation of the LCD display routines for a DOGM128 graphic display. + * by STB for ErikZalm/Marlin. Common LCD 128x64 pixel graphic displays. + * + * Demonstrator: https://www.reprap.org/wiki/STB_Electronics + * License: https://opensource.org/licenses/BSD-3-Clause + * + * With the use of: + * u8glib by Oliver Kraus + * https://github.com/olikraus/U8glib_Arduino + * License: https://opensource.org/licenses/BSD-3-Clause + */ + +#include "../../inc/MarlinConfigPre.h" + +#if HAS_MARLINUI_U8GLIB + +#include "marlinui_DOGM.h" +#include "u8g_fontutf8.h" + +#if ENABLED(SHOW_BOOTSCREEN) + #include "dogm_Bootscreen.h" +#endif + +#include "../lcdprint.h" +#include "../fontutils.h" +#include "../../libs/numtostr.h" +#include "../marlinui.h" + +#include "../../sd/cardreader.h" +#include "../../module/temperature.h" +#include "../../module/printcounter.h" +#include "../../MarlinCore.h" + +#if ENABLED(SDSUPPORT) + #include "../../libs/duration_t.h" +#endif + +#if ENABLED(AUTO_BED_LEVELING_UBL) + #include "../../feature/bedlevel/bedlevel.h" +#endif + +/** + * Include all needed font files + * (See https://marlinfw.org/docs/development/fonts.html) + */ +#include "fontdata/fontdata_ISO10646_1.h" +#if ENABLED(USE_SMALL_INFOFONT) + #include "fontdata/fontdata_6x9_marlin.h" + #define FONT_STATUSMENU_NAME u8g_font_6x9 +#else + #define FONT_STATUSMENU_NAME MENU_FONT_NAME +#endif + +U8G_CLASS u8g; + +#include LANGUAGE_DATA_INCL(LCD_LANGUAGE) +#ifdef LCD_LANGUAGE_2 + #include LANGUAGE_DATA_INCL(LCD_LANGUAGE_2) +#endif +#ifdef LCD_LANGUAGE_3 + #include LANGUAGE_DATA_INCL(LCD_LANGUAGE_3) +#endif +#ifdef LCD_LANGUAGE_4 + #include LANGUAGE_DATA_INCL(LCD_LANGUAGE_4) +#endif +#ifdef LCD_LANGUAGE_5 + #include LANGUAGE_DATA_INCL(LCD_LANGUAGE_5) +#endif + +#if HAS_LCD_CONTRAST + + int16_t MarlinUI::contrast = DEFAULT_LCD_CONTRAST; + + void MarlinUI::set_contrast(const int16_t value) { + contrast = constrain(value, LCD_CONTRAST_MIN, LCD_CONTRAST_MAX); + u8g.setContrast(contrast); + } + +#endif + +void MarlinUI::set_font(const MarlinFont font_nr) { + static char currentfont = 0; + if (font_nr != currentfont) { + switch ((currentfont = font_nr)) { + case FONT_STATUSMENU : u8g.setFont(FONT_STATUSMENU_NAME); break; + case FONT_EDIT : u8g.setFont(EDIT_FONT_NAME); break; + default: + case FONT_MENU : u8g.setFont(MENU_FONT_NAME); break; + } + } +} + +bool MarlinUI::detected() { return true; } + +#if ENABLED(SHOW_BOOTSCREEN) + + #if ENABLED(SHOW_CUSTOM_BOOTSCREEN) + // Draws a slice of a particular frame of the custom bootscreen, without the u8g loop + void MarlinUI::draw_custom_bootscreen(const uint8_t frame/*=0*/) { + constexpr u8g_uint_t left = u8g_uint_t((LCD_PIXEL_WIDTH - (CUSTOM_BOOTSCREEN_BMPWIDTH)) / 2), + top = u8g_uint_t(CUSTOM_BOOTSCREEN_Y); + #if ENABLED(CUSTOM_BOOTSCREEN_INVERTED) + constexpr u8g_uint_t right = left + CUSTOM_BOOTSCREEN_BMPWIDTH, + bottom = top + CUSTOM_BOOTSCREEN_BMPHEIGHT; + #endif + + #if ENABLED(CUSTOM_BOOTSCREEN_ANIMATED) + #if ENABLED(CUSTOM_BOOTSCREEN_ANIMATED_FRAME_TIME) + const u8g_pgm_uint8_t * const bmp = (u8g_pgm_uint8_t*)pgm_read_ptr(&custom_bootscreen_animation[frame].bitmap); + #else + const u8g_pgm_uint8_t * const bmp = (u8g_pgm_uint8_t*)pgm_read_ptr(&custom_bootscreen_animation[frame]); + #endif + #else + const u8g_pgm_uint8_t * const bmp = custom_start_bmp; + #endif + + UNUSED(frame); + + u8g.drawBitmapP(left, top, CUSTOM_BOOTSCREEN_BMP_BYTEWIDTH, CUSTOM_BOOTSCREEN_BMPHEIGHT, bmp); + + #if ENABLED(CUSTOM_BOOTSCREEN_INVERTED) + if (frame == 0) { + u8g.setColorIndex(1); + if (top) u8g.drawBox(0, 0, LCD_PIXEL_WIDTH, top); + if (left) u8g.drawBox(0, top, left, CUSTOM_BOOTSCREEN_BMPHEIGHT); + if (right < LCD_PIXEL_WIDTH) u8g.drawBox(right, top, LCD_PIXEL_WIDTH - right, CUSTOM_BOOTSCREEN_BMPHEIGHT); + if (bottom < LCD_PIXEL_HEIGHT) u8g.drawBox(0, bottom, LCD_PIXEL_WIDTH, LCD_PIXEL_HEIGHT - bottom); + } + #endif + } + + // Shows the custom bootscreen, with the u8g loop, animations and delays + void MarlinUI::show_custom_bootscreen() { + #if DISABLED(CUSTOM_BOOTSCREEN_ANIMATED) + constexpr millis_t frame_time = 0; + constexpr uint8_t f = 0; + #else + #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)) + #endif + { + #if ENABLED(CUSTOM_BOOTSCREEN_ANIMATED_FRAME_TIME) + const uint8_t fr = _MIN(f, COUNT(custom_bootscreen_animation) - 1); + const millis_t frame_time = pgm_read_word(&custom_bootscreen_animation[fr].duration); + #endif + u8g.firstPage(); + do { draw_custom_bootscreen(f); } while (u8g.nextPage()); + if (frame_time) safe_delay(frame_time); + } + + #ifndef CUSTOM_BOOTSCREEN_TIMEOUT + #define CUSTOM_BOOTSCREEN_TIMEOUT 2500 + #endif + #if CUSTOM_BOOTSCREEN_TIMEOUT + safe_delay(CUSTOM_BOOTSCREEN_TIMEOUT); + #endif + } + #endif // SHOW_CUSTOM_BOOTSCREEN + + // Two-part needed to display all info + constexpr bool two_part = ((LCD_PIXEL_HEIGHT) - (START_BMPHEIGHT)) < ((MENU_FONT_ASCENT) * 2); + constexpr uint8_t bootscreen_pages = 1 + two_part; + + // Draw the static Marlin bootscreen from a u8g loop + // or the animated boot screen within its own u8g loop + void MarlinUI::draw_marlin_bootscreen(const bool line2/*=false*/) { + + // Determine text space needed + constexpr u8g_uint_t text_width_1 = u8g_uint_t((sizeof(SHORT_BUILD_VERSION) - 1) * (MENU_FONT_WIDTH)), + text_width_2 = u8g_uint_t((sizeof(MARLIN_WEBSITE_URL) - 1) * (MENU_FONT_WIDTH)), + text_max_width = _MAX(text_width_1, text_width_2), + text_total_height = (MENU_FONT_HEIGHT) * 2, + width = LCD_PIXEL_WIDTH, height = LCD_PIXEL_HEIGHT, + rspace = width - (START_BMPWIDTH); + + u8g_int_t offx, offy, txt_base, txt_offx_1, txt_offx_2; + + // Can the text fit to the right of the bitmap? + if (text_max_width < rspace) { + constexpr int8_t inter = (width - text_max_width - (START_BMPWIDTH)) / 3; // Evenly distribute horizontal space + offx = inter; // First the boot logo... + offy = (height - (START_BMPHEIGHT)) / 2; // ...V-aligned in the full height + txt_offx_1 = txt_offx_2 = inter + (START_BMPWIDTH) + inter; // Text right of the bitmap + txt_base = (height + MENU_FONT_ASCENT + text_total_height - (MENU_FONT_HEIGHT)) / 2; // Text vertical center + } + else { + constexpr int8_t inter = (height - text_total_height - (START_BMPHEIGHT)) / 3; // Evenly distribute vertical space + offx = rspace / 2; // Center the boot logo in the whole space + offy = inter; // V-align boot logo proportionally + txt_offx_1 = (width - text_width_1) / 2; // Text 1 centered + txt_offx_2 = (width - text_width_2) / 2; // Text 2 centered + txt_base = offy + START_BMPHEIGHT + offy + text_total_height - (MENU_FONT_DESCENT); // Even spacing looks best + } + NOLESS(offx, 0); + NOLESS(offy, 0); + + auto _draw_bootscreen_bmp = [&](const uint8_t *bitmap) { + u8g.drawBitmapP(offx, offy, START_BMP_BYTEWIDTH, START_BMPHEIGHT, bitmap); + set_font(FONT_MENU); + if (!two_part || !line2) lcd_put_u8str_P(txt_offx_1, txt_base - (MENU_FONT_HEIGHT), PSTR(SHORT_BUILD_VERSION)); + if (!two_part || line2) lcd_put_u8str_P(txt_offx_2, txt_base, PSTR(MARLIN_WEBSITE_URL)); + }; + + auto draw_bootscreen_bmp = [&](const uint8_t *bitmap) { + u8g.firstPage(); do { _draw_bootscreen_bmp(bitmap); } while (u8g.nextPage()); + }; + + #if DISABLED(BOOT_MARLIN_LOGO_ANIMATED) + draw_bootscreen_bmp(start_bmp); + #else + constexpr millis_t frame_time = MARLIN_BOOTSCREEN_FRAME_TIME; + LOOP_L_N(f, COUNT(marlin_bootscreen_animation)) { + draw_bootscreen_bmp((uint8_t*)pgm_read_ptr(&marlin_bootscreen_animation[f])); + if (frame_time) safe_delay(frame_time); + } + #endif + } + + // Show the Marlin bootscreen, with the u8g loop and delays + void MarlinUI::show_marlin_bootscreen() { + for (uint8_t q = bootscreen_pages; q--;) { + draw_marlin_bootscreen(q == 0); + if (q) safe_delay((BOOTSCREEN_TIMEOUT) / bootscreen_pages); + } + } + + void MarlinUI::show_bootscreen() { + TERN_(SHOW_CUSTOM_BOOTSCREEN, show_custom_bootscreen()); + show_marlin_bootscreen(); + } + + void MarlinUI::bootscreen_completion(const millis_t sofar) { + if ((BOOTSCREEN_TIMEOUT) / bootscreen_pages > sofar) safe_delay((BOOTSCREEN_TIMEOUT) / bootscreen_pages - sofar); + } + +#endif // SHOW_BOOTSCREEN + +#if ENABLED(LIGHTWEIGHT_UI) + #include "status_screen_lite_ST7920.h" +#endif + +// Initialize or re-initialize the LCD +void MarlinUI::init_lcd() { + + static bool did_init_u8g = false; + if (!did_init_u8g) { + u8g.init(U8G_PARAM); + did_init_u8g = true; + } + + #if PIN_EXISTS(LCD_BACKLIGHT) + OUT_WRITE(LCD_BACKLIGHT_PIN, DISABLED(DELAYED_BACKLIGHT_INIT)); // Illuminate after reset or right away + #endif + + #if ANY(MKS_12864OLED, MKS_12864OLED_SSD1306, FYSETC_242_OLED_12864, ZONESTAR_12864OLED, K3D_242_OLED_CONTROLLER) + SET_OUTPUT(LCD_PINS_DC); + #ifndef LCD_RESET_PIN + #define LCD_RESET_PIN LCD_PINS_RS + #endif + #endif + + #if PIN_EXISTS(LCD_RESET) + // Perform a clean hardware reset with needed delays + OUT_WRITE(LCD_RESET_PIN, LOW); + _delay_ms(5); + WRITE(LCD_RESET_PIN, HIGH); + _delay_ms(5); + u8g.begin(); + #endif + + #if PIN_EXISTS(LCD_BACKLIGHT) && ENABLED(DELAYED_BACKLIGHT_INIT) + WRITE(LCD_BACKLIGHT_PIN, HIGH); + #endif + + TERN_(HAS_LCD_CONTRAST, refresh_contrast()); + + TERN_(LCD_SCREEN_ROT_90, u8g.setRot90()); + TERN_(LCD_SCREEN_ROT_180, u8g.setRot180()); + TERN_(LCD_SCREEN_ROT_270, u8g.setRot270()); + + update_language_font(); +} + +void MarlinUI::update_language_font() { + #if HAS_MULTI_LANGUAGE + switch (language) { + default: uxg_SetUtf8Fonts(LANG_FONT_INFO(LCD_LANGUAGE), COUNT(LANG_FONT_INFO(LCD_LANGUAGE))); break; + #ifdef LCD_LANGUAGE_2 + case 1: uxg_SetUtf8Fonts(LANG_FONT_INFO(LCD_LANGUAGE_2), COUNT(LANG_FONT_INFO(LCD_LANGUAGE_2))); break; + #endif + #ifdef LCD_LANGUAGE_3 + case 2: uxg_SetUtf8Fonts(LANG_FONT_INFO(LCD_LANGUAGE_3), COUNT(LANG_FONT_INFO(LCD_LANGUAGE_3))); break; + #endif + #ifdef LCD_LANGUAGE_4 + case 3: uxg_SetUtf8Fonts(LANG_FONT_INFO(LCD_LANGUAGE_4), COUNT(LANG_FONT_INFO(LCD_LANGUAGE_4))); break; + #endif + #ifdef LCD_LANGUAGE_5 + case 4: uxg_SetUtf8Fonts(LANG_FONT_INFO(LCD_LANGUAGE_5), COUNT(LANG_FONT_INFO(LCD_LANGUAGE_5))); break; + #endif + } + #else + uxg_SetUtf8Fonts(LANG_FONT_INFO(LCD_LANGUAGE), COUNT(LANG_FONT_INFO(LCD_LANGUAGE))); + #endif +} + +// The kill screen is displayed for unrecoverable conditions +void MarlinUI::draw_kill_screen() { + TERN_(LIGHTWEIGHT_UI, ST7920_Lite_Status_Screen::clear_text_buffer()); + const u8g_uint_t h4 = u8g.getHeight() / 4; + u8g.firstPage(); + do { + set_font(FONT_MENU); + lcd_put_u8str(0, h4 * 1, status_message); + lcd_put_u8str_P(0, h4 * 2, GET_TEXT(MSG_HALTED)); + lcd_put_u8str_P(0, h4 * 3, GET_TEXT(MSG_PLEASE_RESET)); + } while (u8g.nextPage()); +} + +void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop + +#if HAS_LCD_MENU + + #include "../menu/menu.h" + + u8g_uint_t row_y1, row_y2; + + #if ENABLED(ADVANCED_PAUSE_FEATURE) + + void MarlinUI::draw_hotend_status(const uint8_t row, const uint8_t extruder) { + row_y1 = row * (MENU_FONT_HEIGHT) + 1; + row_y2 = row_y1 + MENU_FONT_HEIGHT - 1; + + if (!PAGE_CONTAINS(row_y1 + 1, row_y2 + 2)) return; + + lcd_put_wchar(LCD_PIXEL_WIDTH - 11 * (MENU_FONT_WIDTH), row_y2, 'E'); + lcd_put_wchar((char)('1' + extruder)); + lcd_put_wchar(' '); + lcd_put_u8str(i16tostr3rj(thermalManager.wholeDegHotend(extruder))); + lcd_put_wchar('/'); + + if (get_blink() || !thermalManager.heater_idle[extruder].timed_out) + lcd_put_u8str(i16tostr3rj(thermalManager.degTargetHotend(extruder))); + } + + #endif // ADVANCED_PAUSE_FEATURE + + // Mark a menu item and set font color if selected. + // Return 'false' if the item is not on screen. + static bool mark_as_selected(const uint8_t row, const bool sel) { + row_y1 = row * (MENU_FONT_HEIGHT) + 1; + row_y2 = row_y1 + MENU_FONT_HEIGHT - 1; + + if (!PAGE_CONTAINS(row_y1 + 1, row_y2 + 2)) return false; + + if (sel) { + #if ENABLED(MENU_HOLLOW_FRAME) + u8g.drawHLine(0, row_y1 + 1, LCD_PIXEL_WIDTH); + u8g.drawHLine(0, row_y2 + 2, LCD_PIXEL_WIDTH); + #else + u8g.setColorIndex(1); // solid outline + u8g.drawBox(0, row_y1 + 2, LCD_PIXEL_WIDTH, MENU_FONT_HEIGHT - 1); + u8g.setColorIndex(0); // inverted text + #endif + } + #if DISABLED(MENU_HOLLOW_FRAME) + else u8g.setColorIndex(1); // solid text + #endif + + if (!PAGE_CONTAINS(row_y1, row_y2)) return false; + + lcd_moveto(0, row_y2); + return true; + } + + // Draw a static line of text in the same idiom as a menu item + void MenuItem_static::draw(const uint8_t row, PGM_P const pstr, const uint8_t style/*=SS_DEFAULT*/, const char * const vstr/*=nullptr*/) { + + if (mark_as_selected(row, style & SS_INVERT)) { + pixel_len_t n = LCD_PIXEL_WIDTH; // pixel width of string allowed + + const int plen = pstr ? calculateWidth(pstr) : 0, + vlen = vstr ? utf8_strlen(vstr) : 0; + if (style & SS_CENTER) { + int pad = (LCD_PIXEL_WIDTH - plen - vlen * MENU_FONT_WIDTH) / MENU_FONT_WIDTH / 2; + while (--pad >= 0) n -= lcd_put_wchar(' '); + } + + if (plen) n = lcd_put_u8str_ind_P(pstr, itemIndex, itemString, n / (MENU_FONT_WIDTH)) * (MENU_FONT_WIDTH); + if (vlen) n -= lcd_put_u8str_max(vstr, n); + while (n > MENU_FONT_WIDTH) n -= lcd_put_wchar(' '); + } + } + + // Draw a generic menu item + void MenuItemBase::_draw(const bool sel, const uint8_t row, PGM_P const pstr, const char, const char post_char) { + if (mark_as_selected(row, sel)) { + pixel_len_t n = lcd_put_u8str_ind_P(pstr, itemIndex, itemString, LCD_WIDTH - 1) * (MENU_FONT_WIDTH); + while (n > MENU_FONT_WIDTH) n -= lcd_put_wchar(' '); + lcd_put_wchar(LCD_PIXEL_WIDTH - (MENU_FONT_WIDTH), row_y2, post_char); + lcd_put_wchar(' '); + } + } + + // Draw a menu item with an editable value + void MenuEditItemBase::draw(const bool sel, const uint8_t row, PGM_P const pstr, const char * const inStr, const bool pgm) { + if (mark_as_selected(row, sel)) { + const uint8_t vallen = (pgm ? utf8_strlen_P(inStr) : utf8_strlen((char*)inStr)), + pixelwidth = (pgm ? uxg_GetUtf8StrPixelWidthP(u8g.getU8g(), inStr) : uxg_GetUtf8StrPixelWidth(u8g.getU8g(), (char*)inStr)); + const u8g_uint_t prop = USE_WIDE_GLYPH ? 2 : 1; + + pixel_len_t n = lcd_put_u8str_ind_P(pstr, itemIndex, itemString, LCD_WIDTH - 2 - vallen * prop) * (MENU_FONT_WIDTH); + if (vallen) { + lcd_put_wchar(':'); + while (n > MENU_FONT_WIDTH) n -= lcd_put_wchar(' '); + lcd_moveto(LCD_PIXEL_WIDTH - _MAX((MENU_FONT_WIDTH) * vallen, pixelwidth + 2), row_y2); + if (pgm) lcd_put_u8str_P(inStr); else lcd_put_u8str((char*)inStr); + } + } + } + + void MenuEditItemBase::draw_edit_screen(PGM_P const pstr, const char * const value/*=nullptr*/) { + ui.encoder_direction_normal(); + + const u8g_uint_t prop = USE_WIDE_GLYPH ? 2 : 1; + const u8g_uint_t labellen = utf8_strlen_P(pstr), vallen = utf8_strlen(value); + bool extra_row = labellen * prop > LCD_WIDTH - 2 - vallen * prop; + + #if ENABLED(USE_BIG_EDIT_FONT) + // Use the menu font if the label won't fit on a single line + constexpr u8g_uint_t lcd_edit_width = (LCD_PIXEL_WIDTH) / (EDIT_FONT_WIDTH); + u8g_uint_t lcd_chr_fit, one_chr_width; + if (labellen * prop <= lcd_edit_width - 1) { + if (labellen * prop + vallen * prop + 1 > lcd_edit_width) extra_row = true; + lcd_chr_fit = lcd_edit_width + 1; + one_chr_width = EDIT_FONT_WIDTH; + ui.set_font(FONT_EDIT); + } + else { + lcd_chr_fit = LCD_WIDTH; + one_chr_width = MENU_FONT_WIDTH; + ui.set_font(FONT_MENU); + } + #else + constexpr u8g_uint_t lcd_chr_fit = LCD_WIDTH, + one_chr_width = MENU_FONT_WIDTH; + #endif + + // Center the label and value lines on the middle line + u8g_uint_t baseline = extra_row ? (LCD_PIXEL_HEIGHT) / 2 - 1 + : (LCD_PIXEL_HEIGHT + EDIT_FONT_ASCENT) / 2; + + // Assume the label is alpha-numeric (with a descender) + bool onpage = PAGE_CONTAINS(baseline - (EDIT_FONT_ASCENT - 1), baseline + EDIT_FONT_DESCENT); + if (onpage) lcd_put_u8str_ind_P(0, baseline, pstr, itemIndex, itemString); + + // If a value is included, print a colon, then print the value right-justified + if (value) { + lcd_put_wchar(':'); + if (extra_row) { + // Assume that value is numeric (with no descender) + baseline += EDIT_FONT_ASCENT + 2; + onpage = PAGE_CONTAINS(baseline - (EDIT_FONT_ASCENT - 1), baseline); + } + if (onpage) { + lcd_put_wchar(((lcd_chr_fit - 1) - (vallen * prop + 1)) * one_chr_width, baseline, ' '); // Right-justified, padded, add a leading space + lcd_put_u8str(value); + } + } + TERN_(USE_BIG_EDIT_FONT, ui.set_font(FONT_MENU)); + } + + inline void draw_boxed_string(const u8g_uint_t x, const u8g_uint_t y, PGM_P const pstr, const bool inv) { + const u8g_uint_t len = utf8_strlen_P(pstr), + by = (y + 1) * (MENU_FONT_HEIGHT); + const u8g_uint_t prop = USE_WIDE_GLYPH ? 2 : 1; + const pixel_len_t bw = len * prop * (MENU_FONT_WIDTH), bx = x * prop * (MENU_FONT_WIDTH); + if (inv) { + u8g.setColorIndex(1); + u8g.drawBox(bx / prop - 1, by - (MENU_FONT_ASCENT), bw + 2, MENU_FONT_HEIGHT); + u8g.setColorIndex(0); + } + lcd_put_u8str_P(bx / prop, by, pstr); + if (inv) u8g.setColorIndex(1); + } + + void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const bool yesno, PGM_P const pref, const char * const string/*=nullptr*/, PGM_P const suff/*=nullptr*/) { + ui.draw_select_screen_prompt(pref, string, suff); + draw_boxed_string(1, LCD_HEIGHT - 1, no, !yesno); + draw_boxed_string(LCD_WIDTH - (utf8_strlen_P(yes) * (USE_WIDE_GLYPH ? 2 : 1) + 1), LCD_HEIGHT - 1, yes, yesno); + } + + #if ENABLED(SDSUPPORT) + + void MenuItem_sdbase::draw(const bool sel, const uint8_t row, PGM_P const, CardReader &theCard, const bool isDir) { + if (mark_as_selected(row, sel)) { + const uint8_t maxlen = LCD_WIDTH - isDir; + if (isDir) lcd_put_wchar(LCD_STR_FOLDER[0]); + const pixel_len_t pixw = maxlen * (MENU_FONT_WIDTH); + pixel_len_t n = pixw - lcd_put_u8str_max(ui.scrolled_filename(theCard, maxlen, row, sel), pixw); + while (n > MENU_FONT_WIDTH) n -= lcd_put_wchar(' '); + } + } + + #endif // SDSUPPORT + + #if ENABLED(AUTO_BED_LEVELING_UBL) + + /** + * UBL LCD "radar" map data + */ + #define MAP_UPPER_LEFT_CORNER_X 35 // These probably should be moved to the .h file But for now, + #define MAP_UPPER_LEFT_CORNER_Y 8 // it is easier to play with things having them here + #define MAP_MAX_PIXELS_X 53 + #define MAP_MAX_PIXELS_Y 49 + + void MarlinUI::ubl_plot(const uint8_t x_plot, const uint8_t y_plot) { + // Scale the box pixels appropriately + u8g_uint_t x_map_pixels = ((MAP_MAX_PIXELS_X - 4) / (GRID_MAX_POINTS_X)) * (GRID_MAX_POINTS_X), + y_map_pixels = ((MAP_MAX_PIXELS_Y - 4) / (GRID_MAX_POINTS_Y)) * (GRID_MAX_POINTS_Y), + + pixels_per_x_mesh_pnt = x_map_pixels / (GRID_MAX_POINTS_X), + pixels_per_y_mesh_pnt = y_map_pixels / (GRID_MAX_POINTS_Y), + + x_offset = MAP_UPPER_LEFT_CORNER_X + 1 + (MAP_MAX_PIXELS_X - x_map_pixels - 2) / 2, + y_offset = MAP_UPPER_LEFT_CORNER_Y + 1 + (MAP_MAX_PIXELS_Y - y_map_pixels - 2) / 2; + + // Clear the Mesh Map + + if (PAGE_CONTAINS(y_offset - 2, y_offset + y_map_pixels + 4)) { + u8g.setColorIndex(1); // First draw the bigger box in White so we have a border around the mesh map box + u8g.drawBox(x_offset - 2, y_offset - 2, x_map_pixels + 4, y_map_pixels + 4); + if (PAGE_CONTAINS(y_offset, y_offset + y_map_pixels)) { + u8g.setColorIndex(0); // Now actually clear the mesh map box + u8g.drawBox(x_offset, y_offset, x_map_pixels, y_map_pixels); + } + } + + // Display Mesh Point Locations + + u8g.setColorIndex(1); + const u8g_uint_t sx = x_offset + pixels_per_x_mesh_pnt / 2; + u8g_uint_t y = y_offset + pixels_per_y_mesh_pnt / 2; + for (uint8_t j = 0; j < GRID_MAX_POINTS_Y; j++, y += pixels_per_y_mesh_pnt) + if (PAGE_CONTAINS(y, y)) + for (uint8_t i = 0, x = sx; i < GRID_MAX_POINTS_X; i++, x += pixels_per_x_mesh_pnt) + u8g.drawBox(x, y, 1, 1); + + // Fill in the Specified Mesh Point + + const uint8_t y_plot_inv = (GRID_MAX_POINTS_Y) - 1 - y_plot; // The origin is typically in the lower right corner. We need to + // invert the Y to get it to plot in the right location. + + const u8g_uint_t by = y_offset + y_plot_inv * pixels_per_y_mesh_pnt; + if (PAGE_CONTAINS(by, by + pixels_per_y_mesh_pnt)) + u8g.drawBox( + x_offset + x_plot * pixels_per_x_mesh_pnt, by, + pixels_per_x_mesh_pnt, pixels_per_y_mesh_pnt + ); + + // Put Relevant Text on Display + + // Show X and Y positions at top of screen + u8g.setColorIndex(1); + if (PAGE_UNDER(7)) { + const xy_pos_t pos = { ubl.mesh_index_to_xpos(x_plot), ubl.mesh_index_to_ypos(y_plot) }, + lpos = pos.asLogical(); + lcd_put_u8str_P(5, 7, X_LBL); + lcd_put_u8str(ftostr52(lpos.x)); + lcd_put_u8str_P(74, 7, Y_LBL); + lcd_put_u8str(ftostr52(lpos.y)); + } + + // Print plot position + if (PAGE_CONTAINS(LCD_PIXEL_HEIGHT - (INFO_FONT_HEIGHT - 1), LCD_PIXEL_HEIGHT)) { + lcd_put_wchar(5, LCD_PIXEL_HEIGHT, '('); + u8g.print(x_plot); + lcd_put_wchar(','); + u8g.print(y_plot); + lcd_put_wchar(')'); + + // Show the location value + lcd_put_u8str_P(74, LCD_PIXEL_HEIGHT, Z_LBL); + if (!isnan(ubl.z_values[x_plot][y_plot])) + lcd_put_u8str(ftostr43sign(ubl.z_values[x_plot][y_plot])); + else + lcd_put_u8str_P(PSTR(" -----")); + } + + } + + #endif // AUTO_BED_LEVELING_UBL + + #if EITHER(BABYSTEP_ZPROBE_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY) + + // + // Draw knob rotation => Z motion key for: + // - menu.cpp:lcd_babystep_zoffset + // - menu_ubl.cpp:_lcd_mesh_fine_tune + // + + const unsigned char cw_bmp[] PROGMEM = { + B00000000,B11111110,B00000000, + B00000011,B11111111,B10000000, + B00000111,B11000111,B11000000, + B00000111,B00000001,B11100000, + B00000000,B00000000,B11100000, + B00000000,B00000000,B11110000, + B00000000,B00000000,B01110000, + B00000100,B00000000,B01110000, + B00001110,B00000000,B01110000, + B00011111,B00000000,B01110000, + B00111111,B10000000,B11110000, + B00001110,B00000000,B11100000, + B00001111,B00000001,B11100000, + B00000111,B11000111,B11000000, + B00000011,B11111111,B10000000, + B00000000,B11111110,B00000000 + }; + + const unsigned char ccw_bmp[] PROGMEM = { + B00000000,B11111110,B00000000, + B00000011,B11111111,B10000000, + B00000111,B11000111,B11000000, + B00001111,B00000001,B11100000, + B00001110,B00000000,B11100000, + B00111111,B10000000,B11110000, + B00011111,B00000000,B01110000, + B00001110,B00000000,B01110000, + B00000100,B00000000,B01110000, + B00000000,B00000000,B01110000, + B00000000,B00000000,B11110000, + B00000000,B00000000,B11100000, + B00000111,B00000001,B11100000, + B00000111,B11000111,B11000000, + B00000011,B11111111,B10000000, + B00000000,B11111110,B00000000 + }; + + const unsigned char up_arrow_bmp[] PROGMEM = { + B00000100,B00000000, + B00001110,B00000000, + B00011111,B00000000, + B00111111,B10000000, + B01111111,B11000000, + B00001110,B00000000, + B00001110,B00000000, + B00001110,B00000000, + B00001110,B00000000, + B00001110,B00000000, + B00001110,B00000000, + B00001110,B00000000, + B00001110,B00000000 + }; + + const unsigned char down_arrow_bmp[] PROGMEM = { + B00001110,B00000000, + B00001110,B00000000, + B00001110,B00000000, + B00001110,B00000000, + B00001110,B00000000, + B00001110,B00000000, + B00001110,B00000000, + B00001110,B00000000, + B01111111,B11000000, + B00111111,B10000000, + B00011111,B00000000, + B00001110,B00000000, + B00000100,B00000000 + }; + + const unsigned char offset_bedline_bmp[] PROGMEM = { + B11111111,B11111111,B11111111 + }; + + const unsigned char nozzle_bmp[] PROGMEM = { + B01111111,B10000000, + B11111111,B11000000, + B11111111,B11000000, + B11111111,B11000000, + B01111111,B10000000, + B01111111,B10000000, + B11111111,B11000000, + B11111111,B11000000, + B11111111,B11000000, + B00111111,B00000000, + B00011110,B00000000, + B00001100,B00000000 + }; + + void _lcd_zoffset_overlay_gfx(const_float_t zvalue) { + // Determine whether the user is raising or lowering the nozzle. + static int8_t dir; + static float old_zvalue; + if (zvalue != old_zvalue) { + dir = zvalue ? zvalue < old_zvalue ? -1 : 1 : 0; + old_zvalue = zvalue; + } + + const unsigned char *rot_up = TERN(OVERLAY_GFX_REVERSE, ccw_bmp, cw_bmp), + *rot_down = TERN(OVERLAY_GFX_REVERSE, cw_bmp, ccw_bmp); + + const int left = TERN(USE_BIG_EDIT_FONT, 0, 5), + right = TERN(USE_BIG_EDIT_FONT, 45, 90), + nozzle = TERN(USE_BIG_EDIT_FONT, 95, 60); + + // Draw nozzle lowered or raised according to direction moved + if (PAGE_CONTAINS( 3, 16)) u8g.drawBitmapP(nozzle + 6, 4 - dir, 2, 12, nozzle_bmp); + if (PAGE_CONTAINS(20, 20)) u8g.drawBitmapP(nozzle + 0, 20 , 3, 1, offset_bedline_bmp); + + // Draw cw/ccw indicator and up/down arrows. + if (PAGE_CONTAINS(47, 62)) { + u8g.drawBitmapP(right + 0, 48 - dir, 2, 13, up_arrow_bmp); + u8g.drawBitmapP(left + 0, 49 - dir, 2, 13, down_arrow_bmp); + u8g.drawBitmapP(left + 13, 47 , 3, 16, rot_down); + u8g.drawBitmapP(right + 13, 47 , 3, 16, rot_up); + } + } + + #endif // BABYSTEP_ZPROBE_GFX_OVERLAY || MESH_EDIT_GFX_OVERLAY + +#endif // HAS_LCD_MENU + +#endif // HAS_MARLINUI_U8GLIB diff --git a/Marlin/src/lcd/dogm/marlinui_DOGM.h b/Marlin/src/lcd/dogm/marlinui_DOGM.h new file mode 100644 index 000000000000..328b69b93b6c --- /dev/null +++ b/Marlin/src/lcd/dogm/marlinui_DOGM.h @@ -0,0 +1,234 @@ +/** + * 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 + +/** + * lcd/dogm/marlinui_DOGM.h + */ + +#include "../../inc/MarlinConfigPre.h" + +#include +#include "HAL_LCD_class_defines.h" + +//#define ALTERNATIVE_LCD + +#if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) + + // RepRapWorld Graphical LCD + + #define U8G_CLASS U8GLIB_ST7920_128X64_4X + #if DISABLED(SDSUPPORT) && (LCD_PINS_D4 == SD_SCK_PIN) && (LCD_PINS_ENABLE == SD_MOSI_PIN) + #define U8G_PARAM LCD_PINS_RS + #else + #define U8G_PARAM LCD_PINS_D4, LCD_PINS_ENABLE, LCD_PINS_RS + #endif + +#elif ENABLED(U8GLIB_ST7920) + + // 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) + #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 + #if ENABLED(ALTERNATIVE_LCD) + #define U8G_CLASS U8GLIB_ST7920_128X64_4X // 2 stripes, SW SPI (Original u8glib device) + #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 + // HAL version uses these pin settings + #endif + +#elif ENABLED(CARTESIO_UI) + + // CartesioUI LCD + + #if ENABLED(ALTERNATIVE_LCD) + #define U8G_CLASS U8GLIB_DOGM128_2X // 4 stripes + #define FORCE_SOFT_SPI // SW-SPI + #else + #define U8G_CLASS U8GLIB_DOGM128_2X // 4 stripes (HW-SPI) + #endif + +#elif ENABLED(U8GLIB_LM6059_AF) + + // Based on the Adafruit ST7565 (https://www.adafruit.com/products/250) + + #if ENABLED(ALTERNATIVE_LCD) + #define U8G_CLASS U8GLIB_LM6059 // 8 stripes (HW-SPI) + #else + #define U8G_CLASS U8GLIB_LM6059_2X // 4 stripes (HW-SPI) + #endif + +#elif ENABLED(U8GLIB_ST7565_64128N) + + // MaKrPanel, Mini Viki, Viki 2.0, AZSMZ 12864 ST7565 controller + + #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 + #define FORCE_SOFT_SPI // SW-SPI + #endif + +#elif ANY(FYSETC_MINI_12864, MKS_MINI_12864, ENDER2_STOCKDISPLAY) + + // The FYSETC Mini 12864 display // "4 stripes" + + // The MKS_MINI_12864 V1/V2 aren't exact copies of the MiniPanel. + // Panel management is in u8g_dev_uc1701_mini12864_HAL.cpp with + // extra delays added to remove glitches seen with fast MCUs. + + #define U8G_CLASS U8GLIB_MINI12864_2X_HAL // 8 stripes (HW-SPI) + +#elif ENABLED(MINIPANEL) + + #if ENABLED(ALTERNATIVE_LCD) + #define U8G_CLASS U8GLIB_MINI12864 + #else + #define U8G_CLASS U8GLIB_MINI12864_2X // 8 stripes (HW-SPI) + #endif + +#elif ENABLED(MKS_12864OLED_SSD1306) + + // MKS 128x64 (SSD1306) OLED I2C LCD + + #define FORCE_SOFT_SPI // SW-SPI + + #if ENABLED(ALTERNATIVE_LCD) + #define U8G_CLASS U8GLIB_SSD1306_128X64_2X // 4 stripes + #else + #define U8G_CLASS U8GLIB_SSD1306_128X64 // 8 stripes + #endif + +#elif EITHER(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 + + #define FORCE_SOFT_SPI // SW-SPI + + #if ENABLED(ALTERNATIVE_LCD) + #define U8G_CLASS U8GLIB_SSD1306_128X64_2X // 4 stripes + #else + #define U8G_CLASS U8GLIB_SSD1309_128X64_HAL + #endif + +#elif ENABLED(ZONESTAR_12864OLED_SSD1306) + + // Zonestar SSD1306 OLED SPI LCD + + #define FORCE_SOFT_SPI // SW-SPI + #if ENABLED(ALTERNATIVE_LCD) + #define U8G_CLASS U8GLIB_SH1306_128X64_2X // 4 stripes + #else + #define U8G_CLASS U8GLIB_SH1306_128X64 // 8 stripes + #endif + +#elif EITHER(MKS_12864OLED, ZONESTAR_12864OLED) + + // MKS 128x64 (SH1106) OLED I2C LCD + // - or - + // Zonestar SH1106 OLED SPI LCD + + #define FORCE_SOFT_SPI // SW-SPI + #if ENABLED(ALTERNATIVE_LCD) + #define U8G_CLASS U8GLIB_SH1106_128X64_2X // 4 stripes + #else + #define U8G_CLASS U8GLIB_SH1106_128X64 // 8 stripes + #endif + +#elif ENABLED(U8GLIB_SH1106_EINSTART) + + // Connected via motherboard header + + #define U8G_CLASS U8GLIB_SH1106_128X64 + #define U8G_PARAM DOGLCD_SCK, DOGLCD_MOSI, DOGLCD_CS, LCD_PINS_DC, LCD_PINS_RS + +#elif ENABLED(U8GLIB_SH1106) + + // Generic SH1106 OLED I2C LCD + + #if ENABLED(ALTERNATIVE_LCD) + #define U8G_CLASS U8GLIB_SH1106_128X64_2X_I2C_2_WIRE // 4 stripes + #else + #define U8G_CLASS U8GLIB_SH1106_128X64_2X // 4 stripes + #endif + #define U8G_PARAM (U8G_I2C_OPT_NONE | U8G_I2C_OPT_FAST) // I2C + +#elif ENABLED(U8GLIB_SSD1309) + + // Generic support for SSD1309 OLED I2C LCDs + + #define U8G_CLASS U8GLIB_SSD1309_128X64 + #define U8G_PARAM (U8G_I2C_OPT_NONE | U8G_I2C_OPT_FAST) // I2C + +#elif ENABLED(U8GLIB_SSD1306) + + // Generic SSD1306 OLED I2C LCD + + #if ENABLED(ALTERNATIVE_LCD) + #define U8G_CLASS U8GLIB_SSD1306_128X64_2X_I2C_2_WIRE // 4 stripes + #else + #define U8G_CLASS U8GLIB_SSD1306_128X64_2X // 4 stripes + #endif + #define U8G_PARAM (U8G_I2C_OPT_NONE | U8G_I2C_OPT_FAST) + +#elif TFT_SCALED_DOGLCD + + // Unspecified 320x240 TFT pre-initialized by built-in bootloader + + #define U8G_CLASS U8GLIB_TFT_320X240_UPSCALE_FROM_128X64 + #if HAS_FSMC_GRAPHICAL_TFT + #define U8G_PARAM FSMC_CS_PIN, FSMC_RS_PIN + #else + #define U8G_PARAM -1, -1 + #endif + +#else + + #if ENABLED(ALTERNATIVE_LCD) + #define U8G_CLASS U8GLIB_DOGM128 // 8 stripes (HW-SPI) + #else + #define U8G_CLASS U8GLIB_DOGM128_2X // 4 stripes (HW-SPI) + #endif + +#endif + +// Use HW-SPI if no other option is specified +#ifndef U8G_PARAM + #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 + #endif +#endif + +// For selective rendering within a Y range +#define PAGE_OVER(ya) ((ya) <= u8g.getU8g()->current_page.y1) // Does the current page follow a region top? +#define PAGE_UNDER(yb) ((yb) >= u8g.getU8g()->current_page.y0) // Does the current page precede a region bottom? +#define PAGE_CONTAINS(ya, yb) ((yb) >= u8g.getU8g()->current_page.y0 && (ya) <= u8g.getU8g()->current_page.y1) // Do two vertical regions overlap? + +extern U8G_CLASS u8g; diff --git a/Marlin/src/lcd/dogm/status/ammeter.h b/Marlin/src/lcd/dogm/status/ammeter.h new file mode 100644 index 000000000000..d99ea6949a64 --- /dev/null +++ b/Marlin/src/lcd/dogm/status/ammeter.h @@ -0,0 +1,68 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +// +// lcd/dogm/status/ammeter.h - Status Screen Laser Ammeter bitmaps +// + +#define STATUS_AMMETER_WIDTH 20 + +const unsigned char status_ammeter_bmp_mA[] PROGMEM = { + B00000000,B11111100,B00000000, + B00000011,B00000011,B00000000, + B00000100,B00000000,B10000000, + B00001000,B00000000,B01000000, + B00010000,B00000110,B00100000, + B00010000,B00001001,B00100000, + B00100000,B00001001,B00010000, + B00100011,B01001111,B00010000, + B11100010,B10101001,B00011100, + B00100010,B10101001,B00010000, + B00100010,B10101001,B00010000, + B00010000,B00000000,B00100000, + B00010000,B00000000,B00100000, + B00001000,B00000000,B01000000, + B00000100,B00000000,B10000000, + B00000011,B00000011,B00000000, + B00000000,B11111100,B00000000 +}; + +const unsigned char status_ammeter_bmp_A[] PROGMEM = { + B00000000,B11111100,B00000000, + B00000011,B00000011,B00000000, + B00000100,B00000000,B10000000, + B00001000,B00000000,B01000000, + B00010000,B00000000,B00100000, + B00010000,B00110000,B00100000, + B00100000,B01001000,B00010000, + B00100000,B01001000,B00010000, + B11100000,B01111000,B00011100, + B00100000,B01001000,B00010000, + B00100000,B01001000,B00010000, + B00010000,B01001000,B00100000, + B00010000,B00000000,B00100000, + B00001000,B00000000,B01000000, + B00000100,B00000000,B10000000, + B00000011,B00000011,B00000000, + B00000000,B11111100,B00000000, +}; diff --git a/Marlin/src/lcd/dogm/status/bed.h b/Marlin/src/lcd/dogm/status/bed.h new file mode 100644 index 000000000000..c484a129293e --- /dev/null +++ b/Marlin/src/lcd/dogm/status/bed.h @@ -0,0 +1,110 @@ +/** + * 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 + +// +// lcd/dogm/status/bed.h - Status Screen Bed bitmaps +// + +#if ENABLED(STATUS_ALT_BED_BITMAP) + + #define STATUS_BED_ANIM + #define STATUS_BED_WIDTH 24 + #ifndef STATUS_BED_X + #define STATUS_BED_X (LCD_PIXEL_WIDTH - (STATUS_BED_BYTEWIDTH + STATUS_CHAMBER_BYTEWIDTH + STATUS_FAN_BYTEWIDTH) * 8) + #endif + #define STATUS_BED_TEXT_X (STATUS_BED_X + 11) + + const unsigned char status_bed_bmp[] PROGMEM = { + B11111111,B11111111,B11000000, + B01000000,B00000000,B00100000, + B00100000,B00000000,B00010000, + B00010000,B00000000,B00001000, + B00001000,B00000000,B00000100, + B00000100,B00000000,B00000010, + B00000011,B11111111,B11111111 + }; + + const unsigned char status_bed_on_bmp[] PROGMEM = { + B00000010,B00100010,B00000000, + B00000100,B01000100,B00000000, + B00000100,B01000100,B00000000, + B00000010,B00100010,B00000000, + B00000001,B00010001,B00000000, + B11111111,B11111111,B11000000, + B01000000,B10001000,B10100000, + B00100001,B00010001,B00010000, + B00010010,B00100010,B00001000, + B00001000,B00000000,B00000100, + B00000100,B00000000,B00000010, + B00000011,B11111111,B11111111 + }; + +#else + + #define STATUS_BED_WIDTH 21 + #ifndef STATUS_BED_X + #define STATUS_BED_X (LCD_PIXEL_WIDTH - (STATUS_BED_BYTEWIDTH + STATUS_CHAMBER_BYTEWIDTH + STATUS_FAN_BYTEWIDTH) * 8) + #endif + + #ifdef STATUS_BED_ANIM + + const unsigned char status_bed_bmp[] PROGMEM = { + B00011111,B11111111,B11111000, + B00011111,B11111111,B11111000 + }; + + const unsigned char status_bed_on_bmp[] PROGMEM = { + B00000100,B00010000,B01000000, + B00000010,B00001000,B00100000, + B00000010,B00001000,B00100000, + B00000100,B00010000,B01000000, + B00001000,B00100000,B10000000, + B00010000,B01000001,B00000000, + B00010000,B01000001,B00000000, + B00001000,B00100000,B10000000, + B00000100,B00010000,B01000000, + B00000000,B00000000,B00000000, + B00011111,B11111111,B11111000, + B00011111,B11111111,B11111000 + }; + + #else + + const unsigned char status_bed_bmp[] PROGMEM = { + B00000100,B00010000,B01000000, + B00000010,B00001000,B00100000, + B00000010,B00001000,B00100000, + B00000100,B00010000,B01000000, + B00001000,B00100000,B10000000, + B00010000,B01000001,B00000000, + B00010000,B01000001,B00000000, + B00001000,B00100000,B10000000, + B00000100,B00010000,B01000000, + B00000000,B00000000,B00000000, + B00011111,B11111111,B11111000, + B00011111,B11111111,B11111000 + }; + + #endif + +#endif diff --git a/Marlin/src/lcd/dogm/status/chamber.h b/Marlin/src/lcd/dogm/status/chamber.h new file mode 100644 index 000000000000..787a90884ae8 --- /dev/null +++ b/Marlin/src/lcd/dogm/status/chamber.h @@ -0,0 +1,89 @@ +/** + * 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 + +// +// lcd/dogm/status/chamber.h - Status Screen Chamber bitmaps +// + +#define STATUS_CHAMBER_WIDTH 21 +#if STATUS_HEATERS_WIDTH + #if ENABLED(STATUS_COMBINE_HEATERS) + #define STATUS_CHAMBER_X (LCD_PIXEL_WIDTH - 2 - (STATUS_CHAMBER_BYTEWIDTH) * 8) + #elif HAS_FAN0 && HAS_HEATED_BED && HOTENDS <= 2 + #define STATUS_CHAMBER_X (LCD_PIXEL_WIDTH - 2 - (STATUS_HEATERS_BYTEWIDTH - STATUS_CHAMBER_BYTEWIDTH) * 8) + #elif HAS_FAN0 && !HAS_HEATED_BED + #define STATUS_CHAMBER_X (LCD_PIXEL_WIDTH - (STATUS_CHAMBER_BYTEWIDTH + STATUS_FAN_BYTEWIDTH) * 8) + #else + #define STATUS_CHAMBER_X (LCD_PIXEL_WIDTH - (STATUS_CHAMBER_BYTEWIDTH) * 8) + #endif +#endif + +#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 + }; + 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 + }; + +#else + + const unsigned char status_chamber_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 + }; + +#endif diff --git a/Marlin/src/lcd/dogm/status/combined.h b/Marlin/src/lcd/dogm/status/combined.h new file mode 100644 index 000000000000..ca18f21af6d5 --- /dev/null +++ b/Marlin/src/lcd/dogm/status/combined.h @@ -0,0 +1,309 @@ +/** + * 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 + +// +// lcd/dogm/status/combined.h - Status Screen Combined Heater bitmaps +// + +#undef STATUS_HOTEND_ANIM +#undef STATUS_BED_ANIM +#define STATUS_HEATERS_XSPACE 24 + +// +// Status Screen Combined Heater bitmaps +// +#if HAS_HEATED_BED && HOTENDS <= 4 + + #if HOTENDS == 0 + + #define STATUS_HEATERS_WIDTH 96 + + const unsigned char status_heaters_bmp[] PROGMEM = { + B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000100,B00010000,B01000000, + B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000010,B00001000,B00100000, + B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000010,B00001000,B00100000, + B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000100,B00010000,B01000000, + B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00001000,B00100000,B10000000, + B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00010000,B01000001,B00000000, + B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00010000,B01000001,B00000000, + B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00001000,B00100000,B10000000, + B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000100,B00010000,B01000000, + B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000, + B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00011111,B11111111,B11111000, + B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00011111,B11111111,B11111000 + }; + + #elif HOTENDS == 1 + + #define STATUS_HEATERS_WIDTH 96 + + const unsigned char status_heaters_bmp[] PROGMEM = { + B00011111,B11100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000100,B00010000,B01000000, + B00111111,B11110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000010,B00001000,B00100000, + B00111111,B11110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000010,B00001000,B00100000, + B00111111,B11110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000100,B00010000,B01000000, + B00011111,B11100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00001000,B00100000,B10000000, + B00011111,B11100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00010000,B01000001,B00000000, + B00111111,B11110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00010000,B01000001,B00000000, + B00111111,B11110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00001000,B00100000,B10000000, + B00111111,B11110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000100,B00010000,B01000000, + B00001111,B11000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000, + B00000111,B10000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00011111,B11111111,B11111000, + B00000011,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00011111,B11111111,B11111000 + }; + + #elif HOTENDS == 2 + + #define STATUS_HEATERS_WIDTH 96 + + const unsigned char status_heaters_bmp[] PROGMEM = { + B00011111,B11100000,B00000000,B00011111,B11100000,B00000000,B00000000,B00000000,B00000000,B00000100,B00010000,B01000000, + #if LCD_FIRST_TOOL == 0 + B00111100,B11110000,B00000000,B00111110,B11110000,B00000000,B00000000,B00000000,B00000000,B00000010,B00001000,B00100000, + B00111011,B01110000,B00000000,B00111100,B11110000,B00000000,B00000000,B00000000,B00000000,B00000010,B00001000,B00100000, + B00111011,B01110000,B00000000,B00111010,B11110000,B00000000,B00000000,B00000000,B00000000,B00000100,B00010000,B01000000, + B00011011,B01100000,B00000000,B00011110,B11100000,B00000000,B00000000,B00000000,B00000000,B00001000,B00100000,B10000000, + B00011011,B01100000,B00000000,B00011110,B11100000,B00000000,B00000000,B00000000,B00000000,B00010000,B01000001,B00000000, + B00111011,B01110000,B00000000,B00111110,B11110000,B00000000,B00000000,B00000000,B00000000,B00010000,B01000001,B00000000, + B00111100,B11110000,B00000000,B00111110,B11110000,B00000000,B00000000,B00000000,B00000000,B00001000,B00100000,B10000000, + #else + B00111110,B11110000,B00000000,B00111100,B11110000,B00000000,B00000000,B00000000,B00000000,B00000010,B00001000,B00100000, + B00111100,B11110000,B00000000,B00111011,B01110000,B00000000,B00000000,B00000000,B00000000,B00000010,B00001000,B00100000, + B00111010,B11110000,B00000000,B00111111,B01110000,B00000000,B00000000,B00000000,B00000000,B00000100,B00010000,B01000000, + B00011110,B11100000,B00000000,B00011110,B11100000,B00000000,B00000000,B00000000,B00000000,B00001000,B00100000,B10000000, + B00011110,B11100000,B00000000,B00011101,B11100000,B00000000,B00000000,B00000000,B00000000,B00010000,B01000001,B00000000, + B00111110,B11110000,B00000000,B00111011,B11110000,B00000000,B00000000,B00000000,B00000000,B00010000,B01000001,B00000000, + B00111110,B11110000,B00000000,B00111000,B01110000,B00000000,B00000000,B00000000,B00000000,B00001000,B00100000,B10000000, + #endif + B00111111,B11110000,B00000000,B00111111,B11110000,B00000000,B00000000,B00000000,B00000000,B00000100,B00010000,B01000000, + B00001111,B11000000,B00000000,B00001111,B11000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000, + B00000111,B10000000,B00000000,B00000111,B10000000,B00000000,B00000000,B00000000,B00000000,B00011111,B11111111,B11111000, + B00000011,B00000000,B00000000,B00000011,B00000000,B00000000,B00000000,B00000000,B00000000,B00011111,B11111111,B11111000 + }; + + #elif HOTENDS == 3 + + #define STATUS_HEATERS_WIDTH 96 + + const unsigned char status_heaters_bmp[] PROGMEM = { + B00011111,B11100000,B00000000,B00011111,B11100000,B00000000,B00011111,B11100000,B00000000,B00000100,B00010000,B01000000, + #if LCD_FIRST_TOOL == 0 + B00111100,B11110000,B00000000,B00111110,B11110000,B00000000,B00111100,B11110000,B00000000,B00000010,B00001000,B00100000, + B00111011,B01110000,B00000000,B00111100,B11110000,B00000000,B00111011,B01110000,B00000000,B00000010,B00001000,B00100000, + B00111011,B01110000,B00000000,B00111010,B11110000,B00000000,B00111111,B01110000,B00000000,B00000100,B00010000,B01000000, + B00011011,B01100000,B00000000,B00011110,B11100000,B00000000,B00011110,B11100000,B00000000,B00001000,B00100000,B10000000, + B00011011,B01100000,B00000000,B00011110,B11100000,B00000000,B00011101,B11100000,B00000000,B00010000,B01000001,B00000000, + B00111011,B01110000,B00000000,B00111110,B11110000,B00000000,B00111011,B11110000,B00000000,B00010000,B01000001,B00000000, + B00111100,B11110000,B00000000,B00111110,B11110000,B00000000,B00111000,B01110000,B00000000,B00001000,B00100000,B10000000, + #else + B00111110,B11110000,B00000000,B00111100,B11110000,B00000000,B00111100,B11110000,B00000000,B00000010,B00001000,B00100000, + B00111100,B11110000,B00000000,B00111011,B01110000,B00000000,B00111011,B01110000,B00000000,B00000010,B00001000,B00100000, + B00111010,B11110000,B00000000,B00111111,B01110000,B00000000,B00111111,B01110000,B00000000,B00000100,B00010000,B01000000, + B00011110,B11100000,B00000000,B00011110,B11100000,B00000000,B00011100,B11100000,B00000000,B00001000,B00100000,B10000000, + B00011110,B11100000,B00000000,B00011101,B11100000,B00000000,B00011111,B01100000,B00000000,B00010000,B01000001,B00000000, + B00111110,B11110000,B00000000,B00111011,B11110000,B00000000,B00111011,B01110000,B00000000,B00010000,B01000001,B00000000, + B00111110,B11110000,B00000000,B00111000,B01110000,B00000000,B00111100,B11110000,B00000000,B00001000,B00100000,B10000000, + #endif + B00111111,B11110000,B00000000,B00111111,B11110000,B00000000,B00111111,B11110000,B00000000,B00000100,B00010000,B01000000, + B00001111,B11000000,B00000000,B00001111,B11000000,B00000000,B00001111,B11000000,B00000000,B00000000,B00000000,B00000000, + B00000111,B10000000,B00000000,B00000111,B10000000,B00000000,B00000111,B10000000,B00000000,B00011111,B11111111,B11111000, + B00000011,B00000000,B00000000,B00000011,B00000000,B00000000,B00000011,B00000000,B00000000,B00011111,B11111111,B11111000 + }; + + #else // HOTENDS > 3 + + #define STATUS_HEATERS_WIDTH 120 + + const unsigned char status_heaters_bmp[] PROGMEM = { + B00011111,B11100000,B00000000,B00011111,B11100000,B00000000,B00011111,B11100000,B00000000,B00011111,B11100000,B00000000,B00000100,B00010000,B01000000, + #if LCD_FIRST_TOOL == 0 + B00111100,B11110000,B00000000,B00111110,B11110000,B00000000,B00111100,B11110000,B00000000,B00111100,B11110000,B00000000,B00000010,B00001000,B00100000, + B00111011,B01110000,B00000000,B00111100,B11110000,B00000000,B00111011,B01110000,B00000000,B00111011,B01110000,B00000000,B00000010,B00001000,B00100000, + B00111011,B01110000,B00000000,B00111010,B11110000,B00000000,B00111111,B01110000,B00000000,B00111111,B01110000,B00000000,B00000100,B00010000,B01000000, + B00011011,B01100000,B00000000,B00011110,B11100000,B00000000,B00011110,B11100000,B00000000,B00011100,B11100000,B00000000,B00001000,B00100000,B10000000, + B00011011,B01100000,B00000000,B00011110,B11100000,B00000000,B00011101,B11100000,B00000000,B00011111,B01100000,B00000000,B00010000,B01000001,B00000000, + B00111011,B01110000,B00000000,B00111110,B11110000,B00000000,B00111011,B11110000,B00000000,B00111011,B01110000,B00000000,B00010000,B01000001,B00000000, + B00111100,B11110000,B00000000,B00111110,B11110000,B00000000,B00111000,B01110000,B00000000,B00111100,B11110000,B00000000,B00001000,B00100000,B10000000, + #else + B00111110,B11110000,B00000000,B00111100,B11110000,B00000000,B00111100,B11110000,B00000000,B00111011,B01110000,B00000000,B00000010,B00001000,B00100000, + B00111100,B11110000,B00000000,B00111011,B01110000,B00000000,B00111011,B01110000,B00000000,B00111011,B01110000,B00000000,B00000010,B00001000,B00100000, + B00111010,B11110000,B00000000,B00111111,B01110000,B00000000,B00111111,B01110000,B00000000,B00111011,B01110000,B00000000,B00000100,B00010000,B01000000, + B00011110,B11100000,B00000000,B00011110,B11100000,B00000000,B00011100,B11100000,B00000000,B00011011,B01100000,B00000000,B00001000,B00100000,B10000000, + B00011110,B11100000,B00000000,B00011101,B11100000,B00000000,B00011111,B01100000,B00000000,B00011000,B00100000,B00000000,B00010000,B01000001,B00000000, + B00111110,B11110000,B00000000,B00111011,B11110000,B00000000,B00111011,B01110000,B00000000,B00111111,B01110000,B00000000,B00010000,B01000001,B00000000, + B00111110,B11110000,B00000000,B00111000,B01110000,B00000000,B00111100,B11110000,B00000000,B00111111,B01110000,B00000000,B00001000,B00100000,B10000000, + #endif + B00111111,B11110000,B00000000,B00111111,B11110000,B00000000,B00111111,B11110000,B00000000,B00111111,B11110000,B00000000,B00000100,B00010000,B01000000, + B00001111,B11000000,B00000000,B00001111,B11000000,B00000000,B00001111,B11000000,B00000000,B00001111,B11000000,B00000000,B00000000,B00000000,B00000000, + B00000111,B10000000,B00000000,B00000111,B10000000,B00000000,B00000111,B10000000,B00000000,B00000111,B10000000,B00000000,B00011111,B11111111,B11111000, + B00000011,B00000000,B00000000,B00000011,B00000000,B00000000,B00000011,B00000000,B00000000,B00000011,B00000000,B00000000,B00011111,B11111111,B11111000 + }; + + #endif // HOTENDS + + #define STATUS_BED_TEXT_X (STATUS_HEATERS_WIDTH - 10) + +#else // !HAS_HEATED_BED || HOTENDS > 3 + + #if HOTENDS == 0 + + #define STATUS_HEATERS_WIDTH 0 + + #elif HOTENDS == 1 + + #define STATUS_HEATERS_WIDTH 12 + + const unsigned char status_heaters_bmp[] PROGMEM = { + B00011111,B11100000, + B00111111,B11110000, + B00111111,B11110000, + B00111111,B11110000, + B00011111,B11100000, + B00011111,B11100000, + B00111111,B11110000, + B00111111,B11110000, + B00111111,B11110000, + B00001111,B11000000, + B00000111,B10000000, + B00000011,B00000000 + }; + + #elif HOTENDS == 2 + + #define STATUS_HEATERS_WIDTH 36 + + const unsigned char status_heaters_bmp[] PROGMEM = { + B00011111,B11100000,B00000000,B00011111,B11100000, + #if LCD_FIRST_TOOL == 0 + B00111100,B11110000,B00000000,B00111110,B11110000, + B00111011,B01110000,B00000000,B00111100,B11110000, + B00111011,B01110000,B00000000,B00111010,B11110000, + B00011011,B01100000,B00000000,B00011110,B11100000, + B00011011,B01100000,B00000000,B00011110,B11100000, + B00111011,B01110000,B00000000,B00111110,B11110000, + B00111100,B11110000,B00000000,B00111110,B11110000, + #else + B00111110,B11110000,B00000000,B00111100,B11110000, + B00111100,B11110000,B00000000,B00111011,B01110000, + B00111010,B11110000,B00000000,B00111111,B01110000, + B00011110,B11100000,B00000000,B00011110,B11100000, + B00011110,B11100000,B00000000,B00011101,B11100000, + B00111110,B11110000,B00000000,B00111011,B11110000, + B00111110,B11110000,B00000000,B00111000,B01110000, + #endif + B00111111,B11110000,B00000000,B00111111,B11110000, + B00001111,B11000000,B00000000,B00001111,B11000000, + B00000111,B10000000,B00000000,B00000111,B10000000, + B00000011,B00000000,B00000000,B00000011,B00000000 + }; + + #elif HOTENDS == 3 + + #define STATUS_HEATERS_WIDTH 60 + + const unsigned char status_heaters_bmp[] PROGMEM = { + B00011111,B11100000,B00000000,B00011111,B11100000,B00000000,B00011111,B11100000, + #if LCD_FIRST_TOOL == 0 + B00111100,B11110000,B00000000,B00111110,B11110000,B00000000,B00111100,B11110000, + B00111011,B01110000,B00000000,B00111100,B11110000,B00000000,B00111011,B01110000, + B00111011,B01110000,B00000000,B00111010,B11110000,B00000000,B00111111,B01110000, + B00011011,B01100000,B00000000,B00011110,B11100000,B00000000,B00011110,B11100000, + B00011011,B01100000,B00000000,B00011110,B11100000,B00000000,B00011101,B11100000, + B00111011,B01110000,B00000000,B00111110,B11110000,B00000000,B00111011,B11110000, + B00111100,B11110000,B00000000,B00111110,B11110000,B00000000,B00111000,B01110000, + #else + B00111110,B11110000,B00000000,B00111100,B11110000,B00000000,B00111100,B11110000, + B00111100,B11110000,B00000000,B00111011,B01110000,B00000000,B00111011,B01110000, + B00111010,B11110000,B00000000,B00111111,B01110000,B00000000,B00111111,B01110000, + B00011110,B11100000,B00000000,B00011110,B11100000,B00000000,B00011100,B11100000, + B00011110,B11100000,B00000000,B00011101,B11100000,B00000000,B00011111,B01100000, + B00111110,B11110000,B00000000,B00111011,B11110000,B00000000,B00111011,B01110000, + B00111110,B11110000,B00000000,B00111000,B01110000,B00000000,B00111100,B11110000, + #endif + B00111111,B11110000,B00000000,B00111111,B11110000,B00000000,B00111111,B11110000, + B00001111,B11000000,B00000000,B00001111,B11000000,B00000000,B00001111,B11000000, + B00000111,B10000000,B00000000,B00000111,B10000000,B00000000,B00000111,B10000000, + B00000011,B00000000,B00000000,B00000011,B00000000,B00000000,B00000011,B00000000 + }; + + #elif HOTENDS == 4 + + #define STATUS_HEATERS_WIDTH 84 + + const unsigned char status_heaters_bmp[] PROGMEM = { + B00011111,B11100000,B00000000,B00011111,B11100000,B00000000,B00011111,B11100000,B00000000,B00011111,B11100000, + #if LCD_FIRST_TOOL == 0 + B00111100,B11110000,B00000000,B00111110,B11110000,B00000000,B00111100,B11110000,B00000000,B00111100,B11110000, + B00111011,B01110000,B00000000,B00111100,B11110000,B00000000,B00111011,B01110000,B00000000,B00111011,B01110000, + B00111011,B01110000,B00000000,B00111010,B11110000,B00000000,B00111111,B01110000,B00000000,B00111111,B01110000, + B00011011,B01100000,B00000000,B00011110,B11100000,B00000000,B00011110,B11100000,B00000000,B00011100,B11100000, + B00011011,B01100000,B00000000,B00011110,B11100000,B00000000,B00011101,B11100000,B00000000,B00011111,B01100000, + B00111011,B01110000,B00000000,B00111110,B11110000,B00000000,B00111011,B11110000,B00000000,B00111011,B01110000, + B00111100,B11110000,B00000000,B00111110,B11110000,B00000000,B00111000,B01110000,B00000000,B00111100,B11110000, + #else + B00111110,B11110000,B00000000,B00111100,B11110000,B00000000,B00111100,B11110000,B00000000,B00111011,B01110000, + B00111100,B11110000,B00000000,B00111011,B01110000,B00000000,B00111011,B01110000,B00000000,B00111011,B01110000, + B00111010,B11110000,B00000000,B00111111,B01110000,B00000000,B00111111,B01110000,B00000000,B00111011,B01110000, + B00011110,B11100000,B00000000,B00011110,B11100000,B00000000,B00011100,B11100000,B00000000,B00011011,B01100000, + B00011110,B11100000,B00000000,B00011101,B11100000,B00000000,B00011111,B01100000,B00000000,B00011000,B00100000, + B00111110,B11110000,B00000000,B00111011,B11110000,B00000000,B00111011,B01110000,B00000000,B00111111,B01110000, + B00111110,B11110000,B00000000,B00111000,B01110000,B00000000,B00111100,B11110000,B00000000,B00111111,B01110000, + #endif + B00111111,B11110000,B00000000,B00111111,B11110000,B00000000,B00111111,B11110000,B00000000,B00111111,B11110000, + B00001111,B11000000,B00000000,B00001111,B11000000,B00000000,B00001111,B11000000,B00000000,B00001111,B11000000, + B00000111,B10000000,B00000000,B00000111,B10000000,B00000000,B00000111,B10000000,B00000000,B00000111,B10000000, + B00000011,B00000000,B00000000,B00000011,B00000000,B00000000,B00000011,B00000000,B00000000,B00000011,B00000000 + }; + + #else // HOTENDS > 4 + + #define STATUS_HEATERS_WIDTH 108 + + const unsigned char status_heaters_bmp[] PROGMEM = { + B00011111,B11100000,B00000000,B00011111,B11100000,B00000000,B00011111,B11100000,B00000000,B00011111,B11100000,B00000000,B00011111,B11100000, + #if LCD_FIRST_TOOL == 0 + B00111100,B11110000,B00000000,B00111110,B11110000,B00000000,B00111100,B11110000,B00000000,B00111100,B11110000,B00000000,B00111011,B01110000, + B00111011,B01110000,B00000000,B00111100,B11110000,B00000000,B00111011,B01110000,B00000000,B00111011,B01110000,B00000000,B00111011,B01110000, + B00111011,B01110000,B00000000,B00111010,B11110000,B00000000,B00111111,B01110000,B00000000,B00111111,B01110000,B00000000,B00111011,B01110000, + B00011011,B01100000,B00000000,B00011110,B11100000,B00000000,B00011110,B11100000,B00000000,B00011100,B11100000,B00000000,B00011011,B01100000, + B00011011,B01100000,B00000000,B00011110,B11100000,B00000000,B00011101,B11100000,B00000000,B00011111,B01100000,B00000000,B00011000,B00100000, + B00111011,B01110000,B00000000,B00111110,B11110000,B00000000,B00111011,B11110000,B00000000,B00111011,B01110000,B00000000,B00111111,B01110000, + B00111100,B11110000,B00000000,B00111110,B11110000,B00000000,B00111000,B01110000,B00000000,B00111100,B11110000,B00000000,B00111111,B01110000, + #else + B00111110,B11110000,B00000000,B00111100,B11110000,B00000000,B00111100,B11110000,B00000000,B00111011,B01110000,B00000000,B00111000,B01110000, + B00111100,B11110000,B00000000,B00111011,B01110000,B00000000,B00111011,B01110000,B00000000,B00111011,B01110000,B00000000,B00111011,B11110000, + B00111010,B11110000,B00000000,B00111111,B01110000,B00000000,B00111111,B01110000,B00000000,B00111011,B01110000,B00000000,B00111000,B11110000, + B00011110,B11100000,B00000000,B00011110,B11100000,B00000000,B00011100,B11100000,B00000000,B00011011,B01100000,B00000000,B00011111,B01100000, + B00011110,B11100000,B00000000,B00011101,B11100000,B00000000,B00011111,B01100000,B00000000,B00011000,B00100000,B00000000,B00011111,B01100000, + B00111110,B11110000,B00000000,B00111011,B11110000,B00000000,B00111011,B01110000,B00000000,B00111111,B01110000,B00000000,B00111011,B01110000, + B00111110,B11110000,B00000000,B00111000,B01110000,B00000000,B00111100,B11110000,B00000000,B00111111,B01110000,B00000000,B00111100,B11110000, + #endif + B00111111,B11110000,B00000000,B00111111,B11110000,B00000000,B00111111,B11110000,B00000000,B00111111,B11110000,B00000000,B00111111,B11110000, + B00001111,B11000000,B00000000,B00001111,B11000000,B00000000,B00001111,B11000000,B00000000,B00001111,B11000000,B00000000,B00001111,B11000000, + B00000111,B10000000,B00000000,B00000111,B10000000,B00000000,B00000111,B10000000,B00000000,B00000111,B10000000,B00000000,B00000111,B10000000, + B00000011,B00000000,B00000000,B00000011,B00000000,B00000000,B00000011,B00000000,B00000000,B00000011,B00000000,B00000000,B00000011,B00000000 + }; + + #endif // HOTENDS + +#endif // !HAS_HEATED_BED || HOTENDS > 3 diff --git a/Marlin/src/lcd/dogm/status/cooler.h b/Marlin/src/lcd/dogm/status/cooler.h new file mode 100644 index 000000000000..65c28ec28e15 --- /dev/null +++ b/Marlin/src/lcd/dogm/status/cooler.h @@ -0,0 +1,119 @@ +/** + * 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 + +// +// lcd/dogm/status/cooler.h - Status Screen Laser Cooler bitmaps +// +#if HAS_COOLER + + #define STATUS_COOLER_WIDTH 22 + + const unsigned char status_cooler_bmp2[] PROGMEM = { + B00000001,B00000000,B10000000, + B00000001,B00100100,B10010000, + B00000101,B01000010,B10100000, + B00000011,B10000001,B11000000, + B00001111,B11101111,B11110000, + B00000011,B10000001,B11000000, + B00000101,B01000010,B10100000, + B00001001,B00001000,B10010000, + B00000001,B00001000,B00000000, + B00000000,B01001001,B00000000, + B00000000,B00101010,B00000000, + B00000000,B00011100,B00000000, + B00000001,B11111111,B11000000, + B00000000,B00011100,B00000000, + B00000000,B00101010,B00000000, + B00000000,B01001001,B00000000 + }; + const unsigned char status_cooler_bmp1[] PROGMEM = { + B00000001,B00000000,B10000000, + B00000001,B00100100,B10010000, + B00000101,B01000010,B10100000, + B00000010,B10000001,B01000000, + B00001100,B01110110,B00110000, + B00000010,B10000001,B01000000, + B00000101,B01000010,B10100000, + B00001001,B00001000,B10010000, + B00000001,B00001000,B00000000, + B00000000,B01001001,B00000000, + B00000000,B00101010,B00000000, + B00000000,B00010100,B00000000, + B00000001,B11100011,B11000000, + B00000000,B00010100,B00000000, + B00000000,B00101010,B00000000, + B00000000,B01001001,B00000000 + }; + +#endif + +#if ENABLED(LASER_COOLANT_FLOW_METER) + + #define STATUS_FLOWMETER_WIDTH 24 + + const unsigned char status_flowmeter_bmp2[] PROGMEM = { + B00000000,B01111110,B00000000, + B00000001,B10000001,B10000000, + B00000010,B00011000,B01000000, + B00000100,B00011000,B00100000, + B00001000,B00011000,B00010000, + B00001000,B00011000,B00010000, + B00010000,B00011000,B00001000, + B00010000,B00011000,B00001000, + B00010111,B11111111,B11101000, + B00010111,B11111111,B11101000, + B00010000,B00011000,B00001000, + B00010000,B00011000,B00001000, + B00001000,B00011000,B00010000, + B00001000,B00011000,B00010000, + B00000100,B00011000,B00100000, + B00000010,B00011000,B01000000, + B00000001,B10000001,B10000000, + B00000000,B01111110,B00000000, + B00000000,B00011000,B00000000, + B00000111,B11111111,B11100000 + }; + const unsigned char status_flowmeter_bmp1[] PROGMEM = { + B00000000,B01111110,B00000000, + B00000001,B10000001,B10000000, + B00000010,B00000000,B01000000, + B00000101,B00000000,B10100000, + B00001011,B10000001,B11010000, + B00001001,B11000011,B10010000, + B00010000,B11100111,B00001000, + B00010000,B01111110,B00001000, + B00010000,B00111100,B00001000, + B00010000,B00111100,B00001000, + B00010000,B01111110,B00001000, + B00010000,B11100111,B00001000, + B00001001,B11000011,B10010000, + B00001011,B10000001,B11010000, + B00000101,B00000000,B10100000, + B00000010,B00000000,B01000000, + B00000001,B10000001,B10000000, + B00000000,B01111110,B00000000, + B00000000,B00011000,B00000000, + B00000111,B11111111,B11100000 + }; + +#endif diff --git a/Marlin/src/lcd/dogm/status/cutter.h b/Marlin/src/lcd/dogm/status/cutter.h new file mode 100644 index 000000000000..0e3b9dd18851 --- /dev/null +++ b/Marlin/src/lcd/dogm/status/cutter.h @@ -0,0 +1,123 @@ +/** + * 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 + +// +// lcd/dogm/status/cutter.h - Status Screen Laser / Spindle bitmaps +// + +#define STATUS_CUTTER_WIDTH 24 +#define STATUS_CUTTER_X 80 + +#if ENABLED(LASER_FEATURE) + #ifdef STATUS_CUTTER_ANIM + const unsigned char status_cutter_on_bmp[] PROGMEM = { + B00000000,B00100100,B00000000, + B00000000,B01100110,B00000000, + B00000000,B11000011,B00000000, + B00000001,B10011001,B10000000, + B00000011,B00100100,B11000000, + B00000000,B01000010,B00000000, + B00000000,B01000010,B00000000, + B00000011,B00100100,B11000000, + B00000001,B10011001,B10000000, + B00000000,B11000011,B00000000, + B00000000,B01100110,B00000000, + B00000000,B00100100,B00000000 + }; + const unsigned char status_cutter_bmp[] PROGMEM = { + B00000000,B00100100,B00000000, + B00000000,B01100110,B00000000, + B00000000,B00000000,B00000000, + B00000001,B00000000,B10000000, + B00000011,B00000000,B11000000, + B00000000,B00011000,B00000000, + B00000000,B00011000,B00000000, + B00000011,B00000000,B11000000, + B00000001,B00000000,B10000000, + B00000000,B00000000,B00000000, + B00000000,B01100110,B00000000, + B00000000,B00100100,B00000000 + }; + #else + const unsigned char status_cutter_bmp[] PROGMEM = { + B00000000,B00100100,B00000000, + B00000000,B01100110,B00000000, + B00000000,B11000011,B00000000, + B00000001,B10000001,B10000000, + B00000011,B00000000,B11000000, + B00000000,B00000000,B00000000, + B00000000,B00000000,B00000000, + B00000011,B00000000,B11000000, + B00000001,B10000001,B10000000, + B00000000,B11000011,B00000000, + B00000000,B01100110,B00000000, + B00000000,B00100100,B00000000 + }; + #endif +#else + #ifdef STATUS_CUTTER_ANIM + const unsigned char status_cutter_on_bmp[] PROGMEM = { + B00000001,B11111110,B10000000, + B00000000,B11000000,B00000000, + B00000001,B10000000,B10000000, + B00000001,B00000000,B10000000, + B00000001,B11111100,B10000000, + B00000000,B11100000,B00000000, + B00000001,B11000000,B10000000, + B00000000,B10000001,B00000000, + B00000000,B01111010,B00000000, + B00000000,B00110100,B00000000, + B00000000,B00011000,B00000000, + B00000000,B00000000,B00000000 + }; + const unsigned char status_cutter_bmp[] PROGMEM = { + B00000001,B11111110,B10000000, + B00000000,B11000000,B00000000, + B00000001,B10000000,B10000000, + B00000001,B00000000,B10000000, + B00000001,B11111100,B10000000, + B00000000,B11100000,B00000000, + B00000001,B11000000,B10000000, + B00000000,B10000001,B00000000, + B00000000,B01111010,B00000000, + B00000000,B00110100,B00000000, + B00000000,B00011000,B00000000, + B00000000,B00000000,B00000000 + }; + #else + const unsigned char status_cutter_bmp[] PROGMEM = { + B00000001,B11000010,B10000000, + B00000001,B00011100,B10000000, + B00000000,B11100001,B00000000, + B00000001,B00001110,B10000000, + B00000001,B01110000,B10000000, + B00000000,B10000111,B10000000, + B00000001,B00111111,B10000000, + B00000000,B11111111,B00000000, + B00000000,B01111110,B00000000, + B00000000,B00111100,B00000000, + B00000000,B00011000,B00000000, + B00000000,B00000000,B00000000 + }; + #endif +#endif diff --git a/Marlin/src/lcd/dogm/status/fan.h b/Marlin/src/lcd/dogm/status/fan.h new file mode 100644 index 000000000000..65f8e9c2300d --- /dev/null +++ b/Marlin/src/lcd/dogm/status/fan.h @@ -0,0 +1,443 @@ +/** + * 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 + +// +// lcd/dogm/status/fan.h - Status Screen Fan bitmaps +// + +#undef STATUS_FAN_WIDTH +#define STATUS_FAN_WIDTH 20 + +#if STATUS_FAN_FRAMES <= 2 + + #define STATUS_FAN_Y 2 + + #if ENABLED(STATUS_ALT_FAN_BITMAP) + + const unsigned char status_fan0_bmp[] PROGMEM = { + B00000001,B11111110,B00000000, + B00000110,B00000001,B10000000, + B00001000,B11111100,B01000000, + B00010000,B11111100,B00100000, + B00010000,B01111000,B00100000, + B00100000,B00110000,B00010000, + B00101100,B00000000,B11010000, + B00101110,B00110001,B11010000, + B00101111,B01111011,B11010000, + B00101111,B01111011,B11010000, + B00101110,B00110001,B11010000, + B00101100,B00000000,B11010000, + B00100000,B00110000,B00010000, + B00010000,B01111000,B00100000, + B00010000,B11111100,B00100000, + B00001000,B11111100,B01000000, + B00000110,B00000001,B10000000, + B00000001,B11111110,B00000000 + }; + + #if STATUS_FAN_FRAMES == 2 + const unsigned char status_fan1_bmp[] PROGMEM = { + B00000001,B11111110,B00000000, + B00000110,B00000001,B10000000, + B00001001,B10000110,B01000000, + B00010011,B10000111,B00100000, + B00010111,B10000111,B10100000, + B00101111,B10000111,B11010000, + B00101111,B00000011,B11010000, + B00100000,B00110000,B00010000, + B00100000,B01111000,B00010000, + B00100000,B01111000,B00010000, + B00100000,B00110000,B00010000, + B00101111,B00000011,B11010000, + B00101111,B10000111,B11010000, + B00010111,B10000111,B10100000, + B00010011,B10000111,B00100000, + B00001001,B10000110,B01000000, + B00000110,B00000001,B10000000, + B00000001,B11111110,B00000000 + }; + #endif + + #else // !STATUS_ALT_FAN_BITMAP + + const unsigned char status_fan0_bmp[] PROGMEM = { + B00111111,B11111111,B11110000, + B00111000,B00000000,B01110000, + B00110000,B11111100,B00110000, + B00100000,B11111100,B00010000, + B00100000,B01111000,B00010000, + B00100000,B00110000,B00010000, + B00101100,B00000000,B11010000, + B00101110,B00110001,B11010000, + B00101111,B01111011,B11010000, + B00101111,B01111011,B11010000, + B00101110,B00110001,B11010000, + B00101100,B00000000,B11010000, + B00100000,B00110000,B00010000, + B00100000,B01111000,B00010000, + B00100000,B11111100,B00010000, + B00110000,B11111100,B00110000, + B00111000,B00000000,B01110000, + B00111111,B11111111,B11110000 + }; + + #if STATUS_FAN_FRAMES == 2 + const unsigned char status_fan1_bmp[] PROGMEM = { + B00111111,B11111111,B11110000, + B00111000,B00000000,B01110000, + B00110001,B10000110,B00110000, + B00100011,B10000111,B00010000, + B00100111,B10000111,B10010000, + B00101111,B10000111,B11010000, + B00101111,B00000011,B11010000, + B00100000,B00110000,B00010000, + B00100000,B01111000,B00010000, + B00100000,B01111000,B00010000, + B00100000,B00110000,B00010000, + B00101111,B00000011,B11010000, + B00101111,B10000111,B11010000, + B00100111,B10000111,B10010000, + B00100011,B10000111,B00010000, + B00110001,B10000110,B00110000, + B00111000,B00000000,B01110000, + B00111111,B11111111,B11110000 + }; + #endif + + #endif // !STATUS_ALT_FAN_BITMAP + +#elif STATUS_FAN_FRAMES == 3 + + #if ENABLED(STATUS_ALT_FAN_BITMAP) + + const unsigned char status_fan0_bmp[] PROGMEM = { + B00000001,B11111111,B00000000, + B00000110,B00000000,B11000000, + B00001001,B00000001,B00100000, + B00010111,B10000011,B11010000, + B00010111,B10000011,B11010000, + B00101111,B11000111,B11101000, + B00100111,B11000111,B11001000, + B00100001,B11111111,B00001000, + B00100000,B01111100,B00001000, + B00100000,B01111100,B00001000, + B00100000,B01111100,B00001000, + B00100001,B11111111,B00001000, + B00100111,B11000111,B11001000, + B00101111,B11000111,B11101000, + B00010111,B10000011,B11010000, + B00010111,B10000011,B11010000, + B00001001,B00000001,B00100000, + B00000110,B00000000,B11000000, + B00000001,B11111111,B00000000 + }; + const unsigned char status_fan1_bmp[] PROGMEM = { + B00000001,B11111111,B00000000, + B00000110,B00110000,B11000000, + B00001001,B11110000,B00100000, + B00010001,B11110000,B00010000, + B00010000,B11110000,B00010000, + B00100000,B11110000,B01101000, + B00100000,B00110001,B11101000, + B00100000,B00111001,B11101000, + B00100000,B01111111,B11111000, + B00111111,B11111111,B11111000, + B00111111,B11111100,B00001000, + B00101111,B00111000,B00001000, + B00101110,B00011000,B00001000, + B00101100,B00011110,B00001000, + B00010000,B00011110,B00010000, + B00010000,B00011111,B00010000, + B00001000,B00011111,B00100000, + B00000110,B00011000,B11000000, + B00000001,B11111111,B00000000 + }; + const unsigned char status_fan2_bmp[] PROGMEM = { + B00000001,B11111111,B00000000, + B00000110,B00011000,B11000000, + B00001000,B00011111,B00100000, + B00010000,B00011111,B10010000, + B00010100,B00011111,B00010000, + B00101110,B00011110,B00001000, + B00101111,B00011100,B00001000, + B00101111,B10111000,B00001000, + B00111111,B11111100,B00001000, + B00111111,B11111111,B11111000, + B00100000,B01111111,B11111000, + B00100000,B00111011,B11101000, + B00100000,B01110001,B11101000, + B00100000,B11110000,B11101000, + B00010001,B11110000,B01010000, + B00010011,B11110000,B00010000, + B00001001,B11110000,B00100000, + B00000110,B00110000,B11000000, + B00000001,B11111111,B00000000 + }; + + #else // !STATUS_ALT_FAN_BITMAP + + const unsigned char status_fan0_bmp[] PROGMEM = { + B00111111,B11111111,B11111000, + B00111110,B00000000,B11111000, + B00111001,B00000001,B00111000, + B00110111,B10000011,B11011000, + B00110111,B10000011,B11011000, + B00101111,B11000111,B11101000, + B00100111,B11000111,B11001000, + B00100001,B11111111,B00001000, + B00100000,B01111100,B00001000, + B00100000,B01111100,B00001000, + B00100000,B01111100,B00001000, + B00100001,B11111111,B00001000, + B00100111,B11000111,B11001000, + B00101111,B11000111,B11101000, + B00110111,B10000011,B11011000, + B00110111,B10000011,B11011000, + B00111001,B00000001,B00111000, + B00111110,B00000000,B11111000, + B00111111,B11111111,B11111000 + }; + const unsigned char status_fan1_bmp[] PROGMEM = { + B00111111,B11111111,B11111000, + B00111110,B00110000,B11111000, + B00111001,B11110000,B00111000, + B00110001,B11110000,B00011000, + B00110000,B11110000,B00011000, + B00100000,B11110000,B01101000, + B00100000,B00110001,B11101000, + B00100000,B00111001,B11101000, + B00100000,B01111111,B11111000, + B00111111,B11111111,B11111000, + B00111111,B11111100,B00001000, + B00101111,B00111000,B00001000, + B00101110,B00011000,B00001000, + B00101100,B00011110,B00001000, + B00110000,B00011110,B00011000, + B00110000,B00011111,B00011000, + B00111000,B00011111,B00111000, + B00111110,B00011000,B11111000, + B00111111,B11111111,B11111000 + }; + const unsigned char status_fan2_bmp[] PROGMEM = { + B00111111,B11111111,B11111000, + B00111110,B00011000,B11111000, + B00111000,B00011111,B00111000, + B00110000,B00011111,B10011000, + B00110100,B00011111,B00011000, + B00101110,B00011110,B00001000, + B00101111,B00011100,B00001000, + B00101111,B10111000,B00001000, + B00111111,B11111100,B00001000, + B00111111,B11111111,B11111000, + B00100000,B01111111,B11111000, + B00100000,B00111011,B11101000, + B00100000,B01110001,B11101000, + B00100000,B11110000,B11101000, + B00110001,B11110000,B01011000, + B00110011,B11110000,B00011000, + B00111001,B11110000,B00111000, + B00111110,B00110000,B11111000, + B00111111,B11111111,B11111000 + }; + + #endif // !STATUS_ALT_FAN_BITMAP + +#elif STATUS_FAN_FRAMES == 4 + + #if ENABLED(STATUS_ALT_FAN_BITMAP) + + const unsigned char status_fan0_bmp[] PROGMEM = { + B00000001,B11111111,B00000000, + B00000110,B00000000,B11000000, + B00001000,B00111111,B00100000, + B00010000,B01111110,B00010000, + B00010000,B01111100,B00010000, + B00101000,B01111100,B00001000, + B00101100,B00111000,B00001000, + B00101111,B00111001,B11001000, + B00101111,B11111111,B11101000, + B00101111,B11000111,B11101000, + B00101111,B11111111,B11101000, + B00100111,B00111001,B11101000, + B00100000,B00111000,B01101000, + B00100000,B01111100,B00101000, + B00010000,B01111100,B00010000, + B00010000,B11111100,B00010000, + B00001001,B11111000,B00100000, + B00000110,B00000000,B11000000, + B00000001,B11111111,B00000000 + }; + const unsigned char status_fan1_bmp[] PROGMEM = { + B00000001,B11111111,B00000000, + B00000110,B00000000,B11000000, + B00001000,B00001111,B00100000, + B00010100,B00011111,B11010000, + B00010110,B00011111,B10010000, + B00101111,B00011111,B00001000, + B00101111,B10011110,B00001000, + B00101111,B11111100,B00001000, + B00101111,B11011100,B00001000, + B00100111,B11101111,B11001000, + B00100000,B01110111,B11101000, + B00100000,B01111111,B11101000, + B00100000,B11110011,B11101000, + B00100001,B11110001,B11101000, + B00010011,B11110000,B11010000, + B00010111,B11110000,B01010000, + B00001001,B11100000,B00100000, + B00000110,B00000000,B11000000, + B00000001,B11111111,B00000000 + }; + const unsigned char status_fan2_bmp[] PROGMEM = { + B00000001,B11111111,B00000000, + B00000110,B10000000,B11000000, + B00001001,B10000000,B00100000, + B00010111,B10000001,B11010000, + B00010111,B11000011,B11010000, + B00100111,B11000111,B11101000, + B00100011,B11000111,B11111000, + B00100001,B11111111,B10001000, + B00100000,B01101100,B00001000, + B00100000,B01101100,B00001000, + B00100000,B01101100,B00001000, + B00100011,B11111111,B00001000, + B00111111,B11000111,B10001000, + B00101111,B11000111,B11001000, + B00010111,B10000111,B11010000, + B00010111,B00000011,B11010000, + B00001000,B00000011,B00100000, + B00000110,B00000010,B11000000, + B00000001,B11111111,B00000000 + }; + const unsigned char status_fan3_bmp[] PROGMEM = { + B00000001,B11111111,B00000000, + B00000110,B00000000,B11000000, + B00001001,B11110000,B00100000, + B00010001,B11100000,B00010000, + B00010001,B11100000,B00010000, + B00100001,B11100001,B11101000, + B00100000,B11110011,B11101000, + B00100000,B01111111,B11101000, + B00100000,B01110111,B11101000, + B00101000,B11101110,B00101000, + B00101111,B11011100,B00001000, + B00101111,B11111100,B00001000, + B00101111,B10011110,B00001000, + B00101111,B00001111,B00001000, + B00010000,B00001111,B00010000, + B00010000,B00001111,B00010000, + B00001000,B00011111,B00100000, + B00000110,B00000000,B11000000, + B00000001,B11111111,B00000000 + }; + + #else // !STATUS_ALT_FAN_BITMAP + + const unsigned char status_fan0_bmp[] PROGMEM = { + B00111111,B11111111,B11111000, + B00111110,B00000000,B11111000, + B00111000,B00111111,B00111000, + B00110000,B01111110,B00011000, + B00110000,B01111100,B00011000, + B00101000,B01111100,B00001000, + B00101100,B00111000,B00001000, + B00101111,B00111001,B11001000, + B00101111,B11111111,B11101000, + B00101111,B11000111,B11101000, + B00101111,B11111111,B11101000, + B00100111,B00111001,B11101000, + B00100000,B00111000,B01101000, + B00100000,B01111100,B00101000, + B00110000,B01111100,B00011000, + B00110000,B11111100,B00011000, + B00111001,B11111000,B00111000, + B00111110,B00000000,B11111000, + B00111111,B11111111,B11111000 + }; + const unsigned char status_fan1_bmp[] PROGMEM = { + B00111111,B11111111,B11111000, + B00111110,B00000000,B11111000, + B00111000,B00001111,B00111000, + B00110100,B00011111,B11011000, + B00110110,B00011111,B10011000, + B00101111,B00011111,B00001000, + B00101111,B10011110,B00001000, + B00101111,B11111100,B00001000, + B00101111,B11011100,B00001000, + B00100111,B11101111,B11001000, + B00100000,B01110111,B11101000, + B00100000,B01111111,B11101000, + B00100000,B11110011,B11101000, + B00100001,B11110001,B11101000, + B00110011,B11110000,B11011000, + B00110111,B11110000,B01011000, + B00111001,B11100000,B00111000, + B00111110,B00000000,B11111000, + B00111111,B11111111,B11111000 + }; + const unsigned char status_fan2_bmp[] PROGMEM = { + B00111111,B11111111,B11111000, + B00111110,B10000000,B11111000, + B00111001,B10000000,B00111000, + B00110111,B10000001,B11011000, + B00110111,B11000011,B11011000, + B00100111,B11000111,B11101000, + B00100011,B11000111,B11111000, + B00100001,B11111111,B10001000, + B00100000,B01101100,B00001000, + B00100000,B01101100,B00001000, + B00100000,B01101100,B00001000, + B00100011,B11111111,B00001000, + B00111111,B11000111,B10001000, + B00101111,B11000111,B11001000, + B00110111,B10000111,B11011000, + B00110111,B00000011,B11011000, + B00111000,B00000011,B00111000, + B00111110,B00000010,B11111000, + B00111111,B11111111,B11111000 + }; + const unsigned char status_fan3_bmp[] PROGMEM = { + B00111111,B11111111,B11111000, + B00111110,B00000000,B11111000, + B00111001,B11110000,B00111000, + B00110001,B11100000,B00011000, + B00110001,B11100000,B00011000, + B00100001,B11100001,B11101000, + B00100000,B11110011,B11101000, + B00100000,B01111111,B11101000, + B00100000,B01110111,B11101000, + B00101000,B11101110,B00101000, + B00101111,B11011100,B00001000, + B00101111,B11111100,B00001000, + B00101111,B10011110,B00001000, + B00101111,B00001111,B00001000, + B00110000,B00001111,B00011000, + B00110000,B00001111,B00011000, + B00111000,B00011111,B00111000, + B00111110,B00000000,B11111000, + B00111111,B11111111,B11111000 + }; + + #endif // !STATUS_ALT_FAN_BITMAP + +#endif diff --git a/Marlin/src/lcd/dogm/status/hotend.h b/Marlin/src/lcd/dogm/status/hotend.h new file mode 100644 index 000000000000..aac29da45122 --- /dev/null +++ b/Marlin/src/lcd/dogm/status/hotend.h @@ -0,0 +1,759 @@ +/** + * 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 + +// +// lcd/dogm/status/hotend.h - Status Screen Hotends bitmaps +// + +#if HAS_MMU + #define STATUS_HOTEND_BITMAPS EXTRUDERS + #define MAX_HOTEND_BITMAPS 8 +#else + #define STATUS_HOTEND_BITMAPS HOTENDS + #define MAX_HOTEND_BITMAPS 5 +#endif +#if STATUS_HOTEND_BITMAPS > MAX_HOTEND_BITMAPS + #undef STATUS_HOTEND_BITMAPS + #define STATUS_HOTEND_BITMAPS MAX_HOTEND_BITMAPS +#endif + +#define STATUS_HOTEND1_WIDTH 16 + +#if STATUS_HOTEND_BITMAPS == 1 || defined(STATUS_HOTEND_NUMBERLESS) + + const unsigned char status_hotend_a_bmp[] PROGMEM = { + B00011111,B11100000, + #if defined(STATUS_HOTEND_INVERTED) && !defined(STATUS_HOTEND_ANIM) + B00100000,B00010000, + B00100000,B00010000, + B00100000,B00010000, + B00010000,B00100000, + B00010000,B00100000, + B00100000,B00010000, + B00100000,B00010000, + B00110000,B00110000, + B00001000,B01000000, + B00000100,B10000000, + #else + B00111111,B11110000, + B00111111,B11110000, + B00111111,B11110000, + B00011111,B11100000, + B00011111,B11100000, + B00111111,B11110000, + B00111111,B11110000, + B00111111,B11110000, + B00001111,B11000000, + B00000111,B10000000, + #endif + B00000011,B00000000 + }; + + #ifdef STATUS_HOTEND_ANIM + + const unsigned char status_hotend_b_bmp[] PROGMEM = { + B00011111,B11100000, + B00100000,B00010000, + B00100000,B00010000, + B00100000,B00010000, + B00010000,B00100000, + B00010000,B00100000, + B00100000,B00010000, + B00100000,B00010000, + B00110000,B00110000, + B00001000,B01000000, + B00000100,B10000000, + B00000011,B00000000 + }; + + #endif + +#elif STATUS_HOTEND_BITMAPS > 1 + + #ifdef STATUS_HOTEND_ANIM + + const unsigned char status_hotend1_a_bmp[] PROGMEM = { + B00011111,B11100000, + B00111111,B11110000, + #if LCD_FIRST_TOOL == 0 + B00111100,B11110000, + B00111011,B01110000, + B00111011,B01110000, + B00011011,B01100000, + B00011011,B01100000, + B00111011,B01110000, + B00111100,B11110000, + #else + B00111110,B11110000, + B00111100,B11110000, + B00011010,B11100000, + B00011110,B11100000, + B00111110,B11110000, + B00111110,B11110000, + B00111110,B11110000, + #endif + B00001111,B11000000, + B00000111,B10000000, + B00000011,B00000000 + }; + + const unsigned char status_hotend1_b_bmp[] PROGMEM = { + B00011111,B11100000, + B00100000,B00010000, + #if LCD_FIRST_TOOL == 0 + B00100011,B00010000, + B00100100,B10010000, + B00010100,B10100000, + B00010100,B10100000, + B00100100,B10010000, + B00100100,B10010000, + B00110011,B00110000, + #else + B00100001,B00010000, + B00100011,B00010000, + B00010101,B00100000, + B00010001,B00100000, + B00100001,B00010000, + B00100001,B00010000, + B00110001,B00110000, + #endif + B00001000,B01000000, + B00000100,B10000000, + B00000011,B00000000 + }; + + const unsigned char status_hotend2_a_bmp[] PROGMEM = { + B00011111,B11100000, + B00111111,B11110000, + #if LCD_FIRST_TOOL == 0 + B00111110,B11110000, + B00111100,B11110000, + B00011010,B11100000, + B00011110,B11100000, + B00111110,B11110000, + B00111110,B11110000, + B00111110,B11110000, + #else + B00111100,B11110000, + B00111011,B01110000, + B00011111,B01100000, + B00011110,B11100000, + B00111101,B11110000, + B00111011,B11110000, + B00111000,B01110000, + #endif + B00001111,B11000000, + B00000111,B10000000, + B00000011,B00000000 + }; + + const unsigned char status_hotend2_b_bmp[] PROGMEM = { + B00011111,B11100000, + B00100000,B00010000, + #if LCD_FIRST_TOOL == 0 + B00100001,B00010000, + B00100011,B00010000, + B00010101,B00100000, + B00010001,B00100000, + B00100001,B00010000, + B00100001,B00010000, + B00110001,B00110000, + #else + B00100011,B00010000, + B00100100,B10010000, + B00010000,B10100000, + B00010001,B00100000, + B00100010,B00010000, + B00100100,B00010000, + B00110111,B10110000, + #endif + B00001000,B01000000, + B00000100,B10000000, + B00000011,B00000000 + }; + + #else + + const unsigned char status_hotend1_a_bmp[] PROGMEM = { + B00011111,B11100000, + #if LCD_FIRST_TOOL == 0 + B00111100,B11110000, + B00111011,B01110000, + B00111011,B01110000, + B00011011,B01100000, + B00011011,B01100000, + B00111011,B01110000, + B00111100,B11110000, + #else + B00111110,B11110000, + B00111100,B11110000, + B00111010,B11110000, + B00011110,B11100000, + B00011110,B11100000, + B00111110,B11110000, + B00111110,B11110000, + #endif + B00111111,B11110000, + B00001111,B11000000, + B00000111,B10000000, + B00000011,B00000000 + }; + + const unsigned char status_hotend2_a_bmp[] PROGMEM = { + B00011111,B11100000, + #if LCD_FIRST_TOOL == 0 + B00111110,B11110000, + B00111100,B11110000, + B00111010,B11110000, + B00011110,B11100000, + B00011110,B11100000, + B00111110,B11110000, + B00111110,B11110000, + #else + B00111100,B11110000, + B00111011,B01110000, + B00111111,B01110000, + B00011110,B11100000, + B00011101,B11100000, + B00111011,B11110000, + B00111000,B01110000, + #endif + B00111111,B11110000, + B00001111,B11000000, + B00000111,B10000000, + B00000011,B00000000 + }; + + #endif + + #if STATUS_HOTEND_BITMAPS >= 3 + + #ifdef STATUS_HOTEND_ANIM + + const unsigned char status_hotend3_a_bmp[] PROGMEM = { + B00011111,B11100000, + B00111111,B11110000, + #if LCD_FIRST_TOOL == 0 + B00111100,B11110000, + B00111011,B01110000, + B00011111,B01100000, + B00011110,B11100000, + B00111101,B11110000, + B00111011,B11110000, + B00111000,B01110000, + #else + B00111100,B11110000, + B00111011,B01110000, + B00011111,B01100000, + B00011100,B11100000, + B00111111,B01110000, + B00111011,B01110000, + B00111100,B11110000, + #endif + B00001111,B11000000, + B00000111,B10000000, + B00000011,B00000000 + }; + + const unsigned char status_hotend3_b_bmp[] PROGMEM = { + B00011111,B11100000, + B00100000,B00010000, + #if LCD_FIRST_TOOL == 0 + B00100011,B00010000, + B00100100,B10010000, + B00010000,B10100000, + B00010001,B00100000, + B00100010,B00010000, + B00100100,B00010000, + B00110111,B10110000, + #else + B00100011,B00010000, + B00100100,B10010000, + B00010000,B10100000, + B00010011,B00100000, + B00100000,B10010000, + B00100100,B10010000, + B00110011,B00110000, + #endif + B00001000,B01000000, + B00000100,B10000000, + B00000011,B00000000 + }; + + #else + + const unsigned char status_hotend3_a_bmp[] PROGMEM = { + B00011111,B11100000, + #if LCD_FIRST_TOOL == 0 + B00111100,B11110000, + B00111011,B01110000, + B00111111,B01110000, + B00011110,B11100000, + B00011101,B11100000, + B00111011,B11110000, + B00111000,B01110000, + #else + B00111100,B11110000, + B00111011,B01110000, + B00111111,B01110000, + B00011100,B11100000, + B00011111,B01100000, + B00111011,B01110000, + B00111100,B11110000, + #endif + B00111111,B11110000, + B00001111,B11000000, + B00000111,B10000000, + B00000011,B00000000 + }; + + #endif + + #endif + + #if STATUS_HOTEND_BITMAPS >= 4 + + #ifdef STATUS_HOTEND_ANIM + + const unsigned char status_hotend4_a_bmp[] PROGMEM = { + B00011111,B11100000, + B00111111,B11110000, + #if LCD_FIRST_TOOL == 0 + B00111100,B11110000, + B00111011,B01110000, + B00011111,B01100000, + B00011100,B11100000, + B00111111,B01110000, + B00111011,B01110000, + B00111100,B11110000, + #else + B00111011,B01110000, + B00111011,B01110000, + B00011011,B01100000, + B00011011,B01100000, + B00111000,B00110000, + B00111111,B01110000, + B00111111,B01110000, + #endif + B00001111,B11000000, + B00000111,B10000000, + B00000011,B00000000 + }; + + const unsigned char status_hotend4_b_bmp[] PROGMEM = { + B00011111,B11100000, + B00100000,B00010000, + #if LCD_FIRST_TOOL == 0 + B00100011,B00010000, + B00100100,B10010000, + B00010000,B10100000, + B00010011,B00100000, + B00100000,B10010000, + B00100100,B10010000, + B00110011,B00110000, + #else + B00100100,B10010000, + B00100100,B10010000, + B00010100,B10100000, + B00010100,B10100000, + B00100111,B11010000, + B00100000,B10010000, + B00110000,B10110000, + #endif + B00001000,B01000000, + B00000100,B10000000, + B00000011,B00000000 + }; + + #else + + const unsigned char status_hotend4_a_bmp[] PROGMEM = { + B00011111,B11100000, + #if LCD_FIRST_TOOL == 0 + B00111100,B11110000, + B00111011,B01110000, + B00111111,B01110000, + B00011100,B11100000, + B00011111,B01100000, + B00111011,B01110000, + B00111100,B11110000, + #else + B00111011,B01110000, + B00111011,B01110000, + B00111011,B01110000, + B00011011,B01100000, + B00011000,B00100000, + B00111111,B01110000, + B00111111,B01110000, + #endif + B00111111,B11110000, + B00001111,B11000000, + B00000111,B10000000, + B00000011,B00000000 + }; + + #endif + + #endif + + #if STATUS_HOTEND_BITMAPS >= 5 + + #ifdef STATUS_HOTEND_ANIM + + const unsigned char status_hotend5_a_bmp[] PROGMEM = { + B00011111,B11100000, + B00111111,B11110000, + #if LCD_FIRST_TOOL == 0 + B00111011,B01110000, + B00111011,B01110000, + B00011011,B01100000, + B00011011,B01100000, + B00111000,B00110000, + B00111111,B01110000, + B00111111,B01110000, + #else + B00111000,B01110000, + B00111011,B11110000, + B00011000,B11100000, + B00011111,B01100000, + B00111111,B01110000, + B00111011,B01110000, + B00111100,B11110000, + #endif + B00001111,B11000000, + B00000111,B10000000, + B00000011,B00000000 + }; + + const unsigned char status_hotend5_b_bmp[] PROGMEM = { + B00011111,B11100000, + B00100000,B00010000, + #if LCD_FIRST_TOOL == 0 + B00100100,B10010000, + B00100100,B10010000, + B00010100,B10100000, + B00010100,B10100000, + B00100111,B11010000, + B00100000,B10010000, + B00110000,B10110000, + #else + B00100111,B10010000, + B00100100,B00010000, + B00010111,B00100000, + B00010000,B10100000, + B00100000,B10010000, + B00100100,B10010000, + B00110011,B00110000, + #endif + B00001000,B01000000, + B00000100,B10000000, + B00000011,B00000000 + }; + + #else + + const unsigned char status_hotend5_a_bmp[] PROGMEM = { + B00011111,B11100000, + #if LCD_FIRST_TOOL == 0 + B00111011,B01110000, + B00111011,B01110000, + B00111011,B01110000, + B00011011,B01100000, + B00011000,B00100000, + B00111111,B01110000, + B00111111,B01110000, + #else + B00111000,B01110000, + B00111011,B11110000, + B00111000,B11110000, + B00011111,B01100000, + B00011111,B01100000, + B00111011,B01110000, + B00111100,B11110000, + #endif + B00111111,B11110000, + B00001111,B11000000, + B00000111,B10000000, + B00000011,B00000000 + }; + + #endif + + #endif + + #if STATUS_HOTEND_BITMAPS >= 6 + + #ifdef STATUS_HOTEND_ANIM + + const unsigned char status_hotend6_a_bmp[] PROGMEM = { + B00011111,B11100000, + B00111111,B11110000, + #if LCD_FIRST_TOOL == 0 + B00111000,B01110000, + B00111011,B11110000, + B00011000,B11100000, + B00011111,B01100000, + B00111111,B01110000, + B00111011,B01110000, + B00111100,B11110000, + #else + B00111100,B01110000, + B00111011,B11110000, + B00011011,B11100000, + B00011000,B11100000, + B00111011,B01110000, + B00111011,B01110000, + B00111100,B11110000, + #endif + B00001111,B11000000, + B00000111,B10000000, + B00000011,B00000000 + }; + + const unsigned char status_hotend6_b_bmp[] PROGMEM = { + B00011111,B11100000, + B00100000,B00010000, + #if LCD_FIRST_TOOL == 0 + B00100111,B10010000, + B00100100,B00010000, + B00010111,B00100000, + B00010000,B10100000, + B00100000,B10010000, + B00100100,B10010000, + B00110011,B00110000, + #else + B00100011,B10010000, + B00100100,B00010000, + B00010100,B00100000, + B00010111,B00100000, + B00100100,B10010000, + B00100100,B10010000, + B00110011,B00110000, + #endif + B00001000,B01000000, + B00000100,B10000000, + B00000011,B00000000 + }; + + #else + + const unsigned char status_hotend6_a_bmp[] PROGMEM = { + B00011111,B11100000, + #if LCD_FIRST_TOOL == 0 + B00111000,B01110000, + B00111011,B11110000, + B00111000,B11110000, + B00011111,B01100000, + B00011111,B01100000, + B00111011,B01110000, + B00111100,B11110000, + #else + B00111100,B01110000, + B00111011,B11110000, + B00111011,B11110000, + B00011000,B11100000, + B00011011,B01100000, + B00111011,B01110000, + B00111100,B11110000, + #endif + B00111111,B11110000, + B00001111,B11000000, + B00000111,B10000000, + B00000011,B00000000 + }; + + #endif + + #endif + + #if STATUS_HOTEND_BITMAPS >= 7 + + #ifdef STATUS_HOTEND_ANIM + + const unsigned char status_hotend7_a_bmp[] PROGMEM = { + B00011111,B11100000, + B00111111,B11110000, + #if LCD_FIRST_TOOL == 0 + B00111100,B01110000, + B00111011,B11110000, + B00011011,B11100000, + B00011000,B11100000, + B00111011,B01110000, + B00111011,B01110000, + B00111100,B11110000, + #else + B00111000,B01110000, + B00111011,B01110000, + B00011111,B01100000, + B00011110,B11100000, + B00111110,B11110000, + B00111101,B11110000, + B00111101,B11110000, + #endif + B00001111,B11000000, + B00000111,B10000000, + B00000011,B00000000 + }; + + const unsigned char status_hotend7_b_bmp[] PROGMEM = { + B00011111,B11100000, + B00100000,B00010000, + #if LCD_FIRST_TOOL == 0 + B00100011,B10010000, + B00100100,B00010000, + B00010100,B00100000, + B00010111,B00100000, + B00100100,B10010000, + B00100100,B10010000, + B00110011,B00110000, + #else + B00100111,B10010000, + B00100100,B10010000, + B00010000,B10100000, + B00010001,B00100000, + B00100001,B00010000, + B00100010,B00010000, + B00110010,B00110000, + #endif + B00001000,B01000000, + B00000100,B10000000, + B00000011,B00000000 + }; + + #else + + const unsigned char status_hotend7_a_bmp[] PROGMEM = { + B00011111,B11100000, + #if LCD_FIRST_TOOL == 0 + B00111100,B01110000, + B00111011,B11110000, + B00111011,B11110000, + B00011000,B11100000, + B00011011,B01100000, + B00111011,B01110000, + B00111100,B11110000, + #else + B00111000,B01110000, + B00111011,B01110000, + B00111111,B01110000, + B00011110,B11100000, + B00011110,B11100000, + B00111101,B11110000, + B00111101,B11110000, + #endif + B00111111,B11110000, + B00001111,B11000000, + B00000111,B10000000, + B00000011,B00000000 + }; + + #endif + + #endif + + #if STATUS_HOTEND_BITMAPS >= 8 + + #ifdef STATUS_HOTEND_ANIM + + const unsigned char status_hotend8_a_bmp[] PROGMEM = { + B00011111,B11100000, + B00111111,B11110000, + #if LCD_FIRST_TOOL == 0 + B00111000,B01110000, + B00111011,B01110000, + B00011111,B01100000, + B00011110,B11100000, + B00111110,B11110000, + B00111101,B11110000, + B00111101,B11110000, + #else + B00111100,B11110000, + B00111011,B01110000, + B00011011,B01100000, + B00011100,B11100000, + B00111011,B01110000, + B00111011,B01110000, + B00111100,B11110000, + #endif + B00001111,B11000000, + B00000111,B10000000, + B00000011,B00000000 + }; + + const unsigned char status_hotend8_b_bmp[] PROGMEM = { + B00011111,B11100000, + B00100000,B00010000, + #if LCD_FIRST_TOOL == 0 + B00100111,B10010000, + B00100100,B10010000, + B00010000,B10100000, + B00010001,B00100000, + B00100001,B00010000, + B00100010,B00010000, + B00110010,B00110000, + #else + B00100011,B00010000, + B00100100,B10010000, + B00010100,B10100000, + B00010011,B00100000, + B00100100,B10010000, + B00100100,B10010000, + B00110011,B00110000, + #endif + B00001000,B01000000, + B00000100,B10000000, + B00000011,B00000000 + }; + + #else + + const unsigned char status_hotend8_a_bmp[] PROGMEM = { + B00011111,B11100000, + #if LCD_FIRST_TOOL == 0 + B00111000,B01110000, + B00111011,B01110000, + B00111111,B01110000, + B00011110,B11100000, + B00011110,B11100000, + B00111101,B11110000, + B00111101,B11110000, + #else + B00111100,B11110000, + B00111011,B01110000, + B00111011,B01110000, + B00011100,B11100000, + B00011011,B01100000, + B00111011,B01110000, + B00111100,B11110000, + #endif + B00111111,B11110000, + B00001111,B11000000, + B00000111,B10000000, + B00000011,B00000000 + }; + + #endif + + #endif + +#endif diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index 987924201a80..5fe8b61bf4cc 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -30,24 +30,37 @@ #if HAS_MARLINUI_U8GLIB && DISABLED(LIGHTWEIGHT_UI) #include "dogm_Statusscreen.h" -#include "ultralcd_DOGM.h" -#include "../ultralcd.h" +#include "marlinui_DOGM.h" +#include "../marlinui.h" #include "../lcdprint.h" #include "../../libs/numtostr.h" #include "../../module/motion.h" #include "../../module/temperature.h" +#include "../../gcode/parser.h" // for units (and volumetric) + +#if ENABLED(LCD_SHOW_E_TOTAL) + #include "../../MarlinCore.h" // for printingIsActive() +#endif + #if ENABLED(FILAMENT_LCD_DISPLAY) #include "../../feature/filwidth.h" #include "../../module/planner.h" - #include "../../gcode/parser.h" #endif #if HAS_CUTTER #include "../../feature/spindle_laser.h" #endif +#if EITHER(HAS_COOLER, LASER_COOLANT_FLOW_METER) + #include "../../feature/cooler.h" +#endif + +#if ENABLED(I2C_AMMETER) + #include "../../feature/ammeter.h" +#endif + #if HAS_POWER_MONITOR #include "../../feature/power_monitor.h" #endif @@ -67,43 +80,51 @@ #define X_LABEL_POS 3 #define X_VALUE_POS 11 #define XYZ_SPACING 37 + +#define X_LABEL_POS_IN (X_LABEL_POS - 2) +#define X_VALUE_POS_IN (X_VALUE_POS - 5) +#define XYZ_SPACING_IN (XYZ_SPACING + 9) + #define XYZ_BASELINE (30 + INFO_FONT_ASCENT) #define EXTRAS_BASELINE (40 + INFO_FONT_ASCENT) #define STATUS_BASELINE (LCD_PIXEL_HEIGHT - INFO_FONT_DESCENT) #if ANIM_HBCC enum HeatBits : uint8_t { - HEATBIT_HOTEND, - HEATBIT_BED = HOTENDS, - HEATBIT_CHAMBER, - HEATBIT_CUTTER + DRAWBIT_HOTEND, + DRAWBIT_BED = HOTENDS, + DRAWBIT_CHAMBER, + DRAWBIT_CUTTER }; - IF<(HEATBIT_CUTTER > 7), uint16_t, uint8_t>::type heat_bits; + IF<(DRAWBIT_CUTTER > 7), uint16_t, uint8_t>::type draw_bits; #endif #if ANIM_HOTEND - #define HOTEND_ALT(N) TEST(heat_bits, HEATBIT_HOTEND + N) + #define HOTEND_ALT(N) TEST(draw_bits, DRAWBIT_HOTEND + N) #else #define HOTEND_ALT(N) false #endif #if ANIM_BED - #define BED_ALT() TEST(heat_bits, HEATBIT_BED) + #define BED_ALT() TEST(draw_bits, DRAWBIT_BED) #else #define BED_ALT() false #endif #if ANIM_CHAMBER - #define CHAMBER_ALT() TEST(heat_bits, HEATBIT_CHAMBER) + #define CHAMBER_ALT() TEST(draw_bits, DRAWBIT_CHAMBER) #else #define CHAMBER_ALT() false #endif #if ANIM_CUTTER - #define CUTTER_ALT(N) TEST(heat_bits, HEATBIT_CUTTER) + #define CUTTER_ALT(N) TEST(draw_bits, DRAWBIT_CUTTER) #else #define CUTTER_ALT() false #endif #if DO_DRAW_HOTENDS #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) #define STATUS_HEATERS_BOT (STATUS_HEATERS_Y + STATUS_HEATERS_HEIGHT - 1) #endif @@ -119,7 +140,7 @@ #if ENABLED(POWER_MONITOR_CURRENT) const bool iflag = power_monitor.current_display_enabled(); #endif - #if HAS_POWER_MONITOR_VREF + #if ENABLED(POWER_MONITOR_VOLTAGE) const bool vflag = power_monitor.voltage_display_enabled(); #endif @@ -131,7 +152,7 @@ } #elif ENABLED(POWER_MONITOR_CURRENT) power_monitor.display_item = 0; - #elif HAS_POWER_MONITOR_VREF + #elif ENABLED(POWER_MONITOR_VOLTAGE) power_monitor.display_item = 1; #endif @@ -140,7 +161,7 @@ #if ENABLED(POWER_MONITOR_CURRENT) if (power_monitor.display_item == 0 && !iflag) ++power_monitor.display_item; #endif - #if HAS_POWER_MONITOR_VREF + #if ENABLED(POWER_MONITOR_VOLTAGE) if (power_monitor.display_item == 1 && !vflag) ++power_monitor.display_item; #endif #if HAS_POWER_MONITOR_WATTS @@ -153,7 +174,7 @@ #if ENABLED(POWER_MONITOR_CURRENT) // Current case 0: if (iflag) power_monitor.draw_current(); break; #endif - #if HAS_POWER_MONITOR_VREF // Voltage + #if ENABLED(POWER_MONITOR_VOLTAGE) // Voltage case 1: if (vflag) power_monitor.draw_voltage(); break; #endif #if HAS_POWER_MONITOR_WATTS // Power @@ -168,13 +189,34 @@ #define PROGRESS_BAR_Y (EXTRAS_BASELINE + 1) #define PROGRESS_BAR_WIDTH (LCD_PIXEL_WIDTH - PROGRESS_BAR_X) -FORCE_INLINE void _draw_centered_temp(const int16_t temp, const uint8_t tx, const uint8_t ty) { - const char *str = i16tostr3rj(temp); - const uint8_t len = str[0] != ' ' ? 3 : str[1] != ' ' ? 2 : 1; - lcd_put_u8str(tx - len * (INFO_FONT_WIDTH) / 2 + 1, ty, &str[3-len]); - lcd_put_wchar(LCD_STR_DEGREE[0]); +FORCE_INLINE void _draw_centered_temp(const celsius_t temp, const uint8_t tx, const uint8_t ty) { + if (temp < 0) + lcd_put_u8str(tx - 3 * (INFO_FONT_WIDTH) / 2 + 1, ty, "err"); + else { + const char *str = i16tostr3rj(temp); + const uint8_t len = str[0] != ' ' ? 3 : str[1] != ' ' ? 2 : 1; + lcd_put_u8str(tx - len * (INFO_FONT_WIDTH) / 2 + 1, ty, &str[3-len]); + lcd_put_wchar(LCD_STR_DEGREE[0]); + } } +#if DO_DRAW_FLOWMETER + FORCE_INLINE void _draw_centered_flowrate(const float flow, const uint8_t tx, const uint8_t ty) { + const char *str = ftostr11ns(flow); + const uint8_t len = str[0] != ' ' ? 3 : str[1] != ' ' ? 2 : 1; + lcd_put_u8str(tx - len * (INFO_FONT_WIDTH) / 2 + 1, ty, &str[3-len]); + lcd_put_u8str("L"); + } +#endif + +#if DO_DRAW_AMMETER + FORCE_INLINE void _draw_centered_current(const float current, const uint8_t tx, const uint8_t ty) { + const char *str = ftostr31ns(current); + const uint8_t len = str[0] != ' ' ? 3 : str[1] != ' ' ? 2 : 1; + lcd_put_u8str(tx - len * (INFO_FONT_WIDTH) / 2 + 1, ty, &str[3-len]); + } +#endif + #if DO_DRAW_HOTENDS // Draw hotend bitmap with current and target temperatures @@ -187,8 +229,8 @@ FORCE_INLINE void _draw_centered_temp(const int16_t temp, const uint8_t tx, cons const uint8_t tx = STATUS_HOTEND_TEXT_X(heater_id); - const float temp = thermalManager.degHotend(heater_id), - target = thermalManager.degTargetHotend(heater_id); + const celsius_t temp = thermalManager.wholeDegHotend(heater_id), + target = thermalManager.degTargetHotend(heater_id); #if DISABLED(STATUS_HOTEND_ANIM) #define STATIC_HOTEND true @@ -198,24 +240,20 @@ FORCE_INLINE void _draw_centered_temp(const int16_t temp, const uint8_t tx, cons #define HOTEND_DOT false #endif - #if ANIM_HOTEND && BOTH(STATUS_HOTEND_INVERTED, STATUS_HOTEND_NUMBERLESS) - #define OFF_BMP(N) status_hotend_b_bmp - #define ON_BMP(N) status_hotend_a_bmp - #elif ANIM_HOTEND && DISABLED(STATUS_HOTEND_INVERTED) && ENABLED(STATUS_HOTEND_NUMBERLESS) - #define OFF_BMP(N) status_hotend_a_bmp - #define ON_BMP(N) status_hotend_b_bmp - #elif BOTH(ANIM_HOTEND, STATUS_HOTEND_INVERTED) - #define OFF_BMP(N) status_hotend##N##_b_bmp - #define ON_BMP(N) status_hotend##N##_a_bmp + #if ENABLED(STATUS_HOTEND_NUMBERLESS) + #define OFF_BMP(N) TERN(STATUS_HOTEND_INVERTED, status_hotend_b_bmp, status_hotend_a_bmp) + #define ON_BMP(N) TERN(STATUS_HOTEND_INVERTED, status_hotend_a_bmp, status_hotend_b_bmp) #else - #define OFF_BMP(N) status_hotend##N##_a_bmp - #define ON_BMP(N) status_hotend##N##_b_bmp + #define OFF_BMP(N) TERN(STATUS_HOTEND_INVERTED, status_hotend##N##_b_bmp, status_hotend##N##_a_bmp) + #define ON_BMP(N) TERN(STATUS_HOTEND_INVERTED, status_hotend##N##_a_bmp, status_hotend##N##_b_bmp) #endif #if STATUS_HOTEND_BITMAPS > 1 - static const unsigned char* const status_hotend_gfx[STATUS_HOTEND_BITMAPS] PROGMEM = ARRAY_N(STATUS_HOTEND_BITMAPS, OFF_BMP(1), OFF_BMP(2), OFF_BMP(3), OFF_BMP(4), OFF_BMP(5), OFF_BMP(6)); + #define _OFF_BMP(N) OFF_BMP(N), + #define _ON_BMP(N) ON_BMP(N), + static const unsigned char* const status_hotend_gfx[STATUS_HOTEND_BITMAPS] PROGMEM = { REPEAT_1(STATUS_HOTEND_BITMAPS, _OFF_BMP) }; #if ANIM_HOTEND - static const unsigned char* const status_hotend_on_gfx[STATUS_HOTEND_BITMAPS] PROGMEM = ARRAY_N(STATUS_HOTEND_BITMAPS, ON_BMP(1), ON_BMP(2), ON_BMP(3), ON_BMP(4), ON_BMP(5), ON_BMP(6)); + static const unsigned char* const status_hotend_on_gfx[STATUS_HOTEND_BITMAPS] PROGMEM = { REPEAT_1(STATUS_HOTEND_BITMAPS, _ON_BMP) }; #define HOTEND_BITMAP(N,S) (unsigned char*)pgm_read_ptr((S) ? &status_hotend_on_gfx[(N) % (STATUS_HOTEND_BITMAPS)] : &status_hotend_gfx[(N) % (STATUS_HOTEND_BITMAPS)]) #else #define HOTEND_BITMAP(N,S) (unsigned char*)pgm_read_ptr(&status_hotend_gfx[(N) % (STATUS_HOTEND_BITMAPS)]) @@ -226,31 +264,33 @@ FORCE_INLINE void _draw_centered_temp(const int16_t temp, const uint8_t tx, cons #define HOTEND_BITMAP(N,S) status_hotend_a_bmp #endif - if (PAGE_CONTAINS(STATUS_HEATERS_Y, STATUS_HEATERS_BOT)) { + #if DISABLED(STATUS_COMBINE_HEATERS) - #define BAR_TALL (STATUS_HEATERS_HEIGHT - 2) + if (PAGE_CONTAINS(STATUS_HEATERS_Y, STATUS_HEATERS_BOT)) { - const float prop = target - 20, - perc = prop > 0 && temp >= 20 ? (temp - 20) / prop : 0; - uint8_t tall = uint8_t(perc * BAR_TALL + 0.5f); - NOMORE(tall, BAR_TALL); + #define BAR_TALL (STATUS_HEATERS_HEIGHT - 2) + + const float prop = target - 20, + perc = prop > 0 && temp >= 20 ? (temp - 20) / prop : 0; + uint8_t tall = uint8_t(perc * BAR_TALL + 0.5f); + NOMORE(tall, BAR_TALL); - #if ANIM_HOTEND // Draw hotend bitmap, either whole or split by the heating percent const uint8_t hx = STATUS_HOTEND_X(heater_id), bw = STATUS_HOTEND_BYTEWIDTH(heater_id); #if ENABLED(STATUS_HEAT_PERCENT) if (isHeat && tall <= BAR_TALL) { const uint8_t ph = STATUS_HEATERS_HEIGHT - 1 - tall; - u8g.drawBitmapP(hx, STATUS_HEATERS_Y, bw, ph, HOTEND_BITMAP(heater_id, false)); - u8g.drawBitmapP(hx, STATUS_HEATERS_Y + ph, bw, tall + 1, HOTEND_BITMAP(heater_id, true) + ph * bw); + u8g.drawBitmapP(hx, STATUS_HEATERS_Y, bw, ph, HOTEND_BITMAP(TERN(HAS_MMU, active_extruder, heater_id), false)); + u8g.drawBitmapP(hx, STATUS_HEATERS_Y + ph, bw, tall + 1, HOTEND_BITMAP(TERN(HAS_MMU, active_extruder, heater_id), true) + ph * bw); } else #endif - u8g.drawBitmapP(hx, STATUS_HEATERS_Y, bw, STATUS_HEATERS_HEIGHT, HOTEND_BITMAP(heater_id, isHeat)); - #endif + u8g.drawBitmapP(hx, STATUS_HEATERS_Y, bw, STATUS_HEATERS_HEIGHT, HOTEND_BITMAP(TERN(HAS_MMU, active_extruder, heater_id), isHeat)); - } // PAGE_CONTAINS + } // PAGE_CONTAINS + + #endif // !STATUS_COMBINE_HEATERS if (PAGE_UNDER(7)) { #if HEATER_IDLE_HANDLER @@ -258,11 +298,11 @@ FORCE_INLINE void _draw_centered_temp(const int16_t temp, const uint8_t tx, cons #else constexpr bool dodraw = true; #endif - if (dodraw) _draw_centered_temp(target + 0.5, tx, 7); + if (dodraw) _draw_centered_temp(target, tx, 7); } if (PAGE_CONTAINS(28 - INFO_FONT_ASCENT, 28 - 1)) - _draw_centered_temp(temp + 0.5f, tx, 28); + _draw_centered_temp(temp, tx, 28); if (STATIC_HOTEND && HOTEND_DOT && PAGE_CONTAINS(17, 19)) { u8g.setColorIndex(0); // set to white on black @@ -284,8 +324,8 @@ FORCE_INLINE void _draw_centered_temp(const int16_t temp, const uint8_t tx, cons const uint8_t tx = STATUS_BED_TEXT_X; - const float temp = thermalManager.degBed(), - target = thermalManager.degTargetBed(); + const celsius_t temp = thermalManager.wholeDegBed(), + target = thermalManager.degTargetBed(); #if ENABLED(STATUS_HEAT_PERCENT) || DISABLED(STATUS_BED_ANIM) const bool isHeat = BED_ALT(); @@ -331,11 +371,11 @@ FORCE_INLINE void _draw_centered_temp(const int16_t temp, const uint8_t tx, cons #else constexpr bool dodraw = true; #endif - if (dodraw) _draw_centered_temp(target + 0.5, tx, 7); + if (dodraw) _draw_centered_temp(target, tx, 7); } if (PAGE_CONTAINS(28 - INFO_FONT_ASCENT, 28 - 1)) - _draw_centered_temp(temp + 0.5f, tx, 28); + _draw_centered_temp(temp, tx, 28); if (STATIC_BED && BED_DOT && PAGE_CONTAINS(17, 19)) { u8g.setColorIndex(0); // set to white on black @@ -348,18 +388,36 @@ FORCE_INLINE void _draw_centered_temp(const int16_t temp, const uint8_t tx, cons #endif // DO_DRAW_BED #if DO_DRAW_CHAMBER - FORCE_INLINE void _draw_chamber_status() { #if HAS_HEATED_CHAMBER if (PAGE_UNDER(7)) - _draw_centered_temp(thermalManager.degTargetChamber() + 0.5f, STATUS_CHAMBER_TEXT_X, 7); + _draw_centered_temp(thermalManager.degTargetChamber(), STATUS_CHAMBER_TEXT_X, 7); #endif + if (PAGE_CONTAINS(28 - INFO_FONT_ASCENT, 28 - 1)) + _draw_centered_temp(thermalManager.wholeDegChamber(), STATUS_CHAMBER_TEXT_X, 28); + } +#endif +#if DO_DRAW_COOLER + FORCE_INLINE void _draw_cooler_status() { if (PAGE_CONTAINS(28 - INFO_FONT_ASCENT, 28 - 1)) - _draw_centered_temp(thermalManager.degChamber() + 0.5f, STATUS_CHAMBER_TEXT_X, 28); + _draw_centered_temp(thermalManager.wholeDegCooler(), STATUS_COOLER_TEXT_X, 28); } +#endif -#endif // DO_DRAW_CHAMBER +#if DO_DRAW_FLOWMETER + FORCE_INLINE void _draw_flowmeter_status() { + if (PAGE_CONTAINS(28 - INFO_FONT_ASCENT, 28 - 1)) + _draw_centered_flowrate(cooler.flowrate, STATUS_FLOWMETER_TEXT_X, 28); + } +#endif + +#if DO_DRAW_AMMETER + FORCE_INLINE void _draw_ammeter_status() { + if (PAGE_CONTAINS(28 - INFO_FONT_ASCENT, 28 - 1)) + _draw_centered_current(ammeter.read(), STATUS_AMMETER_TEXT_X, 28); + } +#endif // // Before homing, blink '123' <-> '???'. @@ -367,29 +425,32 @@ FORCE_INLINE void _draw_centered_temp(const int16_t temp, const uint8_t tx, cons // Homed and known, display constantly. // FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const bool blink) { + const bool is_inch = parser.using_inch_units(); const AxisEnum a = TERN(LCD_SHOW_E_TOTAL, axis == E_AXIS ? X_AXIS : axis, axis); - const uint8_t offs = (XYZ_SPACING) * a; - lcd_put_wchar(X_LABEL_POS + offs, XYZ_BASELINE, axis_codes[axis]); - lcd_moveto(X_VALUE_POS + offs, XYZ_BASELINE); + const uint8_t offs = a * (is_inch ? XYZ_SPACING_IN : XYZ_SPACING); + lcd_put_wchar((is_inch ? X_LABEL_POS_IN : X_LABEL_POS) + offs, XYZ_BASELINE, axis_codes[axis]); + lcd_moveto((is_inch ? X_VALUE_POS_IN : X_VALUE_POS) + offs, XYZ_BASELINE); + if (blink) lcd_put_u8str(value); - else { - if (!TEST(axis_homed, axis)) - while (const char c = *value++) lcd_put_wchar(c <= '.' ? c : '?'); - else { - #if NONE(HOME_AFTER_DEACTIVATE, DISABLE_REDUCED_ACCURACY_WARNING) - if (!TEST(axis_known_position, axis)) - lcd_put_u8str_P(axis == Z_AXIS ? PSTR(" ") : PSTR(" ")); - else - #endif - lcd_put_u8str(value); - } - } + else if (axis_should_home(axis)) + while (const char c = *value++) lcd_put_wchar(c <= '.' ? c : '?'); + else if (NONE(HOME_AFTER_DEACTIVATE, DISABLE_REDUCED_ACCURACY_WARNING) && !axis_is_trusted(axis)) + lcd_put_u8str_P(axis == Z_AXIS ? PSTR(" ") : PSTR(" ")); + else + lcd_put_u8str(value); } +/** + * Draw the Status Screen for a 128x64 DOGM (U8glib) display. + * + * Called as needed to update the current display stripe. + * Use the PAGE_CONTAINS macros to avoid pointless draw calls. + */ void MarlinUI::draw_status_screen() { + constexpr int xystorage = TERN(INCH_MODE_SUPPORT, 8, 5); + static char xstring[TERN(LCD_SHOW_E_TOTAL, 12, xystorage)], ystring[xystorage], zstring[8]; - static char xstring[TERN(LCD_SHOW_E_TOTAL, 12, 5)], ystring[5], zstring[8]; #if ENABLED(FILAMENT_LCD_DISPLAY) static char wstring[5], mstring[4]; #endif @@ -418,25 +479,26 @@ void MarlinUI::draw_status_screen() { #endif #endif - const bool show_e_total = TERN0(LCD_SHOW_E_TOTAL, printingIsActive() || marlin_state == MF_SD_COMPLETE); + const bool show_e_total = TERN0(LCD_SHOW_E_TOTAL, printingIsActive()); // At the first page, generate new display values if (first_page) { #if ANIM_HBCC uint8_t new_bits = 0; #if ANIM_HOTEND - HOTEND_LOOP() if (thermalManager.isHeatingHotend(e)) SBI(new_bits, HEATBIT_HOTEND + e); + HOTEND_LOOP() if (thermalManager.isHeatingHotend(e)) SBI(new_bits, DRAWBIT_HOTEND + e); #endif - if (TERN0(ANIM_BED, thermalManager.isHeatingBed())) SBI(new_bits, HEATBIT_BED); + if (TERN0(ANIM_BED, thermalManager.isHeatingBed())) SBI(new_bits, DRAWBIT_BED); #if DO_DRAW_CHAMBER && HAS_HEATED_CHAMBER - if (thermalManager.isHeatingChamber()) SBI(new_bits, HEATBIT_CHAMBER); + if (thermalManager.isHeatingChamber()) SBI(new_bits, DRAWBIT_CHAMBER); #endif - if (TERN0(ANIM_CUTTER, cutter.enabled())) SBI(new_bits, HEATBIT_CUTTER); - heat_bits = new_bits; + if (TERN0(ANIM_CUTTER, cutter.enabled())) SBI(new_bits, DRAWBIT_CUTTER); + draw_bits = new_bits; #endif const xyz_pos_t lpos = current_position.asLogical(); - strcpy(zstring, ftostr52sp(lpos.z)); + const bool is_inch = parser.using_inch_units(); + strcpy(zstring, is_inch ? ftostr42_52(LINEAR_UNIT(lpos.z)) : ftostr52sp(lpos.z)); if (show_e_total) { #if ENABLED(LCD_SHOW_E_TOTAL) @@ -445,8 +507,8 @@ void MarlinUI::draw_status_screen() { #endif } else { - strcpy(xstring, ftostr4sign(lpos.x)); - strcpy(ystring, ftostr4sign(lpos.y)); + strcpy(xstring, is_inch ? ftostr53_63(LINEAR_UNIT(lpos.x)) : ftostr4sign(lpos.x)); + strcpy(ystring, is_inch ? ftostr53_63(LINEAR_UNIT(lpos.y)) : ftostr4sign(lpos.y)); } #if ENABLED(FILAMENT_LCD_DISPLAY) @@ -605,7 +667,6 @@ void MarlinUI::draw_status_screen() { if (cutter.isReady && PAGE_CONTAINS(STATUS_CUTTER_TEXT_Y - INFO_FONT_ASCENT, STATUS_CUTTER_TEXT_Y - 1)) { #if CUTTER_UNIT_IS(PERCENT) lcd_put_u8str(STATUS_CUTTER_TEXT_X, STATUS_CUTTER_TEXT_Y, cutter_power2str(cutter.unitPower)); - lcd_put_wchar('%'); #elif CUTTER_UNIT_IS(RPM) lcd_put_u8str(STATUS_CUTTER_TEXT_X - 2, STATUS_CUTTER_TEXT_Y, ftostr51rj(float(cutter.unitPower) / 1000)); lcd_put_wchar('K'); @@ -615,12 +676,45 @@ void MarlinUI::draw_status_screen() { } #endif + // Laser Cooler + #if DO_DRAW_COOLER + const uint8_t coolery = STATUS_COOLER_Y(status_cooler_bmp1), + coolerh = STATUS_COOLER_HEIGHT(status_cooler_bmp1); + if (PAGE_CONTAINS(coolery, coolery + coolerh - 1)) + u8g.drawBitmapP(STATUS_COOLER_X, coolery, STATUS_COOLER_BYTEWIDTH, coolerh, blink && cooler.enabled ? status_cooler_bmp2 : status_cooler_bmp1); + #endif + + // Laser Cooler Flow Meter + #if DO_DRAW_FLOWMETER + const uint8_t flowmetery = STATUS_FLOWMETER_Y(status_flowmeter_bmp1), + flowmeterh = STATUS_FLOWMETER_HEIGHT(status_flowmeter_bmp1); + if (PAGE_CONTAINS(flowmetery, flowmetery + flowmeterh - 1)) + u8g.drawBitmapP(STATUS_FLOWMETER_X, flowmetery, STATUS_FLOWMETER_BYTEWIDTH, flowmeterh, blink && cooler.flowpulses ? status_flowmeter_bmp2 : status_flowmeter_bmp1); + #endif + + // Laser Ammeter + #if DO_DRAW_AMMETER + const uint8_t ammetery = STATUS_AMMETER_Y(status_ammeter_bmp_mA), + ammeterh = STATUS_AMMETER_HEIGHT(status_ammeter_bmp_mA); + if (PAGE_CONTAINS(ammetery, ammetery + ammeterh - 1)) + u8g.drawBitmapP(STATUS_AMMETER_X, ammetery, STATUS_AMMETER_BYTEWIDTH, ammeterh, (ammeter.current < 0.1f) ? status_ammeter_bmp_mA : status_ammeter_bmp_A); + #endif + // Heated Bed TERN_(DO_DRAW_BED, _draw_bed_status(blink)); // Heated Chamber TERN_(DO_DRAW_CHAMBER, _draw_chamber_status()); + // Cooler + TERN_(DO_DRAW_COOLER, _draw_cooler_status()); + + // Flowmeter + TERN_(DO_DRAW_FLOWMETER, _draw_flowmeter_status()); + + // Flowmeter + TERN_(DO_DRAW_AMMETER, _draw_ammeter_status()); + // Fan, if a bitmap was provided #if DO_DRAW_FAN if (PAGE_CONTAINS(STATUS_FAN_TEXT_Y - INFO_FONT_ASCENT, STATUS_FAN_TEXT_Y - 1)) { @@ -633,7 +727,7 @@ void MarlinUI::draw_status_screen() { c = '*'; } #endif - lcd_put_u8str(STATUS_FAN_TEXT_X, STATUS_FAN_TEXT_Y, i16tostr3rj(thermalManager.fanPercent(spd))); + lcd_put_u8str(STATUS_FAN_TEXT_X, STATUS_FAN_TEXT_Y, i16tostr3rj(thermalManager.pwmToPercent(spd))); lcd_put_wchar(c); } } @@ -771,14 +865,26 @@ void MarlinUI::draw_status_screen() { mixer.update_mix_from_vtool(); mix_label = PSTR("Mx"); } + + #if GCC_VERSION <= 50000 + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wformat-overflow" + #endif + sprintf_P(mixer_messages, PSTR(S_FMT " %d;%d%% "), mix_label, int(mixer.mix[0]), int(mixer.mix[1])); lcd_put_u8str(X_LABEL_POS, XYZ_BASELINE, mixer_messages); + #if GCC_VERSION <= 50000 + #pragma GCC diagnostic pop + #endif + #else if (show_e_total) { - _draw_axis_value(E_AXIS, xstring, true); - lcd_put_u8str_P(PSTR(" ")); + #if ENABLED(LCD_SHOW_E_TOTAL) + _draw_axis_value(E_AXIS, xstring, true); + lcd_put_u8str_P(PSTR(" ")); + #endif } else { _draw_axis_value(X_AXIS, xstring, blink); @@ -845,6 +951,9 @@ void MarlinUI::draw_status_screen() { } } +/** + * Draw the Status Message area + */ void MarlinUI::draw_status_message(const bool blink) { // Get the UTF8 character count of the string @@ -870,6 +979,10 @@ void MarlinUI::draw_status_message(const bool blink) { } else { // String is longer than the available space + if (blink != last_blink) { + last_blink = blink; + advance_status_scroll(); + } // Get a pointer to the next valid UTF8 character // and the string remaining length @@ -879,21 +992,19 @@ void MarlinUI::draw_status_message(const bool blink) { // If the remaining string doesn't completely fill the screen if (rlen < lcd_width) { - lcd_put_wchar('.'); // Always at 1+ spaces left, draw a dot uint8_t chars = lcd_width - rlen; // Amount of space left in characters - if (--chars) { // Draw a second dot if there's space - lcd_put_wchar('.'); - if (--chars) { // Print a second copy of the message - lcd_put_u8str_max(status_message, pixel_width - (rlen + 2) * (MENU_FONT_WIDTH)); + lcd_put_wchar(' '); // Always at 1+ spaces left, draw a space + if (--chars) { // Draw a second space if there's room + lcd_put_wchar(' '); + if (--chars) { // Draw a third space if there's room lcd_put_wchar(' '); + if (--chars) { // Print a second copy of the message + lcd_put_u8str_max(status_message, pixel_width - (rlen + 2) * (MENU_FONT_WIDTH)); + lcd_put_wchar(' '); + } } } } - - if (last_blink != blink) { - last_blink = blink; - advance_status_scroll(); - } } #else // !STATUS_MESSAGE_SCROLLING diff --git a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp index 806f370db327..be112c8d549e 100644 --- a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp +++ b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp @@ -46,7 +46,7 @@ #include "status_screen_lite_ST7920.h" -#include "../ultralcd.h" +#include "../marlinui.h" #include "../fontutils.h" #include "../lcdprint.h" #include "../../libs/duration_t.h" @@ -447,7 +447,7 @@ void ST7920_Lite_Status_Screen::draw_static_elements() { * data buffer (DDRAM) to be used in conjunction with the graphics * bitmap buffer (CGRAM). The contents of the graphics buffer is * XORed with the data from the character generator. This allows - * us to make the progess bar out of graphical data (the bar) and + * us to make the progress bar out of graphical data (the bar) and * text data (the percentage). */ void ST7920_Lite_Status_Screen::draw_progress_bar(const uint8_t value) { @@ -536,7 +536,9 @@ void ST7920_Lite_Status_Screen::draw_heat_icon(const bool whichIcon, const bool static struct { bool E1_show_target : 1; bool E2_show_target : 1; - TERN_(HAS_HEATED_BED, bool bed_show_target : 1); + #if HAS_HEATED_BED + bool bed_show_target : 1; + #endif } display_state = { true, true, TERN_(HAS_HEATED_BED, true) }; @@ -640,11 +642,14 @@ void ST7920_Lite_Status_Screen::draw_status_message() { // If the remaining string doesn't completely fill the screen if (rlen < TEXT_MODE_LCD_WIDTH) { - write_byte('.'); // Always at 1+ spaces left, draw a dot - uint8_t chars = TEXT_MODE_LCD_WIDTH - rlen; // Amount of space left in characters - if (--chars) { // Draw a second dot if there's space - write_byte('.'); - if (--chars) write_str(str, chars); // Print a second copy of the message + uint8_t chars = TEXT_MODE_LCD_WIDTH - rlen; // Amount of space left in characters + write_byte(' '); // Always at 1+ spaces left, draw a space + if (--chars) { // Draw a second space if there's room + write_byte(' '); + if (--chars) { // Draw a third space if there's room + write_byte(' '); + if (--chars) write_str(str, chars); // Print a second copy of the message + } } } ui.advance_status_scroll(); @@ -659,13 +664,13 @@ void ST7920_Lite_Status_Screen::draw_status_message() { #endif } -void ST7920_Lite_Status_Screen::draw_position(const xyze_pos_t &pos, const bool position_known) { +void ST7920_Lite_Status_Screen::draw_position(const xyze_pos_t &pos, const bool position_trusted) { char str[7]; set_ddram_address(DDRAM_LINE_4); begin_data(); // If position is unknown, flash the labels. - const unsigned char alt_label = position_known ? 0 : (ui.get_blink() ? ' ' : 0); + const unsigned char alt_label = position_trusted ? 0 : (ui.get_blink() ? ' ' : 0); if (TERN1(LCD_SHOW_E_TOTAL, !printingIsActive())) { write_byte(alt_label ? alt_label : 'X'); @@ -691,15 +696,15 @@ bool ST7920_Lite_Status_Screen::indicators_changed() { // We only add the target temperatures to the checksum // because the actual temps fluctuate so by updating // them only during blinks we gain a bit of stability. - const bool blink = ui.get_blink(); - const uint16_t feedrate_perc = feedrate_percentage; - const uint16_t fs = thermalManager.scaledFanSpeed(0); - const int16_t extruder_1_target = thermalManager.degTargetHotend(0); + const bool blink = ui.get_blink(); + const uint16_t feedrate_perc = feedrate_percentage; + const uint16_t fs = thermalManager.scaledFanSpeed(0); + const celsius_t extruder_1_target = thermalManager.degTargetHotend(0); #if HAS_MULTI_HOTEND - const int16_t extruder_2_target = thermalManager.degTargetHotend(1); + const celsius_t extruder_2_target = thermalManager.degTargetHotend(1); #endif #if HAS_HEATED_BED - const int16_t bed_target = thermalManager.degTargetBed(); + const celsius_t bed_target = thermalManager.degTargetBed(); #endif static uint16_t last_checksum = 0; const uint16_t checksum = blink ^ feedrate_perc ^ fs ^ extruder_1_target @@ -712,33 +717,31 @@ bool ST7920_Lite_Status_Screen::indicators_changed() { void ST7920_Lite_Status_Screen::update_indicators(const bool forceUpdate) { if (forceUpdate || indicators_changed()) { - const bool blink = ui.get_blink(); - const duration_t elapsed = print_job_timer.duration(); - duration_t remaining = TERN0(USE_M73_REMAINING_TIME, ui.get_remaining_time()); - const uint16_t feedrate_perc = feedrate_percentage; - const int16_t extruder_1_temp = thermalManager.degHotend(0), - extruder_1_target = thermalManager.degTargetHotend(0); + const bool blink = ui.get_blink(); + const duration_t elapsed = print_job_timer.duration(); + duration_t remaining = TERN0(USE_M73_REMAINING_TIME, ui.get_remaining_time()); + const uint16_t feedrate_perc = feedrate_percentage; + const celsius_t extruder_1_temp = thermalManager.wholeDegHotend(0), + extruder_1_target = thermalManager.degTargetHotend(0); #if HAS_MULTI_HOTEND - const int16_t extruder_2_temp = thermalManager.degHotend(1), - extruder_2_target = thermalManager.degTargetHotend(1); + const celsius_t extruder_2_temp = thermalManager.wholeDegHotend(1), + extruder_2_target = thermalManager.degTargetHotend(1); #endif #if HAS_HEATED_BED - const int16_t bed_temp = thermalManager.degBed(), - bed_target = thermalManager.degTargetBed(); + const celsius_t bed_temp = thermalManager.wholeDegBed(), + bed_target = thermalManager.degTargetBed(); #endif draw_extruder_1_temp(extruder_1_temp, extruder_1_target, forceUpdate); TERN_(HAS_MULTI_HOTEND, draw_extruder_2_temp(extruder_2_temp, extruder_2_target, forceUpdate)); TERN_(HAS_HEATED_BED, draw_bed_temp(bed_temp, bed_target, forceUpdate)); - uint16_t spd = thermalManager.fan_speed[0]; - + uint8_t spd = thermalManager.fan_speed[0]; #if ENABLED(ADAPTIVE_FAN_SLOWING) if (!blink && thermalManager.fan_speed_scaler[0] < 128) spd = thermalManager.scaledFanSpeed(0, spd); #endif - - draw_fan_speed(thermalManager.fanPercent(spd)); + draw_fan_speed(thermalManager.pwmToPercent(spd)); // Draw elapsed/remaining time const bool show_remaining = ENABLED(SHOW_REMAINING_TIME) && (DISABLED(ROTATE_PROGRESS_DISPLAY) || blink); @@ -831,9 +834,8 @@ void ST7920_Lite_Status_Screen::update_status_or_position(bool forceUpdate) { } } - if (countdown == 0 && (forceUpdate || position_changed() - || TERN(DISABLE_REDUCED_ACCURACY_WARNING, 0, blink_changed()) - )) draw_position(current_position, TERN(DISABLE_REDUCED_ACCURACY_WARNING, 1, all_axes_known())); + if (countdown == 0 && (forceUpdate || position_changed() || TERN(DISABLE_REDUCED_ACCURACY_WARNING, 0, blink_changed()))) + draw_position(current_position, TERN(DISABLE_REDUCED_ACCURACY_WARNING, 1, all_axes_trusted())); #endif } @@ -855,7 +857,7 @@ void ST7920_Lite_Status_Screen::update_progress(const bool forceUpdate) { UNUSED(forceUpdate); - #endif // LCD_SET_PROGRESS_MANUALLY || SDSUPPORT + #endif } void ST7920_Lite_Status_Screen::update(const bool forceUpdate) { 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 f97a323350ee..b3e579e6a44a 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 @@ -245,9 +245,8 @@ u8g_dev_t u8g_dev_ssd1306_128x64_2x_i2c_2_wire = { u8g_dev_ssd1306_128x64_2x_2_w uint8_t u8g_WriteEscSeqP_2_wire(u8g_t *u8g, u8g_dev_t *dev, const uint8_t *esc_seq) { uint8_t is_escape = 0; - uint8_t value; for (;;) { - value = u8g_pgm_read(esc_seq); + uint8_t value = u8g_pgm_read(esc_seq); if (is_escape == 0) { if (value != 255) { if (u8g_WriteByte(u8g, dev, value) == 0 ) diff --git a/Marlin/src/lcd/dogm/u8g_dev_ssd1309_12864.cpp b/Marlin/src/lcd/dogm/u8g_dev_ssd1309_12864.cpp new file mode 100644 index 000000000000..2a21bd67cad5 --- /dev/null +++ b/Marlin/src/lcd/dogm/u8g_dev_ssd1309_12864.cpp @@ -0,0 +1,128 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../inc/MarlinConfigPre.h" + +#if HAS_MARLINUI_U8GLIB + +#include "HAL_LCD_com_defines.h" +#include + +#define WIDTH 128 +#define HEIGHT 64 +#define PAGE_HEIGHT 8 + +// SSD1309 init sequence +static const uint8_t u8g_dev_ssd1309_128x64_init_seq[] PROGMEM = { + U8G_ESC_CS(0), // Disable chip + U8G_ESC_ADR(0), // Instruction mode + U8G_ESC_RST(1), // Do reset low pulse with (1*16)+2 milliseconds + U8G_ESC_CS(1), // Enable chip + + 0xFD,0x12, // Command Lock + 0xAE, // Set Display Off + 0xD5,0xA0, // Set Display Clock Divide Ratio/Oscillator Frequency + 0xA8,0x3F, // Set Multiplex Ratio + 0x3D,0x00, // Set Display Offset + 0x40, // Set Display Start Line + 0xA1, // Set Segment Re-Map + 0xC8, // Set COM Output Scan Direction + 0xDA,0x12, // Set COM Pins Hardware Configuration + 0x81,0xDF, // Set Current Control + 0xD9,0x82, // Set Pre-Charge Period + 0xDB,0x34, // Set VCOMH Deselect Level + 0xA4, // Set Entire Display On/Off + 0xA6, // Set Normal/Inverse Display + U8G_ESC_VCC(1), // Power up VCC & Stabilized + U8G_ESC_DLY(50), + 0xAF, // Set Display On + U8G_ESC_DLY(50), + U8G_ESC_CS(0), // Disable chip + U8G_ESC_END // End of sequence +}; + +// Select one init sequence here +#define u8g_dev_ssd1309_128x64_init_seq u8g_dev_ssd1309_128x64_init_seq + +static const uint8_t u8g_dev_ssd1309_128x64_data_start[] PROGMEM = { + U8G_ESC_ADR(0), // Instruction mode + U8G_ESC_CS(1), // Enable chip + 0x010, // Set upper 4 bit of the col adr to 0 + 0x000, // Set lower 4 bit of the col adr to 4 + U8G_ESC_END // End of sequence +}; + +static const uint8_t u8g_dev_ssd13xx_sleep_on[] PROGMEM = { + U8G_ESC_ADR(0), // Instruction mode + U8G_ESC_CS(1), // Enable chip + 0x0AE, // Display off + U8G_ESC_CS(0), // Disable chip + U8G_ESC_END // End of sequence +}; + +static const uint8_t u8g_dev_ssd13xx_sleep_off[] PROGMEM = { + U8G_ESC_ADR(0), // Instruction mode + U8G_ESC_CS(1), // Enable chip + 0x0AF, // Display on + U8G_ESC_DLY(50), // Delay 50 ms + U8G_ESC_CS(0), // Disable chip + U8G_ESC_END // End of sequence +}; + +uint8_t u8g_dev_ssd1309_128x64_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) { + switch (msg) { + case U8G_DEV_MSG_INIT: + u8g_InitCom(u8g, dev, U8G_SPI_CLK_CYCLE_300NS); + u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd1309_128x64_init_seq); + break; + case U8G_DEV_MSG_STOP: + break; + case U8G_DEV_MSG_PAGE_NEXT: { + u8g_pb_t *pb = (u8g_pb_t *)(dev->dev_mem); + u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd1309_128x64_data_start); + u8g_WriteByte(u8g, dev, 0x0B0 | pb->p.page); // Select current page (SSD1306) + u8g_SetAddress(u8g, dev, 1); // Data mode + if (u8g_pb_WriteBuffer(pb, u8g, dev) == 0) return 0; + u8g_SetChipSelect(u8g, dev, 0); + } + break; + case U8G_DEV_MSG_CONTRAST: + u8g_SetChipSelect(u8g, dev, 1); + u8g_SetAddress(u8g, dev, 0); // Instruction mode + u8g_WriteByte(u8g, dev, 0x081); + u8g_WriteByte(u8g, dev, (*(uint8_t *)arg) ); // 11 Jul 2015: fixed contrast calculation + u8g_SetChipSelect(u8g, dev, 0); + return 1; + case U8G_DEV_MSG_SLEEP_ON: + u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd13xx_sleep_on); + return 1; + case U8G_DEV_MSG_SLEEP_OFF: + u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd13xx_sleep_off); + return 1; + } + return u8g_dev_pb8v1_base_fn(u8g, dev, msg, arg); +} + +uint8_t u8g_dev_ssd1309_buf[WIDTH*2] U8G_NOCOMMON ; +u8g_pb_t u8g_dev_ssd1309_pb = { {8, HEIGHT, 0, 0, 0}, WIDTH, u8g_dev_ssd1309_buf}; +u8g_dev_t u8g_dev_ssd1309_sw_spi = { u8g_dev_ssd1309_128x64_fn, &u8g_dev_ssd1309_pb, U8G_COM_HAL_SW_SPI_FN }; + +#endif // HAS_MARLINUI_U8GLIB 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 84c10dbb4d2e..fda090338ca1 100644 --- a/Marlin/src/lcd/dogm/u8g_dev_st7565_64128n_HAL.cpp +++ b/Marlin/src/lcd/dogm/u8g_dev_st7565_64128n_HAL.cpp @@ -57,7 +57,7 @@ #if HAS_MARLINUI_U8GLIB -#include +#include #include "HAL_LCD_com_defines.h" #define WIDTH 128 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 740436d93c07..fde6e41792dc 100644 --- a/Marlin/src/lcd/dogm/u8g_dev_st7920_128x64_HAL.cpp +++ b/Marlin/src/lcd/dogm/u8g_dev_st7920_128x64_HAL.cpp @@ -55,7 +55,7 @@ #include "../../inc/MarlinConfigPre.h" -#if HAS_MARLINUI_U8GLIB +#if HAS_MARLINUI_U8GLIB && DISABLED(TFT_CLASSIC_UI) #include "HAL_LCD_com_defines.h" @@ -73,7 +73,7 @@ static const uint8_t u8g_dev_st7920_128x64_HAL_init_seq[] PROGMEM = { 0x038, // 8 Bit interface (DL=1), basic instruction set (RE=0) 0x00C, // display on, cursor & blink off; 0x08: all off 0x006, // Entry mode: Cursor move to right, DDRAM address counter (AC) plus 1, no shift - 0x002, // disable scroll, enable CGRAM adress + 0x002, // disable scroll, enable CGRAM address 0x001, // clear RAM, needs 1.6 ms U8G_ESC_DLY(100), // delay 100 ms @@ -201,7 +201,7 @@ u8g_dev_t u8g_dev_st7920_128x64_HAL_4x_hw_spi = { u8g_dev_st7920_128x64_HAL_4x_f #if NONE(__AVR__, ARDUINO_ARCH_STM32, ARDUINO_ARCH_ESP32) || defined(U8G_HAL_LINKS) // Also use this device for HAL version of rrd class. This results in the same device being used - // for the ST7920 for HAL systems no matter what is selected in ultralcd_impl_DOGM.h. + // for the ST7920 for HAL systems no matter what is selected in marlinui_DOGM.h. u8g_dev_t u8g_dev_st7920_128x64_rrd_sw_spi = { u8g_dev_st7920_128x64_HAL_4x_fn, &u8g_dev_st7920_128x64_HAL_4x_pb, U8G_COM_ST7920_HAL_SW_SPI }; #endif 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 d18b617987cb..b0cb59a12cba 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 @@ -55,14 +55,14 @@ #include "../../inc/MarlinConfig.h" -#if HAS_MARLINUI_U8GLIB && (PIN_EXISTS(FSMC_CS) || ENABLED(SPI_GRAPHICAL_TFT)) +#if HAS_MARLINUI_U8GLIB && (PIN_EXISTS(FSMC_CS) || HAS_SPI_GRAPHICAL_TFT || HAS_LTDC_GRAPHICAL_TFT) #include "HAL_LCD_com_defines.h" -#include "ultralcd_DOGM.h" +#include "marlinui_DOGM.h" #include -#if EITHER(LCD_USE_DMA_FSMC, LCD_USE_DMA_SPI) +#if ANY(LCD_USE_DMA_FSMC, LCD_USE_DMA_SPI, HAS_LTDC_GRAPHICAL_TFT) #define HAS_LCD_IO 1 #endif @@ -73,14 +73,18 @@ TFT_IO tftio; #define HEIGHT LCD_PIXEL_HEIGHT #define PAGE_HEIGHT 8 -#include "../scaled_tft.h" +#include "../touch/touch_buttons.h" + +#if ENABLED(TOUCH_SCREEN_CALIBRATION) + #include "../tft_io/touch_calibration.h" + #include "../marlinui.h" +#endif -#define UPSCALE0(M) ((M) * (GRAPHICAL_TFT_UPSCALE)) -#define UPSCALE(A,M) (UPSCALE0(M) + (A)) #define X_HI (UPSCALE(TFT_PIXEL_OFFSET_X, WIDTH) - 1) #define Y_HI (UPSCALE(TFT_PIXEL_OFFSET_Y, HEIGHT) - 1) -// see https://ee-programming-notepad.blogspot.com/2016/10/16-bit-color-generator-picker.html +// 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 #define COLOR_BLACK 0x0000 // #000000 #define COLOR_WHITE 0xFFFF // #FFFFFF @@ -88,7 +92,7 @@ TFT_IO tftio; #define COLOR_GREY 0x7BEF // #808080 #define COLOR_DARKGREY 0x4208 // #404040 #define COLOR_DARKGREY2 0x39E7 // #303030 -#define COLOR_DARK 0x0003 // Some dark color +#define COLOR_DARK 0x0003 // #000019 #define COLOR_RED 0xF800 // #FF0000 #define COLOR_LIME 0x7E00 // #00FF00 @@ -131,7 +135,7 @@ static void setWindow(u8g_t *u8g, u8g_dev_t *dev, uint16_t Xmin, uint16_t Ymin, tftio.set_window(Xmin, Ymin, Xmax, Ymax); } -#if HAS_TOUCH_XPT2046 +#if HAS_TOUCH_BUTTONS static const uint8_t buttonD[] = { B01111111,B11111111,B11111111,B11111110, @@ -276,29 +280,10 @@ static void setWindow(u8g_t *u8g, u8g_dev_t *dev, uint16_t Xmin, uint16_t Ymin, B01111111,B11111111,B11111111,B11111110, }; - #define BUTTON_SIZE_X 32 - #define BUTTON_SIZE_Y 20 - - // 14, 90, 166, 242, 185 are the original values upscaled 2x. - #define BUTTOND_X_LO UPSCALE0(14 / 2) - #define BUTTOND_X_HI (UPSCALE(BUTTOND_X_LO, BUTTON_SIZE_X) - 1) - - #define BUTTONA_X_LO UPSCALE0(90 / 2) - #define BUTTONA_X_HI (UPSCALE(BUTTONA_X_LO, BUTTON_SIZE_X) - 1) - - #define BUTTONB_X_LO UPSCALE0(166 / 2) - #define BUTTONB_X_HI (UPSCALE(BUTTONB_X_LO, BUTTON_SIZE_X) - 1) - - #define BUTTONC_X_LO UPSCALE0(242 / 2) - #define BUTTONC_X_HI (UPSCALE(BUTTONC_X_LO, BUTTON_SIZE_X) - 1) - - #define BUTTON_Y_LO UPSCALE0(140 / 2) + 44 // 184 2x, 254 3x - #define BUTTON_Y_HI (UPSCALE(BUTTON_Y_LO, BUTTON_SIZE_Y) - 1) - void drawImage(const uint8_t *data, u8g_t *u8g, u8g_dev_t *dev, uint16_t length, uint16_t height, uint16_t color) { - uint16_t buffer[BUTTON_SIZE_X * sq(GRAPHICAL_TFT_UPSCALE)]; + uint16_t buffer[BUTTON_WIDTH * sq(GRAPHICAL_TFT_UPSCALE)]; - if (length > BUTTON_SIZE_X) return; + if (length > BUTTON_WIDTH) return; for (uint16_t i = 0; i < height; i++) { uint16_t k = 0; @@ -323,69 +308,80 @@ static void setWindow(u8g_t *u8g, u8g_dev_t *dev, uint16_t Xmin, uint16_t Ymin, } } -#endif // HAS_TOUCH_XPT2046 +#endif // HAS_TOUCH_BUTTONS // Used to fill RGB565 (16bits) background inline void memset2(const void *ptr, uint16_t fill, size_t cnt) { - uint16_t* wptr = (uint16_t*)ptr; + uint16_t *wptr = (uint16_t*)ptr; for (size_t i = 0; i < cnt; i += 2) { *wptr = fill; wptr++; } } static bool preinit = true; static uint8_t page; +#if HAS_TOUCH_BUTTONS + static bool redrawTouchButtons = true; + static void drawTouchButtons(u8g_t *u8g, u8g_dev_t *dev) { + if (!redrawTouchButtons) return; + redrawTouchButtons = false; + + // Bottom buttons + setWindow(u8g, dev, BUTTOND_X_LO, BUTTON_Y_LO, BUTTOND_X_HI, BUTTON_Y_HI); + drawImage(buttonD, u8g, dev, BUTTON_DRAW_WIDTH, BUTTON_DRAW_HEIGHT, TFT_BTCANCEL_COLOR); + + setWindow(u8g, dev, BUTTONA_X_LO, BUTTON_Y_LO, BUTTONA_X_HI, BUTTON_Y_HI); + drawImage(buttonA, u8g, dev, BUTTON_DRAW_WIDTH, BUTTON_DRAW_HEIGHT, TFT_BTARROWS_COLOR); + + setWindow(u8g, dev, BUTTONB_X_LO, BUTTON_Y_LO, BUTTONB_X_HI, BUTTON_Y_HI); + drawImage(buttonB, u8g, dev, BUTTON_DRAW_WIDTH, BUTTON_DRAW_HEIGHT, TFT_BTARROWS_COLOR); + + setWindow(u8g, dev, BUTTONC_X_LO, BUTTON_Y_LO, BUTTONC_X_HI, BUTTON_Y_HI); + drawImage(buttonC, u8g, dev, BUTTON_DRAW_WIDTH, BUTTON_DRAW_HEIGHT, TFT_BTOKMENU_COLOR); + } +#endif // HAS_TOUCH_BUTTONS + +static uint8_t msgInitCount = 2; // Ignore all messages until 2nd U8G_COM_MSG_INIT + uint8_t u8g_dev_tft_320x240_upscale_from_128x64_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) { u8g_pb_t *pb = (u8g_pb_t *)(dev->dev_mem); #if HAS_LCD_IO static uint16_t bufferA[WIDTH * sq(GRAPHICAL_TFT_UPSCALE)], bufferB[WIDTH * sq(GRAPHICAL_TFT_UPSCALE)]; - uint16_t* buffer = &bufferA[0]; + uint16_t *buffer = &bufferA[0]; #else uint16_t buffer[WIDTH * GRAPHICAL_TFT_UPSCALE]; // 16-bit RGB 565 pixel line buffer #endif switch (msg) { case U8G_DEV_MSG_INIT: - dev->com_fn(u8g, U8G_COM_MSG_INIT, U8G_SPI_CLK_CYCLE_NONE, NULL); - tftio.Init(); - tftio.InitTFT(); + dev->com_fn(u8g, U8G_COM_MSG_INIT, U8G_SPI_CLK_CYCLE_NONE, nullptr); if (preinit) { preinit = false; return u8g_dev_pb8v1_base_fn(u8g, dev, msg, arg); } + if (msgInitCount) return -1; + tftio.Init(); + tftio.InitTFT(); + TERN_(TOUCH_SCREEN_CALIBRATION, touch_calibration.calibration_reset()); + // Clear Screen setWindow(u8g, dev, 0, 0, (TFT_WIDTH) - 1, (TFT_HEIGHT) - 1); #if HAS_LCD_IO - tftio.WriteMultiple(TFT_MARLINBG_COLOR, uint32_t(TFT_WIDTH) * (TFT_HEIGHT)); + tftio.WriteMultiple(TFT_MARLINBG_COLOR, (TFT_WIDTH) * (TFT_HEIGHT)); #else memset2(buffer, TFT_MARLINBG_COLOR, (TFT_WIDTH) / 2); for (uint16_t i = 0; i < (TFT_HEIGHT) * sq(GRAPHICAL_TFT_UPSCALE); i++) u8g_WriteSequence(u8g, dev, (TFT_WIDTH) / 2, (uint8_t *)buffer); #endif - - // Bottom buttons - #if HAS_TOUCH_XPT2046 - setWindow(u8g, dev, BUTTOND_X_LO, BUTTON_Y_LO, BUTTOND_X_HI, BUTTON_Y_HI); - drawImage(buttonD, u8g, dev, 32, 20, TFT_BTCANCEL_COLOR); - - setWindow(u8g, dev, BUTTONA_X_LO, BUTTON_Y_LO, BUTTONA_X_HI, BUTTON_Y_HI); - drawImage(buttonA, u8g, dev, 32, 20, TFT_BTARROWS_COLOR); - - setWindow(u8g, dev, BUTTONB_X_LO, BUTTON_Y_LO, BUTTONB_X_HI, BUTTON_Y_HI); - drawImage(buttonB, u8g, dev, 32, 20, TFT_BTARROWS_COLOR); - - setWindow(u8g, dev, BUTTONC_X_LO, BUTTON_Y_LO, BUTTONC_X_HI, BUTTON_Y_HI); - drawImage(buttonC, u8g, dev, 32, 20, TFT_BTOKMENU_COLOR); - #endif // HAS_TOUCH_XPT2046 - return 0; case U8G_DEV_MSG_STOP: preinit = true; break; case U8G_DEV_MSG_PAGE_FIRST: page = 0; + TERN_(HAS_TOUCH_BUTTONS, drawTouchButtons(u8g, dev)); setWindow(u8g, dev, TFT_PIXEL_OFFSET_X, TFT_PIXEL_OFFSET_Y, X_HI, Y_HI); break; @@ -409,7 +405,7 @@ uint8_t u8g_dev_tft_320x240_upscale_from_128x64_fn(u8g_t *u8g, u8g_dev_t *dev, u tftio.WriteSequence(buffer, COUNT(bufferA)); #else - uint8_t* bufptr = (uint8_t*) buffer; + uint8_t *bufptr = (uint8_t*) buffer; for (uint8_t i = GRAPHICAL_TFT_UPSCALE; i--;) { LOOP_S_L_N(n, 0, GRAPHICAL_TFT_UPSCALE * 2) { u8g_WriteSequence(u8g, dev, WIDTH, &bufptr[WIDTH * n]); @@ -429,8 +425,6 @@ uint8_t u8g_dev_tft_320x240_upscale_from_128x64_fn(u8g_t *u8g, u8g_dev_t *dev, u return u8g_dev_pb8v1_base_fn(u8g, dev, msg, arg); } -static uint8_t msgInitCount = 2; // Ignore all messages until 2nd U8G_COM_MSG_INIT - uint8_t u8g_com_hal_tft_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) { if (msgInitCount) { if (msg == U8G_COM_MSG_INIT) msgInitCount--; @@ -442,8 +436,6 @@ uint8_t u8g_com_hal_tft_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_p switch (msg) { case U8G_COM_MSG_STOP: break; case U8G_COM_MSG_INIT: - u8g_SetPIOutput(u8g, U8G_PI_RESET); - u8g_Delay(50); isCommand = 0; break; @@ -452,7 +444,6 @@ uint8_t u8g_com_hal_tft_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_p break; case U8G_COM_MSG_RESET: - u8g_SetPILevel(u8g, U8G_PI_RESET, arg_val); break; case U8G_COM_MSG_WRITE_BYTE: @@ -467,7 +458,7 @@ uint8_t u8g_com_hal_tft_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_p case U8G_COM_MSG_WRITE_SEQ: tftio.DataTransferBegin(DATASIZE_16BIT); for (uint8_t i = 0; i < arg_val; i += 2) - tftio.WriteData(*(uint16_t *)(((uint32_t)arg_ptr) + i)); + tftio.WriteData(*(uint16_t *)(((uintptr_t)arg_ptr) + i)); tftio.DataTransferEnd(); break; @@ -477,4 +468,70 @@ uint8_t u8g_com_hal_tft_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_p U8G_PB_DEV(u8g_dev_tft_320x240_upscale_from_128x64, WIDTH, HEIGHT, PAGE_HEIGHT, u8g_dev_tft_320x240_upscale_from_128x64_fn, U8G_COM_HAL_TFT_FN); -#endif // HAS_MARLINUI_U8GLIB && FSMC_CS +#if ENABLED(TOUCH_SCREEN_CALIBRATION) + + static void drawCross(uint16_t x, uint16_t y, uint16_t color) { + tftio.set_window(x - 15, y, x + 15, y); + tftio.WriteMultiple(color, 31); + tftio.set_window(x, y - 15, x, y + 15); + tftio.WriteMultiple(color, 31); + } + + void MarlinUI::touch_calibration_screen() { + uint16_t x, y; + calibrationState calibration_stage = touch_calibration.get_calibration_state(); + + if (calibration_stage == CALIBRATION_NONE) { + // start and clear screen + defer_status_screen(true); + calibration_stage = touch_calibration.calibration_start(); + tftio.set_window(0, 0, (TFT_WIDTH) - 1, (TFT_HEIGHT) - 1); + tftio.WriteMultiple(TFT_MARLINBG_COLOR, uint32_t(TFT_WIDTH) * (TFT_HEIGHT)); + } + else { + // clear last cross + x = touch_calibration.calibration_points[_MIN(calibration_stage - 1, CALIBRATION_BOTTOM_RIGHT)].x; + y = touch_calibration.calibration_points[_MIN(calibration_stage - 1, CALIBRATION_BOTTOM_RIGHT)].y; + drawCross(x, y, TFT_MARLINBG_COLOR); + } + + const char *str = nullptr; + if (calibration_stage < CALIBRATION_SUCCESS) { + // handle current state + switch (calibration_stage) { + case CALIBRATION_TOP_LEFT: str = GET_TEXT(MSG_TOP_LEFT); break; + case CALIBRATION_BOTTOM_LEFT: str = GET_TEXT(MSG_BOTTOM_LEFT); break; + case CALIBRATION_TOP_RIGHT: str = GET_TEXT(MSG_TOP_RIGHT); break; + case CALIBRATION_BOTTOM_RIGHT: str = GET_TEXT(MSG_BOTTOM_RIGHT); break; + default: break; + } + + x = touch_calibration.calibration_points[calibration_stage].x; + y = touch_calibration.calibration_points[calibration_stage].y; + drawCross(x, y, TFT_MARLINUI_COLOR); + } + else { + // end calibration + str = calibration_stage == CALIBRATION_SUCCESS ? GET_TEXT(MSG_CALIBRATION_COMPLETED) : GET_TEXT(MSG_CALIBRATION_FAILED); + defer_status_screen(false); + touch_calibration.calibration_end(); + TERN_(HAS_TOUCH_BUTTONS, redrawTouchButtons = true); + } + + // draw current message + tftio.set_window(TFT_PIXEL_OFFSET_X, TFT_PIXEL_OFFSET_Y, X_HI, Y_HI); + do { + set_font(FONT_MENU); + lcd_put_u8str(0, LCD_PIXEL_HEIGHT / 2, str); + } while (u8g.nextPage()); + drawing_screen = false; + safe_delay(250); + if (calibration_stage == CALIBRATION_SUCCESS) { + safe_delay(500); + ui.goto_previous_screen(); + } + } + +#endif // TOUCH_SCREEN_CALIBRATION + +#endif // HAS_MARLINUI_U8GLIB && (FSMC_CS_PIN || HAS_SPI_GRAPHICAL_TFT) diff --git a/Marlin/src/lcd/dogm/u8g_fontutf8.h b/Marlin/src/lcd/dogm/u8g_fontutf8.h index 34e365cf9553..9760ef106bd1 100644 --- a/Marlin/src/lcd/dogm/u8g_fontutf8.h +++ b/Marlin/src/lcd/dogm/u8g_fontutf8.h @@ -8,7 +8,7 @@ */ #pragma once -#include +#include #include "../fontutils.h" // the macro to indicate a UTF-8 string @@ -35,3 +35,6 @@ int uxg_GetUtf8StrPixelWidth(u8g_t *pu8g, const char *utf8_msg); int uxg_GetUtf8StrPixelWidthP(u8g_t *pu8g, PGM_P utf8_msg); #define uxg_GetFont(puxg) ((puxg)->font) + +#define _LANG_FONT_INFO(L) g_fontinfo_##L +#define LANG_FONT_INFO(L) _LANG_FONT_INFO(L) diff --git a/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp b/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp deleted file mode 100644 index c48abac81016..000000000000 --- a/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp +++ /dev/null @@ -1,690 +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 . - * - */ - -/** - * lcd/dogm/ultralcd_DOGM.h - * - * Implementation of the LCD display routines for a DOGM128 graphic display. - * by STB for ErikZalm/Marlin. Common LCD 128x64 pixel graphic displays. - * - * Demonstrator: https://www.reprap.org/wiki/STB_Electronics - * License: https://opensource.org/licenses/BSD-3-Clause - * - * With the use of: - * u8glib by Oliver Kraus - * https://github.com/olikraus/U8glib_Arduino - * License: https://opensource.org/licenses/BSD-3-Clause - */ - -#include "../../inc/MarlinConfigPre.h" - -#if HAS_MARLINUI_U8GLIB - -#include "ultralcd_DOGM.h" -#include "u8g_fontutf8.h" - -#if ENABLED(SHOW_BOOTSCREEN) - #include "dogm_Bootscreen.h" -#endif - -#include "../lcdprint.h" -#include "../fontutils.h" -#include "../../libs/numtostr.h" -#include "../ultralcd.h" - -#include "../../sd/cardreader.h" -#include "../../module/temperature.h" -#include "../../module/printcounter.h" - -#if ENABLED(SDSUPPORT) - #include "../../libs/duration_t.h" -#endif - -#if ENABLED(AUTO_BED_LEVELING_UBL) - #include "../../feature/bedlevel/bedlevel.h" -#endif - -/** - * Include all needed font files - * (See https://marlinfw.org/docs/development/fonts.html) - */ -#include "fontdata/fontdata_ISO10646_1.h" -#if ENABLED(USE_SMALL_INFOFONT) - #include "fontdata/fontdata_6x9_marlin.h" - #define FONT_STATUSMENU_NAME u8g_font_6x9 -#else - #define FONT_STATUSMENU_NAME MENU_FONT_NAME -#endif - -U8G_CLASS u8g(U8G_PARAM); - -#include LANGUAGE_DATA_INCL(LCD_LANGUAGE) - -#if HAS_LCD_CONTRAST - - int16_t MarlinUI::contrast = DEFAULT_LCD_CONTRAST; - - void MarlinUI::set_contrast(const int16_t value) { - contrast = constrain(value, LCD_CONTRAST_MIN, LCD_CONTRAST_MAX); - u8g.setContrast(contrast); - } - -#endif - -void MarlinUI::set_font(const MarlinFont font_nr) { - static char currentfont = 0; - if (font_nr != currentfont) { - switch ((currentfont = font_nr)) { - case FONT_STATUSMENU : u8g.setFont(FONT_STATUSMENU_NAME); break; - case FONT_EDIT : u8g.setFont(EDIT_FONT_NAME); break; - default: - case FONT_MENU : u8g.setFont(MENU_FONT_NAME); break; - } - } -} - -bool MarlinUI::detected() { return true; } - -#if ENABLED(SHOW_BOOTSCREEN) - - #if ENABLED(SHOW_CUSTOM_BOOTSCREEN) - // Draws a slice of a particular frame of the custom bootscreen, without the u8g loop - void MarlinUI::draw_custom_bootscreen(const uint8_t frame/*=0*/) { - constexpr u8g_uint_t left = u8g_uint_t((LCD_PIXEL_WIDTH - (CUSTOM_BOOTSCREEN_BMPWIDTH)) / 2), - top = u8g_uint_t((LCD_PIXEL_HEIGHT - (CUSTOM_BOOTSCREEN_BMPHEIGHT)) / 2); - #if ENABLED(CUSTOM_BOOTSCREEN_INVERTED) - constexpr u8g_uint_t right = left + CUSTOM_BOOTSCREEN_BMPWIDTH, - bottom = top + CUSTOM_BOOTSCREEN_BMPHEIGHT; - #endif - - const u8g_pgm_uint8_t * const bmp = - #if ENABLED(CUSTOM_BOOTSCREEN_ANIMATED) - (u8g_pgm_uint8_t*)pgm_read_ptr(&custom_bootscreen_animation[frame]) - #else - custom_start_bmp - #endif - ; - TERN(CUSTOM_BOOTSCREEN_ANIMATED,,UNUSED(frame)); - - u8g.drawBitmapP(left, top, CUSTOM_BOOTSCREEN_BMP_BYTEWIDTH, CUSTOM_BOOTSCREEN_BMPHEIGHT, bmp); - - #if ENABLED(CUSTOM_BOOTSCREEN_INVERTED) - if (frame == 0) { - u8g.setColorIndex(1); - if (top) u8g.drawBox(0, 0, LCD_PIXEL_WIDTH, top); - if (left) u8g.drawBox(0, top, left, CUSTOM_BOOTSCREEN_BMPHEIGHT); - if (right < LCD_PIXEL_WIDTH) u8g.drawBox(right, top, LCD_PIXEL_WIDTH - right, CUSTOM_BOOTSCREEN_BMPHEIGHT); - if (bottom < LCD_PIXEL_HEIGHT) u8g.drawBox(0, bottom, LCD_PIXEL_WIDTH, LCD_PIXEL_HEIGHT - bottom); - } - #endif - } - - // Shows the custom bootscreen, with the u8g loop, animations and delays - void MarlinUI::show_custom_bootscreen() { - #if DISABLED(CUSTOM_BOOTSCREEN_ANIMATED) - constexpr millis_t d = 0; - constexpr uint8_t f = 0; - #else - constexpr millis_t d = CUSTOM_BOOTSCREEN_FRAME_TIME; - LOOP_L_N(f, COUNT(custom_bootscreen_animation)) - #endif - { - u8g.firstPage(); - do { draw_custom_bootscreen(f); } while (u8g.nextPage()); - if (d) safe_delay(d); - } - - #ifndef CUSTOM_BOOTSCREEN_TIMEOUT - #define CUSTOM_BOOTSCREEN_TIMEOUT 2500 - #endif - safe_delay(CUSTOM_BOOTSCREEN_TIMEOUT); - } - #endif // SHOW_CUSTOM_BOOTSCREEN - - // Two-part needed to display all info - constexpr bool two_part = ((LCD_PIXEL_HEIGHT) - (START_BMPHEIGHT)) < ((MENU_FONT_ASCENT) * 2); - - // Draw the static Marlin bootscreen from a u8g loop - // or the animated boot screen within its own u8g loop - void MarlinUI::draw_marlin_bootscreen(const bool line2/*=false*/) { - - // Determine text space needed - constexpr u8g_uint_t text_width_1 = u8g_uint_t((sizeof(SHORT_BUILD_VERSION) - 1) * (MENU_FONT_WIDTH)), - text_width_2 = u8g_uint_t((sizeof(MARLIN_WEBSITE_URL) - 1) * (MENU_FONT_WIDTH)), - text_max_width = _MAX(text_width_1, text_width_2), - text_total_height = (MENU_FONT_HEIGHT) * 2, - width = LCD_PIXEL_WIDTH, height = LCD_PIXEL_HEIGHT, - rspace = width - (START_BMPWIDTH); - - u8g_int_t offx, offy, txt_base, txt_offx_1, txt_offx_2; - - // Can the text fit to the right of the bitmap? - if (text_max_width < rspace) { - constexpr int8_t inter = (width - text_max_width - (START_BMPWIDTH)) / 3; // Evenly distribute horizontal space - offx = inter; // First the boot logo... - offy = (height - (START_BMPHEIGHT)) / 2; // ...V-aligned in the full height - txt_offx_1 = txt_offx_2 = inter + (START_BMPWIDTH) + inter; // Text right of the bitmap - txt_base = (height + MENU_FONT_ASCENT + text_total_height - (MENU_FONT_HEIGHT)) / 2; // Text vertical center - } - else { - constexpr int8_t inter = (height - text_total_height - (START_BMPHEIGHT)) / 3; // Evenly distribute vertical space - offx = rspace / 2; // Center the boot logo in the whole space - offy = inter; // V-align boot logo proportionally - txt_offx_1 = (width - text_width_1) / 2; // Text 1 centered - txt_offx_2 = (width - text_width_2) / 2; // Text 2 centered - txt_base = offy + START_BMPHEIGHT + offy + text_total_height - (MENU_FONT_DESCENT); // Even spacing looks best - } - NOLESS(offx, 0); - NOLESS(offy, 0); - - auto _draw_bootscreen_bmp = [&](const uint8_t *bitmap) { - u8g.drawBitmapP(offx, offy, START_BMP_BYTEWIDTH, START_BMPHEIGHT, bitmap); - set_font(FONT_MENU); - if (!two_part || !line2) lcd_put_u8str_P(txt_offx_1, txt_base - (MENU_FONT_HEIGHT), PSTR(SHORT_BUILD_VERSION)); - if (!two_part || line2) lcd_put_u8str_P(txt_offx_2, txt_base, PSTR(MARLIN_WEBSITE_URL)); - }; - - auto draw_bootscreen_bmp = [&](const uint8_t *bitmap) { - u8g.firstPage(); do { _draw_bootscreen_bmp(bitmap); } while (u8g.nextPage()); - }; - - #if DISABLED(BOOT_MARLIN_LOGO_ANIMATED) - draw_bootscreen_bmp(start_bmp); - #else - constexpr millis_t d = MARLIN_BOOTSCREEN_FRAME_TIME; - LOOP_L_N(f, COUNT(marlin_bootscreen_animation)) { - draw_bootscreen_bmp((uint8_t*)pgm_read_ptr(&marlin_bootscreen_animation[f])); - if (d) safe_delay(d); - } - #endif - } - - // Show the Marlin bootscreen, with the u8g loop and delays - void MarlinUI::show_marlin_bootscreen() { - constexpr uint8_t pages = two_part ? 2 : 1; - for (uint8_t q = pages; q--;) { - draw_marlin_bootscreen(q == 0); - safe_delay((BOOTSCREEN_TIMEOUT) / pages); - } - } - - void MarlinUI::show_bootscreen() { - TERN_(SHOW_CUSTOM_BOOTSCREEN, show_custom_bootscreen()); - show_marlin_bootscreen(); - } - -#endif // SHOW_BOOTSCREEN - -#if ENABLED(LIGHTWEIGHT_UI) - #include "status_screen_lite_ST7920.h" -#endif - -// Initialize or re-initialize the LCD -void MarlinUI::init_lcd() { - #if PIN_EXISTS(LCD_BACKLIGHT) - OUT_WRITE(LCD_BACKLIGHT_PIN, DISABLED(DELAYED_BACKLIGHT_INIT)); // Illuminate after reset or right away - #endif - - #if ANY(MKS_12864OLED, MKS_12864OLED_SSD1306, FYSETC_242_OLED_12864, ZONESTAR_12864OLED) - SET_OUTPUT(LCD_PINS_DC); - #ifndef LCD_RESET_PIN - #define LCD_RESET_PIN LCD_PINS_RS - #endif - #endif - - #if PIN_EXISTS(LCD_RESET) - // Perform a clean hardware reset with needed delays - OUT_WRITE(LCD_RESET_PIN, LOW); - _delay_ms(5); - WRITE(LCD_RESET_PIN, HIGH); - _delay_ms(5); - u8g.begin(); - #endif - - #if PIN_EXISTS(LCD_BACKLIGHT) && ENABLED(DELAYED_BACKLIGHT_INIT) - WRITE(LCD_BACKLIGHT_PIN, HIGH); - #endif - - TERN_(HAS_LCD_CONTRAST, refresh_contrast()); - - TERN_(LCD_SCREEN_ROT_90, u8g.setRot90()); - TERN_(LCD_SCREEN_ROT_180, u8g.setRot180()); - TERN_(LCD_SCREEN_ROT_270, u8g.setRot270()); - - uxg_SetUtf8Fonts(g_fontinfo, COUNT(g_fontinfo)); -} - -// The kill screen is displayed for unrecoverable conditions -void MarlinUI::draw_kill_screen() { - TERN_(LIGHTWEIGHT_UI, ST7920_Lite_Status_Screen::clear_text_buffer()); - const u8g_uint_t h4 = u8g.getHeight() / 4; - u8g.firstPage(); - do { - set_font(FONT_MENU); - lcd_put_u8str(0, h4 * 1, status_message); - lcd_put_u8str_P(0, h4 * 2, GET_TEXT(MSG_HALTED)); - lcd_put_u8str_P(0, h4 * 3, GET_TEXT(MSG_PLEASE_RESET)); - } while (u8g.nextPage()); -} - -void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop - -#if HAS_LCD_MENU - - #include "../menu/menu.h" - - u8g_uint_t row_y1, row_y2; - - #if ENABLED(ADVANCED_PAUSE_FEATURE) - - void MarlinUI::draw_hotend_status(const uint8_t row, const uint8_t extruder) { - row_y1 = row * (MENU_FONT_HEIGHT) + 1; - row_y2 = row_y1 + MENU_FONT_HEIGHT - 1; - - if (!PAGE_CONTAINS(row_y1 + 1, row_y2 + 2)) return; - - lcd_put_wchar(LCD_PIXEL_WIDTH - 11 * (MENU_FONT_WIDTH), row_y2, 'E'); - lcd_put_wchar((char)('1' + extruder)); - lcd_put_wchar(' '); - lcd_put_u8str(i16tostr3rj(thermalManager.degHotend(extruder))); - lcd_put_wchar('/'); - - if (get_blink() || !thermalManager.heater_idle[extruder].timed_out) - lcd_put_u8str(i16tostr3rj(thermalManager.degTargetHotend(extruder))); - } - - #endif // ADVANCED_PAUSE_FEATURE - - // Mark a menu item and set font color if selected. - // Return 'false' if the item is not on screen. - static bool mark_as_selected(const uint8_t row, const bool sel) { - row_y1 = row * (MENU_FONT_HEIGHT) + 1; - row_y2 = row_y1 + MENU_FONT_HEIGHT - 1; - - if (!PAGE_CONTAINS(row_y1 + 1, row_y2 + 2)) return false; - - if (sel) { - #if ENABLED(MENU_HOLLOW_FRAME) - u8g.drawHLine(0, row_y1 + 1, LCD_PIXEL_WIDTH); - u8g.drawHLine(0, row_y2 + 2, LCD_PIXEL_WIDTH); - #else - u8g.setColorIndex(1); // solid outline - u8g.drawBox(0, row_y1 + 2, LCD_PIXEL_WIDTH, MENU_FONT_HEIGHT - 1); - u8g.setColorIndex(0); // inverted text - #endif - } - #if DISABLED(MENU_HOLLOW_FRAME) - else u8g.setColorIndex(1); // solid text - #endif - - if (!PAGE_CONTAINS(row_y1, row_y2)) return false; - - lcd_moveto(0, row_y2); - return true; - } - - // Draw a static line of text in the same idiom as a menu item - void MenuItem_static::draw(const uint8_t row, PGM_P const pstr, const uint8_t style/*=SS_DEFAULT*/, const char * const vstr/*=nullptr*/) { - - if (mark_as_selected(row, style & SS_INVERT)) { - - pixel_len_t n = LCD_PIXEL_WIDTH; // pixel width of string allowed - - const int8_t plen = pstr ? utf8_strlen_P(pstr) : 0, - vlen = vstr ? utf8_strlen(vstr) : 0; - if (style & SS_CENTER) { - int8_t pad = (LCD_WIDTH - plen - vlen) / 2; - while (--pad >= 0) n -= lcd_put_wchar(' '); - } - - if (plen) n = lcd_put_u8str_ind_P(pstr, itemIndex, itemString, n / (MENU_FONT_WIDTH)) * (MENU_FONT_WIDTH); - if (vlen) n -= lcd_put_u8str_max(vstr, n); - while (n > MENU_FONT_WIDTH) n -= lcd_put_wchar(' '); - } - } - - // Draw a generic menu item - void MenuItemBase::_draw(const bool sel, const uint8_t row, PGM_P const pstr, const char, const char post_char) { - if (mark_as_selected(row, sel)) { - pixel_len_t n = lcd_put_u8str_ind_P(pstr, itemIndex, itemString, LCD_WIDTH - 1) * (MENU_FONT_WIDTH); - while (n > MENU_FONT_WIDTH) n -= lcd_put_wchar(' '); - lcd_put_wchar(LCD_PIXEL_WIDTH - (MENU_FONT_WIDTH), row_y2, post_char); - lcd_put_wchar(' '); - } - } - - // Draw a menu item with an editable value - void MenuEditItemBase::draw(const bool sel, const uint8_t row, PGM_P const pstr, const char* const inStr, const bool pgm) { - if (mark_as_selected(row, sel)) { - const uint8_t vallen = (pgm ? utf8_strlen_P(inStr) : utf8_strlen((char*)inStr)), - pixelwidth = (pgm ? uxg_GetUtf8StrPixelWidthP(u8g.getU8g(), inStr) : uxg_GetUtf8StrPixelWidth(u8g.getU8g(), (char*)inStr)); - - pixel_len_t n = lcd_put_u8str_ind_P(pstr, itemIndex, itemString, LCD_WIDTH - 2 - vallen) * (MENU_FONT_WIDTH); - if (vallen) { - lcd_put_wchar(':'); - while (n > MENU_FONT_WIDTH) n -= lcd_put_wchar(' '); - lcd_moveto(LCD_PIXEL_WIDTH - _MAX((MENU_FONT_WIDTH) * vallen, pixelwidth + 2), row_y2); - if (pgm) lcd_put_u8str_P(inStr); else lcd_put_u8str((char*)inStr); - } - } - } - - void MenuEditItemBase::draw_edit_screen(PGM_P const pstr, const char* const value/*=nullptr*/) { - ui.encoder_direction_normal(); - - const u8g_uint_t labellen = utf8_strlen_P(pstr), vallen = utf8_strlen(value); - bool extra_row = labellen > LCD_WIDTH - 2 - vallen; - - #if ENABLED(USE_BIG_EDIT_FONT) - // Use the menu font if the label won't fit on a single line - constexpr u8g_uint_t lcd_edit_width = (LCD_PIXEL_WIDTH) / (EDIT_FONT_WIDTH); - u8g_uint_t lcd_chr_fit, one_chr_width; - if (labellen <= lcd_edit_width - 1) { - if (labellen + vallen + 1 > lcd_edit_width) extra_row = true; - lcd_chr_fit = lcd_edit_width + 1; - one_chr_width = EDIT_FONT_WIDTH; - ui.set_font(FONT_EDIT); - } - else { - lcd_chr_fit = LCD_WIDTH; - one_chr_width = MENU_FONT_WIDTH; - ui.set_font(FONT_MENU); - } - #else - constexpr u8g_uint_t lcd_chr_fit = LCD_WIDTH, - one_chr_width = MENU_FONT_WIDTH; - #endif - - // Center the label and value lines on the middle line - u8g_uint_t baseline = extra_row ? (LCD_PIXEL_HEIGHT) / 2 - 1 - : (LCD_PIXEL_HEIGHT + EDIT_FONT_ASCENT) / 2; - - // Assume the label is alpha-numeric (with a descender) - bool onpage = PAGE_CONTAINS(baseline - (EDIT_FONT_ASCENT - 1), baseline + EDIT_FONT_DESCENT); - if (onpage) lcd_put_u8str_ind_P(0, baseline, pstr, itemIndex, itemString); - - // If a value is included, print a colon, then print the value right-justified - if (value != nullptr) { - lcd_put_wchar(':'); - if (extra_row) { - // Assume that value is numeric (with no descender) - baseline += EDIT_FONT_ASCENT + 2; - onpage = PAGE_CONTAINS(baseline - (EDIT_FONT_ASCENT - 1), baseline); - } - if (onpage) { - lcd_put_wchar(((lcd_chr_fit - 1) - (vallen + 1)) * one_chr_width, baseline, ' '); // Right-justified, padded, add a leading space - lcd_put_u8str(value); - } - } - TERN_(USE_BIG_EDIT_FONT, ui.set_font(FONT_MENU)); - } - - inline void draw_boxed_string(const u8g_uint_t x, const u8g_uint_t y, PGM_P const pstr, const bool inv) { - const u8g_uint_t len = utf8_strlen_P(pstr), - by = (y + 1) * (MENU_FONT_HEIGHT); - const pixel_len_t bw = len * (MENU_FONT_WIDTH), bx = x * (MENU_FONT_WIDTH); - if (inv) { - u8g.setColorIndex(1); - u8g.drawBox(bx - 1, by - (MENU_FONT_ASCENT) + 1, bw + 2, MENU_FONT_HEIGHT - 1); - u8g.setColorIndex(0); - } - lcd_put_u8str_P(bx, by, pstr); - if (inv) u8g.setColorIndex(1); - } - - void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const bool yesno, PGM_P const pref, const char * const string/*=nullptr*/, PGM_P const suff/*=nullptr*/) { - ui.draw_select_screen_prompt(pref, string, suff); - draw_boxed_string(1, LCD_HEIGHT - 1, no, !yesno); - draw_boxed_string(LCD_WIDTH - (utf8_strlen_P(yes) + 1), LCD_HEIGHT - 1, yes, yesno); - } - - #if ENABLED(SDSUPPORT) - - void MenuItem_sdbase::draw(const bool sel, const uint8_t row, PGM_P const, CardReader &theCard, const bool isDir) { - if (mark_as_selected(row, sel)) { - if (isDir) lcd_put_wchar(LCD_STR_FOLDER[0]); - constexpr uint8_t maxlen = LCD_WIDTH - 1; - const pixel_len_t pixw = maxlen * (MENU_FONT_WIDTH); - pixel_len_t n = pixw - lcd_put_u8str_max(ui.scrolled_filename(theCard, maxlen, row, sel), pixw); - while (n > MENU_FONT_WIDTH) n -= lcd_put_wchar(' '); - } - } - - #endif // SDSUPPORT - - #if ENABLED(AUTO_BED_LEVELING_UBL) - - /** - * UBL LCD "radar" map data - */ - #define MAP_UPPER_LEFT_CORNER_X 35 // These probably should be moved to the .h file But for now, - #define MAP_UPPER_LEFT_CORNER_Y 8 // it is easier to play with things having them here - #define MAP_MAX_PIXELS_X 53 - #define MAP_MAX_PIXELS_Y 49 - - void MarlinUI::ubl_plot(const uint8_t x_plot, const uint8_t y_plot) { - // Scale the box pixels appropriately - u8g_uint_t x_map_pixels = ((MAP_MAX_PIXELS_X - 4) / (GRID_MAX_POINTS_X)) * (GRID_MAX_POINTS_X), - y_map_pixels = ((MAP_MAX_PIXELS_Y - 4) / (GRID_MAX_POINTS_Y)) * (GRID_MAX_POINTS_Y), - - pixels_per_x_mesh_pnt = x_map_pixels / (GRID_MAX_POINTS_X), - pixels_per_y_mesh_pnt = y_map_pixels / (GRID_MAX_POINTS_Y), - - x_offset = MAP_UPPER_LEFT_CORNER_X + 1 + (MAP_MAX_PIXELS_X - x_map_pixels - 2) / 2, - y_offset = MAP_UPPER_LEFT_CORNER_Y + 1 + (MAP_MAX_PIXELS_Y - y_map_pixels - 2) / 2; - - // Clear the Mesh Map - - if (PAGE_CONTAINS(y_offset - 2, y_offset + y_map_pixels + 4)) { - u8g.setColorIndex(1); // First draw the bigger box in White so we have a border around the mesh map box - u8g.drawBox(x_offset - 2, y_offset - 2, x_map_pixels + 4, y_map_pixels + 4); - if (PAGE_CONTAINS(y_offset, y_offset + y_map_pixels)) { - u8g.setColorIndex(0); // Now actually clear the mesh map box - u8g.drawBox(x_offset, y_offset, x_map_pixels, y_map_pixels); - } - } - - // Display Mesh Point Locations - - u8g.setColorIndex(1); - const u8g_uint_t sx = x_offset + pixels_per_x_mesh_pnt / 2; - u8g_uint_t y = y_offset + pixels_per_y_mesh_pnt / 2; - for (uint8_t j = 0; j < GRID_MAX_POINTS_Y; j++, y += pixels_per_y_mesh_pnt) - if (PAGE_CONTAINS(y, y)) - for (uint8_t i = 0, x = sx; i < GRID_MAX_POINTS_X; i++, x += pixels_per_x_mesh_pnt) - u8g.drawBox(x, y, 1, 1); - - // Fill in the Specified Mesh Point - - const uint8_t y_plot_inv = (GRID_MAX_POINTS_Y - 1) - y_plot; // The origin is typically in the lower right corner. We need to - // invert the Y to get it to plot in the right location. - - const u8g_uint_t by = y_offset + y_plot_inv * pixels_per_y_mesh_pnt; - if (PAGE_CONTAINS(by, by + pixels_per_y_mesh_pnt)) - u8g.drawBox( - x_offset + x_plot * pixels_per_x_mesh_pnt, by, - pixels_per_x_mesh_pnt, pixels_per_y_mesh_pnt - ); - - // Put Relevant Text on Display - - // Show X and Y positions at top of screen - u8g.setColorIndex(1); - if (PAGE_UNDER(7)) { - const xy_pos_t pos = { ubl.mesh_index_to_xpos(x_plot), ubl.mesh_index_to_ypos(y_plot) }, - lpos = pos.asLogical(); - lcd_put_u8str_P(5, 7, X_LBL); - lcd_put_u8str(ftostr52(lpos.x)); - lcd_put_u8str_P(74, 7, Y_LBL); - lcd_put_u8str(ftostr52(lpos.y)); - } - - // Print plot position - if (PAGE_CONTAINS(LCD_PIXEL_HEIGHT - (INFO_FONT_HEIGHT - 1), LCD_PIXEL_HEIGHT)) { - lcd_put_wchar(5, LCD_PIXEL_HEIGHT, '('); - u8g.print(x_plot); - lcd_put_wchar(','); - u8g.print(y_plot); - lcd_put_wchar(')'); - - // Show the location value - lcd_put_u8str_P(74, LCD_PIXEL_HEIGHT, Z_LBL); - if (!isnan(ubl.z_values[x_plot][y_plot])) - lcd_put_u8str(ftostr43sign(ubl.z_values[x_plot][y_plot])); - else - lcd_put_u8str_P(PSTR(" -----")); - } - - } - - #endif // AUTO_BED_LEVELING_UBL - - #if EITHER(BABYSTEP_ZPROBE_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY) - - const unsigned char cw_bmp[] PROGMEM = { - B00000000,B11111110,B00000000, - B00000011,B11111111,B10000000, - B00000111,B11000111,B11000000, - B00000111,B00000001,B11100000, - B00000000,B00000000,B11100000, - B00000000,B00000000,B11110000, - B00000000,B00000000,B01110000, - B00000100,B00000000,B01110000, - B00001110,B00000000,B01110000, - B00011111,B00000000,B01110000, - B00111111,B10000000,B11110000, - B00001110,B00000000,B11100000, - B00001111,B00000001,B11100000, - B00000111,B11000111,B11000000, - B00000011,B11111111,B10000000, - B00000000,B11111110,B00000000 - }; - - const unsigned char ccw_bmp[] PROGMEM = { - B00000000,B11111110,B00000000, - B00000011,B11111111,B10000000, - B00000111,B11000111,B11000000, - B00001111,B00000001,B11100000, - B00001110,B00000000,B11100000, - B00111111,B10000000,B11110000, - B00011111,B00000000,B01110000, - B00001110,B00000000,B01110000, - B00000100,B00000000,B01110000, - B00000000,B00000000,B01110000, - B00000000,B00000000,B11110000, - B00000000,B00000000,B11100000, - B00000111,B00000001,B11100000, - B00000111,B11000111,B11000000, - B00000011,B11111111,B10000000, - B00000000,B11111110,B00000000 - }; - - const unsigned char up_arrow_bmp[] PROGMEM = { - B00000100,B00000000, - B00001110,B00000000, - B00011111,B00000000, - B00111111,B10000000, - B01111111,B11000000, - B00001110,B00000000, - B00001110,B00000000, - B00001110,B00000000, - B00001110,B00000000, - B00001110,B00000000, - B00001110,B00000000, - B00001110,B00000000, - B00001110,B00000000 - }; - - const unsigned char down_arrow_bmp[] PROGMEM = { - B00001110,B00000000, - B00001110,B00000000, - B00001110,B00000000, - B00001110,B00000000, - B00001110,B00000000, - B00001110,B00000000, - B00001110,B00000000, - B00001110,B00000000, - B01111111,B11000000, - B00111111,B10000000, - B00011111,B00000000, - B00001110,B00000000, - B00000100,B00000000 - }; - - const unsigned char offset_bedline_bmp[] PROGMEM = { - B11111111,B11111111,B11111111 - }; - - const unsigned char nozzle_bmp[] PROGMEM = { - B01111111,B10000000, - B11111111,B11000000, - B11111111,B11000000, - B11111111,B11000000, - B01111111,B10000000, - B01111111,B10000000, - B11111111,B11000000, - B11111111,B11000000, - B11111111,B11000000, - B00111111,B00000000, - B00011110,B00000000, - B00001100,B00000000 - }; - - void _lcd_zoffset_overlay_gfx(const float zvalue) { - // Determine whether the user is raising or lowering the nozzle. - static int8_t dir; - static float old_zvalue; - if (zvalue != old_zvalue) { - dir = zvalue ? zvalue < old_zvalue ? -1 : 1 : 0; - old_zvalue = zvalue; - } - - #if ENABLED(OVERLAY_GFX_REVERSE) - const unsigned char *rot_up = ccw_bmp, *rot_down = cw_bmp; - #else - const unsigned char *rot_up = cw_bmp, *rot_down = ccw_bmp; - #endif - - #if ENABLED(USE_BIG_EDIT_FONT) - const int left = 0, right = 45, nozzle = 95; - #else - const int left = 5, right = 90, nozzle = 60; - #endif - - // Draw a representation of the nozzle - if (PAGE_CONTAINS(3, 16)) u8g.drawBitmapP(nozzle + 6, 4 - dir, 2, 12, nozzle_bmp); - if (PAGE_CONTAINS(20, 20)) u8g.drawBitmapP(nozzle + 0, 20, 3, 1, offset_bedline_bmp); - - // Draw cw/ccw indicator and up/down arrows. - if (PAGE_CONTAINS(47, 62)) { - u8g.drawBitmapP(right + 0, 48 - dir, 2, 13, up_arrow_bmp); - u8g.drawBitmapP(left + 0, 49 - dir, 2, 13, down_arrow_bmp); - u8g.drawBitmapP(left + 13, 47, 3, 16, rot_down); - u8g.drawBitmapP(right + 13, 47, 3, 16, rot_up); - } - } - - #endif // BABYSTEP_ZPROBE_GFX_OVERLAY || MESH_EDIT_GFX_OVERLAY - -#endif // HAS_LCD_MENU - -#endif // HAS_MARLINUI_U8GLIB diff --git a/Marlin/src/lcd/dogm/ultralcd_DOGM.h b/Marlin/src/lcd/dogm/ultralcd_DOGM.h deleted file mode 100644 index 228cee6848b4..000000000000 --- a/Marlin/src/lcd/dogm/ultralcd_DOGM.h +++ /dev/null @@ -1,222 +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 - -/** - * lcd/dogm/ultralcd_DOGM.h - */ - -#include "../../inc/MarlinConfigPre.h" - -#include -#include "HAL_LCD_class_defines.h" - -//#define ALTERNATIVE_LCD - -#if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - - // RepRapWorld Graphical LCD - - #define U8G_CLASS U8GLIB_ST7920_128X64_4X - #if DISABLED(SDSUPPORT) && (LCD_PINS_D4 == SCK_PIN) && (LCD_PINS_ENABLE == MOSI_PIN) - #define U8G_PARAM LCD_PINS_RS - #else - #define U8G_PARAM LCD_PINS_D4, LCD_PINS_ENABLE, LCD_PINS_RS - #endif - -#elif ENABLED(U8GLIB_ST7920) - - // RepRap Discount Full Graphics Smart Controller - // and other variant LCDs using ST7920 - - #if DISABLED(SDSUPPORT) && (LCD_PINS_D4 == SCK_PIN) && (LCD_PINS_ENABLE == 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 - #if ENABLED(ALTERNATIVE_LCD) - #define U8G_CLASS U8GLIB_ST7920_128X64_4X // 2 stripes, SW SPI (Original u8glib device) - #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 - // HAL version uses these pin settings - #endif - -#elif ENABLED(CARTESIO_UI) - - // CartesioUI LCD - - #if ENABLED(ALTERNATIVE_LCD) - #define U8G_CLASS U8GLIB_DOGM128_2X // 4 stripes - #define FORCE_SOFT_SPI // SW-SPI - #else - #define U8G_CLASS U8GLIB_DOGM128_2X // 4 stripes (HW-SPI) - #endif - -#elif ENABLED(U8GLIB_LM6059_AF) - - // Based on the Adafruit ST7565 (https://www.adafruit.com/products/250) - - #if ENABLED(ALTERNATIVE_LCD) - #define U8G_CLASS U8GLIB_LM6059 // 8 stripes (HW-SPI) - #else - #define U8G_CLASS U8GLIB_LM6059_2X // 4 stripes (HW-SPI) - #endif - -#elif ENABLED(U8GLIB_ST7565_64128N) - - // MaKrPanel, Mini Viki, Viki 2.0, AZSMZ 12864 ST7565 controller - - #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 || DOGLCD_SCK != SCK_PIN || DOGLCD_MOSI != MOSI_PIN - #define FORCE_SOFT_SPI // SW-SPI - #endif - -#elif ANY(FYSETC_MINI_12864, MKS_MINI_12864, ENDER2_STOCKDISPLAY) - - // The FYSETC Mini 12864 display // "4 stripes" - - // The MKS_MINI_12864 V1/V2 aren't exact copies of the MiniPanel. - // Panel management is in u8g_dev_uc1701_mini12864_HAL.cpp with - // extra delays added to remove glitches seen with fast MCUs. - - #define U8G_CLASS U8GLIB_MINI12864_2X_HAL // 8 stripes (HW-SPI) - -#elif ENABLED(MINIPANEL) - - #if ENABLED(ALTERNATIVE_LCD) - #define U8G_CLASS U8GLIB_MINI12864 - #else - #define U8G_CLASS U8GLIB_MINI12864_2X // 8 stripes (HW-SPI) - #endif - -#elif EITHER(MKS_12864OLED_SSD1306, FYSETC_242_OLED_12864) - - // MKS 128x64 (SSD1306) OLED I2C LCD - // - or - - // FYSETC OLED 2.42" 128 × 64 FULL GRAPHICS CONTROLLER - - #define FORCE_SOFT_SPI // SW-SPI - - #if ENABLED(ALTERNATIVE_LCD) - #define U8G_CLASS U8GLIB_SSD1306_128X64_2X // 4 stripes - #else - #define U8G_CLASS U8GLIB_SSD1306_128X64 // 8 stripes - #endif - -#elif ENABLED(ZONESTAR_12864OLED_SSD1306) - - // Zonestar SSD1306 OLED SPI LCD - - #define FORCE_SOFT_SPI // SW-SPI - #if ENABLED(ALTERNATIVE_LCD) - #define U8G_CLASS U8GLIB_SH1306_128X64_2X // 4 stripes - #else - #define U8G_CLASS U8GLIB_SH1306_128X64 // 8 stripes - #endif - -#elif EITHER(MKS_12864OLED, ZONESTAR_12864OLED) - - // MKS 128x64 (SH1106) OLED I2C LCD - // - or - - // Zonestar SH1106 OLED SPI LCD - - #define FORCE_SOFT_SPI // SW-SPI - #if ENABLED(ALTERNATIVE_LCD) - #define U8G_CLASS U8GLIB_SH1106_128X64_2X // 4 stripes - #else - #define U8G_CLASS U8GLIB_SH1106_128X64 // 8 stripes - #endif - -#elif ENABLED(U8GLIB_SH1106_EINSTART) - - // Connected via motherboard header - - #define U8G_CLASS U8GLIB_SH1106_128X64 - #define U8G_PARAM DOGLCD_SCK, DOGLCD_MOSI, DOGLCD_CS, LCD_PINS_DC, LCD_PINS_RS - -#elif ENABLED(U8GLIB_SH1106) - - // Generic SH1106 OLED I2C LCD - - #if ENABLED(ALTERNATIVE_LCD) - #define U8G_CLASS U8GLIB_SH1106_128X64_2X_I2C_2_WIRE // 4 stripes - #else - #define U8G_CLASS U8GLIB_SH1106_128X64_2X // 4 stripes - #endif - #define U8G_PARAM (U8G_I2C_OPT_NONE | U8G_I2C_OPT_FAST) // I2C - -#elif ENABLED(U8GLIB_SSD1309) - - // Generic support for SSD1309 OLED I2C LCDs - - #define U8G_CLASS U8GLIB_SSD1309_128X64 - #define U8G_PARAM (U8G_I2C_OPT_NONE | U8G_I2C_OPT_FAST) // I2C - -#elif ENABLED(U8GLIB_SSD1306) - - // Generic SSD1306 OLED I2C LCD - - #if ENABLED(ALTERNATIVE_LCD) - #define U8G_CLASS U8GLIB_SSD1306_128X64_2X_I2C_2_WIRE // 4 stripes - #else - #define U8G_CLASS U8GLIB_SSD1306_128X64_2X // 4 stripes - #endif - #define U8G_PARAM (U8G_I2C_OPT_NONE | U8G_I2C_OPT_FAST) - -#elif TFT_SCALED_DOGLCD - - // Unspecified 320x240 TFT pre-initialized by built-in bootloader - - #define U8G_CLASS U8GLIB_TFT_320X240_UPSCALE_FROM_128X64 - #if ENABLED(FSMC_GRAPHICAL_TFT) - #define U8G_PARAM FSMC_CS_PIN, FSMC_RS_PIN - #else - #define U8G_PARAM -1, -1 - #endif - -#else - - #if ENABLED(ALTERNATIVE_LCD) - #define U8G_CLASS U8GLIB_DOGM128 // 8 stripes (HW-SPI) - #else - #define U8G_CLASS U8GLIB_DOGM128_2X // 4 stripes (HW-SPI) - #endif - -#endif - -// Use HW-SPI if no other option is specified -#ifndef U8G_PARAM - #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 - #endif -#endif - -// For selective rendering within a Y range -#define PAGE_OVER(ya) ((ya) <= u8g.getU8g()->current_page.y1) // Does the current page follow a region top? -#define PAGE_UNDER(yb) ((yb) >= u8g.getU8g()->current_page.y0) // Does the current page precede a region bottom? -#define PAGE_CONTAINS(ya, yb) ((yb) >= u8g.getU8g()->current_page.y0 && (ya) <= u8g.getU8g()->current_page.y1) // Do two vertical regions overlap? - -extern U8G_CLASS u8g; 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 e6bd80c2c2fd..4abf91edbd6e 100644 --- a/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.cpp +++ b/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.cpp @@ -33,6 +33,38 @@ #include "ultralcd_st7920_u8glib_rrd_AVR.h" +#if F_CPU >= 20000000 + #define CPU_ST7920_DELAY_1 DELAY_NS(150) + #define CPU_ST7920_DELAY_2 DELAY_NS(0) + #define CPU_ST7920_DELAY_3 DELAY_NS(150) +#elif MB(3DRAG, K8200, K8400) + #define CPU_ST7920_DELAY_1 DELAY_NS(0) + #define CPU_ST7920_DELAY_2 DELAY_NS(188) + #define CPU_ST7920_DELAY_3 DELAY_NS(0) +#elif MB(MINIRAMBO, EINSY_RAMBO, EINSY_RETRO, SILVER_GATE) + #define CPU_ST7920_DELAY_1 DELAY_NS(0) + #define CPU_ST7920_DELAY_2 DELAY_NS(250) + #define CPU_ST7920_DELAY_3 DELAY_NS(0) +#elif MB(RAMBO) + #define CPU_ST7920_DELAY_1 DELAY_NS(0) + #define CPU_ST7920_DELAY_2 DELAY_NS(0) + #define CPU_ST7920_DELAY_3 DELAY_NS(0) +#elif MB(BQ_ZUM_MEGA_3D) + #define CPU_ST7920_DELAY_1 DELAY_NS(0) + #define CPU_ST7920_DELAY_2 DELAY_NS(0) + #define CPU_ST7920_DELAY_3 DELAY_NS(189) +#elif defined(ARDUINO_ARCH_STM32) + #define CPU_ST7920_DELAY_1 DELAY_NS(300) + #define CPU_ST7920_DELAY_2 DELAY_NS(40) + #define CPU_ST7920_DELAY_3 DELAY_NS(340) +#elif F_CPU == 16000000 + #define CPU_ST7920_DELAY_1 DELAY_NS(125) + #define CPU_ST7920_DELAY_2 DELAY_NS(0) + #define CPU_ST7920_DELAY_3 DELAY_NS(188) +#else + #error "No valid condition for delays in 'ultralcd_st7920_u8glib_rrd_AVR.h'" +#endif + #ifndef ST7920_DELAY_1 #ifdef BOARD_ST7920_DELAY_1 #define ST7920_DELAY_1 BOARD_ST7920_DELAY_1 @@ -116,8 +148,8 @@ uint8_t u8g_dev_rrd_st7920_128x64_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, vo case U8G_DEV_MSG_STOP: break; case U8G_DEV_MSG_PAGE_NEXT: { - uint8_t* ptr; - u8g_pb_t* pb = (u8g_pb_t*)(dev->dev_mem); + uint8_t *ptr; + u8g_pb_t *pb = (u8g_pb_t*)(dev->dev_mem); y = pb->p.page_y0; ptr = (uint8_t*)pb->buf; 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 70be70eab79a..446bfcfd4212 100644 --- a/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.h +++ b/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.h @@ -35,44 +35,7 @@ #define PAGE_HEIGHT 16 // 256 byte framebuffer //#define PAGE_HEIGHT 32 // 512 byte framebuffer -#include - -// If you want you can define your own set of delays in Configuration.h -//#define ST7920_DELAY_1 DELAY_NS(0) -//#define ST7920_DELAY_2 DELAY_NS(0) -//#define ST7920_DELAY_3 DELAY_NS(0) - -#if F_CPU >= 20000000 - #define CPU_ST7920_DELAY_1 DELAY_NS(0) - #define CPU_ST7920_DELAY_2 DELAY_NS(0) - #define CPU_ST7920_DELAY_3 DELAY_NS(50) -#elif MB(3DRAG, K8200, K8400) - #define CPU_ST7920_DELAY_1 DELAY_NS(0) - #define CPU_ST7920_DELAY_2 DELAY_NS(188) - #define CPU_ST7920_DELAY_3 DELAY_NS(0) -#elif MB(MINIRAMBO, EINSY_RAMBO, EINSY_RETRO, SILVER_GATE) - #define CPU_ST7920_DELAY_1 DELAY_NS(0) - #define CPU_ST7920_DELAY_2 DELAY_NS(250) - #define CPU_ST7920_DELAY_3 DELAY_NS(0) -#elif MB(RAMBO) - #define CPU_ST7920_DELAY_1 DELAY_NS(0) - #define CPU_ST7920_DELAY_2 DELAY_NS(0) - #define CPU_ST7920_DELAY_3 DELAY_NS(0) -#elif MB(BQ_ZUM_MEGA_3D) - #define CPU_ST7920_DELAY_1 DELAY_NS(0) - #define CPU_ST7920_DELAY_2 DELAY_NS(0) - #define CPU_ST7920_DELAY_3 DELAY_NS(189) -#elif defined(ARDUINO_ARCH_STM32) - #define CPU_ST7920_DELAY_1 DELAY_NS(300) - #define CPU_ST7920_DELAY_2 DELAY_NS(40) - #define CPU_ST7920_DELAY_3 DELAY_NS(340) -#elif F_CPU == 16000000 - #define CPU_ST7920_DELAY_1 DELAY_NS(0) - #define CPU_ST7920_DELAY_2 DELAY_NS(0) - #define CPU_ST7920_DELAY_3 DELAY_NS(63) -#else - #error "No valid condition for delays in 'ultralcd_st7920_u8glib_rrd_AVR.h'" -#endif +#include void ST7920_SWSPI_SND_8BIT(uint8_t val); @@ -82,8 +45,8 @@ void ST7920_SWSPI_SND_8BIT(uint8_t val); #define U8G_DELAY() DELAY_US(10) #endif -#define ST7920_CS() { WRITE(ST7920_CS_PIN,1); U8G_DELAY(); } -#define ST7920_NCS() { WRITE(ST7920_CS_PIN,0); } +#define ST7920_CS() { WRITE(ST7920_CS_PIN, HIGH); U8G_DELAY(); } +#define ST7920_NCS() { WRITE(ST7920_CS_PIN, LOW); } #define ST7920_SET_CMD() { ST7920_SWSPI_SND_8BIT(0xF8); U8G_DELAY(); } #define ST7920_SET_DAT() { ST7920_SWSPI_SND_8BIT(0xFA); U8G_DELAY(); } #define ST7920_WRITE_BYTE(a) { ST7920_SWSPI_SND_8BIT((uint8_t)((a)&0xF0u)); ST7920_SWSPI_SND_8BIT((uint8_t)((a)<<4U)); U8G_DELAY(); } diff --git a/Marlin/src/lcd/dwin/dwin_lcd.h b/Marlin/src/lcd/dwin/dwin_lcd.h deleted file mode 100644 index 9ae6d076d502..000000000000 --- a/Marlin/src/lcd/dwin/dwin_lcd.h +++ /dev/null @@ -1,213 +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 - -/******************************************************************************** - * @file dwin_lcd.h - * @author LEO / Creality3D - * @date 2019/07/18 - * @version 2.0.1 - * @brief 迪文屏控制操作函数 - ********************************************************************************/ - -#include - -#define RECEIVED_NO_DATA 0x00 -#define RECEIVED_SHAKE_HAND_ACK 0x01 - -#define FHONE 0xAA - -#define DWIN_SCROLL_UP 2 -#define DWIN_SCROLL_DOWN 3 - -#define DWIN_WIDTH 272 -#define DWIN_HEIGHT 480 - -/*-------------------------------------- System variable function --------------------------------------*/ - -// Handshake (1: Success, 0: Fail) -bool DWIN_Handshake(void); - -// Common DWIN startup -void DWIN_Startup(void); - -// Set the backlight luminance -// luminance: (0x00-0xFF) -void DWIN_Backlight_SetLuminance(const uint8_t luminance); - -// Set screen display direction -// dir: 0=0°, 1=90°, 2=180°, 3=270° -void DWIN_Frame_SetDir(uint8_t dir); - -// Update display -void DWIN_UpdateLCD(void); - -/*---------------------------------------- Drawing functions ----------------------------------------*/ - -// Clear screen -// color: Clear screen color -void DWIN_Frame_Clear(const uint16_t color); - -// Draw a point -// width: point width 0x01-0x0F -// height: point height 0x01-0x0F -// x,y: upper left point -void DWIN_Draw_Point(uint8_t width, uint8_t height, uint16_t x, uint16_t y); - -// Draw a line -// color: Line segment color -// xStart/yStart: Start point -// xEnd/yEnd: End point -void DWIN_Draw_Line(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); - -// Draw a Horizontal line -// color: Line segment color -// xStart/yStart: Start point -// xLength: Line Length -inline void DWIN_Draw_HLine(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xLength) { - DWIN_Draw_Line(color, xStart, yStart, xStart + xLength - 1, yStart); -} - -// Draw a Vertical line -// color: Line segment color -// xStart/yStart: Start point -// yLength: Line Length -inline void DWIN_Draw_VLine(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t yLength) { - DWIN_Draw_Line(color, xStart, yStart, xStart, yStart + yLength - 1); -} - -// Draw a rectangle -// mode: 0=frame, 1=fill, 2=XOR fill -// color: Rectangle color -// xStart/yStart: upper left point -// xEnd/yEnd: lower right point -void DWIN_Draw_Rectangle(uint8_t mode, uint16_t color, - uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); - -// Draw a box -// mode: 0=frame, 1=fill, 2=XOR fill -// color: Rectangle color -// xStart/yStart: upper left point -// xSize/ySize: box size -inline void DWIN_Draw_Box(uint8_t mode, uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xSize, uint16_t ySize) { - DWIN_Draw_Rectangle(mode, color, xStart, yStart, xStart + xSize - 1, yStart + ySize - 1); -} - -// Move a screen area -// mode: 0, circle shift; 1, translation -// dir: 0=left, 1=right, 2=up, 3=down -// dis: Distance -// color: Fill color -// xStart/yStart: upper left point -// xEnd/yEnd: bottom right point -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 -// widthAdjust: true=self-adjust character width; false=no adjustment -// bShow: true=display background color; false=don't display background color -// size: Font size -// color: Character color -// bColor: Background color -// x/y: Upper-left coordinate of the string -// *string: The string -void DWIN_Draw_String(bool widthAdjust, bool bShow, uint8_t size, - uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, char *string); - -class __FlashStringHelper; - -inline void DWIN_Draw_String(bool widthAdjust, bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const __FlashStringHelper *title) { - DWIN_Draw_String(widthAdjust, bShow, size, color, bColor, x, y, (char *)title); -} - -// Draw a positive integer -// bShow: true=display background color; false=don't display background color -// zeroFill: true=zero fill; false=no zero fill -// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space -// size: Font size -// color: Character color -// bColor: Background color -// iNum: Number of digits -// x/y: Upper-left coordinate -// value: Integer value -void DWIN_Draw_IntValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, - uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, uint16_t value); - -// Draw a floating point number -// bShow: true=display background color; false=don't display background color -// zeroFill: true=zero fill; false=no zero fill -// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space -// size: Font size -// color: Character color -// bColor: Background color -// iNum: Number of whole digits -// fNum: Number of decimal digits -// x/y: Upper-left point -// value: Float value -void DWIN_Draw_FloatValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, - uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value); - -/*---------------------------------------- Picture related functions ----------------------------------------*/ - -// Draw JPG and cached in #0 virtual display area -// id: Picture ID -void DWIN_JPG_ShowAndCache(const uint8_t id); - -// Draw an Icon -// libID: Icon library ID -// picID: Icon ID -// x/y: Upper-left point -void DWIN_ICON_Show(uint8_t libID, uint8_t picID, uint16_t x, uint16_t y); - -// Unzip the JPG picture to a virtual display area -// n: Cache index -// id: Picture ID -void DWIN_JPG_CacheToN(uint8_t n, uint8_t id); - -// Unzip the JPG picture to virtual display area #1 -// id: Picture ID -inline void DWIN_JPG_CacheTo1(uint8_t id) { DWIN_JPG_CacheToN(1, id); } - -// Copy area from virtual display area to current screen -// cacheID: virtual area number -// xStart/yStart: Upper-left of virtual area -// xEnd/yEnd: Lower-right of virtual area -// x/y: Screen paste point -void DWIN_Frame_AreaCopy(uint8_t cacheID, uint16_t xStart, uint16_t yStart, - uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y); - -// Animate a series of icons -// animID: Animation ID up to 16 -// animate: animation on or off -// libID: Icon library ID -// picIDs: Icon starting ID -// picIDe: Icon ending ID -// x/y: Upper-left point -// interval: Display time interval, unit 10mS -void DWIN_ICON_Animation(uint8_t animID, bool animate, uint8_t libID, uint8_t picIDs, - uint8_t picIDe, uint16_t x, uint16_t y, uint16_t interval); - -// Animation Control -// state: 16 bits, each bit is the state of an animation id -void DWIN_ICON_AnimationControl(uint16_t state); diff --git a/Marlin/src/lcd/dwin/e3v2/dwin.cpp b/Marlin/src/lcd/dwin/e3v2/dwin.cpp deleted file mode 100644 index 28087497371f..000000000000 --- a/Marlin/src/lcd/dwin/e3v2/dwin.cpp +++ /dev/null @@ -1,3702 +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 . - * - */ - -/** - * DWIN by Creality3D - */ - -#include "../../../inc/MarlinConfigPre.h" - -#if ENABLED(DWIN_CREALITY_LCD) - -#include "dwin.h" - -#if ANY(AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT) && DISABLED(PROBE_MANUALLY) - #define HAS_ONESTEP_LEVELING 1 -#endif - -#if ANY(BABYSTEPPING, HAS_BED_PROBE, HAS_WORKSPACE_OFFSET) - #define HAS_ZOFFSET_ITEM 1 -#endif - -#if !HAS_BED_PROBE && ENABLED(BABYSTEPPING) - #define JUST_BABYSTEP 1 -#endif - -#include -#include -#include - -#include "../../fontutils.h" -#include "../../ultralcd.h" - -#include "../../../sd/cardreader.h" - -#include "../../../MarlinCore.h" -#include "../../../core/serial.h" -#include "../../../core/macros.h" -#include "../../../gcode/queue.h" - -#include "../../../module/temperature.h" -#include "../../../module/printcounter.h" -#include "../../../module/motion.h" -#include "../../../module/planner.h" - -#if ENABLED(EEPROM_SETTINGS) - #include "../../../module/settings.h" -#endif - -#if ENABLED(HOST_ACTION_COMMANDS) - #include "../../../feature/host_actions.h" -#endif - -#if HAS_ONESTEP_LEVELING - #include "../../../feature/bedlevel/bedlevel.h" -#endif - -#if HAS_BED_PROBE - #include "../../../module/probe.h" -#endif - -#if EITHER(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) - #include "../../../feature/babystep.h" -#endif - -#if ENABLED(POWER_LOSS_RECOVERY) - #include "../../../feature/powerloss.h" -#endif - -#ifndef MACHINE_SIZE - #define MACHINE_SIZE "220x220x250" -#endif -#ifndef CORP_WEBSITE_C - #define CORP_WEBSITE_C "www.cxsw3d.com" -#endif -#ifndef CORP_WEBSITE_E - #define CORP_WEBSITE_E "www.creality.com" -#endif - -#define PAUSE_HEAT - -#define USE_STRING_HEADINGS - -#define DWIN_FONT_MENU font8x16 -#define DWIN_FONT_STAT font10x20 -#define DWIN_FONT_HEAD font10x20 - -#define MENU_CHAR_LIMIT 24 -#define STATUS_Y 360 - -// Fan speed limit -#define FANON 255 -#define FANOFF 0 - -// Print speed limit -#define MAX_PRINT_SPEED 999 -#define MIN_PRINT_SPEED 10 - -// Temp limits -#if HAS_HOTEND - #define MAX_E_TEMP (HEATER_0_MAXTEMP - (HOTEND_OVERSHOOT)) - #define MIN_E_TEMP HEATER_0_MINTEMP -#endif - -#if HAS_HEATED_BED - #define MIN_BED_TEMP BED_MINTEMP -#endif - -// Feedspeed limit (max feedspeed = DEFAULT_MAX_FEEDRATE * 2) -#define MIN_MAXFEEDSPEED 1 -#define MIN_MAXACCELERATION 1 -#define MIN_MAXJERK 0.1 -#define MIN_STEP 1 - -#define FEEDRATE_E (60) - -// Mininum unit (0.1) : multiple (10) -#define MINUNITMULT 10 - -#define ENCODER_WAIT 20 -#define DWIN_SCROLL_UPDATE_INTERVAL 2000 -#define DWIN_REMAIN_TIME_UPDATE_INTERVAL 20000 - -constexpr uint16_t TROWS = 6, MROWS = TROWS - 1, // Total rows, and other-than-Back - TITLE_HEIGHT = 30, // Title bar height - MLINE = 53, // Menu line height - LBLX = 60, // Menu item label X - MENU_CHR_W = 8, STAT_CHR_W = 10; - -#define MBASE(L) (49 + MLINE * (L)) - -#define BABY_Z_VAR TERN(HAS_BED_PROBE, probe.offset.z, dwin_zoffset) - -/* Value Init */ -HMI_value_t HMI_ValueStruct; -HMI_Flag_t HMI_flag{0}; - -millis_t dwin_heat_time = 0; - -uint8_t checkkey = 0; - -typedef struct { - uint8_t now, last; - void set(uint8_t v) { now = last = v; } - void reset() { set(0); } - bool changed() { bool c = (now != last); if (c) last = now; return c; } - bool dec() { if (now) now--; return changed(); } - bool inc(uint8_t v) { if (now < (v - 1)) now++; else now = (v - 1); return changed(); } -} select_t; - -select_t select_page{0}, select_file{0}, select_print{0}, select_prepare{0} - , select_control{0}, select_axis{0}, select_temp{0}, select_motion{0}, select_tune{0} - , select_PLA{0}, select_ABS{0} - , select_speed{0} - , select_acc{0} - , select_jerk{0} - , select_step{0} - ; - -uint8_t index_file = MROWS, - index_prepare = MROWS, - index_control = MROWS, - index_leveling = MROWS, - index_tune = MROWS; - -bool dwin_abort_flag = false; // Flag to reset feedrate, return to Home - -constexpr float default_max_feedrate[] = DEFAULT_MAX_FEEDRATE; -constexpr float default_max_acceleration[] = DEFAULT_MAX_ACCELERATION; -constexpr float default_max_jerk[] = { DEFAULT_XJERK, DEFAULT_YJERK, DEFAULT_ZJERK, DEFAULT_EJERK }; -constexpr float default_axis_steps_per_unit[] = DEFAULT_AXIS_STEPS_PER_UNIT; - -uint8_t Percentrecord = 0; -uint16_t remain_time = 0; - -#if ENABLED(PAUSE_HEAT) - #if HAS_HOTEND - uint16_t temphot = 0; - #endif - #if HAS_HEATED_BED - uint16_t tempbed = 0; - #endif -#endif - -#if HAS_ZOFFSET_ITEM - float dwin_zoffset = 0, last_zoffset = 0; -#endif - -#define DWIN_LANGUAGE_EEPROM_ADDRESS 0x01 // Between 0x01 and 0x63 (EEPROM_OFFSET-1) - // BL24CXX::check() uses 0x00 - -inline bool HMI_IsChinese() { return HMI_flag.language == DWIN_CHINESE; } - -void HMI_SetLanguageCache() { - DWIN_JPG_CacheTo1(HMI_IsChinese() ? Language_Chinese : Language_English); -} - -void HMI_SetLanguage() { - #if ENABLED(EEPROM_SETTINGS) - BL24CXX::read(DWIN_LANGUAGE_EEPROM_ADDRESS, (uint8_t*)&HMI_flag.language, sizeof(HMI_flag.language)); - #endif - HMI_SetLanguageCache(); -} - -void HMI_ToggleLanguage() { - HMI_flag.language = HMI_IsChinese() ? DWIN_ENGLISH : DWIN_CHINESE; - HMI_SetLanguageCache(); - #if ENABLED(EEPROM_SETTINGS) - BL24CXX::write(DWIN_LANGUAGE_EEPROM_ADDRESS, (uint8_t*)&HMI_flag.language, sizeof(HMI_flag.language)); - #endif -} - -void DWIN_Draw_Signed_Float(uint8_t size, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { - if (value < 0) { - DWIN_Draw_String(false, true, size, Color_White, bColor, x - 6, y, F("-")); - DWIN_Draw_FloatValue(true, true, 0, size, Color_White, bColor, iNum, fNum, x, y, -value); - } - else { - DWIN_Draw_String(false, true, size, Color_White, bColor, x - 6, y, F(" ")); - DWIN_Draw_FloatValue(true, true, 0, size, Color_White, bColor, iNum, fNum, x, y, value); - } -} - -void ICON_Print() { - if (select_page.now == 0) { - DWIN_ICON_Show(ICON, ICON_Print_1, 17, 130); - DWIN_Draw_Rectangle(0, Color_White, 17, 130, 126, 229); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 1, 447, 28, 460, 58, 201); - else - DWIN_Frame_AreaCopy(1, 1, 451, 31, 463, 57, 201); - } - else { - DWIN_ICON_Show(ICON, ICON_Print_0, 17, 130); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 1, 405, 28, 420, 58, 201); - else - DWIN_Frame_AreaCopy(1, 1, 423, 31, 435, 57, 201); - } -} - -void ICON_Prepare() { - if (select_page.now == 1) { - DWIN_ICON_Show(ICON, ICON_Prepare_1, 145, 130); - DWIN_Draw_Rectangle(0, Color_White, 145, 130, 254, 229); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 31, 447, 58, 460, 186, 201); - else - DWIN_Frame_AreaCopy(1, 33, 451, 82, 466, 175, 201); - } - else { - DWIN_ICON_Show(ICON, ICON_Prepare_0, 145, 130); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 31, 405, 58, 420, 186, 201); - else - DWIN_Frame_AreaCopy(1, 33, 423, 82, 438, 175, 201); - } -} - -void ICON_Control() { - if (select_page.now == 2) { - DWIN_ICON_Show(ICON, ICON_Control_1, 17, 246); - DWIN_Draw_Rectangle(0, Color_White, 17, 246, 126, 345); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 61, 447, 88, 460, 58, 318); - else - DWIN_Frame_AreaCopy(1, 85, 451, 132, 463, 48, 318); - } - else { - DWIN_ICON_Show(ICON, ICON_Control_0, 17, 246); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 61, 405, 88, 420, 58, 318); - else - DWIN_Frame_AreaCopy(1, 85, 423, 132, 434, 48, 318); - } -} - -void ICON_StartInfo(bool show) { - if (show) { - DWIN_ICON_Show(ICON, ICON_Info_1, 145, 246); - DWIN_Draw_Rectangle(0, Color_White, 145, 246, 254, 345); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 91, 447, 118, 460, 186, 318); - else - DWIN_Frame_AreaCopy(1, 132, 451, 159, 466, 186, 318); - } - else { - DWIN_ICON_Show(ICON, ICON_Info_0, 145, 246); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 91, 405, 118, 420, 186, 318); - else - DWIN_Frame_AreaCopy(1, 132, 423, 159, 435, 186, 318); - } -} - -void ICON_Leveling(bool show) { - if (show) { - DWIN_ICON_Show(ICON, ICON_Leveling_1, 145, 246); - DWIN_Draw_Rectangle(0, Color_White, 145, 246, 254, 345); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 211, 447, 238, 460, 186, 318); - else - DWIN_Frame_AreaCopy(1, 84, 437, 120, 449, 182, 318); - } - else { - DWIN_ICON_Show(ICON, ICON_Leveling_0, 145, 246); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 211, 405, 238, 420, 186, 318); - else - DWIN_Frame_AreaCopy(1, 84, 465, 120, 478, 182, 318); - } -} - -void ICON_Tune() { - if (select_print.now == 0) { - DWIN_ICON_Show(ICON, ICON_Setup_1, 8, 252); - DWIN_Draw_Rectangle(0, Color_White, 8, 252, 87, 351); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 121, 447, 148, 458, 34, 325); - else - DWIN_Frame_AreaCopy(1, 0, 466, 34, 476, 31, 325); - } - else { - DWIN_ICON_Show(ICON, ICON_Setup_0, 8, 252); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 121, 405, 148, 420, 34, 325); - else - DWIN_Frame_AreaCopy(1, 0, 438, 32, 448, 31, 325); - } -} - -void ICON_Pause() { - if (select_print.now == 1) { - DWIN_ICON_Show(ICON, ICON_Pause_1, 96, 252); - DWIN_Draw_Rectangle(0, Color_White, 96, 252, 175, 351); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 181, 447, 208, 459, 124, 325); - else - DWIN_Frame_AreaCopy(1, 177, 451, 216, 462, 116, 325); - } - else { - DWIN_ICON_Show(ICON, ICON_Pause_0, 96, 252); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 181, 405, 208, 420, 124, 325); - else - DWIN_Frame_AreaCopy(1, 177, 423, 215, 433, 116, 325); - } -} - -void ICON_Continue() { - if (select_print.now == 1) { - DWIN_ICON_Show(ICON, ICON_Continue_1, 96, 252); - DWIN_Draw_Rectangle(0, Color_White, 96, 252, 175, 351); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 1, 447, 28, 460, 124, 325); - else - DWIN_Frame_AreaCopy(1, 1, 452, 32, 464, 121, 325); - } - else { - DWIN_ICON_Show(ICON, ICON_Continue_0, 96, 252); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 1, 405, 28, 420, 124, 325); - else - DWIN_Frame_AreaCopy(1, 1, 424, 31, 434, 121, 325); - } -} - -void ICON_Stop() { - if (select_print.now == 2) { - DWIN_ICON_Show(ICON, ICON_Stop_1, 184, 252); - DWIN_Draw_Rectangle(0, Color_White, 184, 252, 263, 351); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 151, 447, 178, 459, 210, 325); - else - DWIN_Frame_AreaCopy(1, 218, 452, 249, 466, 209, 325); - } - else { - DWIN_ICON_Show(ICON, ICON_Stop_0, 184, 252); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 151, 405, 178, 420, 210, 325); - else - DWIN_Frame_AreaCopy(1, 218, 423, 247, 436, 209, 325); - } -} - -inline void Clear_Title_Bar() { - DWIN_Draw_Rectangle(1, Color_Bg_Blue, 0, 0, DWIN_WIDTH, 30); -} - -inline void Draw_Title(const char * const title) { - DWIN_Draw_String(false, false, DWIN_FONT_HEAD, Color_White, Color_Bg_Blue, 14, 4, (char*)title); -} - -inline void Draw_Title(const __FlashStringHelper * title) { - DWIN_Draw_String(false, false, DWIN_FONT_HEAD, Color_White, Color_Bg_Blue, 14, 4, (char*)title); -} - -inline void Clear_Menu_Area() { - DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, 31, DWIN_WIDTH, STATUS_Y); -} - -inline void Clear_Main_Window() { - Clear_Title_Bar(); - Clear_Menu_Area(); -} - -inline void Clear_Popup_Area() { - Clear_Title_Bar(); - DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, 31, DWIN_WIDTH, DWIN_HEIGHT); -} - -void Draw_Popup_Bkgd_105() { - DWIN_Draw_Rectangle(1, Color_Bg_Window, 14, 105, 258, 374); -} - -inline void Draw_More_Icon(const uint8_t line) { - DWIN_ICON_Show(ICON, ICON_More, 226, MBASE(line) - 3); -} - -inline void Draw_Menu_Cursor(const uint8_t line) { - // DWIN_ICON_Show(ICON,ICON_Rectangle, 0, MBASE(line) - 18); - DWIN_Draw_Rectangle(1, Rectangle_Color, 0, MBASE(line) - 18, 14, MBASE(line + 1) - 20); -} - -inline void Erase_Menu_Cursor(const uint8_t line) { - DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, MBASE(line) - 18, 14, MBASE(line + 1) - 20); -} - -inline void Move_Highlight(const int16_t from, const uint16_t newline) { - Erase_Menu_Cursor(newline - from); - Draw_Menu_Cursor(newline); -} - -inline void Add_Menu_Line() { - Move_Highlight(1, MROWS); - DWIN_Draw_Line(Line_Color, 16, MBASE(MROWS + 1) - 20, 256, MBASE(MROWS + 1) - 19); -} - -inline void Scroll_Menu(const uint8_t dir) { - DWIN_Frame_AreaMove(1, dir, MLINE, Color_Bg_Black, 0, 31, DWIN_WIDTH, 349); - switch (dir) { - case DWIN_SCROLL_DOWN: Move_Highlight(-1, 0); break; - case DWIN_SCROLL_UP: Add_Menu_Line(); break; - } -} - -inline uint16_t nr_sd_menu_items() { - return card.get_num_Files() + !card.flag.workDirIsRoot; -} - -inline void Draw_Menu_Icon(const uint8_t line, const uint8_t icon) { - DWIN_ICON_Show(ICON, icon, 26, MBASE(line) - 3); -} - -inline void Erase_Menu_Text(const uint8_t line) { - DWIN_Draw_Rectangle(1, Color_Bg_Black, LBLX, MBASE(line) - 14, 271, MBASE(line) + 28); -} - -inline void Draw_Menu_Line(const uint8_t line, const uint8_t icon=0, const char * const label=nullptr) { - if (label) DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(line) - 1, (char*)label); - if (icon) Draw_Menu_Icon(line, icon); - DWIN_Draw_Line(Line_Color, 16, MBASE(line) + 33, 256, MBASE(line) + 34); -} - -// The "Back" label is always on the first line -inline void Draw_Back_Label() { - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 129, 72, 156, 84, LBLX, MBASE(0)); - else - DWIN_Frame_AreaCopy(1, 226, 179, 256, 189, LBLX, MBASE(0)); -} - -// Draw "Back" line at the top -inline void Draw_Back_First(const bool is_sel=true) { - Draw_Menu_Line(0, ICON_Back); - Draw_Back_Label(); - if (is_sel) Draw_Menu_Cursor(0); -} - -inline bool Apply_Encoder(const ENCODER_DiffState &encoder_diffState, auto &valref) { - if (encoder_diffState == ENCODER_DIFF_CW) - valref += EncoderRate.encoderMoveValue; - else if (encoder_diffState == ENCODER_DIFF_CCW) - valref -= EncoderRate.encoderMoveValue; - else if (encoder_diffState == ENCODER_DIFF_ENTER) - return true; - return false; -} - -// -// Draw Menus -// - -#define MOTION_CASE_RATE 1 -#define MOTION_CASE_ACCEL 2 -#define MOTION_CASE_JERK (MOTION_CASE_ACCEL + ENABLED(HAS_CLASSIC_JERK)) -#define MOTION_CASE_STEPS (MOTION_CASE_JERK + 1) -#define MOTION_CASE_TOTAL MOTION_CASE_STEPS - -#define PREPARE_CASE_MOVE 1 -#define PREPARE_CASE_DISA 2 -#define PREPARE_CASE_HOME 3 -#define PREPARE_CASE_ZOFF (PREPARE_CASE_HOME + ENABLED(HAS_ZOFFSET_ITEM)) -#define PREPARE_CASE_PLA (PREPARE_CASE_ZOFF + ENABLED(HAS_HOTEND)) -#define PREPARE_CASE_ABS (PREPARE_CASE_PLA + ENABLED(HAS_HOTEND)) -#define PREPARE_CASE_COOL (PREPARE_CASE_ABS + EITHER(HAS_HOTEND, HAS_HEATED_BED)) -#define PREPARE_CASE_LANG (PREPARE_CASE_COOL + 1) -#define PREPARE_CASE_TOTAL PREPARE_CASE_LANG - -#define CONTROL_CASE_TEMP 1 -#define CONTROL_CASE_MOVE (CONTROL_CASE_TEMP + 1) -#define CONTROL_CASE_SAVE (CONTROL_CASE_MOVE + ENABLED(EEPROM_SETTINGS)) -#define CONTROL_CASE_LOAD (CONTROL_CASE_SAVE + ENABLED(EEPROM_SETTINGS)) -#define CONTROL_CASE_RESET (CONTROL_CASE_LOAD + ENABLED(EEPROM_SETTINGS)) -#define CONTROL_CASE_INFO (CONTROL_CASE_RESET + 1) -#define CONTROL_CASE_TOTAL CONTROL_CASE_INFO - -#define TUNE_CASE_SPEED 1 -#define TUNE_CASE_TEMP (TUNE_CASE_SPEED + ENABLED(HAS_HOTEND)) -#define TUNE_CASE_BED (TUNE_CASE_TEMP + ENABLED(HAS_HEATED_BED)) -#define TUNE_CASE_FAN (TUNE_CASE_BED + ENABLED(HAS_FAN)) -#define TUNE_CASE_ZOFF (TUNE_CASE_FAN + ENABLED(HAS_ZOFFSET_ITEM)) -#define TUNE_CASE_TOTAL TUNE_CASE_ZOFF - -#define TEMP_CASE_TEMP (0 + ENABLED(HAS_HOTEND)) -#define TEMP_CASE_BED (TEMP_CASE_TEMP + ENABLED(HAS_HEATED_BED)) -#define TEMP_CASE_FAN (TEMP_CASE_BED + ENABLED(HAS_FAN)) -#define TEMP_CASE_PLA (TEMP_CASE_FAN + ENABLED(HAS_HOTEND)) -#define TEMP_CASE_ABS (TEMP_CASE_PLA + ENABLED(HAS_HOTEND)) -#define TEMP_CASE_TOTAL TEMP_CASE_ABS - -#define PREHEAT_CASE_TEMP (0 + ENABLED(HAS_HOTEND)) -#define PREHEAT_CASE_BED (PREHEAT_CASE_TEMP + ENABLED(HAS_HEATED_BED)) -#define PREHEAT_CASE_FAN (PREHEAT_CASE_BED + ENABLED(HAS_FAN)) -#define PREHEAT_CASE_SAVE (PREHEAT_CASE_FAN + ENABLED(EEPROM_SETTINGS)) -#define PREHEAT_CASE_TOTAL PREHEAT_CASE_SAVE - -// -// Draw Menus -// - -inline void draw_move_en(const uint16_t line) { - DWIN_Frame_AreaCopy(1, 69, 61, 102, 71, LBLX, line); // "Move" -} - -inline void DWIN_Frame_TitleCopy(uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2) { DWIN_Frame_AreaCopy(id, x1, y1, x2, y2, 14, 8); } - -inline void Item_Prepare_Move(const uint8_t row) { - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 159, 70, 200, 84, LBLX, MBASE(row)); - else - draw_move_en(MBASE(row)); // "Move >" - Draw_Menu_Line(row, ICON_Axis); - Draw_More_Icon(row); -} - -inline void Item_Prepare_Disable(const uint8_t row) { - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 204, 70, 259, 82, LBLX, MBASE(row)); - else - DWIN_Frame_AreaCopy(1, 103, 59, 200, 74, LBLX, MBASE(row)); // "Disable Stepper" - Draw_Menu_Line(row, ICON_CloseMotor); -} - -inline void Item_Prepare_Home(const uint8_t row) { - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 0, 89, 41, 101, LBLX, MBASE(row)); - else - DWIN_Frame_AreaCopy(1, 202, 61, 271, 71, LBLX, MBASE(row)); // "Auto Home" - Draw_Menu_Line(row, ICON_Homing); -} - -#if HAS_ZOFFSET_ITEM - - inline void Item_Prepare_Offset(const uint8_t row) { - if (HMI_IsChinese()) { - #if HAS_BED_PROBE - DWIN_Frame_AreaCopy(1, 174, 164, 223, 177, LBLX, MBASE(row)); - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 2, 2, 202, MBASE(row), BABY_Z_VAR * 100); - #else - DWIN_Frame_AreaCopy(1, 43, 89, 98, 101, LBLX, MBASE(row)); - #endif - } - else { - #if HAS_BED_PROBE - DWIN_Frame_AreaCopy(1, 93, 179, 141, 189, LBLX, MBASE(row)); // "Z-Offset" - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 2, 2, 202, MBASE(row), BABY_Z_VAR * 100); - #else - DWIN_Frame_AreaCopy(1, 1, 76, 106, 86, LBLX, MBASE(row)); // "..." - #endif - } - Draw_Menu_Line(row, ICON_SetHome); - } - -#endif - -#if HAS_HOTEND - inline void Item_Prepare_PLA(const uint8_t row) { - if (HMI_IsChinese()) { - DWIN_Frame_AreaCopy(1, 100, 89, 151, 101, LBLX, MBASE(row)); - } - else { - DWIN_Frame_AreaCopy(1, 107, 76, 156, 86, LBLX, MBASE(row)); // "Preheat" - DWIN_Frame_AreaCopy(1, 157, 76, 181, 86, LBLX + 52, MBASE(row)); // "PLA" - } - Draw_Menu_Line(row, ICON_PLAPreheat); - } - - inline void Item_Prepare_ABS(const uint8_t row) { - if (HMI_IsChinese()) { - DWIN_Frame_AreaCopy(1, 180, 89, 233, 100, LBLX, MBASE(row)); - } - else { - DWIN_Frame_AreaCopy(1, 107, 76, 156, 86, LBLX, MBASE(row)); // "Preheat" - DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX + 52, MBASE(row)); // "ABS" - } - Draw_Menu_Line(row, ICON_ABSPreheat); - } -#endif - -#if HAS_PREHEAT - inline void Item_Prepare_Cool(const uint8_t row) { - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 1, 104, 56, 117, LBLX, MBASE(row)); - else - DWIN_Frame_AreaCopy(1, 200, 76, 264, 86, LBLX, MBASE(row)); // "Cooldown" - Draw_Menu_Line(row, ICON_Cool); - } -#endif - -inline void Item_Prepare_Lang(const uint8_t row) { - if (HMI_IsChinese()) { - DWIN_Frame_AreaCopy(1, 239, 134, 266, 146, LBLX, MBASE(row)); - DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, 226, MBASE(row), F("CN")); - } - else { - DWIN_Frame_AreaCopy(1, 0, 194, 121, 207, LBLX, MBASE(row)); // "Language selection" - DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, 226, MBASE(row), F("EN")); - } - Draw_Menu_Icon(row, ICON_Language); -} - -inline void Draw_Prepare_Menu() { - Clear_Main_Window(); - - const int16_t scroll = MROWS - index_prepare; // Scrolled-up lines - #define PSCROL(L) (scroll + (L)) - #define PVISI(L) WITHIN(PSCROL(L), 0, MROWS) - - if (HMI_IsChinese()) { - DWIN_Frame_TitleCopy(1, 133, 1, 160, 13); // "Prepare" - } - else { - #ifdef USE_STRING_HEADINGS - Draw_Title(GET_TEXT_F(MSG_PREPARE)); - #else - DWIN_Frame_TitleCopy(1, 178, 2, 229, 14); // "Prepare" - #endif - } - - if (PVISI(0)) Draw_Back_First(select_prepare.now == 0); // < Back - if (PVISI(PREPARE_CASE_MOVE)) Item_Prepare_Move(PSCROL(PREPARE_CASE_MOVE)); // Move > - if (PVISI(PREPARE_CASE_DISA)) Item_Prepare_Disable(PSCROL(PREPARE_CASE_DISA)); // Disable Stepper - if (PVISI(PREPARE_CASE_HOME)) Item_Prepare_Home(PSCROL(PREPARE_CASE_HOME)); // Auto Home - #if HAS_ZOFFSET_ITEM - if (PVISI(PREPARE_CASE_ZOFF)) Item_Prepare_Offset(PSCROL(PREPARE_CASE_ZOFF)); // Edit Z-Offset / Babystep / Set Home Offset - #endif - #if HAS_HOTEND - if (PVISI(PREPARE_CASE_PLA)) Item_Prepare_PLA(PSCROL(PREPARE_CASE_PLA)); // Preheat PLA - if (PVISI(PREPARE_CASE_ABS)) Item_Prepare_ABS(PSCROL(PREPARE_CASE_ABS)); // Preheat ABS - #endif - #if HAS_PREHEAT - if (PVISI(PREPARE_CASE_COOL)) Item_Prepare_Cool(PSCROL(PREPARE_CASE_COOL)); // Cooldown - #endif - if (PVISI(PREPARE_CASE_LANG)) Item_Prepare_Lang(PSCROL(PREPARE_CASE_LANG)); // Language CN/EN - - if (select_prepare.now) Draw_Menu_Cursor(PSCROL(select_prepare.now)); -} - -inline void Draw_Control_Menu() { - Clear_Main_Window(); - - #if CONTROL_CASE_TOTAL >= 6 - const int16_t scroll = MROWS - index_control; // Scrolled-up lines - #define CSCROL(L) (scroll + (L)) - #else - #define CSCROL(L) (L) - #endif - #define CLINE(L) MBASE(CSCROL(L)) - #define CVISI(L) WITHIN(CSCROL(L), 0, MROWS) - - if (CVISI(0)) Draw_Back_First(select_control.now == 0); // < Back - - if (HMI_IsChinese()) { - DWIN_Frame_TitleCopy(1, 103, 1, 130, 14); // "Control" - - DWIN_Frame_AreaCopy(1, 57, 104, 84, 116, LBLX, CLINE(CONTROL_CASE_TEMP)); // Temperature > - DWIN_Frame_AreaCopy(1, 87, 104, 114, 116, LBLX, CLINE(CONTROL_CASE_MOVE)); // Motion > - - #if ENABLED(EEPROM_SETTINGS) - DWIN_Frame_AreaCopy(1, 117, 104, 172, 116, LBLX, CLINE(CONTROL_CASE_SAVE)); // Store Configuration - DWIN_Frame_AreaCopy(1, 174, 103, 229, 116, LBLX, CLINE(CONTROL_CASE_LOAD)); // Read Configuration - DWIN_Frame_AreaCopy(1, 1, 118, 56, 131, LBLX, CLINE(CONTROL_CASE_RESET)); // Reset Configuration - #endif - - if (CVISI(CONTROL_CASE_INFO)) - DWIN_Frame_AreaCopy(1, 231, 104, 258, 116, LBLX, CLINE(CONTROL_CASE_TEMP)); // Info > - } - else { - #ifdef USE_STRING_HEADINGS - Draw_Title(GET_TEXT_F(MSG_CONTROL)); - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(CONTROL_CASE_TEMP), GET_TEXT_F(MSG_TEMPERATURE)); - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(CONTROL_CASE_MOVE), GET_TEXT_F(MSG_MOTION)); - #if ENABLED(EEPROM_SETTINGS) - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(CONTROL_CASE_SAVE), GET_TEXT_F(MSG_STORE_EEPROM)); - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(CONTROL_CASE_LOAD), GET_TEXT_F(MSG_LOAD_EEPROM)); - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(CONTROL_CASE_RESET), GET_TEXT_F(MSG_RESTORE_DEFAULTS)); - #endif - if (CVISI(CONTROL_CASE_INFO)) DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(CONTROL_CASE_INFO), F("Info")); - #else - DWIN_Frame_TitleCopy(1, 128, 2, 176, 12); // "Control" - DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX, CLINE(CONTROL_CASE_TEMP)); // Temperature > - DWIN_Frame_AreaCopy(1, 84, 89, 128, 99, LBLX, CLINE(CONTROL_CASE_MOVE)); // Motion > - #if ENABLED(EEPROM_SETTINGS) - DWIN_Frame_AreaCopy(1, 148, 89, 268, 101, LBLX , CLINE(CONTROL_CASE_SAVE // "Store Configuration" - DWIN_Frame_AreaCopy(1, 26, 104, 57, 114, LBLX , CLINE(CONTROL_CASE_LOAD)); // "Read" - DWIN_Frame_AreaCopy(1, 182, 89, 268, 101, LBLX + 34, CLINE(CONTROL_CASE_LOAD)); // "Configuration" - DWIN_Frame_AreaCopy(1, 59, 104, 93, 114, LBLX , CLINE(CONTROL_CASE_RESET)); // "Reset" - DWIN_Frame_AreaCopy(1, 182, 89, 268, 101, LBLX + 37, CLINE(CONTROL_CASE_RESET)); // "Configuration" - #endif - if (CVISI(CONTROL_CASE_INFO)) DWIN_Frame_AreaCopy(1, 0, 104, 25, 115, LBLX, CLINE(CONTROL_CASE_INFO)); // Info > - #endif - } - - if (select_control.now && CVISI(select_control.now)) - Draw_Menu_Cursor(CSCROL(select_control.now)); - - // Draw icons and lines - uint8_t i = 0; - #define _TEMP_ICON(N) do{ ++i; if (CVISI(i)) Draw_Menu_Line(CSCROL(i), ICON_Temperature + (N) - 1); }while(0) - - _TEMP_ICON(CONTROL_CASE_TEMP); - if (CVISI(i)) Draw_More_Icon(CSCROL(i)); - - _TEMP_ICON(CONTROL_CASE_MOVE); - Draw_More_Icon(CSCROL(i)); - - #if ENABLED(EEPROM_SETTINGS) - _TEMP_ICON(CONTROL_CASE_SAVE); - _TEMP_ICON(CONTROL_CASE_LOAD); - _TEMP_ICON(CONTROL_CASE_RESET); - #endif - - _TEMP_ICON(CONTROL_CASE_INFO); - if (CVISI(CONTROL_CASE_INFO)) Draw_More_Icon(CSCROL(i)); -} - -inline void Draw_Tune_Menu() { - Clear_Main_Window(); - - if (HMI_IsChinese()) { - DWIN_Frame_AreaCopy(1, 73, 2, 100, 13, 14, 9); - DWIN_Frame_AreaCopy(1, 116, 164, 171, 176, LBLX, MBASE(TUNE_CASE_SPEED)); - #if HAS_HOTEND - DWIN_Frame_AreaCopy(1, 1, 134, 56, 146, LBLX, MBASE(TUNE_CASE_TEMP)); - #endif - #if HAS_HEATED_BED - DWIN_Frame_AreaCopy(1, 58, 134, 113, 146, LBLX, MBASE(TUNE_CASE_BED)); - #endif - #if HAS_FAN - DWIN_Frame_AreaCopy(1, 115, 134, 170, 146, LBLX, MBASE(TUNE_CASE_FAN)); - #endif - #if HAS_ZOFFSET_ITEM - DWIN_Frame_AreaCopy(1, 174, 164, 223, 177, LBLX, MBASE(TUNE_CASE_ZOFF)); - #endif - } - else { - #ifdef USE_STRING_HEADINGS - Draw_Title(GET_TEXT_F(MSG_TUNE)); - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(TUNE_CASE_SPEED), GET_TEXT_F(MSG_SPEED)); - #if HAS_HOTEND - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(TUNE_CASE_TEMP), GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND)); - #endif - #if HAS_HEATED_BED - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(TUNE_CASE_BED), GET_TEXT_F(MSG_UBL_SET_TEMP_BED)); - #endif - #if HAS_FAN - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(TUNE_CASE_FAN), GET_TEXT_F(MSG_FAN_SPEED)); - #endif - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(TUNE_CASE_ZOFF), GET_TEXT_F(MSG_ZPROBE_ZOFFSET)); - #else - DWIN_Frame_AreaCopy(1, 94, 2, 126, 12, 14, 9); - DWIN_Frame_AreaCopy(1, 1, 179, 92, 190, LBLX, MBASE(TUNE_CASE_SPEED)); // Print speed - #if HAS_HOTEND - DWIN_Frame_AreaCopy(1, 197, 104, 238, 114, LBLX, MBASE(TUNE_CASE_TEMP)); // Hotend... - DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 44, MBASE(TUNE_CASE_TEMP)); // ...Temperature - #endif - #if HAS_HEATED_BED - DWIN_Frame_AreaCopy(1, 240, 104, 264, 114, LBLX, MBASE(TUNE_CASE_BED)); // Bed... - DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 27, MBASE(TUNE_CASE_BED)); // ...Temperature - #endif - #if HAS_FAN - DWIN_Frame_AreaCopy(1, 0, 119, 64, 132, LBLX, MBASE(TUNE_CASE_FAN)); // Fan speed - #endif - #if HAS_ZOFFSET_ITEM - DWIN_Frame_AreaCopy(1, 93, 179, 141, 189, LBLX, MBASE(TUNE_CASE_ZOFF)); // Z-offset - #endif - #endif - } - - Draw_Back_First(select_tune.now == 0); - if (select_tune.now) Draw_Menu_Cursor(select_tune.now); - - Draw_Menu_Line(TUNE_CASE_SPEED, ICON_Speed); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TUNE_CASE_SPEED), feedrate_percentage); - - #if HAS_HOTEND - Draw_Menu_Line(TUNE_CASE_TEMP, ICON_HotendTemp); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TUNE_CASE_TEMP), thermalManager.temp_hotend[0].target); - #endif - #if HAS_HEATED_BED - Draw_Menu_Line(TUNE_CASE_BED, ICON_BedTemp); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TUNE_CASE_BED), thermalManager.temp_bed.target); - #endif - #if HAS_FAN - Draw_Menu_Line(TUNE_CASE_FAN, ICON_FanSpeed); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TUNE_CASE_FAN), thermalManager.fan_speed[0]); - #endif - #if HAS_ZOFFSET_ITEM - Draw_Menu_Line(TUNE_CASE_ZOFF, ICON_Zoffset); - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 2, 2, 202, MBASE(TUNE_CASE_ZOFF), BABY_Z_VAR * 100); - #endif -} - -inline void draw_max_en(const uint16_t line) { - DWIN_Frame_AreaCopy(1, 245, 119, 269, 129, LBLX, line); // "Max" -} -inline void draw_max_accel_en(const uint16_t line) { - draw_max_en(line); - DWIN_Frame_AreaCopy(1, 1, 135, 79, 145, LBLX + 27, line); // "Acceleration" -} -inline void draw_speed_en(const uint16_t inset, const uint16_t line) { - DWIN_Frame_AreaCopy(1, 184, 119, 224, 132, LBLX + inset, line); // "Speed" -} -inline void draw_jerk_en(const uint16_t line) { - DWIN_Frame_AreaCopy(1, 64, 119, 106, 129, LBLX + 27, line); // "Jerk" -} -inline void draw_steps_per_mm(const uint16_t line) { - DWIN_Frame_AreaCopy(1, 1, 151, 101, 161, LBLX, line); // "Steps-per-mm" -} -inline void say_x(const uint16_t inset, const uint16_t line) { - DWIN_Frame_AreaCopy(1, 95, 104, 102, 114, LBLX + inset, line); // "X" -} -inline void say_y(const uint16_t inset, const uint16_t line) { - DWIN_Frame_AreaCopy(1, 104, 104, 110, 114, LBLX + inset, line); // "Y" -} -inline void say_z(const uint16_t inset, const uint16_t line) { - DWIN_Frame_AreaCopy(1, 112, 104, 120, 114, LBLX + inset, line); // "Z" -} -inline void say_e(const uint16_t inset, const uint16_t line) { - DWIN_Frame_AreaCopy(1, 237, 119, 244, 129, LBLX + inset, line); // "E" -} - -inline void Draw_Motion_Menu() { - Clear_Main_Window(); - - if (HMI_IsChinese()) { - DWIN_Frame_TitleCopy(1, 1, 16, 28, 28); // "Motion" - DWIN_Frame_AreaCopy(1, 173, 133, 228, 147, LBLX, MBASE(MOTION_CASE_RATE)); // Max speed - DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX, MBASE(MOTION_CASE_ACCEL)); // Max... - DWIN_Frame_AreaCopy(1, 28, 149, 69, 161, LBLX + 27, MBASE(MOTION_CASE_ACCEL) + 1); // ...Acceleration - #if HAS_CLASSIC_JERK - DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX, MBASE(MOTION_CASE_JERK)); // Max... - DWIN_Frame_AreaCopy(1, 1, 180, 28, 192, LBLX + 27, MBASE(MOTION_CASE_JERK) + 1); // ... - DWIN_Frame_AreaCopy(1, 202, 133, 228, 147, LBLX + 54, MBASE(MOTION_CASE_JERK)); // ...Jerk - #endif - DWIN_Frame_AreaCopy(1, 153, 148, 194, 161, LBLX, MBASE(MOTION_CASE_STEPS)); // Flow ratio - } - else { - #ifdef USE_STRING_HEADINGS - Draw_Title(GET_TEXT_F(MSG_MOTION)); - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(MOTION_CASE_RATE), F("Feedrate")); - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(MOTION_CASE_ACCEL), GET_TEXT_F(MSG_ACCELERATION)); - #if HAS_CLASSIC_JERK - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(MOTION_CASE_JERK), GET_TEXT_F(MSG_JERK)); - #endif - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(MOTION_CASE_STEPS), GET_TEXT_F(MSG_STEPS_PER_MM)); - #else - DWIN_Frame_TitleCopy(1, 144, 16, 189, 26); // "Motion" - draw_max_en(MBASE(MOTION_CASE_RATE)); draw_speed_en(27, MBASE(MOTION_CASE_RATE)); // "Max Speed" - draw_max_accel_en(MBASE(MOTION_CASE_ACCEL)); // "Max Acceleration" - #if HAS_CLASSIC_JERK - draw_max_en(MBASE(MOTION_CASE_JERK)); draw_jerk_en(MBASE(MOTION_CASE_JERK)); // "Max Jerk" - #endif - draw_steps_per_mm(MBASE(MOTION_CASE_STEPS)); // "Steps-per-mm" - #endif - } - - Draw_Back_First(select_motion.now == 0); - if (select_motion.now) Draw_Menu_Cursor(select_motion.now); - - uint8_t i = 0; - #define _MOTION_ICON(N) Draw_Menu_Line(++i, ICON_MaxSpeed + (N) - 1) - _MOTION_ICON(MOTION_CASE_RATE); Draw_More_Icon(i); - _MOTION_ICON(MOTION_CASE_ACCEL); Draw_More_Icon(i); - #if HAS_CLASSIC_JERK - _MOTION_ICON(MOTION_CASE_JERK); Draw_More_Icon(i); - #endif - _MOTION_ICON(MOTION_CASE_STEPS); Draw_More_Icon(i); -} - -// -// Draw Popup Windows -// -#if HAS_HOTEND || HAS_HEATED_BED - - void DWIN_Popup_Temperature(const bool toohigh) { - Clear_Popup_Area(); - Draw_Popup_Bkgd_105(); - if (toohigh) { - DWIN_ICON_Show(ICON, ICON_TempTooHigh, 102, 165); - if (HMI_IsChinese()) { - DWIN_Frame_AreaCopy(1, 103, 371, 237, 386, 52, 285); - DWIN_Frame_AreaCopy(1, 151, 389, 185, 402, 187, 285); - DWIN_Frame_AreaCopy(1, 189, 389, 271, 402, 95, 310); - } - else { - DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, 36, 300, F("Nozzle or Bed temperature")); - DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, 92, 300, F("is too high")); - } - } - else { - DWIN_ICON_Show(ICON, ICON_TempTooLow, 102, 165); - if (HMI_IsChinese()) { - DWIN_Frame_AreaCopy(1, 103, 371, 270, 386, 52, 285); - DWIN_Frame_AreaCopy(1, 189, 389, 271, 402, 95, 310); - } - else { - DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, 36, 300, F("Nozzle or Bed temperature")); - DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, 92, 300, F("is too low")); - } - } - } - -#endif - -inline void Draw_Popup_Bkgd_60() { - DWIN_Draw_Rectangle(1, Color_Bg_Window, 14, 60, 258, 330); -} - -#if HAS_HOTEND - - void Popup_Window_ETempTooLow() { - Clear_Main_Window(); - Draw_Popup_Bkgd_60(); - DWIN_ICON_Show(ICON, ICON_TempTooLow, 102, 105); - if (HMI_IsChinese()) { - DWIN_Frame_AreaCopy(1, 103, 371, 136, 386, 69, 240); - DWIN_Frame_AreaCopy(1, 170, 371, 270, 386, 102, 240); - DWIN_ICON_Show(ICON, ICON_Confirm_C, 86, 280); - } - else { - DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, 20, 235, F("Nozzle is too cold")); - DWIN_ICON_Show(ICON, ICON_Confirm_E, 86, 280); - } - } - -#endif - -void Popup_Window_Resume() { - Clear_Popup_Area(); - Draw_Popup_Bkgd_105(); - if (HMI_IsChinese()) { - DWIN_Frame_AreaCopy(1, 160, 338, 235, 354, 98, 135); - DWIN_Frame_AreaCopy(1, 103, 321, 271, 335, 52, 192); - DWIN_ICON_Show(ICON, ICON_Cancel_C, 26, 307); - DWIN_ICON_Show(ICON, ICON_Continue_C, 146, 307); - } - else { - DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 14) / 2, 115, F("Continue Print")); - DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 22) / 2, 192, F("It looks like the last")); - DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 22) / 2, 212, F("file was interrupted.")); - DWIN_ICON_Show(ICON, ICON_Cancel_E, 26, 307); - DWIN_ICON_Show(ICON, ICON_Continue_E, 146, 307); - } -} - -void Popup_Window_Home(const bool parking/*=false*/) { - Clear_Main_Window(); - Draw_Popup_Bkgd_60(); - DWIN_ICON_Show(ICON, ICON_BLTouch, 101, 105); - if (HMI_IsChinese()) { - DWIN_Frame_AreaCopy(1, 0, 371, 33, 386, 85, 240); - DWIN_Frame_AreaCopy(1, 203, 286, 271, 302, 118, 240); - DWIN_Frame_AreaCopy(1, 0, 389, 150, 402, 61, 280); - } - else { - DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * (parking ? 7 : 10)) / 2, 230, parking ? F("Parking") : F("Homing XYZ")); - DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 23) / 2, 260, F("Please wait until done.")); - } -} - -#if HAS_ONESTEP_LEVELING - - void Popup_Window_Leveling() { - Clear_Main_Window(); - Draw_Popup_Bkgd_60(); - DWIN_ICON_Show(ICON, ICON_AutoLeveling, 101, 105); - if (HMI_IsChinese()) { - DWIN_Frame_AreaCopy(1, 0, 371, 100, 386, 84, 240); - DWIN_Frame_AreaCopy(1, 0, 389, 150, 402, 61, 280); - } - else { - DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 13) / 2, 230, GET_TEXT_F(MSG_BED_LEVELING)); - DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 23) / 2, 260, F("Please wait until done.")); - } - } - -#endif - -void Draw_Select_Highlight(const bool sel) { - HMI_flag.select_flag = sel; - const uint16_t c1 = sel ? Select_Color : Color_Bg_Window, - c2 = sel ? Color_Bg_Window : Select_Color; - DWIN_Draw_Rectangle(0, c1, 25, 279, 126, 318); - DWIN_Draw_Rectangle(0, c1, 24, 278, 127, 319); - DWIN_Draw_Rectangle(0, c2, 145, 279, 246, 318); - DWIN_Draw_Rectangle(0, c2, 144, 278, 247, 319); -} - -void Popup_window_PauseOrStop() { - Clear_Main_Window(); - Draw_Popup_Bkgd_60(); - if (HMI_IsChinese()) { - if (select_print.now == 1) DWIN_Frame_AreaCopy(1, 237, 338, 269, 356, 98, 150); - else if (select_print.now == 2) DWIN_Frame_AreaCopy(1, 221, 320, 253, 336, 98, 150); - DWIN_Frame_AreaCopy(1, 220, 304, 264, 319, 130, 150); - DWIN_ICON_Show(ICON, ICON_Confirm_C, 26, 280); - DWIN_ICON_Show(ICON, ICON_Cancel_C, 146, 280); - } - else { - if (select_print.now == 1) DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 11) / 2, 150, GET_TEXT_F(MSG_PAUSE_PRINT)); - else if (select_print.now == 2) DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 10) / 2, 150, GET_TEXT_F(MSG_STOP_PRINT)); - DWIN_ICON_Show(ICON, ICON_Confirm_E, 26, 280); - DWIN_ICON_Show(ICON, ICON_Cancel_E, 146, 280); - } - Draw_Select_Highlight(true); -} - -void Draw_Printing_Screen() { - if (HMI_IsChinese()) { - DWIN_Frame_AreaCopy(1, 30, 1, 71, 14, 14, 9); // Tune - DWIN_Frame_AreaCopy(1, 0, 72, 63, 86, 41, 188); // Pause - DWIN_Frame_AreaCopy(1, 65, 72, 128, 86, 176, 188); // Stop - } - else { - DWIN_Frame_AreaCopy(1, 40, 2, 92, 14, 14, 9); // Tune - DWIN_Frame_AreaCopy(1, 0, 44, 96, 58, 41, 188); // Pause - DWIN_Frame_AreaCopy(1, 98, 44, 152, 58, 176, 188); // Stop - } -} - -void Draw_Print_ProgressBar() { - DWIN_ICON_Show(ICON, ICON_Bar, 15, 93); - DWIN_Draw_Rectangle(1, BarFill_Color, 16 + Percentrecord * 240 / 100, 93, 256, 113); - DWIN_Draw_IntValue(true, true, 0, font8x16, Percent_Color, Color_Bg_Black, 2, 117, 133, Percentrecord); - DWIN_Draw_String(false, false, font8x16, Percent_Color, Color_Bg_Black, 133, 133, F("%")); -} - -void Draw_Print_ProgressElapsed() { - duration_t elapsed = print_job_timer.duration(); // print timer - DWIN_Draw_IntValue(true, true, 1, font8x16, Color_White, Color_Bg_Black, 2, 42, 212, elapsed.value / 3600); - DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, 58, 212, F(":")); - DWIN_Draw_IntValue(true, true, 1, font8x16, Color_White, Color_Bg_Black, 2, 66, 212, (elapsed.value % 3600) / 60); -} - -void Draw_Print_ProgressRemain() { - DWIN_Draw_IntValue(true, true, 1, font8x16, Color_White, Color_Bg_Black, 2, 176, 212, remain_time / 3600); - DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, 192, 212, F(":")); - DWIN_Draw_IntValue(true, true, 1, font8x16, Color_White, Color_Bg_Black, 2, 200, 212, (remain_time % 3600) / 60); -} - -void Goto_PrintProcess() { - checkkey = PrintProcess; - - Clear_Main_Window(); - Draw_Printing_Screen(); - - ICON_Tune(); - if (printingIsPaused()) ICON_Continue(); else ICON_Pause(); - ICON_Stop(); - - // Copy into filebuf string before entry - char * const name = card.longest_filename(); - const int8_t npos = _MAX(0U, DWIN_WIDTH - strlen(name) * MENU_CHR_W) / 2; - DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, npos, 60, name); - - DWIN_ICON_Show(ICON, ICON_PrintTime, 17, 193); - DWIN_ICON_Show(ICON, ICON_RemainTime, 150, 191); - - Draw_Print_ProgressBar(); - Draw_Print_ProgressElapsed(); - Draw_Print_ProgressRemain(); -} - -void Goto_MainMenu() { - checkkey = MainMenu; - - Clear_Main_Window(); - - if (HMI_IsChinese()) { - DWIN_Frame_AreaCopy(1, 2, 2, 27, 14, 14, 9); // "Home" - } - else { - #ifdef USE_STRING_HEADINGS - Draw_Title(GET_TEXT_F(MSG_MAIN)); - #else - DWIN_Frame_AreaCopy(1, 0, 2, 39, 12, 14, 9); - #endif - } - - DWIN_ICON_Show(ICON, ICON_LOGO, 71, 52); - - ICON_Print(); - ICON_Prepare(); - ICON_Control(); - TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(select_page.now == 3); -} - -inline ENCODER_DiffState get_encoder_state() { - static millis_t Encoder_ms = 0; - const millis_t ms = millis(); - if (PENDING(ms, Encoder_ms)) return ENCODER_DIFF_NO; - const ENCODER_DiffState state = Encoder_ReceiveAnalyze(); - if (state != ENCODER_DIFF_NO) Encoder_ms = ms + ENCODER_WAIT; - return state; -} - -void HMI_Move_X() { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Move_X_scale)) { - checkkey = AxisMove; - EncoderRate.enabled = false; - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 216, MBASE(1), HMI_ValueStruct.Move_X_scale); - if (!planner.is_full()) { - // Wait for planner moves to finish! - planner.synchronize(); - planner.buffer_line(current_position, MMM_TO_MMS(HOMING_FEEDRATE_XY), active_extruder); - } - DWIN_UpdateLCD(); - return; - } - NOLESS(HMI_ValueStruct.Move_X_scale, (X_MIN_POS) * MINUNITMULT); - NOMORE(HMI_ValueStruct.Move_X_scale, (X_MAX_POS) * MINUNITMULT); - current_position.x = HMI_ValueStruct.Move_X_scale / 10; - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 216, MBASE(1), HMI_ValueStruct.Move_X_scale); - DWIN_UpdateLCD(); - } -} - -void HMI_Move_Y() { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Move_Y_scale)) { - checkkey = AxisMove; - EncoderRate.enabled = false; - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 216, MBASE(2), HMI_ValueStruct.Move_Y_scale); - if (!planner.is_full()) { - // Wait for planner moves to finish! - planner.synchronize(); - planner.buffer_line(current_position, MMM_TO_MMS(HOMING_FEEDRATE_XY), active_extruder); - } - DWIN_UpdateLCD(); - return; - } - NOLESS(HMI_ValueStruct.Move_Y_scale, (Y_MIN_POS) * MINUNITMULT); - NOMORE(HMI_ValueStruct.Move_Y_scale, (Y_MAX_POS) * MINUNITMULT); - current_position.y = HMI_ValueStruct.Move_Y_scale / 10; - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 216, MBASE(2), HMI_ValueStruct.Move_Y_scale); - DWIN_UpdateLCD(); - } -} - -void HMI_Move_Z() { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Move_Z_scale)) { - checkkey = AxisMove; - EncoderRate.enabled = false; - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 216, MBASE(3), HMI_ValueStruct.Move_Z_scale); - if (!planner.is_full()) { - // Wait for planner moves to finish! - planner.synchronize(); - planner.buffer_line(current_position, MMM_TO_MMS(HOMING_FEEDRATE_Z), active_extruder); - } - DWIN_UpdateLCD(); - return; - } - NOLESS(HMI_ValueStruct.Move_Z_scale, Z_MIN_POS * MINUNITMULT); - NOMORE(HMI_ValueStruct.Move_Z_scale, Z_MAX_POS * MINUNITMULT); - current_position.z = HMI_ValueStruct.Move_Z_scale / 10; - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 216, MBASE(3), HMI_ValueStruct.Move_Z_scale); - DWIN_UpdateLCD(); - } -} - -#if HAS_HOTEND - - void HMI_Move_E() { - static float last_E_scale = 0; - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Move_E_scale)) { - checkkey = AxisMove; - EncoderRate.enabled = false; - last_E_scale = HMI_ValueStruct.Move_E_scale; - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, 1, 216, MBASE(4), HMI_ValueStruct.Move_E_scale); - if (!planner.is_full()) { - planner.synchronize(); // Wait for planner moves to finish! - planner.buffer_line(current_position, MMM_TO_MMS(FEEDRATE_E), active_extruder); - } - DWIN_UpdateLCD(); - return; - } - if ((HMI_ValueStruct.Move_E_scale - last_E_scale) > (EXTRUDE_MAXLENGTH) * MINUNITMULT) - HMI_ValueStruct.Move_E_scale = last_E_scale + (EXTRUDE_MAXLENGTH) * MINUNITMULT; - else if ((last_E_scale - HMI_ValueStruct.Move_E_scale) > (EXTRUDE_MAXLENGTH) * MINUNITMULT) - HMI_ValueStruct.Move_E_scale = last_E_scale - (EXTRUDE_MAXLENGTH) * MINUNITMULT; - current_position.e = HMI_ValueStruct.Move_E_scale / 10; - DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, 1, 216, MBASE(4), HMI_ValueStruct.Move_E_scale); - DWIN_UpdateLCD(); - } - } - -#endif - -#if HAS_ZOFFSET_ITEM - - bool printer_busy() { return planner.movesplanned() || printingIsActive(); } - - void HMI_Zoffset() { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - uint8_t zoff_line; - switch (HMI_ValueStruct.show_mode) { - case -4: zoff_line = PREPARE_CASE_ZOFF + MROWS - index_prepare; break; - default: zoff_line = TUNE_CASE_ZOFF + MROWS - index_tune; - } - if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.offset_value)) { - EncoderRate.enabled = false; - #if HAS_BED_PROBE - probe.offset.z = dwin_zoffset; - TERN_(EEPROM_SETTINGS, settings.save()); - #endif - if (HMI_ValueStruct.show_mode == -4) { - checkkey = Prepare; - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 2, 2, 202, MBASE(zoff_line), TERN(HAS_BED_PROBE, BABY_Z_VAR * 100, HMI_ValueStruct.offset_value)); - } - else { - checkkey = Tune; - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 2, 2, 202, MBASE(zoff_line), TERN(HAS_BED_PROBE, BABY_Z_VAR * 100, HMI_ValueStruct.offset_value)); - } - DWIN_UpdateLCD(); - return; - } - NOLESS(HMI_ValueStruct.offset_value, (Z_PROBE_OFFSET_RANGE_MIN) * 100); - NOMORE(HMI_ValueStruct.offset_value, (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 ( (ENABLED(BABYSTEP_WITHOUT_HOMING) || all_axes_known()) && (ENABLED(BABYSTEP_ALWAYS_AVAILABLE) || printer_busy()) ) - babystep.add_mm(Z_AXIS, dwin_zoffset - last_zoffset); - #endif - DWIN_Draw_Signed_Float(font8x16, Select_Color, 2, 2, 202, MBASE(zoff_line), HMI_ValueStruct.offset_value); - DWIN_UpdateLCD(); - } - } - -#endif // HAS_ZOFFSET_ITEM - -#if HAS_HOTEND - - void HMI_ETemp() { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - uint8_t temp_line; - switch (HMI_ValueStruct.show_mode) { - case -1: temp_line = TEMP_CASE_TEMP; break; - case -2: temp_line = PREHEAT_CASE_TEMP; break; - case -3: temp_line = PREHEAT_CASE_TEMP; break; - default: temp_line = TUNE_CASE_TEMP + MROWS - index_tune; - } - if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.E_Temp)) { - EncoderRate.enabled = false; - if (HMI_ValueStruct.show_mode == -1) { // temperature - checkkey = TemperatureID; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(temp_line), HMI_ValueStruct.E_Temp); - } - else if (HMI_ValueStruct.show_mode == -2) { - checkkey = PLAPreheat; - ui.material_preset[0].hotend_temp = HMI_ValueStruct.E_Temp; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(temp_line), ui.material_preset[0].hotend_temp); - return; - } - else if (HMI_ValueStruct.show_mode == -3) { - checkkey = ABSPreheat; - ui.material_preset[1].hotend_temp = HMI_ValueStruct.E_Temp; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(temp_line), ui.material_preset[1].hotend_temp); - return; - } - else { // tune - checkkey = Tune; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(temp_line), HMI_ValueStruct.E_Temp); - } - thermalManager.setTargetHotend(HMI_ValueStruct.E_Temp, 0); - return; - } - // E_Temp limit - NOMORE(HMI_ValueStruct.E_Temp, MAX_E_TEMP); - NOLESS(HMI_ValueStruct.E_Temp, MIN_E_TEMP); - // E_Temp value - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(temp_line), HMI_ValueStruct.E_Temp); - } - } - -#endif // HAS_HOTEND - -#if HAS_HEATED_BED - - void HMI_BedTemp() { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - uint8_t bed_line; - switch (HMI_ValueStruct.show_mode) { - case -1: bed_line = TEMP_CASE_BED; break; - case -2: bed_line = PREHEAT_CASE_BED; break; - case -3: bed_line = PREHEAT_CASE_BED; break; - default: bed_line = TUNE_CASE_BED + MROWS - index_tune; - } - if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Bed_Temp)) { - EncoderRate.enabled = false; - if (HMI_ValueStruct.show_mode == -1) { - checkkey = TemperatureID; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(bed_line), HMI_ValueStruct.Bed_Temp); - } - else if (HMI_ValueStruct.show_mode == -2) { - checkkey = PLAPreheat; - ui.material_preset[0].bed_temp = HMI_ValueStruct.Bed_Temp; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(bed_line), ui.material_preset[0].bed_temp); - return; - } - else if (HMI_ValueStruct.show_mode == -3) { - checkkey = ABSPreheat; - ui.material_preset[1].bed_temp = HMI_ValueStruct.Bed_Temp; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(bed_line), ui.material_preset[1].bed_temp); - return; - } - else { - checkkey = Tune; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(bed_line), HMI_ValueStruct.Bed_Temp); - } - thermalManager.setTargetBed(HMI_ValueStruct.Bed_Temp); - return; - } - // Bed_Temp limit - NOMORE(HMI_ValueStruct.Bed_Temp, BED_MAX_TARGET); - NOLESS(HMI_ValueStruct.Bed_Temp, MIN_BED_TEMP); - // Bed_Temp value - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(bed_line), HMI_ValueStruct.Bed_Temp); - } - } - -#endif // HAS_HEATED_BED - -#if HAS_PREHEAT - - void HMI_FanSpeed() { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - uint8_t fan_line; - switch (HMI_ValueStruct.show_mode) { - case -1: fan_line = TEMP_CASE_FAN; break; - case -2: fan_line = PREHEAT_CASE_FAN; break; - case -3: fan_line = PREHEAT_CASE_FAN; break; - default: fan_line = TUNE_CASE_FAN + MROWS - index_tune; - } - - if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Fan_speed)) { - EncoderRate.enabled = false; - if (HMI_ValueStruct.show_mode == -1) { - checkkey = TemperatureID; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(fan_line), HMI_ValueStruct.Fan_speed); - } - else if (HMI_ValueStruct.show_mode == -2) { - checkkey = PLAPreheat; - ui.material_preset[0].fan_speed = HMI_ValueStruct.Fan_speed; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(fan_line), ui.material_preset[0].fan_speed); - return; - } - else if (HMI_ValueStruct.show_mode == -3) { - checkkey = ABSPreheat; - ui.material_preset[1].fan_speed = HMI_ValueStruct.Fan_speed; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(fan_line), ui.material_preset[1].fan_speed); - return; - } - else { - checkkey = Tune; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(fan_line), HMI_ValueStruct.Fan_speed); - } - thermalManager.set_fan_speed(0, HMI_ValueStruct.Fan_speed); - return; - } - // Fan_speed limit - NOMORE(HMI_ValueStruct.Fan_speed, FANON); - NOLESS(HMI_ValueStruct.Fan_speed, FANOFF); - // Fan_speed value - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(fan_line), HMI_ValueStruct.Fan_speed); - } - } - -#endif // HAS_PREHEAT - -void HMI_PrintSpeed() { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.print_speed)) { - checkkey = Tune; - EncoderRate.enabled = false; - feedrate_percentage = HMI_ValueStruct.print_speed; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(select_tune.now + MROWS - index_tune), HMI_ValueStruct.print_speed); - return; - } - // print_speed limit - NOMORE(HMI_ValueStruct.print_speed, MAX_PRINT_SPEED); - NOLESS(HMI_ValueStruct.print_speed, MIN_PRINT_SPEED); - // print_speed value - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(select_tune.now + MROWS - index_tune), HMI_ValueStruct.print_speed); - } -} - -void HMI_MaxFeedspeedXYZE() { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Max_Feedspeed)) { - checkkey = MaxSpeed; - EncoderRate.enabled = false; - if (WITHIN(HMI_flag.feedspeed_axis, X_AXIS, E_AXIS)) - planner.set_max_feedrate(HMI_flag.feedspeed_axis, HMI_ValueStruct.Max_Feedspeed); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(select_speed.now), HMI_ValueStruct.Max_Feedspeed); - return; - } - // MaxFeedspeed limit - if (WITHIN(HMI_flag.feedspeed_axis, X_AXIS, E_AXIS)) - NOMORE(HMI_ValueStruct.Max_Feedspeed, default_max_feedrate[HMI_flag.feedspeed_axis] * 2); - if (HMI_ValueStruct.Max_Feedspeed < MIN_MAXFEEDSPEED) HMI_ValueStruct.Max_Feedspeed = MIN_MAXFEEDSPEED; - // MaxFeedspeed value - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 4, 210, MBASE(select_speed.now), HMI_ValueStruct.Max_Feedspeed); - } -} - -void HMI_MaxAccelerationXYZE() { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Max_Acceleration)) { - checkkey = MaxAcceleration; - EncoderRate.enabled = false; - if (HMI_flag.acc_axis == X_AXIS) planner.set_max_acceleration(X_AXIS, HMI_ValueStruct.Max_Acceleration); - else if (HMI_flag.acc_axis == Y_AXIS) planner.set_max_acceleration(Y_AXIS, HMI_ValueStruct.Max_Acceleration); - else if (HMI_flag.acc_axis == Z_AXIS) planner.set_max_acceleration(Z_AXIS, HMI_ValueStruct.Max_Acceleration); - #if HAS_HOTEND - else if (HMI_flag.acc_axis == E_AXIS) planner.set_max_acceleration(E_AXIS, HMI_ValueStruct.Max_Acceleration); - #endif - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(select_acc.now), HMI_ValueStruct.Max_Acceleration); - return; - } - // MaxAcceleration limit - if (WITHIN(HMI_flag.acc_axis, X_AXIS, E_AXIS)) - NOMORE(HMI_ValueStruct.Max_Acceleration, default_max_acceleration[HMI_flag.acc_axis] * 2); - if (HMI_ValueStruct.Max_Acceleration < MIN_MAXACCELERATION) HMI_ValueStruct.Max_Acceleration = MIN_MAXACCELERATION; - // MaxAcceleration value - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 4, 210, MBASE(select_acc.now), HMI_ValueStruct.Max_Acceleration); - } -} - -#if HAS_CLASSIC_JERK - - void HMI_MaxJerkXYZE() { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Max_Jerk)) { - checkkey = MaxJerk; - EncoderRate.enabled = false; - if (WITHIN(HMI_flag.step_axis, X_AXIS, E_AXIS)) - planner.set_max_jerk(HMI_flag.step_axis, HMI_ValueStruct.Max_Jerk / 10); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk); - return; - } - // MaxJerk limit - if (WITHIN(HMI_flag.jerk_axis, X_AXIS, E_AXIS)) - NOMORE(HMI_ValueStruct.Max_Jerk, default_max_jerk[HMI_flag.jerk_axis] * 2 * MINUNITMULT); - NOLESS(HMI_ValueStruct.Max_Jerk, (MIN_MAXJERK) * MINUNITMULT); - // MaxJerk value - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk); - } - } - -#endif // HAS_CLASSIC_JERK - -void HMI_StepXYZE() { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Max_Step)) { - checkkey = Step; - EncoderRate.enabled = false; - if (WITHIN(HMI_flag.step_axis, X_AXIS, E_AXIS)) - planner.settings.axis_steps_per_mm[HMI_flag.step_axis] = HMI_ValueStruct.Max_Step / 10; - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step); - return; - } - // Step limit - if (WITHIN(HMI_flag.step_axis, X_AXIS, E_AXIS)) - NOMORE(HMI_ValueStruct.Max_Step, default_axis_steps_per_unit[HMI_flag.step_axis] * 2 * MINUNITMULT); - NOLESS(HMI_ValueStruct.Max_Step, MIN_STEP); - // Step value - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step); - } -} - -void update_variable() { - #if HAS_HOTEND - static float last_temp_hotend_target = 0, last_temp_hotend_current = 0; - #endif - #if HAS_HEATED_BED - static float last_temp_bed_target = 0, last_temp_bed_current = 0; - #endif - #if HAS_FAN - static uint8_t last_fan_speed = 0; - #endif - - /* Tune page temperature update */ - if (checkkey == Tune) { - #if HAS_HOTEND - if (last_temp_hotend_target != thermalManager.temp_hotend[0].target) - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TUNE_CASE_TEMP + MROWS - index_tune), thermalManager.temp_hotend[0].target); - #endif - #if HAS_HEATED_BED - if (last_temp_bed_target != thermalManager.temp_bed.target) - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TUNE_CASE_BED + MROWS - index_tune), thermalManager.temp_bed.target); - #endif - #if HAS_FAN - if (last_fan_speed != thermalManager.fan_speed[0]) { - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TUNE_CASE_FAN + MROWS - index_tune), thermalManager.fan_speed[0]); - last_fan_speed = thermalManager.fan_speed[0]; - } - #endif - } - - /* Temperature page temperature update */ - if (checkkey == TemperatureID) { - #if HAS_HOTEND - if (last_temp_hotend_target != thermalManager.temp_hotend[0].target) - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TEMP_CASE_TEMP), thermalManager.temp_hotend[0].target); - #endif - #if HAS_HEATED_BED - if (last_temp_bed_target != thermalManager.temp_bed.target) - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TEMP_CASE_BED), thermalManager.temp_bed.target); - #endif - #if HAS_FAN - if (last_fan_speed != thermalManager.fan_speed[0]) { - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TEMP_CASE_FAN), thermalManager.fan_speed[0]); - last_fan_speed = thermalManager.fan_speed[0]; - } - #endif - } - - /* Bottom temperature update */ - #if HAS_HOTEND - if (last_temp_hotend_current != thermalManager.temp_hotend[0].celsius) { - DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 33, 382, thermalManager.temp_hotend[0].celsius); - last_temp_hotend_current = thermalManager.temp_hotend[0].celsius; - } - if (last_temp_hotend_target != thermalManager.temp_hotend[0].target) { - DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 33 + 4 * STAT_CHR_W + 6, 382, thermalManager.temp_hotend[0].target); - last_temp_hotend_target = thermalManager.temp_hotend[0].target; - } - #endif - #if HAS_HEATED_BED - if (last_temp_bed_current != thermalManager.temp_bed.celsius) { - DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 178, 382, thermalManager.temp_bed.celsius); - last_temp_bed_current = thermalManager.temp_bed.celsius; - } - if (last_temp_bed_target != thermalManager.temp_bed.target) { - DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 178 + 4 * STAT_CHR_W + 6, 382, thermalManager.temp_bed.target); - last_temp_bed_target = thermalManager.temp_bed.target; - } - #endif - static uint16_t last_speed = 0; - if (last_speed != feedrate_percentage) { - DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 33 + 2 * STAT_CHR_W, 429, feedrate_percentage); - last_speed = feedrate_percentage; - } - #if HAS_ZOFFSET_ITEM - if (last_zoffset != BABY_Z_VAR) { - DWIN_Draw_Signed_Float(DWIN_FONT_STAT, Color_Bg_Black, 2, 2, 178 + STAT_CHR_W, 429, BABY_Z_VAR * 100); - last_zoffset = BABY_Z_VAR; - } - #endif -} - -/** - * Read and cache the working directory. - * - * TODO: New code can follow the pattern of menu_media.cpp - * and rely on Marlin caching for performance. No need to - * cache files here. - */ - -#ifndef strcasecmp_P - #define strcasecmp_P(a, b) strcasecmp((a), (b)) -#endif - -inline void make_name_without_ext(char *dst, char *src, size_t maxlen=MENU_CHAR_LIMIT) { - char * const name = card.longest_filename(); - size_t pos = strlen(name); // index of ending nul - - // For files, remove the extension - // which may be .gcode, .gco, or .g - if (!card.flag.filenameIsDir) - while (pos && src[pos] != '.') pos--; // find last '.' (stop at 0) - - size_t len = pos; // nul or '.' - if (len > maxlen) { // Keep the name short - pos = len = maxlen; // move nul down - dst[--pos] = '.'; // insert dots - dst[--pos] = '.'; - dst[--pos] = '.'; - } - - dst[len] = '\0'; // end it - - // Copy down to 0 - while (pos--) dst[pos] = src[pos]; -} - -inline void HMI_SDCardInit() { card.cdroot(); } - -void MarlinUI::refresh() { /* Nothing to see here */ } - -#define ICON_Folder ICON_More - -#if ENABLED(SCROLL_LONG_FILENAMES) - - char shift_name[LONG_FILENAME_LENGTH + 1]; - int8_t shift_amt; // = 0 - millis_t shift_ms; // = 0 - - // Init the shift name based on the highlighted item - inline 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(); - if (WITHIN(filenum, 0, fileCnt - 1)) { - card.getfilename_sorted(SD_ORDER(filenum, fileCnt)); - char * const name = card.longest_filename(); - make_name_without_ext(shift_name, name, 100); - } - } - - inline void Init_SDItem_Shift() { - shift_amt = 0; - shift_ms = select_file.now > 0 && strlen(shift_name) > MENU_CHAR_LIMIT - ? millis() + 750UL : 0; - } - -#endif - -/** - * Display an SD item, adding a CDUP for subfolders. - */ -inline void Draw_SDItem(const uint16_t item, int16_t row=-1) { - if (row < 0) row = item + 1 + MROWS - index_file; - const bool is_subdir = !card.flag.workDirIsRoot; - if (is_subdir && item == 0) { - Draw_Menu_Line(row, ICON_Folder, ".."); - return; - } - - card.getfilename_sorted(item - is_subdir); - char * const name = card.longest_filename(); - - #if ENABLED(SCROLL_LONG_FILENAMES) - // Init the current selected name - // This is used during scroll drawing - if (item == select_file.now - 1) { - make_name_without_ext(shift_name, name, 100); - Init_SDItem_Shift(); - } - #endif - - // Draw the file/folder with name aligned left - char str[strlen(name) + 1]; - make_name_without_ext(str, name); - Draw_Menu_Line(row, card.flag.filenameIsDir ? ICON_Folder : ICON_File, str); -} - -#if ENABLED(SCROLL_LONG_FILENAMES) - - inline void Draw_SDItem_Shifted(int8_t &shift) { - // Limit to the number of chars past the cutoff - const size_t len = strlen(shift_name); - NOMORE(shift, _MAX(len - MENU_CHAR_LIMIT, 0U)); - - // Shorten to the available space - const size_t lastchar = _MIN((signed)len, shift + MENU_CHAR_LIMIT); - - const char c = shift_name[lastchar]; - shift_name[lastchar] = '\0'; - - const uint8_t row = select_file.now + MROWS - index_file; // skip "Back" and scroll - Erase_Menu_Text(row); - Draw_Menu_Line(row, 0, &shift_name[shift]); - - shift_name[lastchar] = c; - } - -#endif - -// Redraw the first set of SD Files -inline void Redraw_SD_List() { - select_file.reset(); - index_file = MROWS; - - Clear_Menu_Area(); // Leave title bar unchanged - - Draw_Back_First(); - - if (card.isMounted()) { - // As many files as will fit - LOOP_L_N(i, _MIN(nr_sd_menu_items(), MROWS)) - Draw_SDItem(i, i + 1); - - TERN_(SCROLL_LONG_FILENAMES, Init_SDItem_Shift()); - } - else { - DWIN_Draw_Rectangle(1, Color_Bg_Red, 10, MBASE(3) - 10, DWIN_WIDTH - 10, MBASE(4)); - DWIN_Draw_String(false, false, font16x32, Color_Yellow, Color_Bg_Red, ((DWIN_WIDTH) - 8 * 16) / 2, MBASE(3), F("No Media")); - } -} - -bool DWIN_lcd_sd_status = false; - -inline void SDCard_Up() { - card.cdup(); - Redraw_SD_List(); - DWIN_lcd_sd_status = false; // On next DWIN_Update -} - -inline void SDCard_Folder(char * const dirname) { - card.cd(dirname); - Redraw_SD_List(); - DWIN_lcd_sd_status = false; // On next DWIN_Update -} - -// -// Watch for media mount / unmount -// -void HMI_SDCardUpdate() { - if (HMI_flag.home_flag) return; - if (DWIN_lcd_sd_status != card.isMounted()) { - DWIN_lcd_sd_status = card.isMounted(); - // SERIAL_ECHOLNPAIR("HMI_SDCardUpdate: ", int(DWIN_lcd_sd_status)); - if (DWIN_lcd_sd_status) { - if (checkkey == SelectFile) - Redraw_SD_List(); - } - else { - // clean file icon - if (checkkey == SelectFile) { - Redraw_SD_List(); - } - else if (checkkey == PrintProcess || checkkey == Tune || printingIsActive()) { - // TODO: Move card removed abort handling - // to CardReader::manage_media. - card.flag.abort_sd_printing = true; - wait_for_heatup = wait_for_user = false; - dwin_abort_flag = true; // Reset feedrate, return to Home - } - } - DWIN_UpdateLCD(); - } -} - -// -// The status area is always on-screen, except during -// full-screen modal dialogs. (TODO: Keep alive during dialogs) -// -void Draw_Status_Area(const bool with_update) { - - // Clear the bottom area of the screen - DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, STATUS_Y, DWIN_WIDTH, DWIN_HEIGHT - 1); - - // - // Status Area - // - #if HAS_HOTEND - DWIN_ICON_Show(ICON, ICON_HotendTemp, 13, 381); - DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 33, 382, thermalManager.temp_hotend[0].celsius); - DWIN_Draw_String(false, false, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 33 + 3 * STAT_CHR_W + 5, 383, F("/")); - DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 33 + 4 * STAT_CHR_W + 6, 382, thermalManager.temp_hotend[0].target); - #endif - #if HOTENDS > 1 - // DWIN_ICON_Show(ICON,ICON_HotendTemp, 13, 381); - #endif - - #if HAS_HEATED_BED - DWIN_ICON_Show(ICON, ICON_BedTemp, 158, 381); - DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 178, 382, thermalManager.temp_bed.celsius); - DWIN_Draw_String(false, false, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 178 + 3 * STAT_CHR_W + 5, 383, F("/")); - DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 178 + 4 * STAT_CHR_W + 6, 382, thermalManager.temp_bed.target); - #endif - - DWIN_ICON_Show(ICON, ICON_Speed, 13, 429); - DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 33 + 2 * STAT_CHR_W, 429, feedrate_percentage); - DWIN_Draw_String(false, false, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 33 + 5 * STAT_CHR_W + 2, 429, F("%")); - - #if HAS_ZOFFSET_ITEM - DWIN_ICON_Show(ICON, ICON_Zoffset, 158, 428); - DWIN_Draw_Signed_Float(DWIN_FONT_STAT, Color_Bg_Black, 2, 2, 178, 429, BABY_Z_VAR * 100); - #endif - - if (with_update) { - DWIN_UpdateLCD(); - delay(5); - } -} - -void HMI_StartFrame(const bool with_update) { - Goto_MainMenu(); - Draw_Status_Area(with_update); -} - -inline void Draw_Info_Menu() { - Clear_Main_Window(); - - DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, (DWIN_WIDTH - strlen(MACHINE_SIZE) * MENU_CHR_W) / 2, 122, (char*)MACHINE_SIZE); - DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, (DWIN_WIDTH - strlen(SHORT_BUILD_VERSION) * MENU_CHR_W) / 2, 195, (char*)SHORT_BUILD_VERSION); - - if (HMI_IsChinese()) { - DWIN_Frame_TitleCopy(1, 30, 17, 57, 29); // "Info" - - DWIN_Frame_AreaCopy(1, 197, 149, 252, 161, 108, 102); - DWIN_Frame_AreaCopy(1, 1, 164, 56, 176, 108, 175); - DWIN_Frame_AreaCopy(1, 58, 164, 113, 176, 105, 248); - DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, (DWIN_WIDTH - strlen(CORP_WEBSITE_C) * MENU_CHR_W) / 2, 268, (char*)CORP_WEBSITE_C); - } - else { - #ifdef USE_STRING_HEADINGS - Draw_Title(GET_TEXT_F(MSG_INFO_SCREEN)); - #else - DWIN_Frame_TitleCopy(1, 190, 16, 215, 26); // "Info" - #endif - - DWIN_Frame_AreaCopy(1, 120, 150, 146, 161, 124, 102); - DWIN_Frame_AreaCopy(1, 146, 151, 254, 161, 82, 175); - DWIN_Frame_AreaCopy(1, 0, 165, 94, 175, 89, 248); - DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, (DWIN_WIDTH - strlen(CORP_WEBSITE_E) * MENU_CHR_W) / 2, 268, (char*)CORP_WEBSITE_E); - } - - Draw_Back_First(); - LOOP_L_N(i, 3) { - 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); - } -} - -inline void Draw_Print_File_Menu() { - Clear_Title_Bar(); - - if (HMI_IsChinese()) { - DWIN_Frame_TitleCopy(1, 0, 31, 55, 44); // "Print file" - } - else { - #ifdef USE_STRING_HEADINGS - Draw_Title("Print file"); // TODO: GET_TEXT_F - #else - DWIN_Frame_TitleCopy(1, 52, 31, 137, 41); // "Print file" - #endif - } - - Redraw_SD_List(); -} - -/* Main Process */ -void HMI_MainMenu() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - - if (encoder_diffState == ENCODER_DIFF_CW) { - if (select_page.inc(4)) { - switch (select_page.now) { - case 0: ICON_Print(); break; - case 1: ICON_Print(); ICON_Prepare(); break; - case 2: ICON_Prepare(); ICON_Control(); break; - case 3: ICON_Control(); TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(1); break; - } - } - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - if (select_page.dec()) { - switch (select_page.now) { - case 0: ICON_Print(); ICON_Prepare(); break; - case 1: ICON_Prepare(); ICON_Control(); break; - case 2: ICON_Control(); TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(0); break; - case 3: TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(1); break; - } - } - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - switch (select_page.now) { - case 0: // Print File - checkkey = SelectFile; - Draw_Print_File_Menu(); - break; - - case 1: // Prepare - checkkey = Prepare; - select_prepare.reset(); - index_prepare = MROWS; - Draw_Prepare_Menu(); - break; - - case 2: // Control - checkkey = Control; - select_control.reset(); - index_control = MROWS; - Draw_Control_Menu(); - break; - - case 3: // Leveling or Info - #if HAS_ONESTEP_LEVELING - checkkey = Leveling; - HMI_Leveling(); - #else - checkkey = Info; - Draw_Info_Menu(); - #endif - break; - } - } - DWIN_UpdateLCD(); -} - -// Select (and Print) File -void HMI_SelectFile() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - - const uint16_t hasUpDir = !card.flag.workDirIsRoot; - - if (encoder_diffState == ENCODER_DIFF_NO) { - #if ENABLED(SCROLL_LONG_FILENAMES) - if (shift_ms && select_file.now >= 1 + hasUpDir) { - // Scroll selected filename every second - const millis_t ms = millis(); - if (ELAPSED(ms, shift_ms)) { - const bool was_reset = shift_amt < 0; - shift_ms = ms + 375UL + was_reset * 250UL; // ms per character - int8_t shift_new = shift_amt + 1; // Try to shift by... - Draw_SDItem_Shifted(shift_new); // Draw the item - if (!was_reset && shift_new == 0) // Was it limited to 0? - shift_ms = 0; // No scrolling needed - else if (shift_new == shift_amt) // Scroll reached the end - shift_new = -1; // Reset - shift_amt = shift_new; // Set new scroll - } - } - #endif - return; - } - - // First pause is long. Easy. - // On reset, long pause must be after 0. - - const uint16_t fullCnt = nr_sd_menu_items(); - - if (encoder_diffState == ENCODER_DIFF_CW && fullCnt) { - if (select_file.inc(1 + fullCnt)) { - const uint8_t itemnum = select_file.now - 1; // -1 for "Back" - if (TERN0(SCROLL_LONG_FILENAMES, shift_ms)) { // If line was shifted - Erase_Menu_Text(itemnum + MROWS - index_file); // Erase and - Draw_SDItem(itemnum - 1); // redraw - } - if (select_file.now > MROWS && select_file.now > index_file) { // Cursor past the bottom - index_file = select_file.now; // New bottom line - Scroll_Menu(DWIN_SCROLL_UP); - Draw_SDItem(itemnum, MROWS); // Draw and init the shift name - } - else { - Move_Highlight(1, select_file.now + MROWS - index_file); // Just move highlight - TERN_(SCROLL_LONG_FILENAMES, Init_Shift_Name()); // ...and init the shift name - } - TERN_(SCROLL_LONG_FILENAMES, Init_SDItem_Shift()); - } - } - else if (encoder_diffState == ENCODER_DIFF_CCW && fullCnt) { - if (select_file.dec()) { - const uint8_t itemnum = select_file.now - 1; // -1 for "Back" - if (TERN0(SCROLL_LONG_FILENAMES, shift_ms)) { // If line was shifted - Erase_Menu_Text(select_file.now + 1 + MROWS - index_file); // Erase and - Draw_SDItem(itemnum + 1); // redraw - } - if (select_file.now < index_file - MROWS) { // Cursor past the top - index_file--; // New bottom line - Scroll_Menu(DWIN_SCROLL_DOWN); - if (index_file == MROWS) { - Draw_Back_First(); - TERN_(SCROLL_LONG_FILENAMES, shift_ms = 0); - } - else { - Draw_SDItem(itemnum, 0); // Draw the item (and init shift name) - } - } - else { - Move_Highlight(-1, select_file.now + MROWS - index_file); // Just move highlight - TERN_(SCROLL_LONG_FILENAMES, Init_Shift_Name()); // ...and init the shift name - } - TERN_(SCROLL_LONG_FILENAMES, Init_SDItem_Shift()); // Reset left. Init timer. - } - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - if (select_file.now == 0) { // Back - select_page.set(0); - Goto_MainMenu(); - } - else if (hasUpDir && select_file.now == 1) { // CD-Up - SDCard_Up(); - goto HMI_SelectFileExit; - } - else { - const uint16_t filenum = select_file.now - 1 - hasUpDir; - card.getfilename_sorted(SD_ORDER(filenum, card.get_num_Files())); - - // Enter that folder! - if (card.flag.filenameIsDir) { - SDCard_Folder(card.filename); - goto HMI_SelectFileExit; - } - - // Reset highlight for next entry - select_print.reset(); - select_file.reset(); - - // Start choice and print SD file - HMI_flag.heat_flag = true; - HMI_flag.print_finish = false; - HMI_ValueStruct.show_mode = 0; - - card.openAndPrintFile(card.filename); - - #if FAN_COUNT > 0 - // All fans on for Ender 3 v2 ? - // The slicer should manage this for us. - // for (uint8_t i = 0; i < FAN_COUNT; i++) - // thermalManager.fan_speed[i] = FANON; - #endif - - Goto_PrintProcess(); - } - } -HMI_SelectFileExit: - DWIN_UpdateLCD(); -} - -/* Printing */ -void HMI_Printing() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - - if (HMI_flag.done_confirm_flag) { - if (encoder_diffState == ENCODER_DIFF_ENTER) { - HMI_flag.done_confirm_flag = false; - dwin_abort_flag = true; // Reset feedrate, return to Home - } - return; - } - - // Avoid flicker by updating only the previous menu - if (encoder_diffState == ENCODER_DIFF_CW) { - if (select_print.inc(3)) { - switch (select_print.now) { - case 0: ICON_Tune(); break; - case 1: - ICON_Tune(); - if (printingIsPaused()) ICON_Continue(); else ICON_Pause(); - break; - case 2: - if (printingIsPaused()) ICON_Continue(); else ICON_Pause(); - ICON_Stop(); - break; - } - } - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - if (select_print.dec()) { - switch (select_print.now) { - case 0: - ICON_Tune(); - if (printingIsPaused()) ICON_Continue(); else ICON_Pause(); - break; - case 1: - if (printingIsPaused()) ICON_Continue(); else ICON_Pause(); - ICON_Stop(); - break; - case 2: ICON_Stop(); break; - } - } - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - switch (select_print.now) { - case 0: // Tune - checkkey = Tune; - HMI_ValueStruct.show_mode = 0; - select_tune.reset(); - index_tune = MROWS; - Draw_Tune_Menu(); - break; - case 1: // Pause - if (HMI_flag.pause_flag) { - ICON_Pause(); - - char cmd[40]; - cmd[0] = '\0'; - - #if ENABLED(PAUSE_HEAT) - #if HAS_HEATED_BED - if (tempbed) sprintf_P(cmd, PSTR("M190 S%i\n"), tempbed); - #endif - #if HAS_HOTEND - if (temphot) sprintf_P(&cmd[strlen(cmd)], PSTR("M109 S%i\n"), temphot); - #endif - #endif - - strcat_P(cmd, PSTR("M24")); - queue.inject(cmd); - } - else { - HMI_flag.select_flag = true; - checkkey = Print_window; - Popup_window_PauseOrStop(); - } - break; - - case 2: // Stop - HMI_flag.select_flag = true; - checkkey = Print_window; - Popup_window_PauseOrStop(); - break; - - default: break; - } - } - DWIN_UpdateLCD(); -} - -/* Pause and Stop window */ -void HMI_PauseOrStop() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - - if (encoder_diffState == ENCODER_DIFF_CW) - Draw_Select_Highlight(false); - else if (encoder_diffState == ENCODER_DIFF_CCW) - Draw_Select_Highlight(true); - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - if (select_print.now == 1) { // pause window - if (HMI_flag.select_flag) { - HMI_flag.pause_action = true; - ICON_Continue(); - #if ENABLED(POWER_LOSS_RECOVERY) - if (recovery.enabled) recovery.save(true); - #endif - queue.inject_P(PSTR("M25")); - } - else { - // cancel pause - } - Goto_PrintProcess(); - } - else if (select_print.now == 2) { // stop window - if (HMI_flag.select_flag) { - checkkey = Back_Main; - if (HMI_flag.home_flag) planner.synchronize(); // Wait for planner moves to finish! - wait_for_heatup = wait_for_user = false; // Stop waiting for heating/user - card.flag.abort_sd_printing = true; // Let the main loop handle SD abort - dwin_abort_flag = true; // Reset feedrate, return to Home - #ifdef ACTION_ON_CANCEL - host_action_cancel(); - #endif - Popup_Window_Home(true); - } - else - Goto_PrintProcess(); // cancel stop - } - } - DWIN_UpdateLCD(); -} - -inline void Draw_Move_Menu() { - Clear_Main_Window(); - - if (HMI_IsChinese()) { - DWIN_Frame_TitleCopy(1, 192, 1, 233, 14); // "Move" - DWIN_Frame_AreaCopy(1, 58, 118, 106, 132, LBLX, MBASE(1)); - DWIN_Frame_AreaCopy(1, 109, 118, 157, 132, LBLX, MBASE(2)); - DWIN_Frame_AreaCopy(1, 160, 118, 209, 132, LBLX, MBASE(3)); - #if HAS_HOTEND - DWIN_Frame_AreaCopy(1, 212, 118, 253, 131, LBLX, MBASE(4)); - #endif - } - else { - #ifdef USE_STRING_HEADINGS - Draw_Title(GET_TEXT_F(MSG_MOVE_AXIS)); - #else - DWIN_Frame_TitleCopy(1, 231, 2, 265, 12); // "Move" - #endif - draw_move_en(MBASE(1)); say_x(36, MBASE(1)); // "Move X" - draw_move_en(MBASE(2)); say_y(36, MBASE(2)); // "Move Y" - draw_move_en(MBASE(3)); say_z(36, MBASE(3)); // "Move Z" - #if HAS_HOTEND - DWIN_Frame_AreaCopy(1, 123, 192, 176, 202, LBLX, MBASE(4)); // "Extruder" - #endif - } - - Draw_Back_First(select_axis.now == 0); - if (select_axis.now) 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); -} - -#include "../../../libs/buzzer.h" - -void HMI_AudioFeedback(const bool success=true) { - if (success) { - buzzer.tone(100, 659); - buzzer.tone(10, 0); - buzzer.tone(100, 698); - } - else - buzzer.tone(40, 440); -} - -/* Prepare */ -void HMI_Prepare() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - - // Avoid flicker by updating only the previous menu - if (encoder_diffState == ENCODER_DIFF_CW) { - if (select_prepare.inc(1 + PREPARE_CASE_TOTAL)) { - if (select_prepare.now > MROWS && select_prepare.now > index_prepare) { - index_prepare = select_prepare.now; - - // Scroll up and draw a blank bottom line - Scroll_Menu(DWIN_SCROLL_UP); - Draw_Menu_Icon(MROWS, ICON_Axis + select_prepare.now - 1); - - // Draw "More" icon for sub-menus - if (index_prepare < 7) Draw_More_Icon(MROWS - index_prepare + 1); - - #if HAS_HOTEND - if (index_prepare == PREPARE_CASE_ABS) Item_Prepare_ABS(MROWS); - #endif - #if HAS_PREHEAT - if (index_prepare == PREPARE_CASE_COOL) Item_Prepare_Cool(MROWS); - #endif - if (index_prepare == PREPARE_CASE_LANG) Item_Prepare_Lang(MROWS); - } - else { - Move_Highlight(1, select_prepare.now + MROWS - index_prepare); - } - } - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - if (select_prepare.dec()) { - if (select_prepare.now < index_prepare - MROWS) { - index_prepare--; - Scroll_Menu(DWIN_SCROLL_DOWN); - - if (index_prepare == MROWS) - Draw_Back_First(); - else - Draw_Menu_Line(0, ICON_Axis + select_prepare.now - 1); - - if (index_prepare < 7) Draw_More_Icon(MROWS - index_prepare + 1); - - if (index_prepare == 6) Item_Prepare_Move(0); - else if (index_prepare == 7) Item_Prepare_Disable(0); - else if (index_prepare == 8) Item_Prepare_Home(0); - } - else { - Move_Highlight(-1, select_prepare.now + MROWS - index_prepare); - } - } - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - switch (select_prepare.now) { - case 0: // Back - select_page.set(1); - Goto_MainMenu(); - break; - case PREPARE_CASE_MOVE: // Axis move - checkkey = AxisMove; - select_axis.reset(); - Draw_Move_Menu(); - - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 216, MBASE(1), current_position.x * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 216, MBASE(2), current_position.y * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 216, MBASE(3), current_position.z * MINUNITMULT); - #if HAS_HOTEND - queue.inject_P(PSTR("G92 E0")); - current_position.e = HMI_ValueStruct.Move_E_scale = 0; - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, 1, 216, MBASE(4), 0); - #endif - break; - case PREPARE_CASE_DISA: // Disable steppers - queue.inject_P(PSTR("M84")); - break; - case PREPARE_CASE_HOME: // Homing - checkkey = Last_Prepare; - index_prepare = MROWS; - queue.inject_P(PSTR("G28")); // G28 will set home_flag - Popup_Window_Home(); - break; - #if HAS_ZOFFSET_ITEM - case PREPARE_CASE_ZOFF: // Z-offset - #if EITHER(HAS_BED_PROBE, BABYSTEPPING) - checkkey = Homeoffset; - HMI_ValueStruct.show_mode = -4; - HMI_ValueStruct.offset_value = BABY_Z_VAR * 100; - DWIN_Draw_Signed_Float(font8x16, Select_Color, 2, 2, 202, MBASE(PREPARE_CASE_ZOFF + MROWS - index_prepare), HMI_ValueStruct.offset_value); - EncoderRate.enabled = true; - #else - // Apply workspace offset, making the current position 0,0,0 - queue.inject_P(PSTR("G92 X0 Y0 Z0")); - HMI_AudioFeedback(); - #endif - break; - #endif - #if HAS_HOTEND - case PREPARE_CASE_PLA: // PLA preheat - thermalManager.setTargetHotend(ui.material_preset[0].hotend_temp, 0); - thermalManager.setTargetBed(ui.material_preset[0].bed_temp); - thermalManager.set_fan_speed(0, ui.material_preset[0].fan_speed); - break; - case PREPARE_CASE_ABS: // ABS preheat - thermalManager.setTargetHotend(ui.material_preset[1].hotend_temp, 0); - thermalManager.setTargetBed(ui.material_preset[1].bed_temp); - thermalManager.set_fan_speed(0, ui.material_preset[1].fan_speed); - break; - #endif - #if HAS_PREHEAT - case PREPARE_CASE_COOL: // Cool - TERN_(HAS_FAN, thermalManager.zero_fan_speeds()); - #if HAS_HOTEND || HAS_HEATED_BED - thermalManager.disable_all_heaters(); - #endif - break; - #endif - case PREPARE_CASE_LANG: // Toggle Language - HMI_ToggleLanguage(); - Draw_Prepare_Menu(); - break; - default: break; - } - } - DWIN_UpdateLCD(); -} - -void Draw_Temperature_Menu() { - Clear_Main_Window(); - - if (HMI_IsChinese()) { - DWIN_Frame_TitleCopy(1, 236, 2, 263, 13); // "Temperature" - #if HAS_HOTEND - DWIN_Frame_AreaCopy(1, 1, 134, 56, 146, LBLX, MBASE(TEMP_CASE_TEMP)); - #endif - #if HAS_HEATED_BED - DWIN_Frame_AreaCopy(1, 58, 134, 113, 146, LBLX, MBASE(TEMP_CASE_BED)); - #endif - #if HAS_FAN - DWIN_Frame_AreaCopy(1, 115, 134, 170, 146, LBLX, MBASE(TEMP_CASE_FAN)); - #endif - #if HAS_HOTEND - DWIN_Frame_AreaCopy(1, 100, 89, 178, 101, LBLX, MBASE(TEMP_CASE_PLA)); - DWIN_Frame_AreaCopy(1, 180, 89, 260, 100, LBLX, MBASE(TEMP_CASE_ABS)); - #endif - } - else { - #ifdef USE_STRING_HEADINGS - Draw_Title(GET_TEXT_F(MSG_TEMPERATURE)); - #if HAS_HOTEND - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(TEMP_CASE_TEMP), GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND)); - #endif - #if HAS_HEATED_BED - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(TEMP_CASE_BED), GET_TEXT_F(MSG_UBL_SET_TEMP_BED)); - #endif - #if HAS_FAN - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(TEMP_CASE_FAN), GET_TEXT_F(MSG_FAN_SPEED)); - #endif - #if HAS_HOTEND - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(TEMP_CASE_PLA), F("PLA Preheat Settings")); - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(TEMP_CASE_ABS), F("ABS Preheat Settings")); - #endif - #else - DWIN_Frame_TitleCopy(1, 56, 16, 141, 28); // "Temperature" - #if HAS_HOTEND - DWIN_Frame_AreaCopy(1, 197, 104, 238, 114, LBLX, MBASE(TEMP_CASE_TEMP)); // Nozzle... - DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 44, MBASE(TEMP_CASE_TEMP)); // ...Temperature - #endif - #if HAS_HEATED_BED - DWIN_Frame_AreaCopy(1, 240, 104, 264, 114, LBLX, MBASE(TEMP_CASE_BED)); // Bed... - DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 27, MBASE(TEMP_CASE_BED)); // ...Temperature - #endif - #if HAS_FAN - DWIN_Frame_AreaCopy(1, 0, 119, 64, 132, LBLX, MBASE(TEMP_CASE_FAN)); // Fan speed - #endif - #if HAS_HOTEND - DWIN_Frame_AreaCopy(1, 107, 76, 156, 86, LBLX, MBASE(TEMP_CASE_PLA)); // Preheat... - DWIN_Frame_AreaCopy(1, 157, 76, 181, 86, LBLX + 52, MBASE(TEMP_CASE_PLA)); // ...PLA - DWIN_Frame_AreaCopy(1, 131, 119, 182, 132, LBLX + 79, MBASE(TEMP_CASE_PLA)); // PLA setting - DWIN_Frame_AreaCopy(1, 107, 76, 156, 86, LBLX, MBASE(TEMP_CASE_ABS)); // Preheat... - DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX + 52, MBASE(TEMP_CASE_ABS)); // ...ABS - DWIN_Frame_AreaCopy(1, 131, 119, 182, 132, LBLX + 81, MBASE(TEMP_CASE_ABS)); // ABS setting - #endif - #endif - } - - Draw_Back_First(select_temp.now == 0); - if (select_temp.now) Draw_Menu_Cursor(select_temp.now); - - // Draw icons and lines - uint8_t i = 0; - #define _TMENU_ICON(N) Draw_Menu_Line(++i, ICON_SetEndTemp + (N) - 1) - #if HAS_HOTEND - _TMENU_ICON(TEMP_CASE_TEMP); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), thermalManager.temp_hotend[0].target); - #endif - #if HAS_HEATED_BED - _TMENU_ICON(TEMP_CASE_BED); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), thermalManager.temp_bed.target); - #endif - #if HAS_FAN - _TMENU_ICON(TEMP_CASE_FAN); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), thermalManager.fan_speed[0]); - #endif - #if HAS_HOTEND - // PLA/ABS items have submenus - _TMENU_ICON(TEMP_CASE_PLA); - Draw_More_Icon(i); - _TMENU_ICON(TEMP_CASE_ABS); - Draw_More_Icon(i); - #endif -} - -/* Control */ -void HMI_Control() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - - // Avoid flicker by updating only the previous menu - if (encoder_diffState == ENCODER_DIFF_CW) { - if (select_control.inc(1 + CONTROL_CASE_TOTAL)) { - if (select_control.now > MROWS && select_control.now > index_control) { - index_control = select_control.now; - Scroll_Menu(DWIN_SCROLL_UP); - Draw_Menu_Icon(MROWS, ICON_Temperature + index_control - 1); - Draw_More_Icon(CONTROL_CASE_TEMP + MROWS - index_control); // Temperature > - Draw_More_Icon(CONTROL_CASE_MOVE + MROWS - index_control); // Motion > - if (index_control > MROWS) { - Draw_More_Icon(CONTROL_CASE_INFO + MROWS - index_control); // Info > - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 231, 104, 258, 116, LBLX, MBASE(CONTROL_CASE_INFO - 1)); - else - DWIN_Frame_AreaCopy(1, 0, 104, 24, 114, LBLX, MBASE(CONTROL_CASE_INFO - 1)); - } - } - else { - Move_Highlight(1, select_control.now + MROWS - index_control); - } - } - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - if (select_control.dec()) { - if (select_control.now < index_control - MROWS) { - index_control--; - Scroll_Menu(DWIN_SCROLL_DOWN); - if (index_control == MROWS) - Draw_Back_First(); - else - Draw_Menu_Line(0, ICON_Temperature + select_control.now - 1); - Draw_More_Icon(0 + MROWS - index_control + 1); // Temperature > - Draw_More_Icon(1 + MROWS - index_control + 1); // Motion > - } - else { - Move_Highlight(-1, select_control.now + MROWS - index_control); - } - } - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - switch (select_control.now) { - case 0: // Back - select_page.set(2); - Goto_MainMenu(); - break; - case CONTROL_CASE_TEMP: // Temperature - checkkey = TemperatureID; - HMI_ValueStruct.show_mode = -1; - select_temp.reset(); - Draw_Temperature_Menu(); - break; - case CONTROL_CASE_MOVE: // Motion - checkkey = Motion; - select_motion.reset(); - Draw_Motion_Menu(); - break; - #if ENABLED(EEPROM_SETTINGS) - case CONTROL_CASE_SAVE: { // Write EEPROM - const bool success = settings.save(); - HMI_AudioFeedback(success); - } break; - case CONTROL_CASE_LOAD: { // Read EEPROM - const bool success = settings.load(); - HMI_AudioFeedback(success); - } break; - case CONTROL_CASE_RESET: // Reset EEPROM - settings.reset(); - HMI_AudioFeedback(); - break; - #endif - case CONTROL_CASE_INFO: // Info - checkkey = Info; - Draw_Info_Menu(); - break; - default: break; - } - } - DWIN_UpdateLCD(); -} - - -#if HAS_ONESTEP_LEVELING - - /* Leveling */ - void HMI_Leveling() { - Popup_Window_Leveling(); - DWIN_UpdateLCD(); - queue.inject_P(PSTR("G28O\nG29")); - } - -#endif - -/* Axis Move */ -void HMI_AxisMove() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - - #if ENABLED(PREVENT_COLD_EXTRUSION) - // popup window resume - if (HMI_flag.ETempTooLow_flag) { - if (encoder_diffState == ENCODER_DIFF_ENTER) { - HMI_flag.ETempTooLow_flag = false; - current_position.e = HMI_ValueStruct.Move_E_scale = 0; - Draw_Move_Menu(); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 216, MBASE(1), HMI_ValueStruct.Move_X_scale); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 216, MBASE(2), HMI_ValueStruct.Move_Y_scale); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 216, MBASE(3), HMI_ValueStruct.Move_Z_scale); - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, 1, 216, MBASE(4), 0); - DWIN_UpdateLCD(); - } - return; - } - #endif - - // Avoid flicker by updating only the previous menu - if (encoder_diffState == ENCODER_DIFF_CW) { - if (select_axis.inc(1 + 3 + ENABLED(HAS_HOTEND))) Move_Highlight(1, select_axis.now); - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - if (select_axis.dec()) Move_Highlight(-1, select_axis.now); - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - switch (select_axis.now) { - case 0: // Back - checkkey = Prepare; - select_prepare.set(1); - index_prepare = MROWS; - Draw_Prepare_Menu(); - break; - case 1: // X axis move - checkkey = Move_X; - HMI_ValueStruct.Move_X_scale = current_position.x * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 216, MBASE(1), HMI_ValueStruct.Move_X_scale); - EncoderRate.enabled = true; - break; - case 2: // Y axis move - checkkey = Move_Y; - HMI_ValueStruct.Move_Y_scale = current_position.y * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 216, MBASE(2), HMI_ValueStruct.Move_Y_scale); - EncoderRate.enabled = true; - break; - case 3: // Z axis move - checkkey = Move_Z; - HMI_ValueStruct.Move_Z_scale = current_position.z * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 216, MBASE(3), HMI_ValueStruct.Move_Z_scale); - EncoderRate.enabled = true; - break; - #if HAS_HOTEND - case 4: // Extruder - // window tips - #ifdef PREVENT_COLD_EXTRUSION - if (thermalManager.temp_hotend[0].celsius < EXTRUDE_MINTEMP) { - HMI_flag.ETempTooLow_flag = true; - Popup_Window_ETempTooLow(); - DWIN_UpdateLCD(); - return; - } - #endif - checkkey = Extruder; - HMI_ValueStruct.Move_E_scale = current_position.e * MINUNITMULT; - DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, 1, 216, MBASE(4), HMI_ValueStruct.Move_E_scale); - EncoderRate.enabled = true; - break; - #endif - } - } - DWIN_UpdateLCD(); -} - -/* TemperatureID */ -void HMI_Temperature() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - - // Avoid flicker by updating only the previous menu - if (encoder_diffState == ENCODER_DIFF_CW) { - if (select_temp.inc(1 + TEMP_CASE_TOTAL)) Move_Highlight(1, select_temp.now); - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - if (select_temp.dec()) Move_Highlight(-1, select_temp.now); - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - switch (select_temp.now) { - case 0: // Back - checkkey = Control; - select_control.set(1); - index_control = MROWS; - Draw_Control_Menu(); - break; - #if HAS_HOTEND - case TEMP_CASE_TEMP: // Nozzle temperature - checkkey = ETemp; - HMI_ValueStruct.E_Temp = thermalManager.temp_hotend[0].target; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(1), thermalManager.temp_hotend[0].target); - EncoderRate.enabled = true; - break; - #endif - #if HAS_HEATED_BED - case TEMP_CASE_BED: // Bed temperature - checkkey = BedTemp; - HMI_ValueStruct.Bed_Temp = thermalManager.temp_bed.target; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(2), thermalManager.temp_bed.target); - EncoderRate.enabled = true; - break; - #endif - #if HAS_FAN - case TEMP_CASE_FAN: // Fan speed - checkkey = FanSpeed; - HMI_ValueStruct.Fan_speed = thermalManager.fan_speed[0]; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(3), thermalManager.fan_speed[0]); - EncoderRate.enabled = true; - break; - #endif - #if HAS_HOTEND - case TEMP_CASE_PLA: { // PLA preheat setting - checkkey = PLAPreheat; - select_PLA.reset(); - HMI_ValueStruct.show_mode = -2; - - Clear_Main_Window(); - - if (HMI_IsChinese()) { - DWIN_Frame_TitleCopy(1, 59, 16, 139, 29); // "PLA Settings" - DWIN_Frame_AreaCopy(1, 100, 89, 124, 101, LBLX, MBASE(PREHEAT_CASE_TEMP)); - DWIN_Frame_AreaCopy(1, 1, 134, 56, 146, LBLX + 24, MBASE(PREHEAT_CASE_TEMP)); // PLA nozzle temp - #if HAS_HEATED_BED - DWIN_Frame_AreaCopy(1, 100, 89, 124, 101, LBLX, MBASE(PREHEAT_CASE_BED)); - DWIN_Frame_AreaCopy(1, 58, 134, 113, 146, LBLX + 24, MBASE(PREHEAT_CASE_BED)); // PLA bed temp - #endif - #if HAS_FAN - DWIN_Frame_AreaCopy(1, 100, 89, 124, 101, LBLX, MBASE(PREHEAT_CASE_FAN)); - DWIN_Frame_AreaCopy(1, 115, 134, 170, 146, LBLX + 24, MBASE(PREHEAT_CASE_FAN)); // PLA fan speed - #endif - #if ENABLED(EEPROM_SETTINGS) - DWIN_Frame_AreaCopy(1, 72, 148, 151, 162, LBLX, MBASE(PREHEAT_CASE_SAVE)); // Save PLA configuration - #endif - } - else { - #ifdef USE_STRING_HEADINGS - Draw_Title("PLA Settings"); // TODO: GET_TEXT_F - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(PREHEAT_CASE_TEMP), F("Nozzle Temp")); - #if HAS_HEATED_BED - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(PREHEAT_CASE_BED), F("Bed Temp")); - #endif - #if HAS_FAN - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(PREHEAT_CASE_FAN), GET_TEXT_F(MSG_FAN_SPEED)); - #endif - #if ENABLED(EEPROM_SETTINGS) - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(PREHEAT_CASE_SAVE), GET_TEXT_F(MSG_STORE_EEPROM)); - #endif - #else - DWIN_Frame_TitleCopy(1, 56, 16, 141, 28); // "PLA Settings" - DWIN_Frame_AreaCopy(1, 157, 76, 181, 86, LBLX, MBASE(PREHEAT_CASE_TEMP)); - DWIN_Frame_AreaCopy(1, 197, 104, 238, 114, LBLX + 27, MBASE(PREHEAT_CASE_TEMP)); - DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 71, MBASE(PREHEAT_CASE_TEMP)); // PLA nozzle temp - #if HAS_HEATED_BED - DWIN_Frame_AreaCopy(1, 157, 76, 181, 86, LBLX, MBASE(PREHEAT_CASE_BED) + 3); - DWIN_Frame_AreaCopy(1, 240, 104, 264, 114, LBLX + 27, MBASE(PREHEAT_CASE_BED) + 3); - DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 54, MBASE(PREHEAT_CASE_BED) + 3); // PLA bed temp - #endif - #if HAS_FAN - DWIN_Frame_AreaCopy(1, 157, 76, 181, 86, LBLX, MBASE(PREHEAT_CASE_FAN)); - DWIN_Frame_AreaCopy(1, 0, 119, 64, 132, LBLX + 27, MBASE(PREHEAT_CASE_FAN)); // PLA fan speed - #endif - #if ENABLED(EEPROM_SETTINGS) - DWIN_Frame_AreaCopy(1, 97, 165, 229, 177, LBLX, MBASE(PREHEAT_CASE_SAVE)); // Save PLA configuration - #endif - #endif - } - - Draw_Back_First(); - - uint8_t i = 0; - Draw_Menu_Line(++i, ICON_SetEndTemp); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), ui.material_preset[0].hotend_temp); - #if HAS_HEATED_BED - Draw_Menu_Line(++i, ICON_SetBedTemp); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), ui.material_preset[0].bed_temp); - #endif - #if HAS_FAN - Draw_Menu_Line(++i, ICON_FanSpeed); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), ui.material_preset[0].fan_speed); - #endif - #if ENABLED(EEPROM_SETTINGS) - Draw_Menu_Line(++i, ICON_WriteEEPROM); - #endif - } break; - - case TEMP_CASE_ABS: { // ABS preheat setting - checkkey = ABSPreheat; - select_ABS.reset(); - HMI_ValueStruct.show_mode = -3; - - Clear_Main_Window(); - - if (HMI_IsChinese()) { - DWIN_Frame_TitleCopy(1, 142, 16, 223, 29); // "ABS Settings" - - DWIN_Frame_AreaCopy(1, 180, 89, 204, 100, LBLX, MBASE(PREHEAT_CASE_TEMP)); - DWIN_Frame_AreaCopy(1, 1, 134, 56, 146, LBLX + 24, MBASE(PREHEAT_CASE_TEMP)); // ABS nozzle temp - #if HAS_HEATED_BED - DWIN_Frame_AreaCopy(1, 180, 89, 204, 100, LBLX, MBASE(PREHEAT_CASE_BED)); - DWIN_Frame_AreaCopy(1, 58, 134, 113, 146, LBLX + 24, MBASE(PREHEAT_CASE_BED)); // ABS bed temp - #endif - #if HAS_FAN - DWIN_Frame_AreaCopy(1, 180, 89, 204, 100, LBLX, MBASE(PREHEAT_CASE_FAN)); - DWIN_Frame_AreaCopy(1, 115, 134, 170, 146, LBLX + 24, MBASE(PREHEAT_CASE_FAN)); // ABS fan speed - #endif - #if ENABLED(EEPROM_SETTINGS) - DWIN_Frame_AreaCopy(1, 72, 148, 151, 162, LBLX, MBASE(PREHEAT_CASE_SAVE)); - DWIN_Frame_AreaCopy(1, 180, 89, 204, 100, LBLX + 28, MBASE(PREHEAT_CASE_SAVE) + 2); // Save ABS configuration - #endif - } - else { - #ifdef USE_STRING_HEADINGS - Draw_Title("ABS Settings"); // TODO: GET_TEXT_F - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(PREHEAT_CASE_TEMP), F("Nozzle Temp")); - #if HAS_HEATED_BED - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(PREHEAT_CASE_BED), F("Bed Temp")); - #endif - #if HAS_FAN - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(PREHEAT_CASE_FAN), GET_TEXT_F(MSG_FAN_SPEED)); - #endif - #if ENABLED(EEPROM_SETTINGS) - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(PREHEAT_CASE_SAVE), GET_TEXT_F(MSG_STORE_EEPROM)); - #endif - #else - DWIN_Frame_TitleCopy(1, 56, 16, 141, 28); // "ABS Settings" - DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX, MBASE(PREHEAT_CASE_TEMP)); - DWIN_Frame_AreaCopy(1, 197, 104, 238, 114, LBLX + 27, MBASE(PREHEAT_CASE_TEMP)); - DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 71, MBASE(PREHEAT_CASE_TEMP)); // ABS nozzle temp - #if HAS_HEATED_BED - DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX, MBASE(PREHEAT_CASE_BED) + 3); - DWIN_Frame_AreaCopy(1, 240, 104, 264, 114, LBLX + 27, MBASE(PREHEAT_CASE_BED) + 3); - DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 54, MBASE(PREHEAT_CASE_BED) + 3); // ABS bed temp - #endif - #if HAS_FAN - DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX, MBASE(PREHEAT_CASE_FAN)); - DWIN_Frame_AreaCopy(1, 0, 119, 64, 132, LBLX + 27, MBASE(PREHEAT_CASE_FAN)); // ABS fan speed - #endif - #if ENABLED(EEPROM_SETTINGS) - DWIN_Frame_AreaCopy(1, 97, 165, 229, 177, LBLX, MBASE(PREHEAT_CASE_SAVE)); - DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX + 33, MBASE(PREHEAT_CASE_SAVE)); // Save ABS configuration - #endif - #endif - } - - Draw_Back_First(); - - uint8_t i = 0; - Draw_Menu_Line(++i, ICON_SetEndTemp); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), ui.material_preset[1].hotend_temp); - #if HAS_HEATED_BED - Draw_Menu_Line(++i, ICON_SetBedTemp); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), ui.material_preset[1].bed_temp); - #endif - #if HAS_FAN - Draw_Menu_Line(++i, ICON_FanSpeed); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), ui.material_preset[1].fan_speed); - #endif - #if ENABLED(EEPROM_SETTINGS) - Draw_Menu_Line(++i, ICON_WriteEEPROM); - #endif - - } break; - - #endif // HAS_HOTEND - } - } - DWIN_UpdateLCD(); -} - -inline void Draw_Max_Speed_Menu() { - Clear_Main_Window(); - - if (HMI_IsChinese()) { - DWIN_Frame_TitleCopy(1, 1, 16, 28, 28); // "Max Speed (mm/s)" - - auto say_max_speed = [](const uint16_t row) { - DWIN_Frame_AreaCopy(1, 173, 133, 228, 147, LBLX, row); // "Max speed" - }; - - say_max_speed(MBASE(1)); // "Max speed" - DWIN_Frame_AreaCopy(1, 229, 133, 236, 147, LBLX + 58, MBASE(1)); // X - say_max_speed(MBASE(2)); // "Max speed" - DWIN_Frame_AreaCopy(1, 1, 150, 7, 160, LBLX + 58, MBASE(2) + 3); // Y - say_max_speed(MBASE(3)); // "Max speed" - DWIN_Frame_AreaCopy(1, 9, 150, 16, 160, LBLX + 58, MBASE(3) + 3); // Z - #if HAS_HOTEND - say_max_speed(MBASE(4)); // "Max speed" - DWIN_Frame_AreaCopy(1, 18, 150, 25, 160, LBLX + 58, MBASE(4) + 3); // E - #endif - } - else { - #ifdef USE_STRING_HEADINGS - Draw_Title("Max Speed (mm/s)"); // TODO: GET_TEXT_F - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(1), F("Max Feedrate X")); - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(2), F("Max Feedrate Y")); - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(3), F("Max Feedrate Z")); - #if HAS_HOTEND - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(4), F("Max Feedrate E")); - #endif - #else - DWIN_Frame_TitleCopy(1, 144, 16, 189, 26); // "Max Speed (mm/s)" - - draw_max_en(MBASE(1)); // "Max" - DWIN_Frame_AreaCopy(1, 184, 119, 234, 132, LBLX + 27, MBASE(1)); // "Speed X" - - draw_max_en(MBASE(2)); // "Max" - draw_speed_en(27, MBASE(2)); // "Speed" - say_y(70, MBASE(2)); // "Y" - - draw_max_en(MBASE(3)); // "Max" - draw_speed_en(27, MBASE(3)); // "Speed" - say_z(70, MBASE(3)); // "Z" - - #if HAS_HOTEND - draw_max_en(MBASE(4)); // "Max" - draw_speed_en(27, MBASE(4)); // "Speed" - say_e(70, MBASE(4)); // "E" - #endif - #endif - } - - Draw_Back_First(); - LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_MaxSpeedX + i); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(1), planner.settings.max_feedrate_mm_s[X_AXIS]); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(2), planner.settings.max_feedrate_mm_s[Y_AXIS]); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(3), planner.settings.max_feedrate_mm_s[Z_AXIS]); - #if HAS_HOTEND - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(4), planner.settings.max_feedrate_mm_s[E_AXIS]); - #endif -} - -inline void Draw_Max_Accel_Menu() { - Clear_Main_Window(); - - if (HMI_IsChinese()) { - DWIN_Frame_TitleCopy(1, 1, 16, 28, 28); // "Acceleration" - - DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX, MBASE(1)); - DWIN_Frame_AreaCopy(1, 28, 149, 69, 161, LBLX + 27, MBASE(1) + 1); - DWIN_Frame_AreaCopy(1, 229, 133, 236, 147, LBLX + 71, MBASE(1)); // Max acceleration X - DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX, MBASE(2)); - DWIN_Frame_AreaCopy(1, 28, 149, 69, 161, LBLX + 27, MBASE(2) + 1); - DWIN_Frame_AreaCopy(1, 1, 150, 7, 160, LBLX + 71, MBASE(2) + 2); // Max acceleration Y - DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX, MBASE(3)); - DWIN_Frame_AreaCopy(1, 28, 149, 69, 161, LBLX + 27, MBASE(3) + 1); - DWIN_Frame_AreaCopy(1, 9, 150, 16, 160, LBLX + 71, MBASE(3) + 2); // Max acceleration Z - #if HAS_HOTEND - DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX, MBASE(4)); - DWIN_Frame_AreaCopy(1, 28, 149, 69, 161, LBLX + 27, MBASE(4) + 1); - DWIN_Frame_AreaCopy(1, 18, 150, 25, 160, LBLX + 71, MBASE(4) + 2); // Max acceleration E - #endif - } - else { - #ifdef USE_STRING_HEADINGS - Draw_Title(GET_TEXT_F(MSG_ACCELERATION)); - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(1), F("Max Accel X")); - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(2), F("Max Accel Y")); - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(3), F("Max Accel Z")); - #if HAS_HOTEND - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(4), F("Max Accel E")); - #endif - #else - DWIN_Frame_TitleCopy(1, 144, 16, 189, 26); // "Acceleration" - draw_max_accel_en(MBASE(1)); say_x(108, MBASE(1)); // "Max Acceleration X" - draw_max_accel_en(MBASE(2)); say_y(108, MBASE(2)); // "Max Acceleration Y" - draw_max_accel_en(MBASE(3)); say_z(108, MBASE(3)); // "Max Acceleration Z" - #if HAS_HOTEND - draw_max_accel_en(MBASE(4)); say_e(108, MBASE(4)); // "Max Acceleration E" - #endif - #endif - } - - Draw_Back_First(); - LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_MaxAccX + i); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(1), planner.settings.max_acceleration_mm_per_s2[X_AXIS]); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(2), planner.settings.max_acceleration_mm_per_s2[Y_AXIS]); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(3), planner.settings.max_acceleration_mm_per_s2[Z_AXIS]); - #if HAS_HOTEND - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(4), planner.settings.max_acceleration_mm_per_s2[E_AXIS]); - #endif -} - -inline void Draw_Max_Jerk_Menu() { - Clear_Main_Window(); - - if (HMI_IsChinese()) { - DWIN_Frame_TitleCopy(1, 1, 16, 28, 28); // "Jerk" - - DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX , MBASE(1)); - DWIN_Frame_AreaCopy(1, 1, 180, 28, 192, LBLX + 27, MBASE(1) + 1); - DWIN_Frame_AreaCopy(1, 202, 133, 228, 147, LBLX + 53, MBASE(1)); - DWIN_Frame_AreaCopy(1, 229, 133, 236, 147, LBLX + 83, MBASE(1)); // Max Jerk speed X - DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX , MBASE(2)); - DWIN_Frame_AreaCopy(1, 1, 180, 28, 192, LBLX + 27, MBASE(2) + 1); - DWIN_Frame_AreaCopy(1, 202, 133, 228, 147, LBLX + 53, MBASE(2)); - DWIN_Frame_AreaCopy(1, 1, 150, 7, 160, LBLX + 83, MBASE(2) + 3); // Max Jerk speed Y - DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX , MBASE(3)); - DWIN_Frame_AreaCopy(1, 1, 180, 28, 192, LBLX + 27, MBASE(3) + 1); - DWIN_Frame_AreaCopy(1, 202, 133, 228, 147, LBLX + 53, MBASE(3)); - DWIN_Frame_AreaCopy(1, 9, 150, 16, 160, LBLX + 83, MBASE(3) + 3); // Max Jerk speed Z - #if HAS_HOTEND - DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX , MBASE(4)); - DWIN_Frame_AreaCopy(1, 1, 180, 28, 192, LBLX + 27, MBASE(4) + 1); - DWIN_Frame_AreaCopy(1, 202, 133, 228, 147, LBLX + 53, MBASE(4)); - DWIN_Frame_AreaCopy(1, 18, 150, 25, 160, LBLX + 83, MBASE(4) + 3); // Max Jerk speed E - #endif - } - else { - #ifdef USE_STRING_HEADINGS - Draw_Title(GET_TEXT_F(MSG_JERK)); - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(1), F("Max Jerk X")); - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(2), F("Max Jerk Y")); - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(3), F("Max Jerk Z")); - #if HAS_HOTEND - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(4), F("Max Jerk E")); - #endif - #else - DWIN_Frame_TitleCopy(1, 144, 16, 189, 26); // "Jerk" - draw_max_en(MBASE(1)); // "Max" - draw_jerk_en(MBASE(1)); // "Jerk" - draw_speed_en(72, MBASE(1)); // "Speed" - say_x(115, MBASE(1)); // "X" - - draw_max_en(MBASE(2)); // "Max" - draw_jerk_en(MBASE(2)); // "Jerk" - draw_speed_en(72, MBASE(2)); // "Speed" - say_y(115, MBASE(2)); // "Y" - - draw_max_en(MBASE(3)); // "Max" - draw_jerk_en(MBASE(3)); // "Jerk" - draw_speed_en(72, MBASE(3)); // "Speed" - say_z(115, MBASE(3)); // "Z" - - #if HAS_HOTEND - draw_max_en(MBASE(4)); // "Max" - draw_jerk_en(MBASE(4)); // "Jerk" - draw_speed_en(72, MBASE(4)); // "Speed" - say_e(115, MBASE(4)); // "E" - #endif - #endif - } - - Draw_Back_First(); - LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_MaxSpeedJerkX + i); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 210, MBASE(1), planner.max_jerk[X_AXIS] * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 210, MBASE(2), planner.max_jerk[Y_AXIS] * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 210, MBASE(3), planner.max_jerk[Z_AXIS] * MINUNITMULT); - #if HAS_HOTEND - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 210, MBASE(4), planner.max_jerk[E_AXIS] * MINUNITMULT); - #endif -} - -inline void Draw_Steps_Menu() { - Clear_Main_Window(); - - if (HMI_IsChinese()) { - DWIN_Frame_TitleCopy(1, 1, 16, 28, 28); // "Steps per mm" - - DWIN_Frame_AreaCopy(1, 153, 148, 194, 161, LBLX, MBASE(1)); - DWIN_Frame_AreaCopy(1, 229, 133, 236, 147, LBLX + 44, MBASE(1)); // Transmission Ratio X - DWIN_Frame_AreaCopy(1, 153, 148, 194, 161, LBLX, MBASE(2)); - DWIN_Frame_AreaCopy(1, 1, 150, 7, 160, LBLX + 44, MBASE(2) + 3); // Transmission Ratio Y - DWIN_Frame_AreaCopy(1, 153, 148, 194, 161, LBLX, MBASE(3)); - DWIN_Frame_AreaCopy(1, 9, 150, 16, 160, LBLX + 44, MBASE(3) + 3); // Transmission Ratio Z - #if HAS_HOTEND - DWIN_Frame_AreaCopy(1, 153, 148, 194, 161, LBLX, MBASE(4)); - DWIN_Frame_AreaCopy(1, 18, 150, 25, 160, LBLX + 44, MBASE(4) + 3); // Transmission Ratio E - #endif - } - else { - #ifdef USE_STRING_HEADINGS - Draw_Title(GET_TEXT_F(MSG_STEPS_PER_MM)); - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(1), F("Steps/mm X")); - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(2), F("Steps/mm Y")); - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(3), F("Steps/mm Z")); - #if HAS_HOTEND - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(4), F("Steps/mm E")); - #endif - #else - DWIN_Frame_TitleCopy(1, 144, 16, 189, 26); // "Steps per mm" - draw_steps_per_mm(MBASE(1)); say_x(103, MBASE(1)); // "Steps-per-mm X" - draw_steps_per_mm(MBASE(2)); say_y(103, MBASE(2)); // "Y" - draw_steps_per_mm(MBASE(3)); say_z(103, MBASE(3)); // "Z" - #if HAS_HOTEND - draw_steps_per_mm(MBASE(4)); say_e(103, MBASE(4)); // "E" - #endif - #endif - } - - Draw_Back_First(); - LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_StepX + i); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 210, MBASE(1), planner.settings.axis_steps_per_mm[X_AXIS] * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 210, MBASE(2), planner.settings.axis_steps_per_mm[Y_AXIS] * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 210, MBASE(3), planner.settings.axis_steps_per_mm[Z_AXIS] * MINUNITMULT); - #if HAS_HOTEND - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 210, MBASE(4), planner.settings.axis_steps_per_mm[E_AXIS] * MINUNITMULT); - #endif -} - -/* Motion */ -void HMI_Motion() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - - // Avoid flicker by updating only the previous menu - if (encoder_diffState == ENCODER_DIFF_CW) { - if (select_motion.inc(1 + MOTION_CASE_TOTAL)) Move_Highlight(1, select_motion.now); - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - if (select_motion.dec()) Move_Highlight(-1, select_motion.now); - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - switch (select_motion.now) { - case 0: // Back - checkkey = Control; - select_control.set(CONTROL_CASE_MOVE); - index_control = MROWS; - Draw_Control_Menu(); - break; - case MOTION_CASE_RATE: // Max speed - checkkey = MaxSpeed; - select_speed.reset(); - Draw_Max_Speed_Menu(); - break; - case MOTION_CASE_ACCEL: // Max acceleration - checkkey = MaxAcceleration; - select_acc.reset(); - Draw_Max_Accel_Menu(); - break; - #if HAS_CLASSIC_JERK - case MOTION_CASE_JERK: // Max jerk - checkkey = MaxJerk; - select_jerk.reset(); - Draw_Max_Jerk_Menu(); - break; - #endif - case MOTION_CASE_STEPS: // Steps per mm - checkkey = Step; - select_step.reset(); - Draw_Steps_Menu(); - break; - default: break; - } - } - DWIN_UpdateLCD(); -} - -/* Info */ -void HMI_Info() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - if (encoder_diffState == ENCODER_DIFF_ENTER) { - #if HAS_ONESTEP_LEVELING - checkkey = Control; - select_control.set(CONTROL_CASE_INFO); - Draw_Control_Menu(); - #else - select_page.set(3); - Goto_MainMenu(); - #endif - } - DWIN_UpdateLCD(); -} - -/* Tune */ -void HMI_Tune() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - - // Avoid flicker by updating only the previous menu - if (encoder_diffState == ENCODER_DIFF_CW) { - if (select_tune.inc(1 + TUNE_CASE_TOTAL)) { - if (select_tune.now > MROWS && select_tune.now > index_tune) { - index_tune = select_tune.now; - Scroll_Menu(DWIN_SCROLL_UP); - } - else { - Move_Highlight(1, select_tune.now + MROWS - index_tune); - } - } - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - if (select_tune.dec()) { - if (select_tune.now < index_tune - MROWS) { - index_tune--; - Scroll_Menu(DWIN_SCROLL_DOWN); - if (index_tune == MROWS) Draw_Back_First(); - } - else { - Move_Highlight(-1, select_tune.now + MROWS - index_tune); - } - } - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - switch (select_tune.now) { - case 0: { // Back - select_print.set(0); - Goto_PrintProcess(); - } - break; - case TUNE_CASE_SPEED: // Print speed - checkkey = PrintSpeed; - HMI_ValueStruct.print_speed = feedrate_percentage; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(TUNE_CASE_SPEED + MROWS - index_tune), feedrate_percentage); - EncoderRate.enabled = true; - break; - #if HAS_HOTEND - case TUNE_CASE_TEMP: // Nozzle temp - checkkey = ETemp; - HMI_ValueStruct.E_Temp = thermalManager.temp_hotend[0].target; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(TUNE_CASE_TEMP + MROWS - index_tune), thermalManager.temp_hotend[0].target); - EncoderRate.enabled = true; - break; - #endif - #if HAS_HEATED_BED - case TUNE_CASE_BED: // Bed temp - checkkey = BedTemp; - HMI_ValueStruct.Bed_Temp = thermalManager.temp_bed.target; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(TUNE_CASE_BED + MROWS - index_tune), thermalManager.temp_bed.target); - EncoderRate.enabled = true; - break; - #endif - #if HAS_FAN - case TUNE_CASE_FAN: // Fan speed - checkkey = FanSpeed; - HMI_ValueStruct.Fan_speed = thermalManager.fan_speed[0]; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(TUNE_CASE_FAN + MROWS - index_tune), thermalManager.fan_speed[0]); - EncoderRate.enabled = true; - break; - #endif - #if HAS_ZOFFSET_ITEM - case TUNE_CASE_ZOFF: // Z-offset - #if EITHER(HAS_BED_PROBE, BABYSTEPPING) - checkkey = Homeoffset; - HMI_ValueStruct.offset_value = BABY_Z_VAR * 100; - DWIN_Draw_Signed_Float(font8x16, Select_Color, 2, 2, 202, MBASE(TUNE_CASE_ZOFF + MROWS - index_tune), HMI_ValueStruct.offset_value); - EncoderRate.enabled = true; - #else - // Apply workspace offset, making the current position 0,0,0 - queue.inject_P(PSTR("G92 X0 Y0 Z0")); - HMI_AudioFeedback(); - #endif - break; - #endif - default: break; - } - } - DWIN_UpdateLCD(); -} - -#if HAS_PREHEAT - - /* PLA Preheat */ - void HMI_PLAPreheatSetting() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - - // Avoid flicker by updating only the previous menu - if (encoder_diffState == ENCODER_DIFF_CW) { - if (select_PLA.inc(1 + PREHEAT_CASE_TOTAL)) Move_Highlight(1, select_PLA.now); - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - if (select_PLA.dec()) Move_Highlight(-1, select_PLA.now); - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - switch (select_PLA.now) { - case 0: // Back - checkkey = TemperatureID; - select_temp.now = TEMP_CASE_PLA; - HMI_ValueStruct.show_mode = -1; - Draw_Temperature_Menu(); - break; - #if HAS_HOTEND - case PREHEAT_CASE_TEMP: // Nozzle temperature - checkkey = ETemp; - HMI_ValueStruct.E_Temp = ui.material_preset[0].hotend_temp; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_TEMP), ui.material_preset[0].hotend_temp); - EncoderRate.enabled = true; - break; - #endif - #if HAS_HEATED_BED - case PREHEAT_CASE_BED: // Bed temperature - checkkey = BedTemp; - HMI_ValueStruct.Bed_Temp = ui.material_preset[0].bed_temp; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_BED), ui.material_preset[0].bed_temp); - EncoderRate.enabled = true; - break; - #endif - #if HAS_FAN - case PREHEAT_CASE_FAN: // Fan speed - checkkey = FanSpeed; - HMI_ValueStruct.Fan_speed = ui.material_preset[0].fan_speed; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_FAN), ui.material_preset[0].fan_speed); - EncoderRate.enabled = true; - break; - #endif - #if ENABLED(EEPROM_SETTINGS) - case 4: { // Save PLA configuration - const bool success = settings.save(); - HMI_AudioFeedback(success); - } break; - #endif - default: break; - } - } - DWIN_UpdateLCD(); - } - - /* ABS Preheat */ - void HMI_ABSPreheatSetting() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - - // Avoid flicker by updating only the previous menu - if (encoder_diffState == ENCODER_DIFF_CW) { - if (select_ABS.inc(1 + PREHEAT_CASE_TOTAL)) Move_Highlight(1, select_ABS.now); - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - if (select_ABS.dec()) Move_Highlight(-1, select_ABS.now); - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - switch (select_ABS.now) { - case 0: // Back - checkkey = TemperatureID; - select_temp.now = TEMP_CASE_ABS; - HMI_ValueStruct.show_mode = -1; - Draw_Temperature_Menu(); - break; - #if HAS_HOTEND - case PREHEAT_CASE_TEMP: // Set nozzle temperature - checkkey = ETemp; - HMI_ValueStruct.E_Temp = ui.material_preset[1].hotend_temp; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_TEMP), ui.material_preset[1].hotend_temp); - EncoderRate.enabled = true; - break; - #endif - #if HAS_HEATED_BED - case PREHEAT_CASE_BED: // Set bed temperature - checkkey = BedTemp; - HMI_ValueStruct.Bed_Temp = ui.material_preset[1].bed_temp; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_BED), ui.material_preset[1].bed_temp); - EncoderRate.enabled = true; - break; - #endif - #if HAS_FAN - case PREHEAT_CASE_FAN: // Set fan speed - checkkey = FanSpeed; - HMI_ValueStruct.Fan_speed = ui.material_preset[1].fan_speed; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_FAN), ui.material_preset[1].fan_speed); - EncoderRate.enabled = true; - break; - #endif - #if ENABLED(EEPROM_SETTINGS) - case PREHEAT_CASE_SAVE: { // Save ABS configuration - const bool success = settings.save(); - HMI_AudioFeedback(success); - } break; - #endif - default: break; - } - } - DWIN_UpdateLCD(); - } - -#endif - -/* Max Speed */ -void HMI_MaxSpeed() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - - // Avoid flicker by updating only the previous menu - if (encoder_diffState == ENCODER_DIFF_CW) { - if (select_speed.inc(1 + 3 + ENABLED(HAS_HOTEND))) Move_Highlight(1, select_speed.now); - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - if (select_speed.dec()) Move_Highlight(-1, select_speed.now); - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - if (WITHIN(select_speed.now, 1, 4)) { - checkkey = MaxSpeed_value; - HMI_flag.feedspeed_axis = AxisEnum(select_speed.now - 1); - HMI_ValueStruct.Max_Feedspeed = planner.settings.max_feedrate_mm_s[HMI_flag.feedspeed_axis]; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 4, 210, MBASE(select_speed.now), HMI_ValueStruct.Max_Feedspeed); - EncoderRate.enabled = true; - } - else { // Back - checkkey = Motion; - select_motion.now = MOTION_CASE_RATE; - Draw_Motion_Menu(); - } - } - DWIN_UpdateLCD(); -} - -/* Max Acceleration */ -void HMI_MaxAcceleration() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - - // Avoid flicker by updating only the previous menu - if (encoder_diffState == ENCODER_DIFF_CW) { - if (select_acc.inc(1 + 3 + ENABLED(HAS_HOTEND))) Move_Highlight(1, select_acc.now); - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - if (select_acc.dec()) Move_Highlight(-1, select_acc.now); - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - if (WITHIN(select_acc.now, 1, 4)) { - checkkey = MaxAcceleration_value; - HMI_flag.acc_axis = AxisEnum(select_acc.now - 1); - HMI_ValueStruct.Max_Acceleration = planner.settings.max_acceleration_mm_per_s2[HMI_flag.acc_axis]; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 4, 210, MBASE(select_acc.now), HMI_ValueStruct.Max_Acceleration); - EncoderRate.enabled = true; - } - else { // Back - checkkey = Motion; - select_motion.now = MOTION_CASE_ACCEL; - Draw_Motion_Menu(); - } - } - DWIN_UpdateLCD(); -} - -#if HAS_CLASSIC_JERK - /* Max Jerk */ - void HMI_MaxJerk() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - - // Avoid flicker by updating only the previous menu - if (encoder_diffState == ENCODER_DIFF_CW) { - if (select_jerk.inc(1 + 3 + ENABLED(HAS_HOTEND))) Move_Highlight(1, select_jerk.now); - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - if (select_jerk.dec()) Move_Highlight(-1, select_jerk.now); - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - if (WITHIN(select_jerk.now, 1, 4)) { - checkkey = MaxJerk_value; - HMI_flag.jerk_axis = AxisEnum(select_jerk.now - 1); - HMI_ValueStruct.Max_Jerk = planner.max_jerk[HMI_flag.jerk_axis] * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk); - EncoderRate.enabled = true; - } - else { // Back - checkkey = Motion; - select_motion.now = MOTION_CASE_JERK; - Draw_Motion_Menu(); - } - } - DWIN_UpdateLCD(); - } -#endif // HAS_CLASSIC_JERK - -/* Step */ -void HMI_Step() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - - // Avoid flicker by updating only the previous menu - if (encoder_diffState == ENCODER_DIFF_CW) { - if (select_step.inc(1 + 3 + ENABLED(HAS_HOTEND))) Move_Highlight(1, select_step.now); - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - if (select_step.dec()) Move_Highlight(-1, select_step.now); - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - if (WITHIN(select_step.now, 1, 4)) { - checkkey = Step_value; - HMI_flag.step_axis = AxisEnum(select_step.now - 1); - HMI_ValueStruct.Max_Step = planner.settings.axis_steps_per_mm[HMI_flag.step_axis] * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step); - EncoderRate.enabled = true; - } - else { // Back - checkkey = Motion; - select_motion.now = MOTION_CASE_STEPS; - Draw_Motion_Menu(); - } - } - DWIN_UpdateLCD(); -} - -void HMI_Init() { - HMI_SDCardInit(); - - for (uint16_t t = 0; t <= 100; t += 2) { - DWIN_ICON_Show(ICON, ICON_Bar, 15, 260); - DWIN_Draw_Rectangle(1, Color_Bg_Black, 15 + t * 242 / 100, 260, 257, 280); - DWIN_UpdateLCD(); - delay(20); - } - - HMI_SetLanguage(); -} - -void DWIN_Update() { - EachMomentUpdate(); // Status update - HMI_SDCardUpdate(); // SD card update - DWIN_HandleScreen(); // Rotary encoder update -} - -void EachMomentUpdate() { - static millis_t next_rts_update_ms = 0; - const millis_t ms = millis(); - if (PENDING(ms, next_rts_update_ms)) return; - next_rts_update_ms = ms + DWIN_SCROLL_UPDATE_INTERVAL; - - // variable update - update_variable(); - - if (checkkey == PrintProcess) { - // if print done - if (HMI_flag.print_finish && !HMI_flag.done_confirm_flag) { - HMI_flag.print_finish = false; - HMI_flag.done_confirm_flag = true; - - TERN_(POWER_LOSS_RECOVERY, recovery.cancel()); - - planner.finish_and_disable(); - - // show percent bar and value - Percentrecord = 0; - Draw_Print_ProgressBar(); - - // show print done confirm - DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, 250, DWIN_WIDTH - 1, STATUS_Y); - DWIN_ICON_Show(ICON, HMI_IsChinese() ? ICON_Confirm_C : ICON_Confirm_E, 86, 283); - } - else if (HMI_flag.pause_flag != printingIsPaused()) { - // print status update - HMI_flag.pause_flag = printingIsPaused(); - if (HMI_flag.pause_flag) ICON_Continue(); else ICON_Pause(); - } - } - - // pause after homing - if (HMI_flag.pause_action && printingIsPaused() && !planner.has_blocks_queued()) { - HMI_flag.pause_action = false; - #if ENABLED(PAUSE_HEAT) - #if HAS_HEATED_BED - tempbed = thermalManager.temp_bed.target; - #endif - #if HAS_HOTEND - temphot = thermalManager.temp_hotend[0].target; - #endif - thermalManager.disable_all_heaters(); - #endif - queue.inject_P(PSTR("G1 F1200 X0 Y0")); - } - - if (card.isPrinting() && checkkey == PrintProcess) { // print process - const uint8_t card_pct = card.percentDone(); - static uint8_t last_cardpercentValue = 101; - if (last_cardpercentValue != card_pct) { // print percent - last_cardpercentValue = card_pct; - if (card_pct) { - Percentrecord = card_pct; - Draw_Print_ProgressBar(); - } - } - - duration_t elapsed = print_job_timer.duration(); // print timer - - // Print time so far - static uint16_t last_Printtime = 0; - const uint16_t min = (elapsed.value % 3600) / 60; - if (last_Printtime != min) { // 1 minute update - last_Printtime = min; - Draw_Print_ProgressElapsed(); - } - - // Estimate remaining time every 20 seconds - static millis_t next_remain_time_update = 0; - if (Percentrecord > 1 && ELAPSED(ms, next_remain_time_update) && !HMI_flag.heat_flag) { - remain_time = (elapsed.value - dwin_heat_time) / (Percentrecord * 0.01f) - (elapsed.value - dwin_heat_time); - next_remain_time_update += 20 * 1000UL; - Draw_Print_ProgressRemain(); - } - } - else if (dwin_abort_flag && !HMI_flag.home_flag) { // Print Stop - dwin_abort_flag = false; - HMI_ValueStruct.print_speed = feedrate_percentage = 100; - dwin_zoffset = TERN0(HAS_BED_PROBE, probe.offset.z); - select_page.set(0); - Goto_MainMenu(); - } - #if ENABLED(POWER_LOSS_RECOVERY) - else if (DWIN_lcd_sd_status && recovery.dwin_flag) { // resume print before power off - static bool recovery_flag = false; - - recovery.dwin_flag = false; - recovery_flag = true; - - auto update_selection = [&](const bool sel) { - HMI_flag.select_flag = sel; - const uint16_t c1 = sel ? Color_Bg_Window : Select_Color; - DWIN_Draw_Rectangle(0, c1, 25, 306, 126, 345); - DWIN_Draw_Rectangle(0, c1, 24, 305, 127, 346); - const uint16_t c2 = sel ? Select_Color : Color_Bg_Window; - DWIN_Draw_Rectangle(0, c2, 145, 306, 246, 345); - DWIN_Draw_Rectangle(0, c2, 144, 305, 247, 346); - }; - - Popup_Window_Resume(); - update_selection(true); - - // TODO: Get the name of the current file from someplace - // - //(void)recovery.interrupted_file_exists(); - char * const name = card.longest_filename(); - const int8_t npos = _MAX(0U, DWIN_WIDTH - strlen(name) * (MENU_CHR_W)) / 2; - DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, npos, 252, name); - DWIN_UpdateLCD(); - - while (recovery_flag) { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (encoder_diffState == ENCODER_DIFF_ENTER) { - recovery_flag = false; - if (HMI_flag.select_flag) break; - TERN_(POWER_LOSS_RECOVERY, queue.inject_P(PSTR("M1000C"))); - HMI_StartFrame(true); - return; - } - else - update_selection(encoder_diffState == ENCODER_DIFF_CW); - - DWIN_UpdateLCD(); - } - } - - select_print.set(0); - HMI_ValueStruct.show_mode = 0; - queue.inject_P(PSTR("M1000")); - Goto_PrintProcess(); - Draw_Status_Area(true); - } - #endif - DWIN_UpdateLCD(); -} - -void DWIN_HandleScreen() { - switch (checkkey) { - case MainMenu: HMI_MainMenu(); break; - case SelectFile: HMI_SelectFile(); break; - case Prepare: HMI_Prepare(); break; - case Control: HMI_Control(); break; - case Leveling: break; - case PrintProcess: HMI_Printing(); break; - case Print_window: HMI_PauseOrStop(); break; - case AxisMove: HMI_AxisMove(); break; - case TemperatureID: HMI_Temperature(); break; - case Motion: HMI_Motion(); break; - case Info: HMI_Info(); break; - case Tune: HMI_Tune(); break; - #if HAS_PREHEAT - case PLAPreheat: HMI_PLAPreheatSetting(); break; - case ABSPreheat: HMI_ABSPreheatSetting(); break; - #endif - case MaxSpeed: HMI_MaxSpeed(); break; - case MaxAcceleration: HMI_MaxAcceleration(); break; - case MaxJerk: HMI_MaxJerk(); break; - case Step: HMI_Step(); break; - case Move_X: HMI_Move_X(); break; - case Move_Y: HMI_Move_Y(); break; - case Move_Z: HMI_Move_Z(); break; - #if HAS_HOTEND - case Extruder: HMI_Move_E(); break; - case ETemp: HMI_ETemp(); break; - #endif - #if EITHER(HAS_BED_PROBE, BABYSTEPPING) - case Homeoffset: HMI_Zoffset(); break; - #endif - #if HAS_HEATED_BED - case BedTemp: HMI_BedTemp(); break; - #endif - #if HAS_PREHEAT - case FanSpeed: HMI_FanSpeed(); break; - #endif - case PrintSpeed: HMI_PrintSpeed(); break; - case MaxSpeed_value: HMI_MaxFeedspeedXYZE(); break; - case MaxAcceleration_value: HMI_MaxAccelerationXYZE(); break; - case MaxJerk_value: HMI_MaxJerkXYZE(); break; - case Step_value: HMI_StepXYZE(); break; - default: break; - } -} - -void DWIN_CompletedHoming() { - HMI_flag.home_flag = false; - if (checkkey == Last_Prepare) { - checkkey = Prepare; - select_prepare.now = PREPARE_CASE_HOME; - index_prepare = MROWS; - Draw_Prepare_Menu(); - } - else if (checkkey == Back_Main) { - HMI_ValueStruct.print_speed = feedrate_percentage = 100; - dwin_zoffset = TERN0(HAS_BED_PROBE, probe.offset.z); - planner.finish_and_disable(); - Goto_MainMenu(); - } -} - -void DWIN_CompletedLeveling() { - if (checkkey == Leveling) Goto_MainMenu(); -} - -#endif // DWIN_CREALITY_LCD diff --git a/Marlin/src/lcd/dwin/e3v2/dwin.h b/Marlin/src/lcd/dwin/e3v2/dwin.h deleted file mode 100644 index 5bff2e9f7890..000000000000 --- a/Marlin/src/lcd/dwin/e3v2/dwin.h +++ /dev/null @@ -1,373 +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 - -/** - * DWIN by Creality3D - */ - -#include "../dwin_lcd.h" -#include "rotary_encoder.h" -#include "../../../libs/BL24CXX.h" - -#include "../../../inc/MarlinConfigPre.h" - -#if ANY(HAS_HOTEND, HAS_HEATED_BED, HAS_FAN) && PREHEAT_COUNT - #define HAS_PREHEAT 1 - #if PREHEAT_COUNT < 2 - #error "Creality DWIN requires two material preheat presets." - #endif -#endif - -enum processID : uint8_t { - // Process ID - MainMenu, - SelectFile, - Prepare, - Control, - Leveling, - PrintProcess, - AxisMove, - TemperatureID, - Motion, - Info, - Tune, - #if HAS_PREHEAT - PLAPreheat, - ABSPreheat, - #endif - MaxSpeed, - MaxSpeed_value, - MaxAcceleration, - MaxAcceleration_value, - MaxJerk, - MaxJerk_value, - Step, - Step_value, - - // Last Process ID - Last_Prepare, - - // Back Process ID - Back_Main, - Back_Print, - - // Date variable ID - Move_X, - Move_Y, - Move_Z, - #if HAS_HOTEND - Extruder, - ETemp, - #endif - Homeoffset, - #if HAS_HEATED_BED - BedTemp, - #endif - #if HAS_FAN - FanSpeed, - #endif - PrintSpeed, - - // Window ID - Print_window, - Popup_Window -}; - -// Picture ID -#define Start_Process 0 -#define Language_English 1 -#define Language_Chinese 2 - -// ICON ID -#define ICON 0x09 -#define ICON_LOGO 0 -#define ICON_Print_0 1 -#define ICON_Print_1 2 -#define ICON_Prepare_0 3 -#define ICON_Prepare_1 4 -#define ICON_Control_0 5 -#define ICON_Control_1 6 -#define ICON_Leveling_0 7 -#define ICON_Leveling_1 8 -#define ICON_HotendTemp 9 -#define ICON_BedTemp 10 -#define ICON_Speed 11 -#define ICON_Zoffset 12 -#define ICON_Back 13 -#define ICON_File 14 -#define ICON_PrintTime 15 -#define ICON_RemainTime 16 -#define ICON_Setup_0 17 -#define ICON_Setup_1 18 -#define ICON_Pause_0 19 -#define ICON_Pause_1 20 -#define ICON_Continue_0 21 -#define ICON_Continue_1 22 -#define ICON_Stop_0 23 -#define ICON_Stop_1 24 -#define ICON_Bar 25 -#define ICON_More 26 - -#define ICON_Axis 27 -#define ICON_CloseMotor 28 -#define ICON_Homing 29 -#define ICON_SetHome 30 -#define ICON_PLAPreheat 31 -#define ICON_ABSPreheat 32 -#define ICON_Cool 33 -#define ICON_Language 34 - -#define ICON_MoveX 35 -#define ICON_MoveY 36 -#define ICON_MoveZ 37 -#define ICON_Extruder 38 - -#define ICON_Temperature 40 -#define ICON_Motion 41 -#define ICON_WriteEEPROM 42 -#define ICON_ReadEEPROM 43 -#define ICON_ResumeEEPROM 44 -#define ICON_Info 45 - -#define ICON_SetEndTemp 46 -#define ICON_SetBedTemp 47 -#define ICON_FanSpeed 48 -#define ICON_SetPLAPreheat 49 -#define ICON_SetABSPreheat 50 - -#define ICON_MaxSpeed 51 -#define ICON_MaxAccelerated 52 -#define ICON_MaxJerk 53 -#define ICON_Step 54 -#define ICON_PrintSize 55 -#define ICON_Version 56 -#define ICON_Contact 57 -#define ICON_StockConfiguraton 58 -#define ICON_MaxSpeedX 59 -#define ICON_MaxSpeedY 60 -#define ICON_MaxSpeedZ 61 -#define ICON_MaxSpeedE 62 -#define ICON_MaxAccX 63 -#define ICON_MaxAccY 64 -#define ICON_MaxAccZ 65 -#define ICON_MaxAccE 66 -#define ICON_MaxSpeedJerkX 67 -#define ICON_MaxSpeedJerkY 68 -#define ICON_MaxSpeedJerkZ 69 -#define ICON_MaxSpeedJerkE 70 -#define ICON_StepX 71 -#define ICON_StepY 72 -#define ICON_StepZ 73 -#define ICON_StepE 74 -#define ICON_Setspeed 75 -#define ICON_SetZOffset 76 -#define ICON_Rectangle 77 -#define ICON_BLTouch 78 -#define ICON_TempTooLow 79 -#define ICON_AutoLeveling 80 -#define ICON_TempTooHigh 81 -#define ICON_NoTips_C 82 -#define ICON_NoTips_E 83 -#define ICON_Continue_C 84 -#define ICON_Continue_E 85 -#define ICON_Cancel_C 86 -#define ICON_Cancel_E 87 -#define ICON_Confirm_C 88 -#define ICON_Confirm_E 89 -#define ICON_Info_0 90 -#define ICON_Info_1 91 - -/** - * 3-.0:The font size, 0x00-0x09, corresponds to the font size below: - * 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 -#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 - -// Color -#define Color_White 0xFFFF -#define Color_Yellow 0xFF0F -#define Color_Bg_Window 0x31E8 // Popup background color -#define Color_Bg_Blue 0x1125 // Dark blue background color -#define Color_Bg_Black 0x0841 // Black background color -#define Color_Bg_Red 0xF00F // Red background color -#define Popup_Text_Color 0xD6BA // Popup font background color -#define Line_Color 0x3A6A // Split line color -#define Rectangle_Color 0xEE2F // Blue square cursor color -#define Percent_Color 0xFE29 // Percentage color -#define BarFill_Color 0x10E4 // Fill color of progress bar -#define Select_Color 0x33BB // Selected color - -extern uint8_t checkkey; -extern float zprobe_zoffset; -extern char print_filename[16]; - -extern millis_t dwin_heat_time; - -typedef struct { - TERN_(HAS_HOTEND, int16_t E_Temp = 0); - TERN_(HAS_HEATED_BED, int16_t Bed_Temp = 0); - TERN_(HAS_PREHEAT, int16_t Fan_speed = 0); - int16_t print_speed = 100; - float Max_Feedspeed = 0; - float Max_Acceleration = 0; - float Max_Jerk = 0; - float Max_Step = 0; - float Move_X_scale = 0; - float Move_Y_scale = 0; - float Move_Z_scale = 0; - #if HAS_HOTEND - float Move_E_scale = 0; - #endif - float offset_value = 0; - char show_mode = 0; // -1: Temperature control 0: Printing temperature -} HMI_value_t; - -#define DWIN_CHINESE 123 -#define DWIN_ENGLISH 0 - -typedef struct { - uint8_t language; - bool pause_flag:1; - bool pause_action:1; - bool print_finish:1; - bool done_confirm_flag:1; - bool select_flag:1; - bool home_flag:1; - bool heat_flag:1; // 0: heating done 1: during heating - #if ENABLED(PREVENT_COLD_EXTRUSION) - bool ETempTooLow_flag:1; - #endif - #if HAS_LEVELING - bool leveling_offset_flag:1; - #endif - #if HAS_FAN - AxisEnum feedspeed_axis; - #endif - AxisEnum acc_axis, jerk_axis, step_axis; -} HMI_Flag_t; - -extern HMI_value_t HMI_ValueStruct; -extern HMI_Flag_t HMI_flag; - -// Show ICO -void ICON_Print(bool show); -void ICON_Prepare(bool show); -void ICON_Control(bool show); -void ICON_Leveling(bool show); -void ICON_StartInfo(bool show); - -void ICON_Setting(bool show); -void ICON_Pause(bool show); -void ICON_Continue(bool show); -void ICON_Stop(bool show); - -#if HAS_HOTEND || HAS_HEATED_BED - // Popup message window - void DWIN_Popup_Temperature(const bool toohigh); -#endif - -#if HAS_HOTEND - void Popup_Window_ETempTooLow(); -#endif - -void Popup_Window_Resume(); -void Popup_Window_Home(const bool parking=false); -void Popup_Window_Leveling(); - -void Goto_PrintProcess(); -void Goto_MainMenu(); - -// Variable control -void HMI_Move_X(); -void HMI_Move_Y(); -void HMI_Move_Z(); -void HMI_Move_E(); - -void HMI_Zoffset(); - -TERN_(HAS_HOTEND, void HMI_ETemp()); -TERN_(HAS_HEATED_BED, void HMI_BedTemp()); -TERN_(HAS_FAN, void HMI_FanSpeed()); - -void HMI_PrintSpeed(); - -void HMI_MaxFeedspeedXYZE(); -void HMI_MaxAccelerationXYZE(); -void HMI_MaxJerkXYZE(); -void HMI_StepXYZE(); - -void update_variable(); -void DWIN_Draw_Signed_Float(uint8_t size, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value); - -// SD Card -void HMI_SDCardInit(); -void HMI_SDCardUpdate(); - -// Main Process -void Icon_print(bool value); -void Icon_control(bool value); -void Icon_temperature(bool value); -void Icon_leveling(bool value); - -// Other -void Draw_Status_Area(const bool with_update); // Status Area -void HMI_StartFrame(const bool with_update); // Prepare the menu view -void HMI_MainMenu(); // Main process screen -void HMI_SelectFile(); // File page -void HMI_Printing(); // Print page -void HMI_Prepare(); // Prepare page -void HMI_Control(); // Control page -void HMI_Leveling(); // Level the page -void HMI_AxisMove(); // Axis movement menu -void HMI_Temperature(); // Temperature menu -void HMI_Motion(); // Sports menu -void HMI_Info(); // Information menu -void HMI_Tune(); // Adjust the menu - -#if HAS_PREHEAT - void HMI_PLAPreheatSetting(); // PLA warm-up setting - void HMI_ABSPreheatSetting(); // ABS warm-up setting -#endif - -void HMI_MaxSpeed(); // Maximum speed submenu -void HMI_MaxAcceleration(); // Maximum acceleration submenu -void HMI_MaxJerk(); // Maximum jerk speed submenu -void HMI_Step(); // Transmission ratio - -void HMI_Init(); -void DWIN_Update(); -void EachMomentUpdate(); -void DWIN_HandleScreen(); - -void DWIN_CompletedHoming(); -void DWIN_CompletedLeveling(); diff --git a/Marlin/src/lcd/dwin/e3v2/rotary_encoder.cpp b/Marlin/src/lcd/dwin/e3v2/rotary_encoder.cpp deleted file mode 100644 index d39c6cfbd5e8..000000000000 --- a/Marlin/src/lcd/dwin/e3v2/rotary_encoder.cpp +++ /dev/null @@ -1,254 +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 . - * - */ - -/***************************************************************************** - * @file rotary_encoder.cpp - * @author LEO / Creality3D - * @date 2019/07/06 - * @version 2.0.1 - * @brief Rotary encoder functions - *****************************************************************************/ - -#include "../../../inc/MarlinConfigPre.h" - -#if ENABLED(DWIN_CREALITY_LCD) - -#include "rotary_encoder.h" - -#include "../../../MarlinCore.h" -#include "../../../HAL/shared/Delay.h" - -#if HAS_BUZZER - #include "../../../libs/buzzer.h" -#endif - -#include - -ENCODER_Rate EncoderRate; - -// Buzzer -void Encoder_tick(void) { - WRITE(BEEPER_PIN, 1); - delay(10); - WRITE(BEEPER_PIN, 0); -} - -// Encoder initialization -void Encoder_Configuration(void) { - #if BUTTON_EXISTS(EN1) - SET_INPUT_PULLUP(BTN_EN1); - #endif - #if BUTTON_EXISTS(EN2) - SET_INPUT_PULLUP(BTN_EN2); - #endif - #if BUTTON_EXISTS(ENC) - SET_INPUT_PULLUP(BTN_ENC); - #endif - #ifdef BEEPER_PIN - SET_OUTPUT(BEEPER_PIN); - #endif -} - -// Analyze encoder value and return state -ENCODER_DiffState Encoder_ReceiveAnalyze(void) { - const millis_t now = millis(); - static unsigned char lastEncoderBits; - unsigned char newbutton = 0; - static signed char temp_diff = 0; - - ENCODER_DiffState temp_diffState = ENCODER_DIFF_NO; - if (BUTTON_PRESSED(EN1)) newbutton |= 0x01; - if (BUTTON_PRESSED(EN2)) newbutton |= 0x02; - if (BUTTON_PRESSED(ENC)) { - static millis_t next_click_update_ms; - if (ELAPSED(now, next_click_update_ms)) { - next_click_update_ms = millis() + 300; - Encoder_tick(); - #if PIN_EXISTS(LCD_LED) - //LED_Action(); - #endif - const bool was_waiting = wait_for_user; - wait_for_user = false; - return was_waiting ? ENCODER_DIFF_NO : ENCODER_DIFF_ENTER; - } - else return ENCODER_DIFF_NO; - } - if (newbutton != lastEncoderBits) { - switch (newbutton) { - case ENCODER_PHASE_0: { - if (lastEncoderBits == ENCODER_PHASE_3) temp_diff++; - else if (lastEncoderBits == ENCODER_PHASE_1) temp_diff--; - }break; - case ENCODER_PHASE_1: { - if (lastEncoderBits == ENCODER_PHASE_0) temp_diff++; - else if (lastEncoderBits == ENCODER_PHASE_2) temp_diff--; - }break; - case ENCODER_PHASE_2: { - if (lastEncoderBits == ENCODER_PHASE_1) temp_diff++; - else if (lastEncoderBits == ENCODER_PHASE_3) temp_diff--; - }break; - case ENCODER_PHASE_3: { - if (lastEncoderBits == ENCODER_PHASE_2) temp_diff++; - else if (lastEncoderBits == ENCODER_PHASE_0) temp_diff--; - }break; - } - lastEncoderBits = newbutton; - } - - if (abs(temp_diff) >= ENCODER_PULSES_PER_STEP) { - if (temp_diff > 0) temp_diffState = ENCODER_DIFF_CW; - else temp_diffState = ENCODER_DIFF_CCW; - - #if ENABLED(ENCODER_RATE_MULTIPLIER) - - millis_t ms = millis(); - int32_t encoderMultiplier = 1; - - // if must encoder rati multiplier - if (EncoderRate.enabled) { - const float abs_diff = ABS(temp_diff), - encoderMovementSteps = abs_diff / (ENCODER_PULSES_PER_STEP); - if (EncoderRate.lastEncoderTime) { - // Note that the rate is always calculated between two passes through the - // loop and that the abs of the temp_diff value is tracked. - const float encoderStepRate = encoderMovementSteps / float(ms - EncoderRate.lastEncoderTime) * 1000; - if (encoderStepRate >= ENCODER_100X_STEPS_PER_SEC) encoderMultiplier = 100; - else if (encoderStepRate >= ENCODER_10X_STEPS_PER_SEC) encoderMultiplier = 10; - else if (encoderStepRate >= ENCODER_5X_STEPS_PER_SEC) encoderMultiplier = 5; - } - EncoderRate.lastEncoderTime = ms; - } - #else - constexpr int32_t encoderMultiplier = 1; - #endif // ENCODER_RATE_MULTIPLIER - - // EncoderRate.encoderMoveValue += (temp_diff * encoderMultiplier) / (ENCODER_PULSES_PER_STEP); - EncoderRate.encoderMoveValue = (temp_diff * encoderMultiplier) / (ENCODER_PULSES_PER_STEP); - if (EncoderRate.encoderMoveValue < 0) EncoderRate.encoderMoveValue = -EncoderRate.encoderMoveValue; - - temp_diff = 0; - } - return temp_diffState; -} - -#if PIN_EXISTS(LCD_LED) - - // Take the low 24 valid bits 24Bit: G7 G6 G5 G4 G3 G2 G1 G0 R7 R6 R5 R4 R3 R2 R1 R0 B7 B6 B5 B4 B3 B2 B1 B0 - unsigned int LED_DataArray[LED_NUM]; - - // LED light operation - void LED_Action(void) { - LED_Control(RGB_SCALE_WARM_WHITE,0x0F); - delay(30); - LED_Control(RGB_SCALE_WARM_WHITE,0x00); - } - - // LED initialization - void LED_Configuration(void) { - SET_OUTPUT(LCD_LED_PIN); - } - - // LED write data - void LED_WriteData(void) { - unsigned char tempCounter_LED, tempCounter_Bit; - for (tempCounter_LED = 0; tempCounter_LED < LED_NUM; tempCounter_LED++) { - for (tempCounter_Bit = 0; tempCounter_Bit < 24; tempCounter_Bit++) { - if (LED_DataArray[tempCounter_LED] & (0x800000 >> tempCounter_Bit)) { - LED_DATA_HIGH; - DELAY_NS(300); - LED_DATA_LOW; - DELAY_NS(200); - } - else { - LED_DATA_HIGH; - LED_DATA_LOW; - DELAY_NS(200); - } - } - } - } - - // LED control - // RGB_Scale: RGB color ratio - // luminance: brightness (0~0xFF) - void LED_Control(unsigned char RGB_Scale, unsigned char luminance) { - unsigned char temp_Counter; - for (temp_Counter = 0; temp_Counter < LED_NUM; temp_Counter++) { - LED_DataArray[temp_Counter] = 0; - switch (RGB_Scale) { - case RGB_SCALE_R10_G7_B5: LED_DataArray[temp_Counter] = (luminance*10/10) << 8 | (luminance*7/10) << 16 | luminance*5/10; break; - case RGB_SCALE_R10_G7_B4: LED_DataArray[temp_Counter] = (luminance*10/10) << 8 | (luminance*7/10) << 16 | luminance*4/10; break; - case RGB_SCALE_R10_G8_B7: LED_DataArray[temp_Counter] = (luminance*10/10) << 8 | (luminance*8/10) << 16 | luminance*7/10; break; - } - } - LED_WriteData(); - } - - // LED gradient control - // RGB_Scale: RGB color ratio - // luminance: brightness (0~0xFF) - // change_Time: gradient time (ms) - void LED_GraduallyControl(unsigned char RGB_Scale, unsigned char luminance, unsigned int change_Interval) { - unsigned char temp_Counter; - unsigned char LED_R_Data[LED_NUM], LED_G_Data[LED_NUM], LED_B_Data[LED_NUM]; - bool LED_R_Flag = 0, LED_G_Flag = 0, LED_B_Flag = 0; - - for (temp_Counter = 0; temp_Counter < LED_NUM; temp_Counter++) { - switch (RGB_Scale) { - case RGB_SCALE_R10_G7_B5: { - LED_R_Data[temp_Counter] = luminance*10/10; - LED_G_Data[temp_Counter] = luminance*7/10; - LED_B_Data[temp_Counter] = luminance*5/10; - }break; - case RGB_SCALE_R10_G7_B4: { - LED_R_Data[temp_Counter] = luminance*10/10; - LED_G_Data[temp_Counter] = luminance*7/10; - LED_B_Data[temp_Counter] = luminance*4/10; - }break; - case RGB_SCALE_R10_G8_B7: { - LED_R_Data[temp_Counter] = luminance*10/10; - LED_G_Data[temp_Counter] = luminance*8/10; - LED_B_Data[temp_Counter] = luminance*7/10; - }break; - } - } - for (temp_Counter = 0; temp_Counter < LED_NUM; temp_Counter++) { - if ((unsigned char)(LED_DataArray[temp_Counter] >> 8) > LED_R_Data[temp_Counter]) LED_DataArray[temp_Counter] -= 0x000100; - else if ((unsigned char)(LED_DataArray[temp_Counter] >> 8) < LED_R_Data[temp_Counter]) LED_DataArray[temp_Counter] += 0x000100; - while (1) { - else LED_R_Flag = 1; - if ((unsigned char)(LED_DataArray[temp_Counter]>>16) > LED_G_Data[temp_Counter]) LED_DataArray[temp_Counter] -= 0x010000; - else if ((unsigned char)(LED_DataArray[temp_Counter]>>16) < LED_G_Data[temp_Counter]) LED_DataArray[temp_Counter] += 0x010000; - else LED_G_Flag = 1; - if ((unsigned char)LED_DataArray[temp_Counter] > LED_B_Data[temp_Counter]) LED_DataArray[temp_Counter] -= 0x000001; - else if ((unsigned char)LED_DataArray[temp_Counter] < LED_B_Data[temp_Counter]) LED_DataArray[temp_Counter] += 0x000001; - else LED_B_Flag = 1; - } - LED_WriteData(); - if (LED_R_Flag && LED_G_Flag && LED_B_Flag) break; - else delay(change_Interval); - } - } - -#endif // LCD_LED - -#endif // DWIN_CREALITY_LCD diff --git a/Marlin/src/lcd/dwin/e3v2/README.md b/Marlin/src/lcd/e3v2/creality/README.md similarity index 100% rename from Marlin/src/lcd/dwin/e3v2/README.md rename to Marlin/src/lcd/e3v2/creality/README.md diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp new file mode 100644 index 000000000000..05da343f9e43 --- /dev/null +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -0,0 +1,4146 @@ +/** + * 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 . + * + */ + +/** + * DWIN by Creality3D + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if ENABLED(DWIN_CREALITY_LCD) + +#include "dwin.h" + +#if ANY(AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT) && DISABLED(PROBE_MANUALLY) + #define HAS_ONESTEP_LEVELING 1 +#endif + +#if ANY(BABYSTEPPING, HAS_BED_PROBE, HAS_WORKSPACE_OFFSET) + #define HAS_ZOFFSET_ITEM 1 +#endif + +#if !HAS_BED_PROBE && ENABLED(BABYSTEPPING) + #define JUST_BABYSTEP 1 +#endif + +#include "../../fontutils.h" +#include "../../marlinui.h" + +#include "../../../sd/cardreader.h" + +#include "../../../MarlinCore.h" +#include "../../../core/serial.h" +#include "../../../core/macros.h" +#include "../../../gcode/queue.h" + +#include "../../../module/temperature.h" +#include "../../../module/printcounter.h" +#include "../../../module/motion.h" +#include "../../../module/planner.h" + +#if ENABLED(EEPROM_SETTINGS) + #include "../../../module/settings.h" +#endif + +#if ENABLED(HOST_ACTION_COMMANDS) + #include "../../../feature/host_actions.h" +#endif + +#if HAS_ONESTEP_LEVELING + #include "../../../feature/bedlevel/bedlevel.h" +#endif + +#if HAS_BED_PROBE + #include "../../../module/probe.h" +#endif + +#if EITHER(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) + #include "../../../feature/babystep.h" +#endif + +#if ENABLED(POWER_LOSS_RECOVERY) + #include "../../../feature/powerloss.h" +#endif + +#include +#include +#include + +#ifndef MACHINE_SIZE + #define MACHINE_SIZE STRINGIFY(X_BED_SIZE) "x" STRINGIFY(Y_BED_SIZE) "x" STRINGIFY(Z_MAX_POS) +#endif +#ifndef CORP_WEBSITE + #define CORP_WEBSITE WEBSITE_URL +#endif + +#define PAUSE_HEAT + +#define USE_STRING_HEADINGS +//#define USE_STRING_TITLES + +#define MENU_CHAR_LIMIT 24 +#define STATUS_Y 360 + +// Print speed limit +#define MIN_PRINT_SPEED 10 +#define MAX_PRINT_SPEED 999 + +// Feedspeed limit (max feedspeed = DEFAULT_MAX_FEEDRATE * 2) +#define MIN_MAXFEEDSPEED 1 +#define MIN_MAXACCELERATION 1 +#define MIN_MAXJERK 0.1 +#define MIN_STEP 1 + +#define FEEDRATE_E (60) + +// Minimum unit (0.1) : multiple (10) +#define UNITFDIGITS 1 +#define MINUNITMULT pow(10, UNITFDIGITS) + +#define ENCODER_WAIT_MS 20 +#define DWIN_VAR_UPDATE_INTERVAL 1024 +#define DWIN_SCROLL_UPDATE_INTERVAL SEC_TO_MS(2) +#define DWIN_REMAIN_TIME_UPDATE_INTERVAL SEC_TO_MS(20) + +constexpr uint16_t TROWS = 6, MROWS = TROWS - 1, // Total rows, and other-than-Back + TITLE_HEIGHT = 30, // Title bar height + MLINE = 53, // Menu line height + LBLX = 60, // Menu item label X + MENU_CHR_W = 8, STAT_CHR_W = 10; + +#define MBASE(L) (49 + MLINE * (L)) + +#define BABY_Z_VAR TERN(HAS_BED_PROBE, probe.offset.z, dwin_zoffset) + +#define DWIN_BOTTOM (DWIN_HEIGHT-1) +#define DWIN_RIGHT (DWIN_WIDTH-1) + +/* Value Init */ +HMI_value_t HMI_ValueStruct; +HMI_Flag_t HMI_flag{0}; + +millis_t dwin_heat_time = 0; + +uint8_t checkkey = 0; + +typedef struct { + uint8_t now, last; + void set(uint8_t v) { now = last = v; } + void reset() { set(0); } + bool changed() { bool c = (now != last); if (c) last = now; return c; } + bool dec() { if (now) now--; return changed(); } + bool inc(uint8_t v) { if (now < (v - 1)) now++; else now = (v - 1); return changed(); } +} select_t; + +select_t select_page{0}, select_file{0}, select_print{0}, select_prepare{0} + , select_control{0}, select_axis{0}, select_temp{0}, select_motion{0}, select_tune{0} + , select_advset{0}, select_PLA{0}, select_ABS{0} + , select_speed{0} + , select_acc{0} + , select_jerk{0} + , select_step{0} + , select_item{0} + ; + +uint8_t index_file = MROWS, + index_prepare = MROWS, + index_control = MROWS, + index_leveling = MROWS, + index_tune = MROWS, + index_advset = MROWS; + +bool dwin_abort_flag = false; // Flag to reset feedrate, return to Home + +constexpr float default_max_feedrate[] = DEFAULT_MAX_FEEDRATE; +constexpr float default_max_acceleration[] = DEFAULT_MAX_ACCELERATION; + +#if HAS_CLASSIC_JERK + constexpr float default_max_jerk[] = { DEFAULT_XJERK, DEFAULT_YJERK, DEFAULT_ZJERK, DEFAULT_EJERK }; +#endif + +static uint8_t _card_percent = 0; +static uint16_t _remain_time = 0; + +#if ENABLED(PAUSE_HEAT) + #if HAS_HOTEND + uint16_t resume_hotend_temp = 0; + #endif + #if HAS_HEATED_BED + uint16_t resume_bed_temp = 0; + #endif +#endif + +#if HAS_ZOFFSET_ITEM + float dwin_zoffset = 0, last_zoffset = 0; +#endif + +#define DWIN_LANGUAGE_EEPROM_ADDRESS 0x01 // Between 0x01 and 0x63 (EEPROM_OFFSET-1) + // BL24CXX::check() uses 0x00 + +inline bool HMI_IsChinese() { return HMI_flag.language == DWIN_CHINESE; } + +void HMI_SetLanguageCache() { + DWIN_JPG_CacheTo1(HMI_IsChinese() ? Language_Chinese : Language_English); +} + +void HMI_SetLanguage() { + #if BOTH(EEPROM_SETTINGS, IIC_BL24CXX_EEPROM) + BL24CXX::read(DWIN_LANGUAGE_EEPROM_ADDRESS, (uint8_t*)&HMI_flag.language, sizeof(HMI_flag.language)); + #endif + HMI_SetLanguageCache(); +} + +void HMI_ToggleLanguage() { + HMI_flag.language = HMI_IsChinese() ? DWIN_ENGLISH : DWIN_CHINESE; + HMI_SetLanguageCache(); + #if BOTH(EEPROM_SETTINGS, IIC_BL24CXX_EEPROM) + BL24CXX::write(DWIN_LANGUAGE_EEPROM_ADDRESS, (uint8_t*)&HMI_flag.language, sizeof(HMI_flag.language)); + #endif +} + +void DWIN_Draw_Signed_Float(uint8_t size, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { + if (value < 0) { + DWIN_Draw_String(true, size, Color_White, bColor, x - 6, y, F("-")); + DWIN_Draw_FloatValue(true, true, 0, size, Color_White, bColor, iNum, fNum, x, y, -value); + } + else { + DWIN_Draw_String(true, size, Color_White, bColor, x - 6, y, F(" ")); + DWIN_Draw_FloatValue(true, true, 0, size, Color_White, bColor, iNum, fNum, x, y, value); + } +} + +void ICON_Print() { + if (select_page.now == 0) { + DWIN_ICON_Show(ICON, ICON_Print_1, 17, 130); + DWIN_Draw_Rectangle(0, Color_White, 17, 130, 126, 229); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 1, 447, 28, 460, 58, 201); + else + DWIN_Frame_AreaCopy(1, 1, 451, 31, 463, 57, 201); + } + else { + DWIN_ICON_Show(ICON, ICON_Print_0, 17, 130); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 1, 405, 28, 420, 58, 201); + else + DWIN_Frame_AreaCopy(1, 1, 423, 31, 435, 57, 201); + } +} + +void ICON_Prepare() { + if (select_page.now == 1) { + DWIN_ICON_Show(ICON, ICON_Prepare_1, 145, 130); + DWIN_Draw_Rectangle(0, Color_White, 145, 130, 254, 229); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 31, 447, 58, 460, 186, 201); + else + DWIN_Frame_AreaCopy(1, 33, 451, 82, 466, 175, 201); + } + else { + DWIN_ICON_Show(ICON, ICON_Prepare_0, 145, 130); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 31, 405, 58, 420, 186, 201); + else + DWIN_Frame_AreaCopy(1, 33, 423, 82, 438, 175, 201); + } +} + +void ICON_Control() { + if (select_page.now == 2) { + DWIN_ICON_Show(ICON, ICON_Control_1, 17, 246); + DWIN_Draw_Rectangle(0, Color_White, 17, 246, 126, 345); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 61, 447, 88, 460, 58, 318); + else + DWIN_Frame_AreaCopy(1, 85, 451, 132, 463, 48, 318); + } + else { + DWIN_ICON_Show(ICON, ICON_Control_0, 17, 246); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 61, 405, 88, 420, 58, 318); + else + DWIN_Frame_AreaCopy(1, 85, 423, 132, 434, 48, 318); + } +} + +void ICON_StartInfo(bool show) { + if (show) { + DWIN_ICON_Show(ICON, ICON_Info_1, 145, 246); + DWIN_Draw_Rectangle(0, Color_White, 145, 246, 254, 345); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 91, 447, 118, 460, 186, 318); + else + DWIN_Frame_AreaCopy(1, 132, 451, 159, 466, 186, 318); + } + else { + DWIN_ICON_Show(ICON, ICON_Info_0, 145, 246); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 91, 405, 118, 420, 186, 318); + else + DWIN_Frame_AreaCopy(1, 132, 423, 159, 435, 186, 318); + } +} + +void ICON_Leveling(bool show) { + if (show) { + DWIN_ICON_Show(ICON, ICON_Leveling_1, 145, 246); + DWIN_Draw_Rectangle(0, Color_White, 145, 246, 254, 345); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 211, 447, 238, 460, 186, 318); + else + DWIN_Frame_AreaCopy(1, 84, 437, 120, 449, 182, 318); + } + else { + DWIN_ICON_Show(ICON, ICON_Leveling_0, 145, 246); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 211, 405, 238, 420, 186, 318); + else + DWIN_Frame_AreaCopy(1, 84, 465, 120, 478, 182, 318); + } +} + +void ICON_Tune() { + if (select_print.now == 0) { + DWIN_ICON_Show(ICON, ICON_Setup_1, 8, 252); + DWIN_Draw_Rectangle(0, Color_White, 8, 252, 87, 351); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 121, 447, 148, 458, 34, 325); + else + DWIN_Frame_AreaCopy(1, 0, 466, 34, 476, 31, 325); + } + else { + DWIN_ICON_Show(ICON, ICON_Setup_0, 8, 252); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 121, 405, 148, 420, 34, 325); + else + DWIN_Frame_AreaCopy(1, 0, 438, 32, 448, 31, 325); + } +} + +void ICON_Pause() { + if (select_print.now == 1) { + DWIN_ICON_Show(ICON, ICON_Pause_1, 96, 252); + DWIN_Draw_Rectangle(0, Color_White, 96, 252, 175, 351); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 181, 447, 208, 459, 124, 325); + else + DWIN_Frame_AreaCopy(1, 177, 451, 216, 462, 116, 325); + } + else { + DWIN_ICON_Show(ICON, ICON_Pause_0, 96, 252); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 181, 405, 208, 420, 124, 325); + else + DWIN_Frame_AreaCopy(1, 177, 423, 215, 433, 116, 325); + } +} + +void ICON_Continue() { + if (select_print.now == 1) { + DWIN_ICON_Show(ICON, ICON_Continue_1, 96, 252); + DWIN_Draw_Rectangle(0, Color_White, 96, 252, 175, 351); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 1, 447, 28, 460, 124, 325); + else + DWIN_Frame_AreaCopy(1, 1, 452, 32, 464, 121, 325); + } + else { + DWIN_ICON_Show(ICON, ICON_Continue_0, 96, 252); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 1, 405, 28, 420, 124, 325); + else + DWIN_Frame_AreaCopy(1, 1, 424, 31, 434, 121, 325); + } +} + +void ICON_Stop() { + if (select_print.now == 2) { + DWIN_ICON_Show(ICON, ICON_Stop_1, 184, 252); + DWIN_Draw_Rectangle(0, Color_White, 184, 252, 263, 351); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 151, 447, 178, 459, 210, 325); + else + DWIN_Frame_AreaCopy(1, 218, 452, 249, 466, 209, 325); + } + else { + DWIN_ICON_Show(ICON, ICON_Stop_0, 184, 252); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 151, 405, 178, 420, 210, 325); + else + DWIN_Frame_AreaCopy(1, 218, 423, 247, 436, 209, 325); + } +} + +inline void Clear_Title_Bar() { + DWIN_Draw_Box(1, Color_Bg_Blue, 0, 0, DWIN_WIDTH, TITLE_HEIGHT); +} + +void Draw_Title(const char * const title) { + DWIN_Draw_String(false, DWIN_FONT_HEAD, Color_White, Color_Bg_Blue, 14, 4, (char*)title); +} + +void Draw_Title(const __FlashStringHelper * title) { + DWIN_Draw_String(false, DWIN_FONT_HEAD, Color_White, Color_Bg_Blue, 14, 4, (char*)title); +} + +inline void Clear_Menu_Area() { + DWIN_Draw_Box(1, Color_Bg_Black, 0, TITLE_HEIGHT, DWIN_WIDTH, STATUS_Y - TITLE_HEIGHT); +} + +void Clear_Main_Window() { + Clear_Title_Bar(); + Clear_Menu_Area(); +} + +void Clear_Popup_Area() { + Clear_Title_Bar(); + DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, 31, DWIN_WIDTH, DWIN_HEIGHT); +} + +void Draw_Popup_Bkgd_105() { + DWIN_Draw_Rectangle(1, Color_Bg_Window, 14, 105, 258, 374); +} + +void Draw_More_Icon(const uint8_t line) { + DWIN_ICON_Show(ICON, ICON_More, 226, MBASE(line) - 3); +} + +void Draw_Menu_Cursor(const uint8_t line) { + // DWIN_ICON_Show(ICON,ICON_Rectangle, 0, MBASE(line) - 18); + DWIN_Draw_Rectangle(1, Rectangle_Color, 0, MBASE(line) - 18, 14, MBASE(line + 1) - 20); +} + +void Erase_Menu_Cursor(const uint8_t line) { + DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, MBASE(line) - 18, 14, MBASE(line + 1) - 20); +} + +void Move_Highlight(const int16_t from, const uint16_t newline) { + Erase_Menu_Cursor(newline - from); + Draw_Menu_Cursor(newline); +} + +void Add_Menu_Line() { + Move_Highlight(1, MROWS); + DWIN_Draw_Line(Line_Color, 16, MBASE(MROWS + 1) - 20, 256, MBASE(MROWS + 1) - 19); +} + +void Scroll_Menu(const uint8_t dir) { + DWIN_Frame_AreaMove(1, dir, MLINE, Color_Bg_Black, 0, 31, DWIN_WIDTH, 349); + switch (dir) { + case DWIN_SCROLL_DOWN: Move_Highlight(-1, 0); break; + case DWIN_SCROLL_UP: Add_Menu_Line(); break; + } +} + +inline uint16_t nr_sd_menu_items() { + return card.get_num_Files() + !card.flag.workDirIsRoot; +} + +void Draw_Menu_Icon(const uint8_t line, const uint8_t icon) { + DWIN_ICON_Show(ICON, icon, 26, MBASE(line) - 3); +} + +void Erase_Menu_Text(const uint8_t line) { + DWIN_Draw_Rectangle(1, Color_Bg_Black, LBLX, MBASE(line) - 14, 271, MBASE(line) + 28); +} + +void Draw_Menu_Item(const uint8_t line, const uint8_t icon=0, const char * const label=nullptr, bool more=false) { + if (label) DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(line) - 1, (char*)label); + if (icon) Draw_Menu_Icon(line, icon); + if (more) Draw_More_Icon(line); +} + +void Draw_Menu_Line(const uint8_t line, const uint8_t icon=0, const char * const label=nullptr, bool more=false) { + Draw_Menu_Item(line, icon, label, more); + DWIN_Draw_Line(Line_Color, 16, MBASE(line) + 33, 256, MBASE(line) + 34); +} + +void Draw_Chkb_Line(const uint8_t line, const bool mode) { + DWIN_Draw_Checkbox(Color_White, Color_Bg_Black, 225, MBASE(line) - 1, mode); +} + +// The "Back" label is always on the first line +void Draw_Back_Label() { + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 129, 72, 156, 84, LBLX, MBASE(0)); + else + DWIN_Frame_AreaCopy(1, 226, 179, 256, 189, LBLX, MBASE(0)); +} + +// Draw "Back" line at the top +void Draw_Back_First(const bool is_sel=true) { + Draw_Menu_Line(0, ICON_Back); + Draw_Back_Label(); + if (is_sel) Draw_Menu_Cursor(0); +} + +template +inline bool Apply_Encoder(const ENCODER_DiffState &encoder_diffState, T &valref) { + if (encoder_diffState == ENCODER_DIFF_CW) + valref += EncoderRate.encoderMoveValue; + else if (encoder_diffState == ENCODER_DIFF_CCW) + valref -= EncoderRate.encoderMoveValue; + return encoder_diffState == ENCODER_DIFF_ENTER; +} + +// +// Draw Menus +// + +#define MOTION_CASE_RATE 1 +#define MOTION_CASE_ACCEL 2 +#define MOTION_CASE_JERK (MOTION_CASE_ACCEL + ENABLED(HAS_CLASSIC_JERK)) +#define MOTION_CASE_STEPS (MOTION_CASE_JERK + 1) +#define MOTION_CASE_TOTAL MOTION_CASE_STEPS + +#define PREPARE_CASE_MOVE 1 +#define PREPARE_CASE_DISA 2 +#define PREPARE_CASE_HOME 3 +#define PREPARE_CASE_ZOFF (PREPARE_CASE_HOME + ENABLED(HAS_ZOFFSET_ITEM)) +#define PREPARE_CASE_PLA (PREPARE_CASE_ZOFF + ENABLED(HAS_HOTEND)) +#define PREPARE_CASE_ABS (PREPARE_CASE_PLA + ENABLED(HAS_HOTEND)) +#define PREPARE_CASE_COOL (PREPARE_CASE_ABS + EITHER(HAS_HOTEND, HAS_HEATED_BED)) +#define PREPARE_CASE_LANG (PREPARE_CASE_COOL + 1) +#define PREPARE_CASE_TOTAL PREPARE_CASE_LANG + +#define CONTROL_CASE_TEMP 1 +#define CONTROL_CASE_MOVE (CONTROL_CASE_TEMP + 1) +#define CONTROL_CASE_SAVE (CONTROL_CASE_MOVE + ENABLED(EEPROM_SETTINGS)) +#define CONTROL_CASE_LOAD (CONTROL_CASE_SAVE + ENABLED(EEPROM_SETTINGS)) +#define CONTROL_CASE_RESET (CONTROL_CASE_LOAD + ENABLED(EEPROM_SETTINGS)) +#define CONTROL_CASE_ADVSET (CONTROL_CASE_RESET + 1) +#define CONTROL_CASE_INFO (CONTROL_CASE_ADVSET + 1) +#define CONTROL_CASE_TOTAL CONTROL_CASE_INFO + +#define TUNE_CASE_SPEED 1 +#define TUNE_CASE_TEMP (TUNE_CASE_SPEED + ENABLED(HAS_HOTEND)) +#define TUNE_CASE_BED (TUNE_CASE_TEMP + ENABLED(HAS_HEATED_BED)) +#define TUNE_CASE_FAN (TUNE_CASE_BED + ENABLED(HAS_FAN)) +#define TUNE_CASE_ZOFF (TUNE_CASE_FAN + ENABLED(HAS_ZOFFSET_ITEM)) +#define TUNE_CASE_TOTAL TUNE_CASE_ZOFF + +#define TEMP_CASE_TEMP (0 + ENABLED(HAS_HOTEND)) +#define TEMP_CASE_BED (TEMP_CASE_TEMP + ENABLED(HAS_HEATED_BED)) +#define TEMP_CASE_FAN (TEMP_CASE_BED + ENABLED(HAS_FAN)) +#define TEMP_CASE_PLA (TEMP_CASE_FAN + ENABLED(HAS_HOTEND)) +#define TEMP_CASE_ABS (TEMP_CASE_PLA + ENABLED(HAS_HOTEND)) +#define TEMP_CASE_TOTAL TEMP_CASE_ABS + +#define PREHEAT_CASE_TEMP (0 + ENABLED(HAS_HOTEND)) +#define PREHEAT_CASE_BED (PREHEAT_CASE_TEMP + ENABLED(HAS_HEATED_BED)) +#define PREHEAT_CASE_FAN (PREHEAT_CASE_BED + ENABLED(HAS_FAN)) +#define PREHEAT_CASE_SAVE (PREHEAT_CASE_FAN + ENABLED(EEPROM_SETTINGS)) +#define PREHEAT_CASE_TOTAL PREHEAT_CASE_SAVE + +#define ADVSET_CASE_HOMEOFF 1 +#define ADVSET_CASE_PROBEOFF (ADVSET_CASE_HOMEOFF + ENABLED(HAS_ONESTEP_LEVELING)) +#define ADVSET_CASE_HEPID (ADVSET_CASE_PROBEOFF + ENABLED(HAS_HOTEND)) +#define ADVSET_CASE_BEDPID (ADVSET_CASE_HEPID + ENABLED(HAS_HEATED_BED)) +#define ADVSET_CASE_PWRLOSSR (ADVSET_CASE_BEDPID + ENABLED(POWER_LOSS_RECOVERY)) +#define ADVSET_CASE_TOTAL ADVSET_CASE_PWRLOSSR + +// +// Draw Menus +// + +void DWIN_Draw_Label(const uint16_t y, char *string) { + DWIN_Draw_String(true, font8x16, Color_White, Color_Bg_Black, LBLX, y, string); +} +void DWIN_Draw_Label(const uint16_t y, const __FlashStringHelper *title) { + DWIN_Draw_Label(y, (char*)title); +} + +void draw_move_en(const uint16_t line) { + #ifdef USE_STRING_TITLES + DWIN_Draw_Label(line, F("Move")); + #else + DWIN_Frame_AreaCopy(1, 69, 61, 102, 71, LBLX, line); // "Move" + #endif +} + +inline void DWIN_Frame_TitleCopy(uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2) { + DWIN_Frame_AreaCopy(id, x1, y1, x2, y2, 14, 8); +} + +void Item_Prepare_Move(const uint8_t row) { + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 159, 70, 200, 84, LBLX, MBASE(row)); + else + draw_move_en(MBASE(row)); // "Move" + Draw_Menu_Line(row, ICON_Axis); + Draw_More_Icon(row); +} + +void Item_Prepare_Disable(const uint8_t row) { + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 204, 70, 259, 82, LBLX, MBASE(row)); + else { + #ifdef USE_STRING_TITLES + DWIN_Draw_Label(MBASE(row), GET_TEXT_F(MSG_DISABLE_STEPPERS)); + #else + DWIN_Frame_AreaCopy(1, 103, 59, 200, 74, LBLX, MBASE(row)); // "Disable Stepper" + #endif + } + Draw_Menu_Line(row, ICON_CloseMotor); +} + +void Item_Prepare_Home(const uint8_t row) { + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 0, 89, 41, 101, LBLX, MBASE(row)); + else { + #ifdef USE_STRING_TITLES + DWIN_Draw_Label(MBASE(row), GET_TEXT_F(MSG_AUTO_HOME)); + #else + DWIN_Frame_AreaCopy(1, 202, 61, 271, 71, LBLX, MBASE(row)); // "Auto Home" + #endif + } + Draw_Menu_Line(row, ICON_Homing); +} + +#if HAS_ZOFFSET_ITEM + + void Item_Prepare_Offset(const uint8_t row) { + if (HMI_IsChinese()) { + #if HAS_BED_PROBE + DWIN_Frame_AreaCopy(1, 174, 164, 223, 177, LBLX, MBASE(row)); + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 2, 2, 202, MBASE(row), probe.offset.z * 100); + #else + DWIN_Frame_AreaCopy(1, 43, 89, 98, 101, LBLX, MBASE(row)); + #endif + } + else { + #if HAS_BED_PROBE + #ifdef USE_STRING_TITLES + DWIN_Draw_Label(MBASE(row), GET_TEXT_F(MSG_ZPROBE_ZOFFSET)); + #else + DWIN_Frame_AreaCopy(1, 93, 179, 141, 189, LBLX, MBASE(row)); // "Z-Offset" + #endif + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 2, 2, 202, MBASE(row), probe.offset.z * 100); + #else + #ifdef USE_STRING_TITLES + DWIN_Draw_Label(MBASE(row), GET_TEXT_F(MSG_SET_HOME_OFFSETS)); + #else + DWIN_Frame_AreaCopy(1, 1, 76, 106, 86, LBLX, MBASE(row)); // "Set home offsets" + #endif + #endif + } + Draw_Menu_Line(row, ICON_SetHome); + } + +#endif + +#if HAS_HOTEND + void Item_Prepare_PLA(const uint8_t row) { + if (HMI_IsChinese()) { + DWIN_Frame_AreaCopy(1, 100, 89, 151, 101, LBLX, MBASE(row)); + } + else { + #ifdef USE_STRING_TITLES + DWIN_Draw_Label(MBASE(row), F("Preheat " PREHEAT_1_LABEL)); + #else + DWIN_Frame_AreaCopy(1, 107, 76, 156, 86, LBLX, MBASE(row)); // "Preheat" + DWIN_Frame_AreaCopy(1, 157, 76, 181, 86, LBLX + 52, MBASE(row)); // "PLA" + #endif + } + Draw_Menu_Line(row, ICON_PLAPreheat); + } + + void Item_Prepare_ABS(const uint8_t row) { + if (HMI_IsChinese()) { + DWIN_Frame_AreaCopy(1, 180, 89, 233, 100, LBLX, MBASE(row)); + } + else { + #ifdef USE_STRING_TITLES + DWIN_Draw_Label(MBASE(row), F("Preheat " PREHEAT_2_LABEL)); + #else + DWIN_Frame_AreaCopy(1, 107, 76, 156, 86, LBLX, MBASE(row)); // "Preheat" + DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX + 52, MBASE(row)); // "ABS" + #endif + } + Draw_Menu_Line(row, ICON_ABSPreheat); + } +#endif + +#if HAS_PREHEAT + void Item_Prepare_Cool(const uint8_t row) { + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 1, 104, 56, 117, LBLX, MBASE(row)); + else { + #ifdef USE_STRING_TITLES + DWIN_Draw_Label(MBASE(row), GET_TEXT_F(MSG_COOLDOWN)); + #else + DWIN_Frame_AreaCopy(1, 200, 76, 264, 86, LBLX, MBASE(row)); // "Cooldown" + #endif + } + Draw_Menu_Line(row, ICON_Cool); + } +#endif + +void Item_Prepare_Lang(const uint8_t row) { + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 239, 134, 266, 146, LBLX, MBASE(row)); + else { + #ifdef USE_STRING_TITLES + DWIN_Draw_Label(MBASE(row), F("UI Language")); + #else + DWIN_Frame_AreaCopy(1, 0, 194, 121, 207, LBLX, MBASE(row)); // "Language selection" + #endif + } + DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Black, 226, MBASE(row), HMI_IsChinese() ? F("CN") : F("EN")); + Draw_Menu_Icon(row, ICON_Language); +} + +void Draw_Prepare_Menu() { + Clear_Main_Window(); + + const int16_t scroll = MROWS - index_prepare; // Scrolled-up lines + #define PSCROL(L) (scroll + (L)) + #define PVISI(L) WITHIN(PSCROL(L), 0, MROWS) + + if (HMI_IsChinese()) { + DWIN_Frame_TitleCopy(1, 133, 1, 160, 13); // "Prepare" + } + else { + #ifdef USE_STRING_HEADINGS + Draw_Title(GET_TEXT_F(MSG_PREPARE)); + #else + DWIN_Frame_TitleCopy(1, 178, 2, 229, 14); // "Prepare" + #endif + } + + if (PVISI(0)) Draw_Back_First(select_prepare.now == 0); // < Back + if (PVISI(PREPARE_CASE_MOVE)) Item_Prepare_Move(PSCROL(PREPARE_CASE_MOVE)); // Move > + if (PVISI(PREPARE_CASE_DISA)) Item_Prepare_Disable(PSCROL(PREPARE_CASE_DISA)); // Disable Stepper + if (PVISI(PREPARE_CASE_HOME)) Item_Prepare_Home(PSCROL(PREPARE_CASE_HOME)); // Auto Home + #if HAS_ZOFFSET_ITEM + if (PVISI(PREPARE_CASE_ZOFF)) Item_Prepare_Offset(PSCROL(PREPARE_CASE_ZOFF)); // Edit Z-Offset / Babystep / Set Home Offset + #endif + #if HAS_HOTEND + if (PVISI(PREPARE_CASE_PLA)) Item_Prepare_PLA(PSCROL(PREPARE_CASE_PLA)); // Preheat PLA + if (PVISI(PREPARE_CASE_ABS)) Item_Prepare_ABS(PSCROL(PREPARE_CASE_ABS)); // Preheat ABS + #endif + #if HAS_PREHEAT + if (PVISI(PREPARE_CASE_COOL)) Item_Prepare_Cool(PSCROL(PREPARE_CASE_COOL)); // Cooldown + #endif + if (PVISI(PREPARE_CASE_LANG)) Item_Prepare_Lang(PSCROL(PREPARE_CASE_LANG)); // Language CN/EN + + if (select_prepare.now) Draw_Menu_Cursor(PSCROL(select_prepare.now)); +} + +void Item_Control_Info(const uint16_t line) { + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 231, 104, 258, 116, LBLX, line); + else { + #ifdef USE_STRING_TITLES + DWIN_Draw_Label(line, F("Info")); + #else + DWIN_Frame_AreaCopy(1, 0, 104, 24, 114, LBLX, line); + #endif + } +} + +void Draw_Control_Menu() { + Clear_Main_Window(); + + #if CONTROL_CASE_TOTAL >= 6 + const int16_t scroll = MROWS - index_control; // Scrolled-up lines + #define CSCROL(L) (scroll + (L)) + #else + #define CSCROL(L) (L) + #endif + #define CLINE(L) MBASE(CSCROL(L)) + #define CVISI(L) WITHIN(CSCROL(L), 0, MROWS) + + if (CVISI(0)) Draw_Back_First(select_control.now == 0); // < Back + + if (HMI_IsChinese()) { + DWIN_Frame_TitleCopy(1, 103, 1, 130, 14); // "Control" + + DWIN_Frame_AreaCopy(1, 57, 104, 84, 116, LBLX, CLINE(CONTROL_CASE_TEMP)); // Temperature > + DWIN_Frame_AreaCopy(1, 87, 104, 114, 116, LBLX, CLINE(CONTROL_CASE_MOVE)); // Motion > + + #if ENABLED(EEPROM_SETTINGS) + DWIN_Frame_AreaCopy(1, 117, 104, 172, 116, LBLX, CLINE(CONTROL_CASE_SAVE)); // Store Configuration + DWIN_Frame_AreaCopy(1, 174, 103, 229, 116, LBLX, CLINE(CONTROL_CASE_LOAD)); // Read Configuration + DWIN_Frame_AreaCopy(1, 1, 118, 56, 131, LBLX, CLINE(CONTROL_CASE_RESET)); // Reset Configuration + #endif + } + else { + #ifdef USE_STRING_HEADINGS + Draw_Title(GET_TEXT_F(MSG_CONTROL)); + #else + DWIN_Frame_TitleCopy(1, 128, 2, 176, 12); // "Control" + #endif + #ifdef USE_STRING_TITLES + if (CVISI(CONTROL_CASE_TEMP)) DWIN_Draw_Label(CLINE(CONTROL_CASE_TEMP), GET_TEXT_F(MSG_TEMPERATURE)); + if (CVISI(CONTROL_CASE_MOVE)) DWIN_Draw_Label(CLINE(CONTROL_CASE_MOVE), GET_TEXT_F(MSG_MOTION)); + #if ENABLED(EEPROM_SETTINGS) + if (CVISI(CONTROL_CASE_SAVE)) DWIN_Draw_Label(CLINE(CONTROL_CASE_SAVE), GET_TEXT_F(MSG_STORE_EEPROM)); + if (CVISI(CONTROL_CASE_LOAD)) DWIN_Draw_Label(CLINE(CONTROL_CASE_LOAD), GET_TEXT_F(MSG_LOAD_EEPROM)); + if (CVISI(CONTROL_CASE_RESET)) DWIN_Draw_Label(CLINE(CONTROL_CASE_RESET), GET_TEXT_F(MSG_RESTORE_DEFAULTS)); + #endif + #else + if (CVISI(CONTROL_CASE_TEMP)) DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX, CLINE(CONTROL_CASE_TEMP)); // Temperature > + if (CVISI(CONTROL_CASE_MOVE)) DWIN_Frame_AreaCopy(1, 84, 89, 128, 99, LBLX, CLINE(CONTROL_CASE_MOVE)); // Motion > + #if ENABLED(EEPROM_SETTINGS) + if (CVISI(CONTROL_CASE_SAVE)) DWIN_Frame_AreaCopy(1, 148, 89, 268, 101, LBLX , CLINE(CONTROL_CASE_SAVE)); // "Store Configuration" + if (CVISI(CONTROL_CASE_LOAD)) { + DWIN_Frame_AreaCopy(1, 26, 104, 57, 114, LBLX , CLINE(CONTROL_CASE_LOAD)); // "Read" + DWIN_Frame_AreaCopy(1, 182, 89, 268, 101, LBLX + 34, CLINE(CONTROL_CASE_LOAD)); // "Configuration" + } + if (CVISI(CONTROL_CASE_RESET)) { + DWIN_Frame_AreaCopy(1, 59, 104, 93, 114, LBLX , CLINE(CONTROL_CASE_RESET)); // "Reset" + DWIN_Frame_AreaCopy(1, 182, 89, 268, 101, LBLX + 37, CLINE(CONTROL_CASE_RESET)); // "Configuration" + } + #endif + #endif + } + + if (CVISI(CONTROL_CASE_ADVSET)) { + DWIN_Draw_Label(CLINE(CONTROL_CASE_ADVSET), GET_TEXT_F(MSG_ADVANCED_SETTINGS)); // Advanced Settings + } + + if (CVISI(CONTROL_CASE_INFO)) Item_Control_Info(CLINE(CONTROL_CASE_INFO)); + + if (select_control.now && CVISI(select_control.now)) + Draw_Menu_Cursor(CSCROL(select_control.now)); + + // Draw icons and lines + #define _TEMP_ICON(N, I, M) do { \ + if (CVISI(N)) { \ + Draw_Menu_Line(CSCROL(N), I); \ + if (M) { \ + Draw_More_Icon(CSCROL(N)); \ + } \ + } \ + } while(0) + + _TEMP_ICON(CONTROL_CASE_TEMP, ICON_Temperature, true); + _TEMP_ICON(CONTROL_CASE_MOVE, ICON_Motion, true); + + #if ENABLED(EEPROM_SETTINGS) + _TEMP_ICON(CONTROL_CASE_SAVE, ICON_WriteEEPROM, false); + _TEMP_ICON(CONTROL_CASE_LOAD, ICON_ReadEEPROM, false); + _TEMP_ICON(CONTROL_CASE_RESET, ICON_ResumeEEPROM, false); + #endif + + _TEMP_ICON(CONTROL_CASE_ADVSET, ICON_AdvSet, true); + _TEMP_ICON(CONTROL_CASE_INFO, ICON_Info, true); +} + +void Draw_Tune_Menu() { + Clear_Main_Window(); + + if (HMI_IsChinese()) { + DWIN_Frame_TitleCopy(1, 73, 2, 100, 13); + DWIN_Frame_AreaCopy(1, 116, 164, 171, 176, LBLX, MBASE(TUNE_CASE_SPEED)); + #if HAS_HOTEND + DWIN_Frame_AreaCopy(1, 1, 134, 56, 146, LBLX, MBASE(TUNE_CASE_TEMP)); + #endif + #if HAS_HEATED_BED + DWIN_Frame_AreaCopy(1, 58, 134, 113, 146, LBLX, MBASE(TUNE_CASE_BED)); + #endif + #if HAS_FAN + DWIN_Frame_AreaCopy(1, 115, 134, 170, 146, LBLX, MBASE(TUNE_CASE_FAN)); + #endif + #if HAS_ZOFFSET_ITEM + DWIN_Frame_AreaCopy(1, 174, 164, 223, 177, LBLX, MBASE(TUNE_CASE_ZOFF)); + #endif + } + else { + #ifdef USE_STRING_HEADINGS + Draw_Title(GET_TEXT_F(MSG_TUNE)); + #else + DWIN_Frame_AreaCopy(1, 94, 2, 126, 12, 14, 9); + #endif + #ifdef USE_STRING_TITLES + DWIN_Draw_Label(MBASE(TUNE_CASE_SPEED), GET_TEXT_F(MSG_SPEED)); + #if HAS_HOTEND + DWIN_Draw_Label(MBASE(TUNE_CASE_TEMP), GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND)); + #endif + #if HAS_HEATED_BED + DWIN_Draw_Label(MBASE(TUNE_CASE_BED), GET_TEXT_F(MSG_UBL_SET_TEMP_BED)); + #endif + #if HAS_FAN + DWIN_Draw_Label(MBASE(TUNE_CASE_FAN), GET_TEXT_F(MSG_FAN_SPEED)); + #endif + DWIN_Draw_Label(MBASE(TUNE_CASE_ZOFF), GET_TEXT_F(MSG_ZPROBE_ZOFFSET)); + #else + DWIN_Frame_TitleCopy(1, 94, 2, 126, 12); + DWIN_Frame_AreaCopy(1, 1, 179, 92, 190, LBLX, MBASE(TUNE_CASE_SPEED)); // Print speed + #if HAS_HOTEND + DWIN_Frame_AreaCopy(1, 197, 104, 238, 114, LBLX, MBASE(TUNE_CASE_TEMP)); // Hotend... + DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 44, MBASE(TUNE_CASE_TEMP)); // ...Temperature + #endif + #if HAS_HEATED_BED + DWIN_Frame_AreaCopy(1, 240, 104, 264, 114, LBLX, MBASE(TUNE_CASE_BED)); // Bed... + DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 27, MBASE(TUNE_CASE_BED)); // ...Temperature + #endif + #if HAS_FAN + DWIN_Frame_AreaCopy(1, 0, 119, 64, 132, LBLX, MBASE(TUNE_CASE_FAN)); // Fan speed + #endif + #if HAS_ZOFFSET_ITEM + DWIN_Frame_AreaCopy(1, 93, 179, 141, 189, LBLX, MBASE(TUNE_CASE_ZOFF)); // Z-offset + #endif + #endif + } + + Draw_Back_First(select_tune.now == 0); + if (select_tune.now) Draw_Menu_Cursor(select_tune.now); + + Draw_Menu_Line(TUNE_CASE_SPEED, ICON_Speed); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TUNE_CASE_SPEED), feedrate_percentage); + + #if HAS_HOTEND + Draw_Menu_Line(TUNE_CASE_TEMP, ICON_HotendTemp); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TUNE_CASE_TEMP), thermalManager.degTargetHotend(0)); + #endif + #if HAS_HEATED_BED + Draw_Menu_Line(TUNE_CASE_BED, ICON_BedTemp); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TUNE_CASE_BED), thermalManager.degTargetBed()); + #endif + #if HAS_FAN + Draw_Menu_Line(TUNE_CASE_FAN, ICON_FanSpeed); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TUNE_CASE_FAN), thermalManager.fan_speed[0]); + #endif + #if HAS_ZOFFSET_ITEM + Draw_Menu_Line(TUNE_CASE_ZOFF, ICON_Zoffset); + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 2, 2, 202, MBASE(TUNE_CASE_ZOFF), BABY_Z_VAR * 100); + #endif +} + +void draw_max_en(const uint16_t line) { + DWIN_Frame_AreaCopy(1, 245, 119, 269, 129, LBLX, line); // "Max" +} +void draw_max_accel_en(const uint16_t line) { + draw_max_en(line); + DWIN_Frame_AreaCopy(1, 1, 135, 79, 145, LBLX + 27, line); // "Acceleration" +} +void draw_speed_en(const uint16_t inset, const uint16_t line) { + DWIN_Frame_AreaCopy(1, 184, 119, 224, 132, LBLX + inset, line); // "Speed" +} +void draw_jerk_en(const uint16_t line) { + DWIN_Frame_AreaCopy(1, 64, 119, 106, 129, LBLX + 27, line); // "Jerk" +} +void draw_steps_per_mm(const uint16_t line) { + DWIN_Frame_AreaCopy(1, 1, 151, 101, 161, LBLX, line); // "Steps-per-mm" +} +void say_x(const uint16_t inset, const uint16_t line) { + DWIN_Frame_AreaCopy(1, 95, 104, 102, 114, LBLX + inset, line); // "X" +} +void say_y(const uint16_t inset, const uint16_t line) { + DWIN_Frame_AreaCopy(1, 104, 104, 110, 114, LBLX + inset, line); // "Y" +} +void say_z(const uint16_t inset, const uint16_t line) { + DWIN_Frame_AreaCopy(1, 112, 104, 120, 114, LBLX + inset, line); // "Z" +} +void say_e(const uint16_t inset, const uint16_t line) { + DWIN_Frame_AreaCopy(1, 237, 119, 244, 129, LBLX + inset, line); // "E" +} + +void Draw_Motion_Menu() { + Clear_Main_Window(); + + if (HMI_IsChinese()) { + DWIN_Frame_TitleCopy(1, 1, 16, 28, 28); // "Motion" + DWIN_Frame_AreaCopy(1, 173, 133, 228, 147, LBLX, MBASE(MOTION_CASE_RATE)); // Max speed + DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX, MBASE(MOTION_CASE_ACCEL)); // Max... + DWIN_Frame_AreaCopy(1, 28, 149, 69, 161, LBLX + 27, MBASE(MOTION_CASE_ACCEL) + 1); // ...Acceleration + #if HAS_CLASSIC_JERK + DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX, MBASE(MOTION_CASE_JERK)); // Max... + DWIN_Frame_AreaCopy(1, 1, 180, 28, 192, LBLX + 27, MBASE(MOTION_CASE_JERK) + 1); // ... + DWIN_Frame_AreaCopy(1, 202, 133, 228, 147, LBLX + 54, MBASE(MOTION_CASE_JERK)); // ...Jerk + #endif + DWIN_Frame_AreaCopy(1, 153, 148, 194, 161, LBLX, MBASE(MOTION_CASE_STEPS)); // Flow ratio + } + else { + #ifdef USE_STRING_HEADINGS + Draw_Title(GET_TEXT_F(MSG_MOTION)); + #else + DWIN_Frame_TitleCopy(1, 144, 16, 189, 26); // "Motion" + #endif + #ifdef USE_STRING_TITLES + DWIN_Draw_Label(MBASE(MOTION_CASE_RATE), F("Feedrate")); + DWIN_Draw_Label(MBASE(MOTION_CASE_ACCEL), GET_TEXT_F(MSG_ACCELERATION)); + #if HAS_CLASSIC_JERK + DWIN_Draw_Label(MBASE(MOTION_CASE_JERK), GET_TEXT_F(MSG_JERK)); + #endif + DWIN_Draw_Label(MBASE(MOTION_CASE_STEPS), GET_TEXT_F(MSG_STEPS_PER_MM)); + #else + draw_max_en(MBASE(MOTION_CASE_RATE)); draw_speed_en(27, MBASE(MOTION_CASE_RATE)); // "Max Speed" + draw_max_accel_en(MBASE(MOTION_CASE_ACCEL)); // "Max Acceleration" + #if HAS_CLASSIC_JERK + draw_max_en(MBASE(MOTION_CASE_JERK)); draw_jerk_en(MBASE(MOTION_CASE_JERK)); // "Max Jerk" + #endif + draw_steps_per_mm(MBASE(MOTION_CASE_STEPS)); // "Steps-per-mm" + #endif + } + + Draw_Back_First(select_motion.now == 0); + if (select_motion.now) Draw_Menu_Cursor(select_motion.now); + + uint8_t i = 0; + #define _MOTION_ICON(N) Draw_Menu_Line(++i, ICON_MaxSpeed + (N) - 1) + _MOTION_ICON(MOTION_CASE_RATE); Draw_More_Icon(i); + _MOTION_ICON(MOTION_CASE_ACCEL); Draw_More_Icon(i); + #if HAS_CLASSIC_JERK + _MOTION_ICON(MOTION_CASE_JERK); Draw_More_Icon(i); + #endif + _MOTION_ICON(MOTION_CASE_STEPS); Draw_More_Icon(i); +} + +// +// Draw Popup Windows +// + +#if HAS_HOTEND || HAS_HEATED_BED + + void DWIN_Popup_Temperature(const bool toohigh) { + Clear_Popup_Area(); + Draw_Popup_Bkgd_105(); + if (toohigh) { + DWIN_ICON_Show(ICON, ICON_TempTooHigh, 102, 165); + if (HMI_IsChinese()) { + DWIN_Frame_AreaCopy(1, 103, 371, 237, 386, 52, 285); + DWIN_Frame_AreaCopy(1, 151, 389, 185, 402, 187, 285); + DWIN_Frame_AreaCopy(1, 189, 389, 271, 402, 95, 310); + } + else { + DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, 36, 300, F("Nozzle or Bed temperature")); + DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, 92, 300, F("is too high")); + } + } + else { + DWIN_ICON_Show(ICON, ICON_TempTooLow, 102, 165); + if (HMI_IsChinese()) { + DWIN_Frame_AreaCopy(1, 103, 371, 270, 386, 52, 285); + DWIN_Frame_AreaCopy(1, 189, 389, 271, 402, 95, 310); + } + else { + DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, 36, 300, F("Nozzle or Bed temperature")); + DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, 92, 300, F("is too low")); + } + } + } + +#endif + +void Draw_Popup_Bkgd_60() { + DWIN_Draw_Rectangle(1, Color_Bg_Window, 14, 60, 258, 330); +} + +#if HAS_HOTEND + + void Popup_Window_ETempTooLow() { + Clear_Main_Window(); + Draw_Popup_Bkgd_60(); + DWIN_ICON_Show(ICON, ICON_TempTooLow, 102, 105); + if (HMI_IsChinese()) { + DWIN_Frame_AreaCopy(1, 103, 371, 136, 386, 69, 240); + DWIN_Frame_AreaCopy(1, 170, 371, 270, 386, 69 + 33, 240); + DWIN_ICON_Show(ICON, ICON_Confirm_C, 86, 280); + } + else { + DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, 20, 235, F("Nozzle is too cold")); + DWIN_ICON_Show(ICON, ICON_Confirm_E, 86, 280); + } + } + +#endif + +void Popup_Window_Resume() { + Clear_Popup_Area(); + Draw_Popup_Bkgd_105(); + if (HMI_IsChinese()) { + DWIN_Frame_AreaCopy(1, 160, 338, 235, 354, 98, 135); + DWIN_Frame_AreaCopy(1, 103, 321, 271, 335, 52, 192); + DWIN_ICON_Show(ICON, ICON_Cancel_C, 26, 307); + DWIN_ICON_Show(ICON, ICON_Continue_C, 146, 307); + } + else { + DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 14) / 2, 115, F("Continue Print")); + DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 22) / 2, 192, F("It looks like the last")); + DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 22) / 2, 212, F("file was interrupted.")); + DWIN_ICON_Show(ICON, ICON_Cancel_E, 26, 307); + DWIN_ICON_Show(ICON, ICON_Continue_E, 146, 307); + } +} + +void Popup_Window_Home(const bool parking/*=false*/) { + Clear_Main_Window(); + Draw_Popup_Bkgd_60(); + DWIN_ICON_Show(ICON, ICON_BLTouch, 101, 105); + if (HMI_IsChinese()) { + DWIN_Frame_AreaCopy(1, 0, 371, 33, 386, 85, 240); + DWIN_Frame_AreaCopy(1, 203, 286, 271, 302, 118, 240); + DWIN_Frame_AreaCopy(1, 0, 389, 150, 402, 61, 280); + } + else { + DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * (parking ? 7 : 10)) / 2, 230, parking ? F("Parking") : F("Homing XYZ")); + DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 23) / 2, 260, F("Please wait until done.")); + } +} + +#if HAS_ONESTEP_LEVELING + + void Popup_Window_Leveling() { + Clear_Main_Window(); + Draw_Popup_Bkgd_60(); + DWIN_ICON_Show(ICON, ICON_AutoLeveling, 101, 105); + if (HMI_IsChinese()) { + DWIN_Frame_AreaCopy(1, 0, 371, 100, 386, 84, 240); + DWIN_Frame_AreaCopy(1, 0, 389, 150, 402, 61, 280); + } + else { + DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 13) / 2, 230, GET_TEXT_F(MSG_BED_LEVELING)); + DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 23) / 2, 260, F("Please wait until done.")); + } + } + +#endif + +void Draw_Select_Highlight(const bool sel) { + HMI_flag.select_flag = sel; + const uint16_t c1 = sel ? Select_Color : Color_Bg_Window, + c2 = sel ? Color_Bg_Window : Select_Color; + DWIN_Draw_Rectangle(0, c1, 25, 279, 126, 318); + DWIN_Draw_Rectangle(0, c1, 24, 278, 127, 319); + DWIN_Draw_Rectangle(0, c2, 145, 279, 246, 318); + DWIN_Draw_Rectangle(0, c2, 144, 278, 247, 319); +} + +void Popup_window_PauseOrStop() { + Clear_Main_Window(); + Draw_Popup_Bkgd_60(); + if (HMI_IsChinese()) { + if (select_print.now == 1) DWIN_Frame_AreaCopy(1, 237, 338, 269, 356, 98, 150); + else if (select_print.now == 2) DWIN_Frame_AreaCopy(1, 221, 320, 253, 336, 98, 150); + DWIN_Frame_AreaCopy(1, 220, 304, 264, 319, 130, 150); + DWIN_ICON_Show(ICON, ICON_Confirm_C, 26, 280); + DWIN_ICON_Show(ICON, ICON_Cancel_C, 146, 280); + } + else { + if (select_print.now == 1) DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 11) / 2, 150, GET_TEXT_F(MSG_PAUSE_PRINT)); + else if (select_print.now == 2) DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 10) / 2, 150, GET_TEXT_F(MSG_STOP_PRINT)); + DWIN_ICON_Show(ICON, ICON_Confirm_E, 26, 280); + DWIN_ICON_Show(ICON, ICON_Cancel_E, 146, 280); + } + Draw_Select_Highlight(true); +} + +void Draw_Printing_Screen() { + if (HMI_IsChinese()) { + DWIN_Frame_AreaCopy(1, 30, 1, 71, 14, 14, 9); // Tune + DWIN_Frame_AreaCopy(1, 0, 72, 63, 86, 41, 188); // Pause + DWIN_Frame_AreaCopy(1, 65, 72, 128, 86, 176, 188); // Stop + } + else { + DWIN_Frame_AreaCopy(1, 40, 2, 92, 14, 14, 9); // Tune + DWIN_Frame_AreaCopy(1, 0, 44, 96, 58, 41, 188); // Pause + DWIN_Frame_AreaCopy(1, 98, 44, 152, 58, 176, 188); // Stop + } +} + +void Draw_Print_ProgressBar() { + DWIN_ICON_Show(ICON, ICON_Bar, 15, 93); + DWIN_Draw_Rectangle(1, BarFill_Color, 16 + _card_percent * 240 / 100, 93, 256, 113); + DWIN_Draw_IntValue(true, true, 0, font8x16, Percent_Color, Color_Bg_Black, 2, 117, 133, _card_percent); + DWIN_Draw_String(false, font8x16, Percent_Color, Color_Bg_Black, 133, 133, F("%")); +} + +void Draw_Print_ProgressElapsed() { + duration_t elapsed = print_job_timer.duration(); // print timer + DWIN_Draw_IntValue(true, true, 1, font8x16, Color_White, Color_Bg_Black, 2, 42, 212, elapsed.value / 3600); + DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Black, 58, 212, F(":")); + DWIN_Draw_IntValue(true, true, 1, font8x16, Color_White, Color_Bg_Black, 2, 66, 212, (elapsed.value % 3600) / 60); +} + +void Draw_Print_ProgressRemain() { + DWIN_Draw_IntValue(true, true, 1, font8x16, Color_White, Color_Bg_Black, 2, 176, 212, _remain_time / 3600); + DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Black, 192, 212, F(":")); + DWIN_Draw_IntValue(true, true, 1, font8x16, Color_White, Color_Bg_Black, 2, 200, 212, (_remain_time % 3600) / 60); +} + +void Goto_PrintProcess() { + checkkey = PrintProcess; + + Clear_Main_Window(); + Draw_Printing_Screen(); + + ICON_Tune(); + if (printingIsPaused()) ICON_Continue(); else ICON_Pause(); + ICON_Stop(); + + // Copy into filebuf string before entry + char * const name = card.longest_filename(); + const int8_t npos = _MAX(0U, DWIN_WIDTH - strlen(name) * MENU_CHR_W) / 2; + DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Black, npos, 60, name); + + DWIN_ICON_Show(ICON, ICON_PrintTime, 17, 193); + DWIN_ICON_Show(ICON, ICON_RemainTime, 150, 191); + + Draw_Print_ProgressBar(); + Draw_Print_ProgressElapsed(); + Draw_Print_ProgressRemain(); +} + +void Goto_MainMenu() { + checkkey = MainMenu; + + Clear_Main_Window(); + + if (HMI_IsChinese()) + DWIN_Frame_TitleCopy(1, 2, 2, 27, 14); // "Home" + else { + #ifdef USE_STRING_HEADINGS + Draw_Title(GET_TEXT_F(MSG_MAIN)); + #else + DWIN_Frame_TitleCopy(1, 0, 2, 39, 12); + #endif + } + + DWIN_ICON_Show(ICON, ICON_LOGO, 71, 52); + + ICON_Print(); + ICON_Prepare(); + ICON_Control(); + TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(select_page.now == 3); +} + +inline ENCODER_DiffState get_encoder_state() { + static millis_t Encoder_ms = 0; + const millis_t ms = millis(); + if (PENDING(ms, Encoder_ms)) return ENCODER_DIFF_NO; + const ENCODER_DiffState state = Encoder_ReceiveAnalyze(); + if (state != ENCODER_DIFF_NO) Encoder_ms = ms + ENCODER_WAIT_MS; + return state; +} + +void HMI_Plan_Move(const feedRate_t fr_mm_s) { + if (!planner.is_full()) { + planner.synchronize(); + planner.buffer_line(current_position, fr_mm_s); + DWIN_UpdateLCD(); + } +} + +void HMI_Move_Done(const AxisEnum axis) { + EncoderRate.enabled = false; + planner.synchronize(); + checkkey = AxisMove; + DWIN_UpdateLCD(); +} + +void HMI_Move_X() { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Move_X_scaled)) + return HMI_Move_Done(X_AXIS); + LIMIT(HMI_ValueStruct.Move_X_scaled, (X_MIN_POS) * MINUNITMULT, (X_MAX_POS) * MINUNITMULT); + current_position.x = HMI_ValueStruct.Move_X_scaled / MINUNITMULT; + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 216, MBASE(1), HMI_ValueStruct.Move_X_scaled); + DWIN_UpdateLCD(); + HMI_Plan_Move(homing_feedrate(X_AXIS)); + } +} + +void HMI_Move_Y() { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Move_Y_scaled)) + return HMI_Move_Done(Y_AXIS); + LIMIT(HMI_ValueStruct.Move_Y_scaled, (Y_MIN_POS) * MINUNITMULT, (Y_MAX_POS) * MINUNITMULT); + current_position.y = HMI_ValueStruct.Move_Y_scaled / MINUNITMULT; + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 216, MBASE(2), HMI_ValueStruct.Move_Y_scaled); + DWIN_UpdateLCD(); + HMI_Plan_Move(homing_feedrate(Y_AXIS)); + } +} + +void HMI_Move_Z() { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Move_Z_scaled)) + return HMI_Move_Done(Z_AXIS); + LIMIT(HMI_ValueStruct.Move_Z_scaled, (Z_MIN_POS) * MINUNITMULT, (Z_MAX_POS) * MINUNITMULT); + current_position.z = HMI_ValueStruct.Move_Z_scaled / MINUNITMULT; + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 216, MBASE(3), HMI_ValueStruct.Move_Z_scaled); + DWIN_UpdateLCD(); + HMI_Plan_Move(homing_feedrate(Z_AXIS)); + } +} + +#if HAS_HOTEND + + void HMI_Move_E() { + static float last_E_scaled = 0; + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Move_E_scaled)) { + last_E_scaled = HMI_ValueStruct.Move_E_scaled; + return HMI_Move_Done(E_AXIS); + } + LIMIT(HMI_ValueStruct.Move_E_scaled, last_E_scaled - (EXTRUDE_MAXLENGTH) * MINUNITMULT, last_E_scaled + (EXTRUDE_MAXLENGTH) * MINUNITMULT); + current_position.e = HMI_ValueStruct.Move_E_scaled / MINUNITMULT; + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, UNITFDIGITS, 216, MBASE(4), HMI_ValueStruct.Move_E_scaled); + DWIN_UpdateLCD(); + HMI_Plan_Move(MMM_TO_MMS(FEEDRATE_E)); + } + } + +#endif + +#if HAS_ZOFFSET_ITEM + + bool printer_busy() { return planner.movesplanned() || printingIsActive(); } + + void HMI_Zoffset() { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + uint8_t zoff_line; + switch (HMI_ValueStruct.show_mode) { + case -4: zoff_line = PREPARE_CASE_ZOFF + MROWS - index_prepare; break; + default: zoff_line = TUNE_CASE_ZOFF + MROWS - index_tune; + } + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.offset_value)) { + EncoderRate.enabled = false; + #if HAS_BED_PROBE + probe.offset.z = dwin_zoffset; + TERN_(EEPROM_SETTINGS, settings.save()); + #endif + checkkey = HMI_ValueStruct.show_mode == -4 ? Prepare : Tune; + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 2, 2, 202, MBASE(zoff_line), TERN(HAS_BED_PROBE, BABY_Z_VAR * 100, HMI_ValueStruct.offset_value)); + DWIN_UpdateLCD(); + return; + } + 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 (BABYSTEP_ALLOWED()) babystep.add_mm(Z_AXIS, dwin_zoffset - last_zoffset); + #endif + DWIN_Draw_Signed_Float(font8x16, Select_Color, 2, 2, 202, MBASE(zoff_line), HMI_ValueStruct.offset_value); + DWIN_UpdateLCD(); + } + } + +#endif // HAS_ZOFFSET_ITEM + +#if HAS_HOTEND + + void HMI_ETemp() { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + uint8_t temp_line; + switch (HMI_ValueStruct.show_mode) { + case -1: temp_line = TEMP_CASE_TEMP; break; + case -2: temp_line = PREHEAT_CASE_TEMP; break; + case -3: temp_line = PREHEAT_CASE_TEMP; break; + default: temp_line = TUNE_CASE_TEMP + MROWS - index_tune; + } + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.E_Temp)) { + EncoderRate.enabled = false; + if (HMI_ValueStruct.show_mode == -2) { + checkkey = PLAPreheat; + ui.material_preset[0].hotend_temp = HMI_ValueStruct.E_Temp; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(temp_line), ui.material_preset[0].hotend_temp); + return; + } + else if (HMI_ValueStruct.show_mode == -3) { + checkkey = ABSPreheat; + ui.material_preset[1].hotend_temp = HMI_ValueStruct.E_Temp; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(temp_line), ui.material_preset[1].hotend_temp); + return; + } + else if (HMI_ValueStruct.show_mode == -1) // Temperature + checkkey = TemperatureID; + else + checkkey = Tune; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(temp_line), HMI_ValueStruct.E_Temp); + thermalManager.setTargetHotend(HMI_ValueStruct.E_Temp, 0); + return; + } + // E_Temp limit + LIMIT(HMI_ValueStruct.E_Temp, HEATER_0_MINTEMP, thermalManager.hotend_max_target(0)); + // E_Temp value + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(temp_line), HMI_ValueStruct.E_Temp); + } + } + +#endif // HAS_HOTEND + +#if HAS_HEATED_BED + + void HMI_BedTemp() { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + uint8_t bed_line; + switch (HMI_ValueStruct.show_mode) { + case -1: bed_line = TEMP_CASE_BED; break; + case -2: bed_line = PREHEAT_CASE_BED; break; + case -3: bed_line = PREHEAT_CASE_BED; break; + default: bed_line = TUNE_CASE_BED + MROWS - index_tune; + } + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Bed_Temp)) { + EncoderRate.enabled = false; + if (HMI_ValueStruct.show_mode == -2) { + checkkey = PLAPreheat; + ui.material_preset[0].bed_temp = HMI_ValueStruct.Bed_Temp; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(bed_line), ui.material_preset[0].bed_temp); + return; + } + else if (HMI_ValueStruct.show_mode == -3) { + checkkey = ABSPreheat; + ui.material_preset[1].bed_temp = HMI_ValueStruct.Bed_Temp; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(bed_line), ui.material_preset[1].bed_temp); + return; + } + else if (HMI_ValueStruct.show_mode == -1) + checkkey = TemperatureID; + else + checkkey = Tune; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(bed_line), HMI_ValueStruct.Bed_Temp); + thermalManager.setTargetBed(HMI_ValueStruct.Bed_Temp); + return; + } + // Bed_Temp limit + LIMIT(HMI_ValueStruct.Bed_Temp, BED_MINTEMP, BED_MAX_TARGET); + // Bed_Temp value + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(bed_line), HMI_ValueStruct.Bed_Temp); + } + } + +#endif // HAS_HEATED_BED + +#if HAS_PREHEAT && HAS_FAN + + void HMI_FanSpeed() { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + uint8_t fan_line; + switch (HMI_ValueStruct.show_mode) { + case -1: fan_line = TEMP_CASE_FAN; break; + case -2: fan_line = PREHEAT_CASE_FAN; break; + case -3: fan_line = PREHEAT_CASE_FAN; break; + default: fan_line = TUNE_CASE_FAN + MROWS - index_tune; + } + + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Fan_speed)) { + EncoderRate.enabled = false; + if (HMI_ValueStruct.show_mode == -2) { + checkkey = PLAPreheat; + ui.material_preset[0].fan_speed = HMI_ValueStruct.Fan_speed; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(fan_line), ui.material_preset[0].fan_speed); + return; + } + else if (HMI_ValueStruct.show_mode == -3) { + checkkey = ABSPreheat; + ui.material_preset[1].fan_speed = HMI_ValueStruct.Fan_speed; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(fan_line), ui.material_preset[1].fan_speed); + return; + } + else if (HMI_ValueStruct.show_mode == -1) + checkkey = TemperatureID; + else + checkkey = Tune; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(fan_line), HMI_ValueStruct.Fan_speed); + thermalManager.set_fan_speed(0, HMI_ValueStruct.Fan_speed); + return; + } + // Fan_speed limit + LIMIT(HMI_ValueStruct.Fan_speed, 0, 255); + // Fan_speed value + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(fan_line), HMI_ValueStruct.Fan_speed); + } + } + +#endif // HAS_PREHEAT && HAS_FAN + +void HMI_PrintSpeed() { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.print_speed)) { + checkkey = Tune; + EncoderRate.enabled = false; + feedrate_percentage = HMI_ValueStruct.print_speed; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(select_tune.now + MROWS - index_tune), HMI_ValueStruct.print_speed); + return; + } + // print_speed limit + LIMIT(HMI_ValueStruct.print_speed, MIN_PRINT_SPEED, MAX_PRINT_SPEED); + // print_speed value + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(select_tune.now + MROWS - index_tune), HMI_ValueStruct.print_speed); + } +} + +#define LAST_AXIS TERN(HAS_HOTEND, E_AXIS, Z_AXIS) + +void HMI_MaxFeedspeedXYZE() { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Max_Feedspeed)) { + checkkey = MaxSpeed; + EncoderRate.enabled = false; + if (WITHIN(HMI_flag.feedspeed_axis, X_AXIS, LAST_AXIS)) + planner.set_max_feedrate(HMI_flag.feedspeed_axis, HMI_ValueStruct.Max_Feedspeed); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(select_speed.now), HMI_ValueStruct.Max_Feedspeed); + return; + } + // MaxFeedspeed limit + if (WITHIN(HMI_flag.feedspeed_axis, X_AXIS, LAST_AXIS)) + NOMORE(HMI_ValueStruct.Max_Feedspeed, default_max_feedrate[HMI_flag.feedspeed_axis] * 2); + if (HMI_ValueStruct.Max_Feedspeed < MIN_MAXFEEDSPEED) HMI_ValueStruct.Max_Feedspeed = MIN_MAXFEEDSPEED; + // MaxFeedspeed value + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 4, 210, MBASE(select_speed.now), HMI_ValueStruct.Max_Feedspeed); + } +} + +void HMI_MaxAccelerationXYZE() { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Max_Acceleration)) { + checkkey = MaxAcceleration; + EncoderRate.enabled = false; + if (WITHIN(HMI_flag.acc_axis, X_AXIS, LAST_AXIS)) + planner.set_max_acceleration(HMI_flag.acc_axis, HMI_ValueStruct.Max_Acceleration); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(select_acc.now), HMI_ValueStruct.Max_Acceleration); + return; + } + // MaxAcceleration limit + if (WITHIN(HMI_flag.acc_axis, X_AXIS, LAST_AXIS)) + NOMORE(HMI_ValueStruct.Max_Acceleration, default_max_acceleration[HMI_flag.acc_axis] * 2); + if (HMI_ValueStruct.Max_Acceleration < MIN_MAXACCELERATION) HMI_ValueStruct.Max_Acceleration = MIN_MAXACCELERATION; + // MaxAcceleration value + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 4, 210, MBASE(select_acc.now), HMI_ValueStruct.Max_Acceleration); + } +} + +#if HAS_CLASSIC_JERK + + void HMI_MaxJerkXYZE() { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Max_Jerk_scaled)) { + checkkey = MaxJerk; + EncoderRate.enabled = false; + if (WITHIN(HMI_flag.jerk_axis, X_AXIS, LAST_AXIS)) + planner.set_max_jerk(HMI_flag.jerk_axis, HMI_ValueStruct.Max_Jerk_scaled / 10); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk_scaled); + return; + } + // MaxJerk limit + if (WITHIN(HMI_flag.jerk_axis, X_AXIS, LAST_AXIS)) + NOMORE(HMI_ValueStruct.Max_Jerk_scaled, default_max_jerk[HMI_flag.jerk_axis] * 2 * MINUNITMULT); + NOLESS(HMI_ValueStruct.Max_Jerk_scaled, (MIN_MAXJERK) * MINUNITMULT); + // MaxJerk value + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, UNITFDIGITS, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk_scaled); + } + } + +#endif // HAS_CLASSIC_JERK + +void HMI_StepXYZE() { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Max_Step_scaled)) { + checkkey = Step; + EncoderRate.enabled = false; + if (WITHIN(HMI_flag.step_axis, X_AXIS, LAST_AXIS)) + planner.settings.axis_steps_per_mm[HMI_flag.step_axis] = HMI_ValueStruct.Max_Step_scaled / 10; + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step_scaled); + return; + } + // Step limit + if (WITHIN(HMI_flag.step_axis, X_AXIS, LAST_AXIS)) + NOMORE(HMI_ValueStruct.Max_Step_scaled, 999.9 * MINUNITMULT); + NOLESS(HMI_ValueStruct.Max_Step_scaled, MIN_STEP); + // Step value + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, UNITFDIGITS, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step_scaled); + } +} + +// Draw X, Y, Z and blink if in an un-homed or un-trusted state +void _update_axis_value(const AxisEnum axis, const uint16_t x, const uint16_t y, const bool blink, const bool force) { + const bool draw_qmark = axis_should_home(axis), + draw_empty = NONE(HOME_AFTER_DEACTIVATE, DISABLE_REDUCED_ACCURACY_WARNING) && !draw_qmark && !axis_is_trusted(axis); + + // Check for a position change + static xyz_pos_t oldpos = { -1, -1, -1 }; + const float p = current_position[axis]; + const bool changed = oldpos[axis] != p; + if (changed) oldpos[axis] = p; + + if (force || changed || draw_qmark || draw_empty) { + if (blink && draw_qmark) + DWIN_Draw_String(true, font8x16, Color_White, Color_Bg_Black, x, y, F("???.?")); + else if (blink && draw_empty) + DWIN_Draw_String(true, font8x16, Color_White, Color_Bg_Black, x, y, F(" ")); + else + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, x, y, p * 10); + } +} + +void _draw_xyz_position(const bool force) { + //SERIAL_ECHOPGM("Draw XYZ:"); + static bool _blink = false; + const bool blink = !!(millis() & 0x400UL); + if (force || blink != _blink) { + _blink = blink; + //SERIAL_ECHOPGM(" (blink)"); + _update_axis_value(X_AXIS, 35, 459, blink, true); + _update_axis_value(Y_AXIS, 120, 459, blink, true); + _update_axis_value(Z_AXIS, 205, 459, blink, true); + } + //SERIAL_EOL(); +} + +void update_variable() { + #if HAS_HOTEND + static celsius_t _hotendtemp = 0, _hotendtarget = 0; + const celsius_t hc = thermalManager.wholeDegHotend(0), + ht = thermalManager.degTargetHotend(0); + const bool _new_hotend_temp = _hotendtemp != hc, + _new_hotend_target = _hotendtarget != ht; + if (_new_hotend_temp) _hotendtemp = hc; + if (_new_hotend_target) _hotendtarget = ht; + #endif + #if HAS_HEATED_BED + static celsius_t _bedtemp = 0, _bedtarget = 0; + const celsius_t bc = thermalManager.wholeDegBed(), + bt = thermalManager.degTargetBed(); + const bool _new_bed_temp = _bedtemp != bc, + _new_bed_target = _bedtarget != bt; + if (_new_bed_temp) _bedtemp = bc; + if (_new_bed_target) _bedtarget = bt; + #endif + #if HAS_FAN + static uint8_t _fanspeed = 0; + const bool _new_fanspeed = _fanspeed != thermalManager.fan_speed[0]; + if (_new_fanspeed) _fanspeed = thermalManager.fan_speed[0]; + #endif + + if (checkkey == Tune) { + // Tune page temperature update + #if HAS_HOTEND + if (_new_hotend_target) + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TUNE_CASE_TEMP + MROWS - index_tune), _hotendtarget); + #endif + #if HAS_HEATED_BED + if (_new_bed_target) + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TUNE_CASE_BED + MROWS - index_tune), _bedtarget); + #endif + #if HAS_FAN + if (_new_fanspeed) + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TUNE_CASE_FAN + MROWS - index_tune), _fanspeed); + #endif + } + else if (checkkey == TemperatureID) { + // Temperature page temperature update + #if HAS_HOTEND + if (_new_hotend_target) + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TEMP_CASE_TEMP), _hotendtarget); + #endif + #if HAS_HEATED_BED + if (_new_bed_target) + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TEMP_CASE_BED), _bedtarget); + #endif + #if HAS_FAN + if (_new_fanspeed) + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TEMP_CASE_FAN), _fanspeed); + #endif + } + + // Bottom temperature update + + #if HAS_HOTEND + if (_new_hotend_temp) + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 28, 384, _hotendtemp); + if (_new_hotend_target) + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 25 + 4 * STAT_CHR_W + 6, 384, _hotendtarget); + + static int16_t _flow = planner.flow_percentage[0]; + if (_flow != planner.flow_percentage[0]) { + _flow = planner.flow_percentage[0]; + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 116 + 2 * STAT_CHR_W, 417, _flow); + } + #endif + + #if HAS_HEATED_BED + if (_new_bed_temp) + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 28, 417, _bedtemp); + if (_new_bed_target) + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 25 + 4 * STAT_CHR_W + 6, 417, _bedtarget); + #endif + + static int16_t _feedrate = 100; + if (_feedrate != feedrate_percentage) { + _feedrate = feedrate_percentage; + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 116 + 2 * STAT_CHR_W, 384, _feedrate); + } + + #if HAS_FAN + if (_new_fanspeed) { + _fanspeed = thermalManager.fan_speed[0]; + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 195 + 2 * STAT_CHR_W, 384, _fanspeed); + } + #endif + + static float _offset = 0; + if (BABY_Z_VAR != _offset) { + _offset = BABY_Z_VAR; + if (BABY_Z_VAR < 0) { + DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 2, 2, 207, 417, -_offset * 100); + DWIN_Draw_String(true, font8x16, Color_White, Color_Bg_Black, 205, 419, F("-")); + } + else { + DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 2, 2, 207, 417, _offset * 100); + DWIN_Draw_String(true, font8x16, Color_White, Color_Bg_Black, 205, 419, F(" ")); + } + } + + _draw_xyz_position(false); +} + +/** + * Read and cache the working directory. + * + * TODO: New code can follow the pattern of menu_media.cpp + * and rely on Marlin caching for performance. No need to + * cache files here. + */ + +#ifndef strcasecmp_P + #define strcasecmp_P(a, b) strcasecmp((a), (b)) +#endif + +void make_name_without_ext(char *dst, char *src, size_t maxlen=MENU_CHAR_LIMIT) { + char * const name = card.longest_filename(); + size_t pos = strlen(name); // index of ending nul + + // For files, remove the extension + // which may be .gcode, .gco, or .g + if (!card.flag.filenameIsDir) + while (pos && src[pos] != '.') pos--; // find last '.' (stop at 0) + + size_t len = pos; // nul or '.' + if (len > maxlen) { // Keep the name short + pos = len = maxlen; // move nul down + dst[--pos] = '.'; // insert dots + dst[--pos] = '.'; + dst[--pos] = '.'; + } + + dst[len] = '\0'; // end it + + // Copy down to 0 + while (pos--) dst[pos] = src[pos]; +} + +void HMI_SDCardInit() { card.cdroot(); } + +void MarlinUI::refresh() { /* Nothing to see here */ } + +#define ICON_Folder ICON_More + +#if ENABLED(SCROLL_LONG_FILENAMES) + + char shift_name[LONG_FILENAME_LENGTH + 1]; + int8_t shift_amt; // = 0 + millis_t shift_ms; // = 0 + + // Init the shift name based on the highlighted item + 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(); + if (WITHIN(filenum, 0, fileCnt - 1)) { + card.getfilename_sorted(SD_ORDER(filenum, fileCnt)); + char * const name = card.longest_filename(); + make_name_without_ext(shift_name, name, 100); + } + } + + void Init_SDItem_Shift() { + shift_amt = 0; + shift_ms = select_file.now > 0 && strlen(shift_name) > MENU_CHAR_LIMIT + ? millis() + 750UL : 0; + } + +#endif + +/** + * Display an SD item, adding a CDUP for subfolders. + */ +void Draw_SDItem(const uint16_t item, int16_t row=-1) { + if (row < 0) row = item + 1 + MROWS - index_file; + const bool is_subdir = !card.flag.workDirIsRoot; + if (is_subdir && item == 0) { + Draw_Menu_Line(row, ICON_Folder, ".."); + return; + } + + card.getfilename_sorted(SD_ORDER(item - is_subdir, card.get_num_Files())); + char * const name = card.longest_filename(); + + #if ENABLED(SCROLL_LONG_FILENAMES) + // Init the current selected name + // This is used during scroll drawing + if (item == select_file.now - 1) { + make_name_without_ext(shift_name, name, 100); + Init_SDItem_Shift(); + } + #endif + + // Draw the file/folder with name aligned left + char str[strlen(name) + 1]; + make_name_without_ext(str, name); + Draw_Menu_Line(row, card.flag.filenameIsDir ? ICON_Folder : ICON_File, str); +} + +#if ENABLED(SCROLL_LONG_FILENAMES) + + void Draw_SDItem_Shifted(uint8_t &shift) { + // Limit to the number of chars past the cutoff + const size_t len = strlen(shift_name); + NOMORE(shift, _MAX(len - MENU_CHAR_LIMIT, 0U)); + + // Shorten to the available space + const size_t lastchar = _MIN((signed)len, shift + MENU_CHAR_LIMIT); + + const char c = shift_name[lastchar]; + shift_name[lastchar] = '\0'; + + const uint8_t row = select_file.now + MROWS - index_file; // skip "Back" and scroll + Erase_Menu_Text(row); + Draw_Menu_Line(row, 0, &shift_name[shift]); + + shift_name[lastchar] = c; + } + +#endif + +// Redraw the first set of SD Files +void Redraw_SD_List() { + select_file.reset(); + index_file = MROWS; + + Clear_Menu_Area(); // Leave title bar unchanged + + Draw_Back_First(); + + if (card.isMounted()) { + // As many files as will fit + LOOP_L_N(i, _MIN(nr_sd_menu_items(), MROWS)) + Draw_SDItem(i, i + 1); + + TERN_(SCROLL_LONG_FILENAMES, Init_SDItem_Shift()); + } + else { + DWIN_Draw_Rectangle(1, Color_Bg_Red, 10, MBASE(3) - 10, DWIN_WIDTH - 10, MBASE(4)); + DWIN_Draw_String(false, font16x32, Color_Yellow, Color_Bg_Red, ((DWIN_WIDTH) - 8 * 16) / 2, MBASE(3), F("No Media")); + } +} + +bool DWIN_lcd_sd_status = false; + +void SDCard_Up() { + card.cdup(); + Redraw_SD_List(); + DWIN_lcd_sd_status = false; // On next DWIN_Update +} + +void SDCard_Folder(char * const dirname) { + card.cd(dirname); + Redraw_SD_List(); + DWIN_lcd_sd_status = false; // On next DWIN_Update +} + +// +// Watch for media mount / unmount +// +void HMI_SDCardUpdate() { + if (HMI_flag.home_flag) return; + if (DWIN_lcd_sd_status != card.isMounted()) { + DWIN_lcd_sd_status = card.isMounted(); + //SERIAL_ECHOLNPAIR("HMI_SDCardUpdate: ", DWIN_lcd_sd_status); + if (DWIN_lcd_sd_status) { + if (checkkey == SelectFile) + Redraw_SD_List(); + } + else { + // clean file icon + if (checkkey == SelectFile) { + Redraw_SD_List(); + } + else if (checkkey == PrintProcess || checkkey == Tune || printingIsActive()) { + // TODO: Move card removed abort handling + // to CardReader::manage_media. + card.abortFilePrintSoon(); + wait_for_heatup = wait_for_user = false; + dwin_abort_flag = true; // Reset feedrate, return to Home + } + } + DWIN_UpdateLCD(); + } +} + +// +// The status area is always on-screen, except during +// full-screen modal dialogs. (TODO: Keep alive during dialogs) +// +void Draw_Status_Area(const bool with_update) { + + DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, STATUS_Y, DWIN_WIDTH, DWIN_HEIGHT - 1); + + #if HAS_HOTEND + DWIN_ICON_Show(ICON, ICON_HotendTemp, 10, 383); + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 28, 384, thermalManager.wholeDegHotend(0)); + DWIN_Draw_String(false, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 25 + 3 * STAT_CHR_W + 5, 384, F("/")); + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 25 + 4 * STAT_CHR_W + 6, 384, thermalManager.degTargetHotend(0)); + + DWIN_ICON_Show(ICON, ICON_StepE, 112, 417); + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 116 + 2 * STAT_CHR_W, 417, planner.flow_percentage[0]); + DWIN_Draw_String(false, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 116 + 5 * STAT_CHR_W + 2, 417, F("%")); + #endif + + #if HAS_HEATED_BED + DWIN_ICON_Show(ICON, ICON_BedTemp, 10, 416); + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 28, 417, thermalManager.wholeDegBed()); + DWIN_Draw_String(false, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 25 + 3 * STAT_CHR_W + 5, 417, F("/")); + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 25 + 4 * STAT_CHR_W + 6, 417, thermalManager.degTargetBed()); + #endif + + DWIN_ICON_Show(ICON, ICON_Speed, 113, 383); + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 116 + 2 * STAT_CHR_W, 384, feedrate_percentage); + DWIN_Draw_String(false, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 116 + 5 * STAT_CHR_W + 2, 384, F("%")); + + #if HAS_FAN + DWIN_ICON_Show(ICON, ICON_FanSpeed, 187, 383); + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 195 + 2 * STAT_CHR_W, 384, thermalManager.fan_speed[0]); + #endif + + #if HAS_ZOFFSET_ITEM + DWIN_ICON_Show(ICON, ICON_Zoffset, 187, 416); + #endif + + if (BABY_Z_VAR < 0) { + DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 2, 2, 207, 417, -BABY_Z_VAR * 100); + DWIN_Draw_String(true, font8x16, Color_White, Color_Bg_Black, 205, 419, F("-")); + } + else { + DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 2, 2, 207, 417, BABY_Z_VAR * 100); + DWIN_Draw_String(true, font8x16, Color_White, Color_Bg_Black, 205, 419, F(" ")); + } + + DWIN_Draw_Rectangle(1, Line_Color, 0, 449, DWIN_WIDTH, 451); + + DWIN_ICON_Show(ICON, ICON_MaxSpeedX, 10, 456); + DWIN_ICON_Show(ICON, ICON_MaxSpeedY, 95, 456); + DWIN_ICON_Show(ICON, ICON_MaxSpeedZ, 180, 456); + _draw_xyz_position(true); + + if (with_update) { + DWIN_UpdateLCD(); + delay(5); + } +} + +void HMI_StartFrame(const bool with_update) { + Goto_MainMenu(); + Draw_Status_Area(with_update); +} + +void Draw_Info_Menu() { + Clear_Main_Window(); + + DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Black, (DWIN_WIDTH - strlen(MACHINE_SIZE) * MENU_CHR_W) / 2, 122, F(MACHINE_SIZE)); + DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Black, (DWIN_WIDTH - strlen(SHORT_BUILD_VERSION) * MENU_CHR_W) / 2, 195, F(SHORT_BUILD_VERSION)); + + if (HMI_IsChinese()) { + DWIN_Frame_TitleCopy(1, 30, 17, 57, 29); // "Info" + + DWIN_Frame_AreaCopy(1, 197, 149, 252, 161, 108, 102); + DWIN_Frame_AreaCopy(1, 1, 164, 56, 176, 108, 175); + DWIN_Frame_AreaCopy(1, 58, 164, 113, 176, 105, 248); + } + else { + #ifdef USE_STRING_HEADINGS + Draw_Title(GET_TEXT_F(MSG_INFO_SCREEN)); + #else + DWIN_Frame_TitleCopy(1, 190, 16, 215, 26); // "Info" + #endif + + DWIN_Frame_AreaCopy(1, 120, 150, 146, 161, 124, 102); + DWIN_Frame_AreaCopy(1, 146, 151, 254, 161, 82, 175); + DWIN_Frame_AreaCopy(1, 0, 165, 94, 175, 89, 248); + } + 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) { + 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); + } +} + +void Draw_Print_File_Menu() { + Clear_Title_Bar(); + + if (HMI_IsChinese()) { + DWIN_Frame_TitleCopy(1, 0, 31, 55, 44); // "Print file" + } + else { + #ifdef USE_STRING_HEADINGS + Draw_Title("Print file"); // TODO: GET_TEXT_F + #else + DWIN_Frame_TitleCopy(1, 52, 31, 137, 41); // "Print file" + #endif + } + + Redraw_SD_List(); +} + +/* Main Process */ +void HMI_MainMenu() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_page.inc(4)) { + switch (select_page.now) { + case 0: ICON_Print(); break; + case 1: ICON_Print(); ICON_Prepare(); break; + case 2: ICON_Prepare(); ICON_Control(); break; + case 3: ICON_Control(); TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(1); break; + } + } + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_page.dec()) { + switch (select_page.now) { + case 0: ICON_Print(); ICON_Prepare(); break; + case 1: ICON_Prepare(); ICON_Control(); break; + case 2: ICON_Control(); TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(0); break; + case 3: TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(1); break; + } + } + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + switch (select_page.now) { + case 0: // Print File + checkkey = SelectFile; + Draw_Print_File_Menu(); + break; + + case 1: // Prepare + checkkey = Prepare; + select_prepare.reset(); + index_prepare = MROWS; + Draw_Prepare_Menu(); + break; + + case 2: // Control + checkkey = Control; + select_control.reset(); + index_control = MROWS; + Draw_Control_Menu(); + break; + + case 3: // Leveling or Info + #if HAS_ONESTEP_LEVELING + checkkey = Leveling; + HMI_Leveling(); + #else + checkkey = Info; + Draw_Info_Menu(); + #endif + break; + } + } + DWIN_UpdateLCD(); +} + +// Select (and Print) File +void HMI_SelectFile() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + + const uint16_t hasUpDir = !card.flag.workDirIsRoot; + + if (encoder_diffState == ENCODER_DIFF_NO) { + #if ENABLED(SCROLL_LONG_FILENAMES) + if (shift_ms && select_file.now >= 1 + hasUpDir) { + // Scroll selected filename every second + const millis_t ms = millis(); + if (ELAPSED(ms, shift_ms)) { + const bool was_reset = shift_amt < 0; + shift_ms = ms + 375UL + was_reset * 250UL; // ms per character + uint8_t shift_new = shift_amt + 1; // Try to shift by... + Draw_SDItem_Shifted(shift_new); // Draw the item + if (!was_reset && shift_new == 0) // Was it limited to 0? + shift_ms = 0; // No scrolling needed + else if (shift_new == shift_amt) // Scroll reached the end + shift_new = -1; // Reset + shift_amt = shift_new; // Set new scroll + } + } + #endif + return; + } + + // First pause is long. Easy. + // On reset, long pause must be after 0. + + const uint16_t fullCnt = nr_sd_menu_items(); + + if (encoder_diffState == ENCODER_DIFF_CW && fullCnt) { + if (select_file.inc(1 + fullCnt)) { + const uint8_t itemnum = select_file.now - 1; // -1 for "Back" + if (TERN0(SCROLL_LONG_FILENAMES, shift_ms)) { // If line was shifted + Erase_Menu_Text(itemnum + MROWS - index_file); // Erase and + Draw_SDItem(itemnum - 1); // redraw + } + if (select_file.now > MROWS && select_file.now > index_file) { // Cursor past the bottom + index_file = select_file.now; // New bottom line + Scroll_Menu(DWIN_SCROLL_UP); + Draw_SDItem(itemnum, MROWS); // Draw and init the shift name + } + else { + Move_Highlight(1, select_file.now + MROWS - index_file); // Just move highlight + TERN_(SCROLL_LONG_FILENAMES, Init_Shift_Name()); // ...and init the shift name + } + TERN_(SCROLL_LONG_FILENAMES, Init_SDItem_Shift()); + } + } + else if (encoder_diffState == ENCODER_DIFF_CCW && fullCnt) { + if (select_file.dec()) { + const uint8_t itemnum = select_file.now - 1; // -1 for "Back" + if (TERN0(SCROLL_LONG_FILENAMES, shift_ms)) { // If line was shifted + Erase_Menu_Text(select_file.now + 1 + MROWS - index_file); // Erase and + Draw_SDItem(itemnum + 1); // redraw + } + if (select_file.now < index_file - MROWS) { // Cursor past the top + index_file--; // New bottom line + Scroll_Menu(DWIN_SCROLL_DOWN); + if (index_file == MROWS) { + Draw_Back_First(); + TERN_(SCROLL_LONG_FILENAMES, shift_ms = 0); + } + else { + Draw_SDItem(itemnum, 0); // Draw the item (and init shift name) + } + } + else { + Move_Highlight(-1, select_file.now + MROWS - index_file); // Just move highlight + TERN_(SCROLL_LONG_FILENAMES, Init_Shift_Name()); // ...and init the shift name + } + TERN_(SCROLL_LONG_FILENAMES, Init_SDItem_Shift()); // Reset left. Init timer. + } + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + if (select_file.now == 0) { // Back + select_page.set(0); + Goto_MainMenu(); + } + else if (hasUpDir && select_file.now == 1) { // CD-Up + SDCard_Up(); + goto HMI_SelectFileExit; + } + else { + const uint16_t filenum = select_file.now - 1 - hasUpDir; + card.getfilename_sorted(SD_ORDER(filenum, card.get_num_Files())); + + // Enter that folder! + if (card.flag.filenameIsDir) { + SDCard_Folder(card.filename); + goto HMI_SelectFileExit; + } + + // Reset highlight for next entry + select_print.reset(); + select_file.reset(); + + // Start choice and print SD file + HMI_flag.heat_flag = true; + HMI_flag.print_finish = false; + HMI_ValueStruct.show_mode = 0; + + card.openAndPrintFile(card.filename); + + #if HAS_FAN + // All fans on for Ender 3 v2 ? + // The slicer should manage this for us. + //for (uint8_t i = 0; i < FAN_COUNT; i++) + // thermalManager.fan_speed[i] = 255; + #endif + + Goto_PrintProcess(); + } + } +HMI_SelectFileExit: + DWIN_UpdateLCD(); +} + +/* Printing */ +void HMI_Printing() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + if (HMI_flag.done_confirm_flag) { + if (encoder_diffState == ENCODER_DIFF_ENTER) { + HMI_flag.done_confirm_flag = false; + dwin_abort_flag = true; // Reset feedrate, return to Home + } + return; + } + + // Avoid flicker by updating only the previous menu + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_print.inc(3)) { + switch (select_print.now) { + case 0: ICON_Tune(); break; + case 1: + ICON_Tune(); + if (printingIsPaused()) ICON_Continue(); else ICON_Pause(); + break; + case 2: + if (printingIsPaused()) ICON_Continue(); else ICON_Pause(); + ICON_Stop(); + break; + } + } + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_print.dec()) { + switch (select_print.now) { + case 0: + ICON_Tune(); + if (printingIsPaused()) ICON_Continue(); else ICON_Pause(); + break; + case 1: + if (printingIsPaused()) ICON_Continue(); else ICON_Pause(); + ICON_Stop(); + break; + case 2: ICON_Stop(); break; + } + } + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + switch (select_print.now) { + case 0: // Tune + checkkey = Tune; + HMI_ValueStruct.show_mode = 0; + select_tune.reset(); + index_tune = MROWS; + Draw_Tune_Menu(); + break; + case 1: // Pause + if (HMI_flag.pause_flag) { + ICON_Pause(); + + char cmd[40]; + cmd[0] = '\0'; + + #if BOTH(HAS_HEATED_BED, PAUSE_HEAT) + if (resume_bed_temp) sprintf_P(cmd, PSTR("M190 S%i\n"), resume_bed_temp); + #endif + #if BOTH(HAS_HOTEND, PAUSE_HEAT) + if (resume_hotend_temp) sprintf_P(&cmd[strlen(cmd)], PSTR("M109 S%i\n"), resume_hotend_temp); + #endif + + strcat_P(cmd, M24_STR); + queue.inject(cmd); + } + else { + HMI_flag.select_flag = true; + checkkey = Print_window; + Popup_window_PauseOrStop(); + } + break; + + case 2: // Stop + HMI_flag.select_flag = true; + checkkey = Print_window; + Popup_window_PauseOrStop(); + break; + + default: break; + } + } + DWIN_UpdateLCD(); +} + +/* Pause and Stop window */ +void HMI_PauseOrStop() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + if (encoder_diffState == ENCODER_DIFF_CW) + Draw_Select_Highlight(false); + else if (encoder_diffState == ENCODER_DIFF_CCW) + Draw_Select_Highlight(true); + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + if (select_print.now == 1) { // pause window + if (HMI_flag.select_flag) { + HMI_flag.pause_action = true; + ICON_Continue(); + queue.inject_P(PSTR("M25")); + } + else { + // cancel pause + } + Goto_PrintProcess(); + } + else if (select_print.now == 2) { // stop window + if (HMI_flag.select_flag) { + checkkey = Back_Main; + if (HMI_flag.home_flag) planner.synchronize(); // Wait for planner moves to finish! + wait_for_heatup = wait_for_user = false; // Stop waiting for heating/user + card.abortFilePrintSoon(); // Let the main loop handle SD abort + dwin_abort_flag = true; // Reset feedrate, return to Home + #ifdef ACTION_ON_CANCEL + host_action_cancel(); + #endif + Popup_Window_Home(true); + } + else + Goto_PrintProcess(); // cancel stop + } + } + DWIN_UpdateLCD(); +} + +void Draw_Move_Menu() { + Clear_Main_Window(); + + if (HMI_IsChinese()) { + DWIN_Frame_TitleCopy(1, 192, 1, 233, 14); // "Move" + DWIN_Frame_AreaCopy(1, 58, 118, 106, 132, LBLX, MBASE(1)); + DWIN_Frame_AreaCopy(1, 109, 118, 157, 132, LBLX, MBASE(2)); + DWIN_Frame_AreaCopy(1, 160, 118, 209, 132, LBLX, MBASE(3)); + #if HAS_HOTEND + DWIN_Frame_AreaCopy(1, 212, 118, 253, 131, LBLX, MBASE(4)); + #endif + } + else { + #ifdef USE_STRING_HEADINGS + Draw_Title(GET_TEXT_F(MSG_MOVE_AXIS)); + #else + DWIN_Frame_TitleCopy(1, 231, 2, 265, 12); // "Move" + #endif + draw_move_en(MBASE(1)); say_x(36, MBASE(1)); // "Move X" + draw_move_en(MBASE(2)); say_y(36, MBASE(2)); // "Move Y" + draw_move_en(MBASE(3)); say_z(36, MBASE(3)); // "Move Z" + #if HAS_HOTEND + DWIN_Frame_AreaCopy(1, 123, 192, 176, 202, LBLX, MBASE(4)); // "Extruder" + #endif + } + + Draw_Back_First(select_axis.now == 0); + if (select_axis.now) 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); +} + +void Draw_AdvSet_Menu() { + Clear_Main_Window(); + + #if ADVSET_CASE_TOTAL >= 6 + const int16_t scroll = MROWS - index_advset; // Scrolled-up lines + #define ASCROL(L) (scroll + (L)) + #else + #define ASCROL(L) (L) + #endif + + #define AVISI(L) WITHIN(ASCROL(L), 0, MROWS) + + Draw_Title(GET_TEXT_F(MSG_ADVANCED_SETTINGS)); + + if (AVISI(0)) Draw_Back_First(select_advset.now == 0); + if (AVISI(ADVSET_CASE_HOMEOFF)) Draw_Menu_Line(ASCROL(ADVSET_CASE_HOMEOFF), ICON_HomeOff, GET_TEXT(MSG_SET_HOME_OFFSETS),true); // Home Offset > + #if HAS_ONESTEP_LEVELING + if (AVISI(ADVSET_CASE_PROBEOFF)) Draw_Menu_Line(ASCROL(ADVSET_CASE_PROBEOFF), ICON_ProbeOff, GET_TEXT(MSG_ZPROBE_OFFSETS),true); // Probe Offset > + #endif + if (AVISI(ADVSET_CASE_HEPID)) Draw_Menu_Line(ASCROL(ADVSET_CASE_HEPID), ICON_PIDNozzle, "Hotend PID", false); // Nozzle PID + if (AVISI(ADVSET_CASE_BEDPID)) Draw_Menu_Line(ASCROL(ADVSET_CASE_BEDPID), ICON_PIDbed, "Bed PID", false); // Bed PID + #if ENABLED(POWER_LOSS_RECOVERY) + if (AVISI(ADVSET_CASE_PWRLOSSR)) { + Draw_Menu_Line(ASCROL(ADVSET_CASE_PWRLOSSR), ICON_Motion, "Power-loss recovery", false); // Power-loss recovery + Draw_Chkb_Line(ASCROL(ADVSET_CASE_PWRLOSSR), recovery.enabled); + } + #endif + if (select_advset.now) Draw_Menu_Cursor(ASCROL(select_advset.now)); +} + +void Draw_HomeOff_Menu() { + Clear_Main_Window(); + Draw_Title(GET_TEXT_F(MSG_SET_HOME_OFFSETS)); // Home Offsets + Draw_Back_First(select_item.now == 0); + Draw_Menu_Line(1, ICON_HomeOffX, GET_TEXT(MSG_HOME_OFFSET_X)); // Home X Offset + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, 1, 216, MBASE(1), HMI_ValueStruct.Home_OffX_scaled); + Draw_Menu_Line(2, ICON_HomeOffY, GET_TEXT(MSG_HOME_OFFSET_Y)); // Home Y Offset + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, 1, 216, MBASE(2), HMI_ValueStruct.Home_OffY_scaled); + Draw_Menu_Line(3, ICON_HomeOffZ, GET_TEXT(MSG_HOME_OFFSET_Z)); // Home Y Offset + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, 1, 216, MBASE(3), HMI_ValueStruct.Home_OffZ_scaled); + if (select_item.now) Draw_Menu_Cursor(select_item.now); +} + +#if HAS_ONESTEP_LEVELING + void Draw_ProbeOff_Menu() { + Clear_Main_Window(); + Draw_Title(GET_TEXT_F(MSG_ZPROBE_OFFSETS)); // Probe Offsets + Draw_Back_First(select_item.now == 0); + Draw_Menu_Line(1, ICON_ProbeOffX, GET_TEXT(MSG_ZPROBE_XOFFSET)); // Probe X Offset + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, 1, 216, MBASE(1), HMI_ValueStruct.Probe_OffX_scaled); + Draw_Menu_Line(2, ICON_ProbeOffY, GET_TEXT(MSG_ZPROBE_YOFFSET)); // Probe Y Offset + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, 1, 216, MBASE(2), HMI_ValueStruct.Probe_OffY_scaled); + if (select_item.now) Draw_Menu_Cursor(select_item.now); + } +#endif + +#include "../../../libs/buzzer.h" + +void HMI_AudioFeedback(const bool success=true) { + #if HAS_BUZZER + if (success) { + buzzer.tone(100, 659); + buzzer.tone(10, 0); + buzzer.tone(100, 698); + } + else + buzzer.tone(40, 440); + #endif +} + +/* Prepare */ +void HMI_Prepare() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + // Avoid flicker by updating only the previous menu + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_prepare.inc(1 + PREPARE_CASE_TOTAL)) { + if (select_prepare.now > MROWS && select_prepare.now > index_prepare) { + index_prepare = select_prepare.now; + + // Scroll up and draw a blank bottom line + Scroll_Menu(DWIN_SCROLL_UP); + Draw_Menu_Icon(MROWS, ICON_Axis + select_prepare.now - 1); + + // Draw "More" icon for sub-menus + if (index_prepare < 7) Draw_More_Icon(MROWS - index_prepare + 1); + + #if HAS_HOTEND + if (index_prepare == PREPARE_CASE_ABS) Item_Prepare_ABS(MROWS); + #endif + #if HAS_PREHEAT + if (index_prepare == PREPARE_CASE_COOL) Item_Prepare_Cool(MROWS); + #endif + if (index_prepare == PREPARE_CASE_LANG) Item_Prepare_Lang(MROWS); + } + else { + Move_Highlight(1, select_prepare.now + MROWS - index_prepare); + } + } + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_prepare.dec()) { + if (select_prepare.now < index_prepare - MROWS) { + index_prepare--; + Scroll_Menu(DWIN_SCROLL_DOWN); + + if (index_prepare == MROWS) + Draw_Back_First(); + else + Draw_Menu_Line(0, ICON_Axis + select_prepare.now - 1); + + if (index_prepare < 7) Draw_More_Icon(MROWS - index_prepare + 1); + + if (index_prepare == 6) Item_Prepare_Move(0); + else if (index_prepare == 7) Item_Prepare_Disable(0); + else if (index_prepare == 8) Item_Prepare_Home(0); + } + else { + Move_Highlight(-1, select_prepare.now + MROWS - index_prepare); + } + } + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + switch (select_prepare.now) { + case 0: // Back + select_page.set(1); + Goto_MainMenu(); + break; + case PREPARE_CASE_MOVE: // Axis move + checkkey = AxisMove; + select_axis.reset(); + Draw_Move_Menu(); + + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 216, MBASE(1), current_position.x * MINUNITMULT); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 216, MBASE(2), current_position.y * MINUNITMULT); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 216, MBASE(3), current_position.z * MINUNITMULT); + #if HAS_HOTEND + HMI_ValueStruct.Move_E_scaled = current_position.e * MINUNITMULT; + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, 1, 216, MBASE(4), HMI_ValueStruct.Move_E_scaled); + #endif + break; + case PREPARE_CASE_DISA: // Disable steppers + queue.inject_P(PSTR("M84")); + break; + case PREPARE_CASE_HOME: // Homing + checkkey = Last_Prepare; + index_prepare = MROWS; + queue.inject_P(G28_STR); // G28 will set home_flag + Popup_Window_Home(); + break; + #if HAS_ZOFFSET_ITEM + case PREPARE_CASE_ZOFF: // Z-offset + #if EITHER(HAS_BED_PROBE, BABYSTEPPING) + checkkey = Homeoffset; + HMI_ValueStruct.show_mode = -4; + HMI_ValueStruct.offset_value = BABY_Z_VAR * 100; + DWIN_Draw_Signed_Float(font8x16, Select_Color, 2, 2, 202, MBASE(PREPARE_CASE_ZOFF + MROWS - index_prepare), HMI_ValueStruct.offset_value); + EncoderRate.enabled = true; + #else + // Apply workspace offset, making the current position 0,0,0 + queue.inject_P(PSTR("G92 X0 Y0 Z0")); + HMI_AudioFeedback(); + #endif + break; + #endif + #if HAS_PREHEAT + case PREPARE_CASE_PLA: // PLA preheat + TERN_(HAS_HOTEND, thermalManager.setTargetHotend(ui.material_preset[0].hotend_temp, 0)); + TERN_(HAS_HEATED_BED, thermalManager.setTargetBed(ui.material_preset[0].bed_temp)); + TERN_(HAS_FAN, thermalManager.set_fan_speed(0, ui.material_preset[0].fan_speed)); + break; + case PREPARE_CASE_ABS: // ABS preheat + TERN_(HAS_HOTEND, thermalManager.setTargetHotend(ui.material_preset[1].hotend_temp, 0)); + TERN_(HAS_HEATED_BED, thermalManager.setTargetBed(ui.material_preset[1].bed_temp)); + TERN_(HAS_FAN, thermalManager.set_fan_speed(0, ui.material_preset[1].fan_speed)); + break; + case PREPARE_CASE_COOL: // Cool + TERN_(HAS_FAN, thermalManager.zero_fan_speeds()); + #if HAS_HOTEND || HAS_HEATED_BED + thermalManager.disable_all_heaters(); + #endif + break; + #endif + case PREPARE_CASE_LANG: // Toggle Language + HMI_ToggleLanguage(); + Draw_Prepare_Menu(); + break; + default: break; + } + } + DWIN_UpdateLCD(); +} + +void Draw_Temperature_Menu() { + Clear_Main_Window(); + + if (HMI_IsChinese()) { + DWIN_Frame_TitleCopy(1, 236, 2, 263, 13); // "Temperature" + #if HAS_HOTEND + DWIN_Frame_AreaCopy(1, 1, 134, 56, 146, LBLX, MBASE(TEMP_CASE_TEMP)); + #endif + #if HAS_HEATED_BED + DWIN_Frame_AreaCopy(1, 58, 134, 113, 146, LBLX, MBASE(TEMP_CASE_BED)); + #endif + #if HAS_FAN + DWIN_Frame_AreaCopy(1, 115, 134, 170, 146, LBLX, MBASE(TEMP_CASE_FAN)); + #endif + #if HAS_HOTEND + DWIN_Frame_AreaCopy(1, 100, 89, 178, 101, LBLX, MBASE(TEMP_CASE_PLA)); + DWIN_Frame_AreaCopy(1, 180, 89, 260, 100, LBLX, MBASE(TEMP_CASE_ABS)); + #endif + } + else { + #ifdef USE_STRING_HEADINGS + Draw_Title(GET_TEXT_F(MSG_TEMPERATURE)); + #else + DWIN_Frame_TitleCopy(1, 56, 16, 141, 28); // "Temperature" + #endif + #ifdef USE_STRING_TITLES + #if HAS_HOTEND + DWIN_Draw_Label(MBASE(TEMP_CASE_TEMP), GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND)); + #endif + #if HAS_HEATED_BED + DWIN_Draw_Label(MBASE(TEMP_CASE_BED), GET_TEXT_F(MSG_UBL_SET_TEMP_BED)); + #endif + #if HAS_FAN + DWIN_Draw_Label(MBASE(TEMP_CASE_FAN), GET_TEXT_F(MSG_FAN_SPEED)); + #endif + #if HAS_HOTEND + DWIN_Draw_Label(MBASE(TEMP_CASE_PLA), F("PLA Preheat Settings")); + DWIN_Draw_Label(MBASE(TEMP_CASE_ABS), F("ABS Preheat Settings")); + #endif + #else + #if HAS_HOTEND + DWIN_Frame_AreaCopy(1, 197, 104, 238, 114, LBLX, MBASE(TEMP_CASE_TEMP)); // Nozzle... + DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 44, MBASE(TEMP_CASE_TEMP)); // ...Temperature + #endif + #if HAS_HEATED_BED + DWIN_Frame_AreaCopy(1, 240, 104, 264, 114, LBLX, MBASE(TEMP_CASE_BED)); // Bed... + DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 27, MBASE(TEMP_CASE_BED)); // ...Temperature + #endif + #if HAS_FAN + DWIN_Frame_AreaCopy(1, 0, 119, 64, 132, LBLX, MBASE(TEMP_CASE_FAN)); // Fan speed + #endif + #if HAS_HOTEND + DWIN_Frame_AreaCopy(1, 107, 76, 156, 86, LBLX, MBASE(TEMP_CASE_PLA)); // Preheat... + DWIN_Frame_AreaCopy(1, 157, 76, 181, 86, LBLX + 52, MBASE(TEMP_CASE_PLA)); // ...PLA + DWIN_Frame_AreaCopy(1, 131, 119, 182, 132, LBLX + 79, MBASE(TEMP_CASE_PLA)); // PLA setting + DWIN_Frame_AreaCopy(1, 107, 76, 156, 86, LBLX, MBASE(TEMP_CASE_ABS)); // Preheat... + DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX + 52, MBASE(TEMP_CASE_ABS)); // ...ABS + DWIN_Frame_AreaCopy(1, 131, 119, 182, 132, LBLX + 81, MBASE(TEMP_CASE_ABS)); // ABS setting + #endif + #endif + } + + Draw_Back_First(select_temp.now == 0); + if (select_temp.now) Draw_Menu_Cursor(select_temp.now); + + // Draw icons and lines + uint8_t i = 0; + #define _TMENU_ICON(N) Draw_Menu_Line(++i, ICON_SetEndTemp + (N) - 1) + #if HAS_HOTEND + _TMENU_ICON(TEMP_CASE_TEMP); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), thermalManager.degTargetHotend(0)); + #endif + #if HAS_HEATED_BED + _TMENU_ICON(TEMP_CASE_BED); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), thermalManager.degTargetBed()); + #endif + #if HAS_FAN + _TMENU_ICON(TEMP_CASE_FAN); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), thermalManager.fan_speed[0]); + #endif + #if HAS_HOTEND + // PLA/ABS items have submenus + _TMENU_ICON(TEMP_CASE_PLA); + Draw_More_Icon(i); + _TMENU_ICON(TEMP_CASE_ABS); + Draw_More_Icon(i); + #endif +} + +/* Control */ +void HMI_Control() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + // Avoid flicker by updating only the previous menu + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_control.inc(1 + CONTROL_CASE_TOTAL)) { + if (select_control.now > MROWS && select_control.now > index_control) { + index_control = select_control.now; + + // Scroll up and draw a blank bottom line + Scroll_Menu(DWIN_SCROLL_UP); + + switch (index_control) { // Last menu items + case CONTROL_CASE_ADVSET: // Advanced Settings > + Draw_Menu_Item(MROWS, ICON_AdvSet, GET_TEXT(MSG_ADVANCED_SETTINGS), true); + break; + case CONTROL_CASE_INFO: // Info > + Item_Control_Info(MBASE(MROWS)); + Draw_Menu_Icon(MROWS, ICON_Info); + break; + default: break; + } + + } + else { + Move_Highlight(1, select_control.now + MROWS - index_control); + } + } + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_control.dec()) { + if (select_control.now < index_control - MROWS) { + index_control--; + Scroll_Menu(DWIN_SCROLL_DOWN); + switch (index_control) { // First menu items + case MROWS : + Draw_Back_First(); + break; + case MROWS + 1: // Temperature > + Draw_Menu_Line(0, ICON_Temperature, GET_TEXT(MSG_TEMPERATURE), true); + break; + case MROWS + 2: // Move > + Draw_Menu_Line(0, ICON_Motion, GET_TEXT(MSG_MOTION), true); + default: break; + } + } + else { + Move_Highlight(-1, select_control.now + MROWS - index_control); + } + } + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + switch (select_control.now) { + case 0: // Back + select_page.set(2); + Goto_MainMenu(); + break; + case CONTROL_CASE_TEMP: // Temperature + checkkey = TemperatureID; + HMI_ValueStruct.show_mode = -1; + select_temp.reset(); + Draw_Temperature_Menu(); + break; + case CONTROL_CASE_MOVE: // Motion + checkkey = Motion; + select_motion.reset(); + Draw_Motion_Menu(); + break; + #if ENABLED(EEPROM_SETTINGS) + case CONTROL_CASE_SAVE: { // Write EEPROM + const bool success = settings.save(); + HMI_AudioFeedback(success); + } break; + case CONTROL_CASE_LOAD: { // Read EEPROM + const bool success = settings.load(); + HMI_AudioFeedback(success); + } break; + case CONTROL_CASE_RESET: // Reset EEPROM + settings.reset(); + HMI_AudioFeedback(); + break; + #endif + case CONTROL_CASE_ADVSET: // Advanced Settings + checkkey = AdvSet; + select_advset.reset(); + Draw_AdvSet_Menu(); + break; + case CONTROL_CASE_INFO: // Info + checkkey = Info; + Draw_Info_Menu(); + break; + default: break; + } + } + DWIN_UpdateLCD(); +} + + +#if HAS_ONESTEP_LEVELING + + /* Leveling */ + void HMI_Leveling() { + Popup_Window_Leveling(); + DWIN_UpdateLCD(); + queue.inject_P(PSTR("G28O\nG29")); + } + +#endif + +/* Axis Move */ +void HMI_AxisMove() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + #if ENABLED(PREVENT_COLD_EXTRUSION) + // popup window resume + if (HMI_flag.ETempTooLow_flag) { + if (encoder_diffState == ENCODER_DIFF_ENTER) { + HMI_flag.ETempTooLow_flag = false; + HMI_ValueStruct.Move_E_scaled = current_position.e * MINUNITMULT; + Draw_Move_Menu(); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 216, MBASE(1), HMI_ValueStruct.Move_X_scaled); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 216, MBASE(2), HMI_ValueStruct.Move_Y_scaled); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 216, MBASE(3), HMI_ValueStruct.Move_Z_scaled); + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, 1, 216, MBASE(4), 0); + DWIN_UpdateLCD(); + } + return; + } + #endif + + // Avoid flicker by updating only the previous menu + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_axis.inc(1 + 3 + ENABLED(HAS_HOTEND))) Move_Highlight(1, select_axis.now); + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_axis.dec()) Move_Highlight(-1, select_axis.now); + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + switch (select_axis.now) { + case 0: // Back + checkkey = Prepare; + select_prepare.set(1); + index_prepare = MROWS; + Draw_Prepare_Menu(); + break; + case 1: // X axis move + checkkey = Move_X; + HMI_ValueStruct.Move_X_scaled = current_position.x * MINUNITMULT; + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 216, MBASE(1), HMI_ValueStruct.Move_X_scaled); + EncoderRate.enabled = true; + break; + case 2: // Y axis move + checkkey = Move_Y; + HMI_ValueStruct.Move_Y_scaled = current_position.y * MINUNITMULT; + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 216, MBASE(2), HMI_ValueStruct.Move_Y_scaled); + EncoderRate.enabled = true; + break; + case 3: // Z axis move + checkkey = Move_Z; + HMI_ValueStruct.Move_Z_scaled = current_position.z * MINUNITMULT; + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 216, MBASE(3), HMI_ValueStruct.Move_Z_scaled); + EncoderRate.enabled = true; + break; + #if HAS_HOTEND + case 4: // Extruder + // window tips + #ifdef PREVENT_COLD_EXTRUSION + if (thermalManager.tooColdToExtrude(0)) { + HMI_flag.ETempTooLow_flag = true; + Popup_Window_ETempTooLow(); + DWIN_UpdateLCD(); + return; + } + #endif + checkkey = Extruder; + HMI_ValueStruct.Move_E_scaled = current_position.e * MINUNITMULT; + DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, 1, 216, MBASE(4), HMI_ValueStruct.Move_E_scaled); + EncoderRate.enabled = true; + break; + #endif + } + } + DWIN_UpdateLCD(); +} + +/* TemperatureID */ +void HMI_Temperature() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + // Avoid flicker by updating only the previous menu + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_temp.inc(1 + TEMP_CASE_TOTAL)) Move_Highlight(1, select_temp.now); + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_temp.dec()) Move_Highlight(-1, select_temp.now); + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + switch (select_temp.now) { + case 0: // Back + checkkey = Control; + select_control.set(1); + index_control = MROWS; + Draw_Control_Menu(); + break; + #if HAS_HOTEND + case TEMP_CASE_TEMP: // Nozzle temperature + checkkey = ETemp; + HMI_ValueStruct.E_Temp = thermalManager.degTargetHotend(0); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(1), HMI_ValueStruct.E_Temp); + EncoderRate.enabled = true; + break; + #endif + #if HAS_HEATED_BED + case TEMP_CASE_BED: // Bed temperature + checkkey = BedTemp; + HMI_ValueStruct.Bed_Temp = thermalManager.degTargetBed(); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(2), HMI_ValueStruct.Bed_Temp); + EncoderRate.enabled = true; + break; + #endif + #if HAS_FAN + case TEMP_CASE_FAN: // Fan speed + checkkey = FanSpeed; + HMI_ValueStruct.Fan_speed = thermalManager.fan_speed[0]; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(3), HMI_ValueStruct.Fan_speed); + EncoderRate.enabled = true; + break; + #endif + #if HAS_HOTEND + case TEMP_CASE_PLA: { // PLA preheat setting + checkkey = PLAPreheat; + select_PLA.reset(); + HMI_ValueStruct.show_mode = -2; + + Clear_Main_Window(); + + if (HMI_IsChinese()) { + DWIN_Frame_TitleCopy(1, 59, 16, 139, 29); // "PLA Settings" + DWIN_Frame_AreaCopy(1, 100, 89, 124, 101, LBLX, MBASE(PREHEAT_CASE_TEMP)); + DWIN_Frame_AreaCopy(1, 1, 134, 56, 146, LBLX + 24, MBASE(PREHEAT_CASE_TEMP)); // PLA nozzle temp + #if HAS_HEATED_BED + DWIN_Frame_AreaCopy(1, 100, 89, 124, 101, LBLX, MBASE(PREHEAT_CASE_BED)); + DWIN_Frame_AreaCopy(1, 58, 134, 113, 146, LBLX + 24, MBASE(PREHEAT_CASE_BED)); // PLA bed temp + #endif + #if HAS_FAN + DWIN_Frame_AreaCopy(1, 100, 89, 124, 101, LBLX, MBASE(PREHEAT_CASE_FAN)); + DWIN_Frame_AreaCopy(1, 115, 134, 170, 146, LBLX + 24, MBASE(PREHEAT_CASE_FAN)); // PLA fan speed + #endif + #if ENABLED(EEPROM_SETTINGS) + DWIN_Frame_AreaCopy(1, 72, 148, 151, 162, LBLX, MBASE(PREHEAT_CASE_SAVE)); // Save PLA configuration + #endif + } + else { + #ifdef USE_STRING_HEADINGS + Draw_Title("PLA Settings"); // TODO: GET_TEXT_F + #else + DWIN_Frame_TitleCopy(1, 56, 16, 141, 28); // "PLA Settings" + #endif + #ifdef USE_STRING_TITLES + DWIN_Draw_Label(MBASE(PREHEAT_CASE_TEMP), F("Nozzle Temp")); + #if HAS_HEATED_BED + DWIN_Draw_Label(MBASE(PREHEAT_CASE_BED), F("Bed Temp")); + #endif + #if HAS_FAN + DWIN_Draw_Label(MBASE(PREHEAT_CASE_FAN), GET_TEXT_F(MSG_FAN_SPEED)); + #endif + #if ENABLED(EEPROM_SETTINGS) + DWIN_Draw_Label(MBASE(PREHEAT_CASE_SAVE), GET_TEXT_F(MSG_STORE_EEPROM)); + #endif + #else + DWIN_Frame_AreaCopy(1, 157, 76, 181, 86, LBLX, MBASE(PREHEAT_CASE_TEMP)); + DWIN_Frame_AreaCopy(1, 197, 104, 238, 114, LBLX + 27, MBASE(PREHEAT_CASE_TEMP)); + DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 71, MBASE(PREHEAT_CASE_TEMP)); // PLA nozzle temp + #if HAS_HEATED_BED + DWIN_Frame_AreaCopy(1, 157, 76, 181, 86, LBLX, MBASE(PREHEAT_CASE_BED) + 3); + DWIN_Frame_AreaCopy(1, 240, 104, 264, 114, LBLX + 27, MBASE(PREHEAT_CASE_BED) + 3); + DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 54, MBASE(PREHEAT_CASE_BED) + 3); // PLA bed temp + #endif + #if HAS_FAN + DWIN_Frame_AreaCopy(1, 157, 76, 181, 86, LBLX, MBASE(PREHEAT_CASE_FAN)); + DWIN_Frame_AreaCopy(1, 0, 119, 64, 132, LBLX + 27, MBASE(PREHEAT_CASE_FAN)); // PLA fan speed + #endif + #if ENABLED(EEPROM_SETTINGS) + DWIN_Frame_AreaCopy(1, 97, 165, 229, 177, LBLX, MBASE(PREHEAT_CASE_SAVE)); // Save PLA configuration + #endif + #endif + } + + Draw_Back_First(); + + uint8_t i = 0; + Draw_Menu_Line(++i, ICON_SetEndTemp); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), ui.material_preset[0].hotend_temp); + #if HAS_HEATED_BED + Draw_Menu_Line(++i, ICON_SetBedTemp); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), ui.material_preset[0].bed_temp); + #endif + #if HAS_FAN + Draw_Menu_Line(++i, ICON_FanSpeed); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), ui.material_preset[0].fan_speed); + #endif + #if ENABLED(EEPROM_SETTINGS) + Draw_Menu_Line(++i, ICON_WriteEEPROM); + #endif + } break; + + case TEMP_CASE_ABS: { // ABS preheat setting + checkkey = ABSPreheat; + select_ABS.reset(); + HMI_ValueStruct.show_mode = -3; + + Clear_Main_Window(); + + if (HMI_IsChinese()) { + DWIN_Frame_TitleCopy(1, 142, 16, 223, 29); // "ABS Settings" + + DWIN_Frame_AreaCopy(1, 180, 89, 204, 100, LBLX, MBASE(PREHEAT_CASE_TEMP)); + DWIN_Frame_AreaCopy(1, 1, 134, 56, 146, LBLX + 24, MBASE(PREHEAT_CASE_TEMP)); // ABS nozzle temp + #if HAS_HEATED_BED + DWIN_Frame_AreaCopy(1, 180, 89, 204, 100, LBLX, MBASE(PREHEAT_CASE_BED)); + DWIN_Frame_AreaCopy(1, 58, 134, 113, 146, LBLX + 24, MBASE(PREHEAT_CASE_BED)); // ABS bed temp + #endif + #if HAS_FAN + DWIN_Frame_AreaCopy(1, 180, 89, 204, 100, LBLX, MBASE(PREHEAT_CASE_FAN)); + DWIN_Frame_AreaCopy(1, 115, 134, 170, 146, LBLX + 24, MBASE(PREHEAT_CASE_FAN)); // ABS fan speed + #endif + #if ENABLED(EEPROM_SETTINGS) + DWIN_Frame_AreaCopy(1, 72, 148, 151, 162, LBLX, MBASE(PREHEAT_CASE_SAVE)); + DWIN_Frame_AreaCopy(1, 180, 89, 204, 100, LBLX + 28, MBASE(PREHEAT_CASE_SAVE) + 2); // Save ABS configuration + #endif + } + else { + #ifdef USE_STRING_HEADINGS + Draw_Title("ABS Settings"); // TODO: GET_TEXT_F + #else + DWIN_Frame_TitleCopy(1, 56, 16, 141, 28); // "ABS Settings" + #endif + #ifdef USE_STRING_TITLES + DWIN_Draw_Label(MBASE(PREHEAT_CASE_TEMP), F("Nozzle Temp")); + #if HAS_HEATED_BED + DWIN_Draw_Label(MBASE(PREHEAT_CASE_BED), F("Bed Temp")); + #endif + #if HAS_FAN + DWIN_Draw_Label(MBASE(PREHEAT_CASE_FAN), GET_TEXT_F(MSG_FAN_SPEED)); + #endif + #if ENABLED(EEPROM_SETTINGS) + DWIN_Draw_Label(MBASE(PREHEAT_CASE_SAVE), GET_TEXT_F(MSG_STORE_EEPROM)); + #endif + #else + DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX, MBASE(PREHEAT_CASE_TEMP)); + DWIN_Frame_AreaCopy(1, 197, 104, 238, 114, LBLX + 27, MBASE(PREHEAT_CASE_TEMP)); + DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 71, MBASE(PREHEAT_CASE_TEMP)); // ABS nozzle temp + #if HAS_HEATED_BED + DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX, MBASE(PREHEAT_CASE_BED) + 3); + DWIN_Frame_AreaCopy(1, 240, 104, 264, 114, LBLX + 27, MBASE(PREHEAT_CASE_BED) + 3); + DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 54, MBASE(PREHEAT_CASE_BED) + 3); // ABS bed temp + #endif + #if HAS_FAN + DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX, MBASE(PREHEAT_CASE_FAN)); + DWIN_Frame_AreaCopy(1, 0, 119, 64, 132, LBLX + 27, MBASE(PREHEAT_CASE_FAN)); // ABS fan speed + #endif + #if ENABLED(EEPROM_SETTINGS) + DWIN_Frame_AreaCopy(1, 97, 165, 229, 177, LBLX, MBASE(PREHEAT_CASE_SAVE)); + DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX + 33, MBASE(PREHEAT_CASE_SAVE)); // Save ABS configuration + #endif + #endif + } + + Draw_Back_First(); + + uint8_t i = 0; + Draw_Menu_Line(++i, ICON_SetEndTemp); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), ui.material_preset[1].hotend_temp); + #if HAS_HEATED_BED + Draw_Menu_Line(++i, ICON_SetBedTemp); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), ui.material_preset[1].bed_temp); + #endif + #if HAS_FAN + Draw_Menu_Line(++i, ICON_FanSpeed); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), ui.material_preset[1].fan_speed); + #endif + #if ENABLED(EEPROM_SETTINGS) + Draw_Menu_Line(++i, ICON_WriteEEPROM); + #endif + + } break; + + #endif // HAS_HOTEND + } + } + DWIN_UpdateLCD(); +} + +void Draw_Max_Speed_Menu() { + Clear_Main_Window(); + + if (HMI_IsChinese()) { + DWIN_Frame_TitleCopy(1, 1, 16, 28, 28); // "Max Speed (mm/s)" + + auto say_max_speed = [](const uint16_t row) { + DWIN_Frame_AreaCopy(1, 173, 133, 228, 147, LBLX, row); // "Max speed" + }; + + say_max_speed(MBASE(1)); // "Max speed" + DWIN_Frame_AreaCopy(1, 229, 133, 236, 147, LBLX + 58, MBASE(1)); // X + say_max_speed(MBASE(2)); // "Max speed" + DWIN_Frame_AreaCopy(1, 1, 150, 7, 160, LBLX + 58, MBASE(2) + 3); // Y + say_max_speed(MBASE(3)); // "Max speed" + DWIN_Frame_AreaCopy(1, 9, 150, 16, 160, LBLX + 58, MBASE(3) + 3); // Z + #if HAS_HOTEND + say_max_speed(MBASE(4)); // "Max speed" + DWIN_Frame_AreaCopy(1, 18, 150, 25, 160, LBLX + 58, MBASE(4) + 3); // E + #endif + } + else { + #ifdef USE_STRING_HEADINGS + Draw_Title("Max Speed (mm/s)"); // TODO: GET_TEXT_F + #else + DWIN_Frame_TitleCopy(1, 144, 16, 189, 26); // "Max Speed (mm/s)" + #endif + #ifdef USE_STRING_TITLES + DWIN_Draw_Label(MBASE(1), F("Max Feedrate X")); + DWIN_Draw_Label(MBASE(2), F("Max Feedrate Y")); + DWIN_Draw_Label(MBASE(3), F("Max Feedrate Z")); + #if HAS_HOTEND + DWIN_Draw_Label(MBASE(4), F("Max Feedrate E")); + #endif + #else + draw_max_en(MBASE(1)); // "Max" + DWIN_Frame_AreaCopy(1, 184, 119, 234, 132, LBLX + 27, MBASE(1)); // "Speed X" + + draw_max_en(MBASE(2)); // "Max" + draw_speed_en(27, MBASE(2)); // "Speed" + say_y(70, MBASE(2)); // "Y" + + draw_max_en(MBASE(3)); // "Max" + draw_speed_en(27, MBASE(3)); // "Speed" + say_z(70, MBASE(3)); // "Z" + + #if HAS_HOTEND + draw_max_en(MBASE(4)); // "Max" + draw_speed_en(27, MBASE(4)); // "Speed" + say_e(70, MBASE(4)); // "E" + #endif + #endif + } + + Draw_Back_First(); + LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_MaxSpeedX + i); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(1), planner.settings.max_feedrate_mm_s[X_AXIS]); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(2), planner.settings.max_feedrate_mm_s[Y_AXIS]); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(3), planner.settings.max_feedrate_mm_s[Z_AXIS]); + #if HAS_HOTEND + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(4), planner.settings.max_feedrate_mm_s[E_AXIS]); + #endif +} + +void Draw_Max_Accel_Menu() { + Clear_Main_Window(); + + if (HMI_IsChinese()) { + DWIN_Frame_TitleCopy(1, 1, 16, 28, 28); // "Acceleration" + + DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX, MBASE(1)); + DWIN_Frame_AreaCopy(1, 28, 149, 69, 161, LBLX + 27, MBASE(1) + 1); + DWIN_Frame_AreaCopy(1, 229, 133, 236, 147, LBLX + 71, MBASE(1)); // Max acceleration X + DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX, MBASE(2)); + DWIN_Frame_AreaCopy(1, 28, 149, 69, 161, LBLX + 27, MBASE(2) + 1); + DWIN_Frame_AreaCopy(1, 1, 150, 7, 160, LBLX + 71, MBASE(2) + 2); // Max acceleration Y + DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX, MBASE(3)); + DWIN_Frame_AreaCopy(1, 28, 149, 69, 161, LBLX + 27, MBASE(3) + 1); + DWIN_Frame_AreaCopy(1, 9, 150, 16, 160, LBLX + 71, MBASE(3) + 2); // Max acceleration Z + #if HAS_HOTEND + DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX, MBASE(4)); + DWIN_Frame_AreaCopy(1, 28, 149, 69, 161, LBLX + 27, MBASE(4) + 1); + DWIN_Frame_AreaCopy(1, 18, 150, 25, 160, LBLX + 71, MBASE(4) + 2); // Max acceleration E + #endif + } + else { + #ifdef USE_STRING_HEADINGS + Draw_Title(GET_TEXT_F(MSG_ACCELERATION)); + #else + DWIN_Frame_TitleCopy(1, 144, 16, 189, 26); // "Acceleration" + #endif + #ifdef USE_STRING_TITLES + DWIN_Draw_Label(MBASE(1), F("Max Accel X")); + DWIN_Draw_Label(MBASE(2), F("Max Accel Y")); + DWIN_Draw_Label(MBASE(3), F("Max Accel Z")); + #if HAS_HOTEND + DWIN_Draw_Label(MBASE(4), F("Max Accel E")); + #endif + #else + draw_max_accel_en(MBASE(1)); say_x(108, MBASE(1)); // "Max Acceleration X" + draw_max_accel_en(MBASE(2)); say_y(108, MBASE(2)); // "Max Acceleration Y" + draw_max_accel_en(MBASE(3)); say_z(108, MBASE(3)); // "Max Acceleration Z" + #if HAS_HOTEND + draw_max_accel_en(MBASE(4)); say_e(108, MBASE(4)); // "Max Acceleration E" + #endif + #endif + } + + Draw_Back_First(); + LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_MaxAccX + i); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(1), planner.settings.max_acceleration_mm_per_s2[X_AXIS]); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(2), planner.settings.max_acceleration_mm_per_s2[Y_AXIS]); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(3), planner.settings.max_acceleration_mm_per_s2[Z_AXIS]); + #if HAS_HOTEND + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(4), planner.settings.max_acceleration_mm_per_s2[E_AXIS]); + #endif +} + +#if HAS_CLASSIC_JERK + void Draw_Max_Jerk_Menu() { + Clear_Main_Window(); + + if (HMI_IsChinese()) { + DWIN_Frame_TitleCopy(1, 1, 16, 28, 28); // "Jerk" + + DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX , MBASE(1)); + DWIN_Frame_AreaCopy(1, 1, 180, 28, 192, LBLX + 27, MBASE(1) + 1); + DWIN_Frame_AreaCopy(1, 202, 133, 228, 147, LBLX + 53, MBASE(1)); + DWIN_Frame_AreaCopy(1, 229, 133, 236, 147, LBLX + 83, MBASE(1)); // Max Jerk speed X + DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX , MBASE(2)); + DWIN_Frame_AreaCopy(1, 1, 180, 28, 192, LBLX + 27, MBASE(2) + 1); + DWIN_Frame_AreaCopy(1, 202, 133, 228, 147, LBLX + 53, MBASE(2)); + DWIN_Frame_AreaCopy(1, 1, 150, 7, 160, LBLX + 83, MBASE(2) + 3); // Max Jerk speed Y + DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX , MBASE(3)); + DWIN_Frame_AreaCopy(1, 1, 180, 28, 192, LBLX + 27, MBASE(3) + 1); + DWIN_Frame_AreaCopy(1, 202, 133, 228, 147, LBLX + 53, MBASE(3)); + DWIN_Frame_AreaCopy(1, 9, 150, 16, 160, LBLX + 83, MBASE(3) + 3); // Max Jerk speed Z + #if HAS_HOTEND + DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX , MBASE(4)); + DWIN_Frame_AreaCopy(1, 1, 180, 28, 192, LBLX + 27, MBASE(4) + 1); + DWIN_Frame_AreaCopy(1, 202, 133, 228, 147, LBLX + 53, MBASE(4)); + DWIN_Frame_AreaCopy(1, 18, 150, 25, 160, LBLX + 83, MBASE(4) + 3); // Max Jerk speed E + #endif + } + else { + #ifdef USE_STRING_HEADINGS + Draw_Title(GET_TEXT_F(MSG_JERK)); + #else + DWIN_Frame_TitleCopy(1, 144, 16, 189, 26); // "Jerk" + #endif + #ifdef USE_STRING_TITLES + DWIN_Draw_Label(MBASE(1), F("Max Jerk X")); + DWIN_Draw_Label(MBASE(2), F("Max Jerk Y")); + DWIN_Draw_Label(MBASE(3), F("Max Jerk Z")); + #if HAS_HOTEND + DWIN_Draw_Label(MBASE(4), F("Max Jerk E")); + #endif + #else + draw_max_en(MBASE(1)); // "Max" + draw_jerk_en(MBASE(1)); // "Jerk" + draw_speed_en(72, MBASE(1)); // "Speed" + say_x(115, MBASE(1)); // "X" + + draw_max_en(MBASE(2)); // "Max" + draw_jerk_en(MBASE(2)); // "Jerk" + draw_speed_en(72, MBASE(2)); // "Speed" + say_y(115, MBASE(2)); // "Y" + + draw_max_en(MBASE(3)); // "Max" + draw_jerk_en(MBASE(3)); // "Jerk" + draw_speed_en(72, MBASE(3)); // "Speed" + say_z(115, MBASE(3)); // "Z" + + #if HAS_HOTEND + draw_max_en(MBASE(4)); // "Max" + draw_jerk_en(MBASE(4)); // "Jerk" + draw_speed_en(72, MBASE(4)); // "Speed" + say_e(115, MBASE(4)); // "E" + #endif + #endif + } + + Draw_Back_First(); + LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_MaxSpeedJerkX + i); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, MBASE(1), planner.max_jerk[X_AXIS] * MINUNITMULT); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, MBASE(2), planner.max_jerk[Y_AXIS] * MINUNITMULT); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, MBASE(3), planner.max_jerk[Z_AXIS] * MINUNITMULT); + #if HAS_HOTEND + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, MBASE(4), planner.max_jerk[E_AXIS] * MINUNITMULT); + #endif + } +#endif + +void Draw_Steps_Menu() { + Clear_Main_Window(); + + if (HMI_IsChinese()) { + DWIN_Frame_TitleCopy(1, 1, 16, 28, 28); // "Steps per mm" + + DWIN_Frame_AreaCopy(1, 153, 148, 194, 161, LBLX, MBASE(1)); + DWIN_Frame_AreaCopy(1, 229, 133, 236, 147, LBLX + 44, MBASE(1)); // Transmission Ratio X + DWIN_Frame_AreaCopy(1, 153, 148, 194, 161, LBLX, MBASE(2)); + DWIN_Frame_AreaCopy(1, 1, 150, 7, 160, LBLX + 44, MBASE(2) + 3); // Transmission Ratio Y + DWIN_Frame_AreaCopy(1, 153, 148, 194, 161, LBLX, MBASE(3)); + DWIN_Frame_AreaCopy(1, 9, 150, 16, 160, LBLX + 44, MBASE(3) + 3); // Transmission Ratio Z + #if HAS_HOTEND + DWIN_Frame_AreaCopy(1, 153, 148, 194, 161, LBLX, MBASE(4)); + DWIN_Frame_AreaCopy(1, 18, 150, 25, 160, LBLX + 44, MBASE(4) + 3); // Transmission Ratio E + #endif + } + else { + #ifdef USE_STRING_HEADINGS + Draw_Title(GET_TEXT_F(MSG_STEPS_PER_MM)); + #else + DWIN_Frame_TitleCopy(1, 144, 16, 189, 26); // "Steps per mm" + #endif + #ifdef USE_STRING_TITLES + DWIN_Draw_Label(MBASE(1), F("Steps/mm X")); + DWIN_Draw_Label(MBASE(2), F("Steps/mm Y")); + DWIN_Draw_Label(MBASE(3), F("Steps/mm Z")); + #if HAS_HOTEND + DWIN_Draw_Label(MBASE(4), F("Steps/mm E")); + #endif + #else + draw_steps_per_mm(MBASE(1)); say_x(103, MBASE(1)); // "Steps-per-mm X" + draw_steps_per_mm(MBASE(2)); say_y(103, MBASE(2)); // "Y" + draw_steps_per_mm(MBASE(3)); say_z(103, MBASE(3)); // "Z" + #if HAS_HOTEND + draw_steps_per_mm(MBASE(4)); say_e(103, MBASE(4)); // "E" + #endif + #endif + } + + Draw_Back_First(); + LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_StepX + i); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, MBASE(1), planner.settings.axis_steps_per_mm[X_AXIS] * MINUNITMULT); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, MBASE(2), planner.settings.axis_steps_per_mm[Y_AXIS] * MINUNITMULT); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, MBASE(3), planner.settings.axis_steps_per_mm[Z_AXIS] * MINUNITMULT); + #if HAS_HOTEND + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, MBASE(4), planner.settings.axis_steps_per_mm[E_AXIS] * MINUNITMULT); + #endif +} + +/* Motion */ +void HMI_Motion() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + // Avoid flicker by updating only the previous menu + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_motion.inc(1 + MOTION_CASE_TOTAL)) Move_Highlight(1, select_motion.now); + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_motion.dec()) Move_Highlight(-1, select_motion.now); + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + switch (select_motion.now) { + case 0: // Back + checkkey = Control; + select_control.set(CONTROL_CASE_MOVE); + index_control = MROWS; + Draw_Control_Menu(); + break; + case MOTION_CASE_RATE: // Max speed + checkkey = MaxSpeed; + select_speed.reset(); + Draw_Max_Speed_Menu(); + break; + case MOTION_CASE_ACCEL: // Max acceleration + checkkey = MaxAcceleration; + select_acc.reset(); + Draw_Max_Accel_Menu(); + break; + #if HAS_CLASSIC_JERK + case MOTION_CASE_JERK: // Max jerk + checkkey = MaxJerk; + select_jerk.reset(); + Draw_Max_Jerk_Menu(); + break; + #endif + case MOTION_CASE_STEPS: // Steps per mm + checkkey = Step; + select_step.reset(); + Draw_Steps_Menu(); + break; + default: break; + } + } + DWIN_UpdateLCD(); +} + +/* Advanced Settings */ +void HMI_AdvSet() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + // Avoid flicker by updating only the previous menu + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_advset.inc(1 + ADVSET_CASE_TOTAL)) { + if (select_advset.now > MROWS && select_advset.now > index_advset) { + index_advset = select_advset.now; + + // Scroll up and draw a blank bottom line + Scroll_Menu(DWIN_SCROLL_UP); + + //switch (index_advset) { // Redraw last menu items + // default: break; + //} + + } + else { + Move_Highlight(1, select_advset.now + MROWS - index_advset); + } + } + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_advset.dec()) { + if (select_advset.now < index_advset - MROWS) { + index_advset--; + Scroll_Menu(DWIN_SCROLL_DOWN); + + //switch (index_advset) { // Redraw first menu items + // default: break; + //} + } + else { + Move_Highlight(-1, select_advset.now + MROWS - index_advset); + } + } + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + switch (select_advset.now) { + case 0: // Back + checkkey = Control; + select_control.set(CONTROL_CASE_ADVSET); + index_control = CONTROL_CASE_ADVSET; + Draw_Control_Menu(); + break; + + #if HAS_HOME_OFFSET + case ADVSET_CASE_HOMEOFF: // Home Offsets + checkkey = HomeOff; + select_item.reset(); + HMI_ValueStruct.Home_OffX_scaled = home_offset[X_AXIS] * 10; + HMI_ValueStruct.Home_OffY_scaled = home_offset[Y_AXIS] * 10; + HMI_ValueStruct.Home_OffZ_scaled = home_offset[Z_AXIS] * 10; + Draw_HomeOff_Menu(); + break; + #endif + + #if HAS_ONESTEP_LEVELING + case ADVSET_CASE_PROBEOFF: // Probe Offsets + checkkey = ProbeOff; + select_item.reset(); + HMI_ValueStruct.Probe_OffX_scaled = probe.offset.x * 10; + HMI_ValueStruct.Probe_OffY_scaled = probe.offset.y * 10; + Draw_ProbeOff_Menu(); + break; + #endif + + #if HAS_HOTEND + case ADVSET_CASE_HEPID: // Nozzle PID Autotune + thermalManager.setTargetHotend(ui.material_preset[0].hotend_temp, 0); + thermalManager.PID_autotune(ui.material_preset[0].hotend_temp, H_E0, 10, true); + break; + #endif + + #if HAS_HEATED_BED + case ADVSET_CASE_BEDPID: // Bed PID Autotune + thermalManager.setTargetBed(ui.material_preset[0].bed_temp); + thermalManager.PID_autotune(ui.material_preset[0].bed_temp, H_BED, 10, true); + break; + #endif + + #if ENABLED(POWER_LOSS_RECOVERY) + case ADVSET_CASE_PWRLOSSR: // Power-loss recovery + recovery.enable(!recovery.enabled); + Draw_Chkb_Line(ADVSET_CASE_PWRLOSSR + MROWS - index_advset, recovery.enabled); + break; + #endif + default: break; + } + } + DWIN_UpdateLCD(); +} + +#if HAS_HOME_OFFSET + + /* Home Offset */ + void HMI_HomeOff() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + // Avoid flicker by updating only the previous menu + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_item.inc(1 + 3)) Move_Highlight(1, select_item.now); + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_item.dec()) Move_Highlight(-1, select_item.now); + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + switch (select_item.now) { + case 0: // Back + checkkey = AdvSet; + select_advset.set(ADVSET_CASE_HOMEOFF); + Draw_AdvSet_Menu(); + break; + case 1: // Home Offset X + checkkey = HomeOffX; + DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, 1, 216, MBASE(1), HMI_ValueStruct.Home_OffX_scaled); + EncoderRate.enabled = true; + break; + case 2: // Home Offset Y + checkkey = HomeOffY; + DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, 1, 216, MBASE(2), HMI_ValueStruct.Home_OffY_scaled); + EncoderRate.enabled = true; + break; + case 3: // Home Offset Z + checkkey = HomeOffZ; + DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, 1, 216, MBASE(3), HMI_ValueStruct.Home_OffZ_scaled); + EncoderRate.enabled = true; + break; + default: break; + } + } + DWIN_UpdateLCD(); + } + + void HMI_HomeOffN(const AxisEnum axis, float &posScaled, const_float_t lo, const_float_t hi) { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + if (Apply_Encoder(encoder_diffState, posScaled)) { + checkkey = HomeOff; + EncoderRate.enabled = false; + set_home_offset(axis, posScaled / 10); + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, 1, 216, MBASE(select_item.now), posScaled); + return; + } + LIMIT(posScaled, lo, hi); + DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, UNITFDIGITS, 216, MBASE(select_item.now), posScaled); + } + } + + void HMI_HomeOffX() { HMI_HomeOffN(X_AXIS, HMI_ValueStruct.Home_OffX_scaled, -500, 500); } + void HMI_HomeOffY() { HMI_HomeOffN(Y_AXIS, HMI_ValueStruct.Home_OffY_scaled, -500, 500); } + void HMI_HomeOffZ() { HMI_HomeOffN(Z_AXIS, HMI_ValueStruct.Home_OffZ_scaled, -20, 20); } + +#endif // HAS_HOME_OFFSET + +#if HAS_ONESTEP_LEVELING + /*Probe Offset */ + void HMI_ProbeOff() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + // Avoid flicker by updating only the previous menu + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_item.inc(1 + 2)) Move_Highlight(1, select_item.now); + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_item.dec()) Move_Highlight(-1, select_item.now); + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + switch (select_item.now) { + case 0: // Back + checkkey = AdvSet; + select_advset.set(ADVSET_CASE_PROBEOFF); + Draw_AdvSet_Menu(); + break; + case 1: // Probe Offset X + checkkey = ProbeOffX; + DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, 1, 216, MBASE(1), HMI_ValueStruct.Probe_OffX_scaled); + EncoderRate.enabled = true; + break; + case 2: // Probe Offset X + checkkey = ProbeOffY; + DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, 1, 216, MBASE(2), HMI_ValueStruct.Probe_OffY_scaled); + EncoderRate.enabled = true; + break; + } + } + DWIN_UpdateLCD(); + } + + void HMI_ProbeOffN(float &posScaled, float &offset_ref) { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + if (Apply_Encoder(encoder_diffState, posScaled)) { + checkkey = ProbeOff; + EncoderRate.enabled = false; + offset_ref = posScaled / 10; + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, 1, 216, MBASE(select_item.now), posScaled); + return; + } + LIMIT(posScaled, -500, 500); + DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, UNITFDIGITS, 216, MBASE(select_item.now), posScaled); + } + } + + void HMI_ProbeOffX() { HMI_ProbeOffN(HMI_ValueStruct.Probe_OffX_scaled, probe.offset.x); } + void HMI_ProbeOffY() { HMI_ProbeOffN(HMI_ValueStruct.Probe_OffY_scaled, probe.offset.y); } + +#endif // HAS_ONESTEP_LEVELING + +/* Info */ +void HMI_Info() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + if (encoder_diffState == ENCODER_DIFF_ENTER) { + #if HAS_ONESTEP_LEVELING + checkkey = Control; + select_control.set(CONTROL_CASE_INFO); + Draw_Control_Menu(); + #else + select_page.set(3); + Goto_MainMenu(); + #endif + } + DWIN_UpdateLCD(); +} + +/* Tune */ +void HMI_Tune() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + // Avoid flicker by updating only the previous menu + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_tune.inc(1 + TUNE_CASE_TOTAL)) { + if (select_tune.now > MROWS && select_tune.now > index_tune) { + index_tune = select_tune.now; + Scroll_Menu(DWIN_SCROLL_UP); + } + else { + Move_Highlight(1, select_tune.now + MROWS - index_tune); + } + } + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_tune.dec()) { + if (select_tune.now < index_tune - MROWS) { + index_tune--; + Scroll_Menu(DWIN_SCROLL_DOWN); + if (index_tune == MROWS) Draw_Back_First(); + } + else { + Move_Highlight(-1, select_tune.now + MROWS - index_tune); + } + } + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + switch (select_tune.now) { + case 0: { // Back + select_print.set(0); + Goto_PrintProcess(); + } + break; + case TUNE_CASE_SPEED: // Print speed + checkkey = PrintSpeed; + HMI_ValueStruct.print_speed = feedrate_percentage; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(TUNE_CASE_SPEED + MROWS - index_tune), HMI_ValueStruct.print_speed); + EncoderRate.enabled = true; + break; + #if HAS_HOTEND + case TUNE_CASE_TEMP: // Nozzle temp + checkkey = ETemp; + HMI_ValueStruct.E_Temp = thermalManager.degTargetHotend(0); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(TUNE_CASE_TEMP + MROWS - index_tune), HMI_ValueStruct.E_Temp); + EncoderRate.enabled = true; + break; + #endif + #if HAS_HEATED_BED + case TUNE_CASE_BED: // Bed temp + checkkey = BedTemp; + HMI_ValueStruct.Bed_Temp = thermalManager.degTargetBed(); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(TUNE_CASE_BED + MROWS - index_tune), HMI_ValueStruct.Bed_Temp); + EncoderRate.enabled = true; + break; + #endif + #if HAS_FAN + case TUNE_CASE_FAN: // Fan speed + checkkey = FanSpeed; + HMI_ValueStruct.Fan_speed = thermalManager.fan_speed[0]; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(TUNE_CASE_FAN + MROWS - index_tune), HMI_ValueStruct.Fan_speed); + EncoderRate.enabled = true; + break; + #endif + #if HAS_ZOFFSET_ITEM + case TUNE_CASE_ZOFF: // Z-offset + #if EITHER(HAS_BED_PROBE, BABYSTEPPING) + checkkey = Homeoffset; + HMI_ValueStruct.offset_value = BABY_Z_VAR * 100; + DWIN_Draw_Signed_Float(font8x16, Select_Color, 2, 2, 202, MBASE(TUNE_CASE_ZOFF + MROWS - index_tune), HMI_ValueStruct.offset_value); + EncoderRate.enabled = true; + #else + // Apply workspace offset, making the current position 0,0,0 + queue.inject_P(PSTR("G92 X0 Y0 Z0")); + HMI_AudioFeedback(); + #endif + break; + #endif + default: break; + } + } + DWIN_UpdateLCD(); +} + +#if HAS_PREHEAT + + /* PLA Preheat */ + void HMI_PLAPreheatSetting() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + // Avoid flicker by updating only the previous menu + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_PLA.inc(1 + PREHEAT_CASE_TOTAL)) Move_Highlight(1, select_PLA.now); + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_PLA.dec()) Move_Highlight(-1, select_PLA.now); + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + switch (select_PLA.now) { + case 0: // Back + checkkey = TemperatureID; + select_temp.now = TEMP_CASE_PLA; + HMI_ValueStruct.show_mode = -1; + Draw_Temperature_Menu(); + break; + #if HAS_HOTEND + case PREHEAT_CASE_TEMP: // Nozzle temperature + checkkey = ETemp; + HMI_ValueStruct.E_Temp = ui.material_preset[0].hotend_temp; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_TEMP), ui.material_preset[0].hotend_temp); + EncoderRate.enabled = true; + break; + #endif + #if HAS_HEATED_BED + case PREHEAT_CASE_BED: // Bed temperature + checkkey = BedTemp; + HMI_ValueStruct.Bed_Temp = ui.material_preset[0].bed_temp; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_BED), ui.material_preset[0].bed_temp); + EncoderRate.enabled = true; + break; + #endif + #if HAS_FAN + case PREHEAT_CASE_FAN: // Fan speed + checkkey = FanSpeed; + HMI_ValueStruct.Fan_speed = ui.material_preset[0].fan_speed; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_FAN), ui.material_preset[0].fan_speed); + EncoderRate.enabled = true; + break; + #endif + #if ENABLED(EEPROM_SETTINGS) + case 4: { // Save PLA configuration + const bool success = settings.save(); + HMI_AudioFeedback(success); + } break; + #endif + default: break; + } + } + DWIN_UpdateLCD(); + } + + /* ABS Preheat */ + void HMI_ABSPreheatSetting() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + // Avoid flicker by updating only the previous menu + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_ABS.inc(1 + PREHEAT_CASE_TOTAL)) Move_Highlight(1, select_ABS.now); + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_ABS.dec()) Move_Highlight(-1, select_ABS.now); + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + switch (select_ABS.now) { + case 0: // Back + checkkey = TemperatureID; + select_temp.now = TEMP_CASE_ABS; + HMI_ValueStruct.show_mode = -1; + Draw_Temperature_Menu(); + break; + #if HAS_HOTEND + case PREHEAT_CASE_TEMP: // Set nozzle temperature + checkkey = ETemp; + HMI_ValueStruct.E_Temp = ui.material_preset[1].hotend_temp; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_TEMP), ui.material_preset[1].hotend_temp); + EncoderRate.enabled = true; + break; + #endif + #if HAS_HEATED_BED + case PREHEAT_CASE_BED: // Set bed temperature + checkkey = BedTemp; + HMI_ValueStruct.Bed_Temp = ui.material_preset[1].bed_temp; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_BED), ui.material_preset[1].bed_temp); + EncoderRate.enabled = true; + break; + #endif + #if HAS_FAN + case PREHEAT_CASE_FAN: // Set fan speed + checkkey = FanSpeed; + HMI_ValueStruct.Fan_speed = ui.material_preset[1].fan_speed; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_FAN), ui.material_preset[1].fan_speed); + EncoderRate.enabled = true; + break; + #endif + #if ENABLED(EEPROM_SETTINGS) + case PREHEAT_CASE_SAVE: { // Save ABS configuration + const bool success = settings.save(); + HMI_AudioFeedback(success); + } break; + #endif + default: break; + } + } + DWIN_UpdateLCD(); + } + +#endif + +/* Max Speed */ +void HMI_MaxSpeed() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + // Avoid flicker by updating only the previous menu + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_speed.inc(1 + 3 + ENABLED(HAS_HOTEND))) Move_Highlight(1, select_speed.now); + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_speed.dec()) Move_Highlight(-1, select_speed.now); + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + if (WITHIN(select_speed.now, 1, 4)) { + checkkey = MaxSpeed_value; + HMI_flag.feedspeed_axis = AxisEnum(select_speed.now - 1); + HMI_ValueStruct.Max_Feedspeed = planner.settings.max_feedrate_mm_s[HMI_flag.feedspeed_axis]; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 4, 210, MBASE(select_speed.now), HMI_ValueStruct.Max_Feedspeed); + EncoderRate.enabled = true; + } + else { // Back + checkkey = Motion; + select_motion.now = MOTION_CASE_RATE; + Draw_Motion_Menu(); + } + } + DWIN_UpdateLCD(); +} + +/* Max Acceleration */ +void HMI_MaxAcceleration() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + // Avoid flicker by updating only the previous menu + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_acc.inc(1 + 3 + ENABLED(HAS_HOTEND))) Move_Highlight(1, select_acc.now); + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_acc.dec()) Move_Highlight(-1, select_acc.now); + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + if (WITHIN(select_acc.now, 1, 4)) { + checkkey = MaxAcceleration_value; + HMI_flag.acc_axis = AxisEnum(select_acc.now - 1); + HMI_ValueStruct.Max_Acceleration = planner.settings.max_acceleration_mm_per_s2[HMI_flag.acc_axis]; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 4, 210, MBASE(select_acc.now), HMI_ValueStruct.Max_Acceleration); + EncoderRate.enabled = true; + } + else { // Back + checkkey = Motion; + select_motion.now = MOTION_CASE_ACCEL; + Draw_Motion_Menu(); + } + } + DWIN_UpdateLCD(); +} + +#if HAS_CLASSIC_JERK + /* Max Jerk */ + void HMI_MaxJerk() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + // Avoid flicker by updating only the previous menu + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_jerk.inc(1 + 3 + ENABLED(HAS_HOTEND))) Move_Highlight(1, select_jerk.now); + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_jerk.dec()) Move_Highlight(-1, select_jerk.now); + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + if (WITHIN(select_jerk.now, 1, 4)) { + checkkey = MaxJerk_value; + HMI_flag.jerk_axis = AxisEnum(select_jerk.now - 1); + HMI_ValueStruct.Max_Jerk_scaled = planner.max_jerk[HMI_flag.jerk_axis] * MINUNITMULT; + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, UNITFDIGITS, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk_scaled); + EncoderRate.enabled = true; + } + else { // Back + checkkey = Motion; + select_motion.now = MOTION_CASE_JERK; + Draw_Motion_Menu(); + } + } + DWIN_UpdateLCD(); + } +#endif // HAS_CLASSIC_JERK + +/* Step */ +void HMI_Step() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + // Avoid flicker by updating only the previous menu + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_step.inc(1 + 3 + ENABLED(HAS_HOTEND))) Move_Highlight(1, select_step.now); + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_step.dec()) Move_Highlight(-1, select_step.now); + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + if (WITHIN(select_step.now, 1, 4)) { + checkkey = Step_value; + HMI_flag.step_axis = AxisEnum(select_step.now - 1); + HMI_ValueStruct.Max_Step_scaled = planner.settings.axis_steps_per_mm[HMI_flag.step_axis] * MINUNITMULT; + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, UNITFDIGITS, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step_scaled); + EncoderRate.enabled = true; + } + else { // Back + checkkey = Motion; + select_motion.now = MOTION_CASE_STEPS; + Draw_Motion_Menu(); + } + } + DWIN_UpdateLCD(); +} + +void HMI_Init() { + HMI_SDCardInit(); + + for (uint16_t t = 0; t <= 100; t += 2) { + DWIN_ICON_Show(ICON, ICON_Bar, 15, 260); + DWIN_Draw_Rectangle(1, Color_Bg_Black, 15 + t * 242 / 100, 260, 257, 280); + DWIN_UpdateLCD(); + delay(20); + } + + HMI_SetLanguage(); +} + +void DWIN_Update() { + EachMomentUpdate(); // Status update + HMI_SDCardUpdate(); // SD card update + DWIN_HandleScreen(); // Rotary encoder update +} + +void EachMomentUpdate() { + static millis_t next_var_update_ms = 0, next_rts_update_ms = 0; + + const millis_t ms = millis(); + if (ELAPSED(ms, next_var_update_ms)) { + next_var_update_ms = ms + DWIN_VAR_UPDATE_INTERVAL; + update_variable(); + } + + if (PENDING(ms, next_rts_update_ms)) return; + next_rts_update_ms = ms + DWIN_SCROLL_UPDATE_INTERVAL; + + if (checkkey == PrintProcess) { + // if print done + if (HMI_flag.print_finish && !HMI_flag.done_confirm_flag) { + HMI_flag.print_finish = false; + HMI_flag.done_confirm_flag = true; + + TERN_(POWER_LOSS_RECOVERY, recovery.cancel()); + + planner.finish_and_disable(); + + // show percent bar and value + _card_percent = 0; + Draw_Print_ProgressBar(); + + // show print done confirm + DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, 250, DWIN_WIDTH - 1, STATUS_Y); + DWIN_ICON_Show(ICON, HMI_IsChinese() ? ICON_Confirm_C : ICON_Confirm_E, 86, 283); + } + else if (HMI_flag.pause_flag != printingIsPaused()) { + // print status update + HMI_flag.pause_flag = printingIsPaused(); + if (HMI_flag.pause_flag) ICON_Continue(); else ICON_Pause(); + } + } + + // pause after homing + if (HMI_flag.pause_action && printingIsPaused() && !planner.has_blocks_queued()) { + HMI_flag.pause_action = false; + #if ENABLED(PAUSE_HEAT) + TERN_(HAS_HOTEND, resume_hotend_temp = thermalManager.degTargetHotend(0)); + TERN_(HAS_HEATED_BED, resume_bed_temp = thermalManager.degTargetBed()); + thermalManager.disable_all_heaters(); + #endif + queue.inject_P(PSTR("G1 F1200 X0 Y0")); + } + + if (card.isPrinting() && checkkey == PrintProcess) { // print process + const uint8_t card_pct = card.percentDone(); + static uint8_t last_cardpercentValue = 101; + if (last_cardpercentValue != card_pct) { // print percent + last_cardpercentValue = card_pct; + if (card_pct) { + _card_percent = card_pct; + Draw_Print_ProgressBar(); + } + } + + duration_t elapsed = print_job_timer.duration(); // print timer + + // Print time so far + static uint16_t last_Printtime = 0; + const uint16_t min = (elapsed.value % 3600) / 60; + if (last_Printtime != min) { // 1 minute update + last_Printtime = min; + Draw_Print_ProgressElapsed(); + } + + // Estimate remaining time every 20 seconds + static millis_t next_remain_time_update = 0; + if (_card_percent > 1 && ELAPSED(ms, next_remain_time_update) && !HMI_flag.heat_flag) { + _remain_time = (elapsed.value - dwin_heat_time) / (_card_percent * 0.01f) - (elapsed.value - dwin_heat_time); + next_remain_time_update += DWIN_REMAIN_TIME_UPDATE_INTERVAL; + Draw_Print_ProgressRemain(); + } + } + else if (dwin_abort_flag && !HMI_flag.home_flag) { // Print Stop + dwin_abort_flag = false; + HMI_ValueStruct.print_speed = feedrate_percentage = 100; + dwin_zoffset = BABY_Z_VAR; + select_page.set(0); + Goto_MainMenu(); + } + #if ENABLED(POWER_LOSS_RECOVERY) + else if (DWIN_lcd_sd_status && recovery.dwin_flag) { // resume print before power off + static bool recovery_flag = false; + + recovery.dwin_flag = false; + recovery_flag = true; + + auto update_selection = [&](const bool sel) { + HMI_flag.select_flag = sel; + const uint16_t c1 = sel ? Color_Bg_Window : Select_Color; + DWIN_Draw_Rectangle(0, c1, 25, 306, 126, 345); + DWIN_Draw_Rectangle(0, c1, 24, 305, 127, 346); + const uint16_t c2 = sel ? Select_Color : Color_Bg_Window; + DWIN_Draw_Rectangle(0, c2, 145, 306, 246, 345); + DWIN_Draw_Rectangle(0, c2, 144, 305, 247, 346); + }; + + Popup_Window_Resume(); + update_selection(true); + + // TODO: Get the name of the current file from someplace + // + //(void)recovery.interrupted_file_exists(); + char * const name = card.longest_filename(); + const int8_t npos = _MAX(0U, DWIN_WIDTH - strlen(name) * (MENU_CHR_W)) / 2; + DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, npos, 252, name); + DWIN_UpdateLCD(); + + while (recovery_flag) { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + if (encoder_diffState == ENCODER_DIFF_ENTER) { + recovery_flag = false; + if (HMI_flag.select_flag) break; + TERN_(POWER_LOSS_RECOVERY, queue.inject_P(PSTR("M1000C"))); + HMI_StartFrame(true); + return; + } + else + update_selection(encoder_diffState == ENCODER_DIFF_CW); + + DWIN_UpdateLCD(); + } + } + + select_print.set(0); + HMI_ValueStruct.show_mode = 0; + queue.inject_P(PSTR("M1000")); + Goto_PrintProcess(); + Draw_Status_Area(true); + } + #endif // POWER_LOSS_RECOVERY + + DWIN_UpdateLCD(); +} + +void DWIN_HandleScreen() { + switch (checkkey) { + case MainMenu: HMI_MainMenu(); break; + case SelectFile: HMI_SelectFile(); break; + case Prepare: HMI_Prepare(); break; + case Control: HMI_Control(); break; + case Leveling: break; + case PrintProcess: HMI_Printing(); break; + case Print_window: HMI_PauseOrStop(); break; + case AxisMove: HMI_AxisMove(); break; + case TemperatureID: HMI_Temperature(); break; + case Motion: HMI_Motion(); break; + case AdvSet: HMI_AdvSet(); break; + #if HAS_HOME_OFFSET + case HomeOff: HMI_HomeOff(); break; + case HomeOffX: HMI_HomeOffX(); break; + case HomeOffY: HMI_HomeOffY(); break; + case HomeOffZ: HMI_HomeOffZ(); break; + #endif + #if HAS_ONESTEP_LEVELING + case ProbeOff: HMI_ProbeOff(); break; + case ProbeOffX: HMI_ProbeOffX(); break; + case ProbeOffY: HMI_ProbeOffY(); break; + #endif + case Info: HMI_Info(); break; + case Tune: HMI_Tune(); break; + #if HAS_PREHEAT + case PLAPreheat: HMI_PLAPreheatSetting(); break; + case ABSPreheat: HMI_ABSPreheatSetting(); break; + #endif + case MaxSpeed: HMI_MaxSpeed(); break; + case MaxAcceleration: HMI_MaxAcceleration(); break; + #if HAS_CLASSIC_JERK + case MaxJerk: HMI_MaxJerk(); break; + #endif + case Step: HMI_Step(); break; + case Move_X: HMI_Move_X(); break; + case Move_Y: HMI_Move_Y(); break; + case Move_Z: HMI_Move_Z(); break; + #if HAS_HOTEND + case Extruder: HMI_Move_E(); break; + case ETemp: HMI_ETemp(); break; + #endif + #if EITHER(HAS_BED_PROBE, BABYSTEPPING) + case Homeoffset: HMI_Zoffset(); break; + #endif + #if HAS_HEATED_BED + case BedTemp: HMI_BedTemp(); break; + #endif + #if HAS_PREHEAT && HAS_FAN + case FanSpeed: HMI_FanSpeed(); break; + #endif + case PrintSpeed: HMI_PrintSpeed(); break; + case MaxSpeed_value: HMI_MaxFeedspeedXYZE(); break; + case MaxAcceleration_value: HMI_MaxAccelerationXYZE(); break; + #if HAS_CLASSIC_JERK + case MaxJerk_value: HMI_MaxJerkXYZE(); break; + #endif + case Step_value: HMI_StepXYZE(); break; + default: break; + } +} + +void DWIN_CompletedHoming() { + HMI_flag.home_flag = false; + dwin_zoffset = TERN0(HAS_BED_PROBE, probe.offset.z); + if (checkkey == Last_Prepare) { + checkkey = Prepare; + select_prepare.now = PREPARE_CASE_HOME; + index_prepare = MROWS; + Draw_Prepare_Menu(); + } + else if (checkkey == Back_Main) { + HMI_ValueStruct.print_speed = feedrate_percentage = 100; + planner.finish_and_disable(); + Goto_MainMenu(); + } +} + +void DWIN_CompletedLeveling() { + if (checkkey == Leveling) Goto_MainMenu(); +} + +void DWIN_StatusChanged(const char *text) { + DWIN_Draw_Rectangle(1, Color_Bg_Blue, 0, STATUS_Y, DWIN_WIDTH, STATUS_Y + 20); + const int8_t x = _MAX(0U, DWIN_WIDTH - strlen_P(text) * MENU_CHR_W) / 2; + DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Blue, x, STATUS_Y + 2, F(text)); + DWIN_UpdateLCD(); +} + +void DWIN_StatusChanged_P(PGM_P const pstr) { + char str[strlen_P((const char*)pstr) + 1]; + strcpy_P(str, (const char*)pstr); + DWIN_StatusChanged(str); +} + +// GUI extension +void DWIN_Draw_Checkbox(uint16_t color, uint16_t bcolor, uint16_t x, uint16_t y, bool mode=false) { + DWIN_Draw_String(true, font8x16, Select_Color, bcolor, x + 4, y, F(mode ? "x" : " ")); + DWIN_Draw_Rectangle(0, color, x + 2, y + 2, x + 17, y + 17); +} + +#endif // DWIN_CREALITY_LCD diff --git a/Marlin/src/lcd/e3v2/creality/dwin.h b/Marlin/src/lcd/e3v2/creality/dwin.h new file mode 100644 index 000000000000..2808fea99ce1 --- /dev/null +++ b/Marlin/src/lcd/e3v2/creality/dwin.h @@ -0,0 +1,269 @@ +/** + * 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 + +/** + * DWIN by Creality3D + */ + +#include "dwin_lcd.h" +#include "rotary_encoder.h" +#include "../../../libs/BL24CXX.h" + +#include "../../../inc/MarlinConfigPre.h" + +#if ANY(HAS_HOTEND, HAS_HEATED_BED, HAS_FAN) && PREHEAT_COUNT + #define HAS_PREHEAT 1 + #if PREHEAT_COUNT < 2 + #error "Creality DWIN requires two material preheat presets." + #endif +#endif + +enum processID : uint8_t { + // Process ID + MainMenu, + SelectFile, + Prepare, + Control, + Leveling, + PrintProcess, + AxisMove, + TemperatureID, + Motion, + Info, + Tune, + #if HAS_PREHEAT + PLAPreheat, + ABSPreheat, + #endif + MaxSpeed, + MaxSpeed_value, + MaxAcceleration, + MaxAcceleration_value, + MaxJerk, + MaxJerk_value, + Step, + Step_value, + HomeOff, + HomeOffX, + HomeOffY, + HomeOffZ, + + // Last Process ID + Last_Prepare, + + // Advance Settings + AdvSet, + ProbeOff, + ProbeOffX, + ProbeOffY, + + // Back Process ID + Back_Main, + Back_Print, + + // Date variable ID + Move_X, + Move_Y, + Move_Z, + #if HAS_HOTEND + Extruder, + ETemp, + #endif + Homeoffset, + #if HAS_HEATED_BED + BedTemp, + #endif + #if HAS_FAN + FanSpeed, + #endif + PrintSpeed, + + // Window ID + Print_window, + Popup_Window +}; + +extern uint8_t checkkey; +extern float zprobe_zoffset; +extern char print_filename[16]; + +extern millis_t dwin_heat_time; + +typedef struct { + #if HAS_HOTEND + celsius_t E_Temp = 0; + #endif + #if HAS_HEATED_BED + celsius_t Bed_Temp = 0; + #endif + #if HAS_FAN + int16_t Fan_speed = 0; + #endif + int16_t print_speed = 100; + float Max_Feedspeed = 0; + float Max_Acceleration = 0; + float Max_Jerk_scaled = 0; + float Max_Step_scaled = 0; + float Move_X_scaled = 0; + float Move_Y_scaled = 0; + float Move_Z_scaled = 0; + #if HAS_HOTEND + float Move_E_scaled = 0; + #endif + float offset_value = 0; + int8_t show_mode = 0; // -1: Temperature control 0: Printing temperature + float Home_OffX_scaled = 0; + float Home_OffY_scaled = 0; + float Home_OffZ_scaled = 0; + float Probe_OffX_scaled = 0; + float Probe_OffY_scaled = 0; +} HMI_value_t; + +#define DWIN_CHINESE 123 +#define DWIN_ENGLISH 0 + +typedef struct { + uint8_t language; + bool pause_flag:1; + bool pause_action:1; + bool print_finish:1; + bool done_confirm_flag:1; + bool select_flag:1; + bool home_flag:1; + bool heat_flag:1; // 0: heating done 1: during heating + #if ENABLED(PREVENT_COLD_EXTRUSION) + bool ETempTooLow_flag:1; + #endif + #if HAS_LEVELING + bool leveling_offset_flag:1; + #endif + AxisEnum feedspeed_axis, acc_axis, jerk_axis, step_axis; +} HMI_Flag_t; + +extern HMI_value_t HMI_ValueStruct; +extern HMI_Flag_t HMI_flag; + +// Show ICO +void ICON_Print(bool show); +void ICON_Prepare(bool show); +void ICON_Control(bool show); +void ICON_Leveling(bool show); +void ICON_StartInfo(bool show); + +void ICON_Setting(bool show); +void ICON_Pause(bool show); +void ICON_Continue(bool show); +void ICON_Stop(bool show); + +#if HAS_HOTEND || HAS_HEATED_BED + // Popup message window + void DWIN_Popup_Temperature(const bool toohigh); +#endif + +#if HAS_HOTEND + void Popup_Window_ETempTooLow(); +#endif + +void Popup_Window_Resume(); +void Popup_Window_Home(const bool parking=false); +void Popup_Window_Leveling(); + +void Goto_PrintProcess(); +void Goto_MainMenu(); + +// Variable control +void HMI_Move_X(); +void HMI_Move_Y(); +void HMI_Move_Z(); +void HMI_Move_E(); + +void HMI_Zoffset(); + +#if HAS_HOTEND + void HMI_ETemp(); +#endif +#if HAS_HEATED_BED + void HMI_BedTemp(); +#endif +#if HAS_FAN + void HMI_FanSpeed(); +#endif + +void HMI_PrintSpeed(); + +void HMI_MaxFeedspeedXYZE(); +void HMI_MaxAccelerationXYZE(); +void HMI_MaxJerkXYZE(); +void HMI_StepXYZE(); +void HMI_SetLanguageCache(); + +void update_variable(); +void DWIN_Draw_Signed_Float(uint8_t size, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value); + +// SD Card +void HMI_SDCardInit(); +void HMI_SDCardUpdate(); + +// Main Process +void Icon_print(bool value); +void Icon_control(bool value); +void Icon_temperature(bool value); +void Icon_leveling(bool value); + +// Other +void Draw_Status_Area(const bool with_update); // Status Area +void HMI_StartFrame(const bool with_update); // Prepare the menu view +void HMI_MainMenu(); // Main process screen +void HMI_SelectFile(); // File page +void HMI_Printing(); // Print page +void HMI_Prepare(); // Prepare page +void HMI_Control(); // Control page +void HMI_Leveling(); // Level the page +void HMI_AxisMove(); // Axis movement menu +void HMI_Temperature(); // Temperature menu +void HMI_Motion(); // Sports menu +void HMI_Info(); // Information menu +void HMI_Tune(); // Adjust the menu + +#if HAS_PREHEAT + void HMI_PLAPreheatSetting(); // PLA warm-up setting + void HMI_ABSPreheatSetting(); // ABS warm-up setting +#endif + +void HMI_MaxSpeed(); // Maximum speed submenu +void HMI_MaxAcceleration(); // Maximum acceleration submenu +void HMI_MaxJerk(); // Maximum jerk speed submenu +void HMI_Step(); // Transmission ratio + +void HMI_Init(); +void DWIN_Update(); +void EachMomentUpdate(); +void DWIN_HandleScreen(); +void DWIN_StatusChanged(const char *text); +void DWIN_StatusChanged_P(PGM_P const pstr); +void DWIN_Draw_Checkbox(uint16_t color, uint16_t bcolor, uint16_t x, uint16_t y, bool mode /* = false*/); + +inline void DWIN_StartHoming() { HMI_flag.home_flag = true; } + +void DWIN_CompletedHoming(); +void DWIN_CompletedLeveling(); diff --git a/Marlin/src/lcd/dwin/dwin_lcd.cpp b/Marlin/src/lcd/e3v2/creality/dwin_lcd.cpp similarity index 90% rename from Marlin/src/lcd/dwin/dwin_lcd.cpp rename to Marlin/src/lcd/e3v2/creality/dwin_lcd.cpp index 7d1528bed19b..1ce95bd7296e 100644 --- a/Marlin/src/lcd/dwin/dwin_lcd.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin_lcd.cpp @@ -21,24 +21,24 @@ */ /******************************************************************************** - * @file dwin_lcd.cpp + * @file lcd/e3v2/creality/dwin_lcd.cpp * @author LEO / Creality3D * @date 2019/07/18 * @version 2.0.1 * @brief DWIN screen control functions ********************************************************************************/ -#include "../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if ENABLED(DWIN_CREALITY_LCD) -#include "../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #include "dwin_lcd.h" #include // for memset //#define DEBUG_OUT 1 -#include "../../core/debug_out.h" +#include "../../../core/debug_out.h" // Make sure DWIN_SendBuf is large enough to hold the largest string plus draw command and tail. // Assume the narrowest (6 pixel) font and 2-byte gb2312-encoded characters. @@ -82,20 +82,27 @@ inline void DWIN_String(size_t &i, const __FlashStringHelper * string) { // Send the data in the buffer and the packet end inline void DWIN_Send(size_t &i) { ++i; - LOOP_L_N(n, i) { MYSERIAL1.write(DWIN_SendBuf[n]); delayMicroseconds(1); } - LOOP_L_N(n, 4) { MYSERIAL1.write(DWIN_BufTail[n]); delayMicroseconds(1); } + 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); } } /*-------------------------------------- System variable function --------------------------------------*/ // Handshake (1: Success, 0: Fail) bool DWIN_Handshake(void) { + #ifndef LCD_BAUDRATE + #define LCD_BAUDRATE 115200 + #endif + LCD_SERIAL.begin(LCD_BAUDRATE); + const millis_t serial_connect_timeout = millis() + 1000UL; + while (!LCD_SERIAL.connected() && PENDING(millis(), serial_connect_timeout)) { /*nada*/ } + size_t i = 0; DWIN_Byte(i, 0x00); DWIN_Send(i); - while (MYSERIAL1.available() > 0 && recnum < (signed)sizeof(databuf)) { - databuf[recnum] = MYSERIAL1.read(); + while (LCD_SERIAL.available() > 0 && recnum < (signed)sizeof(databuf)) { + databuf[recnum] = LCD_SERIAL.read(); // ignore the invalid data if (databuf[0] != FHONE) { // prevent the program from running. if (recnum > 0) { @@ -115,6 +122,17 @@ bool DWIN_Handshake(void) { && databuf[3] == 'K' ); } +void DWIN_Startup(void) { + DEBUG_ECHOPGM("\r\nDWIN handshake "); + delay(750); // Delay here or init later in the boot process + if (DWIN_Handshake()) DEBUG_ECHOLNPGM("ok."); else DEBUG_ECHOLNPGM("error."); + DWIN_Frame_SetDir(1); + #if DISABLED(SHOW_BOOTSCREEN) + DWIN_Frame_Clear(Color_Bg_Black); // MarlinUI handles the bootscreen so just clear here + #endif + DWIN_UpdateLCD(); +} + // Set the backlight luminance // luminance: (0x00-0xFF) void DWIN_Backlight_SetLuminance(const uint8_t luminance) { @@ -157,9 +175,10 @@ void DWIN_Frame_Clear(const uint16_t color) { // width: point width 0x01-0x0F // height: point height 0x01-0x0F // x,y: upper left point -void DWIN_Draw_Point(uint8_t width, uint8_t height, uint16_t x, uint16_t y) { +void DWIN_Draw_Point(uint16_t color, uint8_t width, uint8_t height, uint16_t x, uint16_t y) { size_t i = 0; DWIN_Byte(i, 0x02); + DWIN_Word(i, color); DWIN_Byte(i, width); DWIN_Byte(i, height); DWIN_Word(i, x); @@ -231,8 +250,8 @@ void DWIN_Frame_AreaMove(uint8_t mode, uint8_t dir, uint16_t dis, // bColor: Background color // x/y: Upper-left coordinate of the string // *string: The string -void DWIN_Draw_String(bool widthAdjust, bool bShow, uint8_t size, - uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, char *string) { +void DWIN_Draw_String(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, char *string) { + uint8_t widthAdjust = 0; size_t i = 0; DWIN_Byte(i, 0x11); // Bit 7: widthAdjust @@ -349,6 +368,7 @@ void DWIN_ICON_Show(uint8_t libID, uint8_t picID, uint16_t x, uint16_t y) { DWIN_Word(i, x); DWIN_Word(i, y); DWIN_Byte(i, 0x80 | libID); + //DWIN_Byte(i, libID); DWIN_Byte(i, picID); DWIN_Send(i); } @@ -414,7 +434,7 @@ void DWIN_ICON_Animation(uint8_t animID, bool animate, uint8_t libID, uint8_t pi // state: 16 bits, each bit is the state of an animation id void DWIN_ICON_AnimationControl(uint16_t state) { size_t i = 0; - DWIN_Byte(i, 0x28); + DWIN_Byte(i, 0x29); DWIN_Word(i, state); DWIN_Send(i); } diff --git a/Marlin/src/lcd/e3v2/creality/dwin_lcd.h b/Marlin/src/lcd/e3v2/creality/dwin_lcd.h new file mode 100644 index 000000000000..e5e79df0fdb4 --- /dev/null +++ b/Marlin/src/lcd/e3v2/creality/dwin_lcd.h @@ -0,0 +1,369 @@ +/** + * 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 + +/******************************************************************************** + * @file dwin_lcd.h + * @author LEO / Creality3D + * @date 2019/07/18 + * @version 2.0.1 + * @brief 迪文屏控制操作函数 + ********************************************************************************/ + +#include + +#define RECEIVED_NO_DATA 0x00 +#define RECEIVED_SHAKE_HAND_ACK 0x01 + +#define FHONE 0xAA + +#define DWIN_SCROLL_UP 2 +#define DWIN_SCROLL_DOWN 3 + +#define DWIN_WIDTH 272 +#define DWIN_HEIGHT 480 + +// Character matrix width x height +//#define LCD_WIDTH ((DWIN_WIDTH) / 8) +//#define LCD_HEIGHT ((DWIN_HEIGHT) / 12) + +// Picture ID +#define DWIN_Boot_Screen 0 +#define Language_English 1 +#define Language_Chinese 2 + +// ICON ID +#define ICON 0x09 + +#define ICON_LOGO 0 +#define ICON_Print_0 1 +#define ICON_Print_1 2 +#define ICON_Prepare_0 3 +#define ICON_Prepare_1 4 +#define ICON_Control_0 5 +#define ICON_Control_1 6 +#define ICON_Leveling_0 7 +#define ICON_Leveling_1 8 +#define ICON_HotendTemp 9 +#define ICON_BedTemp 10 +#define ICON_Speed 11 +#define ICON_Zoffset 12 +#define ICON_Back 13 +#define ICON_File 14 +#define ICON_PrintTime 15 +#define ICON_RemainTime 16 +#define ICON_Setup_0 17 +#define ICON_Setup_1 18 +#define ICON_Pause_0 19 +#define ICON_Pause_1 20 +#define ICON_Continue_0 21 +#define ICON_Continue_1 22 +#define ICON_Stop_0 23 +#define ICON_Stop_1 24 +#define ICON_Bar 25 +#define ICON_More 26 + +#define ICON_Axis 27 +#define ICON_CloseMotor 28 +#define ICON_Homing 29 +#define ICON_SetHome 30 +#define ICON_PLAPreheat 31 +#define ICON_ABSPreheat 32 +#define ICON_Cool 33 +#define ICON_Language 34 + +#define ICON_MoveX 35 +#define ICON_MoveY 36 +#define ICON_MoveZ 37 +#define ICON_Extruder 38 + +#define ICON_Temperature 40 +#define ICON_Motion 41 +#define ICON_WriteEEPROM 42 +#define ICON_ReadEEPROM 43 +#define ICON_ResumeEEPROM 44 +#define ICON_Info 45 + +#define ICON_SetEndTemp 46 +#define ICON_SetBedTemp 47 +#define ICON_FanSpeed 48 +#define ICON_SetPLAPreheat 49 +#define ICON_SetABSPreheat 50 + +#define ICON_MaxSpeed 51 +#define ICON_MaxAccelerated 52 +#define ICON_MaxJerk 53 +#define ICON_Step 54 +#define ICON_PrintSize 55 +#define ICON_Version 56 +#define ICON_Contact 57 +#define ICON_StockConfiguraton 58 +#define ICON_MaxSpeedX 59 +#define ICON_MaxSpeedY 60 +#define ICON_MaxSpeedZ 61 +#define ICON_MaxSpeedE 62 +#define ICON_MaxAccX 63 +#define ICON_MaxAccY 64 +#define ICON_MaxAccZ 65 +#define ICON_MaxAccE 66 +#define ICON_MaxSpeedJerkX 67 +#define ICON_MaxSpeedJerkY 68 +#define ICON_MaxSpeedJerkZ 69 +#define ICON_MaxSpeedJerkE 70 +#define ICON_StepX 71 +#define ICON_StepY 72 +#define ICON_StepZ 73 +#define ICON_StepE 74 +#define ICON_Setspeed 75 +#define ICON_SetZOffset 76 +#define ICON_Rectangle 77 +#define ICON_BLTouch 78 +#define ICON_TempTooLow 79 +#define ICON_AutoLeveling 80 +#define ICON_TempTooHigh 81 +#define ICON_NoTips_C 82 +#define ICON_NoTips_E 83 +#define ICON_Continue_C 84 +#define ICON_Continue_E 85 +#define ICON_Cancel_C 86 +#define ICON_Cancel_E 87 +#define ICON_Confirm_C 88 +#define ICON_Confirm_E 89 +#define ICON_Info_0 90 +#define ICON_Info_1 91 + +#define ICON_AdvSet ICON_Language +#define ICON_HomeOff ICON_AdvSet +#define ICON_HomeOffX ICON_StepX +#define ICON_HomeOffY ICON_StepY +#define ICON_HomeOffZ ICON_StepZ +#define ICON_ProbeOff ICON_AdvSet +#define ICON_ProbeOffX ICON_StepX +#define ICON_ProbeOffY ICON_StepY +#define ICON_PIDNozzle ICON_SetEndTemp +#define ICON_PIDbed ICON_SetBedTemp + +/** + * 3-.0:The font size, 0x00-0x09, corresponds to the font size below: + * 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 +#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 + +#define DWIN_FONT_MENU font10x20 +#define DWIN_FONT_STAT font10x20 +#define DWIN_FONT_HEAD font10x20 +#define DWIN_FONT_ALERT font14x28 + +// Color +#define Color_White 0xFFFF +#define Color_Yellow 0xFF0F +#define Color_Error_Red 0xB000 // Error! +#define Color_Bg_Red 0xF00F // Red background color +#define Color_Bg_Window 0x31E8 // Popup background color +#define Color_Bg_Blue 0x1125 // Dark blue background color +#define Color_Bg_Black 0x0841 // Black background color +#define Color_IconBlue 0x45FA // Lighter blue that matches icons/accents +#define Popup_Text_Color 0xD6BA // Popup font background color +#define Line_Color 0x3A6A // Split line color +#define Rectangle_Color 0xEE2F // Blue square cursor color +#define Percent_Color 0xFE29 // Percentage color +#define BarFill_Color 0x10E4 // Fill color of progress bar +#define Select_Color 0x33BB // Selected color + +/*-------------------------------------- System variable function --------------------------------------*/ + +// Handshake (1: Success, 0: Fail) +bool DWIN_Handshake(void); + +// Common DWIN startup +void DWIN_Startup(void); + +// Set the backlight luminance +// luminance: (0x00-0xFF) +void DWIN_Backlight_SetLuminance(const uint8_t luminance); + +// Set screen display direction +// dir: 0=0°, 1=90°, 2=180°, 3=270° +void DWIN_Frame_SetDir(uint8_t dir); + +// Update display +void DWIN_UpdateLCD(void); + +/*---------------------------------------- Drawing functions ----------------------------------------*/ + +// Clear screen +// color: Clear screen color +void DWIN_Frame_Clear(const uint16_t color); + +// Draw a point +// color: point color +// width: point width 0x01-0x0F +// height: point height 0x01-0x0F +// x,y: upper left point +void DWIN_Draw_Point(uint16_t color, uint8_t width, uint8_t height, uint16_t x, uint16_t y); + +// Draw a line +// color: Line segment color +// xStart/yStart: Start point +// xEnd/yEnd: End point +void DWIN_Draw_Line(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); + +// Draw a Horizontal line +// color: Line segment color +// xStart/yStart: Start point +// xLength: Line Length +inline void DWIN_Draw_HLine(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xLength) { + DWIN_Draw_Line(color, xStart, yStart, xStart + xLength - 1, yStart); +} + +// Draw a Vertical line +// color: Line segment color +// xStart/yStart: Start point +// yLength: Line Length +inline void DWIN_Draw_VLine(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t yLength) { + DWIN_Draw_Line(color, xStart, yStart, xStart, yStart + yLength - 1); +} + +// Draw a rectangle +// mode: 0=frame, 1=fill, 2=XOR fill +// color: Rectangle color +// xStart/yStart: upper left point +// xEnd/yEnd: lower right point +void DWIN_Draw_Rectangle(uint8_t mode, uint16_t color, + uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); + +// Draw a box +// mode: 0=frame, 1=fill, 2=XOR fill +// color: Rectangle color +// xStart/yStart: upper left point +// xSize/ySize: box size +inline void DWIN_Draw_Box(uint8_t mode, uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xSize, uint16_t ySize) { + DWIN_Draw_Rectangle(mode, color, xStart, yStart, xStart + xSize - 1, yStart + ySize - 1); +} + +// Move a screen area +// mode: 0, circle shift; 1, translation +// dir: 0=left, 1=right, 2=up, 3=down +// dis: Distance +// color: Fill color +// xStart/yStart: upper left point +// xEnd/yEnd: bottom right point +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 +// bShow: true=display background color; false=don't display background color +// size: Font size +// color: Character color +// bColor: Background color +// x/y: Upper-left coordinate of the string +// *string: The string +void DWIN_Draw_String(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, char *string); + +class __FlashStringHelper; + +inline void DWIN_Draw_String(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const __FlashStringHelper *title) { + DWIN_Draw_String(bShow, size, color, bColor, x, y, (char *)title); +} + +// Draw a positive integer +// bShow: true=display background color; false=don't display background color +// zeroFill: true=zero fill; false=no zero fill +// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space +// size: Font size +// color: Character color +// bColor: Background color +// iNum: Number of digits +// x/y: Upper-left coordinate +// value: Integer value +void DWIN_Draw_IntValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, + uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, uint16_t value); + +// Draw a floating point number +// bShow: true=display background color; false=don't display background color +// zeroFill: true=zero fill; false=no zero fill +// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space +// size: Font size +// color: Character color +// bColor: Background color +// iNum: Number of whole digits +// fNum: Number of decimal digits +// x/y: Upper-left point +// value: Float value +void DWIN_Draw_FloatValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, + uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value); + +/*---------------------------------------- Picture related functions ----------------------------------------*/ + +// Draw JPG and cached in #0 virtual display area +// id: Picture ID +void DWIN_JPG_ShowAndCache(const uint8_t id); + +// Draw an Icon +// libID: Icon library ID +// picID: Icon ID +// x/y: Upper-left point +void DWIN_ICON_Show(uint8_t libID, uint8_t picID, uint16_t x, uint16_t y); + +// Unzip the JPG picture to a virtual display area +// n: Cache index +// id: Picture ID +void DWIN_JPG_CacheToN(uint8_t n, uint8_t id); + +// Unzip the JPG picture to virtual display area #1 +// id: Picture ID +inline void DWIN_JPG_CacheTo1(uint8_t id) { DWIN_JPG_CacheToN(1, id); } + +// Copy area from virtual display area to current screen +// cacheID: virtual area number +// xStart/yStart: Upper-left of virtual area +// xEnd/yEnd: Lower-right of virtual area +// x/y: Screen paste point +void DWIN_Frame_AreaCopy(uint8_t cacheID, uint16_t xStart, uint16_t yStart, + uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y); + +// Animate a series of icons +// animID: Animation ID up to 16 +// animate: animation on or off +// libID: Icon library ID +// picIDs: Icon starting ID +// picIDe: Icon ending ID +// x/y: Upper-left point +// interval: Display time interval, unit 10mS +void DWIN_ICON_Animation(uint8_t animID, bool animate, uint8_t libID, uint8_t picIDs, + uint8_t picIDe, uint16_t x, uint16_t y, uint16_t interval); + +// Animation Control +// state: 16 bits, each bit is the state of an animation id +void DWIN_ICON_AnimationControl(uint16_t state); diff --git a/Marlin/src/lcd/e3v2/creality/rotary_encoder.cpp b/Marlin/src/lcd/e3v2/creality/rotary_encoder.cpp new file mode 100644 index 000000000000..4fc10393b974 --- /dev/null +++ b/Marlin/src/lcd/e3v2/creality/rotary_encoder.cpp @@ -0,0 +1,256 @@ +/** + * 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 . + * + */ + +/***************************************************************************** + * @file lcd/e3v2/creality/rotary_encoder.cpp + * @author LEO / Creality3D + * @date 2019/07/06 + * @version 2.0.1 + * @brief Rotary encoder functions + *****************************************************************************/ + +#include "../../../inc/MarlinConfigPre.h" + +#if ENABLED(DWIN_CREALITY_LCD) + +#include "rotary_encoder.h" +#include "../../buttons.h" + +#include "../../../MarlinCore.h" +#include "../../../HAL/shared/Delay.h" + +#if HAS_BUZZER + #include "../../../libs/buzzer.h" +#endif + +#include + +#ifndef ENCODER_PULSES_PER_STEP + #define ENCODER_PULSES_PER_STEP 4 +#endif + +ENCODER_Rate EncoderRate; + +// Buzzer +void Encoder_tick() { + #if PIN_EXISTS(BEEPER) + WRITE(BEEPER_PIN, HIGH); + delay(10); + WRITE(BEEPER_PIN, LOW); + #endif +} + +// Encoder initialization +void Encoder_Configuration() { + #if BUTTON_EXISTS(EN1) + SET_INPUT_PULLUP(BTN_EN1); + #endif + #if BUTTON_EXISTS(EN2) + SET_INPUT_PULLUP(BTN_EN2); + #endif + #if BUTTON_EXISTS(ENC) + SET_INPUT_PULLUP(BTN_ENC); + #endif + #if PIN_EXISTS(BEEPER) + SET_OUTPUT(BEEPER_PIN); + #endif +} + +// Analyze encoder value and return state +ENCODER_DiffState Encoder_ReceiveAnalyze() { + const millis_t now = millis(); + static uint8_t lastEncoderBits; + uint8_t newbutton = 0; + static signed char temp_diff = 0; + + ENCODER_DiffState temp_diffState = ENCODER_DIFF_NO; + if (BUTTON_PRESSED(EN1)) newbutton |= EN_A; + if (BUTTON_PRESSED(EN2)) newbutton |= EN_B; + if (BUTTON_PRESSED(ENC)) { + static millis_t next_click_update_ms; + if (ELAPSED(now, next_click_update_ms)) { + next_click_update_ms = millis() + 300; + Encoder_tick(); + #if PIN_EXISTS(LCD_LED) + //LED_Action(); + #endif + const bool was_waiting = wait_for_user; + wait_for_user = false; + return was_waiting ? ENCODER_DIFF_NO : ENCODER_DIFF_ENTER; + } + else return ENCODER_DIFF_NO; + } + if (newbutton != lastEncoderBits) { + switch (newbutton) { + case ENCODER_PHASE_0: + if (lastEncoderBits == ENCODER_PHASE_3) temp_diff++; + else if (lastEncoderBits == ENCODER_PHASE_1) temp_diff--; + break; + case ENCODER_PHASE_1: + if (lastEncoderBits == ENCODER_PHASE_0) temp_diff++; + else if (lastEncoderBits == ENCODER_PHASE_2) temp_diff--; + break; + case ENCODER_PHASE_2: + if (lastEncoderBits == ENCODER_PHASE_1) temp_diff++; + else if (lastEncoderBits == ENCODER_PHASE_3) temp_diff--; + break; + case ENCODER_PHASE_3: + if (lastEncoderBits == ENCODER_PHASE_2) temp_diff++; + else if (lastEncoderBits == ENCODER_PHASE_0) temp_diff--; + break; + } + lastEncoderBits = newbutton; + } + + if (ABS(temp_diff) >= ENCODER_PULSES_PER_STEP) { + if (temp_diff > 0) temp_diffState = ENCODER_DIFF_CW; + else temp_diffState = ENCODER_DIFF_CCW; + + #if ENABLED(ENCODER_RATE_MULTIPLIER) + + millis_t ms = millis(); + int32_t encoderMultiplier = 1; + + // if must encoder rati multiplier + if (EncoderRate.enabled) { + const float abs_diff = ABS(temp_diff), + encoderMovementSteps = abs_diff / (ENCODER_PULSES_PER_STEP); + if (EncoderRate.lastEncoderTime) { + // Note that the rate is always calculated between two passes through the + // loop and that the abs of the temp_diff value is tracked. + const float encoderStepRate = encoderMovementSteps / float(ms - EncoderRate.lastEncoderTime) * 1000; + if (encoderStepRate >= ENCODER_100X_STEPS_PER_SEC) encoderMultiplier = 100; + else if (encoderStepRate >= ENCODER_10X_STEPS_PER_SEC) encoderMultiplier = 10; + else if (encoderStepRate >= ENCODER_5X_STEPS_PER_SEC) encoderMultiplier = 5; + } + EncoderRate.lastEncoderTime = ms; + } + + #else + + constexpr int32_t encoderMultiplier = 1; + + #endif + + // EncoderRate.encoderMoveValue += (temp_diff * encoderMultiplier) / (ENCODER_PULSES_PER_STEP); + EncoderRate.encoderMoveValue = (temp_diff * encoderMultiplier) / (ENCODER_PULSES_PER_STEP); + if (EncoderRate.encoderMoveValue < 0) EncoderRate.encoderMoveValue = -EncoderRate.encoderMoveValue; + + temp_diff = 0; + } + return temp_diffState; +} + +#if PIN_EXISTS(LCD_LED) + + // Take the low 24 valid bits 24Bit: G7 G6 G5 G4 G3 G2 G1 G0 R7 R6 R5 R4 R3 R2 R1 R0 B7 B6 B5 B4 B3 B2 B1 B0 + uint16_t LED_DataArray[LED_NUM]; + + // LED light operation + void LED_Action() { + LED_Control(RGB_SCALE_WARM_WHITE,0x0F); + delay(30); + LED_Control(RGB_SCALE_WARM_WHITE,0x00); + } + + // LED initialization + void LED_Configuration() { + SET_OUTPUT(LCD_LED_PIN); + } + + // LED write data + void LED_WriteData() { + uint8_t tempCounter_LED, tempCounter_Bit; + for (tempCounter_LED = 0; tempCounter_LED < LED_NUM; tempCounter_LED++) { + for (tempCounter_Bit = 0; tempCounter_Bit < 24; tempCounter_Bit++) { + if (LED_DataArray[tempCounter_LED] & (0x800000 >> tempCounter_Bit)) { + LED_DATA_HIGH; + DELAY_NS(300); + LED_DATA_LOW; + DELAY_NS(200); + } + else { + LED_DATA_HIGH; + LED_DATA_LOW; + DELAY_NS(200); + } + } + } + } + + // LED control + // RGB_Scale: RGB color ratio + // luminance: brightness (0~0xFF) + void LED_Control(const uint8_t RGB_Scale, const uint8_t luminance) { + for (uint8_t i = 0; i < LED_NUM; i++) { + LED_DataArray[i] = 0; + switch (RGB_Scale) { + case RGB_SCALE_R10_G7_B5: LED_DataArray[i] = (luminance * 10/10) << 8 | (luminance * 7/10) << 16 | luminance * 5/10; break; + case RGB_SCALE_R10_G7_B4: LED_DataArray[i] = (luminance * 10/10) << 8 | (luminance * 7/10) << 16 | luminance * 4/10; break; + case RGB_SCALE_R10_G8_B7: LED_DataArray[i] = (luminance * 10/10) << 8 | (luminance * 8/10) << 16 | luminance * 7/10; break; + } + } + LED_WriteData(); + } + + // LED gradient control + // RGB_Scale: RGB color ratio + // luminance: brightness (0~0xFF) + // change_Time: gradient time (ms) + void LED_GraduallyControl(const uint8_t RGB_Scale, const uint8_t luminance, const uint16_t change_Interval) { + struct { uint8_t g, r, b; } led_data[LED_NUM]; + for (uint8_t i = 0; i < LED_NUM; i++) { + switch (RGB_Scale) { + case RGB_SCALE_R10_G7_B5: + led_data[i] = { luminance * 7/10, luminance * 10/10, luminance * 5/10 }; + break; + case RGB_SCALE_R10_G7_B4: + led_data[i] = { luminance * 7/10, luminance * 10/10, luminance * 4/10 }; + break; + case RGB_SCALE_R10_G8_B7: + led_data[i] = { luminance * 8/10, luminance * 10/10, luminance * 7/10 }; + break; + } + } + + struct { bool g, r, b; } led_flag = { false, false, false }; + for (uint8_t i = 0; i < LED_NUM; i++) { + while (1) { + const uint8_t g = uint8_t(LED_DataArray[i] >> 16), + r = uint8_t(LED_DataArray[i] >> 8), + b = uint8_t(LED_DataArray[i]); + if (g == led_data[i].g) led_flag.g = true; + else LED_DataArray[i] += (g > led_data[i].g) ? -0x010000 : 0x010000; + if (r == led_data[i].r) led_flag.r = true; + else LED_DataArray[i] += (r > led_data[i].r) ? -0x000100 : 0x000100; + if (b == led_data[i].b) led_flag.b = true; + else LED_DataArray[i] += (b > led_data[i].b) ? -0x000001 : 0x000001; + LED_WriteData(); + if (led_flag.r && led_flag.g && led_flag.b) break; + delay(change_Interval); + } + } + } + +#endif // LCD_LED + +#endif // DWIN_CREALITY_LCD diff --git a/Marlin/src/lcd/dwin/e3v2/rotary_encoder.h b/Marlin/src/lcd/e3v2/creality/rotary_encoder.h similarity index 80% rename from Marlin/src/lcd/dwin/e3v2/rotary_encoder.h rename to Marlin/src/lcd/e3v2/creality/rotary_encoder.h index 93e54839d625..f73577b3b031 100644 --- a/Marlin/src/lcd/dwin/e3v2/rotary_encoder.h +++ b/Marlin/src/lcd/e3v2/creality/rotary_encoder.h @@ -22,7 +22,7 @@ #pragma once /***************************************************************************** - * @file rotary_encoder.h + * @file lcd/e3v2/creality/rotary_encoder.h * @author LEO / Creality3D * @date 2019/07/06 * @version 2.0.1 @@ -30,19 +30,9 @@ ****************************************************************************/ #include "../../../inc/MarlinConfig.h" -#include "../../../MarlinCore.h" /*********************** Encoder Set ***********************/ -#define ENCODER_PHASE_0 0 -#define ENCODER_PHASE_1 2 -#define ENCODER_PHASE_2 3 -#define ENCODER_PHASE_3 1 - -#define ENCODER_PULSES_PER_STEP 4 - -#define BUTTON_PRESSED(BN) !READ(BTN_## BN) - typedef struct { bool enabled = false; int encoderMoveValue = 0; @@ -59,10 +49,10 @@ typedef enum { } ENCODER_DiffState; // Encoder initialization -void Encoder_Configuration(void); +void Encoder_Configuration(); // Analyze encoder value and return state -ENCODER_DiffState Encoder_ReceiveAnalyze(void); +ENCODER_DiffState Encoder_ReceiveAnalyze(); /*********************** Encoder LED ***********************/ @@ -82,23 +72,23 @@ ENCODER_DiffState Encoder_ReceiveAnalyze(void); extern unsigned int LED_DataArray[LED_NUM]; // LED light operation - void LED_Action(void); + void LED_Action(); // LED initialization - void LED_Configuration(void); + void LED_Configuration(); // LED write data - void LED_WriteData(void); + void LED_WriteData(); // LED control // RGB_Scale: RGB color ratio // luminance: brightness (0~0xFF) - void LED_Control(unsigned char RGB_Scale, unsigned char luminance); + void LED_Control(const uint8_t RGB_Scale, const uint8_t luminance); // LED gradient control // RGB_Scale: RGB color ratio // luminance: brightness (0~0xFF) // change_Time: gradient time (ms) - void LED_GraduallyControl(unsigned char RGB_Scale, unsigned char luminance, unsigned int change_Interval); + void LED_GraduallyControl(const uint8_t RGB_Scale, const uint8_t luminance, const uint16_t change_Interval); #endif // LCD_LED diff --git a/Marlin/src/lcd/extui/anycubic_chiron/FileNavigator.cpp b/Marlin/src/lcd/extui/anycubic_chiron/FileNavigator.cpp new file mode 100644 index 000000000000..58adf9761fa8 --- /dev/null +++ b/Marlin/src/lcd/extui/anycubic_chiron/FileNavigator.cpp @@ -0,0 +1,258 @@ +/** + * 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 . + * + */ + +/** + * lcd/extui/anycubic_chiron/FileNavigator.cpp + * + * Extensible_UI implementation for Anycubic Chiron + * Written By Nick Wells, 2020 [https://github.com/SwiftNick] + * (not affiliated with Anycubic, Ltd.) + * + * The AC panel wants files in block of 4 and can only display a flat list + * This library allows full folder traversal or flat file display and supports both standerd and new style panels. + * + * ## Old Style TFT panel + * Supported chars {}[]-+=_"$%^&*()~<>| + * Max display length 22 chars + * Max path len 29 chars + * (DOS 8.3 filepath max 29chars) + * (long filepath Max 22) + * + * ## New TFT Panel Format file display format + * Supported chars {}[]-+=_!"$%^&*()~<>\| + * Max display length 26 chars + * Max path len 29 chars + * (DOS 8.3 filepath must end '.GCO') + * (long filepath must end '.gcode') + * + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if ENABLED(ANYCUBIC_LCD_CHIRON) +#include "FileNavigator.h" +#include "chiron_tft.h" + +using namespace ExtUI; + +#define DEBUG_OUT ACDEBUG(AC_FILE) +#include "../../../core/debug_out.h" + +namespace Anycubic { + +FileNavigator filenavigator; +FileList FileNavigator::filelist; // Instance of the Marlin file API +uint16_t FileNavigator::lastpanelindex; +uint16_t FileNavigator::currentindex; // override the panel request +uint8_t FileNavigator::currentfolderdepth; +uint16_t FileNavigator::currentfolderindex[MAX_FOLDER_DEPTH]; // track folder pos for iteration +char FileNavigator::currentfoldername[MAX_PATH_LEN + 1]; // Current folder path + +FileNavigator::FileNavigator() { reset(); } + +void FileNavigator::reset() { + DEBUG_ECHOLNPGM("reset()"); + currentfoldername[0] = '\0'; + currentfolderdepth = 0; + currentindex = 0; + lastpanelindex = 0; + ZERO(currentfolderindex); + + // Start at root folder + while (!filelist.isAtRootDir()) filelist.upDir(); + refresh(); +} + +void FileNavigator::refresh() { filelist.refresh(); } + +void FileNavigator::changeDIR(const char *folder) { + if (currentfolderdepth >= MAX_FOLDER_DEPTH) return; // limit the folder depth + DEBUG_ECHOLNPAIR("FD:" , folderdepth, " FP:",currentindex, " currentfolder:", currentfoldername, " enter:", folder); + currentfolderindex[currentfolderdepth] = currentindex; + strcat(currentfoldername, folder); + strcat(currentfoldername, "/"); + filelist.changeDir(folder); + currentfolderdepth++; + currentindex = 0; +} + +void FileNavigator::upDIR() { + DEBUG_ECHOLNPAIR("upDIR() from D:", currentfolderdepth, " N:", currentfoldername); + if (!filelist.isAtRootDir()) { + filelist.upDir(); + currentfolderdepth--; + currentindex = currentfolderindex[currentfolderdepth]; // restore last position in the folder + filelist.seek(currentindex); // restore file information + } + + // Remove the child folder from the stored path + if (currentfolderdepth == 0) + currentfoldername[0] = '\0'; + else { + char * const pos = strchr(currentfoldername, '/'); + *(pos + 1) = '\0'; + } +} + +void FileNavigator::skiptofileindex(uint16_t skip) { + if (skip == 0) return; + while (skip > 0) { + if (filelist.seek(currentindex)) { + DEBUG_ECHOLNPAIR("CI:", currentindex, " FD:", currentfolderdepth, " N:", skip, " ", filelist.longFilename()); + if (!filelist.isDir()) { + skip--; + currentindex++; + } + else + changeDIR(filelist.shortFilename()); + } // valid file + if (currentindex == filelist.count()) { + if (currentfolderdepth > 0) { + upDIR(); + currentindex++; + } + else break; // end of root folder + } // end of folder + } // files needed + // No more files available. +} + +#if ENABLED(AC_SD_FOLDER_VIEW) // SD Folder navigation + + void FileNavigator::getFiles(uint16_t index, panel_type_t paneltype, uint8_t filesneeded) { + if (index == 0) currentindex = 0; + // Each time we change folder we reset the file index to 0 and keep track + // of the current position, since the TFT panel isn't aware of folder trees. + if (index > 0) { + --currentindex; // go back a file to take account of the .. we added to the root. + if (index > lastpanelindex) + currentindex += filesneeded; + else + currentindex = currentindex < 4 ? 0 : currentindex - filesneeded; + } + lastpanelindex = index; + + DEBUG_ECHOLNPAIR("index=", index, " currentindex=", currentindex); + + if (currentindex == 0 && currentfolderdepth > 0) { // Add a link to go up a folder + // The new panel ignores entries that don't end in .GCO or .gcode so add and pad them. + if (paneltype == AC_panel_new) { + TFTSer.println("<<.GCO"); + Chiron.SendtoTFTLN(PSTR(".. .gcode")); + } + else { + TFTSer.println("<<"); + TFTSer.println(".."); + } + filesneeded--; + } + + for (uint16_t seek = currentindex; seek < currentindex + filesneeded; seek++) { + if (filelist.seek(seek)) { + sendFile(paneltype); + DEBUG_ECHOLNPAIR("-", seek, " '", filelist.longFilename(), "' '", currentfoldername, "", filelist.shortFilename(), "'"); + } + } + } + + void FileNavigator::sendFile(panel_type_t paneltype) { + if (filelist.isDir()) { + // Add mandatory tags for new panel otherwise lines are ignored. + if (paneltype == AC_panel_new) { + TFTSer.print(filelist.shortFilename()); + TFTSer.println(".GCO"); + TFTSer.print(filelist.shortFilename()); + TFTSer.write('/'); + // Make sure we fill all 29 chars of the display line to clear the text buffer otherwise the last line is still visible + for (int8_t i = strlen(filelist.shortFilename()); i < 19; i++) + TFTSer.write(' '); + TFTSer.println(".gcode"); + } + else { + TFTSer.println(filelist.shortFilename()); + TFTSer.print(filelist.shortFilename()); + TFTSer.write('/'); + TFTSer.println(); + } + } + else { // Not DIR + TFTSer.write('/'); + if (currentfolderdepth > 0) TFTSer.print(currentfoldername); + TFTSer.println(filelist.shortFilename()); + TFTSer.print(filelist.longFilename()); + + // Make sure we fill all 29 chars of the display line to clear the text buffer otherwise the last line is still visible + if (paneltype == AC_panel_new) + for (int8_t i = strlen(filelist.longFilename()); i < 26; i++) + TFTSer.write(' '); + + TFTSer.println(); + } + } // AC_SD_FOLDER_VIEW + +#else // Flat file list + + void FileNavigator::getFiles(uint16_t index, panel_type_t paneltype, uint8_t filesneeded) { + DEBUG_ECHOLNPAIR("getFiles() I:", index," L:", lastpanelindex); + // if we're searching backwards, jump back to start and search forward + if (index < lastpanelindex) { + reset(); + skiptofileindex(index); + } + lastpanelindex = index; + + while (filesneeded > 0) { + if (filelist.seek(currentindex)) { + if (!filelist.isDir()) { + sendFile(paneltype); + filesneeded--; + currentindex++; + } + else + changeDIR(filelist.shortFilename()); + } // valid file + + if (currentindex == filelist.count()) { + if (currentfolderdepth > 0) { + upDIR(); + currentindex++; + } + else break; // end of root folder + } // end of folder + } // files needed + // No more files available. + } + + void FileNavigator::sendFile(panel_type_t paneltype) { + TFTSer.write('/'); + if (currentfolderdepth > 0) TFTSer.print(currentfoldername); + TFTSer.println(filelist.shortFilename()); + if (currentfolderdepth > 0) TFTSer.print(currentfoldername); + TFTSer.println(filelist.longFilename()); + DEBUG_ECHOLNPAIR("/", currentfoldername, "", filelist.shortFilename(), " ", filelist.longFilename()); + } + +#endif // Flat file list + +} // Anycubic namespace + +#endif // ANYCUBIC_LCD_CHIRON diff --git a/Marlin/src/lcd/extui/anycubic_chiron/FileNavigator.h b/Marlin/src/lcd/extui/anycubic_chiron/FileNavigator.h new file mode 100644 index 000000000000..ca4283f54ba3 --- /dev/null +++ b/Marlin/src/lcd/extui/anycubic_chiron/FileNavigator.h @@ -0,0 +1,61 @@ +/** + * 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 + +/** + * lcd/extui/anycubic_chiron/FileNavigator.h + * + * Extensible_UI implementation for Anycubic Chiron + * Written By Nick Wells, 2020 [https://github.com/SwiftNick] + * (not affiliated with Anycubic, Ltd.) + */ + +#include "chiron_tft_defs.h" +#include "../ui_api.h" + +using namespace ExtUI; + +namespace Anycubic { + +class FileNavigator { + public: + FileNavigator(); + static void reset(); + static void getFiles(uint16_t, panel_type_t, uint8_t filesneeded=4); + static void upDIR(); + static void changeDIR(const char *); + static void sendFile(panel_type_t); + static void refresh(); + static void skiptofileindex(uint16_t); + + static FileList filelist; + private: + static uint16_t lastpanelindex; + static uint16_t currentindex; + static uint8_t currentfolderdepth; + static uint16_t currentfolderindex[MAX_FOLDER_DEPTH]; + static char currentfoldername[MAX_PATH_LEN + 1]; +}; + +extern FileNavigator filenavigator; + +} diff --git a/Marlin/src/lcd/extui/lib/anycubic_chiron/Tunes.cpp b/Marlin/src/lcd/extui/anycubic_chiron/Tunes.cpp similarity index 94% rename from Marlin/src/lcd/extui/lib/anycubic_chiron/Tunes.cpp rename to Marlin/src/lcd/extui/anycubic_chiron/Tunes.cpp index f09c4db3f283..f228c471c9ca 100644 --- a/Marlin/src/lcd/extui/lib/anycubic_chiron/Tunes.cpp +++ b/Marlin/src/lcd/extui/anycubic_chiron/Tunes.cpp @@ -21,7 +21,7 @@ */ /** - * lcd/extui/lib/Tunes.cpp + * lcd/extui/anycubic_chiron/Tunes.cpp * * Extensible_UI implementation for Anycubic Chiron * Written By Nick Wells, 2020 [https://github.com/SwiftNick] @@ -33,12 +33,12 @@ * See Tunes.h for note and tune definitions. * ***********************************************************************/ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if ENABLED(ANYCUBIC_LCD_CHIRON) #include "Tunes.h" -#include "../../ui_api.h" +#include "../ui_api.h" namespace Anycubic { diff --git a/Marlin/src/lcd/extui/lib/anycubic_chiron/Tunes.h b/Marlin/src/lcd/extui/anycubic_chiron/Tunes.h similarity index 99% rename from Marlin/src/lcd/extui/lib/anycubic_chiron/Tunes.h rename to Marlin/src/lcd/extui/anycubic_chiron/Tunes.h index 1bafec43adf3..bf2e92d03e53 100644 --- a/Marlin/src/lcd/extui/lib/anycubic_chiron/Tunes.h +++ b/Marlin/src/lcd/extui/anycubic_chiron/Tunes.h @@ -22,7 +22,7 @@ #pragma once /** - * lcd/extui/lib/Tunes.h + * lcd/extui/anycubic_chiron/Tunes.h * * Extensible_UI implementation for Anycubic Chiron * Written By Nick Wells, 2020 [https://github.com/SwiftNick] diff --git a/Marlin/src/lcd/extui/anycubic_chiron/chiron_extui.cpp b/Marlin/src/lcd/extui/anycubic_chiron/chiron_extui.cpp new file mode 100644 index 000000000000..0f6f8abe3845 --- /dev/null +++ b/Marlin/src/lcd/extui/anycubic_chiron/chiron_extui.cpp @@ -0,0 +1,134 @@ +/** + * 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 . + * + */ + +/** + * lcd/extui/anycubic_chiron/chiron_extui.cpp + * + * Anycubic Chiron TFT support for Marlin + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if ENABLED(ANYCUBIC_LCD_CHIRON) + +#include "../ui_api.h" +#include "chiron_tft.h" + +using namespace Anycubic; + +namespace ExtUI { + + void onStartup() { Chiron.Startup(); } + + void onIdle() { Chiron.IdleLoop(); } + + void onPrinterKilled(PGM_P const error, PGM_P const component) { + Chiron.PrinterKilled(error,component); + } + + void onMediaInserted() { Chiron.MediaEvent(AC_media_inserted); } + void onMediaError() { Chiron.MediaEvent(AC_media_error); } + void onMediaRemoved() { Chiron.MediaEvent(AC_media_removed); } + + void onPlayTone(const uint16_t frequency, const uint16_t duration) { + #if ENABLED(SPEAKER) + ::tone(BEEPER_PIN, frequency, duration); + #endif + } + + void onPrintTimerStarted() { Chiron.TimerEvent(AC_timer_started); } + void onPrintTimerPaused() { Chiron.TimerEvent(AC_timer_paused); } + void onPrintTimerStopped() { Chiron.TimerEvent(AC_timer_stopped); } + void onFilamentRunout(const extruder_t) { Chiron.FilamentRunout(); } + void onUserConfirmRequired(const char * const msg) { Chiron.ConfirmationRequest(msg); } + void onStatusChanged(const char * const msg) { Chiron.StatusChange(msg); } + + void onHomingStart() {} + void onHomingComplete() {} + void onPrintFinished() {} + + void onFactoryReset() {} + + void onStoreSettings(char *buff) { + // Called when saving to EEPROM (i.e. M500). If the ExtUI needs + // permanent data to be stored, it can write up to eeprom_data_size bytes + // into buff. + + // Example: + // static_assert(sizeof(myDataStruct) <= eeprom_data_size); + // memcpy(buff, &myDataStruct, sizeof(myDataStruct)); + } + + void onLoadSettings(const char *buff) { + // Called while loading settings from EEPROM. If the ExtUI + // needs to retrieve data, it should copy up to eeprom_data_size bytes + // from buff + + // Example: + // static_assert(sizeof(myDataStruct) <= eeprom_data_size); + // memcpy(&myDataStruct, buff, sizeof(myDataStruct)); + } + + void onPostprocessSettings() { + // Called after loading or resetting stored settings + } + + void onConfigurationStoreWritten(bool success) { + // Called after the entire EEPROM has been written, + // whether successful or not. + } + + void onConfigurationStoreRead(bool success) { + // Called after the entire EEPROM has been read, + // whether successful or not. + } + + #if HAS_MESH + void onMeshLevelingStart() {} + + void onMeshUpdate(const int8_t xpos, const int8_t ypos, const_float_t zval) { + // Called when any mesh points are updated + //SERIAL_ECHOLNPAIR("onMeshUpdate() x:", xpos, " y:", ypos, " z:", zval); + } + + void onMeshUpdate(const int8_t xpos, const int8_t ypos, const probe_state_t state) { + // Called to indicate a special condition + //SERIAL_ECHOLNPAIR("onMeshUpdate() x:", xpos, " y:", ypos, " state:", state); + } + #endif + + #if ENABLED(POWER_LOSS_RECOVERY) + // Called on resume from power-loss + void onPowerLossResume() { Chiron.PowerLossRecovery(); } + #endif + + #if HAS_PID_HEATING + void onPidTuning(const result_t rst) { + // Called for temperature PID tuning result + } + #endif + + void onSteppersDisabled() {} + void onSteppersEnabled() {} +} + +#endif // ANYCUBIC_LCD_CHIRON diff --git a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp new file mode 100644 index 000000000000..0ecb138bd5f5 --- /dev/null +++ b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp @@ -0,0 +1,975 @@ +/** + * 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 . + * + */ + +/** + * lcd/extui/anycubic_chiron/chiron_tft.cpp + * + * Extensible_UI implementation for Anycubic Chiron + * Written By Nick Wells, 2020 [https://github.com/SwiftNick] + * (not affiliated with Anycubic, Ltd.) + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if ENABLED(ANYCUBIC_LCD_CHIRON) + +#include "chiron_tft.h" +#include "Tunes.h" +#include "FileNavigator.h" + +#include "../../../gcode/queue.h" +#include "../../../sd/cardreader.h" +#include "../../../libs/numtostr.h" +#include "../../../MarlinCore.h" + +namespace Anycubic { + +ChironTFT Chiron; +#if AUTO_DETECT_CHIRON_TFT + panel_type_t ChironTFT::panel_type = AC_panel_unknown; +#endif +last_error_t ChironTFT::last_error; +printer_state_t ChironTFT::printer_state; +paused_state_t ChironTFT::pause_state; +heater_state_t ChironTFT::hotend_state; +heater_state_t ChironTFT::hotbed_state; +xy_uint8_t ChironTFT::selectedmeshpoint; +char ChironTFT::selectedfile[MAX_PATH_LEN + 1]; +char ChironTFT::panel_command[MAX_CMND_LEN + 1]; +uint8_t ChironTFT::command_len; +float ChironTFT::live_Zoffset; +file_menu_t ChironTFT::file_menu; + +void ChironTFT::Startup() { + selectedfile[0] = '\0'; + panel_command[0] = '\0'; + command_len = 0; + last_error = AC_error_none; + printer_state = AC_printer_idle; + pause_state = AC_paused_idle; + hotend_state = AC_heater_off; + hotbed_state = AC_heater_off; + live_Zoffset = 0.0; + file_menu = AC_menu_file; + + // Setup pins for powerloss detection + // Two IO pins are connected on the Trigorilla Board + // On a power interruption the OUTAGECON_PIN goes low. + + #if ENABLED(POWER_LOSS_RECOVERY) + OUT_WRITE(OUTAGECON_PIN, HIGH); + #endif + + // Filament runout is handled by Marlin settings in Configuration.h + // opt_set FIL_RUNOUT_STATE HIGH // Pin state indicating that filament is NOT present. + // opt_enable FIL_RUNOUT_PULLUP + TFTSer.begin(115200); + + // wait for the TFT panel to initialise and finish the animation + delay_ms(250); + + // There are different panels for the Chiron with slightly different commands + // So we need to know what we are working with. + + // Panel type can be defined otherwise detect it automatically + if (panel_type == AC_panel_unknown) DetectPanelType(); + + // Signal Board has reset + SendtoTFTLN(AC_msg_main_board_has_reset); + + // Enable leveling and Disable end stops during print + // as Z home places nozzle above the bed so we need to allow it past the end stops + injectCommands_P(AC_cmnd_enable_leveling); + + // Startup tunes are defined in Tunes.h + PlayTune(BEEPER_PIN, TERN(AC_DEFAULT_STARTUP_TUNE, Anycubic_PowerOn, GB_PowerOn), 1); + + #if ACDEBUGLEVEL + SERIAL_ECHOLNPAIR("AC Debug Level ", ACDEBUGLEVEL); + #endif + SendtoTFTLN(AC_msg_ready); +} + +void ChironTFT::DetectPanelType() { + #if AUTO_DETECT_CHIRON_TFT + // Send a query to the TFT + SendtoTFTLN(AC_Test_for_OldPanel); // The panel will respond with 'SXY 480 320' + SendtoTFTLN(AC_Test_for_NewPanel); // the panel will respond with '[0]=0 ' to '[19]=0 ' + #endif +} + +void ChironTFT::IdleLoop() { + if (ReadTFTCommand()) { + ProcessPanelRequest(); + command_len = 0; + } + CheckHeaters(); +} + +void ChironTFT::PrinterKilled(PGM_P error,PGM_P component) { + SendtoTFTLN(AC_msg_kill_lcd); + #if ACDEBUG(AC_MARLIN) + SERIAL_ECHOLNPAIR("PrinterKilled()\nerror: ", error , "\ncomponent: ", component); + #endif +} + +void ChironTFT::MediaEvent(media_event_t event) { + #if ACDEBUG(AC_MARLIN) + SERIAL_ECHOLNPAIR("ProcessMediaStatus() ", event); + #endif + switch (event) { + case AC_media_inserted: + SendtoTFTLN(AC_msg_sd_card_inserted); + break; + + case AC_media_removed: + SendtoTFTLN(AC_msg_sd_card_removed); + break; + + case AC_media_error: + last_error = AC_error_noSD; + SendtoTFTLN(AC_msg_no_sd_card); + break; + } +} + +void ChironTFT::TimerEvent(timer_event_t event) { + #if ACDEBUG(AC_MARLIN) + SERIAL_ECHOLNPAIR("TimerEvent() ", event); + SERIAL_ECHOLNPAIR("Printer State: ", printer_state); + #endif + + switch (event) { + case AC_timer_started: { + live_Zoffset = 0.0; // reset print offset + setSoftEndstopState(false); // disable endstops to print + printer_state = AC_printer_printing; + SendtoTFTLN(AC_msg_print_from_sd_card); + } break; + + case AC_timer_paused: { + printer_state = AC_printer_paused; + pause_state = AC_paused_idle; + SendtoTFTLN(AC_msg_paused); + } break; + + case AC_timer_stopped: { + if (printer_state != AC_printer_idle) { + printer_state = AC_printer_stopping; + SendtoTFTLN(AC_msg_print_complete); + } + setSoftEndstopState(true); // enable endstops + } break; + } +} + +void ChironTFT::FilamentRunout() { + #if ACDEBUG(AC_MARLIN) + SERIAL_ECHOLNPAIR("FilamentRunout() printer_state ", printer_state); + #endif + // 1 Signal filament out + last_error = AC_error_filament_runout; + SendtoTFTLN(isPrintingFromMedia() ? AC_msg_filament_out_alert : AC_msg_filament_out_block); + PlayTune(BEEPER_PIN, FilamentOut, 1); +} + +void ChironTFT::ConfirmationRequest(const char * const msg) { + // M108 continue + #if ACDEBUG(AC_MARLIN) + SERIAL_ECHOLNPAIR("ConfirmationRequest() ", msg, " printer_state:", printer_state); + #endif + switch (printer_state) { + case AC_printer_pausing: { + if (strcmp_P(msg, MARLIN_msg_print_paused) == 0 || strcmp_P(msg, MARLIN_msg_nozzle_parked) == 0) { + SendtoTFTLN(AC_msg_paused); // enable continue button + printer_state = AC_printer_paused; + } + } break; + + case AC_printer_resuming_from_power_outage: + case AC_printer_printing: + case AC_printer_paused: { + // Heater timeout, send acknowledgement + if (strcmp_P(msg, MARLIN_msg_heater_timeout) == 0) { + pause_state = AC_paused_heater_timed_out; + SendtoTFTLN(AC_msg_paused); // enable continue button + PlayTune(BEEPER_PIN,Heater_Timedout,1); + } + // Reheat finished, send acknowledgement + else if (strcmp_P(msg, MARLIN_msg_reheat_done) == 0) { + pause_state = AC_paused_idle; + SendtoTFTLN(AC_msg_paused); // enable continue button + } + // Filament Purging, send acknowledgement enter run mode + else if (strcmp_P(msg, MARLIN_msg_filament_purging) == 0) { + pause_state = AC_paused_purging_filament; + SendtoTFTLN(AC_msg_paused); // enable continue button + } + } break; + default: + break; + } +} + +void ChironTFT::StatusChange(const char * const msg) { + #if ACDEBUG(AC_MARLIN) + SERIAL_ECHOLNPAIR("StatusChange() ", msg); + SERIAL_ECHOLNPAIR("printer_state:", printer_state); + #endif + bool msg_matched = false; + // The only way to get printer status is to parse messages + // Use the state to minimise the work we do here. + switch (printer_state) { + case AC_printer_probing: { + // If probing completes ok save the mesh and park + // Ignore the custom machine name + if (strcmp_P(msg + strlen(CUSTOM_MACHINE_NAME), MARLIN_msg_ready) == 0) { + injectCommands_P(PSTR("M500\nG27")); + SendtoTFTLN(AC_msg_probing_complete); + printer_state = AC_printer_idle; + msg_matched = true; + } + // If probing fails don't save the mesh raise the probe above the bad point + if (strcmp_P(msg, MARLIN_msg_probing_failed) == 0) { + PlayTune(BEEPER_PIN, BeepBeepBeeep, 1); + injectCommands_P(PSTR("G1 Z50 F500")); + SendtoTFTLN(AC_msg_probing_complete); + printer_state = AC_printer_idle; + msg_matched = true; + } + } break; + + case AC_printer_printing: { + if (strcmp_P(msg, MARLIN_msg_reheating) == 0) { + SendtoTFTLN(AC_msg_paused); // enable continue button + msg_matched = true; + } + } break; + + case AC_printer_pausing: { + if (strcmp_P(msg, MARLIN_msg_print_paused) == 0) { + SendtoTFTLN(AC_msg_paused); + printer_state = AC_printer_paused; + pause_state = AC_paused_idle; + msg_matched = true; + } + } break; + + case AC_printer_stopping: { + if (strcmp_P(msg, MARLIN_msg_print_aborted) == 0) { + SendtoTFTLN(AC_msg_stop); + printer_state = AC_printer_idle; + msg_matched = true; + } + } break; + default: + break; + } + + // If not matched earlier see if this was a heater message + if (!msg_matched) { + if (strcmp_P(msg, MARLIN_msg_extruder_heating) == 0) { + SendtoTFTLN(AC_msg_nozzle_heating); + hotend_state = AC_heater_temp_set; + } + else if (strcmp_P(msg, MARLIN_msg_bed_heating) == 0) { + SendtoTFTLN(AC_msg_bed_heating); + hotbed_state = AC_heater_temp_set; + } + else if (strcmp_P(msg, MARLIN_msg_EEPROM_version) == 0) { + last_error = AC_error_EEPROM; + } + } +} + +void ChironTFT::PowerLossRecovery() { + printer_state = AC_printer_resuming_from_power_outage; // Play tune to notify user we can recover. + last_error = AC_error_powerloss; + PlayTune(BEEPER_PIN, SOS, 1); + SERIAL_ECHOLNPGM_P(AC_msg_powerloss_recovery); +} + +void ChironTFT::PrintComplete() { + SendtoTFT(AC_msg_print_complete); + printer_state = AC_printer_idle; + setSoftEndstopState(true); // enable endstops +} + +void ChironTFT::SendtoTFT(PGM_P str) { // A helper to print PROGMEM string to the panel + #if ACDEBUG(AC_SOME) + SERIAL_ECHOPGM_P(str); + #endif + while (const char c = pgm_read_byte(str++)) TFTSer.write(c); +} + +void ChironTFT::SendtoTFTLN(PGM_P str = nullptr) { + if (str) { + #if ACDEBUG(AC_SOME) + SERIAL_ECHOPGM("> "); + #endif + SendtoTFT(str); + #if ACDEBUG(AC_SOME) + SERIAL_EOL(); + #endif + } + TFTSer.println(); +} + +bool ChironTFT::ReadTFTCommand() { + bool command_ready = false; + while (TFTSer.available() > 0 && command_len < MAX_CMND_LEN) { + panel_command[command_len] = TFTSer.read(); + if (panel_command[command_len] == '\n') { + command_ready = true; + break; + } + command_len++; + } + + if (command_ready || command_len == MAX_CMND_LEN) { + panel_command[command_len] = '\0'; + #if ACDEBUG(AC_ALL) + SERIAL_ECHOLNPAIR("len(",command_len,") < ", panel_command); + #endif + command_ready = true; + } + return command_ready; +} + +int8_t ChironTFT::FindToken(char c) { + int8_t pos = 0; + do { + if (panel_command[pos] == c) { + #if ACDEBUG(AC_INFO) + SERIAL_ECHOLNPAIR("Tpos:", pos, " ", c); + #endif + return pos; + } + } while(++pos < command_len); + #if ACDEBUG(AC_INFO) + SERIAL_ECHOLNPAIR("Not found: ", c); + #endif + return -1; +} + +void ChironTFT::CheckHeaters() { + uint8_t faultDuration = 0; + + // if the hotend temp is abnormal, confirm state before signalling panel + celsius_float_t temp = getActualTemp_celsius(E0); + while (!WITHIN(temp, HEATER_0_MINTEMP, HEATER_0_MAXTEMP)) { + faultDuration++; + if (faultDuration >= AC_HEATER_FAULT_VALIDATION_TIME) { + SendtoTFTLN(AC_msg_nozzle_temp_abnormal); + last_error = AC_error_abnormal_temp_t0; + SERIAL_ECHOLNPAIR("Extruder temp abnormal! : ", temp); + break; + } + delay_ms(500); + temp = getActualTemp_celsius(E0); + } + + // If the hotbed temp is abnormal, confirm state before signaling panel + faultDuration = 0; + temp = getActualTemp_celsius(BED); + while (!WITHIN(temp, BED_MINTEMP, BED_MAXTEMP)) { + faultDuration++; + if (faultDuration >= AC_HEATER_FAULT_VALIDATION_TIME) { + SendtoTFTLN(AC_msg_nozzle_temp_abnormal); + last_error = AC_error_abnormal_temp_bed; + SERIAL_ECHOLNPAIR("Bed temp abnormal! : ", temp); + break; + } + delay_ms(500); + temp = getActualTemp_celsius(E0); + } + + // Update panel with hotend heater status + if (hotend_state != AC_heater_temp_reached) { + if (WITHIN(getActualTemp_celsius(E0) - getTargetTemp_celsius(E0), -(TEMP_WINDOW), TEMP_WINDOW)) { + SendtoTFTLN(AC_msg_nozzle_heating_done); + hotend_state = AC_heater_temp_reached; + } + } + + // Update panel with bed heater status + if (hotbed_state != AC_heater_temp_reached) { + if (WITHIN(getActualTemp_celsius(BED) - getTargetTemp_celsius(BED), -(TEMP_BED_WINDOW), TEMP_BED_WINDOW)) { + SendtoTFTLN(AC_msg_bed_heating_done); + hotbed_state = AC_heater_temp_reached; + } + } +} + +void ChironTFT::SendFileList(int8_t startindex) { + // Respond to panel request for 4 files starting at index + #if ACDEBUG(AC_INFO) + SERIAL_ECHOLNPAIR("## SendFileList ## ", startindex); + #endif + SendtoTFTLN(PSTR("FN ")); + filenavigator.getFiles(startindex, panel_type, 4); + SendtoTFTLN(PSTR("END")); +} + +void ChironTFT::SelectFile() { + if (panel_type == AC_panel_new) { + strncpy(selectedfile, panel_command + 4, command_len - 3); + selectedfile[command_len - 4] = '\0'; + } + else { + strncpy(selectedfile, panel_command + 4, command_len - 4); + selectedfile[command_len - 5] = '\0'; + } + #if ACDEBUG(AC_FILE) + SERIAL_ECHOLNPAIR(" Selected File: ",selectedfile); + #endif + switch (selectedfile[0]) { + case '/': // Valid file selected + SendtoTFTLN(AC_msg_sd_file_open_success); + break; + + case '<': // .. (go up folder level) + filenavigator.upDIR(); + SendtoTFTLN(AC_msg_sd_file_open_failed); + SendFileList( 0 ); + break; + default: // enter sub folder + // for new panel remove the '.GCO' tag that was added to the end of the path + if (panel_type == AC_panel_new) + selectedfile[strlen(selectedfile) - 4] = '\0'; + filenavigator.changeDIR(selectedfile); + SendtoTFTLN(AC_msg_sd_file_open_failed); + SendFileList( 0 ); + break; + } +} + +void ChironTFT::ProcessPanelRequest() { + // Break these up into logical blocks // as its easier to navigate than one huge switch case! + int8_t tpos = FindToken('A'); + // Panel request are 'A0' - 'A36' + if (tpos != -1) { + const int8_t req = atoi(&panel_command[tpos+1]); + + // Information requests A0 - A8 and A33 + if (req <= 8 || req == 33) PanelInfo(req); + + // Simple Actions A9 - A28 + else if (req <= 28) PanelAction(req); + + // Process Initiation + else if (req <= 36) PanelProcess(req); + } + else { + #if AUTO_DETECT_CHIRON_TFT + // This may be a response to a panel type detection query + if (panel_type == AC_panel_unknown) { + tpos = FindToken('S'); // old panel will respond to 'SIZE' with 'SXY 480 320' + if (tpos != -1) { + if (panel_command[tpos+1]== 'X' && panel_command[tpos+2]=='Y') { + panel_type = AC_panel_standard; + SERIAL_ECHOLNPGM_P(AC_msg_old_panel_detected); + } + } + else { + tpos = FindToken('['); // new panel will respond to 'J200' with '[0]=0' + if (tpos != -1) { + if (panel_command[tpos+1]== '0' && panel_command[tpos+2]==']') { + panel_type = AC_panel_new; + SERIAL_ECHOLNPGM_P(AC_msg_new_panel_detected); + } + } + } + return; + } + #endif + + SendtoTFTLN(); // Ignore unknown requests + } +} + +void ChironTFT::PanelInfo(uint8_t req) { + // information requests A0-A8 and A33 + switch (req) { + case 0: // A0 Get HOTEND Temp + SendtoTFT(PSTR("A0V ")); + TFTSer.println(getActualTemp_celsius(E0)); + break; + + case 1: // A1 Get HOTEND Target Temp + SendtoTFT(PSTR("A1V ")); + TFTSer.println(getTargetTemp_celsius(E0)); + break; + + case 2: // A2 Get BED Temp + SendtoTFT(PSTR("A2V ")); + TFTSer.println(getActualTemp_celsius(BED)); + break; + + case 3: // A3 Get BED Target Temp + SendtoTFT(PSTR("A3V ")); + TFTSer.println(getTargetTemp_celsius(BED)); + break; + + case 4: // A4 Get FAN Speed + SendtoTFT(PSTR("A4V ")); + TFTSer.println(getActualFan_percent(FAN0)); + break; + + case 5: // A5 Get Current Coordinates + SendtoTFT(PSTR("A5V X: ")); + TFTSer.print(getAxisPosition_mm(X)); + SendtoTFT(PSTR(" Y: ")); + TFTSer.print(getAxisPosition_mm(Y)); + SendtoTFT(PSTR(" Z: ")); + TFTSer.println(getAxisPosition_mm(Z)); + break; + + case 6: // A6 Get printing progress + if (isPrintingFromMedia()) { + SendtoTFT(PSTR("A6V ")); + TFTSer.println(ui8tostr2(getProgress_percent())); + } + else + SendtoTFTLN(PSTR("A6V ---")); + break; + + case 7: { // A7 Get Printing Time + uint32_t time = getProgress_seconds_elapsed() / 60; + SendtoTFT(PSTR("A7V ")); + TFTSer.print(ui8tostr2(time / 60)); + SendtoTFT(PSTR(" H ")); + TFTSer.print(ui8tostr2(time % 60)); + SendtoTFT(PSTR(" M")); + #if ACDEBUG(AC_ALL) + SERIAL_ECHOLNPAIR("Print time ", ui8tostr2(time / 60), ":", ui8tostr2(time % 60)); + #endif + } break; + + case 8: // A8 Get SD Card list A8 S0 + if (!isMediaInserted()) safe_delay(500); + if (!isMediaInserted()) // Make sure the card is removed + SendtoTFTLN(AC_msg_no_sd_card); + else if (panel_command[3] == 'S') + SendFileList( atoi( &panel_command[4] ) ); + break; + + case 33: // A33 Get firmware info + SendtoTFT(PSTR("J33 ")); + // If there is an error recorded, show that instead of the FW version + if (!GetLastError()) SendtoTFTLN(PSTR(SHORT_BUILD_VERSION)); + break; + } +} + +void ChironTFT::PanelAction(uint8_t req) { + switch (req) { + case 9: // A9 Pause SD print + if (isPrintingFromMedia()) { + SendtoTFTLN(AC_msg_pause); + pausePrint(); + printer_state = AC_printer_pausing; + } + else + SendtoTFTLN(AC_msg_stop); + break; + + case 10: // A10 Resume SD Print + if (pause_state == AC_paused_idle || printer_state == AC_printer_resuming_from_power_outage) + resumePrint(); + else + setUserConfirmed(); + break; + + case 11: // A11 Stop SD print + if (isPrintingFromMedia()) { + printer_state = AC_printer_stopping; + stopPrint(); + } + else { + if (printer_state == AC_printer_resuming_from_power_outage) + injectCommands_P(PSTR("M1000 C")); // Cancel recovery + SendtoTFTLN(AC_msg_stop); + printer_state = AC_printer_idle; + } + break; + + case 12: // A12 Kill printer + kill(); // from marlincore.h + break; + + case 13: // A13 Select file + SelectFile(); + break; + + case 14: { // A14 Start Printing + // Allows printer to restart the job if we don't want to recover + if (printer_state == AC_printer_resuming_from_power_outage) { + injectCommands_P(PSTR("M1000 C")); // Cancel recovery + printer_state = AC_printer_idle; + } + #if ACDebugLevel >= 1 + SERIAL_ECHOLNPAIR_F("Print: ", selectedfile); + #endif + printFile(selectedfile); + SendtoTFTLN(AC_msg_print_from_sd_card); + } break; + + case 15: // A15 Resuming from outage + if (printer_state == AC_printer_resuming_from_power_outage) { + // Need to home here to restore the Z position + injectCommands_P(AC_cmnd_power_loss_recovery); + injectCommands_P(PSTR("M1000")); // home and start recovery + } + break; + + case 16: { // A16 Set HotEnd temp A17 S170 + const float set_Htemp = atof(&panel_command[5]); + hotend_state = set_Htemp ? AC_heater_temp_set : AC_heater_off; + switch ((char)panel_command[4]) { + // Set Temp + case 'S': case 'C': setTargetTemp_celsius(set_Htemp, E0); + } + } break; + + case 17: { // A17 Set bed temp + const float set_Btemp = atof(&panel_command[5]); + hotbed_state = set_Btemp ? AC_heater_temp_set : AC_heater_off; + if (panel_command[4] == 'S') + setTargetTemp_celsius(set_Btemp, BED); + } break; + + case 18: // A18 Set Fan Speed + if (panel_command[4] == 'S') + setTargetFan_percent(atof(&panel_command[5]), FAN0); + break; + + case 19: // A19 Motors off + if (!isPrinting()) { + disable_all_steppers(); // from marlincore.h + SendtoTFTLN(AC_msg_ready); + } + break; + + case 20: // A20 Read/write print speed + if (panel_command[4] == 'S') + setFeedrate_percent(atoi(&panel_command[5])); + else { + SendtoTFT(PSTR("A20V ")); + TFTSer.println(getFeedrate_percent()); + } + break; + + case 21: // A21 Home Axis A21 X + if (!isPrinting()) { + switch ((char)panel_command[4]) { + case 'X': injectCommands_P(PSTR("G28X")); break; + case 'Y': injectCommands_P(PSTR("G28Y")); break; + case 'Z': injectCommands_P(PSTR("G28Z")); break; + case 'C': injectCommands_P(G28_STR); break; + } + } + break; + + case 22: { // A22 Move Axis + // The commands have changed on the new panel + // Old TFT A22 X -1F1500 A22 X +1F1500 + // New TFT A22 X-1.0 F1500 A22 X1.0 F1500 + + // lets just wrap this in a gcode relative nonprint move and let the controller deal with it + // G91 G0 G90 + + if (!isPrinting()) { // Ignore request if printing + char MoveCmnd[30]; + sprintf_P(MoveCmnd, PSTR("G91\nG0%s\nG90"), panel_command + 3); + #if ACDEBUG(AC_ACTION) + SERIAL_ECHOLNPAIR("Move: ", MoveCmnd); + #endif + setSoftEndstopState(true); // enable endstops + injectCommands(MoveCmnd); + } + } break; + + case 23: // A23 Preheat PLA + // Ignore request if printing + if (!isPrinting()) { + // Temps defined in configuration.h + setTargetTemp_celsius(PREHEAT_1_TEMP_BED, BED); + setTargetTemp_celsius(PREHEAT_1_TEMP_HOTEND, E0); + SendtoTFTLN(); + hotbed_state = AC_heater_temp_set; + hotend_state = AC_heater_temp_set; + } + break; + + case 24: // A24 Preheat ABS + // Ignore request if printing + if (!isPrinting()) { + setTargetTemp_celsius(PREHEAT_2_TEMP_BED, BED); + setTargetTemp_celsius(PREHEAT_2_TEMP_HOTEND, E0); + SendtoTFTLN(); + hotbed_state = AC_heater_temp_set; + hotend_state = AC_heater_temp_set; + } + break; + + case 25: // A25 Cool Down + // Ignore request if printing + if (!isPrinting()) { + setTargetTemp_celsius(0, E0); + setTargetTemp_celsius(0, BED); + SendtoTFTLN(AC_msg_ready); + hotbed_state = AC_heater_off; + hotend_state = AC_heater_off; + } + break; + + case 26: // A26 Refresh SD + if (card.isMounted())card.release(); + card.mount(); + safe_delay(500); + filenavigator.reset(); + break; + + case 27: // A27 Servo Angles adjust + break; + + case 28: // A28 Filament set A28 O/C + // Ignore request if printing + if (isPrinting()) break; + SendtoTFTLN(); + break; + } +} + +void ChironTFT::PanelProcess(uint8_t req) { + switch (req) { + case 29: { // A29 Read Mesh Point A29 X1 Y1 + xy_uint8_t pos; + float pos_z; + pos.x = atoi(&panel_command[FindToken('X')+1]); + pos.y = atoi(&panel_command[FindToken('Y')+1]); + pos_z = getMeshPoint(pos); + + SendtoTFT(PSTR("A29V ")); + TFTSer.println(pos_z * 100); + if (!isPrinting()) { + setSoftEndstopState(true); // disable endstops + // If the same meshpoint is selected twice in a row, move the head to that ready for adjustment + if ((selectedmeshpoint.x == pos.x) && (selectedmeshpoint.y == pos.y)) { + if (!isPositionKnown()) + injectCommands_P(G28_STR); // home + + if (isPositionKnown()) { + #if ACDEBUG(AC_INFO) + SERIAL_ECHOLNPAIR("Moving to mesh point at x: ", pos.x, " y: ", pos.y, " z: ", pos_z); + #endif + // Go up before moving + setAxisPosition_mm(3.0,Z); + + setAxisPosition_mm(17 + (93 * pos.x), X); + setAxisPosition_mm(20 + (93 * pos.y), Y); + setAxisPosition_mm(0.0, Z); + #if ACDEBUG(AC_INFO) + SERIAL_ECHOLNPAIR("Current Z: ", getAxisPosition_mm(Z)); + #endif + } + } + selectedmeshpoint.x = pos.x; + selectedmeshpoint.y = pos.y; + } + } break; + + case 30: { // A30 Auto leveling + if (FindToken('S') != -1) { // Start probing New panel adds spaces.. + // Ignore request if printing + if (isPrinting()) + SendtoTFTLN(AC_msg_probing_not_allowed); // forbid auto leveling + else { + + + SendtoTFTLN(AC_msg_start_probing); + injectCommands_P(PSTR("G28\nG29")); + printer_state = AC_printer_probing; + } + } + else { + SendtoTFTLN(AC_msg_start_probing); // Just enter levelling menu + } + } break; + + case 31: { // A31 Adjust all Probe Points + // The tokens can occur in different places on the new panel so we need to find it. + + if (FindToken('C') != -1) { // Restore and apply original offsets + if (!isPrinting()) { + injectCommands_P(PSTR("M501\nM420 S1")); + selectedmeshpoint.x = selectedmeshpoint.y = 99; + SERIAL_ECHOLNPGM_P(AC_msg_mesh_changes_abandoned); + } + } + + else if (FindToken('D') != -1) { // Save Z Offset tables and restore leveling state + if (!isPrinting()) { + setAxisPosition_mm(1.0,Z); // Lift nozzle before any further movements are made + injectCommands_P(PSTR("M500")); + SERIAL_ECHOLNPGM_P(AC_msg_mesh_changes_saved); + selectedmeshpoint.x = selectedmeshpoint.y = 99; + } + } + + else if (FindToken('G') != -1) { // Get current offset + SendtoTFT(PSTR("A31V ")); + // When printing use the live z Offset position + // we will use babystepping to move the print head + if (isPrinting()) + TFTSer.println(live_Zoffset); + else { + TFTSer.println(getZOffset_mm()); + selectedmeshpoint.x = selectedmeshpoint.y = 99; + } + } + + else { + int8_t tokenpos = FindToken('S'); + if (tokenpos != -1) { // Set offset (adjusts all points by value) + float Zshift = atof(&panel_command[tokenpos+1]); + setSoftEndstopState(false); // disable endstops + // Allow temporary Z position nudging during print + // From the leveling panel use the all points UI to adjust the print pos. + if (isPrinting()) { + #if ACDEBUG(AC_INFO) + SERIAL_ECHOLNPAIR("Change Zoffset from:", live_Zoffset, " to ", live_Zoffset + Zshift); + #endif + if (isAxisPositionKnown(Z)) { + #if ACDEBUG(AC_INFO) + const float currZpos = getAxisPosition_mm(Z); + SERIAL_ECHOLNPAIR("Nudge Z pos from ", currZpos, " to ", currZpos + constrain(Zshift, -0.05, 0.05)); + #endif + // Use babystepping to adjust the head position + int16_t steps = mmToWholeSteps(constrain(Zshift,-0.05,0.05), Z); + #if ACDEBUG(AC_INFO) + SERIAL_ECHOLNPAIR("Steps to move Z: ", steps); + #endif + babystepAxis_steps(steps, Z); + live_Zoffset += Zshift; + } + SendtoTFT(PSTR("A31V ")); + TFTSer.println(live_Zoffset); + } + else { + GRID_LOOP(x, y) { + const xy_uint8_t pos { x, y }; + const float currval = getMeshPoint(pos); + setMeshPoint(pos, constrain(currval + Zshift, AC_LOWEST_MESHPOINT_VAL, 2)); + #if ACDEBUG(AC_INFO) + SERIAL_ECHOLNPAIR("Change mesh point X", x," Y",y ," from ", currval, " to ", getMeshPoint(pos) ); + #endif + } + const float currZOffset = getZOffset_mm(); + #if ACDEBUG(AC_INFO) + SERIAL_ECHOLNPAIR("Change probe offset from ", currZOffset, " to ", currZOffset + Zshift); + #endif + + setZOffset_mm(currZOffset + Zshift); + SendtoTFT(PSTR("A31V ")); + TFTSer.println(getZOffset_mm()); + + if (isAxisPositionKnown(Z)) { + // Move Z axis + const float currZpos = getAxisPosition_mm(Z); + #if ACDEBUG(AC_INFO) + SERIAL_ECHOLNPAIR("Move Z pos from ", currZpos, " to ", currZpos + constrain(Zshift, -0.05, 0.05)); + #endif + setAxisPosition_mm(currZpos+constrain(Zshift,-0.05,0.05),Z); + } + } + } + } + } break; + + case 32: { // A32 clean leveling beep flag + // Ignore request if printing + //if (isPrinting()) break; + //injectCommands_P(PSTR("M500\nM420 S1\nG1 Z10 F240\nG1 X0 Y0 F6000")); + //TFTSer.println(); + } break; + + // A33 firmware info request see PanelInfo() + + case 34: { // A34 Adjust single mesh point A34 C/S X1 Y1 V123 + if (panel_command[3] == 'C') { // Restore original offsets + injectCommands_P(PSTR("M501\nM420 S1")); + selectedmeshpoint.x = selectedmeshpoint.y = 99; + //printer_state = AC_printer_idle; + } + else { + xy_uint8_t pos; + pos.x = atoi(&panel_command[5]); + pos.y = atoi(&panel_command[8]); + + float currmesh = getMeshPoint(pos); + float newval = atof(&panel_command[11])/100; + #if ACDEBUG(AC_INFO) + SERIAL_ECHOLNPAIR("Change mesh point x:", pos.x, " y:", pos.y); + SERIAL_ECHOLNPAIR("from ", currmesh, " to ", newval); + #endif + // Update Meshpoint + setMeshPoint(pos,newval); + if (printer_state == AC_printer_idle || printer_state == AC_printer_probing /*!isPrinting()*/) { + // if we are at the current mesh point indicated on the panel Move Z pos +/- 0.05mm + // (The panel changes the mesh value by +/- 0.05mm on each button press) + if (selectedmeshpoint.x == pos.x && selectedmeshpoint.y == pos.y) { + setSoftEndstopState(false); + float currZpos = getAxisPosition_mm(Z); + #if ACDEBUG(AC_INFO) + SERIAL_ECHOLNPAIR("Move Z pos from ", currZpos, " to ", currZpos + constrain(newval - currmesh, -0.05, 0.05)); + #endif + setAxisPosition_mm(currZpos + constrain(newval - currmesh, -0.05, 0.05), Z); + } + } + } + } break; + + case 36: // A36 Auto leveling for new TFT bet that was a typo in the panel code! + SendtoTFTLN(AC_msg_start_probing); + break; + } +} + +bool ChironTFT::GetLastError() { + switch (last_error) { + case AC_error_abnormal_temp_bed: SendtoTFTLN(AC_msg_error_bed_temp); break; + case AC_error_abnormal_temp_t0: SendtoTFTLN(AC_msg_error_hotend_temp); break; + case AC_error_noSD: SendtoTFTLN(AC_msg_error_sd_card); break; + case AC_error_powerloss: SendtoTFTLN(AC_msg_power_loss); break; + case AC_error_EEPROM: SendtoTFTLN(AC_msg_eeprom_version); break; + case AC_error_filament_runout: SendtoTFTLN(AC_msg_filament_out); break; + default: return false; + } + last_error = AC_error_none; + return true; +} + +} // Anycubic namespace + +#endif // ANYCUBIC_LCD_CHIRON diff --git a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.h b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.h new file mode 100644 index 000000000000..7eb0049993f7 --- /dev/null +++ b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.h @@ -0,0 +1,89 @@ +/** + * 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 + +/** + * lcd/extui/anycubic_chiron/chiron_tft.h + * + * Extensible_UI implementation for Anycubic Chiron + * Written By Nick Wells, 2020 [https://github.com/SwiftNick] + * (not affiliated with Anycubic, Ltd.) + */ + +#include "chiron_tft_defs.h" +#include "../../../inc/MarlinConfigPre.h" +#include "../ui_api.h" + +#if NONE(CHIRON_TFT_STANDARD, CHIRON_TFT_NEW) + #define AUTO_DETECT_CHIRON_TFT 1 +#endif + +namespace Anycubic { + +class ChironTFT { + #if AUTO_DETECT_CHIRON_TFT + static panel_type_t panel_type; + #else + static constexpr panel_type_t panel_type = TERN(CHIRON_TFT_NEW, AC_panel_new, AC_panel_standard); + #endif + static last_error_t last_error; + static printer_state_t printer_state; + static paused_state_t pause_state; + static heater_state_t hotend_state; + static heater_state_t hotbed_state; + static xy_uint8_t selectedmeshpoint; + static char panel_command[MAX_CMND_LEN + 1]; + static uint8_t command_len; + static char selectedfile[MAX_PATH_LEN + 1]; + static float live_Zoffset; + static file_menu_t file_menu; + public: + static void Startup(); + static void IdleLoop(); + static void PrinterKilled(PGM_P,PGM_P); + static void MediaEvent(media_event_t); + static void TimerEvent(timer_event_t); + static void FilamentRunout(); + static void ConfirmationRequest(const char * const ); + static void StatusChange(const char * const ); + static void PowerLossRecovery(); + static void PrintComplete(); + static void SendtoTFT(PGM_P); + static void SendtoTFTLN(PGM_P); + private: + static void DetectPanelType(); + static bool ReadTFTCommand(); + static int8_t FindToken(char); + static void CheckHeaters(); + static void SendFileList(int8_t); + static void SelectFile(); + static void InjectCommandandWait(PGM_P); + static void ProcessPanelRequest(); + static void PanelInfo(uint8_t); + static void PanelAction(uint8_t); + static void PanelProcess(uint8_t); + static bool GetLastError(); +}; + +extern ChironTFT Chiron; + +} // Anycubic namespace diff --git a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft_defs.h b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft_defs.h new file mode 100644 index 000000000000..70ac1490dfa5 --- /dev/null +++ b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft_defs.h @@ -0,0 +1,178 @@ +/** + * 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 . + * + */ + +/** + * lcd/extui/anycubic_chiron/chiron_defs.h + * + * Extensible_UI implementation for Anycubic Chiron + * Written By Nick Wells, 2020 [https://github.com/SwiftNick] + * (not affiliated with Anycubic, Ltd.) + */ + +#pragma once +#include "../../../inc/MarlinConfigPre.h" +//#define ACDEBUGLEVEL 4 + +#if ACDEBUGLEVEL + // Bit-masks for selective debug: + enum ACDebugMask : uint8_t { + AC_INFO = 1, + AC_ACTION = 2, + AC_FILE = 4, + AC_PANEL = 8, + AC_MARLIN = 16, + AC_SOME = 32, + AC_ALL = 64 + }; + #define ACDEBUG(mask) ( ((mask) & ACDEBUGLEVEL) == mask ) // Debug flag macro +#else + #define ACDEBUG(mask) false +#endif + +#define TFTSer LCD_SERIAL // Serial interface for TFT panel now uses marlinserial +#define MAX_FOLDER_DEPTH 4 // Limit folder depth TFT has a limit for the file path +#define MAX_CMND_LEN 16 * MAX_FOLDER_DEPTH // Maximum Length for a Panel command +#define MAX_PATH_LEN 16 * MAX_FOLDER_DEPTH // Maximum number of characters in a SD file path + +#define AC_HEATER_FAULT_VALIDATION_TIME 5 // number of 1/2 second loops before signalling a heater fault +#define AC_LOWEST_MESHPOINT_VAL -10 // The lowest value you can set for a single mesh point offset + + // TFT panel commands +#define AC_msg_sd_card_inserted PSTR("J00") +#define AC_msg_sd_card_removed PSTR("J01") +#define AC_msg_no_sd_card PSTR("J02") +#define AC_msg_usb_connected PSTR("J03") +#define AC_msg_print_from_sd_card PSTR("J04") +#define AC_msg_pause PSTR("J05") +#define AC_msg_nozzle_heating PSTR("J06") +#define AC_msg_nozzle_heating_done PSTR("J07") +#define AC_msg_bed_heating PSTR("J08") +#define AC_msg_bed_heating_done PSTR("J09") +#define AC_msg_nozzle_temp_abnormal PSTR("J10") +#define AC_msg_kill_lcd PSTR("J11") +#define AC_msg_ready PSTR("J12") +#define AC_msg_low_nozzle_temp PSTR("J13") +#define AC_msg_print_complete PSTR("J14") +#define AC_msg_filament_out_alert PSTR("J15") +#define AC_msg_stop PSTR("J16") +#define AC_msg_main_board_has_reset PSTR("J17") +#define AC_msg_paused PSTR("J18") +#define AC_msg_j19_unknown PSTR("J19") +#define AC_msg_sd_file_open_success PSTR("J20") +#define AC_msg_sd_file_open_failed PSTR("J21") +#define AC_msg_level_monitor_finished PSTR("J22") +#define AC_msg_filament_out_block PSTR("J23") +#define AC_msg_probing_not_allowed PSTR("J24") +#define AC_msg_probing_complete PSTR("J25") +#define AC_msg_start_probing PSTR("J26") +#define AC_msg_version PSTR("J27") +#define AC_msg_mesh_changes_abandoned PSTR("Mesh changes abandoned, previous mesh restored.") +#define AC_msg_mesh_changes_saved PSTR("Mesh changes saved.") +#define AC_msg_old_panel_detected PSTR("Standard TFT panel detected!") +#define AC_msg_new_panel_detected PSTR("New TFT panel detected!") +#define AC_msg_powerloss_recovery PSTR("Resuming from power outage! select the same SD file then press resume") +// Error messages must not contain spaces +#define AC_msg_error_bed_temp PSTR("Abnormal_bed_temp") +#define AC_msg_error_hotend_temp PSTR("Abnormal_hotend_temp") +#define AC_msg_error_sd_card PSTR("SD_card_error") +#define AC_msg_filament_out PSTR("Filament_runout") +#define AC_msg_power_loss PSTR("Power_failure") +#define AC_msg_eeprom_version PSTR("EEPROM_ver_wrong") + +#define MARLIN_msg_start_probing PSTR("Probing Point 1/25") +#define MARLIN_msg_probing_failed PSTR("Probing Failed") +#define MARLIN_msg_ready PSTR(" Ready.") +#define MARLIN_msg_print_paused PSTR("Print Paused") +#define MARLIN_msg_print_aborted PSTR("Print Aborted") +#define MARLIN_msg_extruder_heating PSTR("E Heating...") +#define MARLIN_msg_bed_heating PSTR("Bed Heating...") +#define MARLIN_msg_EEPROM_version PSTR("EEPROM Version Error") +#define MARLIN_msg_nozzle_parked PSTR("Nozzle Parked") +#define MARLIN_msg_heater_timeout PSTR("Heater Timeout") +#define MARLIN_msg_reheating PSTR("Reheating...") +#define MARLIN_msg_reheat_done PSTR("Reheat finished.") +#define MARLIN_msg_filament_purging PSTR("Filament Purging...") +#define MARLIN_msg_special_pause PSTR("PB") + +#define AC_cmnd_auto_unload_filament PSTR("M701") // Use Marlin unload routine +#define AC_cmnd_auto_load_filament PSTR("M702 M0 PB") // Use Marlin load routing then pause for user to clean nozzle + +#define AC_cmnd_manual_load_filament PSTR("M83\nG1 E50 F700\nM82") // replace the manual panel commands with something a little faster +#define AC_cmnd_manual_unload_filament PSTR("M83\nG1 E-50 F1200\nM82") +#define AC_cmnd_enable_leveling PSTR("M420SV") +#define AC_cmnd_power_loss_recovery PSTR("G28XYR5\nG28Z") // Lift, home X and Y then home Z when in 'safe' position + +#define AC_Test_for_OldPanel PSTR("SIZE") // An old panel will respond with 'SXY 480 320' a new panel wont respond. +#define AC_Test_for_NewPanel PSTR("J200") // A new panel will respond with '[0]=0 [1]=0' to '[19]=0 ' an old panel wont respond + +namespace Anycubic { + enum heater_state_t : uint8_t { + AC_heater_off, + AC_heater_temp_set, + AC_heater_temp_reached + }; + enum paused_state_t : uint8_t { + AC_paused_heater_timed_out, + AC_paused_purging_filament, + AC_paused_idle + }; + enum printer_state_t : uint8_t { + AC_printer_booting, + AC_printer_idle, + AC_printer_probing, + AC_printer_printing, + AC_printer_pausing, + AC_printer_paused, + AC_printer_stopping, + AC_printer_resuming_from_power_outage + }; + enum timer_event_t : uint8_t { + AC_timer_started, + AC_timer_paused, + AC_timer_stopped + }; + enum media_event_t : uint8_t { + AC_media_inserted, + AC_media_removed, + AC_media_error + }; + enum file_menu_t : uint8_t { + AC_menu_file, + AC_menu_command, + AC_menu_change_to_file, + AC_menu_change_to_command + }; + enum panel_type_t : uint8_t { + AC_panel_unknown, + AC_panel_standard, + AC_panel_new + }; + enum last_error_t : uint8_t { + AC_error_none, + AC_error_abnormal_temp_t0, + AC_error_abnormal_temp_bed, + AC_error_noSD, + AC_error_powerloss, + AC_error_filament_runout, + AC_error_EEPROM + }; +} // Anycubic namespace diff --git a/Marlin/src/lcd/extui/anycubic_chiron_lcd.cpp b/Marlin/src/lcd/extui/anycubic_chiron_lcd.cpp deleted file mode 100644 index a7f9a7a0c3e3..000000000000 --- a/Marlin/src/lcd/extui/anycubic_chiron_lcd.cpp +++ /dev/null @@ -1,121 +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 . - * - */ - -/** - * lcd/extui/anycubic_chiron_lcd.cpp - * - * Anycubic Chiron TFT support for Marlin - */ - -#include "../../inc/MarlinConfigPre.h" - -#if ENABLED(ANYCUBIC_LCD_CHIRON) - -#include "ui_api.h" -#include "lib/anycubic_chiron/chiron_tft.h" - -using namespace Anycubic; - -namespace ExtUI { - - void onStartup() { Chiron.Startup(); } - - void onIdle() { Chiron.IdleLoop(); } - - void onPrinterKilled(PGM_P const error, PGM_P const component) { - Chiron.PrinterKilled(error,component); - } - - void onMediaInserted() { Chiron.MediaEvent(AC_media_inserted); } - void onMediaError() { Chiron.MediaEvent(AC_media_error); } - void onMediaRemoved() { Chiron.MediaEvent(AC_media_removed); } - - void onPlayTone(const uint16_t frequency, const uint16_t duration) { - #if ENABLED(SPEAKER) - ::tone(BEEPER_PIN, frequency, duration); - #endif - } - - void onPrintTimerStarted() { Chiron.TimerEvent(AC_timer_started); } - void onPrintTimerPaused() { Chiron.TimerEvent(AC_timer_paused); } - void onPrintTimerStopped() { Chiron.TimerEvent(AC_timer_stopped); } - void onFilamentRunout(const extruder_t) { Chiron.FilamentRunout(); } - void onUserConfirmRequired(const char * const msg) { Chiron.ConfirmationRequest(msg); } - void onStatusChanged(const char * const msg) { Chiron.StatusChange(msg); } - - void onFactoryReset() {} - - void onStoreSettings(char *buff) { - // Called when saving to EEPROM (i.e. M500). If the ExtUI needs - // permanent data to be stored, it can write up to eeprom_data_size bytes - // into buff. - - // Example: - // static_assert(sizeof(myDataStruct) <= ExtUI::eeprom_data_size); - // memcpy(buff, &myDataStruct, sizeof(myDataStruct)); - } - - void onLoadSettings(const char *buff) { - // Called while loading settings from EEPROM. If the ExtUI - // needs to retrieve data, it should copy up to eeprom_data_size bytes - // from buff - - // Example: - // static_assert(sizeof(myDataStruct) <= ExtUI::eeprom_data_size); - // memcpy(&myDataStruct, buff, sizeof(myDataStruct)); - } - - void onConfigurationStoreWritten(bool success) { - // Called after the entire EEPROM has been written, - // whether successful or not. - } - - void onConfigurationStoreRead(bool success) { - // Called after the entire EEPROM has been read, - // whether successful or not. - } - - #if HAS_MESH - void onMeshUpdate(const int8_t xpos, const int8_t ypos, const float zval) { - // Called when any mesh points are updated - //SERIAL_ECHOLNPAIR("onMeshUpdate() x:", xpos, " y:", ypos, " z:", zval); - } - - void onMeshUpdate(const int8_t xpos, const int8_t ypos, const ExtUI::probe_state_t state) { - // Called to indicate a special condition - //SERIAL_ECHOLNPAIR("onMeshUpdate() x:", xpos, " y:", ypos, " state:", state); - } - #endif - - #if ENABLED(POWER_LOSS_RECOVERY) - // Called on resume from power-loss - void onPowerLossResume() { Chiron.PowerLossRecovery(); } - #endif - - #if HAS_PID_HEATING - void onPidTuning(const result_t rst) { - // Called for temperature PID tuning result - } - #endif -} - -#endif // ANYCUBIC_LCD_CHIRON diff --git a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_extui.cpp b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_extui.cpp new file mode 100644 index 000000000000..33e7e84a819f --- /dev/null +++ b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_extui.cpp @@ -0,0 +1,125 @@ +/** + * 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 . + * + */ + +/** + * lcd/extui/anycubic_i3mega/anycubic_extui.cpp + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if ENABLED(ANYCUBIC_LCD_I3MEGA) + +#include "anycubic_i3mega_lcd.h" +#include "../ui_api.h" + +#include // for the ::tone() call + +namespace ExtUI { + + void onStartup() { AnycubicTFT.OnSetup(); } + void onIdle() { AnycubicTFT.OnCommandScan(); } + void onPrinterKilled(PGM_P const error, PGM_P const component) { AnycubicTFT.OnKillTFT(); } + void onMediaInserted() { AnycubicTFT.OnSDCardStateChange(true); } + void onMediaError() { AnycubicTFT.OnSDCardError(); } + void onMediaRemoved() { AnycubicTFT.OnSDCardStateChange(false); } + void onPlayTone(const uint16_t frequency, const uint16_t duration) { + #if ENABLED(SPEAKER) + ::tone(BEEPER_PIN, frequency, duration); + #endif + } + void onPrintTimerStarted() { AnycubicTFT.OnPrintTimerStarted(); } + void onPrintTimerPaused() { AnycubicTFT.OnPrintTimerPaused(); } + void onPrintTimerStopped() { AnycubicTFT.OnPrintTimerStopped(); } + void onFilamentRunout(const extruder_t extruder) { AnycubicTFT.OnFilamentRunout(); } + void onUserConfirmRequired(const char * const msg) { AnycubicTFT.OnUserConfirmRequired(msg); } + void onStatusChanged(const char * const msg) {} + + void onHomingStart() {} + void onHomingComplete() {} + void onPrintFinished() {} + + void onFactoryReset() {} + + void onStoreSettings(char *buff) { + // Called when saving to EEPROM (i.e. M500). If the ExtUI needs + // permanent data to be stored, it can write up to eeprom_data_size bytes + // into buff. + + // Example: + // static_assert(sizeof(myDataStruct) <= eeprom_data_size); + // memcpy(buff, &myDataStruct, sizeof(myDataStruct)); + } + + void onLoadSettings(const char *buff) { + // Called while loading settings from EEPROM. If the ExtUI + // needs to retrieve data, it should copy up to eeprom_data_size bytes + // from buff + + // Example: + // static_assert(sizeof(myDataStruct) <= eeprom_data_size); + // memcpy(&myDataStruct, buff, sizeof(myDataStruct)); + } + + void onPostprocessSettings() { + // Called after loading or resetting stored settings + } + + void onConfigurationStoreWritten(bool success) { + // Called after the entire EEPROM has been written, + // whether successful or not. + } + + void onConfigurationStoreRead(bool success) { + // Called after the entire EEPROM has been read, + // whether successful or not. + } + + #if HAS_MESH + + void onMeshLevelingStart() {} + + void onMeshUpdate(const int8_t xpos, const int8_t ypos, const_float_t zval) { + // Called when any mesh points are updated + } + + void onMeshUpdate(const int8_t xpos, const int8_t ypos, probe_state_t state) { + // Called when any mesh points are updated + } + #endif + + #if ENABLED(POWER_LOSS_RECOVERY) + void onPowerLossResume() { + // Called on resume from power-loss + } + #endif + + #if HAS_PID_HEATING + void onPidTuning(const result_t rst) { + // Called for temperature PID tuning result + } + #endif + + void onSteppersDisabled() {} + void onSteppersEnabled() {} +} + +#endif // ANYCUBIC_LCD_I3MEGA diff --git a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp new file mode 100644 index 000000000000..3277ad4fb498 --- /dev/null +++ b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp @@ -0,0 +1,1025 @@ +/** + * anycubic_i3mega_lcd.cpp --- Support for Anycubic i3 Mega TFT + * Created by Christian Hopp on 09.12.17. + * Improved by David Ramiro + * Converted to ExtUI by John BouAntoun 21 June 2020 + * + * 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 "../../../inc/MarlinConfigPre.h" + +#if ENABLED(ANYCUBIC_LCD_I3MEGA) + +#include "anycubic_i3mega_lcd.h" +#include "../ui_api.h" + +#include "../../../libs/numtostr.h" +#include "../../../module/motion.h" // for quickstop_stepper, A20 read printing speed, feedrate_percentage +#include "../../../MarlinCore.h" // for disable_steppers +#include "../../../inc/MarlinConfig.h" + +// command sending macro's with debugging capability +#define SEND_PGM(x) send_P(PSTR(x)) +#define SENDLINE_PGM(x) sendLine_P(PSTR(x)) +#define SEND_PGM_VAL(x,y) (send_P(PSTR(x)), sendLine(i16tostr3rj(y))) +#define SEND(x) send(x) +#define SENDLINE(x) sendLine(x) +#if ENABLED(ANYCUBIC_LCD_DEBUG) + #define SENDLINE_DBG_PGM(x,y) (sendLine_P(PSTR(x)), SERIAL_ECHOLNPGM(y)) + #define SENDLINE_DBG_PGM_VAL(x,y,z) (sendLine_P(PSTR(x)), SERIAL_ECHOPGM(y), SERIAL_ECHOLN(z)) +#else + #define SENDLINE_DBG_PGM(x,y) sendLine_P(PSTR(x)) + #define SENDLINE_DBG_PGM_VAL(x,y,z) sendLine_P(PSTR(x)) +#endif + +AnycubicTFTClass AnycubicTFT; + +char AnycubicTFTClass::TFTcmdbuffer[TFTBUFSIZE][TFT_MAX_CMD_SIZE]; +int AnycubicTFTClass::TFTbuflen = 0, + AnycubicTFTClass::TFTbufindr = 0, + AnycubicTFTClass::TFTbufindw = 0; +char AnycubicTFTClass::serial3_char; +int AnycubicTFTClass::serial3_count = 0; +char* AnycubicTFTClass::TFTstrchr_pointer; +uint8_t AnycubicTFTClass::SpecialMenu = false; +AnycubicMediaPrintState AnycubicTFTClass::mediaPrintingState = AMPRINTSTATE_NOT_PRINTING; +AnycubicMediaPauseState AnycubicTFTClass::mediaPauseState = AMPAUSESTATE_NOT_PAUSED; + +char AnycubicTFTClass::SelectedDirectory[30]; +char AnycubicTFTClass::SelectedFile[FILENAME_LENGTH]; + +// Serial helpers +static void sendNewLine(void) { LCD_SERIAL.write('\r'); LCD_SERIAL.write('\n'); } +static void send(const char *str) { LCD_SERIAL.print(str); } +static void send_P(PGM_P str) { + while (const char c = pgm_read_byte(str++)) + LCD_SERIAL.write(c); +} +static void sendLine(const char *str) { send(str); sendNewLine(); } +static void sendLine_P(PGM_P str) { send_P(str); sendNewLine(); } + +using namespace ExtUI; + +AnycubicTFTClass::AnycubicTFTClass() {} + +void AnycubicTFTClass::OnSetup() { + #ifndef LCD_BAUDRATE + #define LCD_BAUDRATE 115200 + #endif + LCD_SERIAL.begin(LCD_BAUDRATE); + + SENDLINE_DBG_PGM("J17", "TFT Serial Debug: Main board reset... J17"); // J17 Main board reset + delay_ms(10); + + // initialise the state of the key pins running on the tft + #if ENABLED(SDSUPPORT) && PIN_EXISTS(SD_DETECT) + SET_INPUT_PULLUP(SD_DETECT_PIN); + #endif + #if ENABLED(FILAMENT_RUNOUT_SENSOR) + SET_INPUT_PULLUP(FIL_RUNOUT1_PIN); + #endif + + mediaPrintingState = AMPRINTSTATE_NOT_PRINTING; + mediaPauseState = AMPAUSESTATE_NOT_PAUSED; + + // DoSDCardStateCheck(); + SENDLINE_DBG_PGM("J12", "TFT Serial Debug: Ready... J12"); // J12 Ready + delay_ms(10); + + DoFilamentRunoutCheck(); + SelectedFile[0] = 0; + + #if ENABLED(STARTUP_CHIME) + injectCommands_P(PSTR("M300 P250 S554\nM300 P250 S554\nM300 P250 S740\nM300 P250 S554\nM300 P250 S740\nM300 P250 S554\nM300 P500 S831")); + #endif + #if ENABLED(ANYCUBIC_LCD_DEBUG) + SERIAL_ECHOLNPGM("TFT Serial Debug: Finished startup"); + #endif +} + +void AnycubicTFTClass::OnCommandScan() { + static millis_t nextStopCheck = 0; // used to slow the stopped print check down to reasonable times + const millis_t ms = millis(); + if (ELAPSED(ms, nextStopCheck)) { + nextStopCheck = ms + 1000UL; + if (mediaPrintingState == AMPRINTSTATE_STOP_REQUESTED && IsNozzleHomed()) { + #if ENABLED(ANYCUBIC_LCD_DEBUG) + SERIAL_ECHOLNPGM("TFT Serial Debug: Finished stopping print, releasing motors ..."); + #endif + mediaPrintingState = AMPRINTSTATE_NOT_PRINTING; + mediaPauseState = AMPAUSESTATE_NOT_PAUSED; + injectCommands_P(PSTR("M84\nM27")); // disable stepper motors and force report of SD status + delay_ms(200); + // tell printer to release resources of print to indicate it is done + SENDLINE_DBG_PGM("J14", "TFT Serial Debug: SD Print Stopped... J14"); + } + } + + if (TFTbuflen < (TFTBUFSIZE - 1)) + GetCommandFromTFT(); + + if (TFTbuflen) { + TFTbuflen = (TFTbuflen - 1); + TFTbufindr = (TFTbufindr + 1) % TFTBUFSIZE; + } +} + +void AnycubicTFTClass::OnKillTFT() { + SENDLINE_DBG_PGM("J11", "TFT Serial Debug: Kill command... J11"); +} + +void AnycubicTFTClass::OnSDCardStateChange(bool isInserted) { + #if ENABLED(ANYCUBIC_LCD_DEBUG) + SERIAL_ECHOLNPAIR("TFT Serial Debug: OnSDCardStateChange event triggered...", isInserted); + #endif + DoSDCardStateCheck(); +} + +void AnycubicTFTClass::OnSDCardError() { + #if ENABLED(ANYCUBIC_LCD_DEBUG) + SERIAL_ECHOLNPGM("TFT Serial Debug: OnSDCardError event triggered..."); + #endif + SENDLINE_DBG_PGM("J21", "TFT Serial Debug: On SD Card Error ... J21"); +} + +void AnycubicTFTClass::OnFilamentRunout() { + #if ENABLED(ANYCUBIC_LCD_DEBUG) + SERIAL_ECHOLNPGM("TFT Serial Debug: FilamentRunout triggered..."); + #endif + DoFilamentRunoutCheck(); +} + +void AnycubicTFTClass::OnUserConfirmRequired(const char * const msg) { + #if ENABLED(ANYCUBIC_LCD_DEBUG) + SERIAL_ECHOLNPAIR("TFT Serial Debug: OnUserConfirmRequired triggered... ", msg); + #endif + + #if ENABLED(SDSUPPORT) + /** + * Need to handle the process of following states + * "Nozzle Parked" + * "Load Filament" + * "Filament Purging..." + * "HeaterTimeout" + * "Reheat finished." + * + * NOTE: The only way to handle these states is strcmp_P with the msg unfortunately (very expensive) + */ + if (strcmp_P(msg, PSTR("Nozzle Parked")) == 0) { + mediaPrintingState = AMPRINTSTATE_PAUSED; + mediaPauseState = AMPAUSESTATE_PARKED; + // enable continue button + SENDLINE_DBG_PGM("J18", "TFT Serial Debug: UserConfirm SD print paused done... J18"); + } + else if (strcmp_P(msg, PSTR("Load Filament")) == 0) { + mediaPrintingState = AMPRINTSTATE_PAUSED; + mediaPauseState = AMPAUSESTATE_FILAMENT_OUT; + // enable continue button + SENDLINE_DBG_PGM("J18", "TFT Serial Debug: UserConfirm Filament is out... J18"); + SENDLINE_DBG_PGM("J23", "TFT Serial Debug: UserConfirm Blocking filament prompt... J23"); + } + else if (strcmp_P(msg, PSTR("Filament Purging...")) == 0) { + mediaPrintingState = AMPRINTSTATE_PAUSED; + mediaPauseState = AMPAUSESTATE_PARKING; + // TODO: JBA I don't think J05 just disables the continue button, i think it injects a rogue M25. So taking this out + // disable continue button + // SENDLINE_DBG_PGM("J05", "TFT Serial Debug: UserConfirm SD Filament Purging... J05"); // J05 printing pause + + // enable continue button + SENDLINE_DBG_PGM("J18", "TFT Serial Debug: UserConfirm Filament is purging... J18"); + } + else if (strcmp_P(msg, PSTR("HeaterTimeout")) == 0) { + mediaPrintingState = AMPRINTSTATE_PAUSED; + mediaPauseState = AMPAUSESTATE_HEATER_TIMEOUT; + // enable continue button + SENDLINE_DBG_PGM("J18", "TFT Serial Debug: UserConfirm SD Heater timeout... J18"); + } + else if (strcmp_P(msg, PSTR("Reheat finished.")) == 0) { + mediaPrintingState = AMPRINTSTATE_PAUSED; + mediaPauseState = AMPAUSESTATE_REHEAT_FINISHED; + // enable continue button + SENDLINE_DBG_PGM("J18", "TFT Serial Debug: UserConfirm SD Reheat done... J18"); + } + #endif +} + +float AnycubicTFTClass::CodeValue() { + return (strtod(&TFTcmdbuffer[TFTbufindr][TFTstrchr_pointer - TFTcmdbuffer[TFTbufindr] + 1], nullptr)); +} + +bool AnycubicTFTClass::CodeSeen(char code) { + TFTstrchr_pointer = strchr(TFTcmdbuffer[TFTbufindr], code); + return !!TFTstrchr_pointer; // Return True if a character was found +} + +bool AnycubicTFTClass::IsNozzleHomed() { + const float xPosition = getAxisPosition_mm((axis_t) X); + const float yPosition = getAxisPosition_mm((axis_t) Y); + return WITHIN(xPosition, X_MIN_POS - 0.1, X_MIN_POS + 0.1) && + WITHIN(yPosition, Y_MIN_POS - 0.1, Y_MIN_POS + 0.1); +} + +void AnycubicTFTClass::HandleSpecialMenu() { + /** + * NOTE: that the file selection command actual lowercases the entire selected file/foldername, so charracter comparisons need to be lowercase. + */ + if (SelectedDirectory[0] == '<') { + switch (SelectedDirectory[1]) { + case 'e': // "" + SpecialMenu = false; + return; + break; + + #if ENABLED(PROBE_MANUALLY) + case '0': + switch (SelectedDirectory[2]) { + case '1': // "<01ZUp0.1>" + SERIAL_ECHOLNPGM("Special Menu: Z Up 0.1"); + injectCommands_P(PSTR("G91\nG1 Z+0.1\nG90")); + break; + + case '2': // "<02ZUp0.02>" + SERIAL_ECHOLNPGM("Special Menu: Z Up 0.02"); + injectCommands_P(PSTR("G91\nG1 Z+0.02\nG90")); + break; + + case '3': // "<03ZDn0.02>" + SERIAL_ECHOLNPGM("Special Menu: Z Down 0.02"); + injectCommands_P(PSTR("G91\nG1 Z-0.02\nG90")); + break; + + case '4': // "<04ZDn0.1>" + SERIAL_ECHOLNPGM("Special Menu: Z Down 0.1"); + injectCommands_P(PSTR("G91\nG1 Z-0.1\nG90")); + break; + + case '5': // "<05PrehtBed>" + SERIAL_ECHOLNPGM("Special Menu: Preheat Bed"); + injectCommands_P(PSTR("M140 S65")); + break; + + case '6': // "<06SMeshLvl>" + SERIAL_ECHOLNPGM("Special Menu: Start Mesh Leveling"); + injectCommands_P(PSTR("G29S1")); + break; + + case '7': // "<07MeshNPnt>" + SERIAL_ECHOLNPGM("Special Menu: Next Mesh Point"); + injectCommands_P(PSTR("G29S2")); + break; + + case '8': // "<08HtEndPID>" + SERIAL_ECHOLNPGM("Special Menu: Auto Tune Hotend PID"); + // need to dwell for half a second to give the fan a chance to start before the pid tuning starts + injectCommands_P(PSTR("M106 S204\nG4 P500\nM303 E0 S215 C15 U1")); + break; + + case '9': // "<09HtBedPID>" + SERIAL_ECHOLNPGM("Special Menu: Auto Tune Hotbed Pid"); + injectCommands_P(PSTR("M303 E-1 S65 C6 U1")); + break; + + default: + break; + } + break; + + case '1': + switch (SelectedDirectory[2]) { + case '0': // "<10FWDeflts>" + SERIAL_ECHOLNPGM("Special Menu: Load FW Defaults"); + injectCommands_P(PSTR("M502\nM300 P105 S1661\nM300 P210 S1108")); + break; + + case '1': // "<11SvEEPROM>" + SERIAL_ECHOLNPGM("Special Menu: Save EEPROM"); + injectCommands_P(PSTR("M500\nM300 P105 S1108\nM300 P210 S1661")); + break; + + default: + break; + } + break; + #else // if ENABLED(PROBE_MANUALLY) + case '0': + switch (SelectedDirectory[2]) { + case '1': // "<01PrehtBed>" + SERIAL_ECHOLNPGM("Special Menu: Preheat Bed"); + injectCommands_P(PSTR("M140 S65")); + break; + + case '2': // "<02ABL>" + SERIAL_ECHOLNPGM("Special Menu: Auto Bed Leveling"); + injectCommands_P(PSTR("G29N")); + break; + + case '3': // "<03HtendPID>" + SERIAL_ECHOLNPGM("Special Menu: Auto Tune Hotend PID"); + // need to dwell for half a second to give the fan a chance to start before the pid tuning starts + injectCommands_P(PSTR("M106 S204\nG4 P500\nM303 E0 S215 C15 U1")); + break; + + case '4': // "<04HtbedPID>" + SERIAL_ECHOLNPGM("Special Menu: Auto Tune Hotbed Pid"); + injectCommands_P(PSTR("M303 E-1 S65 C6 U1")); + break; + + case '5': // "<05FWDeflts>" + SERIAL_ECHOLNPGM("Special Menu: Load FW Defaults"); + injectCommands_P(PSTR("M502\nM300 P105 S1661\nM300 P210 S1108")); + break; + + case '6': // "<06SvEEPROM>" + SERIAL_ECHOLNPGM("Special Menu: Save EEPROM"); + injectCommands_P(PSTR("M500\nM300 P105 S1108\nM300 P210 S1661")); + break; + + case '7': // <07SendM108> + SERIAL_ECHOLNPGM("Special Menu: Send User Confirmation"); + injectCommands_P(PSTR("M108")); + break; + + default: + break; + } + break; + #endif // PROBE_MANUALLY + + default: + break; + } + #if ENABLED(ANYCUBIC_LCD_DEBUG) + } + else { + SERIAL_ECHOPGM("TFT Serial Debug: Attempted to HandleSpecialMenu on non-special menu... "); + SERIAL_ECHOLN(SelectedDirectory); + #endif + } +} + +void AnycubicTFTClass::RenderCurrentFileList() { + #if ENABLED(SDSUPPORT) + uint16_t selectedNumber = 0; + SelectedDirectory[0] = 0; + SelectedFile[0] = 0; + FileList currentFileList; + + SENDLINE_PGM("FN "); // Filelist start + + if (!isMediaInserted() && !SpecialMenu) { + SENDLINE_DBG_PGM("J02", "TFT Serial Debug: No SD Card mounted to render Current File List... J02"); + + SENDLINE_PGM(""); + SENDLINE_PGM(""); + } + else { + if (CodeSeen('S')) + selectedNumber = CodeValue(); + + if (SpecialMenu) + RenderSpecialMenu(selectedNumber); + else if (selectedNumber <= currentFileList.count()) + RenderCurrentFolder(selectedNumber); + } + SENDLINE_PGM("END"); // Filelist stop + #endif // SDSUPPORT +} + +void AnycubicTFTClass::RenderSpecialMenu(uint16_t selectedNumber) { + switch (selectedNumber) { + #if ENABLED(PROBE_MANUALLY) + case 0: // First Page + SENDLINE_PGM("<01ZUp0.1>"); + SENDLINE_PGM(""); + SENDLINE_PGM("<02ZUp0.02>"); + SENDLINE_PGM(""); + SENDLINE_PGM("<03ZDn0.02>"); + SENDLINE_PGM(""); + SENDLINE_PGM("<04ZDn0.1>"); + SENDLINE_PGM(""); + break; + + case 4: // Second Page + SENDLINE_PGM("<05PrehtBed>"); + SENDLINE_PGM(""); + SENDLINE_PGM("<06SMeshLvl>"); + SENDLINE_PGM(""); + SENDLINE_PGM("<07MeshNPnt>"); + SENDLINE_PGM(""); + SENDLINE_PGM("<08HtEndPID>"); + SENDLINE_PGM(""); + break; + + case 8: // Third Page + SENDLINE_PGM("<09HtBedPID>"); + SENDLINE_PGM(""); + SENDLINE_PGM("<10FWDeflts>"); + SENDLINE_PGM(""); + SENDLINE_PGM("<11SvEEPROM>"); + SENDLINE_PGM(""); + SENDLINE_PGM(""); + SENDLINE_PGM(""); + break; + #else + case 0: // First Page + SENDLINE_PGM("<01PrehtBed>"); + SENDLINE_PGM(""); + SENDLINE_PGM("<02ABL>"); + SENDLINE_PGM(""); + SENDLINE_PGM("<03HtEndPID>"); + SENDLINE_PGM(""); + SENDLINE_PGM("<04HtBedPID>"); + SENDLINE_PGM(""); + break; + + case 4: // Second Page + SENDLINE_PGM("<05FWDeflts>"); + SENDLINE_PGM(""); + SENDLINE_PGM("<06SvEEPROM>"); + SENDLINE_PGM(""); + SENDLINE_PGM("<07SendM108>"); + SENDLINE_PGM(""); + SENDLINE_PGM(""); + SENDLINE_PGM(""); + break; + + #endif // PROBE_MANUALLY + + default: + break; + } +} + +void AnycubicTFTClass::RenderCurrentFolder(uint16_t selectedNumber) { + FileList currentFileList; + uint16_t cnt = selectedNumber; + uint16_t max_files; + uint16_t dir_files = currentFileList.count(); + + if ((dir_files - selectedNumber) < 4) + max_files = dir_files; + else + max_files = selectedNumber + 3; + + for (cnt = selectedNumber; cnt <= max_files; cnt++) { + if (cnt == 0) { // Special Entry + if (currentFileList.isAtRootDir()) { + SENDLINE_PGM(""); + SENDLINE_PGM(""); + } + else { + SENDLINE_PGM("/.."); + SENDLINE_PGM("/.."); + } + } + else { + currentFileList.seek(cnt - 1, false); + + #if ENABLED(ANYCUBIC_LCD_DEBUG) + SERIAL_ECHOLN(currentFileList.filename()); + #endif + if (currentFileList.isDir()) { + SEND_PGM("/"); + SENDLINE(currentFileList.shortFilename()); + SEND_PGM("/"); + SENDLINE(currentFileList.filename()); + + } + else { + SENDLINE(currentFileList.shortFilename()); + SENDLINE(currentFileList.filename()); + } + } + } +} + +void AnycubicTFTClass::OnPrintTimerStarted() { + #if ENABLED(SDSUPPORT) + if (mediaPrintingState == AMPRINTSTATE_PRINTING) + SENDLINE_DBG_PGM("J04", "TFT Serial Debug: Starting SD Print... J04"); // J04 Starting Print + + #endif +} + +void AnycubicTFTClass::OnPrintTimerPaused() { + #if ENABLED(SDSUPPORT) + if (isPrintingFromMedia()) { + mediaPrintingState = AMPRINTSTATE_PAUSED; + mediaPauseState = AMPAUSESTATE_PARKING; + } + #endif +} + +void AnycubicTFTClass::OnPrintTimerStopped() { + #if ENABLED(SDSUPPORT) + if (mediaPrintingState == AMPRINTSTATE_PRINTING) { + mediaPrintingState = AMPRINTSTATE_NOT_PRINTING; + mediaPauseState = AMPAUSESTATE_NOT_PAUSED; + SENDLINE_DBG_PGM("J14", "TFT Serial Debug: SD Print Completed... J14"); + } + // otherwise it was stopped by the printer so don't send print completed signal to TFT + #endif +} + +#define ROUND(val) int((val)+0.5f) + +void AnycubicTFTClass::GetCommandFromTFT() { + char *starpos = nullptr; + while (LCD_SERIAL.available() > 0 && TFTbuflen < TFTBUFSIZE) { + serial3_char = LCD_SERIAL.read(); + if (serial3_char == '\n' || + serial3_char == '\r' || + serial3_char == ':' || + serial3_count >= (TFT_MAX_CMD_SIZE - 1) + ) { + + if (!serial3_count) return; // if empty line + + TFTcmdbuffer[TFTbufindw][serial3_count] = 0; // terminate string + + if ((strchr(TFTcmdbuffer[TFTbufindw], 'A') != nullptr)) { + int16_t a_command; + TFTstrchr_pointer = strchr(TFTcmdbuffer[TFTbufindw], 'A'); + a_command = ((int)((strtod(&TFTcmdbuffer[TFTbufindw][TFTstrchr_pointer - TFTcmdbuffer[TFTbufindw] + 1], nullptr)))); + + #if ENABLED(ANYCUBIC_LCD_DEBUG) + if ((a_command > 7) && (a_command != 20)) // No debugging of status polls, please! + SERIAL_ECHOLNPAIR("TFT Serial Command: ", TFTcmdbuffer[TFTbufindw]); + #endif + + switch (a_command) { + case 0: { // A0 GET HOTEND TEMP + const celsius_float_t hotendActualTemp = getActualTemp_celsius(E0); + SEND_PGM_VAL("A0V ", ROUND(hotendActualTemp)); + } + break; + + case 1: { // A1 GET HOTEND TARGET TEMP + const celsius_float_t hotendTargetTemp = getTargetTemp_celsius(E0); + SEND_PGM_VAL("A1V ", ROUND(hotendTargetTemp)); + } + break; + + case 2: { // A2 GET HOTBED TEMP + const celsius_float_t heatedBedActualTemp = getActualTemp_celsius(BED); + SEND_PGM_VAL("A2V ", ROUND(heatedBedActualTemp)); + } + break; + + case 3: { // A3 GET HOTBED TARGET TEMP + const celsius_float_t heatedBedTargetTemp = getTargetTemp_celsius(BED); + SEND_PGM_VAL("A3V ", ROUND(heatedBedTargetTemp)); + } break; + + case 4: { // A4 GET FAN SPEED + SEND_PGM_VAL("A4V ", int(getActualFan_percent(FAN0))); + } break; + + case 5: { // A5 GET CURRENT COORDINATE + const float xPosition = getAxisPosition_mm(X), + yPosition = getAxisPosition_mm(Y), + zPosition = getAxisPosition_mm(Z); + SEND_PGM("A5V X: "); LCD_SERIAL.print(xPosition); + SEND_PGM( " Y: "); LCD_SERIAL.print(yPosition); + SEND_PGM( " Z: "); LCD_SERIAL.print(zPosition); + SENDLINE_PGM(""); + } break; + + case 6: // A6 GET SD CARD PRINTING STATUS + #if ENABLED(SDSUPPORT) + if (isPrintingFromMedia()) { + SEND_PGM("A6V "); + if (isMediaInserted()) + SENDLINE(ui8tostr3rj(getProgress_percent())); + else + SENDLINE_DBG_PGM("J02", "TFT Serial Debug: No SD Card mounted to return printing status... J02"); + } + else + SENDLINE_PGM("A6V ---"); + #endif + break; + + case 7: { // A7 GET PRINTING TIME + const uint32_t elapsedSeconds = getProgress_seconds_elapsed(); + SEND_PGM("A7V "); + if (elapsedSeconds != 0) { // print time + const uint32_t elapsedMinutes = elapsedSeconds / 60; + SEND(ui8tostr2(elapsedMinutes / 60)); + SEND_PGM(" H "); + SEND(ui8tostr2(elapsedMinutes % 60)); + SENDLINE_PGM(" M"); + } + else + SENDLINE_PGM(" 999:999"); + } + break; + + case 8: // A8 GET SD LIST + #if ENABLED(SDSUPPORT) + SelectedFile[0] = 0; + RenderCurrentFileList(); + #endif + break; + + case 9: // A9 pause sd print + #if ENABLED(SDSUPPORT) + if (isPrintingFromMedia()) + PausePrint(); + #endif + break; + + case 10: // A10 resume sd print + #if ENABLED(SDSUPPORT) + if (isPrintingFromMediaPaused()) + ResumePrint(); + #endif + break; + + case 11: // A11 STOP SD PRINT + TERN_(SDSUPPORT, StopPrint()); + break; + + case 12: // A12 kill + kill(PSTR(STR_ERR_KILLED)); + break; + + case 13: // A13 SELECTION FILE + #if ENABLED(SDSUPPORT) + if (isMediaInserted()) { + starpos = (strchr(TFTstrchr_pointer + 4, '*')); + if (TFTstrchr_pointer[4] == '/') { + strcpy(SelectedDirectory, TFTstrchr_pointer + 5); + SelectedFile[0] = 0; + SENDLINE_DBG_PGM("J21", "TFT Serial Debug: Clear file selection... J21 "); // J21 Not File Selected + SENDLINE_PGM(""); + } + else if (TFTstrchr_pointer[4] == '<') { + strcpy(SelectedDirectory, TFTstrchr_pointer + 4); + SpecialMenu = true; + SelectedFile[0] = 0; + SENDLINE_DBG_PGM("J21", "TFT Serial Debug: Clear file selection... J21 "); // J21 Not File Selected + SENDLINE_PGM(""); + } + else { + SelectedDirectory[0] = 0; + + if (starpos) *(starpos - 1) = '\0'; + + strcpy(SelectedFile, TFTstrchr_pointer + 4); + SENDLINE_DBG_PGM_VAL("J20", "TFT Serial Debug: File Selected... J20 ", SelectedFile); // J20 File Selected + } + } + #endif + break; + + case 14: // A14 START PRINTING + #if ENABLED(SDSUPPORT) + if (!isPrinting() && strlen(SelectedFile) > 0) + StartPrint(); + #endif + break; + + case 15: // A15 RESUMING FROM OUTAGE + // TODO: JBA implement resume form outage + break; + + case 16: { // A16 set hotend temp + unsigned int tempvalue; + if (CodeSeen('S')) { + tempvalue = constrain(CodeValue(), 0, 275); + setTargetTemp_celsius(tempvalue, (extruder_t)E0); + } + else if (CodeSeen('C') && !isPrinting()) { + if (getAxisPosition_mm(Z) < 10) + injectCommands_P(PSTR("G1 Z10")); // RASE Z AXIS + tempvalue = constrain(CodeValue(), 0, 275); + setTargetTemp_celsius(tempvalue, (extruder_t)E0); + } + } + break; + + case 17: { // A17 set heated bed temp + unsigned int tempbed; + if (CodeSeen('S')) { + tempbed = constrain(CodeValue(), 0, 100); + setTargetTemp_celsius(tempbed, (heater_t)BED); + } + } + break; + + case 18: { // A18 set fan speed + float fanPercent; + if (CodeSeen('S')) { + fanPercent = CodeValue(); + fanPercent = constrain(fanPercent, 0, 100); + setTargetFan_percent(fanPercent, FAN0); + } + else + fanPercent = 100; + + setTargetFan_percent(fanPercent, FAN0); + SENDLINE_PGM(""); + } + break; + + case 19: // A19 stop stepper drivers - sent on stop extrude command and on turn motors off command + if (!isPrinting()) { + quickstop_stepper(); + disable_all_steppers(); + } + + SENDLINE_PGM(""); + break; + + case 20: // A20 read printing speed + if (CodeSeen('S')) + feedrate_percentage = constrain(CodeValue(), 40, 999); + else + SEND_PGM_VAL("A20V ", feedrate_percentage); + break; + + case 21: // A21 all home + if (!isPrinting() && !isPrintingFromMediaPaused()) { + if (CodeSeen('X') || CodeSeen('Y') || CodeSeen('Z')) { + if (CodeSeen('X')) + injectCommands_P(PSTR("G28X")); + if (CodeSeen('Y')) + injectCommands_P(PSTR("G28Y")); + if (CodeSeen('Z')) + injectCommands_P(PSTR("G28Z")); + } + else if (CodeSeen('C')) { + injectCommands_P(G28_STR); + } + } + break; + + case 22: // A22 move X/Y/Z or extrude + if (!isPrinting()) { + float coorvalue; + unsigned int movespeed = 0; + char commandStr[30]; + char fullCommandStr[38]; + + commandStr[0] = 0; // empty string + if (CodeSeen('F')) // Set feedrate + movespeed = CodeValue(); + + if (CodeSeen('X')) { // Move in X direction + coorvalue = CodeValue(); + if ((coorvalue <= 0.2) && coorvalue > 0) + sprintf_P(commandStr, PSTR("G1 X0.1F%i"), movespeed); + else if ((coorvalue <= -0.1) && coorvalue > -1) + sprintf_P(commandStr, PSTR("G1 X-0.1F%i"), movespeed); + else + sprintf_P(commandStr, PSTR("G1 X%iF%i"), int(coorvalue), movespeed); + } + else if (CodeSeen('Y')) { // Move in Y direction + coorvalue = CodeValue(); + if ((coorvalue <= 0.2) && coorvalue > 0) + sprintf_P(commandStr, PSTR("G1 Y0.1F%i"), movespeed); + else if ((coorvalue <= -0.1) && coorvalue > -1) + sprintf_P(commandStr, PSTR("G1 Y-0.1F%i"), movespeed); + else + sprintf_P(commandStr, PSTR("G1 Y%iF%i"), int(coorvalue), movespeed); + } + else if (CodeSeen('Z')) { // Move in Z direction + coorvalue = CodeValue(); + if ((coorvalue <= 0.2) && coorvalue > 0) + sprintf_P(commandStr, PSTR("G1 Z0.1F%i"), movespeed); + else if ((coorvalue <= -0.1) && coorvalue > -1) + sprintf_P(commandStr, PSTR("G1 Z-0.1F%i"), movespeed); + else + sprintf_P(commandStr, PSTR("G1 Z%iF%i"), int(coorvalue), movespeed); + } + else if (CodeSeen('E')) { // Extrude + coorvalue = CodeValue(); + if ((coorvalue <= 0.2) && coorvalue > 0) + sprintf_P(commandStr, PSTR("G1 E0.1F%i"), movespeed); + else if ((coorvalue <= -0.1) && coorvalue > -1) + sprintf_P(commandStr, PSTR("G1 E-0.1F%i"), movespeed); + else + sprintf_P(commandStr, PSTR("G1 E%iF500"), int(coorvalue)); + } + + if (strlen(commandStr) > 0) { + sprintf_P(fullCommandStr, PSTR("G91\n%s\nG90"), commandStr); + #if ENABLED(ANYCUBIC_LCD_DEBUG) + SERIAL_ECHOPGM("TFT Serial Debug: A22 Move final request with gcode... "); + SERIAL_ECHOLN(fullCommandStr); + #endif + injectCommands(fullCommandStr); + } + } + SENDLINE_PGM(""); + break; + + case 23: // A23 preheat pla + if (!isPrinting()) { + if (getAxisPosition_mm(Z) < 10) + injectCommands_P(PSTR("G1 Z10")); // RASE Z AXIS + + setTargetTemp_celsius(PREHEAT_1_TEMP_BED, (heater_t)BED); + setTargetTemp_celsius(PREHEAT_1_TEMP_HOTEND, (extruder_t)E0); + SENDLINE_PGM("OK"); + } + break; + + case 24:// A24 preheat abs + if (!isPrinting()) { + if (getAxisPosition_mm(Z) < 10) + injectCommands_P(PSTR("G1 Z10")); // RASE Z AXIS + + setTargetTemp_celsius(PREHEAT_2_TEMP_BED, (heater_t)BED); + setTargetTemp_celsius(PREHEAT_2_TEMP_HOTEND, (extruder_t)E0); + SENDLINE_PGM("OK"); + } + break; + + case 25: // A25 cool down + if (!isPrinting()) { + setTargetTemp_celsius(0, (heater_t) BED); + setTargetTemp_celsius(0, (extruder_t) E0); + + SENDLINE_DBG_PGM("J12", "TFT Serial Debug: Cooling down... J12"); // J12 cool down + } + break; + + case 26: // A26 refresh SD + #if ENABLED(SDSUPPORT) + if (isMediaInserted()) { + if (strlen(SelectedDirectory) > 0) { + FileList currentFileList; + if ((SelectedDirectory[0] == '.') && (SelectedDirectory[1] == '.')) { + currentFileList.upDir(); + } + else { + if (SelectedDirectory[0] == '<') + HandleSpecialMenu(); + else + currentFileList.changeDir(SelectedDirectory); + } + } + } + else { + SENDLINE_DBG_PGM("J02", "TFT Serial Debug: No SD Card mounted to refresh SD A26... J02"); + } + + SelectedDirectory[0] = 0; + #endif + break; + + #if ENABLED(SERVO_ENDSTOPS) + case 27: break; // A27 servos angles adjust + #endif + + case 28: // A28 filament test + if (CodeSeen('O')) + NOOP; + else if (CodeSeen('C')) + NOOP; + SENDLINE_PGM(""); + break; + + case 33: // A33 get version info + SEND_PGM("J33 "); + SENDLINE_PGM(DETAILED_BUILD_VERSION); + break; + + default: + break; + } + } + + TFTbufindw = (TFTbufindw + 1) % TFTBUFSIZE; + TFTbuflen += 1; + serial3_count = 0; // clear buffer + } + else { + TFTcmdbuffer[TFTbufindw][serial3_count++] = serial3_char; + } + } +} + +void AnycubicTFTClass::DoSDCardStateCheck() { + #if ENABLED(SDSUPPORT) && PIN_EXISTS(SD_DETECT) + bool isInserted = isMediaInserted(); + if (isInserted) + SENDLINE_DBG_PGM("J00", "TFT Serial Debug: SD card state changed... isInserted"); + else + SENDLINE_DBG_PGM("J01", "TFT Serial Debug: SD card state changed... !isInserted"); + + #endif +} + +void AnycubicTFTClass::DoFilamentRunoutCheck() { + #if ENABLED(FILAMENT_RUNOUT_SENSOR) + // NOTE: getFilamentRunoutState() only returns the runout state if the job is printing + // we want to actually check the status of the pin here, regardless of printstate + if (READ(FIL_RUNOUT1_PIN)) { + if (mediaPrintingState == AMPRINTSTATE_PRINTING || mediaPrintingState == AMPRINTSTATE_PAUSED || mediaPrintingState == AMPRINTSTATE_PAUSE_REQUESTED) { + // play tone to indicate filament is out + injectCommands_P(PSTR("\nM300 P200 S1567\nM300 P200 S1174\nM300 P200 S1567\nM300 P200 S1174\nM300 P2000 S1567")); + + // tell the user that the filament has run out and wait + SENDLINE_DBG_PGM("J23", "TFT Serial Debug: Blocking filament prompt... J23"); + } + else { + SENDLINE_DBG_PGM("J15", "TFT Serial Debug: Non blocking filament runout... J15"); + } + } + #endif // FILAMENT_RUNOUT_SENSOR +} + +void AnycubicTFTClass::StartPrint() { + #if ENABLED(SDSUPPORT) + if (!isPrinting() && strlen(SelectedFile) > 0) { + #if ENABLED(ANYCUBIC_LCD_DEBUG) + SERIAL_ECHOPGM("TFT Serial Debug: About to print file ... "); + SERIAL_ECHO(isPrinting()); + SERIAL_ECHOPGM(" "); + SERIAL_ECHOLN(SelectedFile); + #endif + mediaPrintingState = AMPRINTSTATE_PRINTING; + mediaPauseState = AMPAUSESTATE_NOT_PAUSED; + printFile(SelectedFile); + } + #endif // SDUPPORT +} + +void AnycubicTFTClass::PausePrint() { + #if ENABLED(SDSUPPORT) + 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 + SENDLINE_DBG_PGM("J05", "TFT Serial Debug: SD print pause started... J05"); // J05 printing pause + + // for some reason pausing the print doesn't retract the extruder so force a manual one here + injectCommands_P(PSTR("G91\nG1 E-2 F1800\nG90")); + pausePrint(); + } + #endif +} + +void AnycubicTFTClass::ResumePrint() { + #if ENABLED(SDSUPPORT) + #if ENABLED(FILAMENT_RUNOUT_SENSOR) + if (READ(FIL_RUNOUT1_PIN)) { + #if ENABLED(ANYCUBIC_LCD_DEBUG) + SERIAL_ECHOLNPGM("TFT Serial Debug: Resume Print with filament sensor still tripped... "); + #endif + + // trigger the user message box + DoFilamentRunoutCheck(); + + // re-enable the continue button + SENDLINE_DBG_PGM("J18", "TFT Serial Debug: Resume Print with filament sensor still tripped... J18"); + return; + } + #endif + + if (mediaPauseState == AMPAUSESTATE_HEATER_TIMEOUT) { + mediaPauseState = AMPAUSESTATE_REHEATING; + // TODO: JBA I don't think J05 just disables the continue button, i think it injects a rogue M25. So taking this out + // // disable the continue button + // SENDLINE_DBG_PGM("J05", "TFT Serial Debug: Resume called with heater timeout... J05"); // J05 printing pause + + // reheat the nozzle + setUserConfirmed(); + } + else { + mediaPrintingState = AMPRINTSTATE_PRINTING; + mediaPauseState = AMPAUSESTATE_NOT_PAUSED; + + SENDLINE_DBG_PGM("J04", "TFT Serial Debug: SD print resumed... J04"); // J04 printing form sd card now + resumePrint(); + } + #endif +} + +void AnycubicTFTClass::StopPrint() { + #if ENABLED(SDSUPPORT) + mediaPrintingState = AMPRINTSTATE_STOP_REQUESTED; + mediaPauseState = AMPAUSESTATE_NOT_PAUSED; + SENDLINE_DBG_PGM("J16", "TFT Serial Debug: SD print stop called... J16"); + + // for some reason stopping the print doesn't retract the extruder so force a manual one here + injectCommands_P(PSTR("G91\nG1 E-2 F1800\nG90")); + stopPrint(); + #endif +} + +#endif // ANYCUBIC_LCD_I3MEGA diff --git a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.h b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.h new file mode 100644 index 000000000000..fa62b545dcdd --- /dev/null +++ b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.h @@ -0,0 +1,95 @@ +/** + * anycubic_i3mega_lcd.h --- Support for Anycubic i3 Mega TFT + * Created by Christian Hopp on 09.12.17. + * Improved by David Ramiro + * Converted to ExtUI by John BouAntoun 21 June 2020 + * + * 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 + */ +#pragma once + +#include "../../../inc/MarlinConfigPre.h" +#include "../../../sd/SdFatConfig.h" // for the FILENAME_LENGTH macro + +#define TFTBUFSIZE 4 +#define TFT_MAX_CMD_SIZE 96 + +enum AnycubicMediaPrintState { + AMPRINTSTATE_NOT_PRINTING, + AMPRINTSTATE_PRINTING, + AMPRINTSTATE_PAUSE_REQUESTED, + AMPRINTSTATE_PAUSED, + AMPRINTSTATE_STOP_REQUESTED +}; + +enum AnycubicMediaPauseState { + AMPAUSESTATE_NOT_PAUSED, + AMPAUSESTATE_PARKING, + AMPAUSESTATE_PARKED, + AMPAUSESTATE_FILAMENT_OUT, + AMPAUSESTATE_FIAMENT_PRUGING, + AMPAUSESTATE_HEATER_TIMEOUT, + AMPAUSESTATE_REHEATING, + AMPAUSESTATE_REHEAT_FINISHED +}; + +class AnycubicTFTClass { +public: + AnycubicTFTClass(); + static void OnSetup(); + static void OnCommandScan(); + static void OnKillTFT(); + static void OnSDCardStateChange(bool); + static void OnSDCardError(); + static void OnFilamentRunout(); + static void OnUserConfirmRequired(const char *); + static void OnPrintTimerStarted(); + static void OnPrintTimerPaused(); + static void OnPrintTimerStopped(); + +private: + static char TFTcmdbuffer[TFTBUFSIZE][TFT_MAX_CMD_SIZE]; + static int TFTbuflen, TFTbufindr, TFTbufindw; + static char serial3_char; + static int serial3_count; + static char *TFTstrchr_pointer; + static uint8_t SpecialMenu; + static AnycubicMediaPrintState mediaPrintingState; + static AnycubicMediaPauseState mediaPauseState; + + static float CodeValue(); + static bool CodeSeen(char); + static bool IsNozzleHomed(); + static void RenderCurrentFileList(); + static void RenderSpecialMenu(uint16_t); + static void RenderCurrentFolder(uint16_t); + static void GetCommandFromTFT(); + static void CheckSDCardChange(); + static void CheckPauseState(); + static void CheckPrintCompletion(); + static void HandleSpecialMenu(); + static void DoSDCardStateCheck(); + static void DoFilamentRunoutCheck(); + static void StartPrint(); + static void PausePrint(); + static void ResumePrint(); + static void StopPrint(); + + static char SelectedDirectory[30]; + static char SelectedFile[FILENAME_LENGTH]; +}; + +extern AnycubicTFTClass AnycubicTFT; +extern const char G28_STR[]; diff --git a/Marlin/src/lcd/extui/anycubic_i3mega_lcd.cpp b/Marlin/src/lcd/extui/anycubic_i3mega_lcd.cpp deleted file mode 100644 index 15526d16fc21..000000000000 --- a/Marlin/src/lcd/extui/anycubic_i3mega_lcd.cpp +++ /dev/null @@ -1,104 +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 . - * - */ - -/** - * anycubic_i3mega_lcd.cpp - */ - -#include "../../inc/MarlinConfigPre.h" - -#if ENABLED(ANYCUBIC_LCD_I3MEGA) - -#include "lib/anycubic_i3mega/anycubic_i3mega_lcd.h" -#include "ui_api.h" - -#include // for the ::tone() call - -namespace ExtUI { - - void onStartup() { AnycubicTFT.OnSetup(); } - void onIdle() { AnycubicTFT.OnCommandScan(); } - void onPrinterKilled(PGM_P const error, PGM_P const component) { AnycubicTFT.OnKillTFT(); } - void onMediaInserted() { AnycubicTFT.OnSDCardStateChange(true); } - void onMediaError() { AnycubicTFT.OnSDCardError(); } - void onMediaRemoved() { AnycubicTFT.OnSDCardStateChange(false); } - void onPlayTone(const uint16_t frequency, const uint16_t duration) { - #if ENABLED(SPEAKER) - ::tone(BEEPER_PIN, frequency, duration); - #endif - } - void onPrintTimerStarted() { AnycubicTFT.OnPrintTimerStarted(); } - void onPrintTimerPaused() { AnycubicTFT.OnPrintTimerPaused(); } - void onPrintTimerStopped() { AnycubicTFT.OnPrintTimerStopped(); } - void onFilamentRunout(const extruder_t extruder) { AnycubicTFT.OnFilamentRunout(); } - void onUserConfirmRequired(const char * const msg) { AnycubicTFT.OnUserConfirmRequired(msg); } - void onStatusChanged(const char * const msg) {} - void onFactoryReset() {} - - void onStoreSettings(char *buff) { - // Called when saving to EEPROM (i.e. M500). If the ExtUI needs - // permanent data to be stored, it can write up to eeprom_data_size bytes - // into buff. - - // Example: - // static_assert(sizeof(myDataStruct) <= ExtUI::eeprom_data_size); - // memcpy(buff, &myDataStruct, sizeof(myDataStruct)); - } - - void onLoadSettings(const char *buff) { - // Called while loading settings from EEPROM. If the ExtUI - // needs to retrieve data, it should copy up to eeprom_data_size bytes - // from buff - - // Example: - // static_assert(sizeof(myDataStruct) <= ExtUI::eeprom_data_size); - // memcpy(&myDataStruct, buff, sizeof(myDataStruct)); - } - - void onConfigurationStoreWritten(bool success) { - // Called after the entire EEPROM has been written, - // whether successful or not. - } - - void onConfigurationStoreRead(bool success) { - // Called after the entire EEPROM has been read, - // whether successful or not. - } - - void onMeshUpdate(const int8_t xpos, const int8_t ypos, const float zval) { - // Called when any mesh points are updated - } - - #if ENABLED(POWER_LOSS_RECOVERY) - void onPowerLossResume() { - // Called on resume from power-loss - } - #endif - - #if HAS_PID_HEATING - void onPidTuning(const result_t rst) { - // Called for temperature PID tuning result - } - #endif -} - -#endif // ANYCUBIC_LCD_I3MEGA diff --git a/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp b/Marlin/src/lcd/extui/dgus/DGUSDisplay.cpp similarity index 84% rename from Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp rename to Marlin/src/lcd/extui/dgus/DGUSDisplay.cpp index 8577b76ce61f..c2390d63a661 100644 --- a/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp +++ b/Marlin/src/lcd/extui/dgus/DGUSDisplay.cpp @@ -20,34 +20,32 @@ * */ -/* DGUS implementation written by coldtobi in 2019 for Marlin */ - -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_DGUS_LCD #if HOTENDS > 2 - #error "More than 2 hotends not implemented on the Display UI design." + #warning "More than 2 hotends not implemented on DGUS Display UI." #endif -#include "../../ui_api.h" +#include "../ui_api.h" -#include "../../../../MarlinCore.h" -#include "../../../../module/temperature.h" -#include "../../../../module/motion.h" -#include "../../../../gcode/queue.h" -#include "../../../../module/planner.h" -#include "../../../../sd/cardreader.h" -#include "../../../../libs/duration_t.h" -#include "../../../../module/printcounter.h" +#include "../../../MarlinCore.h" +#include "../../../module/motion.h" +#include "../../../gcode/queue.h" +#include "../../../module/planner.h" +#include "../../../libs/duration_t.h" +#include "../../../module/printcounter.h" #if ENABLED(POWER_LOSS_RECOVERY) - #include "../../../../feature/powerloss.h" + #include "../../../feature/powerloss.h" #endif #include "DGUSDisplay.h" #include "DGUSVPVariable.h" #include "DGUSDisplayDef.h" +DGUSDisplay dgusdisplay; + // Preamble... 2 Bytes, usually 0x5A 0xA5, but configurable constexpr uint8_t DGUS_HEADER1 = 0x5A; constexpr uint8_t DGUS_HEADER2 = 0xA5; @@ -64,11 +62,15 @@ void DGUSDisplay::InitDisplay() { #define LCD_BAUDRATE 115200 #endif LCD_SERIAL.begin(LCD_BAUDRATE); - if (TERN1(POWER_LOSS_RECOVERY, !recovery.valid())) - RequestScreen(TERN(SHOW_BOOTSCREEN, DGUSLCD_SCREEN_BOOT, DGUSLCD_SCREEN_MAIN)); + + if (TERN1(POWER_LOSS_RECOVERY, !recovery.valid())) { // If no Power-Loss Recovery is needed... + TERN_(DGUS_LCD_UI_MKS, delay(LOGO_TIME_DELAY)); // Show the logo for a little while + } + + RequestScreen(TERN(SHOW_BOOTSCREEN, DGUSLCD_SCREEN_BOOT, DGUSLCD_SCREEN_MAIN)); } -void DGUSDisplay::WriteVariable(uint16_t adr, const void* values, uint8_t valueslen, bool isstr) { +void DGUSDisplay::WriteVariable(uint16_t adr, const void *values, uint8_t valueslen, bool isstr) { const char* myvalues = static_cast(values); bool strend = !myvalues; WriteHeader(adr, DGUS_CMD_WRITEVAR, valueslen); @@ -84,12 +86,12 @@ void DGUSDisplay::WriteVariable(uint16_t adr, const void* values, uint8_t values } void DGUSDisplay::WriteVariable(uint16_t adr, uint16_t value) { - value = (value & 0xffU) << 8U | (value >> 8U); + value = (value & 0xFFU) << 8U | (value >> 8U); WriteVariable(adr, static_cast(&value), sizeof(uint16_t)); } void DGUSDisplay::WriteVariable(uint16_t adr, int16_t value) { - value = (value & 0xffU) << 8U | (value >> 8U); + value = (value & 0xFFU) << 8U | (value >> 8U); WriteVariable(adr, static_cast(&value), sizeof(uint16_t)); } @@ -101,18 +103,24 @@ void DGUSDisplay::WriteVariable(uint16_t adr, int8_t value) { WriteVariable(adr, static_cast(&value), sizeof(int8_t)); } +#if ENABLED(DGUS_LCD_UI_MKS) + void DGUSDisplay::MKS_WriteVariable(uint16_t adr, uint8_t value) { + WriteVariable(adr, static_cast(&value), sizeof(uint8_t)); + } +#endif + void DGUSDisplay::WriteVariable(uint16_t adr, long value) { - union { long l; char lb[4]; } endian; - char tmp[4]; - endian.l = value; - tmp[0] = endian.lb[3]; - tmp[1] = endian.lb[2]; - tmp[2] = endian.lb[1]; - tmp[3] = endian.lb[0]; - WriteVariable(adr, static_cast(&tmp), sizeof(long)); + union { long l; char lb[4]; } endian; + char tmp[4]; + endian.l = value; + tmp[0] = endian.lb[3]; + tmp[1] = endian.lb[2]; + tmp[2] = endian.lb[1]; + tmp[3] = endian.lb[0]; + WriteVariable(adr, static_cast(&tmp), sizeof(long)); } -void DGUSDisplay::WriteVariablePGM(uint16_t adr, const void* values, uint8_t valueslen, bool isstr) { +void DGUSDisplay::WriteVariablePGM(uint16_t adr, const void *values, uint8_t valueslen, bool isstr) { const char* myvalues = static_cast(values); bool strend = !myvalues; WriteHeader(adr, DGUS_CMD_WRITEVAR, valueslen); diff --git a/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.h b/Marlin/src/lcd/extui/dgus/DGUSDisplay.h similarity index 83% rename from Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.h rename to Marlin/src/lcd/extui/dgus/DGUSDisplay.h index ee536ea21905..e486a0014570 100644 --- a/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.h +++ b/Marlin/src/lcd/extui/dgus/DGUSDisplay.h @@ -21,20 +21,24 @@ */ #pragma once -/* DGUS implementation written by coldtobi in 2019 for Marlin */ +/** + * lcd/extui/dgus/DGUSDisplay.h + */ + +#include "../../../inc/MarlinConfigPre.h" -#include "../../../../inc/MarlinConfigPre.h" +#include // size_t -#include "../../../../MarlinCore.h" #if HAS_BED_PROBE - #include "../../../../module/probe.h" + #include "../../../module/probe.h" #endif #include "DGUSVPVariable.h" enum DGUSLCD_Screens : uint8_t; +//#define DEBUG_DGUSLCD #define DEBUG_OUT ENABLED(DEBUG_DGUSLCD) -#include "../../../../core/debug_out.h" +#include "../../../core/debug_out.h" typedef enum : uint8_t { DGUS_IDLE, //< waiting for DGUS_HEADER1. @@ -52,13 +56,15 @@ class DGUSDisplay { static void InitDisplay(); // Variable access. - static void WriteVariable(uint16_t adr, const void* values, uint8_t valueslen, bool isstr=false); - static void WriteVariablePGM(uint16_t adr, const void* values, uint8_t valueslen, bool isstr=false); + static void WriteVariable(uint16_t adr, const void *values, uint8_t valueslen, bool isstr=false); + static void WriteVariablePGM(uint16_t adr, const void *values, uint8_t valueslen, bool isstr=false); static void WriteVariable(uint16_t adr, int16_t value); static void WriteVariable(uint16_t adr, uint16_t value); static void WriteVariable(uint16_t adr, uint8_t value); static void WriteVariable(uint16_t adr, int8_t value); static void WriteVariable(uint16_t adr, long value); + static void MKS_WriteVariable(uint16_t adr, uint8_t value); + // Utility functions for bridging ui_api and dbus template @@ -87,7 +93,7 @@ class DGUSDisplay { // Helper for users of this class to estimate if an interaction would be blocking. static size_t GetFreeTxBuffer(); - // Checks two things: Can we confirm the presence of the display and has we initiliazed it. + // Checks two things: Can we confirm the presence of the display and has we initialized it. // (both boils down that the display answered to our chatting) static inline bool isInitialized() { return Initialized; } @@ -96,22 +102,22 @@ class DGUSDisplay { static void WritePGM(const char str[], uint8_t len); static void ProcessRx(); - static inline uint16_t swap16(const uint16_t value) { return (value & 0xffU) << 8U | (value >> 8U); } + static inline uint16_t swap16(const uint16_t value) { return (value & 0xFFU) << 8U | (value >> 8U); } static rx_datagram_state_t rx_datagram_state; static uint8_t rx_datagram_len; static bool Initialized, no_reentrance; }; -#define GET_VARIABLE(f, t, V...) (&DGUSDisplay::GetVariable) -#define SET_VARIABLE(f, t, V...) (&DGUSDisplay::SetVariable) - extern DGUSDisplay dgusdisplay; // compile-time x^y constexpr float cpow(const float x, const int y) { return y == 0 ? 1.0 : x * cpow(x, y - 1); } +/// +const uint16_t* DGUSLCD_FindScreenVPMapList(uint8_t screen); + /// Find the flash address of a DGUS_VP_Variable for the VP. -extern const DGUS_VP_Variable* DGUSLCD_FindVPVar(const uint16_t vp); +const DGUS_VP_Variable* DGUSLCD_FindVPVar(const uint16_t vp); /// Helper to populate a DGUS_VP_Variable for a given VP. Return false if not found. -extern bool populate_VPVar(const uint16_t VP, DGUS_VP_Variable * const ramcopy); +bool populate_VPVar(const uint16_t VP, DGUS_VP_Variable * const ramcopy); diff --git a/Marlin/src/lcd/extui/dgus/DGUSDisplayDef.h b/Marlin/src/lcd/extui/dgus/DGUSDisplayDef.h new file mode 100644 index 000000000000..9cbcf0dd7b12 --- /dev/null +++ b/Marlin/src/lcd/extui/dgus/DGUSDisplayDef.h @@ -0,0 +1,57 @@ +/** + * 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 + +/** + * lcd/extui/dgus/DGUSDisplayDef.h + * Defines the interaction between Marlin and the display firmware + */ + +#include "DGUSVPVariable.h" + +#include + +// Information on which screen which VP is displayed. +// As this is a sparse table, two arrays are needed: +// one to list the VPs of one screen and one to map screens to the lists. +// (Strictly this would not be necessary, but allows to only send data the display needs and reducing load on Marlin) +struct VPMapping { + const uint8_t screen; + const uint16_t *VPList; // The list is null-terminated. +}; + +extern const struct VPMapping VPMap[]; + +// List of VPs handled by Marlin / The Display. +extern const struct DGUS_VP_Variable ListOfVP[]; + +#include "../../../inc/MarlinConfig.h" + +#if ENABLED(DGUS_LCD_UI_ORIGIN) + #include "origin/DGUSDisplayDef.h" +#elif ENABLED(DGUS_LCD_UI_MKS) + #include "mks/DGUSDisplayDef.h" +#elif ENABLED(DGUS_LCD_UI_FYSETC) + #include "fysetc/DGUSDisplayDef.h" +#elif ENABLED(DGUS_LCD_UI_HIPRECY) + #include "hiprecy/DGUSDisplayDef.h" +#endif diff --git a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp new file mode 100644 index 000000000000..5c108d07092a --- /dev/null +++ b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp @@ -0,0 +1,775 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_DGUS_LCD + +#include "DGUSScreenHandler.h" + +#include "../../../MarlinCore.h" +#include "../../../gcode/queue.h" +#include "../../../libs/duration_t.h" +#include "../../../module/settings.h" +#include "../../../module/temperature.h" +#include "../../../module/motion.h" +#include "../../../module/planner.h" +#include "../../../module/printcounter.h" +#include "../../../sd/cardreader.h" + +#if ENABLED(POWER_LOSS_RECOVERY) + #include "../../../feature/powerloss.h" +#endif + +DGUSScreenHandler ScreenHandler; + +uint16_t DGUSScreenHandler::ConfirmVP; + +DGUSLCD_Screens DGUSScreenHandler::current_screen; +DGUSLCD_Screens DGUSScreenHandler::past_screens[NUM_PAST_SCREENS]; +uint8_t DGUSScreenHandler::update_ptr; +uint16_t DGUSScreenHandler::skipVP; +bool DGUSScreenHandler::ScreenComplete; + +void (*DGUSScreenHandler::confirm_action_cb)() = nullptr; + +#if ENABLED(SDSUPPORT) + int16_t DGUSScreenHandler::top_file = 0, + DGUSScreenHandler::file_to_print = 0; + static ExtUI::FileList filelist; +#endif + +#if ENABLED(DGUS_FILAMENT_LOADUNLOAD) + filament_data_t filament_data; +#endif + +void DGUSScreenHandler::sendinfoscreen(const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool l4inflash) { + DGUS_VP_Variable ramcopy; + if (populate_VPVar(VP_MSGSTR1, &ramcopy)) { + ramcopy.memadr = (void*) line1; + l1inflash ? DGUSScreenHandler::DGUSLCD_SendStringToDisplayPGM(ramcopy) : DGUSScreenHandler::DGUSLCD_SendStringToDisplay(ramcopy); + } + if (populate_VPVar(VP_MSGSTR2, &ramcopy)) { + ramcopy.memadr = (void*) line2; + l2inflash ? DGUSScreenHandler::DGUSLCD_SendStringToDisplayPGM(ramcopy) : DGUSScreenHandler::DGUSLCD_SendStringToDisplay(ramcopy); + } + if (populate_VPVar(VP_MSGSTR3, &ramcopy)) { + ramcopy.memadr = (void*) line3; + l3inflash ? DGUSScreenHandler::DGUSLCD_SendStringToDisplayPGM(ramcopy) : DGUSScreenHandler::DGUSLCD_SendStringToDisplay(ramcopy); + } + if (populate_VPVar(VP_MSGSTR4, &ramcopy)) { + ramcopy.memadr = (void*) line4; + l4inflash ? DGUSScreenHandler::DGUSLCD_SendStringToDisplayPGM(ramcopy) : DGUSScreenHandler::DGUSLCD_SendStringToDisplay(ramcopy); + } +} + +void DGUSScreenHandler::HandleUserConfirmationPopUp(uint16_t VP, const char *line1, const char *line2, const char *line3, const char *line4, bool l1, bool l2, bool l3, bool l4) { + if (current_screen == DGUSLCD_SCREEN_CONFIRM) // Already showing a pop up, so we need to cancel that first. + PopToOldScreen(); + + ConfirmVP = VP; + sendinfoscreen(line1, line2, line3, line4, l1, l2, l3, l4); + GotoScreen(DGUSLCD_SCREEN_CONFIRM); +} + +void DGUSScreenHandler::setstatusmessage(const char *msg) { + DGUS_VP_Variable ramcopy; + if (populate_VPVar(VP_M117, &ramcopy)) { + ramcopy.memadr = (void*) msg; + DGUSLCD_SendStringToDisplay(ramcopy); + } +} + +void DGUSScreenHandler::setstatusmessagePGM(PGM_P const msg) { + DGUS_VP_Variable ramcopy; + if (populate_VPVar(VP_M117, &ramcopy)) { + ramcopy.memadr = (void*) msg; + DGUSLCD_SendStringToDisplayPGM(ramcopy); + } +} + +// Send an 8 bit or 16 bit value to the display. +void DGUSScreenHandler::DGUSLCD_SendWordValueToDisplay(DGUS_VP_Variable &var) { + if (var.memadr) { + //DEBUG_ECHOPAIR(" DGUS_LCD_SendWordValueToDisplay ", var.VP); + //DEBUG_ECHOLNPAIR(" data ", *(uint16_t *)var.memadr); + if (var.size > 1) + dgusdisplay.WriteVariable(var.VP, *(int16_t*)var.memadr); + else + dgusdisplay.WriteVariable(var.VP, *(int8_t*)var.memadr); + } +} + +// Send an uint8_t between 0 and 255 to the display, but scale to a percentage (0..100) +void DGUSScreenHandler::DGUSLCD_SendPercentageToDisplay(DGUS_VP_Variable &var) { + if (var.memadr) { + //DEBUG_ECHOPAIR(" DGUS_LCD_SendWordValueToDisplay ", var.VP); + //DEBUG_ECHOLNPAIR(" data ", *(uint16_t *)var.memadr); + uint16_t tmp = *(uint8_t *) var.memadr + 1; // +1 -> avoid rounding issues for the display. + tmp = map(tmp, 0, 255, 0, 100); + dgusdisplay.WriteVariable(var.VP, tmp); + } +} + +// Send the current print progress to the display. +void DGUSScreenHandler::DGUSLCD_SendPrintProgressToDisplay(DGUS_VP_Variable &var) { + //DEBUG_ECHOPAIR(" DGUSLCD_SendPrintProgressToDisplay ", var.VP); + uint16_t tmp = ExtUI::getProgress_percent(); + //DEBUG_ECHOLNPAIR(" data ", tmp); + dgusdisplay.WriteVariable(var.VP, tmp); +} + +// Send the current print time to the display. +// It is using a hex display for that: It expects BSD coded data in the format xxyyzz +void DGUSScreenHandler::DGUSLCD_SendPrintTimeToDisplay(DGUS_VP_Variable &var) { + duration_t elapsed = print_job_timer.duration(); + char buf[32]; + elapsed.toString(buf); + dgusdisplay.WriteVariable(VP_PrintTime, buf, var.size, true); +} + +// Send an uint8_t between 0 and 100 to a variable scale to 0..255 +void DGUSScreenHandler::DGUSLCD_PercentageToUint8(DGUS_VP_Variable &var, void *val_ptr) { + if (var.memadr) { + uint16_t value = swap16(*(uint16_t*)val_ptr); + DEBUG_ECHOLNPAIR("FAN value get:", value); + *(uint8_t*)var.memadr = map(constrain(value, 0, 100), 0, 100, 0, 255); + DEBUG_ECHOLNPAIR("FAN value change:", *(uint8_t*)var.memadr); + } +} + +// Sends a (RAM located) string to the DGUS Display +// (Note: The DGUS Display does not clear after the \0, you have to +// overwrite the remainings with spaces.// var.size has the display buffer size! +void DGUSScreenHandler::DGUSLCD_SendStringToDisplay(DGUS_VP_Variable &var) { + char *tmp = (char*) var.memadr; + dgusdisplay.WriteVariable(var.VP, tmp, var.size, true); +} + +// Sends a (flash located) string to the DGUS Display +// (Note: The DGUS Display does not clear after the \0, you have to +// overwrite the remainings with spaces.// var.size has the display buffer size! +void DGUSScreenHandler::DGUSLCD_SendStringToDisplayPGM(DGUS_VP_Variable &var) { + char *tmp = (char*) var.memadr; + dgusdisplay.WriteVariablePGM(var.VP, tmp, var.size, true); +} + +#if HAS_PID_HEATING + void DGUSScreenHandler::DGUSLCD_SendTemperaturePID(DGUS_VP_Variable &var) { + float value = *(float *)var.memadr; + value /= 10; + float valuesend = 0; + switch (var.VP) { + default: return; + #if HAS_HOTEND + case VP_E0_PID_P: valuesend = value; break; + case VP_E0_PID_I: valuesend = unscalePID_i(value); break; + case VP_E0_PID_D: valuesend = unscalePID_d(value); break; + #endif + #if HOTENDS >= 2 + case VP_E1_PID_P: valuesend = value; break; + case VP_E1_PID_I: valuesend = unscalePID_i(value); break; + case VP_E1_PID_D: valuesend = unscalePID_d(value); break; + #endif + #if HAS_HEATED_BED + case VP_BED_PID_P: valuesend = value; break; + case VP_BED_PID_I: valuesend = unscalePID_i(value); break; + case VP_BED_PID_D: valuesend = unscalePID_d(value); break; + #endif + } + + valuesend *= cpow(10, 1); + union { int16_t i; char lb[2]; } endian; + + char tmp[2]; + endian.i = valuesend; + tmp[0] = endian.lb[1]; + tmp[1] = endian.lb[0]; + dgusdisplay.WriteVariable(var.VP, tmp, 2); + } +#endif + +#if ENABLED(PRINTCOUNTER) + + // Send the accumulate print time to the display. + // It is using a hex display for that: It expects BSD coded data in the format xxyyzz + void DGUSScreenHandler::DGUSLCD_SendPrintAccTimeToDisplay(DGUS_VP_Variable &var) { + printStatistics state = print_job_timer.getStats(); + char buf[22]; + duration_t elapsed = state.printTime; + elapsed.toString(buf); + dgusdisplay.WriteVariable(VP_PrintAccTime, buf, var.size, true); + } + + void DGUSScreenHandler::DGUSLCD_SendPrintsTotalToDisplay(DGUS_VP_Variable &var) { + printStatistics state = print_job_timer.getStats(); + char buf[10]; + sprintf_P(buf, PSTR("%u"), state.totalPrints); + dgusdisplay.WriteVariable(VP_PrintsTotal, buf, var.size, true); + } + +#endif + +// Send fan status value to the display. +#if HAS_FAN + + void DGUSScreenHandler::DGUSLCD_SendFanStatusToDisplay(DGUS_VP_Variable &var) { + if (var.memadr) { + DEBUG_ECHOPAIR(" DGUSLCD_SendFanStatusToDisplay ", var.VP); + DEBUG_ECHOLNPAIR(" data ", *(uint8_t *)var.memadr); + uint16_t data_to_send = 0; + if (*(uint8_t *) var.memadr) data_to_send = 1; + dgusdisplay.WriteVariable(var.VP, data_to_send); + } + } + +#endif + +// Send heater status value to the display. +void DGUSScreenHandler::DGUSLCD_SendHeaterStatusToDisplay(DGUS_VP_Variable &var) { + if (var.memadr) { + DEBUG_ECHOPAIR(" DGUSLCD_SendHeaterStatusToDisplay ", var.VP); + DEBUG_ECHOLNPAIR(" data ", *(int16_t *)var.memadr); + uint16_t data_to_send = 0; + if (*(int16_t *) var.memadr) data_to_send = 1; + dgusdisplay.WriteVariable(var.VP, data_to_send); + } +} + +#if ENABLED(DGUS_UI_WAITING) + + void DGUSScreenHandler::DGUSLCD_SendWaitingStatusToDisplay(DGUS_VP_Variable &var) { + // In FYSETC UI design there are 10 statuses to loop + static uint16_t period = 0; + static uint16_t index = 0; + //DEBUG_ECHOPAIR(" DGUSLCD_SendWaitingStatusToDisplay ", var.VP); + //DEBUG_ECHOLNPAIR(" data ", swap16(index)); + if (period++ > DGUS_UI_WAITING_STATUS_PERIOD) { + dgusdisplay.WriteVariable(var.VP, index); + //DEBUG_ECHOLNPAIR(" data ", swap16(index)); + if (++index >= DGUS_UI_WAITING_STATUS) index = 0; + period = 0; + } + } + +#endif + +#if ENABLED(SDSUPPORT) + + void DGUSScreenHandler::ScreenChangeHookIfSD(DGUS_VP_Variable &var, void *val_ptr) { + // default action executed when there is a SD card, but not printing + if (ExtUI::isMediaInserted() && !ExtUI::isPrintingFromMedia()) { + ScreenChangeHook(var, val_ptr); + dgusdisplay.RequestScreen(current_screen); + return; + } + + // if we are printing, we jump to two screens after the requested one. + // This should host e.g a print pause / print abort / print resume dialog. + // This concept allows to recycle this hook for other file + if (ExtUI::isPrintingFromMedia() && !card.flag.abort_sd_printing) { + GotoScreen(DGUSLCD_SCREEN_SDPRINTMANIPULATION); + return; + } + + // Don't let the user in the dark why there is no reaction. + if (!ExtUI::isMediaInserted()) { + setstatusmessagePGM(GET_TEXT(MSG_NO_MEDIA)); + return; + } + if (card.flag.abort_sd_printing) { + setstatusmessagePGM(GET_TEXT(MSG_MEDIA_ABORTING)); + return; + } + } + + void DGUSScreenHandler::DGUSLCD_SD_ScrollFilelist(DGUS_VP_Variable& var, void *val_ptr) { + auto old_top = top_file; + const int16_t scroll = (int16_t)swap16(*(uint16_t*)val_ptr); + if (scroll) { + top_file += scroll; + DEBUG_ECHOPAIR("new topfile calculated:", top_file); + if (top_file < 0) { + top_file = 0; + DEBUG_ECHOLNPGM("Top of filelist reached"); + } + else { + int16_t max_top = filelist.count() - DGUS_SD_FILESPERSCREEN; + NOLESS(max_top, 0); + NOMORE(top_file, max_top); + } + DEBUG_ECHOPAIR("new topfile adjusted:", top_file); + } + else if (!filelist.isAtRootDir()) { + IF_DISABLED(DGUS_LCD_UI_MKS, filelist.upDir()); + top_file = 0; + ForceCompleteUpdate(); + } + + if (old_top != top_file) ForceCompleteUpdate(); + } + + void DGUSScreenHandler::DGUSLCD_SD_ReallyAbort(DGUS_VP_Variable &var, void *val_ptr) { + ExtUI::stopPrint(); + GotoScreen(DGUSLCD_SCREEN_MAIN); + } + + void DGUSScreenHandler::DGUSLCD_SD_PrintTune(DGUS_VP_Variable &var, void *val_ptr) { + if (!ExtUI::isPrintingFromMedia()) return; // avoid race condition when user stays in this menu and printer finishes. + GotoScreen(DGUSLCD_SCREEN_SDPRINTTUNE); + } + + void DGUSScreenHandler::SDCardError() { + DGUSScreenHandler::SDCardRemoved(); + sendinfoscreen(PSTR("NOTICE"), nullptr, PSTR("SD card error"), nullptr, true, true, true, true); + SetupConfirmAction(nullptr); + GotoScreen(DGUSLCD_SCREEN_POPUP); + } +#endif // SDSUPPORT + +void DGUSScreenHandler::ScreenConfirmedOK(DGUS_VP_Variable &var, void *val_ptr) { + DGUS_VP_Variable ramcopy; + if (!populate_VPVar(ConfirmVP, &ramcopy)) return; + if (ramcopy.set_by_display_handler) ramcopy.set_by_display_handler(ramcopy, val_ptr); +} + +const uint16_t* DGUSLCD_FindScreenVPMapList(uint8_t screen) { + const uint16_t *ret; + const struct VPMapping *map = VPMap; + while ((ret = (uint16_t*) pgm_read_ptr(&(map->VPList)))) { + if (pgm_read_byte(&(map->screen)) == screen) return ret; + map++; + } + return nullptr; +} + +const DGUS_VP_Variable* DGUSLCD_FindVPVar(const uint16_t vp) { + const DGUS_VP_Variable *ret = ListOfVP; + do { + const uint16_t vpcheck = pgm_read_word(&(ret->VP)); + if (vpcheck == 0) break; + if (vpcheck == vp) return ret; + ++ret; + } while (1); + + DEBUG_ECHOLNPAIR("FindVPVar NOT FOUND ", vp); + return nullptr; +} + +void DGUSScreenHandler::ScreenChangeHookIfIdle(DGUS_VP_Variable &var, void *val_ptr) { + if (!ExtUI::isPrinting()) { + ScreenChangeHook(var, val_ptr); + dgusdisplay.RequestScreen(current_screen); + } +} + +void DGUSScreenHandler::HandleAllHeatersOff(DGUS_VP_Variable &var, void *val_ptr) { + thermalManager.disable_all_heaters(); + ForceCompleteUpdate(); // hint to send all data. +} + +void DGUSScreenHandler::HandleTemperatureChanged(DGUS_VP_Variable &var, void *val_ptr) { + celsius_t newvalue = swap16(*(uint16_t*)val_ptr); + celsius_t acceptedvalue; + + switch (var.VP) { + default: return; + #if HAS_HOTEND + case VP_T_E0_Set: + NOMORE(newvalue, HEATER_0_MAXTEMP); + thermalManager.setTargetHotend(newvalue, 0); + acceptedvalue = thermalManager.degTargetHotend(0); + break; + #endif + #if HOTENDS >= 2 + case VP_T_E1_Set: + NOMORE(newvalue, HEATER_1_MAXTEMP); + thermalManager.setTargetHotend(newvalue, 1); + acceptedvalue = thermalManager.degTargetHotend(1); + break; + #endif + #if HAS_HEATED_BED + case VP_T_Bed_Set: + NOMORE(newvalue, BED_MAXTEMP); + thermalManager.setTargetBed(newvalue); + acceptedvalue = thermalManager.degTargetBed(); + break; + #endif + } + + // reply to display the new value to update the view if the new value was rejected by the Thermal Manager. + if (newvalue != acceptedvalue && var.send_to_display_handler) var.send_to_display_handler(var); + skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel +} + +void DGUSScreenHandler::HandleFlowRateChanged(DGUS_VP_Variable &var, void *val_ptr) { + #if HAS_EXTRUDERS + uint16_t newvalue = swap16(*(uint16_t*)val_ptr); + uint8_t target_extruder; + switch (var.VP) { + default: return; + case VP_Flowrate_E0: target_extruder = 0; break; + #if HAS_MULTI_EXTRUDER + case VP_Flowrate_E1: target_extruder = 1; break; + #endif + } + + planner.set_flow(target_extruder, newvalue); + skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel + #else + UNUSED(var); UNUSED(val_ptr); + #endif +} + +void DGUSScreenHandler::HandleManualExtrude(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("HandleManualExtrude"); + + int16_t movevalue = swap16(*(uint16_t*)val_ptr); + float target = movevalue * 0.01f; + ExtUI::extruder_t target_extruder; + + switch (var.VP) { + #if HAS_HOTEND + case VP_MOVE_E0: target_extruder = ExtUI::extruder_t::E0; break; + #if HAS_MULTI_EXTRUDER + case VP_MOVE_E1: target_extruder = ExtUI::extruder_t::E1; break; + #endif + #endif + default: return; + } + + target += ExtUI::getAxisPosition_mm(target_extruder); + ExtUI::setAxisPosition_mm(target, target_extruder); + skipVP = var.VP; +} + +#if ENABLED(DGUS_UI_MOVE_DIS_OPTION) + void DGUSScreenHandler::HandleManualMoveOption(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("HandleManualMoveOption"); + *(uint16_t*)var.memadr = swap16(*(uint16_t*)val_ptr); + } +#endif + +void DGUSScreenHandler::HandleMotorLockUnlock(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("HandleMotorLockUnlock"); + + char buf[4]; + const int16_t lock = swap16(*(uint16_t*)val_ptr); + strcpy_P(buf, lock ? PSTR("M18") : PSTR("M17")); + + //DEBUG_ECHOPAIR(" ", buf); + queue.enqueue_one_now(buf); +} + +void DGUSScreenHandler::HandleSettings(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("HandleSettings"); + uint16_t value = swap16(*(uint16_t*)val_ptr); + switch (value) { + default: break; + case 1: + TERN_(PRINTCOUNTER, print_job_timer.initStats()); + settings.reset(); + settings.save(); + break; + case 2: settings.load(); break; + case 3: settings.save(); break; + } +} + +void DGUSScreenHandler::HandleStepPerMMChanged(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("HandleStepPerMMChanged"); + + uint16_t value_raw = swap16(*(uint16_t*)val_ptr); + DEBUG_ECHOLNPAIR("value_raw:", value_raw); + float value = (float)value_raw / 10; + ExtUI::axis_t axis; + switch (var.VP) { + case VP_X_STEP_PER_MM: axis = ExtUI::axis_t::X; break; + case VP_Y_STEP_PER_MM: axis = ExtUI::axis_t::Y; break; + case VP_Z_STEP_PER_MM: axis = ExtUI::axis_t::Z; break; + default: return; + } + DEBUG_ECHOLNPAIR_F("value:", value); + ExtUI::setAxisSteps_per_mm(value, axis); + DEBUG_ECHOLNPAIR_F("value_set:", ExtUI::getAxisSteps_per_mm(axis)); + skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel + return; +} + +void DGUSScreenHandler::HandleStepPerMMExtruderChanged(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("HandleStepPerMMExtruderChanged"); + + uint16_t value_raw = swap16(*(uint16_t*)val_ptr); + DEBUG_ECHOLNPAIR("value_raw:", value_raw); + float value = (float)value_raw / 10; + ExtUI::extruder_t extruder; + switch (var.VP) { + default: return; + #if HAS_EXTRUDERS + case VP_E0_STEP_PER_MM: extruder = ExtUI::extruder_t::E0; break; + #if HAS_MULTI_EXTRUDER + case VP_E1_STEP_PER_MM: extruder = ExtUI::extruder_t::E1; break; + #endif + #endif + } + DEBUG_ECHOLNPAIR_F("value:", value); + ExtUI::setAxisSteps_per_mm(value, extruder); + DEBUG_ECHOLNPAIR_F("value_set:", ExtUI::getAxisSteps_per_mm(extruder)); + skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel +} + +#if HAS_PID_HEATING + void DGUSScreenHandler::HandlePIDAutotune(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("HandlePIDAutotune"); + + char buf[32] = {0}; + + switch (var.VP) { + default: break; + #if ENABLED(PIDTEMP) + #if HAS_HOTEND + case VP_PID_AUTOTUNE_E0: // Autotune Extruder 0 + sprintf_P(buf, PSTR("M303 E%d C5 S210 U1"), ExtUI::extruder_t::E0); + break; + #endif + #if HOTENDS >= 2 + case VP_PID_AUTOTUNE_E1: + sprintf_P(buf, PSTR("M303 E%d C5 S210 U1"), ExtUI::extruder_t::E1); + break; + #endif + #endif + #if ENABLED(PIDTEMPBED) + case VP_PID_AUTOTUNE_BED: + strcpy_P(buf, PSTR("M303 E-1 C5 S70 U1")); + break; + #endif + } + + if (buf[0]) queue.enqueue_one_now(buf); + + #if ENABLED(DGUS_UI_WAITING) + sendinfoscreen(PSTR("PID is autotuning"), PSTR("please wait"), NUL_STR, NUL_STR, true, true, true, true); + GotoScreen(DGUSLCD_SCREEN_WAITING); + #endif + } +#endif // HAS_PID_HEATING + +#if HAS_BED_PROBE + void DGUSScreenHandler::HandleProbeOffsetZChanged(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("HandleProbeOffsetZChanged"); + + const float offset = float(int16_t(swap16(*(uint16_t*)val_ptr))) / 100.0f; + ExtUI::setZOffset_mm(offset); + skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel + return; + } +#endif + +#if HAS_FAN + void DGUSScreenHandler::HandleFanControl(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("HandleFanControl"); + *(uint8_t*)var.memadr = *(uint8_t*)var.memadr > 0 ? 0 : 255; + } +#endif + +void DGUSScreenHandler::HandleHeaterControl(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("HandleHeaterControl"); + + uint8_t preheat_temp = 0; + switch (var.VP) { + #if HAS_HOTEND + case VP_E0_CONTROL: + #if HOTENDS >= 2 + case VP_E1_CONTROL: + #if HOTENDS >= 3 + case VP_E2_CONTROL: + #endif + #endif + preheat_temp = PREHEAT_1_TEMP_HOTEND; + break; + #endif + + case VP_BED_CONTROL: + preheat_temp = PREHEAT_1_TEMP_BED; + break; + } + + *(int16_t*)var.memadr = *(int16_t*)var.memadr > 0 ? 0 : preheat_temp; +} + +#if ENABLED(DGUS_PREHEAT_UI) + + void DGUSScreenHandler::HandlePreheat(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("HandlePreheat"); + + uint8_t e_temp = 0; + #if HAS_HEATED_BED + uint8_t bed_temp = 0; + #endif + const uint16_t preheat_option = swap16(*(uint16_t*)val_ptr); + switch (preheat_option) { + default: + case 0: // Preheat PLA + #if defined(PREHEAT_1_TEMP_HOTEND) && defined(PREHEAT_1_TEMP_BED) + e_temp = PREHEAT_1_TEMP_HOTEND; + TERN_(HAS_HEATED_BED, bed_temp = PREHEAT_1_TEMP_BED); + #endif + break; + case 1: // Preheat ABS + #if defined(PREHEAT_2_TEMP_HOTEND) && defined(PREHEAT_2_TEMP_BED) + e_temp = PREHEAT_2_TEMP_HOTEND; + TERN_(HAS_HEATED_BED, bed_temp = PREHEAT_2_TEMP_BED); + #endif + break; + case 2: // Preheat PET + #if defined(PREHEAT_3_TEMP_HOTEND) && defined(PREHEAT_3_TEMP_BED) + e_temp = PREHEAT_3_TEMP_HOTEND; + TERN_(HAS_HEATED_BED, bed_temp = PREHEAT_3_TEMP_BED); + #endif + break; + case 3: // Preheat FLEX + #if defined(PREHEAT_4_TEMP_HOTEND) && defined(PREHEAT_4_TEMP_BED) + e_temp = PREHEAT_4_TEMP_HOTEND; + TERN_(HAS_HEATED_BED, bed_temp = PREHEAT_4_TEMP_BED); + #endif + break; + case 7: break; // Custom preheat + case 9: break; // Cool down + } + + switch (var.VP) { + default: return; + #if HAS_HOTEND + case VP_E0_BED_PREHEAT: + thermalManager.setTargetHotend(e_temp, 0); + TERN_(HAS_HEATED_BED, thermalManager.setTargetBed(bed_temp)); + break; + #endif + #if HOTENDS >= 2 + case VP_E1_BED_PREHEAT: + thermalManager.setTargetHotend(e_temp, 1); + TERN_(HAS_HEATED_BED, thermalManager.setTargetBed(bed_temp)); + break; + #endif + } + + // Go to the preheat screen to show the heating progress + GotoScreen(DGUSLCD_SCREEN_PREHEAT); + } + +#endif // DGUS_PREHEAT_UI + +#if ENABLED(POWER_LOSS_RECOVERY) + + void DGUSScreenHandler::HandlePowerLossRecovery(DGUS_VP_Variable &var, void *val_ptr) { + uint16_t value = swap16(*(uint16_t*)val_ptr); + if (value) { + queue.inject_P(PSTR("M1000")); + dgusdisplay.WriteVariable(VP_SD_Print_Filename, filelist.filename(), 32, true); + GotoScreen(PLR_SCREEN_RECOVER); + } + else { + recovery.cancel(); + GotoScreen(PLR_SCREEN_CANCEL); + } + } + +#endif + +void DGUSScreenHandler::UpdateNewScreen(DGUSLCD_Screens newscreen, bool popup) { + DEBUG_ECHOLNPAIR("SetNewScreen: ", newscreen); + if (!popup) { + memmove(&past_screens[1], &past_screens[0], sizeof(past_screens) - 1); + past_screens[0] = current_screen; + } + current_screen = newscreen; + skipVP = 0; + ForceCompleteUpdate(); +} + +void DGUSScreenHandler::PopToOldScreen() { + DEBUG_ECHOLNPAIR("PopToOldScreen s=", past_screens[0]); + GotoScreen(past_screens[0], true); + memmove(&past_screens[0], &past_screens[1], sizeof(past_screens) - 1); + past_screens[sizeof(past_screens) - 1] = DGUSLCD_SCREEN_MAIN; +} + +void DGUSScreenHandler::UpdateScreenVPData() { + DEBUG_ECHOPAIR(" UpdateScreenVPData Screen: ", current_screen); + + const uint16_t *VPList = DGUSLCD_FindScreenVPMapList(current_screen); + if (!VPList) { + DEBUG_ECHOLNPAIR(" NO SCREEN FOR: ", current_screen); + ScreenComplete = true; + return; // nothing to do, likely a bug or boring screen. + } + + // Round-robin updating of all VPs. + VPList += update_ptr; + + bool sent_one = false; + do { + uint16_t VP = pgm_read_word(VPList); + DEBUG_ECHOPAIR(" VP: ", VP); + if (!VP) { + update_ptr = 0; + DEBUG_ECHOLNPGM(" UpdateScreenVPData done"); + ScreenComplete = true; + return; // Screen completed. + } + + if (VP == skipVP) { skipVP = 0; continue; } + + DGUS_VP_Variable rcpy; + if (populate_VPVar(VP, &rcpy)) { + uint8_t expected_tx = 6 + rcpy.size; // expected overhead is 6 bytes + payload. + // Send the VP to the display, but try to avoid overrunning the Tx Buffer. + // But send at least one VP, to avoid getting stalled. + if (rcpy.send_to_display_handler && (!sent_one || expected_tx <= dgusdisplay.GetFreeTxBuffer())) { + //DEBUG_ECHOPAIR(" calling handler for ", rcpy.VP); + sent_one = true; + rcpy.send_to_display_handler(rcpy); + } + else { + // auto x=dgusdisplay.GetFreeTxBuffer(); + //DEBUG_ECHOLNPAIR(" tx almost full: ", x); + //DEBUG_ECHOPAIR(" update_ptr ", update_ptr); + ScreenComplete = false; + return; // please call again! + } + } + + } while (++update_ptr, ++VPList, true); +} + +void DGUSScreenHandler::GotoScreen(DGUSLCD_Screens screen, bool ispopup) { + dgusdisplay.RequestScreen(screen); + UpdateNewScreen(screen, ispopup); +} + +void DGUSDisplay::RequestScreen(DGUSLCD_Screens screen) { + DEBUG_ECHOLNPAIR("GotoScreen ", screen); + const unsigned char gotoscreen[] = { 0x5A, 0x01, (unsigned char) (screen >> 8U), (unsigned char) (screen & 0xFFU) }; + WriteVariable(0x84, gotoscreen, sizeof(gotoscreen)); +} + +#endif // HAS_DGUS_LCD diff --git a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.h new file mode 100644 index 000000000000..8ee2761c899b --- /dev/null +++ b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.h @@ -0,0 +1,76 @@ +/** + * 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 + +/** + * lcd/extui/dgus/DGUSScreenHandler.h + */ + +#include "../../../inc/MarlinConfigPre.h" + +#include "../ui_api.h" + +#if ENABLED(DGUS_FILAMENT_LOADUNLOAD) + + typedef struct { + ExtUI::extruder_t extruder; // which extruder to operate + uint8_t action; // load or unload + bool heated; // heating done ? + float purge_length; // the length to extrude before unload, prevent filament jam + } filament_data_t; + + extern filament_data_t filament_data; + +#endif + +// endianness swap +inline uint16_t swap16(const uint16_t value) { return (value & 0xFFU) << 8U | (value >> 8U); } + +#if ENABLED(DGUS_LCD_UI_ORIGIN) + #include "origin/DGUSScreenHandler.h" +#elif ENABLED(DGUS_LCD_UI_MKS) + #include "mks/DGUSScreenHandler.h" +#elif ENABLED(DGUS_LCD_UI_FYSETC) + #include "fysetc/DGUSScreenHandler.h" +#elif ENABLED(DGUS_LCD_UI_HIPRECY) + #include "hiprecy/DGUSScreenHandler.h" +#endif + +extern DGUSScreenHandler ScreenHandler; + +// Helper to define a DGUS_VP_Variable for common use-cases. +#define VPHELPER(VPADR, VPADRVAR, RXFPTR, TXFPTR) { \ + .VP = VPADR, \ + .memadr = VPADRVAR, \ + .size = sizeof(VPADRVAR), \ + .set_by_display_handler = RXFPTR, \ + .send_to_display_handler = TXFPTR \ +} + +// Helper to define a DGUS_VP_Variable when the size of the var cannot be determined automatically (e.g., a string) +#define VPHELPER_STR(VPADR, VPADRVAR, STRLEN, RXFPTR, TXFPTR) { \ + .VP = VPADR, \ + .memadr = VPADRVAR, \ + .size = STRLEN, \ + .set_by_display_handler = RXFPTR, \ + .send_to_display_handler = TXFPTR \ +} diff --git a/Marlin/src/lcd/extui/lib/dgus/DGUSVPVariable.h b/Marlin/src/lcd/extui/dgus/DGUSVPVariable.h similarity index 100% rename from Marlin/src/lcd/extui/lib/dgus/DGUSVPVariable.h rename to Marlin/src/lcd/extui/dgus/DGUSVPVariable.h diff --git a/Marlin/src/lcd/extui/dgus/dgus_extui.cpp b/Marlin/src/lcd/extui/dgus/dgus_extui.cpp new file mode 100644 index 000000000000..55546caaf157 --- /dev/null +++ b/Marlin/src/lcd/extui/dgus/dgus_extui.cpp @@ -0,0 +1,160 @@ +/** + * 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 . + * + */ + +/** + * lcd/extui/dgus/dgus_extui.cpp + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_DGUS_LCD + +#include "../ui_api.h" +#include "DGUSDisplay.h" +#include "DGUSDisplayDef.h" +#include "DGUSScreenHandler.h" + +namespace ExtUI { + + void onStartup() { + dgusdisplay.InitDisplay(); + ScreenHandler.UpdateScreenVPData(); + } + + void onIdle() { ScreenHandler.loop(); } + + void onPrinterKilled(PGM_P const error, PGM_P const component) { + ScreenHandler.sendinfoscreen(GET_TEXT(MSG_HALTED), error, NUL_STR, GET_TEXT(MSG_PLEASE_RESET), true, true, true, true); + ScreenHandler.GotoScreen(DGUSLCD_SCREEN_KILL); + 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 onPlayTone(const uint16_t frequency, const uint16_t duration) {} + void onPrintTimerStarted() {} + void onPrintTimerPaused() {} + void onPrintTimerStopped() {} + void onFilamentRunout(const extruder_t extruder) {} + + void onUserConfirmRequired(const char * const msg) { + if (msg) { + ScreenHandler.sendinfoscreen(PSTR("Please confirm."), nullptr, msg, nullptr, true, true, false, true); + ScreenHandler.SetupConfirmAction(setUserConfirmed); + ScreenHandler.GotoScreen(DGUSLCD_SCREEN_POPUP); + } + else if (ScreenHandler.getCurrentScreen() == DGUSLCD_SCREEN_POPUP ) { + ScreenHandler.SetupConfirmAction(nullptr); + ScreenHandler.PopToOldScreen(); + } + } + + void onStatusChanged(const char * const msg) { ScreenHandler.setstatusmessage(msg); } + + void onHomingStart() {} + void onHomingComplete() {} + void onPrintFinished() {} + + void onFactoryReset() {} + + void onStoreSettings(char *buff) { + // Called when saving to EEPROM (i.e. M500). If the ExtUI needs + // permanent data to be stored, it can write up to eeprom_data_size bytes + // into buff. + + // Example: + // static_assert(sizeof(myDataStruct) <= eeprom_data_size); + // memcpy(buff, &myDataStruct, sizeof(myDataStruct)); + } + + void onLoadSettings(const char *buff) { + // Called while loading settings from EEPROM. If the ExtUI + // needs to retrieve data, it should copy up to eeprom_data_size bytes + // from buff + + // Example: + // static_assert(sizeof(myDataStruct) <= eeprom_data_size); + // memcpy(&myDataStruct, buff, sizeof(myDataStruct)); + } + + void onPostprocessSettings() { + // Called after loading or resetting stored settings + } + + void onConfigurationStoreWritten(bool success) { + // Called after the entire EEPROM has been written, + // whether successful or not. + } + + void onConfigurationStoreRead(bool success) { + // Called after the entire EEPROM has been read, + // whether successful or not. + } + + #if HAS_MESH + void onMeshLevelingStart() {} + + void onMeshUpdate(const int8_t xpos, const int8_t ypos, const_float_t zval) { + // Called when any mesh points are updated + } + + void onMeshUpdate(const int8_t xpos, const int8_t ypos, const probe_state_t state) { + // Called to indicate a special condition + } + #endif + + #if ENABLED(POWER_LOSS_RECOVERY) + void onPowerLossResume() { + // Called on resume from power-loss + IF_DISABLED(DGUS_LCD_UI_MKS, ScreenHandler.GotoScreen(DGUSLCD_SCREEN_POWER_LOSS)); + } + #endif + + #if HAS_PID_HEATING + void onPidTuning(const result_t rst) { + // Called for temperature PID tuning result + switch (rst) { + case PID_BAD_EXTRUDER_NUM: + ScreenHandler.setstatusmessagePGM(GET_TEXT(MSG_PID_BAD_EXTRUDER_NUM)); + break; + case PID_TEMP_TOO_HIGH: + ScreenHandler.setstatusmessagePGM(GET_TEXT(MSG_PID_TEMP_TOO_HIGH)); + break; + case PID_TUNING_TIMEOUT: + ScreenHandler.setstatusmessagePGM(GET_TEXT(MSG_PID_TIMEOUT)); + break; + case PID_DONE: + ScreenHandler.setstatusmessagePGM(GET_TEXT(MSG_PID_AUTOTUNE_DONE)); + break; + case PID_STARTED: break; + } + ScreenHandler.GotoScreen(DGUSLCD_SCREEN_MAIN); + } + #endif + + void onSteppersDisabled() {} + void onSteppersEnabled() {} +} + +#endif // HAS_DGUS_LCD diff --git a/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp new file mode 100644 index 000000000000..d73a7ea552a6 --- /dev/null +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp @@ -0,0 +1,478 @@ +/** + * 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 . + * + */ + +/* DGUS VPs changed by George Fu in 2019 for Marlin */ + +#include "../../../../inc/MarlinConfigPre.h" + +#if ENABLED(DGUS_LCD_UI_FYSETC) + +#include "DGUSDisplayDef.h" +#include "../DGUSDisplay.h" +#include "../DGUSScreenHandler.h" + +#include "../../../../module/temperature.h" +#include "../../../../module/motion.h" +#include "../../../../module/planner.h" + +#include "../../ui_api.h" +#include "../../../marlinui.h" + +#if ENABLED(DGUS_UI_MOVE_DIS_OPTION) + uint16_t distanceToMove = 10; +#endif + +const uint16_t VPList_Boot[] PROGMEM = { + VP_MARLIN_VERSION, + 0x0000 +}; + +const uint16_t VPList_Main[] PROGMEM = { + // VP_M117, for completeness, but it cannot be auto-uploaded. + #if HAS_HOTEND + VP_T_E0_Is, VP_T_E0_Set, VP_E0_STATUS, + #endif + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif + #if HAS_HEATED_BED + VP_T_Bed_Is, VP_T_Bed_Set, VP_BED_STATUS, + #endif + #if HAS_FAN + VP_Fan0_Percentage, VP_FAN0_STATUS, + #endif + VP_XPos, VP_YPos, VP_ZPos, + VP_Fan0_Percentage, + VP_Feedrate_Percentage, + #if ENABLED(LCD_SET_PROGRESS_MANUALLY) + VP_PrintProgress_Percentage, + #endif + 0x0000 +}; + +const uint16_t VPList_Temp[] PROGMEM = { + #if HAS_HOTEND + VP_T_E0_Is, VP_T_E0_Set, + #endif + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif + #if HAS_HEATED_BED + VP_T_Bed_Is, VP_T_Bed_Set, + #endif + 0x0000 +}; + +const uint16_t VPList_Status[] PROGMEM = { + // VP_M117, for completeness, but it cannot be auto-uploaded + #if HAS_HOTEND + VP_T_E0_Is, VP_T_E0_Set, + #endif + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif + #if HAS_HEATED_BED + VP_T_Bed_Is, VP_T_Bed_Set, + #endif + #if HAS_FAN + VP_Fan0_Percentage, + #endif + VP_XPos, VP_YPos, VP_ZPos, + VP_Fan0_Percentage, + VP_Feedrate_Percentage, + VP_PrintProgress_Percentage, + 0x0000 +}; + +const uint16_t VPList_Status2[] PROGMEM = { + // VP_M117, for completeness, but it cannot be auto-uploaded + #if HAS_HOTEND + VP_Flowrate_E0, + #if HAS_MULTI_EXTRUDER + VP_Flowrate_E1, + #endif + #endif + VP_PrintProgress_Percentage, + VP_PrintTime, + 0x0000 +}; + +const uint16_t VPList_Preheat[] PROGMEM = { + #if HAS_HOTEND + VP_T_E0_Is, VP_T_E0_Set, + #endif + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif + #if HAS_HEATED_BED + VP_T_Bed_Is, VP_T_Bed_Set, + #endif + 0x0000 +}; + +const uint16_t VPList_ManualMove[] PROGMEM = { + VP_XPos, VP_YPos, VP_ZPos, + 0x0000 +}; + +const uint16_t VPList_ManualExtrude[] PROGMEM = { + #if HAS_HOTEND + VP_T_E0_Is, VP_T_E0_Set, + #if HAS_MULTI_EXTRUDER + VP_T_E1_Is, VP_T_E1_Set, + #endif + #endif + VP_EPos, + 0x0000 +}; + +const uint16_t VPList_FanAndFeedrate[] PROGMEM = { + VP_Feedrate_Percentage, VP_Fan0_Percentage, + 0x0000 +}; + +const uint16_t VPList_SD_FlowRates[] PROGMEM = { + VP_Flowrate_E0, VP_Flowrate_E1, + 0x0000 +}; + +const uint16_t VPList_Filament_heating[] PROGMEM = { + #if HAS_HOTEND + VP_T_E0_Is, VP_T_E0_Set, + VP_E0_FILAMENT_LOAD_UNLOAD, + #if HAS_MULTI_EXTRUDER + VP_T_E1_Is, VP_T_E1_Set, + VP_E1_FILAMENT_LOAD_UNLOAD, + #endif + #endif + 0x0000 +}; + +const uint16_t VPList_Filament_load_unload[] PROGMEM = { + #if HAS_HOTEND + VP_E0_FILAMENT_LOAD_UNLOAD, + #if HAS_MULTI_EXTRUDER + VP_E1_FILAMENT_LOAD_UNLOAD, + #endif + #endif + 0x0000 +}; + +const uint16_t VPList_SDFileList[] PROGMEM = { + VP_SD_FileName0, VP_SD_FileName1, VP_SD_FileName2, VP_SD_FileName3, VP_SD_FileName4, + 0x0000 +}; + +const uint16_t VPList_SD_PrintManipulation[] PROGMEM = { + VP_PrintProgress_Percentage, VP_PrintTime, + #if HAS_HOTEND + VP_T_E0_Is, VP_T_E0_Set, + #endif + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif + #if HAS_HEATED_BED + VP_T_Bed_Is, VP_T_Bed_Set, + #endif + #if HAS_FAN + VP_Fan0_Percentage, + #if FAN_COUNT > 1 + VP_Fan1_Percentage, + #endif + #endif + VP_Flowrate_E0, + 0x0000 +}; + +const uint16_t VPList_SDPrintTune[] PROGMEM = { + #if HAS_HOTEND + VP_T_E0_Is, VP_T_E0_Set, VP_Flowrate_E0, + #if HAS_MULTI_EXTRUDER + VP_T_E1_Is, VP_T_E1_Set, VP_Flowrate_E1, // ERROR: Flowrate is per-extruder, not per-hotend + #endif + #endif + #if HAS_HEATED_BED + VP_T_Bed_Is, VP_T_Bed_Set, + #endif + VP_Feedrate_Percentage, + VP_SD_Print_ProbeOffsetZ, + 0x0000 +}; + +const uint16_t VPList_StepPerMM[] PROGMEM = { + VP_X_STEP_PER_MM, + VP_Y_STEP_PER_MM, + VP_Z_STEP_PER_MM, + #if HAS_EXTRUDERS + VP_E0_STEP_PER_MM, + #if HAS_MULTI_EXTRUDER + VP_E1_STEP_PER_MM, + #endif + #endif + 0x0000 +}; + +const uint16_t VPList_PIDE0[] PROGMEM = { + #if ENABLED(PIDTEMP) + VP_E0_PID_P, + VP_E0_PID_I, + VP_E0_PID_D, + #endif + 0x0000 +}; + +const uint16_t VPList_PIDBED[] PROGMEM = { + #if ENABLED(PIDTEMP) + VP_BED_PID_P, + VP_BED_PID_I, + VP_BED_PID_D, + #endif + 0x0000 +}; + +const uint16_t VPList_Infos[] PROGMEM = { + VP_MARLIN_VERSION, + VP_PrintTime, + #if ENABLED(PRINTCOUNTER) + VP_PrintAccTime, + VP_PrintsTotal, + #endif + 0x0000 +}; + +const uint16_t VPList_PIDTuningWaiting[] PROGMEM = { + VP_WAITING_STATUS, + 0x0000 +}; + +const uint16_t VPList_FLCPreheat[] PROGMEM = { + #if HAS_HOTEND + VP_T_E0_Is, VP_T_E0_Set, + #endif + #if HAS_HEATED_BED + VP_T_Bed_Is, VP_T_Bed_Set, + #endif + 0x0000 +}; + +const uint16_t VPList_FLCPrinting[] PROGMEM = { + #if HAS_HOTEND + VP_SD_Print_ProbeOffsetZ, + #endif + 0x0000 +}; + +const uint16_t VPList_Z_Offset[] PROGMEM = { + #if HAS_HOTEND + VP_SD_Print_ProbeOffsetZ, + #endif + 0x0000 +}; + +const struct VPMapping VPMap[] PROGMEM = { + { DGUSLCD_SCREEN_BOOT, VPList_Boot }, + { DGUSLCD_SCREEN_MAIN, VPList_Main }, + { DGUSLCD_SCREEN_TEMPERATURE, VPList_Temp }, + { DGUSLCD_SCREEN_STATUS, VPList_Status }, + { DGUSLCD_SCREEN_STATUS2, VPList_Status2 }, + { DGUSLCD_SCREEN_PREHEAT, VPList_Preheat }, + { DGUSLCD_SCREEN_MANUALMOVE, VPList_ManualMove }, + { DGUSLCD_SCREEN_MANUALEXTRUDE, VPList_ManualExtrude }, + { DGUSLCD_SCREEN_FILAMENT_HEATING, VPList_Filament_heating }, + { DGUSLCD_SCREEN_FILAMENT_LOADING, VPList_Filament_load_unload }, + { DGUSLCD_SCREEN_FILAMENT_UNLOADING, VPList_Filament_load_unload }, + { DGUSLCD_SCREEN_SDPRINTMANIPULATION, VPList_SD_PrintManipulation }, + { DGUSLCD_SCREEN_SDFILELIST, VPList_SDFileList }, + { DGUSLCD_SCREEN_SDPRINTTUNE, VPList_SDPrintTune }, + { DGUSLCD_SCREEN_WAITING, VPList_PIDTuningWaiting }, + { DGUSLCD_SCREEN_FLC_PREHEAT, VPList_FLCPreheat }, + { DGUSLCD_SCREEN_FLC_PRINTING, VPList_FLCPrinting }, + { DGUSLCD_SCREEN_Z_OFFSET, VPList_Z_Offset }, + { DGUSLCD_SCREEN_STEPPERMM, VPList_StepPerMM }, + { DGUSLCD_SCREEN_PID_E, VPList_PIDE0 }, + { DGUSLCD_SCREEN_PID_BED, VPList_PIDBED }, + { DGUSLCD_SCREEN_INFOS, VPList_Infos }, + { 0 , nullptr } // List is terminated with an nullptr as table entry. +}; + +const char MarlinVersion[] PROGMEM = SHORT_BUILD_VERSION; + +const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { + // Helper to detect touch events + VPHELPER(VP_SCREENCHANGE, nullptr, ScreenHandler.ScreenChangeHook, nullptr), + VPHELPER(VP_SCREENCHANGE_ASK, nullptr, ScreenHandler.ScreenChangeHookIfIdle, nullptr), + #if ENABLED(SDSUPPORT) + VPHELPER(VP_SCREENCHANGE_WHENSD, nullptr, ScreenHandler.ScreenChangeHookIfSD, nullptr), + #endif + VPHELPER(VP_CONFIRMED, nullptr, ScreenHandler.ScreenConfirmedOK, nullptr), + + VPHELPER(VP_TEMP_ALL_OFF, nullptr, ScreenHandler.HandleAllHeatersOff, nullptr), + #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) + VPHELPER(VP_MOVE_OPTION, &distanceToMove, ScreenHandler.HandleManualMoveOption, nullptr), + #endif + #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) + VPHELPER(VP_MOVE_X, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Y, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Z, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_HOME_ALL, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), + #else + VPHELPER(VP_MOVE_X, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Y, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Z, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_HOME_ALL, nullptr, ScreenHandler.HandleManualMove, nullptr), + #endif + VPHELPER(VP_MOTOR_LOCK_UNLOK, nullptr, ScreenHandler.HandleMotorLockUnlock, nullptr), + #if ENABLED(POWER_LOSS_RECOVERY) + VPHELPER(VP_POWER_LOSS_RECOVERY, nullptr, ScreenHandler.HandlePowerLossRecovery, nullptr), + #endif + VPHELPER(VP_SETTINGS, nullptr, ScreenHandler.HandleSettings, nullptr), + #if ENABLED(SINGLE_Z_CALIBRATION) + VPHELPER(VP_Z_CALIBRATE, nullptr, ScreenHandler.HandleZCalibration, nullptr), + #endif + + #if ENABLED(FIRST_LAYER_CAL) + VPHELPER(VP_Z_FIRST_LAYER_CAL, nullptr, ScreenHandler.HandleFirstLayerCal, nullptr), + #endif + + { .VP = VP_MARLIN_VERSION, .memadr = (void*)MarlinVersion, .size = VP_MARLIN_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + // M117 LCD String (We don't need the string in memory but "just" push it to the display on demand, hence the nullptr + { .VP = VP_M117, .memadr = nullptr, .size = VP_M117_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplay }, + + // Temperature Data + #if HAS_HOTEND + VPHELPER(VP_T_E0_Is, &thermalManager.temp_hotend[0].celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), + VPHELPER(VP_T_E0_Set, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Flowrate_E0, &planner.flow_percentage[ExtUI::extruder_t::E0], ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_EPos, &destination.e, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_MOVE_E0, nullptr, ScreenHandler.HandleManualExtrude, nullptr), + VPHELPER(VP_E0_CONTROL, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_E0_STATUS, &thermalManager.temp_hotend[0].target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + #if ENABLED(DGUS_PREHEAT_UI) + VPHELPER(VP_E0_BED_PREHEAT, nullptr, ScreenHandler.HandlePreheat, nullptr), + #endif + #if ENABLED(PIDTEMP) + VPHELPER(VP_E0_PID_P, &thermalManager.temp_hotend[0].pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), + VPHELPER(VP_E0_PID_I, &thermalManager.temp_hotend[0].pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), + VPHELPER(VP_E0_PID_D, &thermalManager.temp_hotend[0].pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), + VPHELPER(VP_PID_AUTOTUNE_E0, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), + #endif + #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) + VPHELPER(VP_E0_FILAMENT_LOAD_UNLOAD, nullptr, ScreenHandler.HandleFilamentOption, ScreenHandler.HandleFilamentLoadUnload), + #endif + #endif + #if HOTENDS >= 2 + VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), + VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Flowrate_E1, &planner.flow_percentage[ExtUI::extruder_t::E1], ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), // ERROR: Flow is per-extruder, not per-hotend + VPHELPER(VP_MOVE_E1, nullptr, ScreenHandler.HandleManualExtrude, nullptr), + VPHELPER(VP_E1_CONTROL, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_E1_STATUS, &thermalManager.temp_hotend[1].target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + #if ENABLED(PIDTEMP) + VPHELPER(VP_PID_AUTOTUNE_E1, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), + #endif + VPHELPER(VP_E1_FILAMENT_LOAD_UNLOAD, nullptr, ScreenHandler.HandleFilamentOption, ScreenHandler.HandleFilamentLoadUnload), + #endif + #if HAS_HEATED_BED + VPHELPER(VP_T_Bed_Is, &thermalManager.temp_bed.celsius, nullptr, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_T_Bed_Set, &thermalManager.temp_bed.target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_BED_CONTROL, &thermalManager.temp_bed.target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_BED_STATUS, &thermalManager.temp_bed.target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + #if ENABLED(PIDTEMPBED) + VPHELPER(VP_BED_PID_P, &thermalManager.temp_bed.pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), + VPHELPER(VP_BED_PID_I, &thermalManager.temp_bed.pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), + VPHELPER(VP_BED_PID_D, &thermalManager.temp_bed.pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), + VPHELPER(VP_PID_AUTOTUNE_BED, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), + #endif + #endif + + // Fan Data + #if HAS_FAN + #define FAN_VPHELPER(N) \ + VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], ScreenHandler.DGUSLCD_PercentageToUint8, ScreenHandler.DGUSLCD_SendPercentageToDisplay), \ + VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], ScreenHandler.HandleFanControl, nullptr), \ + VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, ScreenHandler.DGUSLCD_SendFanStatusToDisplay), + REPEAT(FAN_COUNT, FAN_VPHELPER) + #endif + + // Feedrate + VPHELPER(VP_Feedrate_Percentage, &feedrate_percentage, ScreenHandler.DGUSLCD_SetValueDirectly, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + + // Position Data + VPHELPER(VP_XPos, ¤t_position.x, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_YPos, ¤t_position.y, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_ZPos, ¤t_position.z, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), + + // Print Progress + VPHELPER(VP_PrintProgress_Percentage, nullptr, nullptr, ScreenHandler.DGUSLCD_SendPrintProgressToDisplay), + + // Print Time + VPHELPER_STR(VP_PrintTime, nullptr, VP_PrintTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintTimeToDisplay), + #if ENABLED(PRINTCOUNTER) + VPHELPER_STR(VP_PrintAccTime, nullptr, VP_PrintAccTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintAccTimeToDisplay), + VPHELPER_STR(VP_PrintsTotal, nullptr, VP_PrintsTotal_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintsTotalToDisplay), + #endif + + VPHELPER(VP_X_STEP_PER_MM, &planner.settings.axis_steps_per_mm[X_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + VPHELPER(VP_Y_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Y_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + VPHELPER(VP_Z_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Z_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + #if HAS_EXTRUDERS + VPHELPER(VP_E0_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(0)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + #if HAS_MULTI_EXTRUDER + VPHELPER(VP_E1_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(1)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + #endif + #endif + + // SDCard File listing. + #if ENABLED(SDSUPPORT) + VPHELPER(VP_SD_ScrollEvent, nullptr, ScreenHandler.DGUSLCD_SD_ScrollFilelist, nullptr), + VPHELPER(VP_SD_FileSelected, nullptr, ScreenHandler.DGUSLCD_SD_FileSelected, nullptr), + VPHELPER(VP_SD_FileSelectConfirm, nullptr, ScreenHandler.DGUSLCD_SD_StartPrint, nullptr), + VPHELPER_STR(VP_SD_FileName0, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), + VPHELPER_STR(VP_SD_FileName1, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), + VPHELPER_STR(VP_SD_FileName2, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), + VPHELPER_STR(VP_SD_FileName3, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), + VPHELPER_STR(VP_SD_FileName4, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), + VPHELPER(VP_SD_ResumePauseAbort, nullptr, ScreenHandler.DGUSLCD_SD_ResumePauseAbort, nullptr), + VPHELPER(VP_SD_AbortPrintConfirmed, nullptr, ScreenHandler.DGUSLCD_SD_ReallyAbort, nullptr), + VPHELPER(VP_SD_Print_Setting, nullptr, ScreenHandler.DGUSLCD_SD_PrintTune, nullptr), + #if HAS_BED_PROBE + VPHELPER(VP_SD_Print_ProbeOffsetZ, &probe.offset.z, ScreenHandler.HandleProbeOffsetZChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<2>), + #if ENABLED(BABYSTEPPING) + VPHELPER(VP_SD_Print_LiveAdjustZ, nullptr, ScreenHandler.HandleLiveAdjustZ, nullptr), + #endif + #endif + #endif + + #if ENABLED(DGUS_UI_WAITING) + VPHELPER(VP_WAITING_STATUS, nullptr, nullptr, ScreenHandler.DGUSLCD_SendWaitingStatusToDisplay), + #endif + + // Messages for the User, shared by the popup and the kill screen. They can't be autouploaded as we do not buffer content. + { .VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + + VPHELPER(0, 0, 0, 0) // must be last entry. +}; + +#endif // DGUS_LCD_UI_FYSETC diff --git a/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.h b/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.h new file mode 100644 index 000000000000..2543d20b7688 --- /dev/null +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.h @@ -0,0 +1,296 @@ +/** + * 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 + +#include "../DGUSDisplayDef.h" + +enum DGUSLCD_Screens : uint8_t { + DGUSLCD_SCREEN_BOOT = 0, + DGUSLCD_SCREEN_MAIN = 1, + DGUSLCD_SCREEN_STATUS = 1, + DGUSLCD_SCREEN_STATUS2 = 1, + DGUSLCD_SCREEN_TEMPERATURE = 10, + DGUSLCD_SCREEN_PREHEAT = 18, + DGUSLCD_SCREEN_POWER_LOSS = 100, + DGUSLCD_SCREEN_MANUALMOVE = 192, + DGUSLCD_SCREEN_UTILITY = 120, + DGUSLCD_SCREEN_FILAMENT_HEATING = 146, + DGUSLCD_SCREEN_FILAMENT_LOADING = 148, + DGUSLCD_SCREEN_FILAMENT_UNLOADING = 158, + DGUSLCD_SCREEN_MANUALEXTRUDE = 160, + DGUSLCD_SCREEN_SDFILELIST = 71, + DGUSLCD_SCREEN_SDPRINTMANIPULATION = 73, + DGUSLCD_SCREEN_SDPRINTTUNE = 75, + DGUSLCD_SCREEN_FLC_PREHEAT = 94, + DGUSLCD_SCREEN_FLC_PRINTING = 96, + DGUSLCD_SCREEN_STEPPERMM = 212, + DGUSLCD_SCREEN_PID_E = 214, + DGUSLCD_SCREEN_PID_BED = 218, + DGUSLCD_SCREEN_Z_OFFSET = 222, + DGUSLCD_SCREEN_INFOS = 36, + DGUSLCD_SCREEN_CONFIRM = 240, + DGUSLCD_SCREEN_KILL = 250, ///< Kill Screen. Must always be 250 (to be able to display "Error wrong LCD Version") + DGUSLCD_SCREEN_WAITING = 251, + DGUSLCD_SCREEN_POPUP = 252, ///< special target, popup screen will also return this code to say "return to previous screen" + DGUSLCD_SCREEN_UNUSED = 255 +}; + +// Display Memory layout used (T5UID) +// Except system variables this is arbitrary, just to organize stuff.... + +// 0x0000 .. 0x0FFF -- System variables and reserved by the display +// 0x1000 .. 0x1FFF -- Variables to never change location, regardless of UI Version +// 0x2000 .. 0x2FFF -- Controls (VPs that will trigger some action) +// 0x3000 .. 0x4FFF -- Marlin Data to be displayed +// 0x5000 .. -- SPs (if we want to modify display elements, e.g change color or like) -- currently unused + +// As there is plenty of space (at least most displays have >8k RAM), we do not pack them too tight, +// so that we can keep variables nicely together in the address space. + +// UI Version always on 0x1000...0x1002 so that the firmware can check this and bail out. +constexpr uint16_t VP_UI_VERSION_MAJOR = 0x1000; // Major -- incremented when incompatible +constexpr uint16_t VP_UI_VERSION_MINOR = 0x1001; // Minor -- incremented on new features, but compatible +constexpr uint16_t VP_UI_VERSION_PATCH = 0x1002; // Patch -- fixed which do not change functionality. +constexpr uint16_t VP_UI_FLAVOUR = 0x1010; // lets reserve 16 bytes here to determine if UI is suitable for this Marlin. tbd. + +// Storage space for the Killscreen messages. 0x1100 - 0x1200 . Reused for the popup. +constexpr uint16_t VP_MSGSTR1 = 0x1100; +constexpr uint8_t VP_MSGSTR1_LEN = 0x20; // might be more place for it... +constexpr uint16_t VP_MSGSTR2 = 0x1140; +constexpr uint8_t VP_MSGSTR2_LEN = 0x20; +constexpr uint16_t VP_MSGSTR3 = 0x1180; +constexpr uint8_t VP_MSGSTR3_LEN = 0x20; +constexpr uint16_t VP_MSGSTR4 = 0x11C0; +constexpr uint8_t VP_MSGSTR4_LEN = 0x20; + +// Screenchange request for screens that only make sense when printer is idle. +// e.g movement is only allowed if printer is not printing. +// Marlin must confirm by setting the screen manually. +constexpr uint16_t VP_SCREENCHANGE_ASK = 0x2000; +constexpr uint16_t VP_SCREENCHANGE = 0x2001; // 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 = 0x2002; // Turn all heaters off. Value arbitrary ;)= +constexpr uint16_t VP_SCREENCHANGE_WHENSD = 0x2003; // "Print" Button touched -- go only there if there is an SD Card. + +constexpr uint16_t VP_CONFIRMED = 0x2010; // OK on confirm screen. + +// Buttons on the SD-Card File listing. +constexpr uint16_t VP_SD_ScrollEvent = 0x2020; // Data: 0 for "up a directory", numbers are the amount to scroll, e.g -1 one up, 1 one down +constexpr uint16_t VP_SD_FileSelected = 0x2022; // Number of file field selected. +constexpr uint16_t VP_SD_FileSelectConfirm = 0x2024; // (This is a virtual VP and emulated by the Confirm Screen when a file has been confirmed) + +constexpr uint16_t VP_SD_ResumePauseAbort = 0x2026; // Resume(Data=0), Pause(Data=1), Abort(Data=2) SD Card prints +constexpr uint16_t VP_SD_AbortPrintConfirmed = 0x2028; // Abort print confirmation (virtual, will be injected by the confirm dialog) +constexpr uint16_t VP_SD_Print_Setting = 0x2040; +constexpr uint16_t VP_SD_Print_LiveAdjustZ = 0x2050; // Data: 0 down, 1 up + +// Controls for movement (we can't use the incremental / decremental feature of the display at this feature works only with 16 bit values +// (which would limit us to 655.35mm, which is likely not a problem for common setups, but i don't want to rule out hangprinters support) +// A word about the coding: The VP will be per axis and the return code will be an signed 16 bit value in 0.01 mm resolution, telling us +// the relative travel amount t he user wants to do. So eg. if the display sends us VP=2100 with value 100, the user wants us to move X by +1 mm. +constexpr uint16_t VP_MOVE_X = 0x2100; +constexpr uint16_t VP_MOVE_Y = 0x2102; +constexpr uint16_t VP_MOVE_Z = 0x2104; +constexpr uint16_t VP_MOVE_E0 = 0x2110; +constexpr uint16_t VP_MOVE_E1 = 0x2112; +//constexpr uint16_t VP_MOVE_E2 = 0x2114; +//constexpr uint16_t VP_MOVE_E3 = 0x2116; +//constexpr uint16_t VP_MOVE_E4 = 0x2118; +//constexpr uint16_t VP_MOVE_E5 = 0x211A; +constexpr uint16_t VP_HOME_ALL = 0x2120; +constexpr uint16_t VP_MOTOR_LOCK_UNLOK = 0x2130; + +// Power loss recovery +constexpr uint16_t VP_POWER_LOSS_RECOVERY = 0x2180; + +// Fan Control Buttons , switch between "off" and "on" +constexpr uint16_t VP_FAN0_CONTROL = 0x2200; +constexpr uint16_t VP_FAN1_CONTROL = 0x2202; +constexpr uint16_t VP_FAN2_CONTROL = 0x2204; +constexpr uint16_t VP_FAN3_CONTROL = 0x2206; + +// Heater Control Buttons , triged between "cool down" and "heat PLA" state +constexpr uint16_t VP_E0_CONTROL = 0x2210; +constexpr uint16_t VP_E1_CONTROL = 0x2212; +//constexpr uint16_t VP_E2_CONTROL = 0x2214; +//constexpr uint16_t VP_E3_CONTROL = 0x2216; +//constexpr uint16_t VP_E4_CONTROL = 0x2218; +//constexpr uint16_t VP_E5_CONTROL = 0x221A; +constexpr uint16_t VP_BED_CONTROL = 0x221C; + +// Preheat +constexpr uint16_t VP_E0_BED_PREHEAT = 0x2220; +constexpr uint16_t VP_E1_BED_PREHEAT = 0x2222; +//constexpr uint16_t VP_E2_BED_PREHEAT = 0x2224; +//constexpr uint16_t VP_E3_BED_PREHEAT = 0x2226; +//constexpr uint16_t VP_E4_BED_PREHEAT = 0x2228; +//constexpr uint16_t VP_E5_BED_PREHEAT = 0x222A; + +// Filament load and unload +constexpr uint16_t VP_E0_FILAMENT_LOAD_UNLOAD = 0x2300; +constexpr uint16_t VP_E1_FILAMENT_LOAD_UNLOAD = 0x2302; + +// Settings store , reset +constexpr uint16_t VP_SETTINGS = 0x2400; + +// PID autotune +constexpr uint16_t VP_PID_AUTOTUNE_E0 = 0x2410; +constexpr uint16_t VP_PID_AUTOTUNE_E1 = 0x2412; +//constexpr uint16_t VP_PID_AUTOTUNE_E2 = 0x2414; +//constexpr uint16_t VP_PID_AUTOTUNE_E3 = 0x2416; +//constexpr uint16_t VP_PID_AUTOTUNE_E4 = 0x2418; +//constexpr uint16_t VP_PID_AUTOTUNE_E5 = 0x241A; +constexpr uint16_t VP_PID_AUTOTUNE_BED = 0x2420; + +// Calibrate Z +constexpr uint16_t VP_Z_CALIBRATE = 0x2430; + +// First layer cal +constexpr uint16_t VP_Z_FIRST_LAYER_CAL = 0x2500; // Data: 0 - Cancel first layer cal progress, >0 filament type have loaded + +// Firmware version on the boot screen. +constexpr uint16_t VP_MARLIN_VERSION = 0x3000; +constexpr uint8_t VP_MARLIN_VERSION_LEN = 16; // there is more space on the display, if needed. + +// Place for status messages. +constexpr uint16_t VP_M117 = 0x3020; +constexpr uint8_t VP_M117_LEN = 0x20; + +// Temperatures. +constexpr uint16_t VP_T_E0_Is = 0x3060; // 4 Byte Integer +constexpr uint16_t VP_T_E0_Set = 0x3062; // 2 Byte Integer +constexpr uint16_t VP_T_E1_Is = 0x3064; // 4 Byte Integer + +// reserved to support up to 6 Extruders: +constexpr uint16_t VP_T_E1_Set = 0x3066; // 2 Byte Integer +//constexpr uint16_t VP_T_E2_Is = 0x3068; // 4 Byte Integer +//constexpr uint16_t VP_T_E2_Set = 0x306A; // 2 Byte Integer +//constexpr uint16_t VP_T_E3_Is = 0x306C; // 4 Byte Integer +//constexpr uint16_t VP_T_E3_Set = 0x306E; // 2 Byte Integer +//constexpr uint16_t VP_T_E4_Is = 0x3070; // 4 Byte Integer +//constexpr uint16_t VP_T_E4_Set = 0x3072; // 2 Byte Integer +//constexpr uint16_t VP_T_E4_Is = 0x3074; // 4 Byte Integer +//constexpr uint16_t VP_T_E4_Set = 0x3076; // 2 Byte Integer +//constexpr uint16_t VP_T_E5_Is = 0x3078; // 4 Byte Integer +//constexpr uint16_t VP_T_E5_Set = 0x307A; // 2 Byte Integer + +constexpr uint16_t VP_T_Bed_Is = 0x3080; // 4 Byte Integer +constexpr uint16_t VP_T_Bed_Set = 0x3082; // 2 Byte Integer + +constexpr uint16_t VP_Flowrate_E0 = 0x3090; // 2 Byte Integer +constexpr uint16_t VP_Flowrate_E1 = 0x3092; // 2 Byte Integer + +// reserved for up to 6 Extruders: +//constexpr uint16_t VP_Flowrate_E2 = 0x3094; +//constexpr uint16_t VP_Flowrate_E3 = 0x3096; +//constexpr uint16_t VP_Flowrate_E4 = 0x3098; +//constexpr uint16_t VP_Flowrate_E5 = 0x309A; + +constexpr uint16_t VP_Fan0_Percentage = 0x3100; // 2 Byte Integer (0..100) +constexpr uint16_t VP_Fan1_Percentage = 0x3102; // 2 Byte Integer (0..100) +constexpr uint16_t VP_Fan2_Percentage = 0x3104; // 2 Byte Integer (0..100) +constexpr uint16_t VP_Fan3_Percentage = 0x3106; // 2 Byte Integer (0..100) +constexpr uint16_t VP_Feedrate_Percentage = 0x3108; // 2 Byte Integer (0..100) + +// Actual Position +constexpr uint16_t VP_XPos = 0x3110; // 4 Byte Fixed point number; format xxx.yy +constexpr uint16_t VP_YPos = 0x3112; // 4 Byte Fixed point number; format xxx.yy +constexpr uint16_t VP_ZPos = 0x3114; // 4 Byte Fixed point number; format xxx.yy + +constexpr uint16_t VP_EPos = 0x3120; // 4 Byte Fixed point number; format xxx.yy + +constexpr uint16_t VP_PrintProgress_Percentage = 0x3130; // 2 Byte Integer (0..100) + +constexpr uint16_t VP_PrintTime = 0x3140; +constexpr uint16_t VP_PrintTime_LEN = 32; + +constexpr uint16_t VP_PrintAccTime = 0x3160; +constexpr uint16_t VP_PrintAccTime_LEN = 32; + +constexpr uint16_t VP_PrintsTotal = 0x3180; +constexpr uint16_t VP_PrintsTotal_LEN = 16; + +// SDCard File Listing +constexpr uint16_t VP_SD_FileName_LEN = 32; // LEN is shared for all entries. +constexpr uint16_t DGUS_SD_FILESPERSCREEN = 5; // FIXME move that info to the display and read it from there. +constexpr uint16_t VP_SD_FileName0 = 0x3200; +constexpr uint16_t VP_SD_FileName1 = 0x3220; +constexpr uint16_t VP_SD_FileName2 = 0x3240; +constexpr uint16_t VP_SD_FileName3 = 0x3260; +constexpr uint16_t VP_SD_FileName4 = 0x3280; + +constexpr uint16_t VP_SD_Print_ProbeOffsetZ = 0x32A0; // +constexpr uint16_t VP_SD_Print_Filename = 0x32C0; + +// Fan status +constexpr uint16_t VP_FAN0_STATUS = 0x3300; +constexpr uint16_t VP_FAN1_STATUS = 0x3302; +constexpr uint16_t VP_FAN2_STATUS = 0x3304; +constexpr uint16_t VP_FAN3_STATUS = 0x3306; + +// Heater status +constexpr uint16_t VP_E0_STATUS = 0x3310; +constexpr uint16_t VP_E1_STATUS = 0x3312; +//constexpr uint16_t VP_E2_STATUS = 0x3314; +//constexpr uint16_t VP_E3_STATUS = 0x3316; +//constexpr uint16_t VP_E4_STATUS = 0x3318; +//constexpr uint16_t VP_E5_STATUS = 0x331A; +constexpr uint16_t VP_BED_STATUS = 0x331C; + +constexpr uint16_t VP_MOVE_OPTION = 0x3400; + +// Step per mm +constexpr uint16_t VP_X_STEP_PER_MM = 0x3600; // at the moment , 2 byte unsigned int , 0~1638.4 +//constexpr uint16_t VP_X2_STEP_PER_MM = 0x3602; +constexpr uint16_t VP_Y_STEP_PER_MM = 0x3604; +//constexpr uint16_t VP_Y2_STEP_PER_MM = 0x3606; +constexpr uint16_t VP_Z_STEP_PER_MM = 0x3608; +//constexpr uint16_t VP_Z2_STEP_PER_MM = 0x360A; +constexpr uint16_t VP_E0_STEP_PER_MM = 0x3610; +constexpr uint16_t VP_E1_STEP_PER_MM = 0x3612; +//constexpr uint16_t VP_E2_STEP_PER_MM = 0x3614; +//constexpr uint16_t VP_E3_STEP_PER_MM = 0x3616; +//constexpr uint16_t VP_E4_STEP_PER_MM = 0x3618; +//constexpr uint16_t VP_E5_STEP_PER_MM = 0x361A; + +// PIDs +constexpr uint16_t VP_E0_PID_P = 0x3700; // at the moment , 2 byte unsigned int , 0~1638.4 +constexpr uint16_t VP_E0_PID_I = 0x3702; +constexpr uint16_t VP_E0_PID_D = 0x3704; +constexpr uint16_t VP_E1_PID_P = 0x3706; // at the moment , 2 byte unsigned int , 0~1638.4 +constexpr uint16_t VP_E1_PID_I = 0x3708; +constexpr uint16_t VP_E1_PID_D = 0x370A; +constexpr uint16_t VP_BED_PID_P = 0x3710; +constexpr uint16_t VP_BED_PID_I = 0x3712; +constexpr uint16_t VP_BED_PID_D = 0x3714; + +// Waiting screen status +constexpr uint16_t VP_WAITING_STATUS = 0x3800; + +// SPs for certain variables... +// located at 0x5000 and up +// Not used yet! +// This can be used e.g to make controls / data display invisible +constexpr uint16_t SP_T_E0_Is = 0x5000; +constexpr uint16_t SP_T_E0_Set = 0x5010; +constexpr uint16_t SP_T_E1_Is = 0x5020; +constexpr uint16_t SP_T_Bed_Is = 0x5030; +constexpr uint16_t SP_T_Bed_Set = 0x5040; diff --git a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp new file mode 100644 index 000000000000..ae6a31fb0571 --- /dev/null +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp @@ -0,0 +1,427 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../../../inc/MarlinConfigPre.h" + +#if ENABLED(DGUS_LCD_UI_FYSETC) + +#include "../DGUSScreenHandler.h" + +#include "../../../../MarlinCore.h" +#include "../../../../gcode/queue.h" +#include "../../../../libs/duration_t.h" +#include "../../../../module/settings.h" +#include "../../../../module/temperature.h" +#include "../../../../module/motion.h" +#include "../../../../module/planner.h" +#include "../../../../module/printcounter.h" +#include "../../../../sd/cardreader.h" + +#if ENABLED(POWER_LOSS_RECOVERY) + #include "../../../../feature/powerloss.h" +#endif + +#if ENABLED(SDSUPPORT) + + static ExtUI::FileList filelist; + + void DGUSScreenHandler::DGUSLCD_SD_FileSelected(DGUS_VP_Variable &var, void *val_ptr) { + uint16_t touched_nr = (int16_t)swap16(*(uint16_t*)val_ptr) + top_file; + if (touched_nr > filelist.count()) return; + if (!filelist.seek(touched_nr)) return; + + if (filelist.isDir()) { + filelist.changeDir(filelist.filename()); + top_file = 0; + ForceCompleteUpdate(); + return; + } + + #if ENABLED(DGUS_PRINT_FILENAME) + // Send print filename + dgusdisplay.WriteVariable(VP_SD_Print_Filename, filelist.filename(), VP_SD_FileName_LEN, true); + #endif + + // Setup Confirmation screen + file_to_print = touched_nr; + + HandleUserConfirmationPopUp(VP_SD_FileSelectConfirm, nullptr, PSTR("Print file"), filelist.filename(), PSTR("from SD Card?"), true, true, false, true); + } + + void DGUSScreenHandler::DGUSLCD_SD_StartPrint(DGUS_VP_Variable &var, void *val_ptr) { + if (!filelist.seek(file_to_print)) return; + ExtUI::printFile(filelist.shortFilename()); + GotoScreen(DGUSLCD_SCREEN_SDPRINTMANIPULATION); + } + + void DGUSScreenHandler::DGUSLCD_SD_ResumePauseAbort(DGUS_VP_Variable &var, void *val_ptr) { + + if (!ExtUI::isPrintingFromMedia()) return; // avoid race condition when user stays in this menu and printer finishes. + switch (swap16(*(uint16_t*)val_ptr)) { + case 0: { // Resume + if (ExtUI::isPrintingFromMediaPaused()) { + ExtUI::resumePrint(); + } + } break; + + case 1: // Pause + + GotoScreen(DGUSLCD_SCREEN_SDPRINTMANIPULATION); + if (!ExtUI::isPrintingFromMediaPaused()) { + ExtUI::pausePrint(); + //ExtUI::mks_pausePrint(); + } + break; + case 2: // Abort + HandleUserConfirmationPopUp(VP_SD_AbortPrintConfirmed, nullptr, PSTR("Abort printing"), filelist.filename(), PSTR("?"), true, true, false, true); + break; + } + } + + void DGUSScreenHandler::DGUSLCD_SD_SendFilename(DGUS_VP_Variable& var) { + uint16_t target_line = (var.VP - VP_SD_FileName0) / VP_SD_FileName_LEN; + if (target_line > DGUS_SD_FILESPERSCREEN) return; + char tmpfilename[VP_SD_FileName_LEN + 1] = ""; + var.memadr = (void*)tmpfilename; + + if (filelist.seek(top_file + target_line)) { + snprintf_P(tmpfilename, VP_SD_FileName_LEN, PSTR("%s%c"), filelist.filename(), filelist.isDir() ? '/' : 0); // snprintf_P(tmpfilename, VP_SD_FileName_LEN, PSTR("%s"), filelist.filename()); + } + DGUSLCD_SendStringToDisplay(var); + } + + void DGUSScreenHandler::SDCardInserted() { + top_file = 0; + filelist.refresh(); + auto cs = getCurrentScreen(); + if (cs == DGUSLCD_SCREEN_MAIN || cs == DGUSLCD_SCREEN_STATUS) + GotoScreen(DGUSLCD_SCREEN_SDFILELIST); + } + + void DGUSScreenHandler::SDCardRemoved() { + if (current_screen == DGUSLCD_SCREEN_SDFILELIST + || (current_screen == DGUSLCD_SCREEN_CONFIRM && (ConfirmVP == VP_SD_AbortPrintConfirmed || ConfirmVP == VP_SD_FileSelectConfirm)) + || current_screen == DGUSLCD_SCREEN_SDPRINTMANIPULATION + ) GotoScreen(DGUSLCD_SCREEN_MAIN); + } + +#endif // SDSUPPORT + +void DGUSScreenHandler::ScreenChangeHook(DGUS_VP_Variable &var, void *val_ptr) { + uint8_t *tmp = (uint8_t*)val_ptr; + + // The keycode in target is coded as , so 0x0100A means + // from screen 1 (main) to 10 (temperature). DGUSLCD_SCREEN_POPUP is special, + // meaning "return to previous screen" + DGUSLCD_Screens target = (DGUSLCD_Screens)tmp[1]; + + DEBUG_ECHOLNPAIR("\n DEBUG target", target); + + if (target == DGUSLCD_SCREEN_POPUP) { + // Special handling for popup is to return to previous menu + if (current_screen == DGUSLCD_SCREEN_POPUP && confirm_action_cb) confirm_action_cb(); + PopToOldScreen(); + return; + } + + UpdateNewScreen(target); + + #ifdef DEBUG_DGUSLCD + if (!DGUSLCD_FindScreenVPMapList(target)) DEBUG_ECHOLNPAIR("WARNING: No screen Mapping found for ", target); + #endif +} + +void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("HandleManualMove"); + + int16_t movevalue = swap16(*(uint16_t*)val_ptr); + #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) + if (movevalue) { + const uint16_t choice = *(uint16_t*)var.memadr; + movevalue = movevalue < 0 ? -choice : choice; + } + #endif + char axiscode; + unsigned int speed = 1500; // FIXME: get default feedrate for manual moves, don't hardcode. + + switch (var.VP) { + default: return; + + case VP_MOVE_X: + axiscode = 'X'; + if (!ExtUI::canMove(ExtUI::axis_t::X)) goto cannotmove; + break; + + case VP_MOVE_Y: + axiscode = 'Y'; + if (!ExtUI::canMove(ExtUI::axis_t::Y)) goto cannotmove; + break; + + case VP_MOVE_Z: + axiscode = 'Z'; + speed = 300; // default to 5mm/s + if (!ExtUI::canMove(ExtUI::axis_t::Z)) goto cannotmove; + break; + + case VP_HOME_ALL: // only used for homing + axiscode = '\0'; + movevalue = 0; // ignore value sent from display, this VP is _ONLY_ for homing. + break; + } + + if (!movevalue) { + // homing + DEBUG_ECHOPAIR(" homing ", AS_CHAR(axiscode)); + char buf[6] = "G28 X"; + buf[4] = axiscode; + //DEBUG_ECHOPAIR(" ", buf); + queue.enqueue_one_now(buf); + //DEBUG_ECHOLNPGM(" ✓"); + ForceCompleteUpdate(); + return; + } + else { + // movement + DEBUG_ECHOPAIR(" move ", AS_CHAR(axiscode)); + bool old_relative_mode = relative_mode; + if (!relative_mode) { + //DEBUG_ECHOPGM(" G91"); + queue.enqueue_now_P(PSTR("G91")); + //DEBUG_ECHOPGM(" ✓ "); + } + char buf[32]; // G1 X9999.99 F12345 + unsigned int backup_speed = MMS_TO_MMM(feedrate_mm_s); + char sign[] = "\0"; + int16_t value = movevalue / 100; + if (movevalue < 0) { value = -value; sign[0] = '-'; } + int16_t fraction = ABS(movevalue) % 100; + snprintf_P(buf, 32, PSTR("G0 %c%s%d.%02d F%d"), axiscode, sign, value, fraction, speed); + //DEBUG_ECHOPAIR(" ", buf); + queue.enqueue_one_now(buf); + //DEBUG_ECHOLNPGM(" ✓ "); + if (backup_speed != speed) { + snprintf_P(buf, 32, PSTR("G0 F%d"), backup_speed); + queue.enqueue_one_now(buf); + //DEBUG_ECHOPAIR(" ", buf); + } + // while (!enqueue_and_echo_command(buf)) idle(); + //DEBUG_ECHOLNPGM(" ✓ "); + if (!old_relative_mode) { + //DEBUG_ECHOPGM("G90"); + queue.enqueue_now_P(PSTR("G90")); + //DEBUG_ECHOPGM(" ✓ "); + } + } + + ForceCompleteUpdate(); + DEBUG_ECHOLNPGM("manmv done."); + return; + + cannotmove: + DEBUG_ECHOLNPAIR(" cannot move ", AS_CHAR(axiscode)); + return; +} + +#if HAS_PID_HEATING + void DGUSScreenHandler::HandleTemperaturePIDChanged(DGUS_VP_Variable &var, void *val_ptr) { + uint16_t rawvalue = swap16(*(uint16_t*)val_ptr); + DEBUG_ECHOLNPAIR("V1:", rawvalue); + float value = (float)rawvalue / 10; + DEBUG_ECHOLNPAIR("V2:", value); + float newvalue = 0; + + switch (var.VP) { + default: return; + #if HAS_HOTEND + case VP_E0_PID_P: newvalue = value; break; + case VP_E0_PID_I: newvalue = scalePID_i(value); break; + case VP_E0_PID_D: newvalue = scalePID_d(value); break; + #endif + #if HOTENDS >= 2 + case VP_E1_PID_P: newvalue = value; break; + case VP_E1_PID_I: newvalue = scalePID_i(value); break; + case VP_E1_PID_D: newvalue = scalePID_d(value); break; + #endif + #if HAS_HEATED_BED + case VP_BED_PID_P: newvalue = value; break; + case VP_BED_PID_I: newvalue = scalePID_i(value); break; + case VP_BED_PID_D: newvalue = scalePID_d(value); break; + #endif + } + + DEBUG_ECHOLNPAIR_F("V3:", newvalue); + *(float *)var.memadr = newvalue; + + skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel + } +#endif // HAS_PID_HEATING + +#if ENABLED(BABYSTEPPING) + void DGUSScreenHandler::HandleLiveAdjustZ(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("HandleLiveAdjustZ"); + int16_t flag = swap16(*(uint16_t*)val_ptr), + steps = flag ? -20 : 20; + ExtUI::smartAdjustAxis_steps(steps, ExtUI::axis_t::Z, true); + ForceCompleteUpdate(); + } +#endif + +#if ENABLED(DGUS_FILAMENT_LOADUNLOAD) + + void DGUSScreenHandler::HandleFilamentOption(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("HandleFilamentOption"); + + uint8_t e_temp = 0; + filament_data.heated = false; + uint16_t preheat_option = swap16(*(uint16_t*)val_ptr); + if (preheat_option <= 8) { // Load filament type + filament_data.action = 1; + } + else if (preheat_option >= 10) { // Unload filament type + preheat_option -= 10; + filament_data.action = 2; + filament_data.purge_length = DGUS_FILAMENT_PURGE_LENGTH; + } + else { // Cancel filament operation + filament_data.action = 0; + } + + switch (preheat_option) { + case 0: // Load PLA + #ifdef PREHEAT_1_TEMP_HOTEND + e_temp = PREHEAT_1_TEMP_HOTEND; + #endif + break; + case 1: // Load ABS + TERN_(PREHEAT_2_TEMP_HOTEND, e_temp = PREHEAT_2_TEMP_HOTEND); + break; + case 2: // Load PET + #ifdef PREHEAT_3_TEMP_HOTEND + e_temp = PREHEAT_3_TEMP_HOTEND; + #endif + break; + case 3: // Load FLEX + #ifdef PREHEAT_4_TEMP_HOTEND + e_temp = PREHEAT_4_TEMP_HOTEND; + #endif + break; + case 9: // Cool down + default: + e_temp = 0; + break; + } + + if (filament_data.action == 0) { // Go back to utility screen + #if HAS_HOTEND + thermalManager.setTargetHotend(e_temp, ExtUI::extruder_t::E0); + #endif + #if HOTENDS >= 2 + thermalManager.setTargetHotend(e_temp, ExtUI::extruder_t::E1); + #endif + GotoScreen(DGUSLCD_SCREEN_UTILITY); + } + else { // Go to the preheat screen to show the heating progress + switch (var.VP) { + default: return; + #if HAS_HOTEND + case VP_E0_FILAMENT_LOAD_UNLOAD: + filament_data.extruder = ExtUI::extruder_t::E0; + thermalManager.setTargetHotend(e_temp, filament_data.extruder); + break; + #endif + #if HAS_MULTI_EXTRUDER + case VP_E1_FILAMENT_LOAD_UNLOAD: + filament_data.extruder = ExtUI::extruder_t::E1; + thermalManager.setTargetHotend(e_temp, filament_data.extruder); + break; + #endif + } + GotoScreen(DGUSLCD_SCREEN_FILAMENT_HEATING); + } + } + + void DGUSScreenHandler::HandleFilamentLoadUnload(DGUS_VP_Variable &var) { + DEBUG_ECHOLNPGM("HandleFilamentLoadUnload"); + if (filament_data.action <= 0) return; + + // If we close to the target temperature, we can start load or unload the filament + if (thermalManager.hotEnoughToExtrude(filament_data.extruder) && \ + thermalManager.targetHotEnoughToExtrude(filament_data.extruder)) { + float movevalue = DGUS_FILAMENT_LOAD_LENGTH_PER_TIME; + + if (filament_data.action == 1) { // load filament + if (!filament_data.heated) { + //GotoScreen(DGUSLCD_SCREEN_FILAMENT_LOADING); + filament_data.heated = true; + } + movevalue = ExtUI::getAxisPosition_mm(filament_data.extruder) + movevalue; + } + else { // unload filament + if (!filament_data.heated) { + GotoScreen(DGUSLCD_SCREEN_FILAMENT_UNLOADING); + filament_data.heated = true; + } + // Before unloading extrude to prevent jamming + if (filament_data.purge_length >= 0) { + movevalue = ExtUI::getAxisPosition_mm(filament_data.extruder) + movevalue; + filament_data.purge_length -= movevalue; + } + else { + movevalue = ExtUI::getAxisPosition_mm(filament_data.extruder) - movevalue; + } + } + ExtUI::setAxisPosition_mm(movevalue, filament_data.extruder); + } + } +#endif // DGUS_FILAMENT_LOADUNLOAD + +bool DGUSScreenHandler::loop() { + dgusdisplay.loop(); + + const millis_t ms = millis(); + static millis_t next_event_ms = 0; + + if (!IsScreenComplete() || ELAPSED(ms, next_event_ms)) { + next_event_ms = ms + DGUS_UPDATE_INTERVAL_MS; + UpdateScreenVPData(); + } + + #if ENABLED(SHOW_BOOTSCREEN) + static bool booted = false; + + if (!booted && TERN0(POWER_LOSS_RECOVERY, recovery.valid())) + booted = true; + + if (!booted && ELAPSED(ms, BOOTSCREEN_TIMEOUT)) { + booted = true; + + if (TERN0(POWER_LOSS_RECOVERY, recovery.valid())) + GotoScreen(DGUSLCD_SCREEN_POWER_LOSS); + else + GotoScreen(DGUSLCD_SCREEN_MAIN); + } + + #endif + return IsScreenComplete(); +} + +#endif // DGUS_LCD_UI_FYSETC diff --git a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.h new file mode 100644 index 000000000000..ee0af013a855 --- /dev/null +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.h @@ -0,0 +1,240 @@ +/** + * 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 + +#include "../DGUSDisplay.h" +#include "../DGUSVPVariable.h" +#include "../DGUSDisplayDef.h" + +#include "../../../../inc/MarlinConfig.h" + +enum DGUSLCD_Screens : uint8_t; + +class DGUSScreenHandler { +public: + DGUSScreenHandler() = default; + + static bool loop(); + + // Send all 4 strings that are displayed on the infoscreen, confirmation screen and kill screen + // The bools specifying whether the strings are in RAM or FLASH. + static void sendinfoscreen(const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); + + static void HandleUserConfirmationPopUp(uint16_t ConfirmVP, const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); + + // "M117" Message -- msg is a RAM ptr. + static void setstatusmessage(const char *msg); + // The same for messages from Flash + static void setstatusmessagePGM(PGM_P const msg); + // Callback for VP "Display wants to change screen on idle printer" + static void ScreenChangeHookIfIdle(DGUS_VP_Variable &var, void *val_ptr); + // Callback for VP "Screen has been changed" + static void ScreenChangeHook(DGUS_VP_Variable &var, void *val_ptr); + + // Callback for VP "All Heaters Off" + static void HandleAllHeatersOff(DGUS_VP_Variable &var, void *val_ptr); + // Hook for "Change this temperature" + static void HandleTemperatureChanged(DGUS_VP_Variable &var, void *val_ptr); + // Hook for "Change Flowrate" + static void HandleFlowRateChanged(DGUS_VP_Variable &var, void *val_ptr); + #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) + // Hook for manual move option + static void HandleManualMoveOption(DGUS_VP_Variable &var, void *val_ptr); + #endif + + // Hook for manual move. + static void HandleManualMove(DGUS_VP_Variable &var, void *val_ptr); + // Hook for manual extrude. + static void HandleManualExtrude(DGUS_VP_Variable &var, void *val_ptr); + // Hook for motor lock and unlook + static void HandleMotorLockUnlock(DGUS_VP_Variable &var, void *val_ptr); + #if ENABLED(POWER_LOSS_RECOVERY) + // Hook for power loss recovery. + static void HandlePowerLossRecovery(DGUS_VP_Variable &var, void *val_ptr); + #endif + // Hook for settings + static void HandleSettings(DGUS_VP_Variable &var, void *val_ptr); + static void HandleStepPerMMChanged(DGUS_VP_Variable &var, void *val_ptr); + static void HandleStepPerMMExtruderChanged(DGUS_VP_Variable &var, void *val_ptr); + + #if HAS_PID_HEATING + // Hook for "Change this temperature PID para" + static void HandleTemperaturePIDChanged(DGUS_VP_Variable &var, void *val_ptr); + // Hook for PID autotune + static void HandlePIDAutotune(DGUS_VP_Variable &var, void *val_ptr); + #endif + #if HAS_BED_PROBE + // Hook for "Change probe offset z" + static void HandleProbeOffsetZChanged(DGUS_VP_Variable &var, void *val_ptr); + #endif + #if ENABLED(BABYSTEPPING) + // Hook for live z adjust action + static void HandleLiveAdjustZ(DGUS_VP_Variable &var, void *val_ptr); + #endif + #if HAS_FAN + // Hook for fan control + static void HandleFanControl(DGUS_VP_Variable &var, void *val_ptr); + #endif + // Hook for heater control + static void HandleHeaterControl(DGUS_VP_Variable &var, void *val_ptr); + #if ENABLED(DGUS_PREHEAT_UI) + // Hook for preheat + static void HandlePreheat(DGUS_VP_Variable &var, void *val_ptr); + #endif + #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) + // Hook for filament load and unload filament option + static void HandleFilamentOption(DGUS_VP_Variable &var, void *val_ptr); + // Hook for filament load and unload + static void HandleFilamentLoadUnload(DGUS_VP_Variable &var); + #endif + + #if ENABLED(SDSUPPORT) + // 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. + static void DGUSLCD_SD_ScrollFilelist(DGUS_VP_Variable &var, void *val_ptr); + // File touched. + static void DGUSLCD_SD_FileSelected(DGUS_VP_Variable &var, void *val_ptr); + // start print after confirmation received. + static void DGUSLCD_SD_StartPrint(DGUS_VP_Variable &var, void *val_ptr); + // User hit the pause, resume or abort button. + static void DGUSLCD_SD_ResumePauseAbort(DGUS_VP_Variable &var, void *val_ptr); + // User confirmed the abort action + static void DGUSLCD_SD_ReallyAbort(DGUS_VP_Variable &var, void *val_ptr); + // User hit the tune button + static void DGUSLCD_SD_PrintTune(DGUS_VP_Variable &var, void *val_ptr); + // Send a single filename to the display. + static void DGUSLCD_SD_SendFilename(DGUS_VP_Variable &var); + // Marlin informed us that a new SD has been inserted. + static void SDCardInserted(); + // Marlin informed us that the SD Card has been removed(). + static void SDCardRemoved(); + // Marlin informed us about a bad SD Card. + static void SDCardError(); + #endif + + // OK Button the Confirm screen. + static void ScreenConfirmedOK(DGUS_VP_Variable &var, void *val_ptr); + + // Update data after went to new screen (by display or by GotoScreen) + // remember: store the last-displayed screen, so it can get returned to. + // (e.g for pop up messages) + static void UpdateNewScreen(DGUSLCD_Screens newscreen, bool popup=false); + + // Recall the remembered screen. + static void PopToOldScreen(); + + // Make the display show the screen and update all VPs in it. + static void GotoScreen(DGUSLCD_Screens screen, bool ispopup = false); + + static void UpdateScreenVPData(); + + // Helpers to convert and transfer data to the display. + static void DGUSLCD_SendWordValueToDisplay(DGUS_VP_Variable &var); + static void DGUSLCD_SendStringToDisplay(DGUS_VP_Variable &var); + static void DGUSLCD_SendStringToDisplayPGM(DGUS_VP_Variable &var); + static void DGUSLCD_SendTemperaturePID(DGUS_VP_Variable &var); + static void DGUSLCD_SendPercentageToDisplay(DGUS_VP_Variable &var); + static void DGUSLCD_SendPrintProgressToDisplay(DGUS_VP_Variable &var); + static void DGUSLCD_SendPrintTimeToDisplay(DGUS_VP_Variable &var); + + #if ENABLED(PRINTCOUNTER) + static void DGUSLCD_SendPrintAccTimeToDisplay(DGUS_VP_Variable &var); + static void DGUSLCD_SendPrintsTotalToDisplay(DGUS_VP_Variable &var); + #endif + #if HAS_FAN + static void DGUSLCD_SendFanStatusToDisplay(DGUS_VP_Variable &var); + #endif + static void DGUSLCD_SendHeaterStatusToDisplay(DGUS_VP_Variable &var); + #if ENABLED(DGUS_UI_WAITING) + static void DGUSLCD_SendWaitingStatusToDisplay(DGUS_VP_Variable &var); + #endif + + // Send a value from 0..100 to a variable with a range from 0..255 + static void DGUSLCD_PercentageToUint8(DGUS_VP_Variable &var, void *val_ptr); + + template + static void DGUSLCD_SetValueDirectly(DGUS_VP_Variable &var, void *val_ptr) { + if (!var.memadr) return; + union { unsigned char tmp[sizeof(T)]; T t; } x; + unsigned char *ptr = (unsigned char*)val_ptr; + LOOP_L_N(i, sizeof(T)) x.tmp[i] = ptr[sizeof(T) - i - 1]; + *(T*)var.memadr = x.t; + } + + // Send a float value to the display. + // Display will get a 4-byte integer scaled to the number of digits: + // Tell the display the number of digits and it cheats by displaying a dot between... + template + static void DGUSLCD_SendFloatAsLongValueToDisplay(DGUS_VP_Variable &var) { + if (var.memadr) { + float f = *(float *)var.memadr; + f *= cpow(10, decimals); + dgusdisplay.WriteVariable(var.VP, (long)f); + } + } + + // Send a float value to the display. + // Display will get a 2-byte integer scaled to the number of digits: + // Tell the display the number of digits and it cheats by displaying a dot between... + template + static void DGUSLCD_SendFloatAsIntValueToDisplay(DGUS_VP_Variable &var) { + if (var.memadr) { + float f = *(float *)var.memadr; + DEBUG_ECHOLNPAIR_F(" >> ", f, 6); + f *= cpow(10, decimals); + dgusdisplay.WriteVariable(var.VP, (int16_t)f); + } + } + + // Force an update of all VP on the current screen. + static inline void ForceCompleteUpdate() { update_ptr = 0; ScreenComplete = false; } + // Has all VPs sent to the screen + static inline bool IsScreenComplete() { return ScreenComplete; } + + static inline DGUSLCD_Screens getCurrentScreen() { return current_screen; } + + static inline void SetupConfirmAction( void (*f)()) { confirm_action_cb = f; } + +private: + static DGUSLCD_Screens current_screen; //< currently on screen + static constexpr uint8_t NUM_PAST_SCREENS = 4; + static DGUSLCD_Screens past_screens[NUM_PAST_SCREENS]; //< LIFO with past screens for the "back" button. + + static uint8_t update_ptr; //< Last sent entry in the VPList for the actual screen. + static uint16_t skipVP; //< When updating the screen data, skip this one, because the user is interacting with it. + static bool ScreenComplete; //< All VPs sent to screen? + + static uint16_t ConfirmVP; //< context for confirm screen (VP that will be emulated-sent on "OK"). + + #if ENABLED(SDSUPPORT) + static int16_t top_file; //< file on top of file chooser + static int16_t file_to_print; //< touched file to be confirmed + #endif + + static void (*confirm_action_cb)(); +}; + +#if ENABLED(POWER_LOSS_RECOVERY) + #define PLR_SCREEN_RECOVER DGUSLCD_SCREEN_SDPRINTMANIPULATION + #define PLR_SCREEN_CANCEL DGUSLCD_SCREEN_STATUS +#endif diff --git a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp new file mode 100644 index 000000000000..bdcff47ae812 --- /dev/null +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp @@ -0,0 +1,477 @@ +/** + * 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 . + * + */ + +/* DGUS VPs changed by George Fu in 2019 for Marlin */ + +#include "../../../../inc/MarlinConfigPre.h" + +#if ENABLED(DGUS_LCD_UI_HIPRECY) + +#include "DGUSDisplayDef.h" +#include "../DGUSDisplay.h" +#include "../DGUSScreenHandler.h" + +#include "../../../../module/temperature.h" +#include "../../../../module/motion.h" +#include "../../../../module/planner.h" + +#include "../../ui_api.h" +#include "../../../marlinui.h" + +#if ENABLED(DGUS_UI_MOVE_DIS_OPTION) + uint16_t distanceToMove = 10; +#endif + +const uint16_t VPList_Boot[] PROGMEM = { + VP_MARLIN_VERSION, + 0x0000 +}; + +const uint16_t VPList_Main[] PROGMEM = { + // VP_M117, for completeness, but it cannot be auto-uploaded. + #if HAS_HOTEND + VP_T_E0_Is, VP_T_E0_Set, VP_E0_STATUS, + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif + #endif + #if HAS_HEATED_BED + VP_T_Bed_Is, VP_T_Bed_Set, VP_BED_STATUS, + #endif + #if HAS_FAN + VP_Fan0_Percentage, VP_FAN0_STATUS, + #endif + VP_XPos, VP_YPos, VP_ZPos, + VP_Fan0_Percentage, + VP_Feedrate_Percentage, + #if ENABLED(LCD_SET_PROGRESS_MANUALLY) + VP_PrintProgress_Percentage, + #endif + 0x0000 +}; + +const uint16_t VPList_Temp[] PROGMEM = { + #if HAS_HOTEND + VP_T_E0_Is, VP_T_E0_Set, + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif + #endif + #if HAS_HEATED_BED + VP_T_Bed_Is, VP_T_Bed_Set, + #endif + 0x0000 +}; + +const uint16_t VPList_Status[] PROGMEM = { + // VP_M117, for completeness, but it cannot be auto-uploaded + #if HAS_HOTEND + VP_T_E0_Is, VP_T_E0_Set, + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif + #endif + #if HAS_HEATED_BED + VP_T_Bed_Is, VP_T_Bed_Set, + #endif + #if HAS_FAN + VP_Fan0_Percentage, + #endif + VP_XPos, VP_YPos, VP_ZPos, + VP_Fan0_Percentage, + VP_Feedrate_Percentage, + VP_PrintProgress_Percentage, + 0x0000 +}; + +const uint16_t VPList_Status2[] PROGMEM = { + // VP_M117, for completeness, but it cannot be auto-uploaded + #if HAS_HOTEND + VP_Flowrate_E0, + #if HOTENDS >= 2 + VP_Flowrate_E1, + #endif + #endif + VP_PrintProgress_Percentage, + VP_PrintTime, + 0x0000 +}; + +const uint16_t VPList_Preheat[] PROGMEM = { + #if HAS_HOTEND + VP_T_E0_Is, VP_T_E0_Set, + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif + #endif + #if HAS_HEATED_BED + VP_T_Bed_Is, VP_T_Bed_Set, + #endif + 0x0000 +}; + +const uint16_t VPList_ManualMove[] PROGMEM = { + VP_XPos, VP_YPos, VP_ZPos, + 0x0000 +}; + +const uint16_t VPList_ManualExtrude[] PROGMEM = { + #if HAS_HOTEND + VP_T_E0_Is, VP_T_E0_Set, + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif + #endif + VP_EPos, + 0x0000 +}; + +const uint16_t VPList_FanAndFeedrate[] PROGMEM = { + VP_Feedrate_Percentage, VP_Fan0_Percentage, + 0x0000 +}; + +const uint16_t VPList_SD_FlowRates[] PROGMEM = { + VP_Flowrate_E0, VP_Flowrate_E1, + 0x0000 +}; + +const uint16_t VPList_Filament_heating[] PROGMEM = { + #if HAS_HOTEND + VP_T_E0_Is, VP_T_E0_Set, + VP_E0_FILAMENT_LOAD_UNLOAD, + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif + #endif + 0x0000 +}; + +const uint16_t VPList_Filament_load_unload[] PROGMEM = { + #if HAS_HOTEND + VP_E0_FILAMENT_LOAD_UNLOAD, + #if HOTENDS >= 2 + VP_E1_FILAMENT_LOAD_UNLOAD, + #endif + #endif + 0x0000 +}; + +const uint16_t VPList_SDFileList[] PROGMEM = { + VP_SD_FileName0, VP_SD_FileName1, VP_SD_FileName2, VP_SD_FileName3, VP_SD_FileName4, + 0x0000 +}; + +const uint16_t VPList_SD_PrintManipulation[] PROGMEM = { + VP_PrintProgress_Percentage, VP_PrintTime, + #if HAS_HOTEND + VP_T_E0_Is, VP_T_E0_Set, + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif + #endif + #if HAS_HEATED_BED + VP_T_Bed_Is, VP_T_Bed_Set, + #endif + #if HAS_FAN + VP_Fan0_Percentage, + #if FAN_COUNT > 1 + VP_Fan1_Percentage, + #endif + #endif + VP_Flowrate_E0, + 0x0000 +}; + +const uint16_t VPList_SDPrintTune[] PROGMEM = { + #if HAS_HOTEND + VP_T_E0_Is, VP_T_E0_Set, + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif + #endif + #if HAS_HEATED_BED + VP_T_Bed_Is, VP_T_Bed_Set, + #endif + VP_Feedrate_Percentage, + #if HAS_FAN + VP_Fan0_Percentage, + #endif + VP_Flowrate_E0, + VP_SD_Print_ProbeOffsetZ, + 0x0000 +}; + +const uint16_t VPList_StepPerMM[] PROGMEM = { + VP_X_STEP_PER_MM, + VP_Y_STEP_PER_MM, + VP_Z_STEP_PER_MM, + #if HAS_HOTEND + VP_E0_STEP_PER_MM, + #if HOTENDS >= 2 + VP_E1_STEP_PER_MM, + #endif + #endif + 0x0000 +}; + +const uint16_t VPList_PIDE0[] PROGMEM = { + #if ENABLED(PIDTEMP) + VP_E0_PID_P, + VP_E0_PID_I, + VP_E0_PID_D, + #endif + 0x0000 +}; + +const uint16_t VPList_PIDBED[] PROGMEM = { + #if ENABLED(PIDTEMP) + VP_BED_PID_P, + VP_BED_PID_I, + VP_BED_PID_D, + #endif + 0x0000 +}; + +const uint16_t VPList_Infos[] PROGMEM = { + VP_MARLIN_VERSION, + VP_PrintTime, + #if ENABLED(PRINTCOUNTER) + VP_PrintAccTime, + VP_PrintsTotal, + #endif + 0x0000 +}; + +const uint16_t VPList_PIDTuningWaiting[] PROGMEM = { + VP_WAITING_STATUS, + 0x0000 +}; + +const uint16_t VPList_FLCPreheat[] PROGMEM = { + #if HAS_HOTEND + VP_T_E0_Is, VP_T_E0_Set, + #endif + #if HAS_HEATED_BED + VP_T_Bed_Is, VP_T_Bed_Set, + #endif + 0x0000 +}; + +const uint16_t VPList_FLCPrinting[] PROGMEM = { + #if HAS_HOTEND + VP_SD_Print_ProbeOffsetZ, + #endif + 0x0000 +}; + +const uint16_t VPList_Z_Offset[] PROGMEM = { + #if HAS_HOTEND + VP_SD_Print_ProbeOffsetZ, + #endif + 0x0000 +}; + +const struct VPMapping VPMap[] PROGMEM = { + { DGUSLCD_SCREEN_BOOT, VPList_Boot }, + { DGUSLCD_SCREEN_MAIN, VPList_Main }, + { DGUSLCD_SCREEN_TEMPERATURE, VPList_Temp }, + { DGUSLCD_SCREEN_STATUS, VPList_Status }, + { DGUSLCD_SCREEN_STATUS2, VPList_Status2 }, + { DGUSLCD_SCREEN_PREHEAT, VPList_Preheat }, + { DGUSLCD_SCREEN_MANUALMOVE, VPList_ManualMove }, + { DGUSLCD_SCREEN_Z_OFFSET, VPList_Z_Offset }, + { DGUSLCD_SCREEN_MANUALEXTRUDE, VPList_ManualExtrude }, + { DGUSLCD_SCREEN_FILAMENT_HEATING, VPList_Filament_heating }, + { DGUSLCD_SCREEN_FILAMENT_LOADING, VPList_Filament_load_unload }, + { DGUSLCD_SCREEN_FILAMENT_UNLOADING, VPList_Filament_load_unload }, + { DGUSLCD_SCREEN_SDPRINTMANIPULATION, VPList_SD_PrintManipulation }, + { DGUSLCD_SCREEN_SDFILELIST, VPList_SDFileList }, + { DGUSLCD_SCREEN_SDPRINTTUNE, VPList_SDPrintTune }, + { DGUSLCD_SCREEN_WAITING, VPList_PIDTuningWaiting }, + { DGUSLCD_SCREEN_FLC_PREHEAT, VPList_FLCPreheat }, + { DGUSLCD_SCREEN_FLC_PRINTING, VPList_FLCPrinting }, + { DGUSLCD_SCREEN_STEPPERMM, VPList_StepPerMM }, + { DGUSLCD_SCREEN_PID_E, VPList_PIDE0 }, + { DGUSLCD_SCREEN_PID_BED, VPList_PIDBED }, + { DGUSLCD_SCREEN_INFOS, VPList_Infos }, + { 0 , nullptr } // List is terminated with an nullptr as table entry. +}; + +const char MarlinVersion[] PROGMEM = SHORT_BUILD_VERSION; + +const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { + // Helper to detect touch events + VPHELPER(VP_SCREENCHANGE, nullptr, ScreenHandler.ScreenChangeHook, nullptr), + VPHELPER(VP_SCREENCHANGE_ASK, nullptr, ScreenHandler.ScreenChangeHookIfIdle, nullptr), + #if ENABLED(SDSUPPORT) + VPHELPER(VP_SCREENCHANGE_WHENSD, nullptr, ScreenHandler.ScreenChangeHookIfSD, nullptr), + #endif + VPHELPER(VP_CONFIRMED, nullptr, ScreenHandler.ScreenConfirmedOK, nullptr), + + VPHELPER(VP_TEMP_ALL_OFF, nullptr, ScreenHandler.HandleAllHeatersOff, nullptr), + + #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) + VPHELPER(VP_MOVE_OPTION, &distanceToMove, ScreenHandler.HandleManualMoveOption, nullptr), + #endif + #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) + VPHELPER(VP_MOVE_X, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Y, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Z, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_HOME_ALL, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), + #else + VPHELPER(VP_MOVE_X, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Y, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Z, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_HOME_ALL, nullptr, ScreenHandler.HandleManualMove, nullptr), + #endif + VPHELPER(VP_MOTOR_LOCK_UNLOK, nullptr, ScreenHandler.HandleMotorLockUnlock, nullptr), + #if ENABLED(POWER_LOSS_RECOVERY) + VPHELPER(VP_POWER_LOSS_RECOVERY, nullptr, ScreenHandler.HandlePowerLossRecovery, nullptr), + #endif + VPHELPER(VP_SETTINGS, nullptr, ScreenHandler.HandleSettings, nullptr), + #if ENABLED(SINGLE_Z_CALIBRATION) + VPHELPER(VP_Z_CALIBRATE, nullptr, ScreenHandler.HandleZCalibration, nullptr), + #endif + #if ENABLED(FIRST_LAYER_CAL) + VPHELPER(VP_Z_FIRST_LAYER_CAL, nullptr, ScreenHandler.HandleFirstLayerCal, nullptr), + #endif + + { .VP = VP_MARLIN_VERSION, .memadr = (void*)MarlinVersion, .size = VP_MARLIN_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + // M117 LCD String (We don't need the string in memory but "just" push it to the display on demand, hence the nullptr + { .VP = VP_M117, .memadr = nullptr, .size = VP_M117_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplay }, + + // Temperature Data + #if HAS_HOTEND + VPHELPER(VP_T_E0_Is, &thermalManager.temp_hotend[0].celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), + VPHELPER(VP_T_E0_Set, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Flowrate_E0, &planner.flow_percentage[ExtUI::extruder_t::E0], ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_EPos, &destination.e, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_MOVE_E0, nullptr, ScreenHandler.HandleManualExtrude, nullptr), + VPHELPER(VP_E0_CONTROL, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_E0_STATUS, &thermalManager.temp_hotend[0].target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + #if ENABLED(DGUS_PREHEAT_UI) + VPHELPER(VP_E0_BED_PREHEAT, nullptr, ScreenHandler.HandlePreheat, nullptr), + #endif + #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) + VPHELPER(VP_E0_FILAMENT_LOAD_UNLOAD, nullptr, ScreenHandler.HandleFilamentOption, ScreenHandler.HandleFilamentLoadUnload), + #endif + #if ENABLED(PIDTEMP) + VPHELPER(VP_E0_PID_P, &thermalManager.temp_hotend[0].pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), + VPHELPER(VP_E0_PID_I, &thermalManager.temp_hotend[0].pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), + VPHELPER(VP_E0_PID_D, &thermalManager.temp_hotend[0].pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), + VPHELPER(VP_PID_AUTOTUNE_E0, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), + #endif + #endif + #if HOTENDS >= 2 + VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), + VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Flowrate_E1, nullptr, ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_MOVE_E1, nullptr, ScreenHandler.HandleManualExtrude, nullptr), + VPHELPER(VP_E1_CONTROL, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_E1_STATUS, &thermalManager.temp_hotend[1].target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + #endif + #if HAS_HEATED_BED + VPHELPER(VP_T_Bed_Is, &thermalManager.temp_bed.celsius, nullptr, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_T_Bed_Set, &thermalManager.temp_bed.target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_BED_CONTROL, &thermalManager.temp_bed.target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_BED_STATUS, &thermalManager.temp_bed.target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + #if ENABLED(PIDTEMPBED) + VPHELPER(VP_BED_PID_P, &thermalManager.temp_bed.pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), + VPHELPER(VP_BED_PID_I, &thermalManager.temp_bed.pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), + VPHELPER(VP_BED_PID_D, &thermalManager.temp_bed.pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), + VPHELPER(VP_PID_AUTOTUNE_BED, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), + #endif + #endif + + // Fan Data + #if HAS_FAN + #define FAN_VPHELPER(N) \ + VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], ScreenHandler.DGUSLCD_PercentageToUint8, ScreenHandler.DGUSLCD_SendPercentageToDisplay), \ + VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], ScreenHandler.HandleFanControl, nullptr), \ + VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, ScreenHandler.DGUSLCD_SendFanStatusToDisplay), + REPEAT(FAN_COUNT, FAN_VPHELPER) + #endif + + // Feedrate + VPHELPER(VP_Feedrate_Percentage, &feedrate_percentage, ScreenHandler.DGUSLCD_SetValueDirectly, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + + // Position Data + VPHELPER(VP_XPos, ¤t_position.x, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_YPos, ¤t_position.y, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_ZPos, ¤t_position.z, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), + + // Print Progress + VPHELPER(VP_PrintProgress_Percentage, nullptr, nullptr, ScreenHandler.DGUSLCD_SendPrintProgressToDisplay), + + // Print Time + VPHELPER_STR(VP_PrintTime, nullptr, VP_PrintTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintTimeToDisplay), + #if ENABLED(PRINTCOUNTER) + VPHELPER_STR(VP_PrintAccTime, nullptr, VP_PrintAccTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintAccTimeToDisplay), + VPHELPER_STR(VP_PrintsTotal, nullptr, VP_PrintsTotal_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintsTotalToDisplay), + #endif + + VPHELPER(VP_X_STEP_PER_MM, &planner.settings.axis_steps_per_mm[X_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + VPHELPER(VP_Y_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Y_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + VPHELPER(VP_Z_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Z_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + #if HAS_HOTEND + VPHELPER(VP_E0_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(0)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + #if HOTENDS >= 2 + VPHELPER(VP_E1_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(1)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + #endif + #endif + + // SDCard File listing. + #if ENABLED(SDSUPPORT) + VPHELPER(VP_SD_ScrollEvent, nullptr, ScreenHandler.DGUSLCD_SD_ScrollFilelist, nullptr), + VPHELPER(VP_SD_FileSelected, nullptr, ScreenHandler.DGUSLCD_SD_FileSelected, nullptr), + VPHELPER(VP_SD_FileSelectConfirm, nullptr, ScreenHandler.DGUSLCD_SD_StartPrint, nullptr), + VPHELPER_STR(VP_SD_FileName0, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), + VPHELPER_STR(VP_SD_FileName1, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), + VPHELPER_STR(VP_SD_FileName2, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), + VPHELPER_STR(VP_SD_FileName3, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), + VPHELPER_STR(VP_SD_FileName4, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), + VPHELPER(VP_SD_ResumePauseAbort, nullptr, ScreenHandler.DGUSLCD_SD_ResumePauseAbort, nullptr), + VPHELPER(VP_SD_AbortPrintConfirmed, nullptr, ScreenHandler.DGUSLCD_SD_ReallyAbort, nullptr), + VPHELPER(VP_SD_Print_Setting, nullptr, ScreenHandler.DGUSLCD_SD_PrintTune, nullptr), + #if HAS_BED_PROBE + VPHELPER(VP_SD_Print_ProbeOffsetZ, &probe.offset.z, ScreenHandler.HandleProbeOffsetZChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<2>), + #if ENABLED(BABYSTEPPING) + VPHELPER(VP_SD_Print_LiveAdjustZ, nullptr, ScreenHandler.HandleLiveAdjustZ, nullptr), + #endif + #endif + #endif + + #if ENABLED(DGUS_UI_WAITING) + VPHELPER(VP_WAITING_STATUS, nullptr, nullptr, ScreenHandler.DGUSLCD_SendWaitingStatusToDisplay), + #endif + + // Messages for the User, shared by the popup and the kill screen. They can't be autouploaded as we do not buffer content. + { .VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + + VPHELPER(0, 0, 0, 0) // must be last entry. +}; + +#endif // DGUS_LCD_UI_HIPRECY diff --git a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.h b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.h new file mode 100644 index 000000000000..e9581553817b --- /dev/null +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.h @@ -0,0 +1,292 @@ +/** + * 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 + +#include "../DGUSDisplayDef.h" + +enum DGUSLCD_Screens : uint8_t { + DGUSLCD_SCREEN_BOOT = 160, + DGUSLCD_SCREEN_MAIN = 1, + DGUSLCD_SCREEN_STATUS = 1, + DGUSLCD_SCREEN_STATUS2 = 1, + DGUSLCD_SCREEN_POWER_LOSS = 17, + DGUSLCD_SCREEN_TEMPERATURE = 40, + DGUSLCD_SCREEN_MANUALMOVE = 86, + DGUSLCD_SCREEN_PREHEAT = 48, + DGUSLCD_SCREEN_UTILITY = 70, + DGUSLCD_SCREEN_FILAMENT_HEATING = 80, + DGUSLCD_SCREEN_FILAMENT_LOADING = 76, + DGUSLCD_SCREEN_FILAMENT_UNLOADING = 82, + DGUSLCD_SCREEN_MANUALEXTRUDE = 84, + DGUSLCD_SCREEN_Z_OFFSET = 88, + DGUSLCD_SCREEN_SDFILELIST = 3, + DGUSLCD_SCREEN_SDPRINTMANIPULATION = 7, + DGUSLCD_SCREEN_SDPRINTTUNE = 9, + DGUSLCD_SCREEN_FLC_PREHEAT = 94, + DGUSLCD_SCREEN_FLC_PRINTING = 96, + DGUSLCD_SCREEN_STEPPERMM = 122, + DGUSLCD_SCREEN_PID_E = 126, + DGUSLCD_SCREEN_PID_BED = 128, + DGUSLCD_SCREEN_INFOS = 131, + DGUSLCD_SCREEN_CONFIRM = 240, + DGUSLCD_SCREEN_KILL = 250, ///< Kill Screen. Must always be 250 (to be able to display "Error wrong LCD Version") + DGUSLCD_SCREEN_WAITING = 251, + DGUSLCD_SCREEN_POPUP = 252, ///< special target, popup screen will also return this code to say "return to previous screen" + DGUSLCD_SCREEN_UNUSED = 255 +}; + +// Display Memory layout used (T5UID) +// Except system variables this is arbitrary, just to organize stuff.... + +// 0x0000 .. 0x0FFF -- System variables and reserved by the display +// 0x1000 .. 0x1FFF -- Variables to never change location, regardless of UI Version +// 0x2000 .. 0x2FFF -- Controls (VPs that will trigger some action) +// 0x3000 .. 0x4FFF -- Marlin Data to be displayed +// 0x5000 .. -- SPs (if we want to modify display elements, e.g change color or like) -- currently unused + +// As there is plenty of space (at least most displays have >8k RAM), we do not pack them too tight, +// so that we can keep variables nicely together in the address space. + +// UI Version always on 0x1000...0x1002 so that the firmware can check this and bail out. +constexpr uint16_t VP_UI_VERSION_MAJOR = 0x1000; // Major -- incremented when incompatible +constexpr uint16_t VP_UI_VERSION_MINOR = 0x1001; // Minor -- incremented on new features, but compatible +constexpr uint16_t VP_UI_VERSION_PATCH = 0x1002; // Patch -- fixed which do not change functionality. +constexpr uint16_t VP_UI_FLAVOUR = 0x1010; // lets reserve 16 bytes here to determine if UI is suitable for this Marlin. tbd. + +// Storage space for the Killscreen messages. 0x1100 - 0x1200 . Reused for the popup. +constexpr uint16_t VP_MSGSTR1 = 0x1100; +constexpr uint8_t VP_MSGSTR1_LEN = 0x20; // might be more place for it... +constexpr uint16_t VP_MSGSTR2 = 0x1140; +constexpr uint8_t VP_MSGSTR2_LEN = 0x20; +constexpr uint16_t VP_MSGSTR3 = 0x1180; +constexpr uint8_t VP_MSGSTR3_LEN = 0x20; +constexpr uint16_t VP_MSGSTR4 = 0x11C0; +constexpr uint8_t VP_MSGSTR4_LEN = 0x20; + +// Screenchange request for screens that only make sense when printer is idle. +// e.g movement is only allowed if printer is not printing. +// Marlin must confirm by setting the screen manually. +constexpr uint16_t VP_SCREENCHANGE_ASK = 0x2000; +constexpr uint16_t VP_SCREENCHANGE = 0x2001; // 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 = 0x2002; // Turn all heaters off. Value arbitrary ;)= +constexpr uint16_t VP_SCREENCHANGE_WHENSD = 0x2003; // "Print" Button touched -- go only there if there is an SD Card. + +constexpr uint16_t VP_CONFIRMED = 0x2010; // OK on confirm screen. + +// Buttons on the SD-Card File listing. +constexpr uint16_t VP_SD_ScrollEvent = 0x2020; // Data: 0 for "up a directory", numbers are the amount to scroll, e.g -1 one up, 1 one down +constexpr uint16_t VP_SD_FileSelected = 0x2022; // Number of file field selected. +constexpr uint16_t VP_SD_FileSelectConfirm = 0x2024; // (This is a virtual VP and emulated by the Confirm Screen when a file has been confirmed) + +constexpr uint16_t VP_SD_ResumePauseAbort = 0x2026; // Resume(Data=0), Pause(Data=1), Abort(Data=2) SD Card prints +constexpr uint16_t VP_SD_AbortPrintConfirmed = 0x2028; // Abort print confirmation (virtual, will be injected by the confirm dialog) +constexpr uint16_t VP_SD_Print_Setting = 0x2040; +constexpr uint16_t VP_SD_Print_LiveAdjustZ = 0x2050; // Data: 0 down, 1 up + +// Controls for movement (we can't use the incremental / decremental feature of the display at this feature works only with 16 bit values +// (which would limit us to 655.35mm, which is likely not a problem for common setups, but i don't want to rule out hangprinters support) +// A word about the coding: The VP will be per axis and the return code will be an signed 16 bit value in 0.01 mm resolution, telling us +// the relative travel amount t he user wants to do. So eg. if the display sends us VP=2100 with value 100, the user wants us to move X by +1 mm. +constexpr uint16_t VP_MOVE_X = 0x2100; +constexpr uint16_t VP_MOVE_Y = 0x2102; +constexpr uint16_t VP_MOVE_Z = 0x2104; +constexpr uint16_t VP_MOVE_E0 = 0x2110; +constexpr uint16_t VP_MOVE_E1 = 0x2112; +//constexpr uint16_t VP_MOVE_E2 = 0x2114; +//constexpr uint16_t VP_MOVE_E3 = 0x2116; +//constexpr uint16_t VP_MOVE_E4 = 0x2118; +//constexpr uint16_t VP_MOVE_E5 = 0x211A; +constexpr uint16_t VP_HOME_ALL = 0x2120; +constexpr uint16_t VP_MOTOR_LOCK_UNLOK = 0x2130; + +// Power loss recovery +constexpr uint16_t VP_POWER_LOSS_RECOVERY = 0x2180; + +// Fan Control Buttons , switch between "off" and "on" +constexpr uint16_t VP_FAN0_CONTROL = 0x2200; +constexpr uint16_t VP_FAN1_CONTROL = 0x2202; +//constexpr uint16_t VP_FAN2_CONTROL = 0x2204; +//constexpr uint16_t VP_FAN3_CONTROL = 0x2206; + +// Heater Control Buttons , triged between "cool down" and "heat PLA" state +constexpr uint16_t VP_E0_CONTROL = 0x2210; +constexpr uint16_t VP_E1_CONTROL = 0x2212; +//constexpr uint16_t VP_E2_CONTROL = 0x2214; +//constexpr uint16_t VP_E3_CONTROL = 0x2216; +//constexpr uint16_t VP_E4_CONTROL = 0x2218; +//constexpr uint16_t VP_E5_CONTROL = 0x221A; +constexpr uint16_t VP_BED_CONTROL = 0x221C; + +// Preheat +constexpr uint16_t VP_E0_BED_PREHEAT = 0x2220; +//constexpr uint16_t VP_E1_BED_PREHEAT = 0x2222; +//constexpr uint16_t VP_E2_BED_PREHEAT = 0x2224; +//constexpr uint16_t VP_E3_BED_PREHEAT = 0x2226; +//constexpr uint16_t VP_E4_BED_PREHEAT = 0x2228; +//constexpr uint16_t VP_E5_BED_PREHEAT = 0x222A; + +// Filament load and unload +constexpr uint16_t VP_E0_FILAMENT_LOAD_UNLOAD = 0x2300; + +// Settings store , reset +constexpr uint16_t VP_SETTINGS = 0x2400; + +// PID autotune +constexpr uint16_t VP_PID_AUTOTUNE_E0 = 0x2410; +//constexpr uint16_t VP_PID_AUTOTUNE_E1 = 0x2412; +//constexpr uint16_t VP_PID_AUTOTUNE_E2 = 0x2414; +//constexpr uint16_t VP_PID_AUTOTUNE_E3 = 0x2416; +//constexpr uint16_t VP_PID_AUTOTUNE_E4 = 0x2418; +//constexpr uint16_t VP_PID_AUTOTUNE_E5 = 0x241A; +constexpr uint16_t VP_PID_AUTOTUNE_BED = 0x2420; + +// Calibrate Z +constexpr uint16_t VP_Z_CALIBRATE = 0x2430; + +// First layer cal +constexpr uint16_t VP_Z_FIRST_LAYER_CAL = 0x2500; // Data: 0 - Cancel first layer cal progress, >0 filament type have loaded + +// Firmware version on the boot screen. +constexpr uint16_t VP_MARLIN_VERSION = 0x3000; +constexpr uint8_t VP_MARLIN_VERSION_LEN = 16; // there is more space on the display, if needed. + +// Place for status messages. +constexpr uint16_t VP_M117 = 0x3020; +constexpr uint8_t VP_M117_LEN = 0x20; + +// Temperatures. +constexpr uint16_t VP_T_E0_Is = 0x3060; // 4 Byte Integer +constexpr uint16_t VP_T_E0_Set = 0x3062; // 2 Byte Integer +constexpr uint16_t VP_T_E1_Is = 0x3064; // 4 Byte Integer + +// reserved to support up to 6 Extruders: +//constexpr uint16_t VP_T_E1_Set = 0x3066; // 2 Byte Integer +//constexpr uint16_t VP_T_E2_Is = 0x3068; // 4 Byte Integer +//constexpr uint16_t VP_T_E2_Set = 0x306A; // 2 Byte Integer +//constexpr uint16_t VP_T_E3_Is = 0x306C; // 4 Byte Integer +//constexpr uint16_t VP_T_E3_Set = 0x306E; // 2 Byte Integer +//constexpr uint16_t VP_T_E4_Is = 0x3070; // 4 Byte Integer +//constexpr uint16_t VP_T_E4_Set = 0x3072; // 2 Byte Integer +//constexpr uint16_t VP_T_E4_Is = 0x3074; // 4 Byte Integer +//constexpr uint16_t VP_T_E4_Set = 0x3076; // 2 Byte Integer +//constexpr uint16_t VP_T_E5_Is = 0x3078; // 4 Byte Integer +//constexpr uint16_t VP_T_E5_Set = 0x307A; // 2 Byte Integer + +constexpr uint16_t VP_T_Bed_Is = 0x3080; // 4 Byte Integer +constexpr uint16_t VP_T_Bed_Set = 0x3082; // 2 Byte Integer + +constexpr uint16_t VP_Flowrate_E0 = 0x3090; // 2 Byte Integer +constexpr uint16_t VP_Flowrate_E1 = 0x3092; // 2 Byte Integer + +// reserved for up to 6 Extruders: +//constexpr uint16_t VP_Flowrate_E2 = 0x3094; +//constexpr uint16_t VP_Flowrate_E3 = 0x3096; +//constexpr uint16_t VP_Flowrate_E4 = 0x3098; +//constexpr uint16_t VP_Flowrate_E5 = 0x309A; + +constexpr uint16_t VP_Fan0_Percentage = 0x3100; // 2 Byte Integer (0..100) +constexpr uint16_t VP_Fan1_Percentage = 0x3102; // 2 Byte Integer (0..100) +constexpr uint16_t VP_Fan2_Percentage = 0x3104; // 2 Byte Integer (0..100) +constexpr uint16_t VP_Fan3_Percentage = 0x3106; // 2 Byte Integer (0..100) +constexpr uint16_t VP_Feedrate_Percentage = 0x3108; // 2 Byte Integer (0..100) + +// Actual Position +constexpr uint16_t VP_XPos = 0x3110; // 4 Byte Fixed point number; format xxx.yy +constexpr uint16_t VP_YPos = 0x3112; // 4 Byte Fixed point number; format xxx.yy +constexpr uint16_t VP_ZPos = 0x3114; // 4 Byte Fixed point number; format xxx.yy + +constexpr uint16_t VP_EPos = 0x3120; // 4 Byte Fixed point number; format xxx.yy + +constexpr uint16_t VP_PrintProgress_Percentage = 0x3130; // 2 Byte Integer (0..100) + +constexpr uint16_t VP_PrintTime = 0x3140; +constexpr uint16_t VP_PrintTime_LEN = 32; + +constexpr uint16_t VP_PrintAccTime = 0x3160; +constexpr uint16_t VP_PrintAccTime_LEN = 32; + +constexpr uint16_t VP_PrintsTotal = 0x3180; +constexpr uint16_t VP_PrintsTotal_LEN = 16; + +// SDCard File Listing +constexpr uint16_t VP_SD_FileName_LEN = 32; // LEN is shared for all entries. +constexpr uint16_t DGUS_SD_FILESPERSCREEN = 5; // FIXME move that info to the display and read it from there. +constexpr uint16_t VP_SD_FileName0 = 0x3200; +constexpr uint16_t VP_SD_FileName1 = 0x3220; +constexpr uint16_t VP_SD_FileName2 = 0x3240; +constexpr uint16_t VP_SD_FileName3 = 0x3260; +constexpr uint16_t VP_SD_FileName4 = 0x3280; + +constexpr uint16_t VP_SD_Print_ProbeOffsetZ = 0x32A0; // + +constexpr uint16_t VP_SD_Print_Filename = 0x32C0; // +// Fan status +constexpr uint16_t VP_FAN0_STATUS = 0x3300; +constexpr uint16_t VP_FAN1_STATUS = 0x3302; +//constexpr uint16_t VP_FAN2_STATUS = 0x3304; +//constexpr uint16_t VP_FAN3_STATUS = 0x3306; + +// Heater status +constexpr uint16_t VP_E0_STATUS = 0x3310; +//constexpr uint16_t VP_E1_STATUS = 0x3312; +//constexpr uint16_t VP_E2_STATUS = 0x3314; +//constexpr uint16_t VP_E3_STATUS = 0x3316; +//constexpr uint16_t VP_E4_STATUS = 0x3318; +//constexpr uint16_t VP_E5_STATUS = 0x331A; +constexpr uint16_t VP_BED_STATUS = 0x331C; + +constexpr uint16_t VP_MOVE_OPTION = 0x3400; + +// Step per mm +constexpr uint16_t VP_X_STEP_PER_MM = 0x3600; // at the moment , 2 byte unsigned int , 0~1638.4 +//constexpr uint16_t VP_X2_STEP_PER_MM = 0x3602; +constexpr uint16_t VP_Y_STEP_PER_MM = 0x3604; +//constexpr uint16_t VP_Y2_STEP_PER_MM = 0x3606; +constexpr uint16_t VP_Z_STEP_PER_MM = 0x3608; +//constexpr uint16_t VP_Z2_STEP_PER_MM = 0x360A; +constexpr uint16_t VP_E0_STEP_PER_MM = 0x3610; +//constexpr uint16_t VP_E1_STEP_PER_MM = 0x3612; +//constexpr uint16_t VP_E2_STEP_PER_MM = 0x3614; +//constexpr uint16_t VP_E3_STEP_PER_MM = 0x3616; +//constexpr uint16_t VP_E4_STEP_PER_MM = 0x3618; +//constexpr uint16_t VP_E5_STEP_PER_MM = 0x361A; + +// PIDs +constexpr uint16_t VP_E0_PID_P = 0x3700; // at the moment , 2 byte unsigned int , 0~1638.4 +constexpr uint16_t VP_E0_PID_I = 0x3702; +constexpr uint16_t VP_E0_PID_D = 0x3704; +constexpr uint16_t VP_BED_PID_P = 0x3710; +constexpr uint16_t VP_BED_PID_I = 0x3712; +constexpr uint16_t VP_BED_PID_D = 0x3714; + +// Waiting screen status +constexpr uint16_t VP_WAITING_STATUS = 0x3800; + +// SPs for certain variables... +// located at 0x5000 and up +// Not used yet! +// This can be used e.g to make controls / data display invisible +constexpr uint16_t SP_T_E0_Is = 0x5000; +constexpr uint16_t SP_T_E0_Set = 0x5010; +constexpr uint16_t SP_T_E1_Is = 0x5020; +constexpr uint16_t SP_T_Bed_Is = 0x5030; +constexpr uint16_t SP_T_Bed_Set = 0x5040; diff --git a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp new file mode 100644 index 000000000000..c67ec73f6192 --- /dev/null +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp @@ -0,0 +1,420 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../../../inc/MarlinConfigPre.h" + +#if ENABLED(DGUS_LCD_UI_HIPRECY) + +#include "../DGUSScreenHandler.h" + +#include "../../../../MarlinCore.h" +#include "../../../../gcode/queue.h" +#include "../../../../libs/duration_t.h" +#include "../../../../module/settings.h" +#include "../../../../module/temperature.h" +#include "../../../../module/motion.h" +#include "../../../../module/planner.h" +#include "../../../../module/printcounter.h" +#include "../../../../sd/cardreader.h" + +#if ENABLED(POWER_LOSS_RECOVERY) + #include "../../../../feature/powerloss.h" +#endif + +#if ENABLED(SDSUPPORT) + + static ExtUI::FileList filelist; + + void DGUSScreenHandler::DGUSLCD_SD_FileSelected(DGUS_VP_Variable &var, void *val_ptr) { + uint16_t touched_nr = (int16_t)swap16(*(uint16_t*)val_ptr) + top_file; + if (touched_nr > filelist.count()) return; + if (!filelist.seek(touched_nr)) return; + + if (filelist.isDir()) { + filelist.changeDir(filelist.filename()); + top_file = 0; + ForceCompleteUpdate(); + return; + } + + #if ENABLED(DGUS_PRINT_FILENAME) + // Send print filename + dgusdisplay.WriteVariable(VP_SD_Print_Filename, filelist.filename(), VP_SD_FileName_LEN, true); + #endif + + // Setup Confirmation screen + file_to_print = touched_nr; + + HandleUserConfirmationPopUp(VP_SD_FileSelectConfirm, nullptr, PSTR("Print file"), filelist.filename(), PSTR("from SD Card?"), true, true, false, true); + } + + void DGUSScreenHandler::DGUSLCD_SD_StartPrint(DGUS_VP_Variable &var, void *val_ptr) { + if (!filelist.seek(file_to_print)) return; + ExtUI::printFile(filelist.shortFilename()); + GotoScreen(DGUSLCD_SCREEN_SDPRINTMANIPULATION); + } + + void DGUSScreenHandler::DGUSLCD_SD_ResumePauseAbort(DGUS_VP_Variable &var, void *val_ptr) { + + if (!ExtUI::isPrintingFromMedia()) return; // avoid race condition when user stays in this menu and printer finishes. + switch (swap16(*(uint16_t*)val_ptr)) { + case 0: { // Resume + if (ExtUI::isPrintingFromMediaPaused()) { + ExtUI::resumePrint(); + } + } break; + + case 1: // Pause + + GotoScreen(MKSLCD_SCREEN_PAUSE); + if (!ExtUI::isPrintingFromMediaPaused()) { + ExtUI::pausePrint(); + //ExtUI::mks_pausePrint(); + } + break; + case 2: // Abort + HandleUserConfirmationPopUp(VP_SD_AbortPrintConfirmed, nullptr, PSTR("Abort printing"), filelist.filename(), PSTR("?"), true, true, false, true); + break; + } + } + + void DGUSScreenHandler::DGUSLCD_SD_SendFilename(DGUS_VP_Variable& var) { + uint16_t target_line = (var.VP - VP_SD_FileName0) / VP_SD_FileName_LEN; + if (target_line > DGUS_SD_FILESPERSCREEN) return; + char tmpfilename[VP_SD_FileName_LEN + 1] = ""; + var.memadr = (void*)tmpfilename; + + if (filelist.seek(top_file + target_line)) { + snprintf_P(tmpfilename, VP_SD_FileName_LEN, PSTR("%s%c"), filelist.filename(), filelist.isDir() ? '/' : 0); // snprintf_P(tmpfilename, VP_SD_FileName_LEN, PSTR("%s"), filelist.filename()); + } + DGUSLCD_SendStringToDisplay(var); + } + + void DGUSScreenHandler::SDCardInserted() { + top_file = 0; + filelist.refresh(); + auto cs = getCurrentScreen(); + if (cs == DGUSLCD_SCREEN_MAIN || cs == DGUSLCD_SCREEN_STATUS) + GotoScreen(DGUSLCD_SCREEN_SDFILELIST); + } + + void DGUSScreenHandler::SDCardRemoved() { + if (current_screen == DGUSLCD_SCREEN_SDFILELIST + || (current_screen == DGUSLCD_SCREEN_CONFIRM && (ConfirmVP == VP_SD_AbortPrintConfirmed || ConfirmVP == VP_SD_FileSelectConfirm)) + || current_screen == DGUSLCD_SCREEN_SDPRINTMANIPULATION + ) GotoScreen(DGUSLCD_SCREEN_MAIN); + } + +#endif // SDSUPPORT + +void DGUSScreenHandler::ScreenChangeHook(DGUS_VP_Variable &var, void *val_ptr) { + uint8_t *tmp = (uint8_t*)val_ptr; + + // The keycode in target is coded as , so 0x0100A means + // from screen 1 (main) to 10 (temperature). DGUSLCD_SCREEN_POPUP is special, + // meaning "return to previous screen" + DGUSLCD_Screens target = (DGUSLCD_Screens)tmp[1]; + + DEBUG_ECHOLNPAIR("\n DEBUG target", target); + + if (target == DGUSLCD_SCREEN_POPUP) { + // Special handling for popup is to return to previous menu + if (current_screen == DGUSLCD_SCREEN_POPUP && confirm_action_cb) confirm_action_cb(); + PopToOldScreen(); + return; + } + + UpdateNewScreen(target); + + #ifdef DEBUG_DGUSLCD + if (!DGUSLCD_FindScreenVPMapList(target)) DEBUG_ECHOLNPAIR("WARNING: No screen Mapping found for ", target); + #endif +} + +void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("HandleManualMove"); + + int16_t movevalue = swap16(*(uint16_t*)val_ptr); + #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) + if (movevalue) { + const uint16_t choice = *(uint16_t*)var.memadr; + movevalue = movevalue < 0 ? -choice : choice; + } + #endif + char axiscode; + unsigned int speed = 1500; // FIXME: get default feedrate for manual moves, don't hardcode. + + switch (var.VP) { + default: return; + + case VP_MOVE_X: + axiscode = 'X'; + if (!ExtUI::canMove(ExtUI::axis_t::X)) goto cannotmove; + break; + + case VP_MOVE_Y: + axiscode = 'Y'; + if (!ExtUI::canMove(ExtUI::axis_t::Y)) goto cannotmove; + break; + + case VP_MOVE_Z: + axiscode = 'Z'; + speed = 300; // default to 5mm/s + if (!ExtUI::canMove(ExtUI::axis_t::Z)) goto cannotmove; + break; + + case VP_HOME_ALL: // only used for homing + axiscode = '\0'; + movevalue = 0; // ignore value sent from display, this VP is _ONLY_ for homing. + break; + } + + if (!movevalue) { + // homing + DEBUG_ECHOPAIR(" homing ", AS_CHAR(axiscode)); + char buf[6] = "G28 X"; + buf[4] = axiscode; + //DEBUG_ECHOPAIR(" ", buf); + queue.enqueue_one_now(buf); + //DEBUG_ECHOLNPGM(" ✓"); + ForceCompleteUpdate(); + return; + } + else { + // movement + DEBUG_ECHOPAIR(" move ", AS_CHAR(axiscode)); + bool old_relative_mode = relative_mode; + if (!relative_mode) { + //DEBUG_ECHOPGM(" G91"); + queue.enqueue_now_P(PSTR("G91")); + //DEBUG_ECHOPGM(" ✓ "); + } + char buf[32]; // G1 X9999.99 F12345 + unsigned int backup_speed = MMS_TO_MMM(feedrate_mm_s); + char sign[] = "\0"; + int16_t value = movevalue / 100; + if (movevalue < 0) { value = -value; sign[0] = '-'; } + int16_t fraction = ABS(movevalue) % 100; + snprintf_P(buf, 32, PSTR("G0 %c%s%d.%02d F%d"), axiscode, sign, value, fraction, speed); + //DEBUG_ECHOPAIR(" ", buf); + queue.enqueue_one_now(buf); + //DEBUG_ECHOLNPGM(" ✓ "); + if (backup_speed != speed) { + snprintf_P(buf, 32, PSTR("G0 F%d"), backup_speed); + queue.enqueue_one_now(buf); + //DEBUG_ECHOPAIR(" ", buf); + } + // while (!enqueue_and_echo_command(buf)) idle(); + //DEBUG_ECHOLNPGM(" ✓ "); + if (!old_relative_mode) { + //DEBUG_ECHOPGM("G90"); + queue.enqueue_now_P(PSTR("G90")); + //DEBUG_ECHOPGM(" ✓ "); + } + } + + ForceCompleteUpdate(); + DEBUG_ECHOLNPGM("manmv done."); + return; + + cannotmove: + DEBUG_ECHOLNPAIR(" cannot move ", AS_CHAR(axiscode)); + return; +} + +#if HAS_PID_HEATING + void DGUSScreenHandler::HandleTemperaturePIDChanged(DGUS_VP_Variable &var, void *val_ptr) { + uint16_t rawvalue = swap16(*(uint16_t*)val_ptr); + DEBUG_ECHOLNPAIR("V1:", rawvalue); + float value = (float)rawvalue / 10; + DEBUG_ECHOLNPAIR("V2:", value); + float newvalue = 0; + + switch (var.VP) { + default: return; + #if HAS_HOTEND + case VP_E0_PID_P: newvalue = value; break; + case VP_E0_PID_I: newvalue = scalePID_i(value); break; + case VP_E0_PID_D: newvalue = scalePID_d(value); break; + #endif + #if HOTENDS >= 2 + case VP_E1_PID_P: newvalue = value; break; + case VP_E1_PID_I: newvalue = scalePID_i(value); break; + case VP_E1_PID_D: newvalue = scalePID_d(value); break; + #endif + #if HAS_HEATED_BED + case VP_BED_PID_P: newvalue = value; break; + case VP_BED_PID_I: newvalue = scalePID_i(value); break; + case VP_BED_PID_D: newvalue = scalePID_d(value); break; + #endif + } + + DEBUG_ECHOLNPAIR_F("V3:", newvalue); + *(float *)var.memadr = newvalue; + + skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel + } +#endif // HAS_PID_HEATING + +#if ENABLED(BABYSTEPPING) + void DGUSScreenHandler::HandleLiveAdjustZ(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("HandleLiveAdjustZ"); + int16_t flag = swap16(*(uint16_t*)val_ptr), + steps = flag ? -20 : 20; + ExtUI::smartAdjustAxis_steps(steps, ExtUI::axis_t::Z, true); + ForceCompleteUpdate(); + } +#endif + +#if ENABLED(DGUS_FILAMENT_LOADUNLOAD) + + void DGUSScreenHandler::HandleFilamentOption(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("HandleFilamentOption"); + + uint8_t e_temp = 0; + filament_data.heated = false; + uint16_t preheat_option = swap16(*(uint16_t*)val_ptr); + if (preheat_option <= 8) { // Load filament type + filament_data.action = 1; + } + else if (preheat_option >= 10) { // Unload filament type + preheat_option -= 10; + filament_data.action = 2; + filament_data.purge_length = DGUS_FILAMENT_PURGE_LENGTH; + } + else { // Cancel filament operation + filament_data.action = 0; + } + + switch (preheat_option) { + case 0: // Load PLA + #ifdef PREHEAT_1_TEMP_HOTEND + e_temp = PREHEAT_1_TEMP_HOTEND; + #endif + break; + case 1: // Load ABS + TERN_(PREHEAT_2_TEMP_HOTEND, e_temp = PREHEAT_2_TEMP_HOTEND); + break; + case 2: // Load PET + #ifdef PREHEAT_3_TEMP_HOTEND + e_temp = PREHEAT_3_TEMP_HOTEND; + #endif + break; + case 3: // Load FLEX + #ifdef PREHEAT_4_TEMP_HOTEND + e_temp = PREHEAT_4_TEMP_HOTEND; + #endif + break; + case 9: // Cool down + default: + e_temp = 0; + break; + } + + if (filament_data.action == 0) { // Go back to utility screen + #if HAS_HOTEND + thermalManager.setTargetHotend(e_temp, ExtUI::extruder_t::E0); + #if HOTENDS >= 2 + thermalManager.setTargetHotend(e_temp, ExtUI::extruder_t::E1); + #endif + #endif + GotoScreen(DGUSLCD_SCREEN_UTILITY); + } + else { // Go to the preheat screen to show the heating progress + switch (var.VP) { + default: return; + #if HAS_HOTEND + case VP_E0_FILAMENT_LOAD_UNLOAD: + filament_data.extruder = ExtUI::extruder_t::E0; + thermalManager.setTargetHotend(e_temp, filament_data.extruder); + break; + #endif + #if HOTENDS >= 2 + case VP_E1_FILAMENT_LOAD_UNLOAD: + filament_data.extruder = ExtUI::extruder_t::E1; + thermalManager.setTargetHotend(e_temp, filament_data.extruder); + break; + #endif + } + GotoScreen(DGUSLCD_SCREEN_FILAMENT_HEATING); + } + } + + void DGUSScreenHandler::HandleFilamentLoadUnload(DGUS_VP_Variable &var) { + DEBUG_ECHOLNPGM("HandleFilamentLoadUnload"); + if (filament_data.action <= 0) return; + + // If we close to the target temperature, we can start load or unload the filament + if (thermalManager.hotEnoughToExtrude(filament_data.extruder) && \ + thermalManager.targetHotEnoughToExtrude(filament_data.extruder)) { + float movevalue = DGUS_FILAMENT_LOAD_LENGTH_PER_TIME; + + if (filament_data.action == 1) { // load filament + if (!filament_data.heated) { + //GotoScreen(DGUSLCD_SCREEN_FILAMENT_LOADING); + filament_data.heated = true; + } + movevalue = ExtUI::getAxisPosition_mm(filament_data.extruder) + movevalue; + } + else { // unload filament + if (!filament_data.heated) { + GotoScreen(DGUSLCD_SCREEN_FILAMENT_UNLOADING); + filament_data.heated = true; + } + // Before unloading extrude to prevent jamming + if (filament_data.purge_length >= 0) { + movevalue = ExtUI::getAxisPosition_mm(filament_data.extruder) + movevalue; + filament_data.purge_length -= movevalue; + } + else { + movevalue = ExtUI::getAxisPosition_mm(filament_data.extruder) - movevalue; + } + } + ExtUI::setAxisPosition_mm(movevalue, filament_data.extruder); + } + } +#endif // DGUS_FILAMENT_LOADUNLOAD + +bool DGUSScreenHandler::loop() { + dgusdisplay.loop(); + + const millis_t ms = millis(); + static millis_t next_event_ms = 0; + + if (!IsScreenComplete() || ELAPSED(ms, next_event_ms)) { + next_event_ms = ms + DGUS_UPDATE_INTERVAL_MS; + UpdateScreenVPData(); + } + + #if ENABLED(SHOW_BOOTSCREEN) + static bool booted = false; + + if (!booted && TERN0(POWER_LOSS_RECOVERY, recovery.valid())) + booted = true; + + if (!booted && ELAPSED(ms, TERN(USE_MKS_GREEN_UI, 1000, BOOTSCREEN_TIMEOUT))) + booted = true; + #endif + return IsScreenComplete(); +} + +#endif // DGUS_LCD_UI_HIPRECY diff --git a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.h new file mode 100644 index 000000000000..ee0af013a855 --- /dev/null +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.h @@ -0,0 +1,240 @@ +/** + * 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 + +#include "../DGUSDisplay.h" +#include "../DGUSVPVariable.h" +#include "../DGUSDisplayDef.h" + +#include "../../../../inc/MarlinConfig.h" + +enum DGUSLCD_Screens : uint8_t; + +class DGUSScreenHandler { +public: + DGUSScreenHandler() = default; + + static bool loop(); + + // Send all 4 strings that are displayed on the infoscreen, confirmation screen and kill screen + // The bools specifying whether the strings are in RAM or FLASH. + static void sendinfoscreen(const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); + + static void HandleUserConfirmationPopUp(uint16_t ConfirmVP, const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); + + // "M117" Message -- msg is a RAM ptr. + static void setstatusmessage(const char *msg); + // The same for messages from Flash + static void setstatusmessagePGM(PGM_P const msg); + // Callback for VP "Display wants to change screen on idle printer" + static void ScreenChangeHookIfIdle(DGUS_VP_Variable &var, void *val_ptr); + // Callback for VP "Screen has been changed" + static void ScreenChangeHook(DGUS_VP_Variable &var, void *val_ptr); + + // Callback for VP "All Heaters Off" + static void HandleAllHeatersOff(DGUS_VP_Variable &var, void *val_ptr); + // Hook for "Change this temperature" + static void HandleTemperatureChanged(DGUS_VP_Variable &var, void *val_ptr); + // Hook for "Change Flowrate" + static void HandleFlowRateChanged(DGUS_VP_Variable &var, void *val_ptr); + #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) + // Hook for manual move option + static void HandleManualMoveOption(DGUS_VP_Variable &var, void *val_ptr); + #endif + + // Hook for manual move. + static void HandleManualMove(DGUS_VP_Variable &var, void *val_ptr); + // Hook for manual extrude. + static void HandleManualExtrude(DGUS_VP_Variable &var, void *val_ptr); + // Hook for motor lock and unlook + static void HandleMotorLockUnlock(DGUS_VP_Variable &var, void *val_ptr); + #if ENABLED(POWER_LOSS_RECOVERY) + // Hook for power loss recovery. + static void HandlePowerLossRecovery(DGUS_VP_Variable &var, void *val_ptr); + #endif + // Hook for settings + static void HandleSettings(DGUS_VP_Variable &var, void *val_ptr); + static void HandleStepPerMMChanged(DGUS_VP_Variable &var, void *val_ptr); + static void HandleStepPerMMExtruderChanged(DGUS_VP_Variable &var, void *val_ptr); + + #if HAS_PID_HEATING + // Hook for "Change this temperature PID para" + static void HandleTemperaturePIDChanged(DGUS_VP_Variable &var, void *val_ptr); + // Hook for PID autotune + static void HandlePIDAutotune(DGUS_VP_Variable &var, void *val_ptr); + #endif + #if HAS_BED_PROBE + // Hook for "Change probe offset z" + static void HandleProbeOffsetZChanged(DGUS_VP_Variable &var, void *val_ptr); + #endif + #if ENABLED(BABYSTEPPING) + // Hook for live z adjust action + static void HandleLiveAdjustZ(DGUS_VP_Variable &var, void *val_ptr); + #endif + #if HAS_FAN + // Hook for fan control + static void HandleFanControl(DGUS_VP_Variable &var, void *val_ptr); + #endif + // Hook for heater control + static void HandleHeaterControl(DGUS_VP_Variable &var, void *val_ptr); + #if ENABLED(DGUS_PREHEAT_UI) + // Hook for preheat + static void HandlePreheat(DGUS_VP_Variable &var, void *val_ptr); + #endif + #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) + // Hook for filament load and unload filament option + static void HandleFilamentOption(DGUS_VP_Variable &var, void *val_ptr); + // Hook for filament load and unload + static void HandleFilamentLoadUnload(DGUS_VP_Variable &var); + #endif + + #if ENABLED(SDSUPPORT) + // 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. + static void DGUSLCD_SD_ScrollFilelist(DGUS_VP_Variable &var, void *val_ptr); + // File touched. + static void DGUSLCD_SD_FileSelected(DGUS_VP_Variable &var, void *val_ptr); + // start print after confirmation received. + static void DGUSLCD_SD_StartPrint(DGUS_VP_Variable &var, void *val_ptr); + // User hit the pause, resume or abort button. + static void DGUSLCD_SD_ResumePauseAbort(DGUS_VP_Variable &var, void *val_ptr); + // User confirmed the abort action + static void DGUSLCD_SD_ReallyAbort(DGUS_VP_Variable &var, void *val_ptr); + // User hit the tune button + static void DGUSLCD_SD_PrintTune(DGUS_VP_Variable &var, void *val_ptr); + // Send a single filename to the display. + static void DGUSLCD_SD_SendFilename(DGUS_VP_Variable &var); + // Marlin informed us that a new SD has been inserted. + static void SDCardInserted(); + // Marlin informed us that the SD Card has been removed(). + static void SDCardRemoved(); + // Marlin informed us about a bad SD Card. + static void SDCardError(); + #endif + + // OK Button the Confirm screen. + static void ScreenConfirmedOK(DGUS_VP_Variable &var, void *val_ptr); + + // Update data after went to new screen (by display or by GotoScreen) + // remember: store the last-displayed screen, so it can get returned to. + // (e.g for pop up messages) + static void UpdateNewScreen(DGUSLCD_Screens newscreen, bool popup=false); + + // Recall the remembered screen. + static void PopToOldScreen(); + + // Make the display show the screen and update all VPs in it. + static void GotoScreen(DGUSLCD_Screens screen, bool ispopup = false); + + static void UpdateScreenVPData(); + + // Helpers to convert and transfer data to the display. + static void DGUSLCD_SendWordValueToDisplay(DGUS_VP_Variable &var); + static void DGUSLCD_SendStringToDisplay(DGUS_VP_Variable &var); + static void DGUSLCD_SendStringToDisplayPGM(DGUS_VP_Variable &var); + static void DGUSLCD_SendTemperaturePID(DGUS_VP_Variable &var); + static void DGUSLCD_SendPercentageToDisplay(DGUS_VP_Variable &var); + static void DGUSLCD_SendPrintProgressToDisplay(DGUS_VP_Variable &var); + static void DGUSLCD_SendPrintTimeToDisplay(DGUS_VP_Variable &var); + + #if ENABLED(PRINTCOUNTER) + static void DGUSLCD_SendPrintAccTimeToDisplay(DGUS_VP_Variable &var); + static void DGUSLCD_SendPrintsTotalToDisplay(DGUS_VP_Variable &var); + #endif + #if HAS_FAN + static void DGUSLCD_SendFanStatusToDisplay(DGUS_VP_Variable &var); + #endif + static void DGUSLCD_SendHeaterStatusToDisplay(DGUS_VP_Variable &var); + #if ENABLED(DGUS_UI_WAITING) + static void DGUSLCD_SendWaitingStatusToDisplay(DGUS_VP_Variable &var); + #endif + + // Send a value from 0..100 to a variable with a range from 0..255 + static void DGUSLCD_PercentageToUint8(DGUS_VP_Variable &var, void *val_ptr); + + template + static void DGUSLCD_SetValueDirectly(DGUS_VP_Variable &var, void *val_ptr) { + if (!var.memadr) return; + union { unsigned char tmp[sizeof(T)]; T t; } x; + unsigned char *ptr = (unsigned char*)val_ptr; + LOOP_L_N(i, sizeof(T)) x.tmp[i] = ptr[sizeof(T) - i - 1]; + *(T*)var.memadr = x.t; + } + + // Send a float value to the display. + // Display will get a 4-byte integer scaled to the number of digits: + // Tell the display the number of digits and it cheats by displaying a dot between... + template + static void DGUSLCD_SendFloatAsLongValueToDisplay(DGUS_VP_Variable &var) { + if (var.memadr) { + float f = *(float *)var.memadr; + f *= cpow(10, decimals); + dgusdisplay.WriteVariable(var.VP, (long)f); + } + } + + // Send a float value to the display. + // Display will get a 2-byte integer scaled to the number of digits: + // Tell the display the number of digits and it cheats by displaying a dot between... + template + static void DGUSLCD_SendFloatAsIntValueToDisplay(DGUS_VP_Variable &var) { + if (var.memadr) { + float f = *(float *)var.memadr; + DEBUG_ECHOLNPAIR_F(" >> ", f, 6); + f *= cpow(10, decimals); + dgusdisplay.WriteVariable(var.VP, (int16_t)f); + } + } + + // Force an update of all VP on the current screen. + static inline void ForceCompleteUpdate() { update_ptr = 0; ScreenComplete = false; } + // Has all VPs sent to the screen + static inline bool IsScreenComplete() { return ScreenComplete; } + + static inline DGUSLCD_Screens getCurrentScreen() { return current_screen; } + + static inline void SetupConfirmAction( void (*f)()) { confirm_action_cb = f; } + +private: + static DGUSLCD_Screens current_screen; //< currently on screen + static constexpr uint8_t NUM_PAST_SCREENS = 4; + static DGUSLCD_Screens past_screens[NUM_PAST_SCREENS]; //< LIFO with past screens for the "back" button. + + static uint8_t update_ptr; //< Last sent entry in the VPList for the actual screen. + static uint16_t skipVP; //< When updating the screen data, skip this one, because the user is interacting with it. + static bool ScreenComplete; //< All VPs sent to screen? + + static uint16_t ConfirmVP; //< context for confirm screen (VP that will be emulated-sent on "OK"). + + #if ENABLED(SDSUPPORT) + static int16_t top_file; //< file on top of file chooser + static int16_t file_to_print; //< touched file to be confirmed + #endif + + static void (*confirm_action_cb)(); +}; + +#if ENABLED(POWER_LOSS_RECOVERY) + #define PLR_SCREEN_RECOVER DGUSLCD_SCREEN_SDPRINTMANIPULATION + #define PLR_SCREEN_CANCEL DGUSLCD_SCREEN_STATUS +#endif diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp new file mode 100644 index 000000000000..9ecfb57397b9 --- /dev/null +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp @@ -0,0 +1,802 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../../../inc/MarlinConfigPre.h" + +#if ENABLED(DGUS_LCD_UI_MKS) + +#include "DGUSDisplayDef.h" +#include "../DGUSDisplay.h" +#include "../DGUSScreenHandler.h" + +#include "../../../../module/temperature.h" +#include "../../../../module/motion.h" +#include "../../../../module/planner.h" + +#include "../../ui_api.h" +#include "../../../marlinui.h" + +#if HAS_STEALTHCHOP + #include "../../../../module/stepper/trinamic.h" +#endif + +#if ENABLED(POWER_LOSS_RECOVERY) + #include "../../../../../feature/powerloss.h" +#endif + +#if ENABLED(DGUS_UI_MOVE_DIS_OPTION) + uint16_t distanceToMove = 10; +#endif + +uint16_t manualMoveStep = 1; +uint16_t distanceFilament = 10; +uint16_t filamentSpeed_mm_s = 25; +float ZOffset_distance = 0.1; +float mesh_adj_distance = 0.01; +float Z_distance = 0.1; + +//struct { uint16_t h, m, s; } dgus_time; + +// +// Persistent settings +// +xy_int_t mks_corner_offsets[5]; // Initialized by settings.load() +xyz_int_t mks_park_pos; // Initialized by settings.load() +celsius_t mks_min_extrusion_temp; // Initialized by settings.load() + +void MKS_reset_settings() { + constexpr xy_int_t init_dgus_level_offsets[5] = { + { 20, 20 }, { 20, 20 }, + { 20, 20 }, { 20, 20 }, + { X_CENTER, Y_CENTER } + }; + mks_language_index = 0; + COPY(mks_corner_offsets, init_dgus_level_offsets); + mks_park_pos.set(20, 20, 10); + mks_min_extrusion_temp = 0; +} + +xyz_pos_t position_before_pause; +constexpr feedRate_t park_speed_xy = TERN(NOZZLE_PARK_FEATURE, NOZZLE_PARK_XY_FEEDRATE, 100), + park_speed_z = TERN(NOZZLE_PARK_FEATURE, NOZZLE_PARK_Z_FEEDRATE, 5); + +void MKS_pause_print_move() { + queue.exhaust(); + position_before_pause = current_position; + + // Save the current position, the raise amount, and 'already raised' + TERN_(POWER_LOSS_RECOVERY, if (recovery.enabled) recovery.save(true, mks_park_pos.z, true)); + + destination.z = _MIN(current_position.z + mks_park_pos.z, Z_MAX_POS); + prepare_internal_move_to_destination(park_speed_z); + + destination.set(X_MIN_POS + mks_park_pos.x, Y_MIN_POS + mks_park_pos.y); + prepare_internal_move_to_destination(park_speed_xy); +} + +void MKS_resume_print_move() { + destination.set(position_before_pause.x, position_before_pause.y); + prepare_internal_move_to_destination(park_speed_xy); + destination.z = position_before_pause.z; + prepare_internal_move_to_destination(park_speed_z); + TERN_(POWER_LOSS_RECOVERY, if (recovery.enabled) recovery.save(true)); +} + +float z_offset_add = 0; + +xyz_int_t tmc_step; // = { 0, 0, 0 } + +uint16_t lcd_default_light = 50; + +EX_FILAMENT_DEF ex_filament; +RUNOUT_MKS_DEF runout_mks; +NOZZLE_PARK_DEF nozzle_park_mks; + +const uint16_t VPList_Boot[] PROGMEM = { + VP_MARLIN_VERSION, + 0x0000 +}; + +#define MKSLIST_E_ITEM(N) VP_T_E##N##_Is, VP_T_E##N##_Set, + +const uint16_t VPList_Main[] PROGMEM = { + // VP_M117, for completeness, but it cannot be auto-uploaded. + #if HAS_HOTEND + MKSLIST_E_ITEM(0) VP_E0_STATUS, + #if HOTENDS >= 2 + MKSLIST_E_ITEM(1) VP_E1_STATUS, + #endif + #endif + #if HAS_HEATED_BED + VP_T_Bed_Is, VP_T_Bed_Set, VP_BED_STATUS, + #endif + #if HAS_FAN + VP_Fan0_Percentage, VP_FAN0_STATUS, + #endif + VP_XPos, VP_YPos, VP_ZPos, + VP_Fan0_Percentage, + VP_Feedrate_Percentage, + #if ENABLED(LCD_SET_PROGRESS_MANUALLY) + VP_PrintProgress_Percentage, + #endif + 0x0000 +}; + +const uint16_t MKSList_Home[] PROGMEM = { + // E Temp + REPEAT(EXTRUDERS, MKSLIST_E_ITEM) + // HB Temp + VP_T_Bed_Is, VP_T_Bed_Set, + // FAN + VP_Fan0_Percentage, + // Language + // VP_HOME_Dis, + + 0x0000 +}; + +const uint16_t MKSList_Setting[] PROGMEM = { + // E Temp + REPEAT(EXTRUDERS, MKSLIST_E_ITEM) + // HB Temp + VP_T_Bed_Is, VP_T_Bed_Set, + // FAN + VP_Fan0_Percentage, + // Language + VP_Setting_Dis, + 0x0000 +}; + +const uint16_t MKSList_Tool[] PROGMEM = { + // E Temp + REPEAT(EXTRUDERS, MKSLIST_E_ITEM) + // HB Temp + VP_T_Bed_Is, VP_T_Bed_Set, + // FAN + VP_Fan0_Percentage, + // Language + VP_Tool_Dis, + // LCD BLK + VP_LCD_BLK, + 0x0000 +}; + +const uint16_t MKSList_EXTRUE[] PROGMEM = { + // E Temp + REPEAT(EXTRUDERS, MKSLIST_E_ITEM) + // HB Temp + VP_T_Bed_Is, VP_T_Bed_Set, + // FAN + VP_Fan0_Percentage, + + VP_Filament_distance, + VP_Filament_speed, + + 0x0000 +}; + +const uint16_t MKSList_LEVEL[] PROGMEM = { + // E Temp + REPEAT(EXTRUDERS, MKSLIST_E_ITEM) + // HB Temp + VP_T_Bed_Is, VP_T_Bed_Set, + // FAN + VP_Fan0_Percentage, + + 0x0000 +}; + +const uint16_t MKSList_MOVE[] PROGMEM = { + // E Temp + REPEAT(EXTRUDERS, MKSLIST_E_ITEM) + // HB Temp + VP_T_Bed_Is, VP_T_Bed_Set, + // FAN + VP_Fan0_Percentage, + + 0x0000 +}; + +const uint16_t MKSList_Print[] PROGMEM = { + // E Temp + REPEAT(EXTRUDERS, MKSLIST_E_ITEM) + // HB Temp + VP_T_Bed_Is, VP_T_Bed_Set, + // FAN + VP_Fan0_Percentage, + // Print Percent + VP_PrintProgress_Percentage, + + VP_PrintTime, + + VP_Flowrate_E0, + VP_Flowrate_E1, + VP_Feedrate_Percentage, + + VP_PrintTime_H, + VP_PrintTime_M, + VP_PrintTime_S, + + VP_XPos, + VP_YPos, + VP_ZPos, + + 0x0000 +}; + +const uint16_t MKSList_SD_File[] PROGMEM = { + VP_SD_FileName0, VP_SD_FileName1, + VP_SD_FileName2, VP_SD_FileName3, + VP_SD_FileName4, VP_SD_FileName5, + VP_SD_FileName6, VP_SD_FileName7, + VP_SD_FileName8, VP_SD_FileName9, + + 0x0000 +}; + +const uint16_t MKSList_TempOnly[] PROGMEM = { + // E Temp + REPEAT(EXTRUDERS, MKSLIST_E_ITEM) + // HB Temp + VP_T_Bed_Is, VP_T_Bed_Set, + // FAN + VP_Fan0_Percentage, + // LCD BLK + VP_LCD_BLK, + 0x0000 +}; + +const uint16_t MKSList_Pluse[] PROGMEM = { + // E Temp + REPEAT(EXTRUDERS, MKSLIST_E_ITEM) + // HB Temp + VP_T_Bed_Is, VP_T_Bed_Set, + // FAN + VP_Fan0_Percentage, + + // Pluse + VP_X_STEP_PER_MM, + VP_Y_STEP_PER_MM, + VP_Z_STEP_PER_MM, + VP_E0_STEP_PER_MM, + VP_E1_STEP_PER_MM, + + 0x0000 +}; + +const uint16_t MKSList_MaxSpeed[] PROGMEM = { + // E Temp + REPEAT(EXTRUDERS, MKSLIST_E_ITEM) + // HB Temp + VP_T_Bed_Is, VP_T_Bed_Set, + // FAN + VP_Fan0_Percentage, + + // Pluse + VP_X_MAX_SPEED, + VP_Y_MAX_SPEED, + VP_Z_MAX_SPEED, + VP_E0_MAX_SPEED, + VP_E1_MAX_SPEED, + + 0x0000 +}; + +const uint16_t MKSList_MaxAcc[] PROGMEM = { + // E Temp + REPEAT(EXTRUDERS, MKSLIST_E_ITEM) + // HB Temp + VP_T_Bed_Is, VP_T_Bed_Set, + // FAN + VP_Fan0_Percentage, + + // ACC + VP_ACC_SPEED, + VP_X_ACC_MAX_SPEED, + VP_Y_ACC_MAX_SPEED, + VP_Z_ACC_MAX_SPEED, + VP_E0_ACC_MAX_SPEED, + VP_E1_ACC_MAX_SPEED, + + 0x0000 +}; + +const uint16_t MKSList_PID[] PROGMEM = { + // E Temp + REPEAT(EXTRUDERS, MKSLIST_E_ITEM) + // HB Temp + VP_T_Bed_Is, VP_T_Bed_Set, + // FAN + VP_Fan0_Percentage, + + // PID + VP_E0_PID_P, + VP_E0_PID_I, + VP_E0_PID_D, + + 0x0000 +}; + +const uint16_t MKSList_Level_Point[] PROGMEM = { + // E Temp + REPEAT(EXTRUDERS, MKSLIST_E_ITEM) + // HB Temp + VP_T_Bed_Is, VP_T_Bed_Set, + // FAN + VP_Fan0_Percentage, + + // Level Point + VP_Level_Point_One_X, + VP_Level_Point_One_Y, + VP_Level_Point_Two_X, + VP_Level_Point_Two_Y, + VP_Level_Point_Three_X, + VP_Level_Point_Three_Y, + VP_Level_Point_Four_X, + VP_Level_Point_Four_Y, + VP_Level_Point_Five_X, + VP_Level_Point_Five_Y, + + 0x0000 +}; + +const uint16_t MKSList_Level_PrintConfig[] PROGMEM = { + VP_T_E0_Set, + VP_T_E1_Set, + VP_T_Bed_Set, + VP_Flowrate_E0, + VP_Flowrate_E1, + VP_Fan0_Percentage, + VP_Feedrate_Percentage, + + 0x0000 +}; + +const uint16_t MKSList_PrintPauseConfig[] PROGMEM = { + // E Temp + REPEAT(EXTRUDERS, MKSLIST_E_ITEM) + // HB Temp + VP_T_Bed_Is, VP_T_Bed_Set, + + VP_X_PARK_POS, + VP_Y_PARK_POS, + VP_Z_PARK_POS, + + 0x0000 +}; + +const uint16_t MKSList_MotoConfig[] PROGMEM = { + // E Temp + REPEAT(EXTRUDERS, MKSLIST_E_ITEM) + // HB Temp + VP_T_Bed_Is, VP_T_Bed_Set, + + VP_TRAVEL_SPEED, + VP_FEEDRATE_MIN_SPEED, + VP_T_F_SPEED, + + 0x0000 +}; + +const uint16_t MKSList_EX_Config[] PROGMEM = { + // E Temp + REPEAT(EXTRUDERS, MKSLIST_E_ITEM) + // HB Temp + VP_T_Bed_Is, VP_T_Bed_Set, + VP_MIN_EX_T,VP_Min_EX_T_E, + 0x0000 +}; + +const uint16_t MKSTMC_Config[] PROGMEM = { + // E Temp + REPEAT(EXTRUDERS, MKSLIST_E_ITEM) + // HB Temp + VP_T_Bed_Is, VP_T_Bed_Set, + VP_MIN_EX_T, + + VP_TMC_X_STEP, + VP_TMC_Y_STEP, + VP_TMC_Z_STEP, + VP_TMC_X1_Current, + VP_TMC_Y1_Current, + VP_TMC_X_Current, + VP_TMC_Y_Current, + VP_TMC_Z_Current, + VP_TMC_E0_Current, + VP_TMC_E1_Current, + VP_TMC_Z1_Current, + + 0x0000 +}; + +const uint16_t MKSAuto_Level[] PROGMEM = { + VP_MESH_LEVEL_POINT_DIS, + VP_ZPos, + 0x0000 +}; + +const uint16_t MKSOffset_Config[] PROGMEM = { + // E Temp + REPEAT(EXTRUDERS, MKSLIST_E_ITEM) + VP_OFFSET_X, + VP_OFFSET_Y, + VP_OFFSET_Z, + 0x0000 +}; + +const uint16_t MKSBabyStep[] PROGMEM = { + VP_ZOffset_DE_DIS, + 0x0000 +}; + +const uint16_t MKSList_About[] PROGMEM = { + // Marlin version + VP_MARLIN_VERSION, + // H43 Version + VP_MKS_H43_VERSION, + VP_MKS_H43_UpdataVERSION, + 0x0000 +}; + +// Page data updata +const struct VPMapping VPMap[] PROGMEM = { + { MKSLCD_SCREEN_BOOT, VPList_Boot }, // Boot Page to show logo 0 + { MKSLCD_SCREEN_HOME, MKSList_Home }, // Home, Page 1 + { MKSLCD_SCREEN_SETTING, MKSList_Setting }, // Setting, Page 2 + { MKSLCD_SCREEM_TOOL, MKSList_Tool }, // Page 3 + { MKSLCD_SCREEN_EXTRUDE_P1, MKSList_EXTRUE }, // Page 4 + { MKSLCD_SCREEN_EXTRUDE_P2, MKSList_EXTRUE }, // Page 11 + { MKSLCD_PAUSE_SETTING_EX, MKSList_EXTRUE }, // Page 57 + { MKSLCD_PAUSE_SETTING_EX2, MKSList_EXTRUE }, // Page 61 + { MKSLCD_SCREEN_LEVEL, MKSList_LEVEL }, // Page 5 + { MKSLCD_SCREEN_MOVE, MKSList_MOVE }, // Page 6 + { MKSLCD_SCREEN_PRINT, MKSList_Print }, // Page 7 + { MKSLCD_SCREEN_PAUSE, MKSList_Print }, // Page 26 + { MKSLCD_SCREEN_CHOOSE_FILE, MKSList_SD_File }, // Page 15 + { MKSLCD_SCREEN_MOTOR_PLUSE, MKSList_Pluse }, // Page 51 + { MKSLCD_SCREEN_MOTOR_SPEED, MKSList_MaxSpeed }, // Page 55 + { MKSLCD_SCREEN_MOTOR_ACC_MAX, MKSList_MaxAcc }, // Page 53 + { MKSLCD_SCREEN_LEVEL_DATA, MKSList_Level_Point }, // Page 48 + { MKSLCD_PrintPause_SET, MKSList_PrintPauseConfig }, // Page 49 + { MKSLCD_FILAMENT_DATA, MKSList_SD_File }, // Page 50 + { MKSLCD_SCREEN_Config, MKSList_TempOnly }, // Page 46 + { MKSLCD_SCREEN_Config_MOTOR, MKSList_MotoConfig }, // Page 47 + { MKSLCD_PID, MKSList_PID }, // Page 56 + { MKSLCD_ABOUT, MKSList_About }, // Page 36 + { MKSLCD_SCREEN_PRINT_CONFIG, MKSList_Level_PrintConfig }, // Page 60 + { MKSLCD_SCREEN_EX_CONFIG, MKSList_EX_Config }, // Page 65 + { MKSLCD_SCREEN_TMC_Config, MKSTMC_Config }, // Page 70 + { MKSLCD_AUTO_LEVEL, MKSAuto_Level }, // Page 73 + { MKSLCD_Screen_Offset_Config, MKSOffset_Config }, // Page 30 + { MKSLCD_Screen_PMove, MKSList_MOVE }, // Page 64 + { MKSLCD_Screen_Baby, MKSBabyStep }, // Page 71 + //{ MKSLCD_SCREEN_LEVEL_DATA, MKSList_SD_File}, + //{ MKSLCD_SCREEN_HOME, VPList_Boot }, + { 0, nullptr } // List is terminated with an nullptr as table entry. +}; + +const char MarlinVersion[] PROGMEM = SHORT_BUILD_VERSION; +const char H43Version[] PROGMEM = "MKS H43_V1.30"; +const char Updata_Time[] PROGMEM = STRING_DISTRIBUTION_DATE; + +const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { + // Helper to detect touch events + VPHELPER(VP_SCREENCHANGE, nullptr, ScreenHandler.ScreenChangeHook, nullptr), + VPHELPER(VP_SCREENCHANGE_ASK, nullptr, ScreenHandler.ScreenChangeHookIfIdle, nullptr), + #if ENABLED(SDSUPPORT) + VPHELPER(VP_SCREENCHANGE_WHENSD, nullptr, ScreenHandler.ScreenChangeHookIfSD, nullptr), + #endif + VPHELPER(VP_CONFIRMED, nullptr, ScreenHandler.ScreenConfirmedOK, nullptr), + + // Back Button + VPHELPER(VP_BACK_PAGE, nullptr, ScreenHandler.ScreenBackChange, nullptr), + VPHELPER(VP_TEMP_ALL_OFF, nullptr, ScreenHandler.HandleAllHeatersOff, nullptr), + + VPHELPER(VP_MOVE_X, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Y, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Z, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_HOME_ALL, nullptr, ScreenHandler.HandleManualMove, nullptr), + + VPHELPER(VP_X_HOME, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_Y_HOME, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_Z_HOME, nullptr, ScreenHandler.HandleManualMove, nullptr), + + VPHELPER(VP_MOVE_DISTANCE, &manualMoveStep, ScreenHandler.GetManualMovestep, nullptr), + + VPHELPER(VP_MOTOR_LOCK_UNLOK, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_LEVEL_POINT, nullptr, ScreenHandler.ManualAssistLeveling, nullptr), + + #if ENABLED(POWER_LOSS_RECOVERY) + VPHELPER(VP_POWER_LOSS_RECOVERY, nullptr, ScreenHandler.HandlePowerLossRecovery, nullptr), + #endif + VPHELPER(VP_SETTINGS, nullptr, ScreenHandler.HandleSettings, nullptr), + #if ENABLED(SINGLE_Z_CALIBRATION) + VPHELPER(VP_Z_CALIBRATE, nullptr, ScreenHandler.HandleZCalibration, nullptr), + #endif + #if ENABLED(FIRST_LAYER_CAL) + VPHELPER(VP_Z_FIRST_LAYER_CAL, nullptr, ScreenHandler.HandleFirstLayerCal, nullptr), + #endif + {.VP = VP_MARLIN_VERSION, .memadr = (void *)MarlinVersion, .size = VP_MARLIN_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, + // M117 LCD String (We don't need the string in memory but "just" push it to the display on demand, hence the nullptr + {.VP = VP_M117, .memadr = nullptr, .size = VP_M117_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplay}, + {.VP = VP_MKS_H43_VERSION, .memadr = (void *)H43Version, .size = VP_MKS_H43_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, + {.VP = VP_MKS_H43_UpdataVERSION, .memadr = (void *)Updata_Time, .size = VP_MKS_H43_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, + + // Temperature Data + #if HAS_HOTEND + VPHELPER(VP_T_E0_Is, &thermalManager.temp_hotend[0].celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), + VPHELPER(VP_T_E0_Set, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Flowrate_E0, &planner.flow_percentage[ExtUI::extruder_t::E0], ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_EPos, &destination.e, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_MOVE_E0, nullptr, ScreenHandler.HandleManualExtrude, nullptr), + VPHELPER(VP_E0_CONTROL, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_E0_STATUS, &thermalManager.temp_hotend[0].target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + #if ENABLED(DGUS_PREHEAT_UI) + VPHELPER(VP_E0_BED_PREHEAT, nullptr, ScreenHandler.HandlePreheat, nullptr), + #endif + #if ENABLED(PIDTEMP) + VPHELPER(VP_E0_PID_P, &thermalManager.temp_hotend[0].pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), + VPHELPER(VP_E0_PID_I, &thermalManager.temp_hotend[0].pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), + VPHELPER(VP_E0_PID_D, &thermalManager.temp_hotend[0].pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), + VPHELPER(VP_PID_AUTOTUNE_E0, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), + #endif + #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) + VPHELPER(VP_LOAD_Filament, nullptr, ScreenHandler.MKS_FilamentLoad, nullptr), + VPHELPER(VP_UNLOAD_Filament, nullptr, ScreenHandler.MKS_FilamentUnLoad, nullptr), + VPHELPER(VP_Filament_distance, &distanceFilament, ScreenHandler.GetManualFilament, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Filament_speed, &filamentSpeed_mm_s, ScreenHandler.GetManualFilamentSpeed, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + #endif + #endif + + #if HOTENDS >= 2 + VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), + VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Flowrate_E1, &planner.flow_percentage[ExtUI::extruder_t::E1], ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_MOVE_E1, nullptr, ScreenHandler.HandleManualExtrude, nullptr), + VPHELPER(VP_E1_CONTROL, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_E1_STATUS, &thermalManager.temp_hotend[1].target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + + #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) + VPHELPER(VP_Filament_distance, &distanceFilament, ScreenHandler.GetManualFilament, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), + VPHELPER(VP_Filament_speed, &filamentSpeed_mm_s, ScreenHandler.GetManualFilamentSpeed, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + #endif + + #if ENABLED(PIDTEMP) + VPHELPER(VP_PID_AUTOTUNE_E1, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), + #endif + + VPHELPER(VP_E1_FILAMENT_LOAD_UNLOAD, nullptr, ScreenHandler.HandleFilamentOption, ScreenHandler.HandleFilamentLoadUnload), + #endif + + #if HAS_HEATED_BED + VPHELPER(VP_T_Bed_Is, &thermalManager.temp_bed.celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), + VPHELPER(VP_T_Bed_Set, &thermalManager.temp_bed.target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_BED_CONTROL, &thermalManager.temp_bed.target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_BED_STATUS, &thermalManager.temp_bed.target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + #if ENABLED(PIDTEMPBED) + VPHELPER(VP_BED_PID_P, &thermalManager.temp_bed.pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), + VPHELPER(VP_BED_PID_I, &thermalManager.temp_bed.pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), + VPHELPER(VP_BED_PID_D, &thermalManager.temp_bed.pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), + VPHELPER(VP_PID_AUTOTUNE_BED, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), + #endif + #endif + + // Fan Data + #if HAS_FAN + #define FAN_VPHELPER(N) \ + VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], ScreenHandler.DGUSLCD_SetUint8, ScreenHandler.DGUSLCD_SendFanToDisplay), \ + VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], ScreenHandler.HandleFanControl, nullptr), \ + VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, ScreenHandler.DGUSLCD_SendFanStatusToDisplay), + REPEAT(FAN_COUNT, FAN_VPHELPER) + #endif + + // Feedrate + VPHELPER(VP_Feedrate_Percentage, &feedrate_percentage, ScreenHandler.DGUSLCD_SetValueDirectly, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + + // Position Data + VPHELPER(VP_XPos, ¤t_position.x, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_YPos, ¤t_position.y, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_ZPos, ¤t_position.z, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), + + // Level Point Set + VPHELPER(VP_Level_Point_One_X, &mks_corner_offsets[0].x, ScreenHandler.HandleChangeLevelPoint_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Level_Point_One_Y, &mks_corner_offsets[0].y, ScreenHandler.HandleChangeLevelPoint_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Level_Point_Two_X, &mks_corner_offsets[1].x, ScreenHandler.HandleChangeLevelPoint_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Level_Point_Two_Y, &mks_corner_offsets[1].y, ScreenHandler.HandleChangeLevelPoint_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Level_Point_Three_X, &mks_corner_offsets[2].x, ScreenHandler.HandleChangeLevelPoint_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Level_Point_Three_Y, &mks_corner_offsets[2].y, ScreenHandler.HandleChangeLevelPoint_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Level_Point_Four_X, &mks_corner_offsets[3].x, ScreenHandler.HandleChangeLevelPoint_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Level_Point_Four_Y, &mks_corner_offsets[3].y, ScreenHandler.HandleChangeLevelPoint_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Level_Point_Five_X, &mks_corner_offsets[4].x, ScreenHandler.HandleChangeLevelPoint_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Level_Point_Five_Y, &mks_corner_offsets[4].y, ScreenHandler.HandleChangeLevelPoint_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + + // Print Progress + VPHELPER(VP_PrintProgress_Percentage, nullptr, nullptr, ScreenHandler.DGUSLCD_SendPrintProgressToDisplay), + + // LCD Control + VPHELPER(VP_LCD_BLK, &lcd_default_light, ScreenHandler.LCD_BLK_Adjust, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + + // SD File - Back + VPHELPER(VP_SD_FileSelect_Back, nullptr, ScreenHandler.SD_FileBack, nullptr), + + // Print Time + VPHELPER_STR(VP_PrintTime, nullptr, VP_PrintTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintTimeToDisplay_MKS), + + #if ENABLED(PRINTCOUNTER) + VPHELPER_STR(VP_PrintAccTime, nullptr, VP_PrintAccTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintAccTimeToDisplay), + VPHELPER_STR(VP_PrintsTotal, nullptr, VP_PrintsTotal_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintsTotalToDisplay), + #endif + + VPHELPER(VP_X_STEP_PER_MM, &planner.settings.axis_steps_per_mm[X_AXIS], ScreenHandler.HandleStepPerMMChanged_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), + VPHELPER(VP_Y_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Y_AXIS], ScreenHandler.HandleStepPerMMChanged_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), + VPHELPER(VP_Z_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Z_AXIS], ScreenHandler.HandleStepPerMMChanged_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), + + VPHELPER(VP_X_MAX_SPEED, &planner.settings.max_feedrate_mm_s[X_AXIS], ScreenHandler.HandleMaxSpeedChange_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), + VPHELPER(VP_Y_MAX_SPEED, &planner.settings.max_feedrate_mm_s[Y_AXIS], ScreenHandler.HandleMaxSpeedChange_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), + VPHELPER(VP_Z_MAX_SPEED, &planner.settings.max_feedrate_mm_s[Z_AXIS], ScreenHandler.HandleMaxSpeedChange_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), + + #if HAS_HOTEND + VPHELPER(VP_E0_MAX_SPEED, &planner.settings.max_feedrate_mm_s[E_AXIS_N(0)], ScreenHandler.HandleExtruderMaxSpeedChange_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), + #if HOTENDS >= 2 + VPHELPER(VP_E1_MAX_SPEED, &planner.settings.max_feedrate_mm_s[E_AXIS_N(1)], ScreenHandler.HandleExtruderMaxSpeedChange_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), + #endif + #endif + + VPHELPER(VP_X_ACC_MAX_SPEED, (uint16_t *)&planner.settings.max_acceleration_mm_per_s2[X_AXIS], ScreenHandler.HandleMaxAccChange_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Y_ACC_MAX_SPEED, (uint16_t *)&planner.settings.max_acceleration_mm_per_s2[Y_AXIS], ScreenHandler.HandleMaxAccChange_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Z_ACC_MAX_SPEED, (uint16_t *)&planner.settings.max_acceleration_mm_per_s2[Z_AXIS], ScreenHandler.HandleMaxAccChange_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + + #if HAS_HOTEND + VPHELPER(VP_E0_ACC_MAX_SPEED, (uint16_t *)&planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(0)], ScreenHandler.HandleExtruderAccChange_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + #if HOTENDS >= 2 + VPHELPER(VP_E1_ACC_MAX_SPEED, (uint16_t *)&planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(1)], ScreenHandler.HandleExtruderAccChange_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + #endif + #endif + + VPHELPER(VP_TRAVEL_SPEED, (uint16_t *)&planner.settings.travel_acceleration, ScreenHandler.HandleTravelAccChange_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), + VPHELPER(VP_FEEDRATE_MIN_SPEED, (uint16_t *)&planner.settings.min_feedrate_mm_s, ScreenHandler.HandleFeedRateMinChange_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), + VPHELPER(VP_T_F_SPEED, (uint16_t *)&planner.settings.min_travel_feedrate_mm_s, ScreenHandler.HandleMin_T_F_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), + VPHELPER(VP_ACC_SPEED, (uint16_t *)&planner.settings.acceleration, ScreenHandler.HandleAccChange_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + + VPHELPER(VP_X_PARK_POS, &mks_park_pos.x, ScreenHandler.GetParkPos_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Y_PARK_POS, &mks_park_pos.y, ScreenHandler.GetParkPos_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Z_PARK_POS, &mks_park_pos.z, ScreenHandler.GetParkPos_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + + #if ENABLED(PREVENT_COLD_EXTRUSION) + VPHELPER(VP_MIN_EX_T, &thermalManager.extrude_min_temp, ScreenHandler.HandleGetExMinTemp_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + #endif + + #if ENABLED(SENSORLESS_HOMING) // TMC SENSORLESS Setting + #if X_HAS_STEALTHCHOP + VPHELPER(VP_TMC_X_STEP, &tmc_step.x, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendTMCStepValue), + #endif + #if Y_HAS_STEALTHCHOP + VPHELPER(VP_TMC_Y_STEP, &tmc_step.y, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendTMCStepValue), + #endif + #if Z_HAS_STEALTHCHOP + VPHELPER(VP_TMC_Z_STEP, &tmc_step.z, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendTMCStepValue), + #endif + #endif + + #if HAS_TRINAMIC_CONFIG // TMC Current Setting + #if AXIS_IS_TMC(X) + VPHELPER(VP_TMC_X_Current, &stepperX.val_mA, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + #endif + #if AXIS_IS_TMC(Y) + VPHELPER(VP_TMC_Y_Current, &stepperY.val_mA, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + #endif + #if AXIS_IS_TMC(Z) + VPHELPER(VP_TMC_Z_Current, &stepperZ.val_mA, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + #endif + #if AXIS_IS_TMC(E0) + VPHELPER(VP_TMC_E0_Current, &stepperE0.val_mA, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + #endif + #if AXIS_IS_TMC(E1) + VPHELPER(VP_TMC_E1_Current, &stepperE1.val_mA, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + #endif + #if AXIS_IS_TMC(X2) + VPHELPER(VP_TMC_X1_Current, &stepperX2.val_mA, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + #endif + #if AXIS_IS_TMC(Y2) + VPHELPER(VP_TMC_Y1_Current, &stepperY2.val_mA, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + #endif + #if AXIS_IS_TMC(Z2) + VPHELPER(VP_TMC_Z1_Current, &stepperZ2.val_mA, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + #endif + #endif + + VPHELPER(VP_EEPROM_CTRL, nullptr, ScreenHandler.EEPROM_CTRL, nullptr), + VPHELPER(VP_LEVEL_BUTTON, nullptr, ScreenHandler.Level_Ctrl_MKS, nullptr), + VPHELPER(VP_LANGUAGE_CHANGE, nullptr, ScreenHandler.LanguageChange_MKS, nullptr), + + //VPHELPER(VP_SD_Print_LiveAdjustZ, nullptr, ScreenHandler.HandleLiveAdjustZ, nullptr), + + VPHELPER(VP_SD_Print_LiveAdjustZ_Confirm, nullptr, ScreenHandler.ZoffsetConfirm, nullptr), + + VPHELPER(VP_ZOffset_Distance,nullptr ,ScreenHandler.GetZoffsetDistance, nullptr), + VPHELPER(VP_MESH_LEVEL_ADJUST, nullptr, ScreenHandler.MeshLevelDistanceConfig, nullptr), + VPHELPER(VP_MESH_LEVEL_POINT,nullptr, ScreenHandler.MeshLevel,nullptr), + + #if ENABLED(PREVENT_COLD_EXTRUSION) + VPHELPER(VP_Min_EX_T_E, &thermalManager.extrude_min_temp, ScreenHandler.GetMinExtrudeTemp, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + #endif + + VPHELPER(VP_AutoTurnOffSw, nullptr, ScreenHandler.GetTurnOffCtrl, nullptr), + + #if HAS_HOTEND + VPHELPER(VP_E0_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(0)], ScreenHandler.HandleStepPerMMExtruderChanged_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), + #if HOTENDS >= 2 + VPHELPER(VP_E1_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(1)], ScreenHandler.HandleStepPerMMExtruderChanged_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), + #endif + #endif + + // SDCard File listing + + #if ENABLED(SDSUPPORT) + VPHELPER(VP_SD_FileSelected, nullptr, ScreenHandler.DGUSLCD_SD_FileSelected, nullptr), + VPHELPER(VP_SD_ScrollEvent, nullptr, ScreenHandler.DGUSLCD_SD_ScrollFilelist, nullptr), + VPHELPER(VP_SD_FileSelectConfirm, nullptr, ScreenHandler.DGUSLCD_SD_StartPrint, nullptr), + VPHELPER_STR(VP_SD_FileName0, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), + VPHELPER_STR(VP_SD_FileName1, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), + VPHELPER_STR(VP_SD_FileName2, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), + VPHELPER_STR(VP_SD_FileName3, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), + VPHELPER_STR(VP_SD_FileName4, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), + VPHELPER_STR(VP_SD_FileName5, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), + VPHELPER_STR(VP_SD_FileName6, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), + VPHELPER_STR(VP_SD_FileName7, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), + VPHELPER_STR(VP_SD_FileName8, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), + VPHELPER_STR(VP_SD_FileName9, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), + VPHELPER(VP_SD_ResumePauseAbort, nullptr, ScreenHandler.DGUSLCD_SD_ResumePauseAbort, nullptr), + VPHELPER(VP_SD_AbortPrintConfirmed, nullptr, ScreenHandler.DGUSLCD_SD_ReallyAbort, nullptr), + VPHELPER(VP_SD_Print_Setting, nullptr, ScreenHandler.DGUSLCD_SD_PrintTune, nullptr), + #if ENABLED(BABYSTEPPING) + VPHELPER(VP_SD_Print_LiveAdjustZ, nullptr, ScreenHandler.HandleLiveAdjustZ, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<2>), + VPHELPER(VP_ZOffset_DE_DIS, &z_offset_add, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), + #endif + #if HAS_BED_PROBE + VPHELPER(VP_OFFSET_X, &probe.offset.x, ScreenHandler.GetOffsetValue,ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_OFFSET_Y, &probe.offset.y, ScreenHandler.GetOffsetValue,ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_OFFSET_Z, &probe.offset.z, ScreenHandler.GetOffsetValue,ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), + #endif + #else + VPHELPER(VP_SD_FileSelected, nullptr, ScreenHandler.PrintReturn, nullptr), + #endif + + #if ENABLED(DGUS_UI_WAITING) + VPHELPER(VP_WAITING_STATUS, nullptr, nullptr, ScreenHandler.DGUSLCD_SendWaitingStatusToDisplay), + #endif + + // Messages for the User, shared by the popup and the kill screen. They can't be autouploaded as we do not buffer content. + //{.VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, + //{.VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, + //{.VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, + //{.VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, + + {.VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplay_Language_MKS}, + {.VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplay_Language_MKS}, + {.VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplay_Language_MKS}, + {.VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplay_Language_MKS}, + + VPHELPER(0, 0, 0, 0) // must be last entry. +}; + +#endif // DGUS_LCD_UI_MKS diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h new file mode 100644 index 000000000000..c78e35e75b56 --- /dev/null +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h @@ -0,0 +1,712 @@ +/** + * 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 + +#include "../DGUSDisplayDef.h" + +//#define DGUS_MKS_RUNOUT_SENSOR + +#define LOGO_TIME_DELAY TERN(USE_MKS_GREEN_UI, 8000, 1500) + +#if ENABLED(DGUS_MKS_RUNOUT_SENSOR) + #define MT_DET_1_PIN 1 + #define MT_DET_2_PIN 2 + #define MT_DET_PIN_INVERTING false +#endif + +#define MKS_FINSH + +extern uint16_t manualMoveStep; +extern uint16_t distanceFilament; +extern uint16_t filamentSpeed_mm_s; +extern float ZOffset_distance; +extern float mesh_adj_distance; +extern float Z_distance; + +//extern struct { uint16_t h, m, s; } dgus_time; + +extern xy_int_t mks_corner_offsets[5]; +extern xyz_int_t mks_park_pos; +extern celsius_t mks_min_extrusion_temp; + +void MKS_reset_settings(); // Restore persistent settings to defaults + +void MKS_pause_print_move(); +void MKS_resume_print_move(); + +extern float z_offset_add; + +extern xyz_int_t tmc_step; + +extern uint16_t lcd_default_light; + +#if X_HAS_STEALTHCHOP + extern uint16_t tmc_x_current; +#endif +#if Y_HAS_STEALTHCHOP + extern uint16_t tmc_y_current; +#endif +#if Z_HAS_STEALTHCHOP + extern uint16_t tmc_z_current; +#endif +#if E0_HAS_STEALTHCHOP + extern uint16_t tmc_e0_current; +#endif +#if E1_HAS_STEALTHCHOP + extern uint16_t tmc_e1_current; +#endif + +typedef enum { + EX_HEATING, + EX_HEAT_STARUS, + EX_CHANGING, + EX_CHANGE_STATUS, + EX_NONE, +} EX_STATUS_DEF; + +typedef struct { + //uint8_t ex_change_flag:1; + //uint8_t ex_heat_flag:1; + uint8_t ex_load_unload_flag:1; //0:unload 1:load + EX_STATUS_DEF ex_status; + uint32_t ex_tick_start; + uint32_t ex_tick_end; + uint32_t ex_speed; + uint32_t ex_length; + uint32_t ex_need_time; +} EX_FILAMENT_DEF; + +extern EX_FILAMENT_DEF ex_filament; + +typedef enum { + UNRUNOUT_STATUS, + RUNOUT_STATUS, + RUNOUT_WAITTING_STATUS, + RUNOUT_BEGIN_STATUS, +} RUNOUT_MKS_STATUS_DEF; + +typedef struct { + RUNOUT_MKS_STATUS_DEF runout_status; + uint8_t pin_status; + uint8_t de_count; + uint8_t de_times; +} RUNOUT_MKS_DEF; + +extern RUNOUT_MKS_DEF runout_mks; + +typedef struct { + uint8_t print_pause_start_flag:1; + uint8_t runout_flag:1; + bool blstatus; + uint16_t x_pos; + uint16_t y_pos; + uint16_t z_pos; +} NOZZLE_PARK_DEF; + +extern NOZZLE_PARK_DEF nozzle_park_mks; + +enum DGUSLCD_Screens : uint8_t { + #if ENABLED(USE_MKS_GREEN_UI) + + DGUSLCD_SCREEN_BOOT = 33, + DGUSLCD_SCREEN_MAIN = 60, + DGUSLCD_SCREEN_STATUS = 60, + DGUSLCD_SCREEN_STATUS2 = 60, + DGUSLCD_SCREEN_PREHEAT = 18, + DGUSLCD_SCREEN_POWER_LOSS = 100, + DGUSLCD_SCREEN_MANUALMOVE = 192, + DGUSLCD_SCREEN_UTILITY = 120, + DGUSLCD_SCREEN_FILAMENT_UNLOADING = 158, + DGUSLCD_SCREEN_SDFILELIST = 15, + DGUSLCD_SCREEN_SDPRINTMANIPULATION = 15, + DGUSLCD_SCREEN_SDPRINTTUNE = 17, + + MKSLCD_SCREEN_BOOT = 33, + MKSLCD_SCREEN_HOME = 60, // MKS main page + MKSLCD_SCREEN_SETTING = 62, // MKS Setting page / no wifi whit + MKSLCD_SCREEM_TOOL = 64, // MKS Tool page + MKSLCD_SCREEN_EXTRUDE_P1 = 75, + MKSLCD_SCREEN_EXTRUDE_P2 = 77, + MKSLCD_SCREEN_LEVEL = 73, + MKSLCD_AUTO_LEVEL = 81, + MKSLCD_SCREEN_MOVE = 66, + MKSLCD_SCREEN_PRINT = 68, + MKSLCD_SCREEN_PAUSE = 70, + MKSLCD_SCREEN_CHOOSE_FILE = 87, + MKSLCD_SCREEN_NO_CHOOSE_FILE = 88, + MKSLCD_SCREEN_Config = 101, + MKSLCD_SCREEN_Config_MOTOR = 103, + MKSLCD_SCREEN_MOTOR_PLUSE = 104, + MKSLCD_SCREEN_MOTOR_SPEED = 102, + MKSLCD_SCREEN_MOTOR_ACC_MAX = 105, + MKSLCD_SCREEN_PRINT_CONFIG = 72, + MKSLCD_SCREEN_LEVEL_DATA = 106, + MKSLCD_PrintPause_SET = 107, + MKSLCD_FILAMENT_DATA = 50, + MKSLCD_ABOUT = 83, + MKSLCD_PID = 108, + MKSLCD_PAUSE_SETTING_MOVE = 98, + MKSLCD_PAUSE_SETTING_EX = 96, + MKSLCD_PAUSE_SETTING_EX2 = 97, + MKSLCD_SCREEN_PRINT_CONFIRM = 94, + MKSLCD_SCREEN_EX_CONFIG = 112, + MKSLCD_SCREEN_EEP_Config = 89, + MKSLCD_SCREEN_PrintDone = 92, + MKSLCD_SCREEN_TMC_Config = 111, + MKSLCD_Screen_Offset_Config = 109, + MKSLCD_Screen_PMove = 98, + MKSLCD_Screen_Baby = 79, + + #else + + DGUSLCD_SCREEN_BOOT = 120, + DGUSLCD_SCREEN_MAIN = 1, + + DGUSLCD_SCREEN_STATUS = 1, + DGUSLCD_SCREEN_STATUS2 = 1, + DGUSLCD_SCREEN_PREHEAT = 18, + DGUSLCD_SCREEN_POWER_LOSS = 100, + DGUSLCD_SCREEN_MANUALMOVE = 192, + DGUSLCD_SCREEN_UTILITY = 120, + DGUSLCD_SCREEN_FILAMENT_UNLOADING = 158, + DGUSLCD_SCREEN_SDFILELIST = 15, + DGUSLCD_SCREEN_SDPRINTMANIPULATION = 15, + DGUSLCD_SCREEN_SDPRINTTUNE = 17, + + MKSLCD_SCREEN_BOOT = 0, + MKSLCD_SCREEN_HOME = 1, // MKS main page + MKSLCD_SCREEN_SETTING = 2, // MKS Setting page / no wifi whit + MKSLCD_SCREEM_TOOL = 3, // MKS Tool page + MKSLCD_SCREEN_EXTRUDE_P1 = 4, + MKSLCD_SCREEN_EXTRUDE_P2 = 11, + MKSLCD_SCREEN_LEVEL = 5, + MKSLCD_AUTO_LEVEL = 73, + MKSLCD_SCREEN_LEVEL_PRESS = 9, + MKSLCD_SCREEN_MOVE = 6, + MKSLCD_SCREEN_PRINT = 7, + MKSLCD_SCREEN_PRINT_PRESS = 13, + MKSLCD_SCREEN_PAUSE = 26, + MKSLCD_SCREEN_PAUSE_PRESS = 26, + MKSLCD_SCREEN_CHOOSE_FILE = 15, + MKSLCD_SCREEN_NO_CHOOSE_FILE = 17, + MKSLCD_SCREEN_Config = 46, + MKSLCD_SCREEN_Config_MOTOR = 47, + MKSLCD_SCREEN_MOTOR_PLUSE = 51, + MKSLCD_SCREEN_MOTOR_SPEED = 55, + MKSLCD_SCREEN_MOTOR_ACC_MAX = 53, + MKSLCD_SCREEN_PRINT_CONFIG = 60, + MKSLCD_SCREEN_LEVEL_DATA = 48, + MKSLCD_PrintPause_SET = 49, + MKSLCD_FILAMENT_DATA = 50, + MKSLCD_ABOUT = 36, + MKSLCD_PID = 56, + MKSLCD_PAUSE_SETTING_MOVE = 58, + MKSLCD_PAUSE_SETTING_EX = 57, + MKSLCD_PAUSE_SETTING_EX2 = 61, + MKSLCD_SCREEN_NO_FILE = 42, + MKSLCD_SCREEN_PRINT_CONFIRM = 43, + MKSLCD_SCREEN_EX_CONFIG = 65, + MKSLCD_SCREEN_EEP_Config = 20, + MKSLCD_SCREEN_PrintDone = 25, + MKSLCD_SCREEN_TMC_Config = 70, + MKSLCD_Screen_Offset_Config = 30, + MKSLCD_Screen_PMove = 64, + MKSLCD_Screen_Baby = 71, + + #endif + + DGUSLCD_SCREEN_CONFIRM = 240, + DGUSLCD_SCREEN_KILL = 250, ///< Kill Screen. Must always be 250 (to be able to display "Error wrong LCD Version") + DGUSLCD_SCREEN_WAITING = 251, + DGUSLCD_SCREEN_POPUP = 252, ///< special target, popup screen will also return this code to say "return to previous screen" + DGUSLCD_SCREEN_UNUSED = 255 +}; + + +// Place for status messages. +constexpr uint16_t VP_M117 = 0x7020; +constexpr uint8_t VP_M117_LEN = 0x20; + +// Heater status +constexpr uint16_t VP_E0_STATUS = 0x3410; +constexpr uint16_t VP_E1_STATUS = 0x3412; +//constexpr uint16_t VP_E2_STATUS = 0x3414; +//constexpr uint16_t VP_E3_STATUS = 0x3416; +//constexpr uint16_t VP_E4_STATUS = 0x3418; +//constexpr uint16_t VP_E5_STATUS = 0x341A; +constexpr uint16_t VP_MOVE_OPTION = 0x3500; + +// // PIDs +// constexpr uint16_t VP_E0_PID_P = 0x3700; // at the moment , 2 byte unsigned int , 0~1638.4 +// constexpr uint16_t VP_E0_PID_I = 0x3702; +// constexpr uint16_t VP_E0_PID_D = 0x3704; +// constexpr uint16_t VP_E1_PID_P = 0x3706; // at the moment , 2 byte unsigned int , 0~1638.4 +// constexpr uint16_t VP_E1_PID_I = 0x3708; +// constexpr uint16_t VP_E1_PID_D = 0x370A; +// constexpr uint16_t VP_BED_PID_P = 0x3710; +// constexpr uint16_t VP_BED_PID_I = 0x3712; +// constexpr uint16_t VP_BED_PID_D = 0x3714; + +// Waiting screen status +constexpr uint16_t VP_WAITING_STATUS = 0x3800; + +// SPs for certain variables... +// located at 0x5000 and up +// Not used yet! +// This can be used e.g to make controls / data display invisible +constexpr uint16_t SP_T_E0_Is = 0x5000; +constexpr uint16_t SP_T_E0_Set = 0x5010; +constexpr uint16_t SP_T_E1_Is = 0x5020; +constexpr uint16_t SP_T_Bed_Is = 0x5030; +constexpr uint16_t SP_T_Bed_Set = 0x5040; + +/************************************************************************************************************************* + ************************************************************************************************************************* + * DGUS for MKS Mem layout + ************************************************************************************************************************ + ************************************************************************************************************************/ + +#if ENABLED(MKS_FINSH) + /* -------------------------------0x1000-0x1FFF------------------------------- */ + constexpr uint16_t VP_MSGSTR1 = 0x1100; + constexpr uint8_t VP_MSGSTR1_LEN = 0x20; // might be more place for it... + constexpr uint16_t VP_MSGSTR2 = 0x1140; + constexpr uint8_t VP_MSGSTR2_LEN = 0x20; + constexpr uint16_t VP_MSGSTR3 = 0x1180; + constexpr uint8_t VP_MSGSTR3_LEN = 0x20; + constexpr uint16_t VP_MSGSTR4 = 0x11C0; + constexpr uint8_t VP_MSGSTR4_LEN = 0x20; + + 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 ;)= + constexpr uint16_t VP_SCREENCHANGE_WHENSD = 0x1503; // "Print" Button touched -- go only there if there is an SD Card. + constexpr uint16_t VP_CONFIRMED = 0x1510; // OK on confirm screen. + + constexpr uint16_t VP_BACK_PAGE = 0x1600; + constexpr uint16_t VP_SETTINGS = 0x1620; + // Power loss recovery + constexpr uint16_t VP_POWER_LOSS_RECOVERY = 0x1680; + /* -------------------------------0x2000-0x2FFF------------------------------- */ + // Temperatures. + constexpr uint16_t VP_T_E0_Is = 0x2000; // 4 Byte Integer + constexpr uint16_t VP_T_E0_Set = 0x2004; // 2 Byte Integer + constexpr uint16_t VP_T_E1_Is = 0x2008; // 4 Byte Integer + constexpr uint16_t VP_T_E1_Set = 0x200B; // 2 Byte Integer + constexpr uint16_t VP_T_E2_Is = 0x2010; // 4 Byte Integer + constexpr uint16_t VP_T_E2_Set = 0x2014; // 2 Byte Integer + constexpr uint16_t VP_T_E3_Is = 0x2018; // 4 Byte Integer + constexpr uint16_t VP_T_E3_Set = 0x201B; // 2 Byte Integer + constexpr uint16_t VP_T_E4_Is = 0x2020; // 4 Byte Integer + constexpr uint16_t VP_T_E4_Set = 0x2024; // 2 Byte Integer + constexpr uint16_t VP_T_E5_Is = 0x2028; // 4 Byte Integer + constexpr uint16_t VP_T_E5_Set = 0x202B; // 2 Byte Integer + constexpr uint16_t VP_T_E6_Is = 0x2030; // 4 Byte Integer + constexpr uint16_t VP_T_E6_Set = 0x2034; // 2 Byte Integer + constexpr uint16_t VP_T_E7_Is = 0x2038; // 4 Byte Integer + constexpr uint16_t VP_T_E7_Set = 0x203B; // 2 Byte Integer + + constexpr uint16_t VP_T_Bed_Is = 0x2040; // 4 Byte Integer + constexpr uint16_t VP_T_Bed_Set = 0x2044; // 2 Byte Integer + + constexpr uint16_t VP_Min_EX_T_E = 0x2100; + + constexpr uint16_t VP_Flowrate_E0 = 0x2200; // 2 Byte Integer + constexpr uint16_t VP_Flowrate_E1 = 0x2202; // 2 Byte Integer + constexpr uint16_t VP_Flowrate_E2 = 0x2204; + constexpr uint16_t VP_Flowrate_E3 = 0x2206; + constexpr uint16_t VP_Flowrate_E4 = 0x2208; + constexpr uint16_t VP_Flowrate_E5 = 0x220A; + constexpr uint16_t VP_Flowrate_E6 = 0x220C; + constexpr uint16_t VP_Flowrate_E7 = 0x220E; + + // Move + constexpr uint16_t VP_MOVE_X = 0x2300; + constexpr uint16_t VP_MOVE_Y = 0x2302; + constexpr uint16_t VP_MOVE_Z = 0x2304; + constexpr uint16_t VP_MOVE_E0 = 0x2310; + constexpr uint16_t VP_MOVE_E1 = 0x2312; + constexpr uint16_t VP_MOVE_E2 = 0x2314; + constexpr uint16_t VP_MOVE_E3 = 0x2316; + constexpr uint16_t VP_MOVE_E4 = 0x2318; + constexpr uint16_t VP_MOVE_E5 = 0x231A; + constexpr uint16_t VP_MOVE_E6 = 0x231C; + constexpr uint16_t VP_MOVE_E7 = 0x231E; + constexpr uint16_t VP_HOME_ALL = 0x2320; + constexpr uint16_t VP_MOTOR_LOCK_UNLOK = 0x2330; + constexpr uint16_t VP_MOVE_DISTANCE = 0x2334; + constexpr uint16_t VP_X_HOME = 0x2336; + constexpr uint16_t VP_Y_HOME = 0x2338; + constexpr uint16_t VP_Z_HOME = 0x233A; + + // Fan Control Buttons , switch between "off" and "on" + constexpr uint16_t VP_FAN0_CONTROL = 0x2350; + constexpr uint16_t VP_FAN1_CONTROL = 0x2352; + constexpr uint16_t VP_FAN2_CONTROL = 0x2354; + constexpr uint16_t VP_FAN3_CONTROL = 0x2356; + constexpr uint16_t VP_FAN4_CONTROL = 0x2358; + constexpr uint16_t VP_FAN5_CONTROL = 0x235A; + + constexpr uint16_t VP_LANGUAGE_CHANGE = 0x2380; + constexpr uint16_t VP_LANGUAGE_CHANGE1 = 0x2382; + constexpr uint16_t VP_LANGUAGE_CHANGE2 = 0x2384; + constexpr uint16_t VP_LANGUAGE_CHANGE3 = 0x2386; + constexpr uint16_t VP_LANGUAGE_CHANGE4 = 0x2388; + constexpr uint16_t VP_LANGUAGE_CHANGE5 = 0x238A; + + // LEVEL + constexpr uint16_t VP_LEVEL_POINT = 0x2400; + constexpr uint16_t VP_MESH_LEVEL_POINT = 0x2410; + constexpr uint16_t VP_MESH_LEVEL_ADJUST = 0x2412; + constexpr uint16_t VP_MESH_LEVEL_DIP = 0x2414; + constexpr uint16_t VP_MESH_LEVEL_POINT_X = 0x2416; + constexpr uint16_t VP_MESH_LEVEL_POINT_Y = 0x2418; + constexpr uint16_t VP_LEVEL_BUTTON = 0x2420; + constexpr uint16_t VP_MESH_LEVEL_POINT_DIS = 0x2422; + constexpr uint16_t VP_MESH_LEVEL_BACK = 0x2424; + + constexpr uint16_t VP_E0_FILAMENT_LOAD_UNLOAD = 0x2500; + constexpr uint16_t VP_E1_FILAMENT_LOAD_UNLOAD = 0x2504; + constexpr uint16_t VP_LOAD_Filament = 0x2508; + // constexpr uint16_t VP_LOAD_UNLOAD_Cancle = 0x250A; + constexpr uint16_t VP_UNLOAD_Filament = 0x250B; + constexpr uint16_t VP_Filament_distance = 0x2600; + constexpr uint16_t VP_Filament_speed = 0x2604; + constexpr uint16_t VP_MIN_EX_T = 0x2606; + + constexpr uint16_t VP_E1_Filament_distance = 0x2614; + constexpr uint16_t VP_E1_Filament_speed = 0x2616; + constexpr uint16_t VP_E1_MIN_EX_T = 0x2618; + + constexpr uint16_t VP_Fan0_Percentage = 0x2700; // 2 Byte Integer (0..100) + constexpr uint16_t VP_Fan1_Percentage = 0x2702; // 2 Byte Integer (0..100) + constexpr uint16_t VP_Fan2_Percentage = 0x2704; // 2 Byte Integer (0..100) + constexpr uint16_t VP_Fan3_Percentage = 0x2706; // 2 Byte Integer (0..100) + constexpr uint16_t VP_Feedrate_Percentage = 0x2708; // 2 Byte Integer (0..100) + + // Fan status + constexpr uint16_t VP_FAN0_STATUS = 0x2710; + constexpr uint16_t VP_FAN1_STATUS = 0x2712; + constexpr uint16_t VP_FAN2_STATUS = 0x2714; + constexpr uint16_t VP_FAN3_STATUS = 0x2716; + + // Step per mm + constexpr uint16_t VP_X_STEP_PER_MM = 0x2900; // at the moment , 2 byte unsigned int , 0~1638.4 + constexpr uint16_t VP_Y_STEP_PER_MM = 0x2904; + constexpr uint16_t VP_Z_STEP_PER_MM = 0x2908; + constexpr uint16_t VP_E0_STEP_PER_MM = 0x2910; + constexpr uint16_t VP_E1_STEP_PER_MM = 0x2912; + constexpr uint16_t VP_E2_STEP_PER_MM = 0x2914; + constexpr uint16_t VP_E3_STEP_PER_MM = 0x2916; + constexpr uint16_t VP_E4_STEP_PER_MM = 0x2918; + constexpr uint16_t VP_E5_STEP_PER_MM = 0x291A; + constexpr uint16_t VP_E6_STEP_PER_MM = 0x291C; + constexpr uint16_t VP_E7_STEP_PER_MM = 0x291E; + + constexpr uint16_t VP_X_MAX_SPEED = 0x2A00; + constexpr uint16_t VP_Y_MAX_SPEED = 0x2A04; + constexpr uint16_t VP_Z_MAX_SPEED = 0x2A08; + constexpr uint16_t VP_E0_MAX_SPEED = 0x2A0C; + constexpr uint16_t VP_E1_MAX_SPEED = 0x2A10; + + constexpr uint16_t VP_X_ACC_MAX_SPEED = 0x2A28; + constexpr uint16_t VP_Y_ACC_MAX_SPEED = 0x2A2C; + constexpr uint16_t VP_Z_ACC_MAX_SPEED = 0x2A30; + constexpr uint16_t VP_E0_ACC_MAX_SPEED = 0x2A34; + constexpr uint16_t VP_E1_ACC_MAX_SPEED = 0x2A38; + + constexpr uint16_t VP_TRAVEL_SPEED = 0x2A3C; + constexpr uint16_t VP_FEEDRATE_MIN_SPEED = 0x2A40; + constexpr uint16_t VP_T_F_SPEED = 0x2A44; + constexpr uint16_t VP_ACC_SPEED = 0x2A48; + + /* -------------------------------0x3000-0x3FFF------------------------------- */ + // Buttons on the SD-Card File listing. + constexpr uint16_t VP_SD_ScrollEvent = 0x3020; // Data: 0 for "up a directory", numbers are the amount to scroll, e.g -1 one up, 1 one down + constexpr uint16_t VP_SD_FileSelected = 0x3022; // Number of file field selected. + constexpr uint16_t VP_SD_FileSelectConfirm = 0x3024; // (This is a virtual VP and emulated by the Confirm Screen when a file has been confirmed) + constexpr uint16_t VP_SD_ResumePauseAbort = 0x3026; // Resume(Data=0), Pause(Data=1), Abort(Data=2) SD Card prints + constexpr uint16_t VP_SD_AbortPrintConfirmed = 0x3028; // Abort print confirmation (virtual, will be injected by the confirm dialog) + constexpr uint16_t VP_SD_Print_Setting = 0x3040; + constexpr uint16_t VP_SD_Print_LiveAdjustZ = 0x3050; // Data: 0 down, 1 up + constexpr uint16_t VP_SD_Print_LiveAdjustZ_Confirm = 0x3060; + constexpr uint16_t VP_ZOffset_Distance = 0x3070; + constexpr uint16_t VP_ZOffset_DE_DIS = 0x3080; + constexpr uint16_t VP_SD_FileSelect_Back = 0x3082; + // SDCard File Listing + constexpr uint16_t VP_SD_FileName_LEN = 32; // LEN is shared for all entries. + constexpr uint16_t DGUS_SD_FILESPERSCREEN = 10; // FIXME move that info to the display and read it from there. + constexpr uint16_t VP_SD_FileName0 = 0x3100; + constexpr uint16_t VP_SD_FileName1 = 0x3120; + constexpr uint16_t VP_SD_FileName2 = 0x3140; + constexpr uint16_t VP_SD_FileName3 = 0x3160; + constexpr uint16_t VP_SD_FileName4 = 0x3180; + constexpr uint16_t VP_SD_FileName5 = 0x31A0; + constexpr uint16_t VP_SD_FileName6 = 0x31C0; + constexpr uint16_t VP_SD_FileName7 = 0x31E0; + constexpr uint16_t VP_SD_FileName8 = 0x3200; + constexpr uint16_t VP_SD_FileName9 = 0x3220; + + constexpr uint16_t VP_SD_Print_ProbeOffsetZ = 0x32A0; + constexpr uint16_t VP_SD_Print_Baby = 0x32B0; + constexpr uint16_t VP_SD_Print_Filename = 0x32C0; + + // X Y Z Point + constexpr uint16_t VP_XPos = 0x3300; // 4 Byte Fixed point number; format xxx.yy + constexpr uint16_t VP_YPos = 0x3302; // 4 Byte Fixed point number; format xxx.yy + constexpr uint16_t VP_ZPos = 0x3304; // 4 Byte Fixed point number; format xxx.yy + constexpr uint16_t VP_EPos = 0x3306; // 4 Byte Fixed point number; format xxx.yy + + // Print + constexpr uint16_t VP_PrintProgress_Percentage = 0x3330; // 2 Byte Integer (0..100) + constexpr uint16_t VP_PrintTime = 0x3340; + constexpr uint16_t VP_PrintTime_LEN = 32; + constexpr uint16_t VP_PrintAccTime = 0x3360; + constexpr uint16_t VP_PrintAccTime_LEN = 32; + constexpr uint16_t VP_PrintsTotal = 0x3380; + constexpr uint16_t VP_PrintsTotal_LEN = 16; + + constexpr uint16_t VP_File_Pictutr0 = 0x3400; + constexpr uint16_t VP_File_Pictutr1 = 0x3402; + constexpr uint16_t VP_File_Pictutr2 = 0x3404; + constexpr uint16_t VP_File_Pictutr3 = 0x3406; + constexpr uint16_t VP_File_Pictutr4 = 0x3408; + constexpr uint16_t VP_File_Pictutr5 = 0x340A; + constexpr uint16_t VP_File_Pictutr6 = 0x340C; + constexpr uint16_t VP_File_Pictutr7 = 0x340E; + constexpr uint16_t VP_File_Pictutr8 = 0x3410; + constexpr uint16_t VP_File_Pictutr9 = 0x3412; + + constexpr uint16_t VP_BED_STATUS = 0x341C; + + constexpr uint16_t VP_TMC_X_STEP = 0x3430; + constexpr uint16_t VP_TMC_Y_STEP = 0x3432; + constexpr uint16_t VP_TMC_Z_STEP = 0x3434; + + constexpr uint16_t VP_TMC_X1_Current = 0x3436; + constexpr uint16_t VP_TMC_Y1_Current = 0x3438; + constexpr uint16_t VP_TMC_X_Current = 0x343A; + constexpr uint16_t VP_TMC_Y_Current = 0x343C; + constexpr uint16_t VP_TMC_Z_Current = 0x343E; + constexpr uint16_t VP_TMC_E0_Current = 0x3440; + 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; + + // PIDs + constexpr uint16_t VP_E0_PID_P = 0x3700; // at the moment , 2 byte unsigned int , 0~1638.4 + constexpr uint16_t VP_E0_PID_I = 0x3702; + constexpr uint16_t VP_E0_PID_D = 0x3704; + constexpr uint16_t VP_E1_PID_P = 0x3706; // at the moment , 2 byte unsigned int , 0~1638.4 + constexpr uint16_t VP_E1_PID_I = 0x3708; + constexpr uint16_t VP_E1_PID_D = 0x370A; + constexpr uint16_t VP_BED_PID_P = 0x3710; + constexpr uint16_t VP_BED_PID_I = 0x3712; + constexpr uint16_t VP_BED_PID_D = 0x3714; + + constexpr uint16_t VP_EEPROM_CTRL = 0x3720; + + constexpr uint16_t VP_OFFSET_X = 0x3724; + constexpr uint16_t VP_OFFSET_Y = 0x3728; + constexpr uint16_t VP_OFFSET_Z = 0x372B; + + // PID autotune + constexpr uint16_t VP_PID_AUTOTUNE_E0 = 0x3800; + constexpr uint16_t VP_PID_AUTOTUNE_E1 = 0x3802; + constexpr uint16_t VP_PID_AUTOTUNE_E2 = 0x3804; + constexpr uint16_t VP_PID_AUTOTUNE_E3 = 0x3806; + constexpr uint16_t VP_PID_AUTOTUNE_E4 = 0x3808; + constexpr uint16_t VP_PID_AUTOTUNE_E5 = 0x380A; + constexpr uint16_t VP_PID_AUTOTUNE_BED = 0x380C; + // Calibrate Z + constexpr uint16_t VP_Z_CALIBRATE = 0x3810; + + constexpr uint16_t VP_AutoTurnOffSw = 0x3812; + constexpr uint16_t VP_LCD_BLK = 0x3814; + + constexpr uint16_t VP_X_PARK_POS = 0x3900; + constexpr uint16_t VP_Y_PARK_POS = 0x3902; + constexpr uint16_t VP_Z_PARK_POS = 0x3904; + + /* -------------------------------0x4000-0x4FFF------------------------------- */ + // Heater Control Buttons , triged between "cool down" and "heat PLA" state + constexpr uint16_t VP_E0_CONTROL = 0x4010; + constexpr uint16_t VP_E1_CONTROL = 0x4012; + //constexpr uint16_t VP_E2_CONTROL = 0x2214; + //constexpr uint16_t VP_E3_CONTROL = 0x2216; + //constexpr uint16_t VP_E4_CONTROL = 0x2218; + //constexpr uint16_t VP_E5_CONTROL = 0x221A; + constexpr uint16_t VP_BED_CONTROL = 0x401C; + + // Preheat + constexpr uint16_t VP_E0_BED_PREHEAT = 0x4020; + constexpr uint16_t VP_E1_BED_PREHEAT = 0x4022; + //constexpr uint16_t VP_E2_BED_PREHEAT = 0x4024; + //constexpr uint16_t VP_E3_BED_PREHEAT = 0x4026; + //constexpr uint16_t VP_E4_BED_PREHEAT = 0x4028; + //constexpr uint16_t VP_E5_BED_PREHEAT = 0x402A; + + // Filament load and unload + // constexpr uint16_t VP_E0_FILAMENT_LOAD_UNLOAD = 0x4030; + // constexpr uint16_t VP_E1_FILAMENT_LOAD_UNLOAD = 0x4032; + + // Settings store , reset + + // Level data + constexpr uint16_t VP_Level_Point_One_X = 0x4100; + constexpr uint16_t VP_Level_Point_One_Y = 0x4102; + constexpr uint16_t VP_Level_Point_Two_X = 0x4104; + constexpr uint16_t VP_Level_Point_Two_Y = 0x4106; + constexpr uint16_t VP_Level_Point_Three_X = 0x4108; + constexpr uint16_t VP_Level_Point_Three_Y = 0x410A; + constexpr uint16_t VP_Level_Point_Four_X = 0x410C; + constexpr uint16_t VP_Level_Point_Four_Y = 0x410E; + 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; + constexpr uint16_t VP_MKS_H43_UpdataVERSION = 0x4A10; // MKS H43 V1.0.0 + constexpr uint16_t VP_MKS_H43_UpdataVERSION_LEN = 16; + + /* -------------------------------0x5000-0xFFFF------------------------------- */ + constexpr uint16_t VP_HOME_Dis = 0x5000; + constexpr uint16_t VP_Setting_Dis = 0x5010; + constexpr uint16_t VP_Tool_Dis = 0x5020; + constexpr uint16_t VP_Printing_Dis = 0x5030; + + constexpr uint16_t VP_Language_Dis = 0x5080; + constexpr uint16_t VP_LossPoint_Dis = 0x5090; + + constexpr uint16_t VP_PrintPauseConfig_Dis = 0x5120; + constexpr uint16_t VP_MotorPluse_Dis = 0x5140; + constexpr uint16_t VP_MotorMaxSpeed_Dis = 0x5150; + constexpr uint16_t VP_MotorMaxAcc_Dis = 0x5160; + + constexpr uint16_t VP_X_Pluse_Dis = 0x5170; + constexpr uint16_t VP_Y_Pluse_Dis = 0x5180; + constexpr uint16_t VP_Z_Pluse_Dis = 0x5190; + constexpr uint16_t VP_E0_Pluse_Dis = 0x51A0; + constexpr uint16_t VP_E1_Pluse_Dis = 0x51B0; + + constexpr uint16_t VP_X_Max_Speed_Dis = 0x5280; + constexpr uint16_t VP_Y_Max_Speed_Dis = 0x5290; + constexpr uint16_t VP_Z_Max_Speed_Dis = 0x52A0; + constexpr uint16_t VP_E0_Max_Speed_Dis = 0x52B0; + constexpr uint16_t VP_E1_Max_Speed_Dis = 0x52C0; + + constexpr uint16_t VP_X_Max_Acc_Speed_Dis = 0x51E0; + constexpr uint16_t VP_Y_Max_Acc_Speed_Dis = 0x51F0; + constexpr uint16_t VP_Z_Max_Acc_Speed_Dis = 0x5200; + 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; + constexpr uint16_t VP_HB_Temp_Dis = 0x5330; + constexpr uint16_t VP_Feedrate_Dis = 0x5350; + constexpr uint16_t VP_PrintAcc_Dis = 0x5340; + constexpr uint16_t VP_Fan_Speed_Dis = 0x5360; + + 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; + constexpr uint16_t VP_ACC_Dis = 0x5480; + + constexpr uint16_t VP_Extrusion_Dis = 0x5230; + constexpr uint16_t VP_HeatBed_Dis = 0x5240; + + constexpr uint16_t VP_Printting_Dis = 0x5430; + constexpr uint16_t VP_FactoryDefaults_Dis = 0x54C0; + constexpr uint16_t VP_StoreSetting_Dis = 0x54B0; + constexpr uint16_t VP_Info_EEPROM_2_Dis = 0x54D0; + constexpr uint16_t VP_Info_EEPROM_1_Dis = 0x54E0; + + constexpr uint16_t VP_AutoLevel_1_Dis = 0x55F0; + + constexpr uint16_t VP_TMC_X_Step_Dis = 0x5530; + constexpr uint16_t VP_TMC_Y_Step_Dis = 0x5540; + constexpr uint16_t VP_TMC_Z_Step_Dis = 0x5550; + constexpr uint16_t VP_TMC_X1_Current_Dis = 0x5560; + constexpr uint16_t VP_TMC_Y1_Current_Dis = 0x5570; + constexpr uint16_t VP_TMC_X_Current_Dis = 0x5580; + constexpr uint16_t VP_TMC_Y_Current_Dis = 0x5590; + constexpr uint16_t VP_TMC_Z_Current_Dis = 0x55A0; + constexpr uint16_t VP_TMC_E0_Current_Dis = 0x55B0; + constexpr uint16_t VP_TMC_E1_Current_Dis = 0x55C0; + constexpr uint16_t VP_TMC_Z1_Current_Dis = 0x55E0; + + constexpr uint16_t VP_AutoLEVEL_INFO1 = 0x5600; + constexpr uint16_t VP_EX_TEMP_INFO1_Dis = 0x5610; + constexpr uint16_t VP_EX_TEMP_INFO2_Dis = 0x5620; + constexpr uint16_t VP_EX_TEMP_INFO3_Dis = 0x5630; + constexpr uint16_t VP_LCD_BLK_Dis = 0x56A0; + constexpr uint16_t VP_Info_PrinfFinsh_1_Dis = 0x5C00; + constexpr uint16_t VP_Info_PrinfFinsh_2_Dis = 0x5C10; + + constexpr uint16_t VP_Length_Dis = 0x5B00; + + constexpr uint16_t VP_PrintConfrim_Info_Dis = 0x5B90; + constexpr uint16_t VP_StopPrintConfrim_Info_Dis = 0x5B80; + + constexpr uint16_t VP_Point_One_Dis = 0x5BA0; + constexpr uint16_t VP_Point_Two_Dis = 0x5BB0; + constexpr uint16_t VP_Point_Three_Dis = 0x5BC0; + constexpr uint16_t VP_Point_Four_Dis = 0x5BD0; + constexpr uint16_t VP_Point_Five_Dis = 0x5BE0; + + constexpr uint16_t VP_Print_Dis = 0x5250; + + constexpr uint16_t VP_About_Dis = 0x5A00; + constexpr uint16_t VP_Config_Dis = 0x5A10; + constexpr uint16_t VP_Filament_Dis = 0x5A20; + constexpr uint16_t VP_Move_Dis = 0x5A30; + constexpr uint16_t VP_Level_Dis = 0x5A50; + constexpr uint16_t VP_Speed_Dis = 0x5A70; + constexpr uint16_t VP_InOut_Dis = 0x5A80; + + constexpr uint16_t VP_MotorConfig_Dis = 0x5100; + constexpr uint16_t VP_LevelConfig_Dis = 0x5110; + constexpr uint16_t VP_Advance_Dis = 0x5130; + constexpr uint16_t VP_TemperatureConfig_Dis = 0x5390; + +#endif // MKS_FINSH diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp new file mode 100644 index 000000000000..8c806f0ecd10 --- /dev/null +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp @@ -0,0 +1,2030 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../../../inc/MarlinConfigPre.h" + +#if ENABLED(DGUS_LCD_UI_MKS) + +#include "../DGUSScreenHandler.h" + +#include "../../../../inc/MarlinConfig.h" + +#include "../../../../MarlinCore.h" +#include "../../../../module/settings.h" +#include "../../../../module/temperature.h" +#include "../../../../module/motion.h" +#include "../../../../module/planner.h" +#include "../../../../module/printcounter.h" + +#include "../../../../gcode/gcode.h" + +#if HAS_STEALTHCHOP + #include "../../../../module/stepper/trinamic.h" + #include "../../../../module/stepper/indirection.h" +#endif +#include "../../../../module/probe.h" + +#if ENABLED(POWER_LOSS_RECOVERY) + #include "../../../../feature/powerloss.h" +#endif + +#if ENABLED(SDSUPPORT) + static ExtUI::FileList filelist; +#endif + +bool DGUSAutoTurnOff = false; +uint8_t mks_language_index; // Initialized by settings.load() + +// endianness swap +uint32_t swap32(const uint32_t value) { return (value & 0x000000FFU) << 24U | (value & 0x0000FF00U) << 8U | (value & 0x00FF0000U) >> 8U | (value & 0xFF000000U) >> 24U; } + +#if 0 +void DGUSScreenHandler::sendinfoscreen_ch_mks(const uint16_t *line1, const uint16_t *line2, const uint16_t *line3, const uint16_t *line4) { + dgusdisplay.WriteVariable(VP_MSGSTR1, line1, 32, true); + dgusdisplay.WriteVariable(VP_MSGSTR2, line2, 32, true); + dgusdisplay.WriteVariable(VP_MSGSTR3, line3, 32, true); + dgusdisplay.WriteVariable(VP_MSGSTR4, line4, 32, true); +} + +void DGUSScreenHandler::sendinfoscreen_en_mks(const char *line1, const char *line2, const char *line3, const char *line4) { + dgusdisplay.WriteVariable(VP_MSGSTR1, line1, 32, true); + dgusdisplay.WriteVariable(VP_MSGSTR2, line2, 32, true); + dgusdisplay.WriteVariable(VP_MSGSTR3, line3, 32, true); + dgusdisplay.WriteVariable(VP_MSGSTR4, line4, 32, true); +} + +void DGUSScreenHandler::sendinfoscreen_mks(const void *line1, const void *line2, const void *line3, const void *line4, uint16_t language) { + if (language == MKS_English) + DGUSScreenHandler::sendinfoscreen_en_mks((char *)line1, (char *)line2, (char *)line3, (char *)line4); + else if (language == MKS_SimpleChinese) + DGUSScreenHandler::sendinfoscreen_ch_mks((uint16_t *)line1, (uint16_t *)line2, (uint16_t *)line3, (uint16_t *)line4); +} + +#endif + +void DGUSScreenHandler::DGUSLCD_SendFanToDisplay(DGUS_VP_Variable &var) { + if (var.memadr) { + //DEBUG_ECHOPAIR(" DGUS_LCD_SendWordValueToDisplay ", var.VP); + //DEBUG_ECHOLNPAIR(" data ", *(uint16_t *)var.memadr); + uint16_t tmp = *(uint8_t *) var.memadr; // +1 -> avoid rounding issues for the display. + // tmp = map(tmp, 0, 255, 0, 100); + dgusdisplay.WriteVariable(var.VP, tmp); + } +} + +void DGUSScreenHandler::DGUSLCD_SendBabyStepToDisplay_MKS(DGUS_VP_Variable &var) { + float value = current_position.z; + DEBUG_ECHOLNPAIR_F(" >> ", value, 6); + value *= cpow(10, 2); + dgusdisplay.WriteVariable(VP_SD_Print_Baby, (uint16_t)value); +} + +void DGUSScreenHandler::DGUSLCD_SendPrintTimeToDisplay_MKS(DGUS_VP_Variable &var) { + duration_t elapsed = print_job_timer.duration(); + uint32_t time = elapsed.value; + dgusdisplay.WriteVariable(VP_PrintTime_H, uint16_t(time / 3600)); + dgusdisplay.WriteVariable(VP_PrintTime_M, uint16_t(time % 3600 / 60)); + dgusdisplay.WriteVariable(VP_PrintTime_S, uint16_t((time % 3600) % 60)); +} + +void DGUSScreenHandler::DGUSLCD_SetUint8(DGUS_VP_Variable &var, void *val_ptr) { + if (var.memadr) { + const uint16_t value = swap16(*(uint16_t*)val_ptr); + DEBUG_ECHOLNPAIR("FAN value get:", value); + *(uint8_t*)var.memadr = map(constrain(value, 0, 255), 0, 255, 0, 255); + DEBUG_ECHOLNPAIR("FAN value change:", *(uint8_t*)var.memadr); + } +} + +void DGUSScreenHandler::DGUSLCD_SendGbkToDisplay(DGUS_VP_Variable &var) { + DEBUG_ECHOLNPAIR(" data ", *(uint16_t *)var.memadr); + uint16_t *tmp = (uint16_t*) var.memadr; + dgusdisplay.WriteVariable(var.VP, tmp, var.size, true); +} + +void DGUSScreenHandler::DGUSLCD_SendStringToDisplay_Language_MKS(DGUS_VP_Variable &var) { + if (mks_language_index == MKS_English) { + char *tmp = (char*) var.memadr; + dgusdisplay.WriteVariable(var.VP, tmp, var.size, true); + } + else if (mks_language_index == MKS_SimpleChinese) { + uint16_t *tmp = (uint16_t *)var.memadr; + dgusdisplay.WriteVariable(var.VP, tmp, var.size, true); + } +} + +void DGUSScreenHandler::DGUSLCD_SendTMCStepValue(DGUS_VP_Variable &var) { + #if ENABLED(SENSORLESS_HOMING) + #if X_HAS_STEALTHCHOP + tmc_step.x = stepperX.homing_threshold(); + dgusdisplay.WriteVariable(var.VP, *(int16_t*)var.memadr); + #endif + #if Y_HAS_STEALTHCHOP + tmc_step.y = stepperY.homing_threshold(); + dgusdisplay.WriteVariable(var.VP, *(int16_t*)var.memadr); + #endif + #if Z_HAS_STEALTHCHOP + tmc_step.z = stepperZ.homing_threshold(); + dgusdisplay.WriteVariable(var.VP, *(int16_t*)var.memadr); + #endif + #endif +} + +#if ENABLED(SDSUPPORT) + + void DGUSScreenHandler::DGUSLCD_SD_FileSelected(DGUS_VP_Variable &var, void *val_ptr) { + uint16_t touched_nr = (int16_t)swap16(*(uint16_t*)val_ptr) + top_file; + if (touched_nr != 0x0F && touched_nr > filelist.count()) return; + if (!filelist.seek(touched_nr) && touched_nr != 0x0F) return; + + if (touched_nr == 0x0F) { + if (filelist.isAtRootDir()) + GotoScreen(DGUSLCD_SCREEN_MAIN); + else + filelist.upDir(); + return; + } + + if (filelist.isDir()) { + filelist.changeDir(filelist.filename()); + top_file = 0; + ForceCompleteUpdate(); + return; + } + + #if ENABLED(DGUS_PRINT_FILENAME) + // Send print filename + dgusdisplay.WriteVariable(VP_SD_Print_Filename, filelist.filename(), VP_SD_FileName_LEN, true); + #endif + + // Setup Confirmation screen + file_to_print = touched_nr; + GotoScreen(MKSLCD_SCREEN_PRINT_CONFIRM); + } + + void DGUSScreenHandler::DGUSLCD_SD_StartPrint(DGUS_VP_Variable &var, void *val_ptr) { + if (!filelist.seek(file_to_print)) return; + ExtUI::printFile(filelist.shortFilename()); + GotoScreen(MKSLCD_SCREEN_PRINT); + z_offset_add = 0; + } + + void DGUSScreenHandler::DGUSLCD_SD_ResumePauseAbort(DGUS_VP_Variable &var, void *val_ptr) { + + if (!ExtUI::isPrintingFromMedia()) return; // avoid race condition when user stays in this menu and printer finishes. + switch (swap16(*(uint16_t*)val_ptr)) { + case 0: { // Resume + + auto cs = getCurrentScreen(); + if (runout_mks.runout_status != RUNOUT_WAITTING_STATUS && runout_mks.runout_status != UNRUNOUT_STATUS) { + if (cs == MKSLCD_SCREEN_PRINT || cs == MKSLCD_SCREEN_PAUSE) + GotoScreen(MKSLCD_SCREEN_PAUSE); + return; + } + else + runout_mks.runout_status = UNRUNOUT_STATUS; + + GotoScreen(MKSLCD_SCREEN_PRINT); + + if (ExtUI::isPrintingFromMediaPaused()) { + nozzle_park_mks.print_pause_start_flag = 0; + nozzle_park_mks.blstatus = true; + ExtUI::resumePrint(); + } + } break; + + case 1: // Pause + + GotoScreen(MKSLCD_SCREEN_PAUSE); + if (!ExtUI::isPrintingFromMediaPaused()) { + nozzle_park_mks.print_pause_start_flag = 1; + nozzle_park_mks.blstatus = true; + ExtUI::pausePrint(); + //ExtUI::mks_pausePrint(); + } + break; + case 2: // Abort + HandleUserConfirmationPopUp(VP_SD_AbortPrintConfirmed, nullptr, PSTR("Abort printing"), filelist.filename(), PSTR("?"), true, true, false, true); + break; + } + } + + void DGUSScreenHandler::DGUSLCD_SD_SendFilename(DGUS_VP_Variable& var) { + uint16_t target_line = (var.VP - VP_SD_FileName0) / VP_SD_FileName_LEN; + if (target_line > DGUS_SD_FILESPERSCREEN) return; + char tmpfilename[VP_SD_FileName_LEN + 1] = ""; + var.memadr = (void*)tmpfilename; + + uint16_t dir_icon_val = 25; + if (filelist.seek(top_file + target_line)) { + snprintf_P(tmpfilename, VP_SD_FileName_LEN, PSTR("%s%c"), filelist.filename(), filelist.isDir() ? '/' : 0); // snprintf_P(tmpfilename, VP_SD_FileName_LEN, PSTR("%s"), filelist.filename()); + dir_icon_val = filelist.isDir() ? 0 : 1; + } + DGUSLCD_SendStringToDisplay(var); + + dgusdisplay.WriteVariable(VP_File_Pictutr0 + target_line * 2, dir_icon_val); + } + + void DGUSScreenHandler::SDCardInserted() { + top_file = 0; + filelist.refresh(); + auto cs = getCurrentScreen(); + if (cs == DGUSLCD_SCREEN_MAIN || cs == DGUSLCD_SCREEN_STATUS) + GotoScreen(MKSLCD_SCREEN_CHOOSE_FILE); + } + + void DGUSScreenHandler::SDCardRemoved() { + if (current_screen == DGUSLCD_SCREEN_SDFILELIST + || (current_screen == DGUSLCD_SCREEN_CONFIRM && (ConfirmVP == VP_SD_AbortPrintConfirmed || ConfirmVP == VP_SD_FileSelectConfirm)) + || current_screen == DGUSLCD_SCREEN_SDPRINTMANIPULATION + ) filelist.refresh(); + } + + void DGUSScreenHandler::SDPrintingFinished() { + if (DGUSAutoTurnOff) { + queue.exhaust(); + gcode.process_subcommands_now_P(PSTR("M81")); + } + GotoScreen(MKSLCD_SCREEN_PrintDone); + } + +#else + void DGUSScreenHandler::PrintReturn(DGUS_VP_Variable& var, void *val_ptr) { + uint16_t value = swap16(*(uint16_t*)val_ptr); + if (value == 0x0F) GotoScreen(DGUSLCD_SCREEN_MAIN); + } +#endif // SDSUPPORT + +void DGUSScreenHandler::ScreenChangeHook(DGUS_VP_Variable &var, void *val_ptr) { + uint8_t *tmp = (uint8_t*)val_ptr; + + // The keycode in target is coded as , so 0x0100A means + // from screen 1 (main) to 10 (temperature). DGUSLCD_SCREEN_POPUP is special, + // meaning "return to previous screen" + DGUSLCD_Screens target = (DGUSLCD_Screens)tmp[1]; + + DEBUG_ECHOLNPAIR("\n DEBUG target", target); + + // when the dgus had reboot, it will enter the DGUSLCD_SCREEN_MAIN page, + // so user can change any page to use this function, an it will check + // if robin nano is printing. when it is, dgus will enter the printing + // page to continue print; + // + //if (printJobOngoing() || printingIsPaused()) { + // if (target == MKSLCD_PAUSE_SETTING_MOVE || target == MKSLCD_PAUSE_SETTING_EX + // || target == MKSLCD_SCREEN_PRINT || target == MKSLCD_SCREEN_PAUSE + // ) { + // } + // else + // GotoScreen(MKSLCD_SCREEN_PRINT); + // return; + //} + + if (target == DGUSLCD_SCREEN_POPUP) { + SetupConfirmAction(ExtUI::setUserConfirmed); + + // Special handling for popup is to return to previous menu + if (current_screen == DGUSLCD_SCREEN_POPUP && confirm_action_cb) confirm_action_cb(); + PopToOldScreen(); + return; + } + + UpdateNewScreen(target); + + #ifdef DEBUG_DGUSLCD + if (!DGUSLCD_FindScreenVPMapList(target)) DEBUG_ECHOLNPAIR("WARNING: No screen Mapping found for ", target); + #endif +} + +void DGUSScreenHandler::ScreenBackChange(DGUS_VP_Variable &var, void *val_ptr) { + const uint16_t target = swap16(*(uint16_t *)val_ptr); + DEBUG_ECHOLNPAIR(" back = 0x%x", target); + switch (target) { + } +} + +void DGUSScreenHandler::ZoffsetConfirm(DGUS_VP_Variable &var, void *val_ptr) { + settings.save(); + if (printJobOngoing()) + GotoScreen(MKSLCD_SCREEN_PRINT); + else if (print_job_timer.isPaused) + GotoScreen(MKSLCD_SCREEN_PAUSE); +} + +void DGUSScreenHandler::GetTurnOffCtrl(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("GetTurnOffCtrl\n"); + const uint16_t value = swap16(*(uint16_t *)val_ptr); + switch (value) { + case 0 ... 1: DGUSAutoTurnOff = (bool)value; break; + default: break; + } +} + +void DGUSScreenHandler::GetMinExtrudeTemp(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("GetMinExtrudeTemp"); + const uint16_t value = swap16(*(uint16_t *)val_ptr); + TERN_(PREVENT_COLD_EXTRUSION, thermalManager.extrude_min_temp = value); + mks_min_extrusion_temp = value; + settings.save(); +} + +void DGUSScreenHandler::GetZoffsetDistance(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("GetZoffsetDistance"); + const uint16_t value = swap16(*(uint16_t *)val_ptr); + float val_distance = 0; + switch (value) { + case 0: val_distance = 0.01; break; + case 1: val_distance = 0.1; break; + case 2: val_distance = 0.5; break; + case 3: val_distance = 1; break; + default: val_distance = 0.01; break; + } + ZOffset_distance = val_distance; +} + +void DGUSScreenHandler::GetManualMovestep(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("\nGetManualMovestep"); + *(uint16_t *)var.memadr = swap16(*(uint16_t *)val_ptr); +} + +void DGUSScreenHandler::EEPROM_CTRL(DGUS_VP_Variable &var, void *val_ptr) { + const uint16_t eep_flag = swap16(*(uint16_t *)val_ptr); + switch (eep_flag) { + case 0: + settings.save(); + settings.load(); // load eeprom data to check the data is right + GotoScreen(MKSLCD_SCREEN_EEP_Config); + break; + + case 1: + settings.reset(); + GotoScreen(MKSLCD_SCREEN_EEP_Config); + break; + + default: break; + } +} + +void DGUSScreenHandler::Z_offset_select(DGUS_VP_Variable &var, void *val_ptr) { + const uint16_t z_value = swap16(*(uint16_t *)val_ptr); + switch (z_value) { + case 0: Z_distance = 0.01; break; + case 1: Z_distance = 0.1; break; + case 2: Z_distance = 0.5; break; + default: Z_distance = 1; break; + } +} + +void DGUSScreenHandler::GetOffsetValue(DGUS_VP_Variable &var, void *val_ptr) { + + #if HAS_BED_PROBE + int32_t value = swap32(*(int32_t *)val_ptr); + float Offset = value / 100.0f; + DEBUG_ECHOLNPAIR_F("\nget int6 offset >> ", value, 6); + #endif + + switch (var.VP) { + case VP_OFFSET_X: TERN_(HAS_BED_PROBE, probe.offset.x = Offset); break; + case VP_OFFSET_Y: TERN_(HAS_BED_PROBE, probe.offset.y = Offset); break; + case VP_OFFSET_Z: TERN_(HAS_BED_PROBE, probe.offset.z = Offset); break; + default: break; + } + settings.save(); +} + +void DGUSScreenHandler::LanguageChange_MKS(DGUS_VP_Variable &var, void *val_ptr) { + const uint16_t lag_flag = swap16(*(uint16_t *)val_ptr); + switch (lag_flag) { + case MKS_SimpleChinese: + DGUS_LanguageDisplay(MKS_SimpleChinese); + mks_language_index = MKS_SimpleChinese; + dgusdisplay.MKS_WriteVariable(VP_LANGUAGE_CHANGE1, MKS_Language_Choose); + dgusdisplay.MKS_WriteVariable(VP_LANGUAGE_CHANGE2, MKS_Language_NoChoose); + settings.save(); + break; + case MKS_English: + DGUS_LanguageDisplay(MKS_English); + mks_language_index = MKS_English; + dgusdisplay.MKS_WriteVariable(VP_LANGUAGE_CHANGE1, MKS_Language_NoChoose); + dgusdisplay.MKS_WriteVariable(VP_LANGUAGE_CHANGE2, MKS_Language_Choose); + settings.save(); + break; + default: break; + } +} + +#if ENABLED(MESH_BED_LEVELING) + uint8_t mesh_point_count = GRID_MAX_POINTS; +#endif + +void DGUSScreenHandler::Level_Ctrl_MKS(DGUS_VP_Variable &var, void *val_ptr) { + const uint16_t lev_but = swap16(*(uint16_t *)val_ptr); + #if ENABLED(MESH_BED_LEVELING) + auto cs = getCurrentScreen(); + #endif + switch (lev_but) { + case 0: + #if ENABLED(AUTO_BED_LEVELING_BILINEAR) + + static uint8_t a_first_level = 1; + if (a_first_level == 1) { + a_first_level = 0; + queue.enqueue_now_P(G28_STR); + } + queue.enqueue_now_P(PSTR("G29")); + + #elif ENABLED(MESH_BED_LEVELING) + + mesh_point_count = GRID_MAX_POINTS; + + if (mks_language_index == MKS_English) { + const char level_buf_en[] = "Start Level"; + dgusdisplay.WriteVariable(VP_AutoLevel_1_Dis, level_buf_en, 32, true); + } + else if (mks_language_index == MKS_SimpleChinese) { + const uint16_t level_buf_ch[] = {0xAABF, 0xBCCA, 0xF7B5, 0xBDC6, 0x2000}; + dgusdisplay.WriteVariable(VP_AutoLevel_1_Dis, level_buf_ch, 32, true); + } + + cs = getCurrentScreen(); + if (cs != MKSLCD_AUTO_LEVEL) GotoScreen(MKSLCD_AUTO_LEVEL); + #else + + GotoScreen(MKSLCD_SCREEN_LEVEL); + + #endif + break; + + case 1: + soft_endstop._enabled = true; + GotoScreen(MKSLCD_SCREEM_TOOL); + break; + + default: break; + } +} + +void DGUSScreenHandler::MeshLevelDistanceConfig(DGUS_VP_Variable &var, void *val_ptr) { + const uint16_t mesh_dist = swap16(*(uint16_t *)val_ptr); + switch (mesh_dist) { + case 0: mesh_adj_distance = 0.01; break; + case 1: mesh_adj_distance = 0.1; break; + case 2: mesh_adj_distance = 1; break; + default: mesh_adj_distance = 0.1; break; + } +} + +void DGUSScreenHandler::MeshLevel(DGUS_VP_Variable &var, void *val_ptr) { + #if ENABLED(MESH_BED_LEVELING) + const uint16_t mesh_value = swap16(*(uint16_t *)val_ptr); + // static uint8_t a_first_level = 1; + char cmd_buf[30]; + float offset = mesh_adj_distance; + int16_t integer, Deci, Deci2; + + if (!queue.ring_buffer.empty()) return; + + switch (mesh_value) { + case 0: + offset = mesh_adj_distance; + integer = offset; // get int + Deci = (offset * 10); + Deci = Deci % 10; + Deci2 = offset * 100; + Deci2 = Deci2 % 10; + soft_endstop._enabled = false; + queue.enqueue_now_P(PSTR("G91")); + snprintf_P(cmd_buf, 30, PSTR("G1 Z%d.%d%d"), integer, Deci, Deci2); + queue.enqueue_one_now(cmd_buf); + queue.enqueue_now_P(PSTR("G90")); + //soft_endstop._enabled = true; + break; + + case 1: + offset = mesh_adj_distance; + integer = offset; // get int + Deci = (offset * 10); + Deci = Deci % 10; + Deci2 = offset * 100; + Deci2 = Deci2 % 10; + soft_endstop._enabled = false; + queue.enqueue_now_P(PSTR("G91")); + snprintf_P(cmd_buf, 30, PSTR("G1 Z-%d.%d%d"), integer, Deci, Deci2); + queue.enqueue_one_now(cmd_buf); + queue.enqueue_now_P(PSTR("G90")); + break; + + case 2: + if (mesh_point_count == GRID_MAX_POINTS) { // The first point + + queue.enqueue_now_P(PSTR("G28")); + queue.enqueue_now_P(PSTR("G29S1")); + mesh_point_count--; + + if (mks_language_index == MKS_English) { + const char level_buf_en1[] = "Next Point"; + dgusdisplay.WriteVariable(VP_AutoLevel_1_Dis, level_buf_en1, 32, true); + } + else if (mks_language_index == MKS_SimpleChinese) { + const uint16_t level_buf_ch1[] = {0xC2CF, 0xBBD2, 0xE3B5, 0x2000}; + dgusdisplay.WriteVariable(VP_AutoLevel_1_Dis, level_buf_ch1, 32, true); + } + } + else if (mesh_point_count > 1) { // 倒数第二个点 + queue.enqueue_now_P(PSTR("G29S2")); + mesh_point_count--; + if (mks_language_index == MKS_English) { + const char level_buf_en2[] = "Next Point"; + dgusdisplay.WriteVariable(VP_AutoLevel_1_Dis, level_buf_en2, 32, true); + } + else if (mks_language_index == MKS_SimpleChinese) { + const uint16_t level_buf_ch2[] = {0xC2CF, 0xBBD2, 0xE3B5, 0x2000}; + dgusdisplay.WriteVariable(VP_AutoLevel_1_Dis, level_buf_ch2, 32, true); + } + } + else if (mesh_point_count == 1) { + queue.enqueue_now_P(PSTR("G29S2")); + mesh_point_count--; + if (mks_language_index == MKS_English) { + const char level_buf_en2[] = "Level Finsh"; + dgusdisplay.WriteVariable(VP_AutoLevel_1_Dis, level_buf_en2, 32, true); + } + else if (mks_language_index == MKS_SimpleChinese) { + const uint16_t level_buf_ch2[] = {0xF7B5, 0xBDC6, 0xEACD, 0xC9B3, 0x2000}; + dgusdisplay.WriteVariable(VP_AutoLevel_1_Dis, level_buf_ch2, 32, true); + } + settings.save(); + } + else if (mesh_point_count == 0) { + mesh_point_count = GRID_MAX_POINTS; + soft_endstop._enabled = true; + settings.save(); + GotoScreen(MKSLCD_SCREEM_TOOL); + } + break; + + default: + break; + } + #endif // MESH_BED_LEVELING +} + +void DGUSScreenHandler::SD_FileBack(DGUS_VP_Variable&, void*) { + GotoScreen(MKSLCD_SCREEN_HOME); +} + +void DGUSScreenHandler::LCD_BLK_Adjust(DGUS_VP_Variable &var, void *val_ptr) { + const uint16_t lcd_value = swap16(*(uint16_t *)val_ptr); + + lcd_default_light = constrain(lcd_value, 10, 100); + + const uint16_t lcd_data[2] = { lcd_default_light, lcd_default_light }; + dgusdisplay.WriteVariable(0x0082, &lcd_data, 5, true); +} + +void DGUSScreenHandler::ManualAssistLeveling(DGUS_VP_Variable &var, void *val_ptr) { + const int16_t point_value = swap16(*(uint16_t *)val_ptr); + + // Insist on leveling first time at this screen + static bool first_level_flag = false; + if (!first_level_flag || point_value == 0x0001) { + queue.enqueue_now_P(G28_STR); + first_level_flag = true; + } + + constexpr uint16_t level_speed = 1500; + + auto enqueue_corner_move = [](int16_t lx, int16_t ly, uint16_t fr) { + char buf_level[32]; + sprintf_P(buf_level, "G0X%dY%dF%d", lx, ly, fr); + queue.enqueue_one_now(buf_level); + }; + + if (WITHIN(point_value, 0x0001, 0x0005)) + queue.enqueue_now_P(PSTR("G1Z10")); + + switch (point_value) { + case 0x0001: + enqueue_corner_move(X_MIN_POS + ABS(mks_corner_offsets[0].x), + Y_MIN_POS + ABS(mks_corner_offsets[0].y), level_speed); + queue.enqueue_now_P(PSTR("G28Z")); + break; + case 0x0002: + enqueue_corner_move(X_MAX_POS - ABS(mks_corner_offsets[1].x), + Y_MIN_POS + ABS(mks_corner_offsets[1].y), level_speed); + break; + case 0x0003: + enqueue_corner_move(X_MAX_POS - ABS(mks_corner_offsets[2].x), + Y_MAX_POS - ABS(mks_corner_offsets[2].y), level_speed); + break; + case 0x0004: + enqueue_corner_move(X_MIN_POS + ABS(mks_corner_offsets[3].x), + Y_MAX_POS - ABS(mks_corner_offsets[3].y), level_speed); + break; + case 0x0005: + enqueue_corner_move(ABS(mks_corner_offsets[4].x), + ABS(mks_corner_offsets[4].y), level_speed); + break; + } + + if (WITHIN(point_value, 0x0002, 0x0005)) { + //queue.enqueue_now_P(PSTR("G28Z")); + queue.enqueue_now_P(PSTR("G1Z-10")); + } +} + +#define mks_min(a, b) ((a) < (b)) ? (a) : (b) +#define mks_max(a, b) ((a) > (b)) ? (a) : (b) +void DGUSScreenHandler::TMC_ChangeConfig(DGUS_VP_Variable &var, void *val_ptr) { + #if EITHER(HAS_TRINAMIC_CONFIG, HAS_STEALTHCHOP) + const uint16_t tmc_value = swap16(*(uint16_t*)val_ptr); + #endif + + switch (var.VP) { + case VP_TMC_X_STEP: + #if USE_SENSORLESS + #if X_HAS_STEALTHCHOP + stepperX.homing_threshold(mks_min(tmc_value, 255)); + settings.save(); + //tmc_step.x = stepperX.homing_threshold(); + #endif + #endif + break; + case VP_TMC_Y_STEP: + #if USE_SENSORLESS + #if Y_HAS_STEALTHCHOP + stepperY.homing_threshold(mks_min(tmc_value, 255)); + settings.save(); + //tmc_step.y = stepperY.homing_threshold(); + #endif + #endif + break; + case VP_TMC_Z_STEP: + #if USE_SENSORLESS + #if Z_HAS_STEALTHCHOP + stepperZ.homing_threshold(mks_min(tmc_value, 255)); + settings.save(); + //tmc_step.z = stepperZ.homing_threshold(); + #endif + #endif + break; + case VP_TMC_X_Current: + #if AXIS_IS_TMC(X) + stepperX.rms_current(tmc_value); + settings.save(); + #endif + break; + case VP_TMC_X1_Current: + #if AXIS_IS_TMC(X2) + stepperX2.rms_current(tmc_value); + settings.save(); + #endif + break; + case VP_TMC_Y_Current: + #if AXIS_IS_TMC(Y) + stepperY.rms_current(tmc_value); + settings.save(); + #endif + break; + case VP_TMC_Y1_Current: + #if AXIS_IS_TMC(X2) + stepperY2.rms_current(tmc_value); + settings.save(); + #endif + break; + case VP_TMC_Z_Current: + #if AXIS_IS_TMC(Z) + stepperZ.rms_current(tmc_value); + settings.save(); + #endif + break; + case VP_TMC_Z1_Current: + #if AXIS_IS_TMC(Z2) + stepperZ2.rms_current(tmc_value); + settings.save(); + #endif + break; + case VP_TMC_E0_Current: + #if AXIS_IS_TMC(E0) + stepperE0.rms_current(tmc_value); + settings.save(); + #endif + break; + case VP_TMC_E1_Current: + #if AXIS_IS_TMC(E1) + stepperE1.rms_current(tmc_value); + settings.save(); + #endif + break; + + default: + break; + } + #if USE_SENSORLESS + TERN_(X_HAS_STEALTHCHOP, tmc_step.x = stepperX.homing_threshold()); + TERN_(Y_HAS_STEALTHCHOP, tmc_step.y = stepperY.homing_threshold()); + TERN_(Z_HAS_STEALTHCHOP, tmc_step.z = stepperZ.homing_threshold()); + #endif +} + +void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("HandleManualMove"); + + int16_t movevalue = swap16(*(uint16_t*)val_ptr); + + // Choose Move distance + if (manualMoveStep == 0x01) manualMoveStep = 10; + else if (manualMoveStep == 0x02) manualMoveStep = 100; + else if (manualMoveStep == 0x03) manualMoveStep = 1000; + + DEBUG_ECHOLNPAIR("QUEUE LEN:", queue.length); + + if (!print_job_timer.isPaused() && !queue.ring_buffer.empty()) + return; + + char axiscode; + unsigned int speed = 1500; // FIXME: get default feedrate for manual moves, don't hardcode. + + switch (var.VP) { // switch X Y Z or Home + default: return; + case VP_MOVE_X: + DEBUG_ECHOLNPGM("X Move"); + axiscode = 'X'; + if (!ExtUI::canMove(ExtUI::axis_t::X)) goto cannotmove; + break; + + case VP_MOVE_Y: + DEBUG_ECHOLNPGM("Y Move"); + axiscode = 'Y'; + if (!ExtUI::canMove(ExtUI::axis_t::Y)) goto cannotmove; + break; + + case VP_MOVE_Z: + DEBUG_ECHOLNPGM("Z Move"); + axiscode = 'Z'; + speed = 300; // default to 5mm/s + if (!ExtUI::canMove(ExtUI::axis_t::Z)) goto cannotmove; + break; + + case VP_MOTOR_LOCK_UNLOK: + DEBUG_ECHOLNPGM("Motor Unlock"); + movevalue = 5; + axiscode = '\0'; + // return ; + break; + + case VP_HOME_ALL: // only used for homing + DEBUG_ECHOLNPGM("Home all"); + axiscode = '\0'; + movevalue = 0; // ignore value sent from display, this VP is _ONLY_ for homing. + //return; + break; + + case VP_X_HOME: + DEBUG_ECHOLNPGM("X Home"); + axiscode = 'X'; + movevalue = 0; + break; + + case VP_Y_HOME: + DEBUG_ECHOLNPGM("Y Home"); + axiscode = 'Y'; + movevalue = 0; + break; + + case VP_Z_HOME: + DEBUG_ECHOLNPGM("Z Home"); + axiscode = 'Z'; + movevalue = 0; + break; + } + + DEBUG_ECHOPAIR("movevalue = ", movevalue); + if (movevalue != 0 && movevalue != 5) { // get move distance + switch (movevalue) { + case 0x0001: movevalue = manualMoveStep; break; + case 0x0002: movevalue = -manualMoveStep; break; + default: movevalue = 0; break; + } + } + + if (!movevalue) { + // homing + DEBUG_ECHOPAIR(" homing ", AS_CHAR(axiscode)); + // char buf[6] = "G28 X"; + // buf[4] = axiscode; + + char buf[6]; + sprintf(buf, "G28 %c", axiscode); + //DEBUG_ECHOPAIR(" ", buf); + queue.enqueue_one_now(buf); + //DEBUG_ECHOLNPGM(" ✓"); + ForceCompleteUpdate(); + return; + } + else if (movevalue == 5) { + DEBUG_ECHOPAIR("send M84"); + char buf[6]; + snprintf_P(buf,6,PSTR("M84 %c"), axiscode); + queue.enqueue_one_now(buf); + ForceCompleteUpdate(); + return; + } + else { + // movement + DEBUG_ECHOPAIR(" move ", AS_CHAR(axiscode)); + bool old_relative_mode = relative_mode; + + if (!relative_mode) { + //DEBUG_ECHOPGM(" G91"); + queue.enqueue_now_P(PSTR("G91")); + //DEBUG_ECHOPGM(" ✓ "); + } + char buf[32]; // G1 X9999.99 F12345 + // unsigned int backup_speed = MMS_TO_MMM(feedrate_mm_s); + char sign[] = "\0"; + int16_t value = movevalue / 100; + if (movevalue < 0) { value = -value; sign[0] = '-'; } + int16_t fraction = ABS(movevalue) % 100; + snprintf_P(buf, 32, PSTR("G0 %c%s%d.%02d F%d"), axiscode, sign, value, fraction, speed); + queue.enqueue_one_now(buf); + + //if (backup_speed != speed) { + // snprintf_P(buf, 32, PSTR("G0 F%d"), backup_speed); + // queue.enqueue_one_now(buf); + // //DEBUG_ECHOPAIR(" ", buf); + //} + + //while (!enqueue_and_echo_command(buf)) idle(); + //DEBUG_ECHOLNPGM(" ✓ "); + if (!old_relative_mode) { + //DEBUG_ECHOPGM("G90"); + //queue.enqueue_now_P(PSTR("G90")); + queue.enqueue_now_P(PSTR("G90")); + //DEBUG_ECHOPGM(" ✓ "); + } + } + + ForceCompleteUpdate(); + DEBUG_ECHOLNPGM("manmv done."); + return; + + cannotmove: + DEBUG_ECHOLNPAIR(" cannot move ", AS_CHAR(axiscode)); + return; +} + +void DGUSScreenHandler::GetParkPos_MKS(DGUS_VP_Variable &var, void *val_ptr) { + const int16_t value_pos = swap16(*(int16_t*)val_ptr); + + switch (var.VP) { + case VP_X_PARK_POS: mks_park_pos.x = value_pos; break; + case VP_Y_PARK_POS: mks_park_pos.y = value_pos; break; + case VP_Z_PARK_POS: mks_park_pos.z = value_pos; break; + default: break; + } + skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel +} + +void DGUSScreenHandler::HandleChangeLevelPoint_MKS(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("HandleChangeLevelPoint_MKS"); + + const int16_t value_raw = swap16(*(int16_t*)val_ptr); + DEBUG_ECHOLNPAIR_F("value_raw:", value_raw); + + *(int16_t*)var.memadr = value_raw; + + settings.save(); + skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel +} + +void DGUSScreenHandler::HandleStepPerMMChanged_MKS(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("HandleStepPerMMChanged_MKS"); + + const uint16_t value_raw = swap16(*(uint16_t*)val_ptr); + const float value = (float)value_raw; + + DEBUG_ECHOLNPAIR("value_raw:", value_raw); + DEBUG_ECHOLNPAIR_F("value:", value); + + ExtUI::axis_t axis; + switch (var.VP) { + default: return; + case VP_X_STEP_PER_MM: axis = ExtUI::axis_t::X; break; + case VP_Y_STEP_PER_MM: axis = ExtUI::axis_t::Y; break; + case VP_Z_STEP_PER_MM: axis = ExtUI::axis_t::Z; break; + } + ExtUI::setAxisSteps_per_mm(value, axis); + DEBUG_ECHOLNPAIR_F("value_set:", ExtUI::getAxisSteps_per_mm(axis)); + settings.save(); + skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel +} + +void DGUSScreenHandler::HandleStepPerMMExtruderChanged_MKS(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("HandleStepPerMMExtruderChanged_MKS"); + + const uint16_t value_raw = swap16(*(uint16_t*)val_ptr); + const float value = (float)value_raw; + + DEBUG_ECHOLNPAIR("value_raw:", value_raw); + DEBUG_ECHOLNPAIR_F("value:", value); + + ExtUI::extruder_t extruder; + switch (var.VP) { + default: return; + #if HAS_HOTEND + case VP_E0_STEP_PER_MM: extruder = ExtUI::extruder_t::E0; break; + #endif + #if HAS_MULTI_HOTEND + case VP_E1_STEP_PER_MM: extruder = ExtUI::extruder_t::E1; break; + #endif + } + ExtUI::setAxisSteps_per_mm(value, extruder); + DEBUG_ECHOLNPAIR_F("value_set:", ExtUI::getAxisSteps_per_mm(extruder)); + settings.save(); + skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel +} + +void DGUSScreenHandler::HandleMaxSpeedChange_MKS(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("HandleMaxSpeedChange_MKS"); + + const uint16_t value_raw = swap16(*(uint16_t*)val_ptr); + const float value = (float)value_raw; + + DEBUG_ECHOLNPAIR("value_raw:", value_raw); + DEBUG_ECHOLNPAIR_F("value:", value); + + ExtUI::axis_t axis; + switch (var.VP) { + case VP_X_MAX_SPEED: axis = ExtUI::axis_t::X; break; + case VP_Y_MAX_SPEED: axis = ExtUI::axis_t::Y; break; + case VP_Z_MAX_SPEED: axis = ExtUI::axis_t::Z; break; + default: return; + } + ExtUI::setAxisMaxFeedrate_mm_s(value, axis); + DEBUG_ECHOLNPAIR_F("value_set:", ExtUI::getAxisMaxFeedrate_mm_s(axis)); + settings.save(); + skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel +} + +void DGUSScreenHandler::HandleExtruderMaxSpeedChange_MKS(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("HandleExtruderMaxSpeedChange_MKS"); + + const uint16_t value_raw = swap16(*(uint16_t*)val_ptr); + const float value = (float)value_raw; + + DEBUG_ECHOLNPAIR("value_raw:", value_raw); + DEBUG_ECHOLNPAIR_F("value:", value); + + ExtUI::extruder_t extruder; + switch (var.VP) { + default: return; + #if HAS_HOTEND + case VP_E0_MAX_SPEED: extruder = ExtUI::extruder_t::E0; break; + #endif + #if HAS_MULTI_HOTEND + #endif + case VP_E1_MAX_SPEED: extruder = ExtUI::extruder_t::E1; break; + } + ExtUI::setAxisMaxFeedrate_mm_s(value, extruder); + DEBUG_ECHOLNPAIR_F("value_set:", ExtUI::getAxisMaxFeedrate_mm_s(extruder)); + settings.save(); + skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel +} + +void DGUSScreenHandler::HandleMaxAccChange_MKS(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("HandleMaxAccChange_MKS"); + + const uint16_t value_raw = swap16(*(uint16_t*)val_ptr); + const float value = (float)value_raw; + + DEBUG_ECHOLNPAIR("value_raw:", value_raw); + DEBUG_ECHOLNPAIR_F("value:", value); + + ExtUI::axis_t axis; + switch (var.VP) { + default: return; + case VP_X_ACC_MAX_SPEED: axis = ExtUI::axis_t::X; break; + case VP_Y_ACC_MAX_SPEED: axis = ExtUI::axis_t::Y; break; + case VP_Z_ACC_MAX_SPEED: axis = ExtUI::axis_t::Z; break; + } + ExtUI::setAxisMaxAcceleration_mm_s2(value, axis); + DEBUG_ECHOLNPAIR_F("value_set:", ExtUI::getAxisMaxAcceleration_mm_s2(axis)); + settings.save(); + skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel +} + +void DGUSScreenHandler::HandleExtruderAccChange_MKS(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("HandleExtruderAccChange_MKS"); + + uint16_t value_raw = swap16(*(uint16_t*)val_ptr); + DEBUG_ECHOLNPAIR("value_raw:", value_raw); + float value = (float)value_raw; + ExtUI::extruder_t extruder; + switch (var.VP) { + default: return; + #if HAS_HOTEND + case VP_E0_ACC_MAX_SPEED: extruder = ExtUI::extruder_t::E0; settings.load(); break; + #endif + #if HAS_MULTI_HOTEND + case VP_E1_ACC_MAX_SPEED: extruder = ExtUI::extruder_t::E1; settings.load(); break; + #endif + } + DEBUG_ECHOLNPAIR_F("value:", value); + ExtUI::setAxisMaxAcceleration_mm_s2(value, extruder); + DEBUG_ECHOLNPAIR_F("value_set:", ExtUI::getAxisMaxAcceleration_mm_s2(extruder)); + settings.save(); + skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel +} + +void DGUSScreenHandler::HandleTravelAccChange_MKS(DGUS_VP_Variable &var, void *val_ptr) { + uint16_t value_travel = swap16(*(uint16_t*)val_ptr); + planner.settings.travel_acceleration = (float)value_travel; + skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel +} + +void DGUSScreenHandler::HandleFeedRateMinChange_MKS(DGUS_VP_Variable &var, void *val_ptr) { + uint16_t value_t = swap16(*(uint16_t*)val_ptr); + planner.settings.min_feedrate_mm_s = (float)value_t; + skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel +} + +void DGUSScreenHandler::HandleMin_T_F_MKS(DGUS_VP_Variable &var, void *val_ptr) { + uint16_t value_t_f = swap16(*(uint16_t*)val_ptr); + planner.settings.min_travel_feedrate_mm_s = (float)value_t_f; + skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel +} + +void DGUSScreenHandler::HandleAccChange_MKS(DGUS_VP_Variable &var, void *val_ptr) { + uint16_t value_acc = swap16(*(uint16_t*)val_ptr); + planner.settings.acceleration = (float)value_acc; + skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel +} + +#if ENABLED(PREVENT_COLD_EXTRUSION) + void DGUSScreenHandler::HandleGetExMinTemp_MKS(DGUS_VP_Variable &var, void *val_ptr) { + const uint16_t value_ex_min_temp = swap16(*(uint16_t*)val_ptr); + thermalManager.extrude_min_temp = value_ex_min_temp; + skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel + } +#endif + +#if HAS_PID_HEATING + void DGUSScreenHandler::HandleTemperaturePIDChanged(DGUS_VP_Variable &var, void *val_ptr) { + const uint16_t rawvalue = swap16(*(uint16_t*)val_ptr); + DEBUG_ECHOLNPAIR("V1:", rawvalue); + const float value = 1.0f * rawvalue; + DEBUG_ECHOLNPAIR("V2:", value); + float newvalue = 0; + + switch (var.VP) { + default: return; + #if HAS_HOTEND + case VP_E0_PID_P: newvalue = value; break; + case VP_E0_PID_I: newvalue = scalePID_i(value); break; + case VP_E0_PID_D: newvalue = scalePID_d(value); break; + #endif + #if HAS_MULTI_HOTEND + case VP_E1_PID_P: newvalue = value; break; + case VP_E1_PID_I: newvalue = scalePID_i(value); break; + case VP_E1_PID_D: newvalue = scalePID_d(value); break; + #endif + #if HAS_HEATED_BED + case VP_BED_PID_P: newvalue = value; break; + case VP_BED_PID_I: newvalue = scalePID_i(value); break; + case VP_BED_PID_D: newvalue = scalePID_d(value); break; + #endif + } + + DEBUG_ECHOLNPAIR_F("V3:", newvalue); + *(float *)var.memadr = newvalue; + + settings.save(); + skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel + } +#endif // HAS_PID_HEATING + +#if ENABLED(BABYSTEPPING) + void DGUSScreenHandler::HandleLiveAdjustZ(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("HandleLiveAdjustZ"); + char babystep_buf[30]; + float step = ZOffset_distance; + + uint16_t flag = swap16(*(uint16_t*)val_ptr); + switch (flag) { + case 0: + if (step == 0.01) + queue.inject_P(PSTR("M290 Z-0.01")); + else if (step == 0.1) + queue.inject_P(PSTR("M290 Z-0.1")); + else if (step == 0.5) + queue.inject_P(PSTR("M290 Z-0.5")); + else if (step == 1) + queue.inject_P(PSTR("M290 Z-1")); + else + queue.inject_P(PSTR("M290 Z-0.01")); + + z_offset_add = z_offset_add - ZOffset_distance; + break; + + case 1: + if (step == 0.01) + queue.inject_P(PSTR("M290 Z0.01")); + else if (step == 0.1) + queue.inject_P(PSTR("M290 Z0.1")); + else if (step == 0.5) + queue.inject_P(PSTR("M290 Z0.5")); + else if (step == 1) + queue.inject_P(PSTR("M290 Z1")); + else + queue.inject_P(PSTR("M290 Z-0.01")); + + z_offset_add = z_offset_add + ZOffset_distance; + break; + + default: + break; + } + ForceCompleteUpdate(); + } +#endif // BABYSTEPPING + +void DGUSScreenHandler::GetManualFilament(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("GetManualFilament"); + + uint16_t value_len = swap16(*(uint16_t*)val_ptr); + + float value = (float)value_len; + + DEBUG_ECHOLNPAIR_F("Get Filament len value:", value); + distanceFilament = value; + + skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel +} + +void DGUSScreenHandler::GetManualFilamentSpeed(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("GetManualFilamentSpeed"); + + uint16_t value_len = swap16(*(uint16_t*)val_ptr); + + DEBUG_ECHOLNPAIR_F("filamentSpeed_mm_s value:", value_len); + + filamentSpeed_mm_s = value_len; + + skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel +} + +void DGUSScreenHandler::MKS_FilamentLoadUnload(DGUS_VP_Variable &var, void *val_ptr, const int filamentDir) { + #if EITHER(HAS_MULTI_HOTEND, SINGLENOZZLE) + uint8_t swap_tool = 0; + #else + constexpr uint8_t swap_tool = 1; // T0 (or none at all) + #endif + + #if HAS_HOTEND + uint8_t hotend_too_cold = 0; + #endif + + if (!print_job_timer.isPaused() && !queue.ring_buffer.empty()) + return; + + const uint16_t val_t = swap16(*(uint16_t*)val_ptr); + switch (val_t) { + default: break; + case 0: + #if HAS_HOTEND + if (thermalManager.tooColdToExtrude(0)) + hotend_too_cold = 1; + else { + #if EITHER(HAS_MULTI_HOTEND, SINGLENOZZLE) + swap_tool = 1; + #endif + } + #endif + break; + case 1: + #if HAS_MULTI_HOTEND + if (thermalManager.tooColdToExtrude(1)) hotend_too_cold = 2; else swap_tool = 2; + #elif ENABLED(SINGLENOZZLE) + if (thermalManager.tooColdToExtrude(0)) hotend_too_cold = 1; else swap_tool = 2; + #endif + break; + } + + #if BOTH(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(PSTR("NOTICE"), nullptr, PSTR("Please wait."), PSTR("Nozzle heating!"), true, true, true, true); + SetupConfirmAction(nullptr); + GotoScreen(DGUSLCD_SCREEN_POPUP); + } + #endif + + if (swap_tool) { + char buf[30]; + snprintf_P(buf, 30 + #if EITHER(HAS_MULTI_HOTEND, SINGLENOZZLE) + , PSTR("M1002T%cE%dF%d"), char('0' + swap_tool - 1) + #else + , PSTR("M1002E%dF%d") + #endif + , (int)distanceFilament * filamentDir, filamentSpeed_mm_s * 60 + ); + queue.inject(buf); + } +} + +/** + * M1002: Do a tool-change and relative move for MKS_FilamentLoadUnload + * within the G-code execution window for best concurrency. + */ +void GcodeSuite::M1002() { + #if EITHER(HAS_MULTI_HOTEND, SINGLENOZZLE) + { + char buf[3]; + sprintf_P(buf, PSTR("T%c"), char('0' + parser.intval('T'))); + process_subcommands_now(buf); + } + #endif + + const uint8_t old_axis_relative = axis_relative; + set_e_relative(); // M83 + { + char buf[20]; + snprintf_P(buf, 20, PSTR("G1E%dF%d"), parser.intval('E'), parser.intval('F')); + process_subcommands_now(buf); + } + axis_relative = old_axis_relative; +} + +void DGUSScreenHandler::MKS_FilamentLoad(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("MKS_FilamentLoad"); + MKS_FilamentLoadUnload(var, val_ptr, 1); +} + +void DGUSScreenHandler::MKS_FilamentUnLoad(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("MKS_FilamentUnLoad"); + MKS_FilamentLoadUnload(var, val_ptr, -1); +} + +#if ENABLED(DGUS_FILAMENT_LOADUNLOAD) + + void DGUSScreenHandler::HandleFilamentOption(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("HandleFilamentOption"); + + uint8_t e_temp = 0; + filament_data.heated = false; + uint16_t preheat_option = swap16(*(uint16_t*)val_ptr); + if (preheat_option >= 10) { // Unload filament type + preheat_option -= 10; + filament_data.action = 2; + filament_data.purge_length = DGUS_FILAMENT_PURGE_LENGTH; + } + else if (preheat_option <= 8) // Load filament type + filament_data.action = 1; + else // Cancel filament operation + filament_data.action = 0; + + switch (preheat_option) { + case 0: // Load PLA + #ifdef PREHEAT_1_TEMP_HOTEND + e_temp = PREHEAT_1_TEMP_HOTEND; + #endif + break; + case 1: // Load ABS + TERN_(PREHEAT_2_TEMP_HOTEND, e_temp = PREHEAT_2_TEMP_HOTEND); + break; + case 2: // Load PET + #ifdef PREHEAT_3_TEMP_HOTEND + e_temp = PREHEAT_3_TEMP_HOTEND; + #endif + break; + case 3: // Load FLEX + #ifdef PREHEAT_4_TEMP_HOTEND + e_temp = PREHEAT_4_TEMP_HOTEND; + #endif + break; + case 9: // Cool down + default: + e_temp = 0; + break; + } + + if (filament_data.action == 0) { // Go back to utility screen + #if HAS_HOTEND + thermalManager.setTargetHotend(e_temp, ExtUI::extruder_t::E0); + #endif + #if HAS_MULTI_HOTEND + thermalManager.setTargetHotend(e_temp, ExtUI::extruder_t::E1); + #endif + GotoScreen(DGUSLCD_SCREEN_UTILITY); + } + else { // Go to the preheat screen to show the heating progress + switch (var.VP) { + default: return; + #if HAS_HOTEND + case VP_E0_FILAMENT_LOAD_UNLOAD: + filament_data.extruder = ExtUI::extruder_t::E0; + thermalManager.setTargetHotend(e_temp, filament_data.extruder); + break; + #endif + #if HAS_MULTI_HOTEND + case VP_E1_FILAMENT_LOAD_UNLOAD: + filament_data.extruder = ExtUI::extruder_t::E1; + thermalManager.setTargetHotend(e_temp, filament_data.extruder); + break; + #endif + } + } + } + + void DGUSScreenHandler::HandleFilamentLoadUnload(DGUS_VP_Variable &var) { + DEBUG_ECHOLNPGM("HandleFilamentLoadUnload"); + if (filament_data.action <= 0) return; + + // If we close to the target temperature, we can start load or unload the filament + if (thermalManager.hotEnoughToExtrude(filament_data.extruder) && \ + thermalManager.targetHotEnoughToExtrude(filament_data.extruder)) { + float movevalue = DGUS_FILAMENT_LOAD_LENGTH_PER_TIME; + + if (filament_data.action == 1) { // load filament + if (!filament_data.heated) { + filament_data.heated = true; + } + movevalue = ExtUI::getAxisPosition_mm(filament_data.extruder) + movevalue; + } + else { // unload filament + if (!filament_data.heated) { + GotoScreen(DGUSLCD_SCREEN_FILAMENT_UNLOADING); + filament_data.heated = true; + } + // Before unloading extrude to prevent jamming + if (filament_data.purge_length >= 0) { + movevalue = ExtUI::getAxisPosition_mm(filament_data.extruder) + movevalue; + filament_data.purge_length -= movevalue; + } + else { + movevalue = ExtUI::getAxisPosition_mm(filament_data.extruder) - movevalue; + } + } + ExtUI::setAxisPosition_mm(movevalue, filament_data.extruder); + } + } + +#endif // DGUS_FILAMENT_LOADUNLOAD + +bool DGUSScreenHandler::loop() { + dgusdisplay.loop(); + + const millis_t ms = millis(); + static millis_t next_event_ms = 0; + + static uint8_t language_times = 2; + + if (!IsScreenComplete() || ELAPSED(ms, next_event_ms)) { + next_event_ms = ms + DGUS_UPDATE_INTERVAL_MS; + UpdateScreenVPData(); + } + + if (language_times != 0) { + LanguagePInit(); + DGUS_LanguageDisplay(mks_language_index); + language_times--; + } + + #if ENABLED(SHOW_BOOTSCREEN) + static bool booted = false; + if (!booted && ELAPSED(ms, TERN(USE_MKS_GREEN_UI, 1000, BOOTSCREEN_TIMEOUT))) { + booted = true; + #if USE_SENSORLESS + TERN_(X_HAS_STEALTHCHOP, tmc_step.x = stepperX.homing_threshold()); + TERN_(Y_HAS_STEALTHCHOP, tmc_step.y = stepperY.homing_threshold()); + TERN_(Z_HAS_STEALTHCHOP, tmc_step.z = stepperZ.homing_threshold()); + #endif + + #if ENABLED(PREVENT_COLD_EXTRUSION) + if (mks_min_extrusion_temp != 0) + thermalManager.extrude_min_temp = mks_min_extrusion_temp; + #endif + + DGUS_ExtrudeLoadInit(); + + TERN_(DGUS_MKS_RUNOUT_SENSOR, DGUS_RunoutInit()); + + if (TERN0(POWER_LOSS_RECOVERY, recovery.valid())) + GotoScreen(DGUSLCD_SCREEN_POWER_LOSS); + else + GotoScreen(DGUSLCD_SCREEN_MAIN); + } + + #if ENABLED(DGUS_MKS_RUNOUT_SENSOR) + if (booted && printingIsActive()) DGUS_Runout_Idle(); + #endif + #endif // SHOW_BOOTSCREEN + + return IsScreenComplete(); +} + +void DGUSScreenHandler::LanguagePInit() { + switch (mks_language_index) { + case MKS_SimpleChinese: + dgusdisplay.MKS_WriteVariable(VP_LANGUAGE_CHANGE1, MKS_Language_Choose); + dgusdisplay.MKS_WriteVariable(VP_LANGUAGE_CHANGE2, MKS_Language_NoChoose); + break; + case MKS_English: + dgusdisplay.MKS_WriteVariable(VP_LANGUAGE_CHANGE1, MKS_Language_NoChoose); + dgusdisplay.MKS_WriteVariable(VP_LANGUAGE_CHANGE2, MKS_Language_Choose); + break; + default: + break; + } +} + +void DGUSScreenHandler::DGUS_ExtrudeLoadInit(void) { + ex_filament.ex_length = distanceFilament; + ex_filament.ex_load_unload_flag = 0; + ex_filament.ex_need_time = filamentSpeed_mm_s; + ex_filament.ex_speed = 0; + ex_filament.ex_status = EX_NONE; + ex_filament.ex_tick_end = 0; + ex_filament.ex_tick_start = 0; +} + +void DGUSScreenHandler::DGUS_RunoutInit(void) { + #if PIN_EXISTS(MT_DET_1) + SET_INPUT_PULLUP(MT_DET_1_PIN); + #endif + runout_mks.de_count = 0; + runout_mks.de_times = 10; + runout_mks.pin_status = 1; + runout_mks.runout_status = UNRUNOUT_STATUS; +} + +void DGUSScreenHandler::DGUS_Runout_Idle(void) { + #if ENABLED(DGUS_MKS_RUNOUT_SENSOR) + // scanf runout pin + switch (runout_mks.runout_status) { + + case RUNOUT_STATUS: + runout_mks.runout_status = RUNOUT_BEGIN_STATUS; + queue.inject_P(PSTR("M25")); + GotoScreen(MKSLCD_SCREEN_PAUSE); + + sendinfoscreen(PSTR("NOTICE"), nullptr, PSTR("Please change filament!"), nullptr, true, true, true, true); + //SetupConfirmAction(nullptr); + GotoScreen(DGUSLCD_SCREEN_POPUP); + break; + + case UNRUNOUT_STATUS: + if (READ(MT_DET_1_PIN) == LOW) + runout_mks.runout_status = RUNOUT_STATUS; + break; + + case RUNOUT_BEGIN_STATUS: + if (READ(MT_DET_1_PIN) == HIGH) + runout_mks.runout_status = RUNOUT_WAITTING_STATUS; + break; + + case RUNOUT_WAITTING_STATUS: + if (READ(MT_DET_1_PIN) == LOW) + runout_mks.runout_status = RUNOUT_BEGIN_STATUS; + break; + + default: break; + } + #endif +} + +void DGUSScreenHandler::DGUS_LanguageDisplay(uint8_t var) { + if (var == MKS_English) { + const char home_buf_en[] = "Home"; + dgusdisplay.WriteVariable(VP_HOME_Dis, home_buf_en, 32, true); + + const char setting_buf_en[] = "Setting"; + dgusdisplay.WriteVariable(VP_Setting_Dis, setting_buf_en, 32, true); + + const char Tool_buf_en[] = "Tool"; + dgusdisplay.WriteVariable(VP_Tool_Dis, Tool_buf_en, 32, true); + + const char Print_buf_en[] = "Print"; + dgusdisplay.WriteVariable(VP_Print_Dis, Print_buf_en, 32, true); + + const char Language_buf_en[] = "Language"; + dgusdisplay.WriteVariable(VP_Language_Dis, Language_buf_en, 32, true); + + const char About_buf_en[] = "About"; + dgusdisplay.WriteVariable(VP_About_Dis, About_buf_en, 32, true); + + const char Config_buf_en[] = "Config"; + dgusdisplay.WriteVariable(VP_Config_Dis, Config_buf_en, 32, true); + + const char MotorConfig_buf_en[] = "MotorConfig"; + dgusdisplay.WriteVariable(VP_MotorConfig_Dis, MotorConfig_buf_en, 32, true); + + const char LevelConfig_buf_en[] = "LevelConfig"; + dgusdisplay.WriteVariable(VP_LevelConfig_Dis, LevelConfig_buf_en, 32, true); + + const char TemperatureConfig_buf_en[] = "Temperature"; + dgusdisplay.WriteVariable(VP_TemperatureConfig_Dis, TemperatureConfig_buf_en, 32, true); + + const char Advance_buf_en[] = "Advance"; + dgusdisplay.WriteVariable(VP_Advance_Dis, Advance_buf_en, 32, true); + + const char Filament_buf_en[] = "Extrude"; + dgusdisplay.WriteVariable(VP_Filament_Dis, Filament_buf_en, 32, true); + + const char Move_buf_en[] = "Move"; + dgusdisplay.WriteVariable(VP_Move_Dis, Move_buf_en, 32, true); + + #if ENABLED(AUTO_BED_LEVELING_BILINEAR) + const char Level_buf_en[] = "AutoLevel"; + dgusdisplay.WriteVariable(VP_Level_Dis, Level_buf_en, 32, true); + #elif ENABLED(MESH_BED_LEVELING) + const char Level_buf_en[] = "MeshLevel"; + dgusdisplay.WriteVariable(VP_Level_Dis, Level_buf_en, 32, true); + #else + const char Level_buf_en[] = "Level"; + dgusdisplay.WriteVariable(VP_Level_Dis, Level_buf_en, 32, true); + #endif + + const char MotorPluse_buf_en[] = "MotorPluse"; + dgusdisplay.WriteVariable(VP_MotorPluse_Dis, MotorPluse_buf_en, 32, true); + + const char MotorMaxSpeed_buf_en[] = "MotorMaxSpeed"; + dgusdisplay.WriteVariable(VP_MotorMaxSpeed_Dis, MotorMaxSpeed_buf_en, 32, true); + + const char MotorMaxAcc_buf_en[] = "MotorAcc"; + dgusdisplay.WriteVariable(VP_MotorMaxAcc_Dis, MotorMaxAcc_buf_en, 32, true); + + const char TravelAcc_buf_en[] = "TravelAcc"; + dgusdisplay.WriteVariable(VP_TravelAcc_Dis, TravelAcc_buf_en, 32, true); + + const char FeedRateMin_buf_en[] = "FeedRateMin"; + dgusdisplay.WriteVariable(VP_FeedRateMin_Dis, FeedRateMin_buf_en, 32, true); + + const char TravelFeeRateMin_buf_en[] = "TravelFeedRateMin"; + dgusdisplay.WriteVariable(VP_TravelFeeRateMin_Dis, TravelFeeRateMin_buf_en, 32, true); + + const char Acc_buf_en[] = "Acc"; + dgusdisplay.WriteVariable(VP_ACC_Dis, Acc_buf_en, 32, true); + + const char Point_One_buf_en[] = "Point_First"; + dgusdisplay.WriteVariable(VP_Point_One_Dis, Point_One_buf_en, 32, true); + + const char Point_Two_buf_en[] = "Point_Second"; + dgusdisplay.WriteVariable(VP_Point_Two_Dis, Point_Two_buf_en, 32, true); + + const char Point_Three_buf_en[] = "Point_Third"; + dgusdisplay.WriteVariable(VP_Point_Three_Dis, Point_Three_buf_en, 32, true); + + const char Point_Four_buf_en[] = "Point_Fourth"; + dgusdisplay.WriteVariable(VP_Point_Four_Dis, Point_Four_buf_en, 32, true); + + const char Point_Five_buf_en[] = "Point_Fifth"; + dgusdisplay.WriteVariable(VP_Point_Five_Dis, Point_Five_buf_en, 32, true); + + const char Extrusion_buf_en[] = "Extrusion"; + dgusdisplay.WriteVariable(VP_Extrusion_Dis, Extrusion_buf_en, 32, true); + + const char HeatBed_buf_en[] = "HeatBed"; + dgusdisplay.WriteVariable(VP_HeatBed_Dis, HeatBed_buf_en, 32, true); + + const char FactoryDefaults_buf_en[] = "FactoryDefaults"; + dgusdisplay.WriteVariable(VP_FactoryDefaults_Dis, FactoryDefaults_buf_en, 32, true); + + const char StoreSetting_buf_en[] = "StoreSetting"; + dgusdisplay.WriteVariable(VP_StoreSetting_Dis, StoreSetting_buf_en, 32, true); + + const char PrintPauseConfig_buf_en[] = "PrintPauseConfig"; + dgusdisplay.WriteVariable(VP_PrintPauseConfig_Dis, PrintPauseConfig_buf_en, 32, true); + + const char X_Pluse_buf_en[] = "X_Pluse"; + dgusdisplay.WriteVariable(VP_X_Pluse_Dis, X_Pluse_buf_en, 32, true); + + const char Y_Pluse_buf_en[] = "Y_Pluse"; + dgusdisplay.WriteVariable(VP_Y_Pluse_Dis, Y_Pluse_buf_en, 32, true); + + const char Z_Pluse_buf_en[] = "Z_Pluse"; + dgusdisplay.WriteVariable(VP_Z_Pluse_Dis, Z_Pluse_buf_en, 32, true); + + const char E0_Pluse_buf_en[] = "E0_Pluse"; + dgusdisplay.WriteVariable(VP_E0_Pluse_Dis, E0_Pluse_buf_en, 32, true); + + const char E1_Pluse_buf_en[] = "E1_Pluse"; + dgusdisplay.WriteVariable(VP_E1_Pluse_Dis, E1_Pluse_buf_en, 32, true); + + const char X_Max_Speed_buf_en[] = "X_Max_Speed"; + dgusdisplay.WriteVariable(VP_X_Max_Speed_Dis, X_Max_Speed_buf_en, 32, true); + + const char Y_Max_Speed_buf_en[] = "Y_Max_Speed"; + dgusdisplay.WriteVariable(VP_Y_Max_Speed_Dis, Y_Max_Speed_buf_en, 32, true); + + const char Z_Max_Speed_buf_en[] = "Z_Max_Speed"; + dgusdisplay.WriteVariable(VP_Z_Max_Speed_Dis, Z_Max_Speed_buf_en, 32, true); + + const char E0_Max_Speed_buf_en[] = "E0_Max_Speed"; + dgusdisplay.WriteVariable(VP_E0_Max_Speed_Dis, E0_Max_Speed_buf_en, 32, true); + + const char E1_Max_Speed_buf_en[] = "E1_Max_Speed"; + dgusdisplay.WriteVariable(VP_E1_Max_Speed_Dis, E1_Max_Speed_buf_en, 32, true); + + const char X_Max_Acc_Speed_buf_en[] = "X_Max_Acc_Speed"; + dgusdisplay.WriteVariable(VP_X_Max_Acc_Speed_Dis, X_Max_Acc_Speed_buf_en, 32, true); + + const char Y_Max_Acc_Speed_buf_en[] = "Y_Max_Acc_Speed"; + dgusdisplay.WriteVariable(VP_Y_Max_Acc_Speed_Dis, Y_Max_Acc_Speed_buf_en, 32, true); + + const char Z_Max_Acc_Speed_buf_en[] = "Z_Max_Acc_Speed"; + dgusdisplay.WriteVariable(VP_Z_Max_Acc_Speed_Dis, Z_Max_Acc_Speed_buf_en, 32, true); + + const char E0_Max_Acc_Speed_buf_en[] = "E0_Max_Acc_Speed"; + dgusdisplay.WriteVariable(VP_E0_Max_Acc_Speed_Dis, E0_Max_Acc_Speed_buf_en, 32, true); + + const char E1_Max_Acc_Speed_buf_en[] = "E1_Max_Acc_Speed"; + dgusdisplay.WriteVariable(VP_E1_Max_Acc_Speed_Dis, E1_Max_Acc_Speed_buf_en, 32, true); + + const char X_PARK_POS_buf_en[] = "X_PARK_POS"; + dgusdisplay.WriteVariable(VP_X_PARK_POS_Dis, X_PARK_POS_buf_en, 32, true); + + const char Y_PARK_POS_buf_en[] = "Y_PARK_POS"; + dgusdisplay.WriteVariable(VP_Y_PARK_POS_Dis, Y_PARK_POS_buf_en, 32, true); + + const char Z_PARK_POS_buf_en[] = "Z_PARK_POS"; + dgusdisplay.WriteVariable(VP_Z_PARK_POS_Dis, Z_PARK_POS_buf_en, 32, true); + + const char Length_buf_en[] = "Length"; + dgusdisplay.WriteVariable(VP_Length_Dis, Length_buf_en, 32, true); + + const char Speed_buf_en[] = "Speed"; + dgusdisplay.WriteVariable(VP_Speed_Dis, Speed_buf_en, 32, true); + + const char InOut_buf_en[] = "InOut"; + dgusdisplay.WriteVariable(VP_InOut_Dis, InOut_buf_en, 32, true); + + const char PrintTimet_buf_en[] = "PrintTime"; + dgusdisplay.WriteVariable(VP_PrintTime_Dis, PrintTimet_buf_en, 32, true); + + const char E0_Temp_buf_en[] = "E0_Temp"; + dgusdisplay.WriteVariable(VP_E0_Temp_Dis, E0_Temp_buf_en, 32, true); + + const char E1_Temp_buf_en[] = "E1_Temp"; + dgusdisplay.WriteVariable(VP_E1_Temp_Dis, E1_Temp_buf_en, 32, true); + + const char HB_Temp_buf_en[] = "HB_Temp"; + dgusdisplay.WriteVariable(VP_HB_Temp_Dis, HB_Temp_buf_en, 32, true); + + const char Feedrate_buf_en[] = "Feedrate"; + dgusdisplay.WriteVariable(VP_Feedrate_Dis, Feedrate_buf_en, 32, true); + + const char PrintAcc_buf_en[] = "PrintSpeed"; + dgusdisplay.WriteVariable(VP_PrintAcc_Dis, PrintAcc_buf_en, 32, true); + + const char FAN_Speed_buf_en[] = "FAN_Speed"; + dgusdisplay.WriteVariable(VP_Fan_Speed_Dis, FAN_Speed_buf_en, 32, true); + + const char Printing_buf_en[] = "Printing"; + dgusdisplay.WriteVariable(VP_Printing_Dis, Printing_buf_en, 32, true); + + const char Info_EEPROM_1_buf_en[] = "Store setting?"; + dgusdisplay.WriteVariable(VP_Info_EEPROM_1_Dis, Info_EEPROM_1_buf_en, 32, true); + + const char Info_EEPROM_2_buf_en[] = "Revert setting?"; + dgusdisplay.WriteVariable(VP_Info_EEPROM_2_Dis, Info_EEPROM_2_buf_en, 32, true); + + const char Info_PrinfFinsh_1_buf_en[] = "Print Done"; + dgusdisplay.WriteVariable(VP_Info_PrinfFinsh_1_Dis, Info_PrinfFinsh_1_buf_en, 32, true); + + const char TMC_X_Step_buf_en[] = "X_SenSitivity"; + dgusdisplay.WriteVariable(VP_TMC_X_Step_Dis, TMC_X_Step_buf_en, 32, true); + + const char TMC_Y_Step_buf_en[] = "Y_SenSitivity"; + dgusdisplay.WriteVariable(VP_TMC_Y_Step_Dis, TMC_Y_Step_buf_en, 32, true); + + const char TMC_Z_Step_buf_en[] = "Z_SenSitivity"; + dgusdisplay.WriteVariable(VP_TMC_Z_Step_Dis, TMC_Z_Step_buf_en, 32, true); + + const char TMC_X_Current_buf_en[] = "X_Current"; + dgusdisplay.WriteVariable(VP_TMC_X_Current_Dis, TMC_X_Current_buf_en, 32, true); + + const char TMC_Y_Current_buf_en[] = "Y_Current"; + dgusdisplay.WriteVariable(VP_TMC_Y_Current_Dis, TMC_Y_Current_buf_en, 32, true); + + const char TMC_Z_Current_buf_en[] = "Z_Current"; + dgusdisplay.WriteVariable(VP_TMC_Z_Current_Dis, TMC_Z_Current_buf_en, 32, true); + + const char TMC_E0_Current_buf_en[] = "E0_Current"; + dgusdisplay.WriteVariable(VP_TMC_E0_Current_Dis, TMC_E0_Current_buf_en, 32, true); + + const char TMC_X1_Current_buf_en[] = "X1_Current"; + dgusdisplay.WriteVariable(VP_TMC_X1_Current_Dis, TMC_X1_Current_buf_en, 32, true); + + const char TMC_Y1_Current_buf_en[] = "Y1_Current"; + dgusdisplay.WriteVariable(VP_TMC_Y1_Current_Dis, TMC_Y1_Current_buf_en, 32, true); + + const char TMC_Z1_Current_buf_en[] = "Z1_Current"; + dgusdisplay.WriteVariable(VP_TMC_Z1_Current_Dis, TMC_Z1_Current_buf_en, 32, true); + + const char TMC_E1_Current_buf_en[] = "E1_Current"; + dgusdisplay.WriteVariable(VP_TMC_E1_Current_Dis, TMC_E1_Current_buf_en, 32, true); + + const char Min_Ex_Temp_buf_en[] = "Min_Ex_Temp"; + dgusdisplay.WriteVariable(VP_Min_Ex_Temp_Dis, Min_Ex_Temp_buf_en, 32, true); + + const char AutoLEVEL_INFO1_buf_en[] = "Please Press Button!"; + dgusdisplay.WriteVariable(VP_AutoLEVEL_INFO1, AutoLEVEL_INFO1_buf_en, 32, true); + + const char EX_TEMP_INFO2_buf_en[] = "Please wait a monent"; + dgusdisplay.WriteVariable(VP_EX_TEMP_INFO2_Dis, EX_TEMP_INFO2_buf_en, 32, true); + + const char EX_TEMP_INFO3_buf_en[] = "Cancle"; + dgusdisplay.WriteVariable(VP_EX_TEMP_INFO3_Dis, EX_TEMP_INFO3_buf_en, 32, true); + + const char PrintConfrim_Info_buf_en[] = "Start Print?"; + dgusdisplay.WriteVariable(VP_PrintConfrim_Info_Dis, PrintConfrim_Info_buf_en, 32, true); + + const char StopPrintConfrim_Info_buf_en[] = "Stop Print?"; + dgusdisplay.WriteVariable(VP_StopPrintConfrim_Info_Dis, StopPrintConfrim_Info_buf_en, 32, true); + + const char Printting_buf_en[] = "Printing"; + dgusdisplay.WriteVariable(VP_Printting_Dis, Printting_buf_en, 32, true); + + const char LCD_BLK_buf_en[] = "Backlight"; + dgusdisplay.WriteVariable(VP_LCD_BLK_Dis, LCD_BLK_buf_en, 32, true); + } + else if (var == MKS_SimpleChinese) { + uint16_t home_buf_ch[] = { 0xF7D6, 0xB3D2 }; + dgusdisplay.WriteVariable(VP_HOME_Dis, home_buf_ch, 4, true); + + const uint16_t Setting_Dis[] = { 0xE8C9, 0xC3D6, 0x2000, 0x2000, 0x2000 }; + dgusdisplay.WriteVariable(VP_Setting_Dis, Setting_Dis, 7, true); + + const uint16_t Tool_Dis[] = { 0xA4B9, 0xDFBE }; + dgusdisplay.WriteVariable(VP_Tool_Dis, Tool_Dis, 4, true); + + const uint16_t Print_buf_ch[] = { 0xF2B4, 0xA1D3, 0x2000 }; + dgusdisplay.WriteVariable(VP_Print_Dis, Print_buf_ch, 6, true); + + const uint16_t Language_buf_ch[] = { 0xEFD3, 0xD4D1, 0x2000, 0x2000 }; + dgusdisplay.WriteVariable(VP_Language_Dis, Language_buf_ch, 8, true); + + const uint16_t About_buf_ch[] = { 0xD8B9, 0xDAD3, 0x2000 }; + dgusdisplay.WriteVariable(VP_About_Dis, About_buf_ch, 6, true); + + const uint16_t Config_buf_ch[] = { 0xE4C5, 0xC3D6, 0x2000 }; + dgusdisplay.WriteVariable(VP_Config_Dis, Config_buf_ch, 6, true); + + const uint16_t MotorConfig_buf_ch[] = { 0xE7B5, 0xFABB, 0xE4C5, 0xC3D6, 0x2000 }; + dgusdisplay.WriteVariable(VP_MotorConfig_Dis, MotorConfig_buf_ch, 12, true); + + const uint16_t LevelConfig_buf_ch[] = { 0xD6CA, 0xAFB6, 0xF7B5, 0xBDC6, 0xE8C9, 0xC3D6, 0x2000 }; + dgusdisplay.WriteVariable(VP_LevelConfig_Dis, LevelConfig_buf_ch, 32, true); + + const uint16_t TemperatureConfig_buf_ch[] = { 0xC2CE, 0xC8B6, 0x2000 }; + dgusdisplay.WriteVariable(VP_TemperatureConfig_Dis, TemperatureConfig_buf_ch, 11, true); + + const uint16_t Advance_buf_ch[] = { 0xDFB8, 0xB6BC, 0xE8C9, 0xC3D6, 0x2000 }; + dgusdisplay.WriteVariable(VP_Advance_Dis, Advance_buf_ch, 16, true); + + const uint16_t Filament_buf_ch[] = { 0xB7BC, 0xF6B3, 0x2000 }; + dgusdisplay.WriteVariable(VP_Filament_Dis, Filament_buf_ch, 8, true); + + const uint16_t Move_buf_ch[] = { 0xC6D2, 0xAFB6, 0x2000 }; + dgusdisplay.WriteVariable(VP_Move_Dis, Move_buf_ch, 4, true); + + #if ENABLED(AUTO_BED_LEVELING_BILINEAR) + const uint16_t Level_buf_ch[] = { 0xD4D7, 0xAFB6, 0xF7B5, 0xBDC6, 0x2000 }; + dgusdisplay.WriteVariable(VP_Level_Dis, Level_buf_ch, 32, true); + #elif ENABLED(MESH_BED_LEVELING) + const uint16_t Level_buf_ch[] = { 0xF8CD, 0xF1B8, 0xF7B5, 0xBDC6, 0x2000 }; + dgusdisplay.WriteVariable(VP_Level_Dis, Level_buf_ch, 32, true); + #else + const uint16_t Level_buf_ch[] = { 0xD6CA, 0xAFB6, 0xF7B5, 0xBDC6, 0x2000 }; + dgusdisplay.WriteVariable(VP_Level_Dis, Level_buf_ch, 32, true); + #endif + + const uint16_t MotorPluse_buf_ch[] = { 0xF6C2, 0xE5B3, 0x2000 }; + dgusdisplay.WriteVariable(VP_MotorPluse_Dis, MotorPluse_buf_ch, 16, true); + + const uint16_t MotorMaxSpeed_buf_ch[] = { 0xEED7, 0xF3B4, 0xD9CB, 0xC8B6, 0x2000 }; + dgusdisplay.WriteVariable(VP_MotorMaxSpeed_Dis, MotorMaxSpeed_buf_ch, 16, true); + + const uint16_t MotorMaxAcc_buf_ch[] = { 0xEED7, 0xF3B4, 0xD3BC, 0xD9CB, 0xC8B6, 0x2000 }; + dgusdisplay.WriteVariable(VP_MotorMaxAcc_Dis, MotorMaxAcc_buf_ch, 16, true); + + const uint16_t TravelAcc_buf_ch[] = { 0xD5BF, 0xD0D0, 0xD3BC, 0xD9CB, 0xC8B6, 0x2000 }; + dgusdisplay.WriteVariable(VP_TravelAcc_Dis, TravelAcc_buf_ch, 16, true); + + const uint16_t FeedRateMin_buf_ch[] = { 0xEED7, 0xA1D0, 0xD9CB, 0xC8B6, 0x2000 }; + dgusdisplay.WriteVariable(VP_FeedRateMin_Dis, FeedRateMin_buf_ch, 12, true); + + const uint16_t TravelFeeRateMin_buf_ch[] = { 0xD5BF, 0xD0D0, 0xEED7, 0xA1D0, 0xD9CB, 0xC8B6, 0x2000 }; + dgusdisplay.WriteVariable(VP_TravelFeeRateMin_Dis, TravelFeeRateMin_buf_ch, 24, true); + + const uint16_t Acc_buf_ch[] = { 0xD3BC, 0xD9CB, 0xC8B6, 0x2000 }; + dgusdisplay.WriteVariable(VP_ACC_Dis, Acc_buf_ch, 16, true); + + const uint16_t Point_One_buf_ch[] = { 0xDAB5, 0xBBD2, 0xE3B5, 0x2000 }; + dgusdisplay.WriteVariable(VP_Point_One_Dis, Point_One_buf_ch, 12, true); + + const uint16_t Point_Two_buf_ch[] = { 0xDAB5, 0xFEB6, 0xE3B5, 0x2000 }; + dgusdisplay.WriteVariable(VP_Point_Two_Dis, Point_Two_buf_ch, 12, true); + + const uint16_t Point_Three_buf_ch[] = { 0xDAB5, 0xFDC8, 0xE3B5, 0x2000 }; + dgusdisplay.WriteVariable(VP_Point_Three_Dis, Point_Three_buf_ch, 12, true); + + const uint16_t Point_Four_buf_ch[] = { 0xDAB5, 0xC4CB, 0xE3B5, 0x2000 }; + dgusdisplay.WriteVariable(VP_Point_Four_Dis, Point_Four_buf_ch, 12, true); + + const uint16_t Point_Five_buf_ch[] = { 0xDAB5, 0xE5CE, 0xE3B5, 0x2000 }; + dgusdisplay.WriteVariable(VP_Point_Five_Dis, Point_Five_buf_ch, 12, true); + + const uint16_t Extrusion_buf_ch[] = { 0xB7BC, 0xF6B3, 0xB7CD, 0x2000 }; + dgusdisplay.WriteVariable(VP_Extrusion_Dis, Extrusion_buf_ch, 12, true); + + const uint16_t HeatBed_buf_ch[] = { 0xC8C8, 0xB2B4, 0x2000 }; + dgusdisplay.WriteVariable(VP_HeatBed_Dis, HeatBed_buf_ch, 12, true); + + const uint16_t FactoryDefaults_buf_ch[] = { 0xD6BB, 0xB4B8, 0xF6B3, 0xA7B3, 0xE8C9, 0xC3D6, 0x2000 }; + dgusdisplay.WriteVariable(VP_FactoryDefaults_Dis, FactoryDefaults_buf_ch, 16, true); + + const uint16_t StoreSetting_buf_ch[] = { 0xA3B1, 0xE6B4, 0xE8C9, 0xC3D6, 0x2000 }; + dgusdisplay.WriteVariable(VP_StoreSetting_Dis, StoreSetting_buf_ch, 16, true); + + const uint16_t PrintPauseConfig_buf_ch[] = { 0xDDD4, 0xA3CD, 0xBBCE, 0xC3D6, 0x2000 }; + dgusdisplay.WriteVariable(VP_PrintPauseConfig_Dis, PrintPauseConfig_buf_ch, 32, true); + + const uint16_t X_Pluse_buf_ch[] = { 0x2058, 0xE1D6, 0xF6C2, 0xE5B3, 0x2000 }; + dgusdisplay.WriteVariable(VP_X_Pluse_Dis, X_Pluse_buf_ch, 16, true); + + const uint16_t Y_Pluse_buf_ch[] = { 0x2059, 0xE1D6, 0xF6C2, 0xE5B3, 0x2000 }; + dgusdisplay.WriteVariable(VP_Y_Pluse_Dis, Y_Pluse_buf_ch, 16, true); + + const uint16_t Z_Pluse_buf_ch[] = { 0x205A, 0xE1D6, 0xF6C2, 0xE5B3, 0x2000 }; + dgusdisplay.WriteVariable(VP_Z_Pluse_Dis, Z_Pluse_buf_ch, 16, true); + + const uint16_t E0_Pluse_buf_ch[] = { 0x3045, 0xE1D6, 0xF6C2, 0xE5B3, 0x2000 }; + dgusdisplay.WriteVariable(VP_E0_Pluse_Dis, E0_Pluse_buf_ch, 16, true); + + const uint16_t E1_Pluse_buf_ch[] = { 0x3145, 0xE1D6, 0xF6C2, 0xE5B3, 0x2000 }; + dgusdisplay.WriteVariable(VP_E1_Pluse_Dis, E1_Pluse_buf_ch, 16, true); + + const uint16_t X_Max_Speed_buf_ch[] = { 0x2058, 0xEED7, 0xF3B4, 0xD9CB, 0xC8B6, 0x2000 }; + dgusdisplay.WriteVariable(VP_X_Max_Speed_Dis, X_Max_Speed_buf_ch, 16, true); + + const uint16_t Y_Max_Speed_buf_ch[] = { 0x2059, 0xEED7, 0xF3B4, 0xD9CB, 0xC8B6, 0x2000 }; + dgusdisplay.WriteVariable(VP_Y_Max_Speed_Dis, Y_Max_Speed_buf_ch, 16, true); + + const uint16_t Z_Max_Speed_buf_ch[] = { 0x205A, 0xEED7, 0xF3B4, 0xD9CB, 0xC8B6, 0x2000 }; + dgusdisplay.WriteVariable(VP_Z_Max_Speed_Dis, Z_Max_Speed_buf_ch, 16, true); + + const uint16_t E0_Max_Speed_buf_ch[] = { 0x3045, 0xEED7, 0xF3B4, 0xD9CB, 0xC8B6, 0x2000 }; + dgusdisplay.WriteVariable(VP_E0_Max_Speed_Dis, E0_Max_Speed_buf_ch, 16, true); + + const uint16_t E1_Max_Speed_buf_ch[] = { 0x3145, 0xEED7, 0xF3B4, 0xD9CB, 0xC8B6, 0x2000 }; + dgusdisplay.WriteVariable(VP_E1_Max_Speed_Dis, E1_Max_Speed_buf_ch, 16, true); + + const uint16_t X_Max_Acc_Speed_buf_ch[] = { 0x2058, 0xEED7, 0xF3B4, 0xD3BC, 0xD9CB, 0xC8B6, 0x2000 }; + dgusdisplay.WriteVariable(VP_X_Max_Acc_Speed_Dis, X_Max_Acc_Speed_buf_ch, 16, true); + + const uint16_t Y_Max_Acc_Speed_buf_ch[] = { 0x2059, 0xEED7, 0xF3B4, 0xD3BC, 0xD9CB, 0xC8B6, 0x2000 }; + dgusdisplay.WriteVariable(VP_Y_Max_Acc_Speed_Dis, Y_Max_Acc_Speed_buf_ch, 16, true); + + const uint16_t Z_Max_Acc_Speed_buf_ch[] = { 0x205A, 0xEED7, 0xF3B4, 0xD3BC, 0xD9CB, 0xC8B6, 0x2000 }; + dgusdisplay.WriteVariable(VP_Z_Max_Acc_Speed_Dis, Z_Max_Acc_Speed_buf_ch, 16, true); + + const uint16_t E0_Max_Acc_Speed_buf_ch[] = { 0x3045, 0xEED7, 0xF3B4, 0xD3BC, 0xD9CB, 0xC8B6, 0x2000 }; + dgusdisplay.WriteVariable(VP_E0_Max_Acc_Speed_Dis, E0_Max_Acc_Speed_buf_ch, 16, true); + + const uint16_t E1_Max_Acc_Speed_buf_ch[] = { 0x3145, 0xEED7, 0xF3B4, 0xD3BC, 0xD9CB, 0xC8B6, 0x2000 }; + dgusdisplay.WriteVariable(VP_E1_Max_Acc_Speed_Dis, E1_Max_Acc_Speed_buf_ch, 16, true); + + const uint16_t X_PARK_POS_buf_ch[] = { 0x2058, 0xDDD4, 0xA3CD, 0xBBCE, 0xC3D6, 0x2000 }; + dgusdisplay.WriteVariable(VP_X_PARK_POS_Dis, X_PARK_POS_buf_ch, 16, true); + + const uint16_t Y_PARK_POS_buf_ch[] = { 0x2059, 0xDDD4, 0xA3CD, 0xBBCE, 0xC3D6, 0x2000 }; + dgusdisplay.WriteVariable(VP_Y_PARK_POS_Dis, Y_PARK_POS_buf_ch, 16, true); + + const uint16_t Z_PARK_POS_buf_ch[] = { 0x205A, 0xDDD4, 0xA3CD, 0xBBCE, 0xC3D6, 0x2000 }; + dgusdisplay.WriteVariable(VP_Z_PARK_POS_Dis, Z_PARK_POS_buf_ch, 16, true); + + const uint16_t Length_buf_ch[] = { 0xBDB2, 0xA4B3, 0x2000 }; + dgusdisplay.WriteVariable(VP_Length_Dis, Length_buf_ch, 8, true); + + const uint16_t Speed_buf_ch[] = { 0xD9CB, 0xC8B6, 0x2000 }; + dgusdisplay.WriteVariable(VP_Speed_Dis, Speed_buf_ch, 8, true); + + const uint16_t InOut_buf_ch[] = { 0xF8BD, 0xF6B3, 0x2000 }; + dgusdisplay.WriteVariable(VP_InOut_Dis, InOut_buf_ch, 8, true); + + const uint16_t PrintTimet_buf_en[] = { 0xF2B4, 0xA1D3, 0xB1CA, 0xE4BC, 0x2000 }; + dgusdisplay.WriteVariable(VP_PrintTime_Dis, PrintTimet_buf_en, 16, true); + + const uint16_t E0_Temp_buf_ch[] = { 0x3045, 0xC2CE, 0xC8B6, 0x2000 }; + dgusdisplay.WriteVariable(VP_E0_Temp_Dis, E0_Temp_buf_ch, 16, true); + + const uint16_t E1_Temp_buf_ch[] = { 0x3145, 0xC2CE, 0xC8B6, 0x2000 }; + dgusdisplay.WriteVariable(VP_E1_Temp_Dis, E1_Temp_buf_ch, 16, true); + + const uint16_t HB_Temp_buf_ch[] = { 0xC8C8, 0xB2B4, 0xC2CE, 0xC8B6, 0x2000 }; + dgusdisplay.WriteVariable(VP_HB_Temp_Dis, HB_Temp_buf_ch, 16, true); + + const uint16_t Feedrate_buf_ch[] = { 0xB7BC, 0xF6B3, 0xD9CB, 0xC8B6, 0x2000 }; + dgusdisplay.WriteVariable(VP_Feedrate_Dis, Feedrate_buf_ch, 16, true); + + const uint16_t PrintAcc_buf_ch[] = { 0xF2B4, 0xA1D3, 0xD9CB, 0xC8B6, 0x2000 }; + dgusdisplay.WriteVariable(VP_PrintAcc_Dis, PrintAcc_buf_ch, 16, true); + + const uint16_t FAN_Speed_buf_ch[] = { 0xE7B7, 0xC8C9, 0xD9CB, 0xC8B6, 0x2000 }; + dgusdisplay.WriteVariable(VP_Fan_Speed_Dis, FAN_Speed_buf_ch, 16, true); + + const uint16_t Printing_buf_ch[] = { 0xF2B4, 0xA1D3, 0xD0D6, 0x2000 }; + dgusdisplay.WriteVariable(VP_Printing_Dis, Printing_buf_ch, 16, true); + + const uint16_t Info_EEPROM_1_buf_ch[] = { 0xC7CA, 0xF1B7, 0xA3B1, 0xE6B4, 0xE8C9, 0xC3D6, 0xBFA3, 0x2000 }; + dgusdisplay.WriteVariable(VP_Info_EEPROM_1_Dis, Info_EEPROM_1_buf_ch, 32, true); + + const uint16_t Info_EEPROM_2_buf_ch[] = { 0xC7CA, 0xF1B7, 0xD6BB, 0xB4B8, 0xF6B3, 0xA7B3, 0xE8C9, 0xC3D6, 0xBFA3, 0x2000 }; + dgusdisplay.WriteVariable(VP_Info_EEPROM_2_Dis, Info_EEPROM_2_buf_ch, 32, true); + + const uint16_t TMC_X_Step_buf_ch[] = { 0x2058, 0xE9C1, 0xF4C3, 0xC8B6, 0x2000 }; + dgusdisplay.WriteVariable(VP_TMC_X_Step_Dis, TMC_X_Step_buf_ch, 16, true); + + const uint16_t TMC_Y_Step_buf_ch[] = { 0x2059, 0xE9C1, 0xF4C3, 0xC8B6, 0x2000 }; + dgusdisplay.WriteVariable(VP_TMC_Y_Step_Dis, TMC_Y_Step_buf_ch, 16, true); + + const uint16_t TMC_Z_Step_buf_ch[] = { 0x205A, 0xE9C1, 0xF4C3, 0xC8B6, 0x2000 }; + dgusdisplay.WriteVariable(VP_TMC_Z_Step_Dis, TMC_Z_Step_buf_ch, 16, true); + + const uint16_t Info_PrinfFinsh_1_buf_ch[] = { 0xF2B4, 0xA1D3, 0xEACD, 0xC9B3, 0x2000 }; + dgusdisplay.WriteVariable(VP_Info_PrinfFinsh_1_Dis, Info_PrinfFinsh_1_buf_ch, 32, true); + + const uint16_t TMC_X_Current_buf_ch[] = { 0x2058, 0xE1D6, 0xE7B5, 0xF7C1, 0x2000 }; + dgusdisplay.WriteVariable(VP_TMC_X_Current_Dis, TMC_X_Current_buf_ch, 16, true); + + const uint16_t TMC_Y_Current_buf_ch[] = { 0x2059, 0xE1D6, 0xE7B5, 0xF7C1, 0x2000 }; + dgusdisplay.WriteVariable(VP_TMC_Y_Current_Dis, TMC_Y_Current_buf_ch, 16, true); + + const uint16_t TMC_Z_Current_buf_ch[] = { 0x205A, 0xE1D6, 0xE7B5, 0xF7C1, 0x2000 }; + dgusdisplay.WriteVariable(VP_TMC_Z_Current_Dis, TMC_Z_Current_buf_ch, 16, true); + + const uint16_t TMC_E0_Current_buf_ch[] = { 0x3045, 0xE1D6, 0xE7B5, 0xF7C1, 0x2000 }; + dgusdisplay.WriteVariable(VP_TMC_E0_Current_Dis, TMC_E0_Current_buf_ch, 16, true); + + const uint16_t TMC_X1_Current_buf_ch[] = { 0x3158, 0xE1D6, 0xE7B5, 0xF7C1, 0x2000 }; + dgusdisplay.WriteVariable(VP_TMC_X1_Current_Dis, TMC_X1_Current_buf_ch, 16, true); + + const uint16_t TMC_Y1_Current_buf_ch[] = { 0x3159, 0xE1D6, 0xE7B5, 0xF7C1, 0x2000 }; + dgusdisplay.WriteVariable(VP_TMC_Y1_Current_Dis, TMC_Y1_Current_buf_ch, 16, true); + + const uint16_t TMC_Z1_Current_buf_ch[] = { 0x315A, 0xE1D6, 0xE7B5, 0xF7C1, 0x2000 }; + dgusdisplay.WriteVariable(VP_TMC_Z1_Current_Dis, TMC_Z1_Current_buf_ch, 16, true); + + const uint16_t TMC_E1_Current_buf_ch[] = { 0x3145, 0xE1D6, 0xE7B5, 0xF7C1, 0x2000 }; + dgusdisplay.WriteVariable(VP_TMC_E1_Current_Dis, TMC_E1_Current_buf_ch, 16, true); + + const uint16_t Min_Ex_Temp_buf_ch[] = { 0xEED7, 0xA1D0, 0xB7BC, 0xF6B3, 0xC2CE, 0xC8B6, 0x2000 }; + dgusdisplay.WriteVariable(VP_Min_Ex_Temp_Dis, Min_Ex_Temp_buf_ch, 32, true); + + const uint16_t AutoLEVEL_INFO1_buf_ch[] = { 0xEBC7, 0xB4B0, 0xC2CF, 0xB4B0, 0xA5C5, 0x2000 }; + dgusdisplay.WriteVariable(VP_AutoLEVEL_INFO1, AutoLEVEL_INFO1_buf_ch, 32, true); + + const uint16_t EX_TEMP_INFO2_buf_ch[] = { 0xEBC7, 0xD4C9, 0xC8B5, 0x2000 }; + dgusdisplay.WriteVariable(VP_EX_TEMP_INFO2_Dis, EX_TEMP_INFO2_buf_ch, 32, true); + + const uint16_t EX_TEMP_INFO3_buf_ch[] = { 0xA1C8, 0xFBCF, 0xD3BC, 0xC8C8, 0x2000 }; + dgusdisplay.WriteVariable(VP_EX_TEMP_INFO3_Dis, EX_TEMP_INFO3_buf_ch, 32, true); + + const uint16_t PrintConfrim_Info_buf_ch[] = { 0xC7CA, 0xF1B7, 0xAABF, 0xBCCA, 0xF2B4, 0xA1D3, 0x2000 }; + dgusdisplay.WriteVariable(VP_PrintConfrim_Info_Dis, PrintConfrim_Info_buf_ch, 32, true); + + const uint16_t StopPrintConfrim_Info_buf_ch[] = { 0xC7CA, 0xF1B7, 0xA3CD, 0xB9D6, 0xF2B4, 0xA1D3, 0x2000 }; + dgusdisplay.WriteVariable(VP_StopPrintConfrim_Info_Dis, StopPrintConfrim_Info_buf_ch, 32, true); + + const uint16_t Printting_buf_ch[] = { 0xF2B4, 0xA1D3, 0xD0D6, 0x2000 }; + dgusdisplay.WriteVariable(VP_Printting_Dis, Printting_buf_ch, 32, true); + + const uint16_t LCD_BLK_buf_ch[] = { 0xB3B1, 0xE2B9, 0xE8C9, 0xC3D6, 0x2000 }; + dgusdisplay.WriteVariable(VP_LCD_BLK_Dis, LCD_BLK_buf_ch, 32, true); + } +} + +#endif // DGUS_LCD_UI_MKS diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h new file mode 100644 index 000000000000..8d5d9066f4c8 --- /dev/null +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h @@ -0,0 +1,315 @@ +/** + * 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 + +#include "../DGUSDisplay.h" +#include "../DGUSVPVariable.h" +#include "../DGUSDisplayDef.h" + +#include "../../../../inc/MarlinConfig.h" + +enum DGUSLCD_Screens : uint8_t; + +class DGUSScreenHandler { +public: + DGUSScreenHandler() = default; + + static bool loop(); + + // Send all 4 strings that are displayed on the infoscreen, confirmation screen and kill screen + // The bools specifying whether the strings are in RAM or FLASH. + static void sendinfoscreen(const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); + + static void HandleUserConfirmationPopUp(uint16_t ConfirmVP, const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); + + #if 0 + static void sendinfoscreen_ch_mks(const uint16_t *line1, const uint16_t *line2, const uint16_t *line3, const uint16_t *line4); + static void sendinfoscreen_en_mks(const char *line1, const char *line2, const char *line3, const char *line4) ; + static void sendinfoscreen_mks(const void *line1, const void *line2, const void *line3, const void *line4, uint16_t language); + #endif + + // "M117" Message -- msg is a RAM ptr. + static void setstatusmessage(const char *msg); + // The same for messages from Flash + static void setstatusmessagePGM(PGM_P const msg); + // Callback for VP "Display wants to change screen on idle printer" + static void ScreenChangeHookIfIdle(DGUS_VP_Variable &var, void *val_ptr); + // Callback for VP "Screen has been changed" + static void ScreenChangeHook(DGUS_VP_Variable &var, void *val_ptr); + + static void ScreenBackChange(DGUS_VP_Variable &var, void *val_ptr); + + // Callback for VP "All Heaters Off" + static void HandleAllHeatersOff(DGUS_VP_Variable &var, void *val_ptr); + // Hook for "Change this temperature" + static void HandleTemperatureChanged(DGUS_VP_Variable &var, void *val_ptr); + // Hook for "Change Flowrate" + static void HandleFlowRateChanged(DGUS_VP_Variable &var, void *val_ptr); + #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) + // Hook for manual move option + static void HandleManualMoveOption(DGUS_VP_Variable &var, void *val_ptr); + #endif + + static void EEPROM_CTRL(DGUS_VP_Variable &var, void *val_ptr); + static void LanguageChange_MKS(DGUS_VP_Variable &var, void *val_ptr); + static void GetOffsetValue(DGUS_VP_Variable &var, void *val_ptr); + static void Level_Ctrl_MKS(DGUS_VP_Variable &var, void *val_ptr); + static void MeshLevel(DGUS_VP_Variable &var, void *val_ptr); + static void MeshLevelDistanceConfig(DGUS_VP_Variable &var, void *val_ptr); + static void ManualAssistLeveling(DGUS_VP_Variable &var, void *val_ptr); + static void ZoffsetConfirm(DGUS_VP_Variable &var, void *val_ptr); + static void Z_offset_select(DGUS_VP_Variable &var, void *val_ptr); + static void GetManualMovestep(DGUS_VP_Variable &var, void *val_ptr); + static void GetZoffsetDistance(DGUS_VP_Variable &var, void *val_ptr); + static void GetMinExtrudeTemp(DGUS_VP_Variable &var, void *val_ptr); + static void GetParkPos_MKS(DGUS_VP_Variable &var, void *val_ptr); + #if ENABLED(PREVENT_COLD_EXTRUSION) + static void HandleGetExMinTemp_MKS(DGUS_VP_Variable &var, void *val_ptr); + #endif + static void DGUS_LanguageDisplay(uint8_t var); + static void TMC_ChangeConfig(DGUS_VP_Variable &var, void *val_ptr); + static void GetTurnOffCtrl(DGUS_VP_Variable &var, void *val_ptr); + static void LanguagePInit(void); + static void DGUS_Runout_Idle(void); + static void DGUS_RunoutInit(void); + static void DGUS_ExtrudeLoadInit(void); + static void LCD_BLK_Adjust(DGUS_VP_Variable &var, void *val_ptr); + static void SD_FileBack(DGUS_VP_Variable &var, void *val_ptr); + + // Hook for manual move. + static void HandleManualMove(DGUS_VP_Variable &var, void *val_ptr); + // Hook for manual extrude. + static void HandleManualExtrude(DGUS_VP_Variable &var, void *val_ptr); + // Hook for motor lock and unlook + static void HandleMotorLockUnlock(DGUS_VP_Variable &var, void *val_ptr); + #if ENABLED(POWER_LOSS_RECOVERY) + // Hook for power loss recovery. + static void HandlePowerLossRecovery(DGUS_VP_Variable &var, void *val_ptr); + #endif + // Hook for settings + static void HandleSettings(DGUS_VP_Variable &var, void *val_ptr); + static void HandleStepPerMMChanged(DGUS_VP_Variable &var, void *val_ptr); + static void HandleStepPerMMExtruderChanged(DGUS_VP_Variable &var, void *val_ptr); + + static void HandleStepPerMMChanged_MKS(DGUS_VP_Variable &var, void *val_ptr); + static void HandleStepPerMMExtruderChanged_MKS(DGUS_VP_Variable &var, void *val_ptr); + static void HandleMaxSpeedChange_MKS(DGUS_VP_Variable &var, void *val_ptr); + static void HandleExtruderMaxSpeedChange_MKS(DGUS_VP_Variable &var, void *val_ptr); + static void HandleAccChange_MKS(DGUS_VP_Variable &var, void *val_ptr); + static void HandleMaxAccChange_MKS(DGUS_VP_Variable &var, void *val_ptr); + static void HandleExtruderAccChange_MKS(DGUS_VP_Variable &var, void *val_ptr); + static void HandleChangeLevelPoint_MKS(DGUS_VP_Variable &var, void *val_ptr); + static void HandleTravelAccChange_MKS(DGUS_VP_Variable &var, void *val_ptr); + static void HandleFeedRateMinChange_MKS(DGUS_VP_Variable &var, void *val_ptr); + static void HandleMin_T_F_MKS(DGUS_VP_Variable &var, void *val_ptr); + + #if HAS_PID_HEATING + // Hook for "Change this temperature PID para" + static void HandleTemperaturePIDChanged(DGUS_VP_Variable &var, void *val_ptr); + // Hook for PID autotune + static void HandlePIDAutotune(DGUS_VP_Variable &var, void *val_ptr); + #endif + #if HAS_BED_PROBE + // Hook for "Change probe offset z" + static void HandleProbeOffsetZChanged(DGUS_VP_Variable &var, void *val_ptr); + #endif + #if ENABLED(BABYSTEPPING) + // Hook for live z adjust action + static void HandleLiveAdjustZ(DGUS_VP_Variable &var, void *val_ptr); + #endif + #if HAS_FAN + // Hook for fan control + static void HandleFanControl(DGUS_VP_Variable &var, void *val_ptr); + #endif + // Hook for heater control + static void HandleHeaterControl(DGUS_VP_Variable &var, void *val_ptr); + #if ENABLED(DGUS_PREHEAT_UI) + // Hook for preheat + static void HandlePreheat(DGUS_VP_Variable &var, void *val_ptr); + #endif + #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) + // Hook for filament load and unload filament option + static void HandleFilamentOption(DGUS_VP_Variable &var, void *val_ptr); + // Hook for filament load and unload + static void HandleFilamentLoadUnload(DGUS_VP_Variable &var); + + static void MKS_FilamentLoadUnload(DGUS_VP_Variable &var, void *val_ptr, const int filamentDir); + static void MKS_FilamentLoad(DGUS_VP_Variable &var, void *val_ptr); + static void MKS_FilamentUnLoad(DGUS_VP_Variable &var, void *val_ptr); + static void MKS_LOAD_UNLOAD_IDLE(); + static void MKS_LOAD_Cancle(DGUS_VP_Variable &var, void *val_ptr); + static void GetManualFilament(DGUS_VP_Variable &var, void *val_ptr); + static void GetManualFilamentSpeed(DGUS_VP_Variable &var, void *val_ptr); + #endif + + #if ENABLED(SDSUPPORT) + // 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. + static void DGUSLCD_SD_ScrollFilelist(DGUS_VP_Variable &var, void *val_ptr); + // File touched. + static void DGUSLCD_SD_FileSelected(DGUS_VP_Variable &var, void *val_ptr); + // start print after confirmation received. + static void DGUSLCD_SD_StartPrint(DGUS_VP_Variable &var, void *val_ptr); + // User hit the pause, resume or abort button. + static void DGUSLCD_SD_ResumePauseAbort(DGUS_VP_Variable &var, void *val_ptr); + // User confirmed the abort action + static void DGUSLCD_SD_ReallyAbort(DGUS_VP_Variable &var, void *val_ptr); + // User hit the tune button + static void DGUSLCD_SD_PrintTune(DGUS_VP_Variable &var, void *val_ptr); + // Send a single filename to the display. + static void DGUSLCD_SD_SendFilename(DGUS_VP_Variable &var); + // Marlin informed us that a new SD has been inserted. + static void SDCardInserted(); + // Marlin informed us that the SD Card has been removed(). + static void SDCardRemoved(); + // Marlin informed us about a bad SD Card. + static void SDCardError(); + // Marlin informed us about SD print completion. + static void SDPrintingFinished(); + #else + static void PrintReturn(DGUS_VP_Variable &var, void *val_ptr); + #endif + + // OK Button on the Confirm screen. + static void ScreenConfirmedOK(DGUS_VP_Variable &var, void *val_ptr); + + // Update data after going to a new screen (by display or by GotoScreen) + // remember: store the last-displayed screen, so it can be returned to. + // (e.g for popup messages) + static void UpdateNewScreen(DGUSLCD_Screens newscreen, bool popup=false); + + // Recall the remembered screen. + static void PopToOldScreen(); + + // Make the display show the screen and update all VPs in it. + static void GotoScreen(DGUSLCD_Screens screen, bool ispopup = false); + + static void UpdateScreenVPData(); + + // Helpers to convert and transfer data to the display. + static void DGUSLCD_SendWordValueToDisplay(DGUS_VP_Variable &var); + static void DGUSLCD_SendStringToDisplay(DGUS_VP_Variable &var); + static void DGUSLCD_SendStringToDisplayPGM(DGUS_VP_Variable &var); + static void DGUSLCD_SendTemperaturePID(DGUS_VP_Variable &var); + static void DGUSLCD_SendPercentageToDisplay(DGUS_VP_Variable &var); + static void DGUSLCD_SendPrintProgressToDisplay(DGUS_VP_Variable &var); + static void DGUSLCD_SendPrintTimeToDisplay(DGUS_VP_Variable &var); + + static void DGUSLCD_SendPrintTimeToDisplay_MKS(DGUS_VP_Variable &var); + static void DGUSLCD_SendBabyStepToDisplay_MKS(DGUS_VP_Variable &var); + static void DGUSLCD_SendFanToDisplay(DGUS_VP_Variable &var); + static void DGUSLCD_SendGbkToDisplay(DGUS_VP_Variable &var); + static void DGUSLCD_SendStringToDisplay_Language_MKS(DGUS_VP_Variable &var); + static void DGUSLCD_SendTMCStepValue(DGUS_VP_Variable &var); + + #if ENABLED(PRINTCOUNTER) + static void DGUSLCD_SendPrintAccTimeToDisplay(DGUS_VP_Variable &var); + static void DGUSLCD_SendPrintsTotalToDisplay(DGUS_VP_Variable &var); + #endif + #if HAS_FAN + static void DGUSLCD_SendFanStatusToDisplay(DGUS_VP_Variable &var); + #endif + static void DGUSLCD_SendHeaterStatusToDisplay(DGUS_VP_Variable &var); + #if ENABLED(DGUS_UI_WAITING) + static void DGUSLCD_SendWaitingStatusToDisplay(DGUS_VP_Variable &var); + #endif + + // Send a value from 0..100 to a variable with a range from 0..255 + static void DGUSLCD_PercentageToUint8(DGUS_VP_Variable &var, void *val_ptr); + + static void DGUSLCD_SetUint8(DGUS_VP_Variable &var, void *val_ptr); + + template + static void DGUSLCD_SetValueDirectly(DGUS_VP_Variable &var, void *val_ptr) { + if (!var.memadr) return; + union { unsigned char tmp[sizeof(T)]; T t; } x; + unsigned char *ptr = (unsigned char*)val_ptr; + LOOP_L_N(i, sizeof(T)) x.tmp[i] = ptr[sizeof(T) - i - 1]; + *(T*)var.memadr = x.t; + } + + // Send a float value to the display. + // Display will get a 4-byte integer scaled to the number of digits: + // Tell the display the number of digits and it cheats by displaying a dot between... + template + static void DGUSLCD_SendFloatAsLongValueToDisplay(DGUS_VP_Variable &var) { + if (var.memadr) { + float f = *(float *)var.memadr; + f *= cpow(10, decimals); + dgusdisplay.WriteVariable(var.VP, (long)f); + } + } + + // Send a float value to the display. + // Display will get a 2-byte integer scaled to the number of digits: + // Tell the display the number of digits and it cheats by displaying a dot between... + template + static void DGUSLCD_SendFloatAsIntValueToDisplay(DGUS_VP_Variable &var) { + if (var.memadr) { + float f = *(float *)var.memadr; + DEBUG_ECHOLNPAIR_F(" >> ", f, 6); + f *= cpow(10, decimals); + dgusdisplay.WriteVariable(var.VP, (int16_t)f); + } + } + + // Force an update of all VP on the current screen. + static inline void ForceCompleteUpdate() { update_ptr = 0; ScreenComplete = false; } + // Has all VPs sent to the screen + static inline bool IsScreenComplete() { return ScreenComplete; } + + static inline DGUSLCD_Screens getCurrentScreen() { return current_screen; } + + static inline void SetupConfirmAction( void (*f)()) { confirm_action_cb = f; } + +private: + static DGUSLCD_Screens current_screen; //< currently on screen + static constexpr uint8_t NUM_PAST_SCREENS = 4; + static DGUSLCD_Screens past_screens[NUM_PAST_SCREENS]; //< LIFO with past screens for the "back" button. + + static uint8_t update_ptr; //< Last sent entry in the VPList for the actual screen. + static uint16_t skipVP; //< When updating the screen data, skip this one, because the user is interacting with it. + static bool ScreenComplete; //< All VPs sent to screen? + + static uint16_t ConfirmVP; //< context for confirm screen (VP that will be emulated-sent on "OK"). + + #if ENABLED(SDSUPPORT) + static int16_t top_file; //< file on top of file chooser + static int16_t file_to_print; //< touched file to be confirmed + #endif + + static void (*confirm_action_cb)(); +}; + +#define MKS_Language_Choose 0x00 +#define MKS_Language_NoChoose 0x01 + +#define MKS_SimpleChinese 0 +#define MKS_English 1 +extern uint8_t mks_language_index; +extern bool DGUSAutoTurnOff; + +#if ENABLED(POWER_LOSS_RECOVERY) + #define PLR_SCREEN_RECOVER MKSLCD_SCREEN_PRINT + #define PLR_SCREEN_CANCEL MKSLCD_SCREEN_HOME +#endif diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp new file mode 100644 index 000000000000..2f5e2787d615 --- /dev/null +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp @@ -0,0 +1,279 @@ +/** + * 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 . + * + */ + +/** + * lcd/extui/dgus/origin/DGUSDisplayDef.cpp + */ + +#include "../../../../inc/MarlinConfigPre.h" + +#if ENABLED(DGUS_LCD_UI_ORIGIN) + +#include "DGUSDisplayDef.h" +#include "../DGUSDisplay.h" +#include "../DGUSScreenHandler.h" + +#include "../../../../module/temperature.h" +#include "../../../../module/motion.h" +#include "../../../../module/planner.h" + +#include "../../../marlinui.h" +#include "../../ui_api.h" + +#if ENABLED(DGUS_UI_MOVE_DIS_OPTION) + uint16_t distanceToMove = 10; +#endif +using namespace ExtUI; + +const uint16_t VPList_Boot[] PROGMEM = { + VP_MARLIN_VERSION, + 0x0000 +}; + +const uint16_t VPList_Main[] PROGMEM = { + // VP_M117, for completeness, but it cannot be auto-uploaded. + 0x0000 +}; + +const uint16_t VPList_Temp[] PROGMEM = { + #if HAS_HOTEND + VP_T_E0_Is, VP_T_E0_Set, + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif + #endif + #if HAS_HEATED_BED + VP_T_Bed_Is, VP_T_Bed_Set, + #endif + 0x0000 +}; + +const uint16_t VPList_Status[] PROGMEM = { + // VP_M117, for completeness, but it cannot be auto-uploaded + #if HAS_HOTEND + VP_T_E0_Is, VP_T_E0_Set, + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif + #endif + #if HAS_HEATED_BED + VP_T_Bed_Is, VP_T_Bed_Set, + #endif + #if HAS_FAN + VP_Fan0_Percentage, + #endif + VP_XPos, VP_YPos, VP_ZPos, + VP_Fan0_Percentage, + VP_Feedrate_Percentage, + VP_PrintProgress_Percentage, + 0x0000 +}; + +const uint16_t VPList_Status2[] PROGMEM = { + // VP_M117, for completeness, but it cannot be auto-uploaded + #if HAS_HOTEND + VP_Flowrate_E0, + #if HOTENDS >= 2 + VP_Flowrate_E1, + #endif + #endif + VP_PrintProgress_Percentage, + VP_PrintTime, + 0x0000 +}; +const uint16_t VPList_ManualMove[] PROGMEM = { VP_XPos, VP_YPos, VP_ZPos, 0x0000 }; +const uint16_t VPList_ManualExtrude[] PROGMEM = { VP_EPos, 0x0000 }; +const uint16_t VPList_FanAndFeedrate[] PROGMEM = { VP_Feedrate_Percentage, VP_Fan0_Percentage, 0x0000 }; +const uint16_t VPList_SD_FlowRates[] PROGMEM = { VP_Flowrate_E0, VP_Flowrate_E1, 0x0000 }; +const uint16_t VPList_SDFileList[] PROGMEM = { VP_SD_FileName0, VP_SD_FileName1, VP_SD_FileName2, VP_SD_FileName3, VP_SD_FileName4, 0x0000 }; +const uint16_t VPList_SD_PrintManipulation[] PROGMEM = { VP_PrintProgress_Percentage, VP_PrintTime, 0x0000 }; + +const struct VPMapping VPMap[] PROGMEM = { + { DGUSLCD_SCREEN_BOOT, VPList_Boot }, + { DGUSLCD_SCREEN_MAIN, VPList_Main }, + { DGUSLCD_SCREEN_TEMPERATURE, VPList_Temp }, + { DGUSLCD_SCREEN_STATUS, VPList_Status }, + { DGUSLCD_SCREEN_STATUS2, VPList_Status2 }, + { DGUSLCD_SCREEN_MANUALMOVE, VPList_ManualMove }, + { DGUSLCD_SCREEN_MANUALEXTRUDE, VPList_ManualExtrude }, + { DGUSLCD_SCREEN_FANANDFEEDRATE, VPList_FanAndFeedrate }, + { DGUSLCD_SCREEN_FLOWRATES, VPList_SD_FlowRates }, + { DGUSLCD_SCREEN_SDPRINTMANIPULATION, VPList_SD_PrintManipulation }, + { DGUSLCD_SCREEN_SDFILELIST, VPList_SDFileList }, + { 0 , nullptr } // List is terminated with an nullptr as table entry. +}; + +const char MarlinVersion[] PROGMEM = SHORT_BUILD_VERSION; + +const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { + // Helper to detect touch events + VPHELPER(VP_SCREENCHANGE, nullptr, ScreenHandler.ScreenChangeHook, nullptr), + VPHELPER(VP_SCREENCHANGE_ASK, nullptr, ScreenHandler.ScreenChangeHookIfIdle, nullptr), + #if ENABLED(SDSUPPORT) + VPHELPER(VP_SCREENCHANGE_WHENSD, nullptr, ScreenHandler.ScreenChangeHookIfSD, nullptr), + #endif + VPHELPER(VP_CONFIRMED, nullptr, ScreenHandler.ScreenConfirmedOK, nullptr), + + VPHELPER(VP_TEMP_ALL_OFF, nullptr, ScreenHandler.HandleAllHeatersOff, nullptr), + + #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) + VPHELPER(VP_MOVE_OPTION, &distanceToMove, ScreenHandler.HandleManualMoveOption, nullptr), + #endif + #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) + VPHELPER(VP_MOVE_X, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Y, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Z, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_HOME_ALL, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), + #else + VPHELPER(VP_MOVE_X, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Y, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Z, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_HOME_ALL, nullptr, ScreenHandler.HandleManualMove, nullptr), + #endif + + VPHELPER(VP_MOTOR_LOCK_UNLOK, nullptr, ScreenHandler.HandleMotorLockUnlock, nullptr), + #if ENABLED(POWER_LOSS_RECOVERY) + VPHELPER(VP_POWER_LOSS_RECOVERY, nullptr, ScreenHandler.HandlePowerLossRecovery, nullptr), + #endif + VPHELPER(VP_SETTINGS, nullptr, ScreenHandler.HandleSettings, nullptr), + + { .VP = VP_MARLIN_VERSION, .memadr = (void*)MarlinVersion, .size = VP_MARLIN_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + // M117 LCD String (We don't need the string in memory but "just" push it to the display on demand, hence the nullptr + { .VP = VP_M117, .memadr = nullptr, .size = VP_M117_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplay }, + + // Temperature Data + #if HAS_HOTEND + VPHELPER(VP_T_E0_Is, &thermalManager.temp_hotend[0].celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), + VPHELPER(VP_T_E0_Set, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleTemperatureChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Flowrate_E0, nullptr, ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_EPos, &destination.e, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_MOVE_E0, nullptr, ScreenHandler.HandleManualExtrude, nullptr), + VPHELPER(VP_E0_CONTROL, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_E0_STATUS, &thermalManager.temp_hotend[0].target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + #if ENABLED(DGUS_PREHEAT_UI) + VPHELPER(VP_E0_BED_PREHEAT, nullptr, ScreenHandler.HandlePreheat, nullptr), + #endif + #if ENABLED(PIDTEMP) + VPHELPER(VP_E0_PID_P, &thermalManager.temp_hotend[0].pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), + VPHELPER(VP_E0_PID_I, &thermalManager.temp_hotend[0].pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), + VPHELPER(VP_E0_PID_D, &thermalManager.temp_hotend[0].pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), + VPHELPER(VP_PID_AUTOTUNE_E0, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), + #endif + #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) + VPHELPER(VP_E0_FILAMENT_LOAD_UNLOAD, nullptr, ScreenHandler.HandleFilamentOption, ScreenHandler.HandleFilamentLoadUnload), + #endif + #endif + #if HOTENDS >= 2 + VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), + VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Flowrate_E1, nullptr, ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_MOVE_E1, nullptr, ScreenHandler.HandleManualExtrude, nullptr), + VPHELPER(VP_E1_CONTROL, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_E1_STATUS, &thermalManager.temp_hotend[1].target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + #if ENABLED(PIDTEMP) + VPHELPER(VP_PID_AUTOTUNE_E1, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), + #endif + #endif + #if HAS_HEATED_BED + VPHELPER(VP_T_Bed_Is, &thermalManager.temp_bed.celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), + VPHELPER(VP_T_Bed_Set, &thermalManager.temp_bed.target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_BED_CONTROL, &thermalManager.temp_bed.target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_BED_STATUS, &thermalManager.temp_bed.target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + #if ENABLED(PIDTEMPBED) + VPHELPER(VP_BED_PID_P, &thermalManager.temp_bed.pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), + VPHELPER(VP_BED_PID_I, &thermalManager.temp_bed.pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), + VPHELPER(VP_BED_PID_D, &thermalManager.temp_bed.pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), + #endif + #endif + + // Fan Data + #if HAS_FAN + #define FAN_VPHELPER(N) \ + VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], ScreenHandler.DGUSLCD_PercentageToUint8, ScreenHandler.DGUSLCD_SendPercentageToDisplay), \ + VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], ScreenHandler.HandleFanControl, nullptr), \ + VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, ScreenHandler.DGUSLCD_SendFanStatusToDisplay), + REPEAT(FAN_COUNT, FAN_VPHELPER) + #endif + + // Feedrate + VPHELPER(VP_Feedrate_Percentage, &feedrate_percentage, ScreenHandler.DGUSLCD_SetValueDirectly, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + + // Position Data + VPHELPER(VP_XPos, ¤t_position.x, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_YPos, ¤t_position.y, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_ZPos, ¤t_position.z, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), + + // Print Progress + VPHELPER(VP_PrintProgress_Percentage, nullptr, nullptr, ScreenHandler.DGUSLCD_SendPrintProgressToDisplay), + + // Print Time + VPHELPER_STR(VP_PrintTime, nullptr, VP_PrintTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintTimeToDisplay), + #if ENABLED(PRINTCOUNTER) + VPHELPER_STR(VP_PrintAccTime, nullptr, VP_PrintAccTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintAccTimeToDisplay), + VPHELPER_STR(VP_PrintsTotal, nullptr, VP_PrintsTotal_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintsTotalToDisplay), + #endif + + VPHELPER(VP_X_STEP_PER_MM, &planner.settings.axis_steps_per_mm[X_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + VPHELPER(VP_Y_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Y_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + VPHELPER(VP_Z_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Z_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + #if HAS_HOTEND + VPHELPER(VP_E0_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(0)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + #if HOTENDS >= 2 + VPHELPER(VP_E1_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(1)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + #endif + #endif + + // SDCard File listing. + #if ENABLED(SDSUPPORT) + VPHELPER(VP_SD_ScrollEvent, nullptr, ScreenHandler.DGUSLCD_SD_ScrollFilelist, nullptr), + VPHELPER(VP_SD_FileSelected, nullptr, ScreenHandler.DGUSLCD_SD_FileSelected, nullptr), + VPHELPER(VP_SD_FileSelectConfirm, nullptr, ScreenHandler.DGUSLCD_SD_StartPrint, nullptr), + VPHELPER_STR(VP_SD_FileName0, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), + VPHELPER_STR(VP_SD_FileName1, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), + VPHELPER_STR(VP_SD_FileName2, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), + VPHELPER_STR(VP_SD_FileName3, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), + VPHELPER_STR(VP_SD_FileName4, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), + VPHELPER(VP_SD_ResumePauseAbort, nullptr, ScreenHandler.DGUSLCD_SD_ResumePauseAbort, nullptr), + VPHELPER(VP_SD_AbortPrintConfirmed, nullptr, ScreenHandler.DGUSLCD_SD_ReallyAbort, nullptr), + VPHELPER(VP_SD_Print_Setting, nullptr, ScreenHandler.DGUSLCD_SD_PrintTune, nullptr), + #if HAS_BED_PROBE + VPHELPER(VP_SD_Print_ProbeOffsetZ, &probe.offset.z, ScreenHandler.HandleProbeOffsetZChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<2>), + #if ENABLED(BABYSTEPPING) + VPHELPER(VP_SD_Print_LiveAdjustZ, nullptr, ScreenHandler.HandleLiveAdjustZ, nullptr), + #endif + #endif + #endif + + #if ENABLED(DGUS_UI_WAITING) + VPHELPER(VP_WAITING_STATUS, nullptr, nullptr, ScreenHandler.DGUSLCD_SendWaitingStatusToDisplay), + #endif + + // Messages for the User, shared by the popup and the kill screen. They can't be autouploaded as we do not buffer content. + { .VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + + VPHELPER(0, 0, 0, 0) // must be last entry. +}; + +#endif // DGUS_LCD_UI_ORIGIN diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.h b/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.h new file mode 100644 index 000000000000..f5fb986bde51 --- /dev/null +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.h @@ -0,0 +1,282 @@ +/** + * 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 + +#include "../DGUSDisplayDef.h" + +enum DGUSLCD_Screens : uint8_t { + DGUSLCD_SCREEN_BOOT = 0, + DGUSLCD_SCREEN_MAIN = 10, + DGUSLCD_SCREEN_TEMPERATURE = 20, + DGUSLCD_SCREEN_STATUS = 30, + DGUSLCD_SCREEN_STATUS2 = 32, + DGUSLCD_SCREEN_MANUALMOVE = 40, + DGUSLCD_SCREEN_MANUALEXTRUDE = 42, + DGUSLCD_SCREEN_FANANDFEEDRATE = 44, + DGUSLCD_SCREEN_FLOWRATES = 46, + DGUSLCD_SCREEN_SDFILELIST = 50, + DGUSLCD_SCREEN_SDPRINTMANIPULATION = 52, + DGUSLCD_SCREEN_POWER_LOSS = 100, + DGUSLCD_SCREEN_PREHEAT = 120, + DGUSLCD_SCREEN_UTILITY = 110, + DGUSLCD_SCREEN_FILAMENT_HEATING = 146, + DGUSLCD_SCREEN_FILAMENT_LOADING = 148, + DGUSLCD_SCREEN_FILAMENT_UNLOADING = 158, + DGUSLCD_SCREEN_SDPRINTTUNE = 170, + DGUSLCD_SCREEN_CONFIRM = 240, + DGUSLCD_SCREEN_KILL = 250, ///< Kill Screen. Must always be 250 (to be able to display "Error wrong LCD Version") + DGUSLCD_SCREEN_WAITING = 251, + DGUSLCD_SCREEN_POPUP = 252, ///< special target, popup screen will also return this code to say "return to previous screen" + DGUSLCD_SCREEN_UNUSED = 255 +}; + +// Display Memory layout used (T5UID) +// Except system variables this is arbitrary, just to organize stuff.... + +// 0x0000 .. 0x0FFF -- System variables and reserved by the display +// 0x1000 .. 0x1FFF -- Variables to never change location, regardless of UI Version +// 0x2000 .. 0x2FFF -- Controls (VPs that will trigger some action) +// 0x3000 .. 0x4FFF -- Marlin Data to be displayed +// 0x5000 .. -- SPs (if we want to modify display elements, e.g change color or like) -- currently unused + +// As there is plenty of space (at least most displays have >8k RAM), we do not pack them too tight, +// so that we can keep variables nicely together in the address space. + +// UI Version always on 0x1000...0x1002 so that the firmware can check this and bail out. +constexpr uint16_t VP_UI_VERSION_MAJOR = 0x1000; // Major -- incremented when incompatible +constexpr uint16_t VP_UI_VERSION_MINOR = 0x1001; // Minor -- incremented on new features, but compatible +constexpr uint16_t VP_UI_VERSION_PATCH = 0x1002; // Patch -- fixed which do not change functionality. +constexpr uint16_t VP_UI_FLAVOUR = 0x1010; // lets reserve 16 bytes here to determine if UI is suitable for this Marlin. tbd. + +// Storage space for the Killscreen messages. 0x1100 - 0x1200 . Reused for the popup. +constexpr uint16_t VP_MSGSTR1 = 0x1100; +constexpr uint8_t VP_MSGSTR1_LEN = 0x20; // might be more place for it... +constexpr uint16_t VP_MSGSTR2 = 0x1140; +constexpr uint8_t VP_MSGSTR2_LEN = 0x20; +constexpr uint16_t VP_MSGSTR3 = 0x1180; +constexpr uint8_t VP_MSGSTR3_LEN = 0x20; +constexpr uint16_t VP_MSGSTR4 = 0x11C0; +constexpr uint8_t VP_MSGSTR4_LEN = 0x20; + +// Screenchange request for screens that only make sense when printer is idle. +// e.g movement is only allowed if printer is not printing. +// Marlin must confirm by setting the screen manually. +constexpr uint16_t VP_SCREENCHANGE_ASK = 0x2000; +constexpr uint16_t VP_SCREENCHANGE = 0x2001; // 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 = 0x2002; // Turn all heaters off. Value arbitrary ;)= +constexpr uint16_t VP_SCREENCHANGE_WHENSD = 0x2003; // "Print" Button touched -- go only there if there is an SD Card. + +constexpr uint16_t VP_CONFIRMED = 0x2010; // OK on confirm screen. + +// Buttons on the SD-Card File listing. +constexpr uint16_t VP_SD_ScrollEvent = 0x2020; // Data: 0 for "up a directory", numbers are the amount to scroll, e.g -1 one up, 1 one down +constexpr uint16_t VP_SD_FileSelected = 0x2022; // Number of file field selected. +constexpr uint16_t VP_SD_FileSelectConfirm = 0x2024; // (This is a virtual VP and emulated by the Confirm Screen when a file has been confirmed) + +constexpr uint16_t VP_SD_ResumePauseAbort = 0x2026; // Resume(Data=0), Pause(Data=1), Abort(Data=2) SD Card prints +constexpr uint16_t VP_SD_AbortPrintConfirmed = 0x2028; // Abort print confirmation (virtual, will be injected by the confirm dialog) +constexpr uint16_t VP_SD_Print_Setting = 0x2040; +constexpr uint16_t VP_SD_Print_LiveAdjustZ = 0x2050; // Data: 0 down, 1 up + +// Controls for movement (we can't use the incremental / decremental feature of the display at this feature works only with 16 bit values +// (which would limit us to 655.35mm, which is likely not a problem for common setups, but i don't want to rule out hangprinters support) +// A word about the coding: The VP will be per axis and the return code will be an signed 16 bit value in 0.01 mm resolution, telling us +// the relative travel amount t he user wants to do. So eg. if the display sends us VP=2100 with value 100, the user wants us to move X by +1 mm. +constexpr uint16_t VP_MOVE_X = 0x2100; +constexpr uint16_t VP_MOVE_Y = 0x2102; +constexpr uint16_t VP_MOVE_Z = 0x2104; +constexpr uint16_t VP_MOVE_E0 = 0x2110; +constexpr uint16_t VP_MOVE_E1 = 0x2112; +//constexpr uint16_t VP_MOVE_E2 = 0x2114; +//constexpr uint16_t VP_MOVE_E3 = 0x2116; +//constexpr uint16_t VP_MOVE_E4 = 0x2118; +//constexpr uint16_t VP_MOVE_E5 = 0x211A; +constexpr uint16_t VP_HOME_ALL = 0x2120; +constexpr uint16_t VP_MOTOR_LOCK_UNLOK = 0x2130; + +// Power loss recovery +constexpr uint16_t VP_POWER_LOSS_RECOVERY = 0x2180; + +// Fan Control Buttons , switch between "off" and "on" +constexpr uint16_t VP_FAN0_CONTROL = 0x2200; +constexpr uint16_t VP_FAN1_CONTROL = 0x2202; +//constexpr uint16_t VP_FAN2_CONTROL = 0x2204; +//constexpr uint16_t VP_FAN3_CONTROL = 0x2206; + +// Heater Control Buttons , triged between "cool down" and "heat PLA" state +constexpr uint16_t VP_E0_CONTROL = 0x2210; +constexpr uint16_t VP_E1_CONTROL = 0x2212; +//constexpr uint16_t VP_E2_CONTROL = 0x2214; +//constexpr uint16_t VP_E3_CONTROL = 0x2216; +//constexpr uint16_t VP_E4_CONTROL = 0x2218; +//constexpr uint16_t VP_E5_CONTROL = 0x221A; +constexpr uint16_t VP_BED_CONTROL = 0x221C; + +// Preheat +constexpr uint16_t VP_E0_BED_PREHEAT = 0x2220; +constexpr uint16_t VP_E1_BED_CONTROL = 0x2222; +//constexpr uint16_t VP_E2_BED_CONTROL = 0x2224; +//constexpr uint16_t VP_E3_BED_CONTROL = 0x2226; +//constexpr uint16_t VP_E4_BED_CONTROL = 0x2228; +//constexpr uint16_t VP_E5_BED_CONTROL = 0x222A; + +// Filament load and unload +constexpr uint16_t VP_E0_FILAMENT_LOAD_UNLOAD = 0x2300; +constexpr uint16_t VP_E1_FILAMENT_LOAD_UNLOAD = 0x2302; + +// Settings store , reset +constexpr uint16_t VP_SETTINGS = 0x2400; + +// PID autotune +constexpr uint16_t VP_PID_AUTOTUNE_E0 = 0x2410; +//constexpr uint16_t VP_PID_AUTOTUNE_E1 = 0x2412; +//constexpr uint16_t VP_PID_AUTOTUNE_E2 = 0x2414; +//constexpr uint16_t VP_PID_AUTOTUNE_E3 = 0x2416; +//constexpr uint16_t VP_PID_AUTOTUNE_E4 = 0x2418; +//constexpr uint16_t VP_PID_AUTOTUNE_E5 = 0x241A; +constexpr uint16_t VP_PID_AUTOTUNE_BED = 0x2420; + +// Firmware version on the boot screen. +constexpr uint16_t VP_MARLIN_VERSION = 0x3000; +constexpr uint8_t VP_MARLIN_VERSION_LEN = 16; // there is more space on the display, if needed. + +// Place for status messages. +constexpr uint16_t VP_M117 = 0x3020; +constexpr uint8_t VP_M117_LEN = 0x20; + +// Temperatures. +constexpr uint16_t VP_T_E0_Is = 0x3060; // 4 Byte Integer +constexpr uint16_t VP_T_E0_Set = 0x3062; // 2 Byte Integer +constexpr uint16_t VP_T_E1_Is = 0x3064; // 4 Byte Integer + +// reserved to support up to 6 Extruders: +//constexpr uint16_t VP_T_E1_Set = 0x3066; // 2 Byte Integer +//constexpr uint16_t VP_T_E2_Is = 0x3068; // 4 Byte Integer +//constexpr uint16_t VP_T_E2_Set = 0x306A; // 2 Byte Integer +//constexpr uint16_t VP_T_E3_Is = 0x306C; // 4 Byte Integer +//constexpr uint16_t VP_T_E3_Set = 0x306E; // 2 Byte Integer +//constexpr uint16_t VP_T_E4_Is = 0x3070; // 4 Byte Integer +//constexpr uint16_t VP_T_E4_Set = 0x3072; // 2 Byte Integer +//constexpr uint16_t VP_T_E4_Is = 0x3074; // 4 Byte Integer +//constexpr uint16_t VP_T_E4_Set = 0x3076; // 2 Byte Integer +//constexpr uint16_t VP_T_E5_Is = 0x3078; // 4 Byte Integer +//constexpr uint16_t VP_T_E5_Set = 0x307A; // 2 Byte Integer + +constexpr uint16_t VP_T_Bed_Is = 0x3080; // 4 Byte Integer +constexpr uint16_t VP_T_Bed_Set = 0x3082; // 2 Byte Integer + +constexpr uint16_t VP_Flowrate_E0 = 0x3090; // 2 Byte Integer +constexpr uint16_t VP_Flowrate_E1 = 0x3092; // 2 Byte Integer + +// reserved for up to 6 Extruders: +//constexpr uint16_t VP_Flowrate_E2 = 0x3094; +//constexpr uint16_t VP_Flowrate_E3 = 0x3096; +//constexpr uint16_t VP_Flowrate_E4 = 0x3098; +//constexpr uint16_t VP_Flowrate_E5 = 0x309A; + +constexpr uint16_t VP_Fan0_Percentage = 0x3100; // 2 Byte Integer (0..100) +constexpr uint16_t VP_Fan1_Percentage = 0x33A2; // 2 Byte Integer (0..100) +//constexpr uint16_t VP_Fan2_Percentage = 0x33A4; // 2 Byte Integer (0..100) +//constexpr uint16_t VP_Fan3_Percentage = 0x33A6; // 2 Byte Integer (0..100) + +constexpr uint16_t VP_Feedrate_Percentage = 0x3102; // 2 Byte Integer (0..100) +constexpr uint16_t VP_PrintProgress_Percentage = 0x3104; // 2 Byte Integer (0..100) + +constexpr uint16_t VP_PrintTime = 0x3106; +constexpr uint16_t VP_PrintTime_LEN = 10; + +constexpr uint16_t VP_PrintAccTime = 0x3160; +constexpr uint16_t VP_PrintAccTime_LEN = 32; + +constexpr uint16_t VP_PrintsTotal = 0x3180; +constexpr uint16_t VP_PrintsTotal_LEN = 16; + +// Actual Position +constexpr uint16_t VP_XPos = 0x3110; // 4 Byte Fixed point number; format xxx.yy +constexpr uint16_t VP_YPos = 0x3112; // 4 Byte Fixed point number; format xxx.yy +constexpr uint16_t VP_ZPos = 0x3114; // 4 Byte Fixed point number; format xxx.yy + +constexpr uint16_t VP_EPos = 0x3120; // 4 Byte Fixed point number; format xxx.yy + +// SDCard File Listing +constexpr uint16_t VP_SD_FileName_LEN = 32; // LEN is shared for all entries. +constexpr uint16_t DGUS_SD_FILESPERSCREEN = 5; // FIXME move that info to the display and read it from there. +constexpr uint16_t VP_SD_FileName0 = 0x3200; +constexpr uint16_t VP_SD_FileName1 = 0x3220; +constexpr uint16_t VP_SD_FileName2 = 0x3240; +constexpr uint16_t VP_SD_FileName3 = 0x3260; +constexpr uint16_t VP_SD_FileName4 = 0x3280; + +constexpr uint16_t VP_SD_Print_ProbeOffsetZ = 0x32A0; // +constexpr uint16_t VP_SD_Print_Filename = 0x32C0; // + +// Fan status +constexpr uint16_t VP_FAN0_STATUS = 0x3300; +constexpr uint16_t VP_FAN1_STATUS = 0x3302; +//constexpr uint16_t VP_FAN2_STATUS = 0x3304; +//constexpr uint16_t VP_FAN3_STATUS = 0x3306; + +// Heater status +constexpr uint16_t VP_E0_STATUS = 0x3310; +//constexpr uint16_t VP_E1_STATUS = 0x3312; +//constexpr uint16_t VP_E2_STATUS = 0x3314; +//constexpr uint16_t VP_E3_STATUS = 0x3316; +//constexpr uint16_t VP_E4_STATUS = 0x3318; +//constexpr uint16_t VP_E5_STATUS = 0x331A; +constexpr uint16_t VP_BED_STATUS = 0x331C; + +constexpr uint16_t VP_MOVE_OPTION = 0x3400; + +// Step per mm +constexpr uint16_t VP_X_STEP_PER_MM = 0x3600; // at the moment , 2 byte unsigned int , 0~1638.4 +//constexpr uint16_t VP_X2_STEP_PER_MM = 0x3602; +constexpr uint16_t VP_Y_STEP_PER_MM = 0x3604; +//constexpr uint16_t VP_Y2_STEP_PER_MM = 0x3606; +constexpr uint16_t VP_Z_STEP_PER_MM = 0x3608; +//constexpr uint16_t VP_Z2_STEP_PER_MM = 0x360A; +constexpr uint16_t VP_E0_STEP_PER_MM = 0x3610; +//constexpr uint16_t VP_E1_STEP_PER_MM = 0x3612; +//constexpr uint16_t VP_E2_STEP_PER_MM = 0x3614; +//constexpr uint16_t VP_E3_STEP_PER_MM = 0x3616; +//constexpr uint16_t VP_E4_STEP_PER_MM = 0x3618; +//constexpr uint16_t VP_E5_STEP_PER_MM = 0x361A; + +// PIDs +constexpr uint16_t VP_E0_PID_P = 0x3700; // at the moment , 2 byte unsigned int , 0~1638.4 +constexpr uint16_t VP_E0_PID_I = 0x3702; +constexpr uint16_t VP_E0_PID_D = 0x3704; +constexpr uint16_t VP_BED_PID_P = 0x3710; +constexpr uint16_t VP_BED_PID_I = 0x3712; +constexpr uint16_t VP_BED_PID_D = 0x3714; + +// Waiting screen status +constexpr uint16_t VP_WAITING_STATUS = 0x3800; + +// SPs for certain variables... +// located at 0x5000 and up +// Not used yet! +// This can be used e.g to make controls / data display invisible +constexpr uint16_t SP_T_E0_Is = 0x5000; +constexpr uint16_t SP_T_E0_Set = 0x5010; +constexpr uint16_t SP_T_E1_Is = 0x5020; +constexpr uint16_t SP_T_Bed_Is = 0x5030; +constexpr uint16_t SP_T_Bed_Set = 0x5040; diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp new file mode 100644 index 000000000000..b0759c63afaf --- /dev/null +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp @@ -0,0 +1,423 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../../../inc/MarlinConfigPre.h" + +#if ENABLED(DGUS_LCD_UI_ORIGIN) + +#include "../DGUSScreenHandler.h" + +#include "../../../../MarlinCore.h" +#include "../../../../gcode/queue.h" +#include "../../../../libs/duration_t.h" +#include "../../../../module/settings.h" +#include "../../../../module/temperature.h" +#include "../../../../module/motion.h" +#include "../../../../module/planner.h" +#include "../../../../module/printcounter.h" +#include "../../../../sd/cardreader.h" + +#if ENABLED(POWER_LOSS_RECOVERY) + #include "../../../../feature/powerloss.h" +#endif + +#if ENABLED(SDSUPPORT) + + static ExtUI::FileList filelist; + + void DGUSScreenHandler::DGUSLCD_SD_FileSelected(DGUS_VP_Variable &var, void *val_ptr) { + uint16_t touched_nr = (int16_t)swap16(*(uint16_t*)val_ptr) + top_file; + if (touched_nr > filelist.count()) return; + if (!filelist.seek(touched_nr)) return; + + if (filelist.isDir()) { + filelist.changeDir(filelist.filename()); + top_file = 0; + ForceCompleteUpdate(); + return; + } + + #if ENABLED(DGUS_PRINT_FILENAME) + // Send print filename + dgusdisplay.WriteVariable(VP_SD_Print_Filename, filelist.filename(), VP_SD_FileName_LEN, true); + #endif + + // Setup Confirmation screen + file_to_print = touched_nr; + + HandleUserConfirmationPopUp(VP_SD_FileSelectConfirm, nullptr, PSTR("Print file"), filelist.filename(), PSTR("from SD Card?"), true, true, false, true); + } + + void DGUSScreenHandler::DGUSLCD_SD_StartPrint(DGUS_VP_Variable &var, void *val_ptr) { + if (!filelist.seek(file_to_print)) return; + ExtUI::printFile(filelist.shortFilename()); + GotoScreen(DGUSLCD_SCREEN_STATUS); + } + + void DGUSScreenHandler::DGUSLCD_SD_ResumePauseAbort(DGUS_VP_Variable &var, void *val_ptr) { + + if (!ExtUI::isPrintingFromMedia()) return; // avoid race condition when user stays in this menu and printer finishes. + switch (swap16(*(uint16_t*)val_ptr)) { + case 0: { // Resume + if (ExtUI::isPrintingFromMediaPaused()) { + ExtUI::resumePrint(); + } + } break; + + case 1: // Pause + + GotoScreen(DGUSLCD_SCREEN_SDPRINTMANIPULATION); + if (!ExtUI::isPrintingFromMediaPaused()) { + ExtUI::pausePrint(); + //ExtUI::mks_pausePrint(); + } + break; + case 2: // Abort + HandleUserConfirmationPopUp(VP_SD_AbortPrintConfirmed, nullptr, PSTR("Abort printing"), filelist.filename(), PSTR("?"), true, true, false, true); + break; + } + } + + void DGUSScreenHandler::DGUSLCD_SD_SendFilename(DGUS_VP_Variable& var) { + uint16_t target_line = (var.VP - VP_SD_FileName0) / VP_SD_FileName_LEN; + if (target_line > DGUS_SD_FILESPERSCREEN) return; + char tmpfilename[VP_SD_FileName_LEN + 1] = ""; + var.memadr = (void*)tmpfilename; + + if (filelist.seek(top_file + target_line)) { + snprintf_P(tmpfilename, VP_SD_FileName_LEN, PSTR("%s%c"), filelist.filename(), filelist.isDir() ? '/' : 0); // snprintf_P(tmpfilename, VP_SD_FileName_LEN, PSTR("%s"), filelist.filename()); + } + DGUSLCD_SendStringToDisplay(var); + } + + void DGUSScreenHandler::SDCardInserted() { + top_file = 0; + filelist.refresh(); + auto cs = getCurrentScreen(); + if (cs == DGUSLCD_SCREEN_MAIN || cs == DGUSLCD_SCREEN_STATUS) + GotoScreen(DGUSLCD_SCREEN_SDFILELIST); + } + + void DGUSScreenHandler::SDCardRemoved() { + if (current_screen == DGUSLCD_SCREEN_SDFILELIST + || (current_screen == DGUSLCD_SCREEN_CONFIRM && (ConfirmVP == VP_SD_AbortPrintConfirmed || ConfirmVP == VP_SD_FileSelectConfirm)) + || current_screen == DGUSLCD_SCREEN_SDPRINTMANIPULATION + ) GotoScreen(DGUSLCD_SCREEN_MAIN); + } + +#endif // SDSUPPORT + +void DGUSScreenHandler::ScreenChangeHook(DGUS_VP_Variable &var, void *val_ptr) { + uint8_t *tmp = (uint8_t*)val_ptr; + + // The keycode in target is coded as , so 0x0100A means + // from screen 1 (main) to 10 (temperature). DGUSLCD_SCREEN_POPUP is special, + // meaning "return to previous screen" + DGUSLCD_Screens target = (DGUSLCD_Screens)tmp[1]; + + DEBUG_ECHOLNPAIR("\n DEBUG target", target); + + if (target == DGUSLCD_SCREEN_POPUP) { + // Special handling for popup is to return to previous menu + if (current_screen == DGUSLCD_SCREEN_POPUP && confirm_action_cb) confirm_action_cb(); + PopToOldScreen(); + return; + } + + UpdateNewScreen(target); + + #ifdef DEBUG_DGUSLCD + if (!DGUSLCD_FindScreenVPMapList(target)) DEBUG_ECHOLNPAIR("WARNING: No screen Mapping found for ", target); + #endif +} + +void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("HandleManualMove"); + + int16_t movevalue = swap16(*(uint16_t*)val_ptr); + #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) + if (movevalue) { + const uint16_t choice = *(uint16_t*)var.memadr; + movevalue = movevalue < 0 ? -choice : choice; + } + #endif + char axiscode; + unsigned int speed = 1500; // FIXME: get default feedrate for manual moves, don't hardcode. + + switch (var.VP) { + default: return; + + case VP_MOVE_X: + axiscode = 'X'; + if (!ExtUI::canMove(ExtUI::axis_t::X)) goto cannotmove; + break; + + case VP_MOVE_Y: + axiscode = 'Y'; + if (!ExtUI::canMove(ExtUI::axis_t::Y)) goto cannotmove; + break; + + case VP_MOVE_Z: + axiscode = 'Z'; + speed = 300; // default to 5mm/s + if (!ExtUI::canMove(ExtUI::axis_t::Z)) goto cannotmove; + break; + + case VP_HOME_ALL: // only used for homing + axiscode = '\0'; + movevalue = 0; // ignore value sent from display, this VP is _ONLY_ for homing. + break; + } + + if (!movevalue) { + // homing + DEBUG_ECHOPAIR(" homing ", AS_CHAR(axiscode)); + char buf[6] = "G28 X"; + buf[4] = axiscode; + //DEBUG_ECHOPAIR(" ", buf); + queue.enqueue_one_now(buf); + //DEBUG_ECHOLNPGM(" ✓"); + ForceCompleteUpdate(); + return; + } + else { + // movement + DEBUG_ECHOPAIR(" move ", AS_CHAR(axiscode)); + bool old_relative_mode = relative_mode; + if (!relative_mode) { + //DEBUG_ECHOPGM(" G91"); + queue.enqueue_now_P(PSTR("G91")); + //DEBUG_ECHOPGM(" ✓ "); + } + char buf[32]; // G1 X9999.99 F12345 + unsigned int backup_speed = MMS_TO_MMM(feedrate_mm_s); + char sign[] = "\0"; + int16_t value = movevalue / 100; + if (movevalue < 0) { value = -value; sign[0] = '-'; } + int16_t fraction = ABS(movevalue) % 100; + snprintf_P(buf, 32, PSTR("G0 %c%s%d.%02d F%d"), axiscode, sign, value, fraction, speed); + //DEBUG_ECHOPAIR(" ", buf); + queue.enqueue_one_now(buf); + //DEBUG_ECHOLNPGM(" ✓ "); + if (backup_speed != speed) { + snprintf_P(buf, 32, PSTR("G0 F%d"), backup_speed); + queue.enqueue_one_now(buf); + //DEBUG_ECHOPAIR(" ", buf); + } + // while (!enqueue_and_echo_command(buf)) idle(); + //DEBUG_ECHOLNPGM(" ✓ "); + if (!old_relative_mode) { + //DEBUG_ECHOPGM("G90"); + queue.enqueue_now_P(PSTR("G90")); + //DEBUG_ECHOPGM(" ✓ "); + } + } + + ForceCompleteUpdate(); + DEBUG_ECHOLNPGM("manmv done."); + return; + + cannotmove: + DEBUG_ECHOLNPAIR(" cannot move ", AS_CHAR(axiscode)); + return; +} + +#if HAS_PID_HEATING + void DGUSScreenHandler::HandleTemperaturePIDChanged(DGUS_VP_Variable &var, void *val_ptr) { + uint16_t rawvalue = swap16(*(uint16_t*)val_ptr); + DEBUG_ECHOLNPAIR("V1:", rawvalue); + float value = (float)rawvalue / 10; + DEBUG_ECHOLNPAIR("V2:", value); + float newvalue = 0; + + switch (var.VP) { + default: return; + #if HAS_HOTEND + case VP_E0_PID_P: newvalue = value; break; + case VP_E0_PID_I: newvalue = scalePID_i(value); break; + case VP_E0_PID_D: newvalue = scalePID_d(value); break; + #endif + #if HOTENDS >= 2 + case VP_E1_PID_P: newvalue = value; break; + case VP_E1_PID_I: newvalue = scalePID_i(value); break; + case VP_E1_PID_D: newvalue = scalePID_d(value); break; + #endif + #if HAS_HEATED_BED + case VP_BED_PID_P: newvalue = value; break; + case VP_BED_PID_I: newvalue = scalePID_i(value); break; + case VP_BED_PID_D: newvalue = scalePID_d(value); break; + #endif + } + + DEBUG_ECHOLNPAIR_F("V3:", newvalue); + *(float *)var.memadr = newvalue; + + skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel + } +#endif // HAS_PID_HEATING + +#if ENABLED(BABYSTEPPING) + void DGUSScreenHandler::HandleLiveAdjustZ(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("HandleLiveAdjustZ"); + int16_t flag = swap16(*(uint16_t*)val_ptr), + steps = flag ? -20 : 20; + ExtUI::smartAdjustAxis_steps(steps, ExtUI::axis_t::Z, true); + ForceCompleteUpdate(); + } +#endif + +#if ENABLED(DGUS_FILAMENT_LOADUNLOAD) + + void DGUSScreenHandler::HandleFilamentOption(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("HandleFilamentOption"); + + uint8_t e_temp = 0; + filament_data.heated = false; + uint16_t preheat_option = swap16(*(uint16_t*)val_ptr); + if (preheat_option <= 8) { // Load filament type + filament_data.action = 1; + } + else if (preheat_option >= 10) { // Unload filament type + preheat_option -= 10; + filament_data.action = 2; + filament_data.purge_length = DGUS_FILAMENT_PURGE_LENGTH; + } + else { // Cancel filament operation + filament_data.action = 0; + } + + switch (preheat_option) { + case 0: // Load PLA + #ifdef PREHEAT_1_TEMP_HOTEND + e_temp = PREHEAT_1_TEMP_HOTEND; + #endif + break; + case 1: // Load ABS + TERN_(PREHEAT_2_TEMP_HOTEND, e_temp = PREHEAT_2_TEMP_HOTEND); + break; + case 2: // Load PET + #ifdef PREHEAT_3_TEMP_HOTEND + e_temp = PREHEAT_3_TEMP_HOTEND; + #endif + break; + case 3: // Load FLEX + #ifdef PREHEAT_4_TEMP_HOTEND + e_temp = PREHEAT_4_TEMP_HOTEND; + #endif + break; + case 9: // Cool down + default: + e_temp = 0; + break; + } + + if (filament_data.action == 0) { // Go back to utility screen + #if HAS_HOTEND + thermalManager.setTargetHotend(e_temp, ExtUI::extruder_t::E0); + #if HOTENDS >= 2 + thermalManager.setTargetHotend(e_temp, ExtUI::extruder_t::E1); + #endif + #endif + GotoScreen(DGUSLCD_SCREEN_UTILITY); + } + else { // Go to the preheat screen to show the heating progress + switch (var.VP) { + default: return; + #if HAS_HOTEND + case VP_E0_FILAMENT_LOAD_UNLOAD: + filament_data.extruder = ExtUI::extruder_t::E0; + thermalManager.setTargetHotend(e_temp, filament_data.extruder); + break; + #endif + #if HOTENDS >= 2 + case VP_E1_FILAMENT_LOAD_UNLOAD: + filament_data.extruder = ExtUI::extruder_t::E1; + thermalManager.setTargetHotend(e_temp, filament_data.extruder); + break; + #endif + } + GotoScreen(DGUSLCD_SCREEN_FILAMENT_HEATING); + } + } + + void DGUSScreenHandler::HandleFilamentLoadUnload(DGUS_VP_Variable &var) { + DEBUG_ECHOLNPGM("HandleFilamentLoadUnload"); + if (filament_data.action <= 0) return; + + // If we close to the target temperature, we can start load or unload the filament + if (thermalManager.hotEnoughToExtrude(filament_data.extruder) && \ + thermalManager.targetHotEnoughToExtrude(filament_data.extruder)) { + float movevalue = DGUS_FILAMENT_LOAD_LENGTH_PER_TIME; + + if (filament_data.action == 1) { // load filament + if (!filament_data.heated) { + //GotoScreen(DGUSLCD_SCREEN_FILAMENT_LOADING); + filament_data.heated = true; + } + movevalue = ExtUI::getAxisPosition_mm(filament_data.extruder) + movevalue; + } + else { // unload filament + if (!filament_data.heated) { + GotoScreen(DGUSLCD_SCREEN_FILAMENT_UNLOADING); + filament_data.heated = true; + } + // Before unloading extrude to prevent jamming + if (filament_data.purge_length >= 0) { + movevalue = ExtUI::getAxisPosition_mm(filament_data.extruder) + movevalue; + filament_data.purge_length -= movevalue; + } + else { + movevalue = ExtUI::getAxisPosition_mm(filament_data.extruder) - movevalue; + } + } + ExtUI::setAxisPosition_mm(movevalue, filament_data.extruder); + } + } +#endif // DGUS_FILAMENT_LOADUNLOAD + +bool DGUSScreenHandler::loop() { + dgusdisplay.loop(); + + const millis_t ms = millis(); + static millis_t next_event_ms = 0; + + if (!IsScreenComplete() || ELAPSED(ms, next_event_ms)) { + next_event_ms = ms + DGUS_UPDATE_INTERVAL_MS; + UpdateScreenVPData(); + } + + #if ENABLED(SHOW_BOOTSCREEN) + static bool booted = false; + + if (!booted && TERN0(POWER_LOSS_RECOVERY, recovery.valid())) + booted = true; + + if (!booted && ELAPSED(ms, BOOTSCREEN_TIMEOUT)) { + booted = true; + GotoScreen(TERN0(POWER_LOSS_RECOVERY, recovery.valid()) ? DGUSLCD_SCREEN_POWER_LOSS : DGUSLCD_SCREEN_MAIN); + } + #endif + + return IsScreenComplete(); +} + +#endif // DGUS_LCD_UI_ORIGIN diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.h new file mode 100644 index 000000000000..ee0af013a855 --- /dev/null +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.h @@ -0,0 +1,240 @@ +/** + * 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 + +#include "../DGUSDisplay.h" +#include "../DGUSVPVariable.h" +#include "../DGUSDisplayDef.h" + +#include "../../../../inc/MarlinConfig.h" + +enum DGUSLCD_Screens : uint8_t; + +class DGUSScreenHandler { +public: + DGUSScreenHandler() = default; + + static bool loop(); + + // Send all 4 strings that are displayed on the infoscreen, confirmation screen and kill screen + // The bools specifying whether the strings are in RAM or FLASH. + static void sendinfoscreen(const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); + + static void HandleUserConfirmationPopUp(uint16_t ConfirmVP, const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); + + // "M117" Message -- msg is a RAM ptr. + static void setstatusmessage(const char *msg); + // The same for messages from Flash + static void setstatusmessagePGM(PGM_P const msg); + // Callback for VP "Display wants to change screen on idle printer" + static void ScreenChangeHookIfIdle(DGUS_VP_Variable &var, void *val_ptr); + // Callback for VP "Screen has been changed" + static void ScreenChangeHook(DGUS_VP_Variable &var, void *val_ptr); + + // Callback for VP "All Heaters Off" + static void HandleAllHeatersOff(DGUS_VP_Variable &var, void *val_ptr); + // Hook for "Change this temperature" + static void HandleTemperatureChanged(DGUS_VP_Variable &var, void *val_ptr); + // Hook for "Change Flowrate" + static void HandleFlowRateChanged(DGUS_VP_Variable &var, void *val_ptr); + #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) + // Hook for manual move option + static void HandleManualMoveOption(DGUS_VP_Variable &var, void *val_ptr); + #endif + + // Hook for manual move. + static void HandleManualMove(DGUS_VP_Variable &var, void *val_ptr); + // Hook for manual extrude. + static void HandleManualExtrude(DGUS_VP_Variable &var, void *val_ptr); + // Hook for motor lock and unlook + static void HandleMotorLockUnlock(DGUS_VP_Variable &var, void *val_ptr); + #if ENABLED(POWER_LOSS_RECOVERY) + // Hook for power loss recovery. + static void HandlePowerLossRecovery(DGUS_VP_Variable &var, void *val_ptr); + #endif + // Hook for settings + static void HandleSettings(DGUS_VP_Variable &var, void *val_ptr); + static void HandleStepPerMMChanged(DGUS_VP_Variable &var, void *val_ptr); + static void HandleStepPerMMExtruderChanged(DGUS_VP_Variable &var, void *val_ptr); + + #if HAS_PID_HEATING + // Hook for "Change this temperature PID para" + static void HandleTemperaturePIDChanged(DGUS_VP_Variable &var, void *val_ptr); + // Hook for PID autotune + static void HandlePIDAutotune(DGUS_VP_Variable &var, void *val_ptr); + #endif + #if HAS_BED_PROBE + // Hook for "Change probe offset z" + static void HandleProbeOffsetZChanged(DGUS_VP_Variable &var, void *val_ptr); + #endif + #if ENABLED(BABYSTEPPING) + // Hook for live z adjust action + static void HandleLiveAdjustZ(DGUS_VP_Variable &var, void *val_ptr); + #endif + #if HAS_FAN + // Hook for fan control + static void HandleFanControl(DGUS_VP_Variable &var, void *val_ptr); + #endif + // Hook for heater control + static void HandleHeaterControl(DGUS_VP_Variable &var, void *val_ptr); + #if ENABLED(DGUS_PREHEAT_UI) + // Hook for preheat + static void HandlePreheat(DGUS_VP_Variable &var, void *val_ptr); + #endif + #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) + // Hook for filament load and unload filament option + static void HandleFilamentOption(DGUS_VP_Variable &var, void *val_ptr); + // Hook for filament load and unload + static void HandleFilamentLoadUnload(DGUS_VP_Variable &var); + #endif + + #if ENABLED(SDSUPPORT) + // 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. + static void DGUSLCD_SD_ScrollFilelist(DGUS_VP_Variable &var, void *val_ptr); + // File touched. + static void DGUSLCD_SD_FileSelected(DGUS_VP_Variable &var, void *val_ptr); + // start print after confirmation received. + static void DGUSLCD_SD_StartPrint(DGUS_VP_Variable &var, void *val_ptr); + // User hit the pause, resume or abort button. + static void DGUSLCD_SD_ResumePauseAbort(DGUS_VP_Variable &var, void *val_ptr); + // User confirmed the abort action + static void DGUSLCD_SD_ReallyAbort(DGUS_VP_Variable &var, void *val_ptr); + // User hit the tune button + static void DGUSLCD_SD_PrintTune(DGUS_VP_Variable &var, void *val_ptr); + // Send a single filename to the display. + static void DGUSLCD_SD_SendFilename(DGUS_VP_Variable &var); + // Marlin informed us that a new SD has been inserted. + static void SDCardInserted(); + // Marlin informed us that the SD Card has been removed(). + static void SDCardRemoved(); + // Marlin informed us about a bad SD Card. + static void SDCardError(); + #endif + + // OK Button the Confirm screen. + static void ScreenConfirmedOK(DGUS_VP_Variable &var, void *val_ptr); + + // Update data after went to new screen (by display or by GotoScreen) + // remember: store the last-displayed screen, so it can get returned to. + // (e.g for pop up messages) + static void UpdateNewScreen(DGUSLCD_Screens newscreen, bool popup=false); + + // Recall the remembered screen. + static void PopToOldScreen(); + + // Make the display show the screen and update all VPs in it. + static void GotoScreen(DGUSLCD_Screens screen, bool ispopup = false); + + static void UpdateScreenVPData(); + + // Helpers to convert and transfer data to the display. + static void DGUSLCD_SendWordValueToDisplay(DGUS_VP_Variable &var); + static void DGUSLCD_SendStringToDisplay(DGUS_VP_Variable &var); + static void DGUSLCD_SendStringToDisplayPGM(DGUS_VP_Variable &var); + static void DGUSLCD_SendTemperaturePID(DGUS_VP_Variable &var); + static void DGUSLCD_SendPercentageToDisplay(DGUS_VP_Variable &var); + static void DGUSLCD_SendPrintProgressToDisplay(DGUS_VP_Variable &var); + static void DGUSLCD_SendPrintTimeToDisplay(DGUS_VP_Variable &var); + + #if ENABLED(PRINTCOUNTER) + static void DGUSLCD_SendPrintAccTimeToDisplay(DGUS_VP_Variable &var); + static void DGUSLCD_SendPrintsTotalToDisplay(DGUS_VP_Variable &var); + #endif + #if HAS_FAN + static void DGUSLCD_SendFanStatusToDisplay(DGUS_VP_Variable &var); + #endif + static void DGUSLCD_SendHeaterStatusToDisplay(DGUS_VP_Variable &var); + #if ENABLED(DGUS_UI_WAITING) + static void DGUSLCD_SendWaitingStatusToDisplay(DGUS_VP_Variable &var); + #endif + + // Send a value from 0..100 to a variable with a range from 0..255 + static void DGUSLCD_PercentageToUint8(DGUS_VP_Variable &var, void *val_ptr); + + template + static void DGUSLCD_SetValueDirectly(DGUS_VP_Variable &var, void *val_ptr) { + if (!var.memadr) return; + union { unsigned char tmp[sizeof(T)]; T t; } x; + unsigned char *ptr = (unsigned char*)val_ptr; + LOOP_L_N(i, sizeof(T)) x.tmp[i] = ptr[sizeof(T) - i - 1]; + *(T*)var.memadr = x.t; + } + + // Send a float value to the display. + // Display will get a 4-byte integer scaled to the number of digits: + // Tell the display the number of digits and it cheats by displaying a dot between... + template + static void DGUSLCD_SendFloatAsLongValueToDisplay(DGUS_VP_Variable &var) { + if (var.memadr) { + float f = *(float *)var.memadr; + f *= cpow(10, decimals); + dgusdisplay.WriteVariable(var.VP, (long)f); + } + } + + // Send a float value to the display. + // Display will get a 2-byte integer scaled to the number of digits: + // Tell the display the number of digits and it cheats by displaying a dot between... + template + static void DGUSLCD_SendFloatAsIntValueToDisplay(DGUS_VP_Variable &var) { + if (var.memadr) { + float f = *(float *)var.memadr; + DEBUG_ECHOLNPAIR_F(" >> ", f, 6); + f *= cpow(10, decimals); + dgusdisplay.WriteVariable(var.VP, (int16_t)f); + } + } + + // Force an update of all VP on the current screen. + static inline void ForceCompleteUpdate() { update_ptr = 0; ScreenComplete = false; } + // Has all VPs sent to the screen + static inline bool IsScreenComplete() { return ScreenComplete; } + + static inline DGUSLCD_Screens getCurrentScreen() { return current_screen; } + + static inline void SetupConfirmAction( void (*f)()) { confirm_action_cb = f; } + +private: + static DGUSLCD_Screens current_screen; //< currently on screen + static constexpr uint8_t NUM_PAST_SCREENS = 4; + static DGUSLCD_Screens past_screens[NUM_PAST_SCREENS]; //< LIFO with past screens for the "back" button. + + static uint8_t update_ptr; //< Last sent entry in the VPList for the actual screen. + static uint16_t skipVP; //< When updating the screen data, skip this one, because the user is interacting with it. + static bool ScreenComplete; //< All VPs sent to screen? + + static uint16_t ConfirmVP; //< context for confirm screen (VP that will be emulated-sent on "OK"). + + #if ENABLED(SDSUPPORT) + static int16_t top_file; //< file on top of file chooser + static int16_t file_to_print; //< touched file to be confirmed + #endif + + static void (*confirm_action_cb)(); +}; + +#if ENABLED(POWER_LOSS_RECOVERY) + #define PLR_SCREEN_RECOVER DGUSLCD_SCREEN_SDPRINTMANIPULATION + #define PLR_SCREEN_CANCEL DGUSLCD_SCREEN_STATUS +#endif diff --git a/Marlin/src/lcd/extui/dgus_lcd.cpp b/Marlin/src/lcd/extui/dgus_lcd.cpp deleted file mode 100644 index d175b5acac9a..000000000000 --- a/Marlin/src/lcd/extui/dgus_lcd.cpp +++ /dev/null @@ -1,150 +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 . - * - */ - -/** - * dgus_lcd.cpp - * - * DGUS implementation for Marlin by coldtobi, Feb-May 2019 - */ - -#include "../../inc/MarlinConfigPre.h" - -#if HAS_DGUS_LCD - -#include "ui_api.h" -#include "lib/dgus/DGUSDisplay.h" -#include "lib/dgus/DGUSDisplayDef.h" -#include "lib/dgus/DGUSScreenHandler.h" - -extern const char NUL_STR[]; - -namespace ExtUI { - - void onStartup() { - dgusdisplay.InitDisplay(); - ScreenHandler.UpdateScreenVPData(); - } - - void onIdle() { ScreenHandler.loop(); } - - void onPrinterKilled(PGM_P const error, PGM_P const component) { - ScreenHandler.sendinfoscreen(GET_TEXT(MSG_HALTED), error, NUL_STR, GET_TEXT(MSG_PLEASE_RESET), true, true, true, true); - ScreenHandler.GotoScreen(DGUSLCD_SCREEN_KILL); - 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 onPlayTone(const uint16_t frequency, const uint16_t duration) {} - void onPrintTimerStarted() {} - void onPrintTimerPaused() {} - void onPrintTimerStopped() {} - void onFilamentRunout(const extruder_t extruder) {} - - void onUserConfirmRequired(const char * const msg) { - if (msg) { - ScreenHandler.sendinfoscreen(PSTR("Please confirm."), nullptr, msg, nullptr, true, true, false, true); - ScreenHandler.SetupConfirmAction(ExtUI::setUserConfirmed); - ScreenHandler.GotoScreen(DGUSLCD_SCREEN_POPUP); - } - else if (ScreenHandler.getCurrentScreen() == DGUSLCD_SCREEN_POPUP ) { - ScreenHandler.SetupConfirmAction(nullptr); - ScreenHandler.PopToOldScreen(); - } - } - - void onStatusChanged(const char * const msg) { ScreenHandler.setstatusmessage(msg); } - - void onFactoryReset() {} - void onStoreSettings(char *buff) { - // Called when saving to EEPROM (i.e. M500). If the ExtUI needs - // permanent data to be stored, it can write up to eeprom_data_size bytes - // into buff. - - // Example: - // static_assert(sizeof(myDataStruct) <= ExtUI::eeprom_data_size); - // memcpy(buff, &myDataStruct, sizeof(myDataStruct)); - } - - void onLoadSettings(const char *buff) { - // Called while loading settings from EEPROM. If the ExtUI - // needs to retrieve data, it should copy up to eeprom_data_size bytes - // from buff - - // Example: - // static_assert(sizeof(myDataStruct) <= ExtUI::eeprom_data_size); - // memcpy(&myDataStruct, buff, sizeof(myDataStruct)); - } - - void onConfigurationStoreWritten(bool success) { - // Called after the entire EEPROM has been written, - // whether successful or not. - } - - void onConfigurationStoreRead(bool success) { - // Called after the entire EEPROM has been read, - // whether successful or not. - } - - #if HAS_MESH - void onMeshUpdate(const int8_t xpos, const int8_t ypos, const float zval) { - // Called when any mesh points are updated - } - - void onMeshUpdate(const int8_t xpos, const int8_t ypos, const ExtUI::probe_state_t state) { - // Called to indicate a special condition - } - #endif - - #if ENABLED(POWER_LOSS_RECOVERY) - void onPowerLossResume() { - // Called on resume from power-loss - ScreenHandler.GotoScreen(DGUSLCD_SCREEN_POWER_LOSS); - } - #endif - - - #if HAS_PID_HEATING - void onPidTuning(const result_t rst) { - // Called for temperature PID tuning result - switch (rst) { - case PID_BAD_EXTRUDER_NUM: - ScreenHandler.setstatusmessagePGM(GET_TEXT(MSG_PID_BAD_EXTRUDER_NUM)); - break; - case PID_TEMP_TOO_HIGH: - ScreenHandler.setstatusmessagePGM(GET_TEXT(MSG_PID_TEMP_TOO_HIGH)); - break; - case PID_TUNING_TIMEOUT: - ScreenHandler.setstatusmessagePGM(GET_TEXT(MSG_PID_TIMEOUT)); - break; - case PID_DONE: - ScreenHandler.setstatusmessagePGM(GET_TEXT(MSG_PID_AUTOTUNE_DONE)); - break; - } - ScreenHandler.GotoScreen(DGUSLCD_SCREEN_MAIN); - } - #endif - -} -#endif // HAS_DGUS_LCD diff --git a/Marlin/src/lcd/extui/example.cpp b/Marlin/src/lcd/extui/example/example.cpp similarity index 82% rename from Marlin/src/lcd/extui/example.cpp rename to Marlin/src/lcd/extui/example/example.cpp index a5ef5652bc0f..0e7d71ff4da4 100644 --- a/Marlin/src/lcd/extui/example.cpp +++ b/Marlin/src/lcd/extui/example/example.cpp @@ -16,14 +16,14 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ -#include "../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if BOTH(EXTUI_EXAMPLE, EXTENSIBLE_UI) -#include "ui_api.h" +#include "../ui_api.h" // To implement a new UI, complete the functions below and // read or update Marlin's state using the methods in the @@ -47,9 +47,9 @@ namespace ExtUI { } void onIdle() {} void onPrinterKilled(PGM_P const error, PGM_P const component) {} - void onMediaInserted() {}; - void onMediaError() {}; - void onMediaRemoved() {}; + void onMediaInserted() {} + void onMediaError() {} + void onMediaRemoved() {} void onPlayTone(const uint16_t frequency, const uint16_t duration) {} void onPrintTimerStarted() {} void onPrintTimerPaused() {} @@ -57,6 +57,11 @@ namespace ExtUI { void onFilamentRunout(const extruder_t extruder) {} void onUserConfirmRequired(const char * const msg) {} void onStatusChanged(const char * const msg) {} + + void onHomingStart() {} + void onHomingComplete() {} + void onPrintFinished() {} + void onFactoryReset() {} void onStoreSettings(char *buff) { @@ -65,7 +70,7 @@ namespace ExtUI { // into buff. // Example: - // static_assert(sizeof(myDataStruct) <= ExtUI::eeprom_data_size); + // static_assert(sizeof(myDataStruct) <= eeprom_data_size); // memcpy(buff, &myDataStruct, sizeof(myDataStruct)); } @@ -75,10 +80,14 @@ namespace ExtUI { // from buff // Example: - // static_assert(sizeof(myDataStruct) <= ExtUI::eeprom_data_size); + // static_assert(sizeof(myDataStruct) <= eeprom_data_size); // memcpy(&myDataStruct, buff, sizeof(myDataStruct)); } + void onPostprocessSettings() { + // Called after loading or resetting stored settings + } + void onConfigurationStoreWritten(bool success) { // Called after the entire EEPROM has been written, // whether successful or not. @@ -90,11 +99,13 @@ namespace ExtUI { } #if HAS_MESH - void onMeshUpdate(const int8_t xpos, const int8_t ypos, const float zval) { + void onMeshLevelingStart() {} + + void onMeshUpdate(const int8_t xpos, const int8_t ypos, const_float_t zval) { // Called when any mesh points are updated } - void onMeshUpdate(const int8_t xpos, const int8_t ypos, const ExtUI::probe_state_t state) { + void onMeshUpdate(const int8_t xpos, const int8_t ypos, const probe_state_t state) { // Called to indicate a special condition } #endif @@ -108,8 +119,17 @@ namespace ExtUI { #if HAS_PID_HEATING void onPidTuning(const result_t rst) { // Called for temperature PID tuning result + switch (rst) { + case PID_BAD_EXTRUDER_NUM: break; + case PID_TEMP_TOO_HIGH: break; + case PID_TUNING_TIMEOUT: break; + case PID_DONE: break; + } } #endif + + void onSteppersDisabled() {} + void onSteppersEnabled() {} } #endif // EXTUI_EXAMPLE && EXTENSIBLE_UI diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp similarity index 99% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp index 2c466ffd0449..a28318335c59 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp @@ -17,10 +17,10 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ -#include "../compat.h" +#include "../config.h" #if ENABLED(TOUCH_UI_FTDI_EVE) @@ -206,7 +206,7 @@ bool UIFlashStorage::is_present = false; /* In order to provide some degree of wear leveling, each data write to the * SPI Flash chip is appended to data that was already written before, until - * the data storage area is completely filled. New data is written preceeded + * the data storage area is completely filled. New data is written preceded * with a 32-bit delimiter 'LULZ', so that we can distinguish written and * unwritten data: * diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/flash_storage.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.h similarity index 99% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/flash_storage.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.h index 3edc2a9de1c8..eef8cf8677ca 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/flash_storage.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.h @@ -17,7 +17,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ class SPIFlash { diff --git a/Marlin/src/lcd/extui/lib/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 similarity index 93% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/media_file_reader.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/media_file_reader.cpp index 46683401dca7..b4165a742a5f 100644 --- a/Marlin/src/lcd/extui/lib/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 @@ -17,19 +17,17 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ -#include "../compat.h" +#include "../config.h" #if ENABLED(TOUCH_UI_FTDI_EVE) #include "media_file_reader.h" #if ENABLED(SDSUPPORT) - bool MediaFileReader::open(const char* filename) { - card.init(SPI_SPEED, SDSS); - volume.init(&card); - root.openRoot(&volume); + bool MediaFileReader::open(const char *filename) { + root = CardReader::getroot(); return file.open(&root, filename, O_READ); } diff --git a/Marlin/src/lcd/extui/lib/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 similarity index 86% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/media_file_reader.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/media_file_reader.h index fcaa610e8bdb..eb76bb9b2b2c 100644 --- a/Marlin/src/lcd/extui/lib/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 @@ -17,28 +17,26 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once -#include "../../../../../inc/MarlinConfigPre.h" +#include "../../../../inc/MarlinConfigPre.h" #if ENABLED(SDSUPPORT) - #include "../../../../../sd/SdFile.h" - #include "../../../../../sd/cardreader.h" + #include "../../../../sd/SdFile.h" + #include "../../../../sd/cardreader.h" #endif class MediaFileReader { private: #if ENABLED(SDSUPPORT) - Sd2Card card; - SdVolume volume; - SdFile root, file; + SdFile root, file; #endif public: - bool open(const char* filename); + bool open(const char *filename); int16_t read(void *buff, size_t bytes); uint32_t size(); void rewind(); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/advanced_settings.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/advanced_settings.cpp new file mode 100644 index 000000000000..40ec16a9dfe6 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/advanced_settings.cpp @@ -0,0 +1,136 @@ +/***************************** + * bio_advanced_settings.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 FTDI_BIO_ADVANCED_SETTINGS_MENU + +using namespace FTDI; +using namespace Theme; + +void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { + if (what & BACKGROUND) { + CommandProcessor cmd; + cmd.cmd(CLEAR_COLOR_RGB(Theme::bg_color)) + .cmd(CLEAR(true,true,true)); + } + + if (what & FOREGROUND) { + CommandProcessor cmd; + cmd.colors(normal_btn) + .font(Theme::font_medium) + #define GRID_ROWS 9 + #define GRID_COLS 2 + + .tag(2) .button(BTN_POS(1,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_DISPLAY_MENU)) + .enabled( + #if HAS_TRINAMIC_CONFIG + 1 + #endif + ) + .tag(3) .button(BTN_POS(1,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_TMC_CURRENT)) + .enabled( + #if HAS_TRINAMIC_CONFIG + 1 + #endif + ) + .tag(4) .button(BTN_POS(1,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_TMC_HOMING_THRS)) + .tag(5) .button(BTN_POS(1,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_LCD_ENDSTOPS)) + .enabled( + #if HAS_MULTI_HOTEND + 1 + #endif + ) + .tag(6) .button(BTN_POS(1,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_OFFSETS_MENU)) + + + .tag(7) .button(BTN_POS(2,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_STEPS_PER_MM)) + .tag(8) .button(BTN_POS(2,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_VELOCITY)) + .tag(9) .button(BTN_POS(2,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_ACCELERATION)) + #if HAS_JUNCTION_DEVIATION + .tag(10) .button(BTN_POS(2,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_JUNCTION_DEVIATION)) + #else + .tag(10) .button(BTN_POS(2,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_JERK)) + #endif + .enabled( + #if ENABLED(BACKLASH_GCODE) + 1 + #endif + ) + .tag(11) .button(BTN_POS(2,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_BACKLASH)) + .enabled( + #if ENABLED(LIN_ADVANCE) + 1 + #endif + ) + .tag(12) .button(BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_LINEAR_ADVANCE)) + .tag(13) .button(BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_INTERFACE)) + .tag(14) .button(BTN_POS(1,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_RESTORE_DEFAULTS)) + .colors(action_btn) + .tag(1). button( BTN_POS(1,9), BTN_SIZE(2,1), GET_TEXT_F(MSG_BUTTON_DONE)); + #undef GRID_COLS + #undef GRID_ROWS + } +} + +bool AdvancedSettingsMenu::onTouchEnd(uint8_t tag) { + using namespace ExtUI; + + switch (tag) { + case 1: SaveSettingsDialogBox::promptToSaveSettings(); break; + case 2: GOTO_SCREEN(DisplayTuningScreen); break; + #if HAS_TRINAMIC_CONFIG + case 3: GOTO_SCREEN(StepperCurrentScreen); break; + case 4: GOTO_SCREEN(StepperBumpSensitivityScreen); break; + #endif + case 5: GOTO_SCREEN(EndstopStatesScreen); break; + #if HAS_MULTI_HOTEND + case 6: GOTO_SCREEN(NozzleOffsetScreen); break; + #endif + + case 7: GOTO_SCREEN(StepsScreen); break; + case 8: GOTO_SCREEN(MaxVelocityScreen); break; + case 9: GOTO_SCREEN(DefaultAccelerationScreen); break; + case 10: + #if HAS_JUNCTION_DEVIATION + GOTO_SCREEN(JunctionDeviationScreen); + #else + GOTO_SCREEN(JerkScreen); + #endif + break; + #if ENABLED(BACKLASH_GCODE) + case 11: GOTO_SCREEN(BacklashCompensationScreen); break; + #endif + #if ENABLED(LIN_ADVANCE) + case 12: GOTO_SCREEN(LinearAdvanceScreen); break; + #endif + case 13: GOTO_SCREEN(InterfaceSettingsScreen); break; + case 14: GOTO_SCREEN(RestoreFailsafeDialogBox); break; + + default: + return false; + } + return true; +} + +#endif // FTDI_BIO_ADVANCED_SETTINGS_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/advanced_settings.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/advanced_settings.h new file mode 100644 index 000000000000..29a21fe5d992 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/advanced_settings.h @@ -0,0 +1,32 @@ +/*************************** + * bio_advanced_settings.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 FTDI_BIO_ADVANCED_SETTINGS_MENU +#define FTDI_BIO_ADVANCED_SETTINGS_MENU_CLASS AdvancedSettingsMenu + +class AdvancedSettingsMenu : public BaseScreen, public CachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchEnd(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_e.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_e.cpp new file mode 100644 index 000000000000..a5511f94b9eb --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_e.cpp @@ -0,0 +1,56 @@ +/**************************** + * bio_confirm_home_xyz.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 FTDI_BIO_CONFIRM_HOME_E + +using namespace FTDI; + +void BioConfirmHomeE::onRedraw(draw_mode_t) { + drawMessage(GET_TEXT_F(MSG_HOME_E_WARNING)); + drawYesNoButtons(1); +} + +bool BioConfirmHomeE::onTouchEnd(uint8_t tag) { + switch (tag) { + case 1: + #if defined(AXIS_LEVELING_COMMANDS) && defined(PARK_AND_RELEASE_COMMANDS) + SpinnerDialogBox::enqueueAndWait(F( + "G28 E\n" + AXIS_LEVELING_COMMANDS "\n" + PARK_AND_RELEASE_COMMANDS + )); + #endif + current_screen.forget(); + break; + case 2: + GOTO_SCREEN(StatusScreen); + break; + default: + return DialogBoxBaseClass::onTouchEnd(tag); + } + return true; +} + +#endif // FTDI_BIO_CONFIRM_HOME_E diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_e.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_e.h new file mode 100644 index 000000000000..151b784b935b --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_e.h @@ -0,0 +1,32 @@ +/**************************** + * bio_confirm_home_e.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 FTDI_BIO_CONFIRM_HOME_E +#define FTDI_BIO_CONFIRM_HOME_E_CLASS BioConfirmHomeE + +class BioConfirmHomeE : public DialogBoxBaseClass, 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/bioprinter/confirm_home_xyz.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_xyz.cpp new file mode 100644 index 000000000000..e34df42b84d3 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_xyz.cpp @@ -0,0 +1,55 @@ +/**************************** + * bio_confirm_home_xyz.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 FTDI_BIO_CONFIRM_HOME_XYZ + +using namespace FTDI; + +void BioConfirmHomeXYZ::onRedraw(draw_mode_t) { + drawMessage(GET_TEXT_F(MSG_HOME_XYZ_WARNING)); + drawYesNoButtons(1); +} + +bool BioConfirmHomeXYZ::onTouchEnd(uint8_t tag) { + switch (tag) { + case 1: + #ifdef PARK_AND_RELEASE_COMMANDS + SpinnerDialogBox::enqueueAndWait(F( + "G28\n" + PARK_AND_RELEASE_COMMANDS + )); + #endif + current_screen.forget(); + break; + case 2: + GOTO_SCREEN(StatusScreen); + break; + default: + return DialogBoxBaseClass::onTouchEnd(tag); + } + return true; +} + +#endif // FTDI_BIO_CONFIRM_HOME_XYZ diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_xyz.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_xyz.h new file mode 100644 index 000000000000..d8cb1cdb6742 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_xyz.h @@ -0,0 +1,32 @@ +/************************** + * bio_confirm_home_xyz.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 FTDI_BIO_CONFIRM_HOME_XYZ +#define FTDI_BIO_CONFIRM_HOME_XYZ_CLASS BioConfirmHomeXYZ + +class BioConfirmHomeXYZ : public DialogBoxBaseClass, 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/bioprinter/main_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/main_menu.cpp new file mode 100644 index 000000000000..adc84dfa25ff --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/main_menu.cpp @@ -0,0 +1,87 @@ +/********************* + * bio_main_menu.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 FTDI_BIO_MAIN_MENU + +using namespace FTDI; +using namespace Theme; + +void MainMenu::onRedraw(draw_mode_t what) { + #define GRID_ROWS 10 + #define GRID_COLS 2 + + if (what & BACKGROUND) { + CommandProcessor cmd; + cmd.cmd(CLEAR_COLOR_RGB(Theme::bg_color)) + .cmd(CLEAR(true,true,true)) + .tag(0); + } + + 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)) + .colors(normal_btn) + .font(font_medium) + .tag(2).button(BTN_POS(1,2), BTN_SIZE(2,1), GET_TEXT_F(MSG_MOVE_TO_HOME)) + .tag(3).button(BTN_POS(1,3), BTN_SIZE(2,1), GET_TEXT_F(MSG_RAISE_PLUNGER)) + .tag(4).button(BTN_POS(1,4), BTN_SIZE(2,1), GET_TEXT_F(MSG_RELEASE_XY_AXIS)) + .tag(5).button(BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_AUTOLEVEL_X_AXIS)) + .tag(6).button(BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_BED_TEMPERATURE)) + .tag(7).button(BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_INTERFACE)) + .tag(8).button(BTN_POS(1,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_ADVANCED_SETTINGS)) + .tag(9).button(BTN_POS(1,9), BTN_SIZE(2,1), GET_TEXT_F(MSG_INFO_MENU)) + .colors(action_btn) + .tag(1).button(BTN_POS(1,10), BTN_SIZE(2,1), GET_TEXT_F(MSG_BUTTON_DONE)); + } + + #undef GRID_COLS + #undef GRID_ROWS +} + +bool MainMenu::onTouchEnd(uint8_t tag) { + using namespace ExtUI; + + const bool e_homed = isAxisPositionKnown(E0); + + switch (tag) { + case 1: SaveSettingsDialogBox::promptToSaveSettings(); break; + case 2: GOTO_SCREEN(BioConfirmHomeXYZ); break; + case 3: SpinnerDialogBox::enqueueAndWait(e_homed ? F("G0 E0 F120") : F("G112")); break; + case 4: StatusScreen::unlockMotors(); break; + #ifdef AXIS_LEVELING_COMMANDS + case 5: SpinnerDialogBox::enqueueAndWait(F(AXIS_LEVELING_COMMANDS)); break; + #endif + case 6: GOTO_SCREEN(TemperatureScreen); break; + case 7: GOTO_SCREEN(InterfaceSettingsScreen); break; + case 8: GOTO_SCREEN(AdvancedSettingsMenu); break; + case 9: GOTO_SCREEN(AboutScreen); break; + default: + return false; + } + return true; +} + +#endif // FTDI_BIO_MAIN_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/main_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/main_menu.h new file mode 100644 index 000000000000..fdf977fcbfd9 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/main_menu.h @@ -0,0 +1,32 @@ +/********************* + * bio_main_menu.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: . * + ****************************************************************************/ + +#pragma once + +#define FTDI_BIO_MAIN_MENU +#define FTDI_BIO_MAIN_MENU_CLASS MainMenu + +class MainMenu : public BaseScreen, public CachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchEnd(uint8_t tag); +}; 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 new file mode 100644 index 000000000000..86c700f235ac --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.cpp @@ -0,0 +1,147 @@ +/******************************* + * bio_printing_dialog_box.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 FTDI_BIO_PRINTING_DIALOG_BOX + +using namespace FTDI; +using namespace ExtUI; +using namespace Theme; + +#define GRID_COLS 2 +#define GRID_ROWS 9 + +void BioPrintingDialogBox::draw_status_message(draw_mode_t what, const char *message) { + if (what & BACKGROUND) { + CommandProcessor cmd; + cmd.cmd(COLOR_RGB(bg_text_enabled)) + .tag(0); + draw_text_box(cmd, BTN_POS(1,2), BTN_SIZE(2,2), message, OPT_CENTER, font_large); + } +} + +void BioPrintingDialogBox::draw_progress(draw_mode_t what) { + if (what & FOREGROUND) { + CommandProcessor cmd; + cmd.font(font_large) + .text(BTN_POS(1,1), BTN_SIZE(2,2), isPrinting() ? F("Printing...") : F("Finished.")) + .tag(1) + .font(font_xlarge); + + draw_circular_progress(cmd, BTN_POS(1,4), BTN_SIZE(2,3), getProgress_percent(), theme_dark, theme_darkest); + } +} + +void BioPrintingDialogBox::draw_time_remaining(draw_mode_t what) { + if (what & FOREGROUND) { + const uint32_t elapsed = getProgress_seconds_elapsed(); + const uint8_t hrs = elapsed/3600; + const uint8_t min = (elapsed/60)%60; + + char time_str[10]; + sprintf_P(time_str, PSTR("%02dh %02dm"), hrs, min); + + CommandProcessor cmd; + cmd.font(font_large) + .text(BTN_POS(1,7), BTN_SIZE(2,2), time_str); + } +} + +void BioPrintingDialogBox::draw_interaction_buttons(draw_mode_t what) { + if (what & FOREGROUND) { + CommandProcessor cmd; + cmd.colors(normal_btn) + .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) + .tag(3) + .colors(isPrinting() ? normal_btn : action_btn) + .button(BTN_POS(2,9), BTN_SIZE(1,1), isPrinting() ? F("Cancel") : F("Back")); + } +} + +void BioPrintingDialogBox::onRedraw(draw_mode_t what) { + if (what & FOREGROUND) { + draw_progress(FOREGROUND); + draw_time_remaining(FOREGROUND); + draw_interaction_buttons(FOREGROUND); + } +} + +bool BioPrintingDialogBox::onTouchEnd(uint8_t tag) { + switch (tag) { + case 1: GOTO_SCREEN(FeedratePercentScreen); break; + case 2: GOTO_SCREEN(TuneMenu); break; + case 3: + if (isPrinting()) + GOTO_SCREEN(ConfirmAbortPrintDialogBox); + else + GOTO_SCREEN(StatusScreen); + break; + default: return false; + } + return true; +} + +void BioPrintingDialogBox::setStatusMessage(progmem_str message) { + char buff[strlen_P((const char*)message)+1]; + strcpy_P(buff, (const char*) message); + setStatusMessage(buff); +} + +void BioPrintingDialogBox::setStatusMessage(const char *message) { + CommandProcessor cmd; + cmd.cmd(CMD_DLSTART) + .cmd(CLEAR_COLOR_RGB(bg_color)) + .cmd(CLEAR(true,true,true)); + + draw_status_message(BACKGROUND, message); + draw_progress(BACKGROUND); + draw_time_remaining(BACKGROUND); + draw_interaction_buttons(BACKGROUND); + storeBackground(); + + #if ENABLED(TOUCH_UI_DEBUG) + SERIAL_ECHO_MSG("New status message: ", message); + #endif + + if (AT_SCREEN(BioPrintingDialogBox)) + current_screen.onRefresh(); +} + +void BioPrintingDialogBox::onIdle() { + reset_menu_timeout(); + if (refresh_timer.elapsed(STATUS_UPDATE_INTERVAL)) { + onRefresh(); + refresh_timer.start(); + } + BaseScreen::onIdle(); +} + +void BioPrintingDialogBox::show() { + GOTO_SCREEN(BioPrintingDialogBox); +} + +#endif // FTDI_BIO_PRINTING_DIALOG_BOX diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.h new file mode 100644 index 000000000000..aebbd16128aa --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.h @@ -0,0 +1,44 @@ +/***************************** + * bio_printing_dialog_box.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 FTDI_BIO_PRINTING_DIALOG_BOX +#define FTDI_BIO_PRINTING_DIALOG_BOX_CLASS BioPrintingDialogBox + +class BioPrintingDialogBox : public BaseScreen, public CachedScreen { + private: + static void draw_status_message(draw_mode_t, const char * const); + static void draw_progress(draw_mode_t); + static void draw_time_remaining(draw_mode_t); + static void draw_interaction_buttons(draw_mode_t); + public: + static void onRedraw(draw_mode_t); + + static void show(); + + static void setStatusMessage(const char *); + static void setStatusMessage(progmem_str); + + static void onIdle(); + static bool onTouchEnd(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/screens.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/screens.h new file mode 100644 index 000000000000..7294c4aa0b10 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/screens.h @@ -0,0 +1,105 @@ +/************* + * screens.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: . * + ****************************************************************************/ + +/********************************* DL CACHE SLOTS ******************************/ + +// In order to reduce SPI traffic, we cache display lists (DL) in RAMG. This +// is done using the CLCD::DLCache class, which takes a unique ID for each +// cache location. These IDs are defined here: + +enum { + STATUS_SCREEN_CACHE, + MENU_SCREEN_CACHE, + TUNE_SCREEN_CACHE, + ALERT_BOX_CACHE, + SPINNER_CACHE, + ADVANCED_SETTINGS_SCREEN_CACHE, + TEMPERATURE_SCREEN_CACHE, + STEPS_SCREEN_CACHE, + MAX_FEEDRATE_SCREEN_CACHE, + MAX_VELOCITY_SCREEN_CACHE, + MAX_ACCELERATION_SCREEN_CACHE, + DEFAULT_ACCELERATION_SCREEN_CACHE, + FLOW_PERCENT_SCREEN_CACHE, + ZOFFSET_SCREEN_CACHE, + STEPPER_CURRENT_SCREEN_CACHE, + STEPPER_BUMP_SENSITIVITY_SCREEN_CACHE, + PRINTING_SCREEN_CACHE, + FILES_SCREEN_CACHE, + INTERFACE_SETTINGS_SCREEN_CACHE, + INTERFACE_SOUNDS_SCREEN_CACHE, + LOCK_SCREEN_CACHE, + DISPLAY_TIMINGS_SCREEN_CACHE +}; + +// To save MCU RAM, the status message is "baked" in to the status screen +// cache, so we reserve a large chunk of memory for the DL cache + +#define STATUS_SCREEN_DL_SIZE 4096 +#define ALERT_BOX_DL_SIZE 3072 +#define SPINNER_DL_SIZE 3072 +#define FILE_SCREEN_DL_SIZE 4160 +#define PRINTING_SCREEN_DL_SIZE 2048 + +/************************* MENU SCREEN DECLARATIONS *************************/ + +#include "../generic/base_screen.h" +#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" +#include "../generic/restore_failsafe_dialog_box.h" +#include "../generic/save_settings_dialog_box.h" +#include "../generic/confirm_start_print_dialog_box.h" +#include "../generic/confirm_abort_print_dialog_box.h" +#include "../generic/confirm_user_request_alert_box.h" +#include "../generic/touch_calibration_screen.h" +#include "../generic/move_axis_screen.h" +#include "../generic/steps_screen.h" +#include "../generic/feedrate_percent_screen.h" +#include "../generic/max_velocity_screen.h" +#include "../generic/max_acceleration_screen.h" +#include "../generic/default_acceleration_screen.h" +#include "../generic/temperature_screen.h" +#include "../generic/interface_sounds_screen.h" +#include "../generic/interface_settings_screen.h" +#include "../generic/lock_screen.h" +#include "../generic/endstop_state_screen.h" +#include "../generic/display_tuning_screen.h" +#include "../generic/media_player_screen.h" +#include "../generic/statistics_screen.h" +#include "../generic/stepper_current_screen.h" +#include "../generic/stepper_bump_sensitivity_screen.h" +#include "../generic/leveling_menu.h" +#include "../generic/z_offset_screen.h" +#include "../generic/files_screen.h" + +#include "bio_status_screen.h" +#include "bio_main_menu.h" +#include "bio_tune_menu.h" +#include "bio_advanced_settings.h" +#include "bio_printing_dialog_box.h" +#include "bio_confirm_home_xyz.h" +#include "bio_confirm_home_e.h" diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/status_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/status_screen.cpp new file mode 100644 index 000000000000..1382a13bf86e --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/status_screen.cpp @@ -0,0 +1,376 @@ +/************************* + * bio_status_screen.cpp * + *************************/ + +/**************************************************************************** + * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2019 - Cocoa Press * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#include "../config.h" +#include "../screens.h" + +#ifdef FTDI_BIO_STATUS_SCREEN + +#if ENABLED(TOUCH_UI_PORTRAIT) + #include "ui_portrait.h" +#else + #include "ui_landscape.h" +#endif + +#define GRID_COLS 2 +#define GRID_ROWS 9 + +#define POLY(A) PolyUI::poly_reader_t(A, sizeof(A)/sizeof(A[0])) + +const uint8_t shadow_depth = 5; +const float max_speed = 1.00; +const float min_speed = 0.02; +const float emax_speed = 2.00; +const float emin_speed = 0.70; + +using namespace FTDI; +using namespace Theme; +using namespace ExtUI; + +float StatusScreen::increment; +bool StatusScreen::jog_xy; +bool StatusScreen::fine_motion; + +void StatusScreen::unlockMotors() { + injectCommands_P(PSTR("M84 XY")); + jog_xy = false; +} + +void StatusScreen::draw_temperature(draw_mode_t what) { + CommandProcessor cmd; + PolyUI ui(cmd, what); + + int16_t x, y, h, v; + + cmd.tag(15); + + if (what & BACKGROUND) { + cmd.cmd(COLOR_RGB(bg_color)); + + // The LulzBot Bio shows the temperature for + // the bed. + + #if ENABLED(TOUCH_UI_PORTRAIT) + // Draw touch surfaces + ui.bounds(POLY(target_temp), x, y, h, v); + cmd.rectangle(x, y, h, v); + ui.bounds(POLY(actual_temp), x, y, h, v); + cmd.rectangle(x, y, h, v); + #else + ui.bounds(POLY(bed_temp), x, y, h, v); + cmd.rectangle(x, y, h, v); + #endif + ui.bounds(POLY(bed_icon), x, y, h, v); + cmd.rectangle(x, y, h, v); + + // Draw bed icon + cmd.cmd(BITMAP_SOURCE(Bed_Heat_Icon_Info)) + .cmd(BITMAP_LAYOUT(Bed_Heat_Icon_Info)) + .cmd(BITMAP_SIZE (Bed_Heat_Icon_Info)) + .cmd(COLOR_RGB(shadow_rgb)) + .icon (x + 2, y + 2, h, v, Bed_Heat_Icon_Info, icon_scale * 2) + .cmd(COLOR_RGB(bg_text_enabled)) + .icon (x, y, h, v, Bed_Heat_Icon_Info, icon_scale * 2); + + #if ENABLED(TOUCH_UI_USE_UTF8) + load_utf8_bitmaps(cmd); // Restore font bitmap handles + #endif + } + + if (what & FOREGROUND) { + char str[15]; + cmd.cmd(COLOR_RGB(bg_text_enabled)); + cmd.font(font_medium); + + #if ENABLED(TOUCH_UI_PORTRAIT) + if (!isHeaterIdle(BED) && getTargetTemp_celsius(BED) > 0) + format_temp(str, getTargetTemp_celsius(BED)); + else + strcpy_P(str, GET_TEXT(MSG_BED)); + + ui.bounds(POLY(target_temp), x, y, h, v); + cmd.text(x, y, h, v, str); + + format_temp(str, getActualTemp_celsius(BED)); + ui.bounds(POLY(actual_temp), x, y, h, v); + cmd.text(x, y, h, v, str); + #else + if (!isHeaterIdle(BED) && getTargetTemp_celsius(BED) > 0) + format_temp_and_temp(str, getActualTemp_celsius(BED), getTargetTemp_celsius(BED)); + else + format_temp_and_idle(str, getActualTemp_celsius(BED)); + + ui.bounds(POLY(bed_temp), x, y, h, v); + cmd.text(x, y, h, v, str); + #endif + } +} + +void StatusScreen::draw_syringe(draw_mode_t what) { + int16_t x, y, h, v; + const float fill_level = ( + #ifdef E_MAX_POS + 1.0 - min(1.0, max(0.0, getAxisPosition_mm(E0) / E_MAX_POS)) + #else + 0.75 + #endif + ); + const bool e_homed = TERN1(TOUCH_UI_LULZBOT_BIO, isAxisPositionKnown(E0)); + + CommandProcessor cmd; + PolyUI ui(cmd, what); + + if (what & BACKGROUND) { + // Paint the shadow for the syringe + ui.color(shadow_rgb); + ui.shadow(POLY(syringe_outline), shadow_depth); + } + + if (what & FOREGROUND && e_homed) { + // Paint the syringe icon + ui.color(syringe_rgb); + ui.fill(POLY(syringe_outline)); + + ui.color(fluid_rgb); + ui.bounds(POLY(syringe_fluid), x, y, h, v); + cmd.cmd(SAVE_CONTEXT()); + cmd.cmd(SCISSOR_XY(x,y + v * (1.0 - fill_level))); + cmd.cmd(SCISSOR_SIZE(h, v * fill_level)); + ui.fill(POLY(syringe_fluid), false); + cmd.cmd(RESTORE_CONTEXT()); + + ui.color(stroke_rgb); + ui.fill(POLY(syringe)); + } +} + +void StatusScreen::draw_arrows(draw_mode_t what) { + const bool e_homed = TERN1(TOUCH_UI_LULZBOT_BIO, isAxisPositionKnown(E0)), + z_homed = isAxisPositionKnown(Z); + + CommandProcessor cmd; + PolyUI ui(cmd, what); + + ui.button_fill (fill_rgb); + ui.button_stroke(stroke_rgb, 28); + ui.button_shadow(shadow_rgb, shadow_depth); + + constexpr uint8_t style = PolyUI::REGULAR; + + if ((what & BACKGROUND) || jog_xy) { + ui.button(1, POLY(x_neg), style); + ui.button(2, POLY(x_pos), style); + ui.button(3, POLY(y_neg), style); + ui.button(4, POLY(y_pos), style); + } + + if ((what & BACKGROUND) || z_homed) { + ui.button(5, POLY(z_neg), style); + ui.button(6, POLY(z_pos), style); + } + + if ((what & BACKGROUND) || e_homed) { + ui.button(7, POLY(e_neg), style); + ui.button(8, POLY(e_pos), style); + } +} + +void StatusScreen::draw_fine_motion(draw_mode_t what) { + int16_t x, y, h, v; + CommandProcessor cmd; + PolyUI ui(cmd, what); + + cmd.font( + #if ENABLED(TOUCH_UI_PORTRAIT) + font_medium + #else + font_small + #endif + ) + .tag(16); + + if (what & BACKGROUND) { + ui.bounds(POLY(fine_label), x, y, h, v); + cmd.cmd(COLOR_RGB(bg_text_enabled)) + .text(x, y, h, v, GET_TEXT_F(MSG_FINE_MOTION)); + } + + if (what & FOREGROUND) { + ui.bounds(POLY(fine_toggle), x, y, h, v); + cmd.colors(ui_toggle) + .toggle2(x, y, h, v, GET_TEXT_F(MSG_NO), GET_TEXT_F(MSG_YES), fine_motion); + } +} + +void StatusScreen::draw_overlay_icons(draw_mode_t what) { + const bool e_homed = TERN1(TOUCH_UI_LULZBOT_BIO, isAxisPositionKnown(E0)), + z_homed = isAxisPositionKnown(Z); + + CommandProcessor cmd; + PolyUI ui(cmd, what); + + if (what & FOREGROUND) { + ui.button_fill (fill_rgb); + ui.button_stroke(stroke_rgb, 28); + ui.button_shadow(shadow_rgb, shadow_depth); + + constexpr uint8_t style = PolyUI::REGULAR; + if (!jog_xy) ui.button(12, POLY(padlock), style); + if (!e_homed) ui.button(13, POLY(home_e), style); + if (!z_homed) ui.button(14, POLY(home_z), style); + } +} + +void StatusScreen::draw_buttons(draw_mode_t what) { + int16_t x, y, h, v; + + const bool has_media = isMediaInserted() && !isPrintingFromMedia(); + + CommandProcessor cmd; + PolyUI ui(cmd, what); + + ui.bounds(POLY(usb_btn), x, y, h, v); + cmd.font(font_medium) + .colors(normal_btn) + .enabled(has_media) + .colors(has_media ? action_btn : normal_btn) + .tag(9).button(x, y, h, v, + isPrintingFromMedia() ? + GET_TEXT_F(MSG_PRINTING) : + GET_TEXT_F(MSG_BUTTON_MEDIA) + ); + + ui.bounds(POLY(menu_btn), x, y, h, v); + cmd.colors(!has_media ? action_btn : normal_btn).tag(10).button(x, y, h, v, GET_TEXT_F(MSG_BUTTON_MENU)); +} + +void StatusScreen::loadBitmaps() { + // Load the bitmaps for the status screen + constexpr uint32_t base = ftdi_memory_map::RAM_G; + CLCD::mem_write_pgm(base + Bed_Heat_Icon_Info.RAMG_offset, Bed_Heat_Icon, sizeof(Bed_Heat_Icon)); + + // Load fonts for internationalization + #if ENABLED(TOUCH_UI_USE_UTF8) + load_utf8_data(base + UTF8_FONT_OFFSET); + #endif +} + +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); + } + + draw_syringe(what); + draw_temperature(what); + draw_arrows(what); + draw_overlay_icons(what); + draw_buttons(what); + draw_fine_motion(what); +} + +bool StatusScreen::onTouchStart(uint8_t) { + increment = 0; + return true; +} + +bool StatusScreen::onTouchEnd(uint8_t tag) { + switch (tag) { + case 1: + case 2: + case 3: + case 4: + case 12: + if (!jog_xy) { + jog_xy = true; + injectCommands_P(PSTR("M17")); + } + jog({ 0, 0, 0 }); + break; + case 5: + case 6: + jog({ 0, 0, 0 }); + break; + case 9: GOTO_SCREEN(FilesScreen); break; + case 10: GOTO_SCREEN(MainMenu); break; + case 13: GOTO_SCREEN(BioConfirmHomeE); break; + case 14: SpinnerDialogBox::enqueueAndWait(F("G28Z")); break; + case 15: GOTO_SCREEN(TemperatureScreen); break; + case 16: fine_motion = !fine_motion; break; + default: return false; + } + // If a passcode is enabled, the LockScreen will prevent the + // user from proceeding. + LockScreen::check_passcode(); + return true; +} + +bool StatusScreen::onTouchHeld(uint8_t tag) { + if (tag >= 1 && tag <= 4 && !jog_xy) return false; + const float s = min_speed + (fine_motion ? 0 : (max_speed - min_speed) * sq(increment)); + switch (tag) { + case 1: jog({-s, 0, 0}); break; + case 2: jog({ s, 0, 0}); break; + case 4: jog({ 0, -s, 0}); break; // NOTE: Y directions inverted because bed rather than needle moves + case 3: jog({ 0, s, 0}); break; + case 5: jog({ 0, 0, -s}); break; + case 6: jog({ 0, 0, s}); break; + case 7: case 8: + { + if (ExtUI::isMoving()) return false; + const feedRate_t feedrate = emin_speed + (fine_motion ? 0 : (emax_speed - emin_speed) * sq(increment)); + const float increment = 0.25 * feedrate * (tag == 7 ? -1 : 1); + MoveAxisScreen::setManualFeedrate(E0, feedrate); + UI_INCREMENT(AxisPosition_mm, E0); + current_screen.onRefresh(); + break; + } + default: + return false; + } + increment = min(1.0f, increment + 0.1f); + return false; +} + +void StatusScreen::setStatusMessage(progmem_str pstr) { + BioPrintingDialogBox::setStatusMessage(pstr); +} + +void StatusScreen::setStatusMessage(const char * const str) { + BioPrintingDialogBox::setStatusMessage(str); +} + +void StatusScreen::onIdle() { + reset_menu_timeout(); + if (refresh_timer.elapsed(STATUS_UPDATE_INTERVAL)) { + if (!EventLoop::is_touch_held()) + onRefresh(); + if (isPrintingFromMedia()) + BioPrintingDialogBox::show(); + refresh_timer.start(); + } +} + +#endif // FTDI_BIO_STATUS_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/status_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/status_screen.h new file mode 100644 index 000000000000..a3bbb60f6c3b --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/status_screen.h @@ -0,0 +1,56 @@ +/************************* + * bio_status_screen.cpp * + *************************/ + +/**************************************************************************** + * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2019 - Cocoa Press * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#pragma once + +#define FTDI_BIO_STATUS_SCREEN +#define FTDI_BIO_STATUS_SCREEN_CLASS StatusScreen + +class StatusScreen : public BaseScreen, public CachedScreen { + private: + static float increment; + static bool jog_xy; + static bool fine_motion; + + static void draw_progress(draw_mode_t what); + static void draw_temperature(draw_mode_t what); + static void draw_syringe(draw_mode_t what); + static void draw_arrows(draw_mode_t what); + static void draw_overlay_icons(draw_mode_t what); + static void draw_fine_motion(draw_mode_t what); + static void draw_buttons(draw_mode_t what); + public: + static void loadBitmaps(); + static void unlockMotors(); + + static void setStatusMessage(const char *); + static void setStatusMessage(progmem_str); + + static void onRedraw(draw_mode_t); + + static bool onTouchStart(uint8_t tag); + 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/bioprinter/tune_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/tune_menu.cpp new file mode 100644 index 000000000000..48eff0a66149 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/tune_menu.cpp @@ -0,0 +1,78 @@ +/********************* + * bio_tune_menu.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 FTDI_BIO_TUNE_MENU + +using namespace FTDI; +using namespace Theme; +using namespace ExtUI; + +void TuneMenu::onRedraw(draw_mode_t what) { + #define GRID_ROWS 8 + #define GRID_COLS 2 + + if (what & BACKGROUND) { + CommandProcessor cmd; + cmd.cmd(CLEAR_COLOR_RGB(bg_color)) + .cmd(CLEAR(true,true,true)) + .cmd(COLOR_RGB(bg_text_enabled)) + .tag(0) + .font(font_large) + .text( BTN_POS(1,1), BTN_SIZE(2,1), GET_TEXT_F(MSG_PRINT_MENU)); + } + + if (what & FOREGROUND) { + CommandProcessor cmd; + cmd.colors(normal_btn) + .font(font_medium) + .enabled( isPrinting()).tag(2).button(BTN_POS(1,2), BTN_SIZE(2,1), GET_TEXT_F(MSG_PRINT_SPEED)) + .tag(3).button(BTN_POS(1,3), BTN_SIZE(2,1), GET_TEXT_F(MSG_BED_TEMPERATURE)) + .enabled(TERN_(BABYSTEPPING, true)) + .tag(4).button(BTN_POS(1,4), BTN_SIZE(2,1), GET_TEXT_F(MSG_NUDGE_NOZZLE)) + .enabled(!isPrinting()).tag(5).button(BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_MOVE_TO_HOME)) + .enabled(!isPrinting()).tag(6).button(BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_RAISE_PLUNGER)) + .enabled(!isPrinting()).tag(7).button(BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_RELEASE_XY_AXIS)) + .colors(action_btn) .tag(1).button(BTN_POS(1,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_BUTTON_DONE)); + } + #undef GRID_COLS + #undef GRID_ROWS +} + +bool TuneMenu::onTouchEnd(uint8_t tag) { + switch (tag) { + case 1: GOTO_PREVIOUS(); break; + case 2: GOTO_SCREEN(FeedratePercentScreen); break; + case 3: GOTO_SCREEN(TemperatureScreen); break; + case 4: GOTO_SCREEN(NudgeNozzleScreen); break; + case 5: GOTO_SCREEN(BioConfirmHomeXYZ); break; + case 6: SpinnerDialogBox::enqueueAndWait(F("G0 E0 F120")); break; + case 7: StatusScreen::unlockMotors(); break; + default: + return false; + } + return true; +} + +#endif // FTDI_BIO_TUNE_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/tune_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/tune_menu.h new file mode 100644 index 000000000000..52fe694f37bb --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/tune_menu.h @@ -0,0 +1,35 @@ +/******************* + * bio_tune_menu.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 FTDI_BIO_TUNE_MENU +#define FTDI_BIO_TUNE_MENU_CLASS TuneMenu + +class TuneMenu : public BaseScreen, public CachedScreen { + private: + static void pausePrint(); + static void resumePrint(); + public: + static void onRedraw(draw_mode_t); + static bool onTouchEnd(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/ui_landscape.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/ui_landscape.h new file mode 100644 index 000000000000..4faddc64b1d9 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/ui_landscape.h @@ -0,0 +1,59 @@ + +/**************************************************************************** + * 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 z_neg[] = {0x7950, 0x51EA, 0x824E, 0x51EA, 0x824E, 0x71E2, 0x86CD, 0x71E2, 0x7DCF, 0x81DF, 0x74D1, 0x71E2, 0x7950, 0x71E2, 0x7950, 0x51EA}; +const PROGMEM uint16_t z_pos[] = {0x7950, 0x41EE, 0x824E, 0x41EE, 0x824E, 0x21F5, 0x86CD, 0x21F5, 0x7DCF, 0x11F9, 0x74D0, 0x21F5, 0x7950, 0x21F5, 0x7950, 0x41EE}; +const PROGMEM uint16_t y_neg[] = {0x3479, 0x56CF, 0x3EC6, 0x56CF, 0x3747, 0x7281, 0x3C6D, 0x7281, 0x2E61, 0x8059, 0x27D4, 0x7281, 0x2CFA, 0x7281, 0x3479, 0x56CF}; +const PROGMEM uint16_t y_pos[] = {0x3BF9, 0x3B1D, 0x4645, 0x3B1D, 0x4DC4, 0x1F6B, 0x52EB, 0x1F6B, 0x4C5E, 0x1192, 0x3E52, 0x1F6B, 0x4378, 0x1F6B, 0x3BF9, 0x3B1D}; +const PROGMEM uint16_t x_neg[] = {0x350E, 0x4209, 0x314E, 0x4FE2, 0x1CB5, 0x4FE2, 0x1AD6, 0x56CF, 0x1449, 0x48F6, 0x2255, 0x3B1D, 0x2075, 0x4209, 0x350E, 0x4209}; +const PROGMEM uint16_t x_pos[] = {0x498C, 0x4209, 0x45CC, 0x4FE2, 0x5A65, 0x4FE2, 0x5885, 0x56CF, 0x6691, 0x48F6, 0x6004, 0x3B1D, 0x5E25, 0x4209, 0x498C, 0x4209}; +const PROGMEM uint16_t syringe_fluid[] = {0xB4E9, 0x78BE, 0xBB12, 0x7C44, 0xBDE3, 0x7C44, 0xC426, 0x78BE, 0xC426, 0x250D, 0xB4E9, 0x250D, 0xB4E9, 0x78BE}; +const PROGMEM uint16_t syringe[] = {0xB8AD, 0x6BB1, 0xB8AD, 0x6E0C, 0xBE02, 0x6E0C, 0xBE02, 0x6BB1, 0xFFFF, 0xB8AD, 0x6248, 0xB8AD, 0x64A2, 0xBE02, 0x64A2, 0xBE02, 0x6248, 0xFFFF, 0xB8AD, 0x58DF, 0xB8AD, 0x5B39, 0xBE02, 0x5B39, 0xBE02, 0x58DF, 0xFFFF, 0xB8AD, 0x4F75, 0xB8AD, 0x51D0, 0xBE02, 0x51D0, 0xBE02, 0x4F75, 0xFFFF, 0xB8AD, 0x460C, 0xB8AD, 0x4866, 0xBE02, 0x4866, 0xBE02, 0x460C, 0xFFFF, 0xB8AD, 0x3CA3, 0xB8AD, 0x3EFD, 0xBE02, 0x3EFD, 0xBE02, 0x3CA3, 0xFFFF, 0xB8AD, 0x3339, 0xB8AD, 0x3594, 0xBE02, 0x3594, 0xBE02, 0x3339, 0xFFFF, 0xB396, 0x110A, 0xB396, 0x1818, 0xB995, 0x1818, 0xB995, 0x22AD, 0xB396, 0x22AD, 0xB396, 0x7ADA, 0xB995, 0x7E61, 0xB995, 0x88F5, 0xBB95, 0x88F5, 0xBB95, 0xA8B4, 0xBD94, 0xAC3B, 0xBD94, 0x88F5, 0xBF94, 0x88F5, 0xBF94, 0x7E61, 0xC593, 0x7ADA, 0xC593, 0x22AD, 0xBF94, 0x22AD, 0xBF94, 0x1818, 0xC593, 0x1818, 0xC593, 0x110A, 0xFFFF, 0xBB95, 0x1818, 0xBD94, 0x1818, 0xBD94, 0x22AD, 0xBB95, 0x22AD, 0xBB95, 0x1818, 0xFFFF, 0xB596, 0x2634, 0xC393, 0x2634, 0xC393, 0x7753, 0xBD94, 0x7ADA, 0xBB95, 0x7ADA, 0xB596, 0x7753, 0xB596, 0x2634}; +const PROGMEM uint16_t syringe_outline[] = {0xB396, 0x110A, 0xB396, 0x1818, 0xB995, 0x1818, 0xB995, 0x22AD, 0xB396, 0x22AD, 0xB396, 0x7ADA, 0xB995, 0x7E61, 0xB995, 0x88F5, 0xBB95, 0x88F5, 0xBB95, 0xA8B4, 0xBD94, 0xAC3B, 0xBD94, 0x88F5, 0xBF94, 0x88F5, 0xBF94, 0x7E61, 0xC593, 0x7ADA, 0xC593, 0x22AD, 0xBF94, 0x22AD, 0xBF94, 0x1818, 0xC593, 0x1818, 0xC593, 0x110A, 0xB396, 0x110A}; +const PROGMEM uint16_t padlock[] = {0x3FE3, 0x2A04, 0x3D34, 0x2AF9, 0x3AFF, 0x2D93, 0x397D, 0x316D, 0x38E8, 0x3626, 0x38E8, 0x3A14, 0x39B3, 0x3C8F, 0x3B50, 0x3C8F, 0x3C1C, 0x3A14, 0x3C1C, 0x363C, 0x3C6B, 0x33A9, 0x3D3A, 0x3193, 0x3E6C, 0x302D, 0x3FE3, 0x2FAA, 0x415A, 0x302D, 0x428C, 0x3192, 0x435B, 0x33A8, 0x43AB, 0x363C, 0x43AB, 0x4492, 0x38C3, 0x4492, 0x3741, 0x45AC, 0x36A1, 0x4856, 0x36A1, 0x5C41, 0x3741, 0x5EEC, 0x38C3, 0x6005, 0x4703, 0x6005, 0x4886, 0x5EEC, 0x4925, 0x5C41, 0x4925, 0x4856, 0x4886, 0x45AC, 0x4703, 0x4492, 0x46DE, 0x362B, 0x4649, 0x316D, 0x44C7, 0x2D92, 0x4292, 0x2AF9}; +const PROGMEM uint16_t home_z[] = {0x80BB, 0x2B43, 0x712C, 0x46B9, 0x750F, 0x46B9, 0x750F, 0x622F, 0x7CD7, 0x622F, 0x7CD7, 0x5474, 0x849F, 0x5474, 0x849F, 0x622F, 0x8C67, 0x622F, 0x8C67, 0x46B9, 0x904B, 0x46B9, 0x8A48, 0x3C1D, 0x8A48, 0x2ECD, 0x8664, 0x2ECD, 0x8664, 0x3540}; +const PROGMEM uint16_t usb_btn[] = {0x0558, 0xC0D6, 0x3BDB, 0xC0D6, 0x3BDB, 0xF431, 0x0558, 0xF431, 0x0558, 0xC0D6}; +const PROGMEM uint16_t menu_btn[] = {0x416B, 0xC0D6, 0x77EE, 0xC0D6, 0x77EE, 0xF431, 0x416B, 0xF431, 0x416B, 0xC0D6}; +const PROGMEM uint16_t e_pos[] = {0xE04E, 0x5E7B, 0xE94C, 0x5E7B, 0xE94C, 0x7E74, 0xEDCB, 0x7E74, 0xE4CD, 0x8E70, 0xDBCF, 0x7E74, 0xE04E, 0x7E74, 0xE04E, 0x5E7B}; +const PROGMEM uint16_t e_neg[] = {0xE04E, 0x4E7F, 0xE94C, 0x4E7F, 0xE94C, 0x2E87, 0xEDCB, 0x2E87, 0xE4CD, 0x1E8A, 0xDBCF, 0x2E87, 0xE04E, 0x2E87, 0xE04E, 0x4E7F}; +const PROGMEM uint16_t home_e[] = {0xD705, 0x3885, 0xC775, 0x53FB, 0xCB59, 0x53FB, 0xCB59, 0x6F71, 0xD321, 0x6F71, 0xD321, 0x61B6, 0xDAE9, 0x61B6, 0xDAE9, 0x6F71, 0xE2B1, 0x6F71, 0xE2B1, 0x53FB, 0xE695, 0x53FB, 0xE092, 0x495F, 0xE092, 0x3C0E, 0xDCAE, 0x3C0E, 0xDCAE, 0x4281}; +const PROGMEM uint16_t fine_label[] = {0x0D92, 0x9444, 0x5211, 0x9444, 0x5211, 0xA9EA, 0x0D92, 0xA9EA}; +const PROGMEM uint16_t fine_toggle[] = {0x56E7, 0x9444, 0x8007, 0x9444, 0x8007, 0xA9EA, 0x56E7, 0xA9EA}; +const PROGMEM uint16_t h1_temp[] = {0x9C2B, 0xDD3B, 0xBBDE, 0xDD3B, 0xBBDE, 0xFA57, 0x9C2B, 0xFA57}; +const PROGMEM uint16_t h1_label[] = {0x9C2B, 0xBE8F, 0xBBDC, 0xBE8F, 0xBBDC, 0xDBAA, 0x9C2B, 0xDBAA}; +const PROGMEM uint16_t h0_temp[] = {0x7BD0, 0xDD3B, 0x9B83, 0xDD3B, 0x9B83, 0xFA57, 0x7BD0, 0xFA57}; +const PROGMEM uint16_t h0_label[] = {0x7BD0, 0xBE8F, 0x9B83, 0xBE8F, 0x9B83, 0xDBAA, 0x7BD0, 0xDBAA}; +const PROGMEM uint16_t h2_temp[] = {0xBC86, 0xDD3B, 0xDC39, 0xDD3B, 0xDC39, 0xFA57, 0xBC86, 0xFA57}; +const PROGMEM uint16_t h2_label[] = {0xBC86, 0xBE8F, 0xDC37, 0xBE8F, 0xDC37, 0xDBAA, 0xBC86, 0xDBAA}; +const PROGMEM uint16_t h3_temp[] = {0xDCE2, 0xDD0D, 0xFC95, 0xDD0D, 0xFC95, 0xFA28, 0xDCE2, 0xFA28}; +const PROGMEM uint16_t h3_label[] = {0xDCE2, 0xBE60, 0xFC92, 0xBE60, 0xFC92, 0xDB7C, 0xDCE2, 0xDB7C}; +const PROGMEM uint16_t actual_temp[] = {0xCDF6, 0xD037, 0xF7CA, 0xD037, 0xF7CA, 0xF424, 0xCDF6, 0xF424}; +const PROGMEM uint16_t bed_icon[] = {0xCDF6, 0xA5CC, 0xF7CA, 0xA5CC, 0xF7CA, 0xC9B9, 0xCDF6, 0xC9B9}; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/ui_portrait.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/ui_portrait.h new file mode 100644 index 000000000000..50fc5ab9f846 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/ui_portrait.h @@ -0,0 +1,52 @@ + +/**************************************************************************** + * 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 = 272.000000; +constexpr float y_min = 0.000000; +constexpr float y_max = 480.000000; + +const PROGMEM uint16_t z_neg[] = {0xC9B1, 0x96B3, 0xD990, 0x96B3, 0xD990, 0xA8D0, 0xE17F, 0xA8D0, 0xD1A0, 0xB1DF, 0xC1C2, 0xA8D0, 0xC9B1, 0xA8D0, 0xC9B1, 0x96B3}; +const PROGMEM uint16_t z_pos[] = {0xC9B1, 0x8DA4, 0xD990, 0x8DA4, 0xD990, 0x7B86, 0xE17F, 0x7B86, 0xD1A0, 0x7277, 0xC1C2, 0x7B86, 0xC9B1, 0x7B86, 0xC9B1, 0x8DA4}; +const PROGMEM uint16_t y_neg[] = {0x5037, 0x9979, 0x6264, 0x9979, 0x5529, 0xA92A, 0x5E3F, 0xA92A, 0x4575, 0xB103, 0x39E6, 0xA92A, 0x42FC, 0xA92A, 0x5037, 0x9979}; +const PROGMEM uint16_t y_pos[] = {0x5D72, 0x89C7, 0x6F9F, 0x89C7, 0x7CDA, 0x7A15, 0x85F0, 0x7A15, 0x7A61, 0x723D, 0x6197, 0x7A15, 0x6AAD, 0x7A15, 0x5D72, 0x89C7}; +const PROGMEM uint16_t x_neg[] = {0x513D, 0x8DB3, 0x4AA0, 0x958C, 0x2647, 0x958C, 0x22F8, 0x9979, 0x1769, 0x91A0, 0x3033, 0x89C7, 0x2CE4, 0x8DB3, 0x513D, 0x8DB3}; +const PROGMEM uint16_t x_pos[] = {0x7566, 0x8DB3, 0x6EC9, 0x958C, 0x9322, 0x958C, 0x8FD4, 0x9979, 0xA89E, 0x91A0, 0x9D0E, 0x89C7, 0x99C0, 0x8DB3, 0x7566, 0x8DB3}; +const PROGMEM uint16_t syringe_fluid[] = {0x7D1D, 0x4A0F, 0x87FC, 0x4C0E, 0x8CF4, 0x4C0E, 0x9801, 0x4A0F, 0x9801, 0x1AA2, 0x7D1D, 0x1AA2, 0x7D1D, 0x4A0F}; +const PROGMEM uint16_t syringe[] = {0x83C2, 0x42AA, 0x83C2, 0x43FF, 0x8D2C, 0x43FF, 0x8D2C, 0x42AA, 0xFFFF, 0x83C2, 0x3D54, 0x83C2, 0x3EAA, 0x8D2C, 0x3EAA, 0x8D2C, 0x3D54, 0xFFFF, 0x83C2, 0x37FF, 0x83C2, 0x3954, 0x8D2C, 0x3954, 0x8D2C, 0x37FF, 0xFFFF, 0x83C2, 0x32AA, 0x83C2, 0x33FF, 0x8D2C, 0x33FF, 0x8D2C, 0x32AA, 0xFFFF, 0x83C2, 0x2D54, 0x83C2, 0x2EAA, 0x8D2C, 0x2EAA, 0x8D2C, 0x2D54, 0xFFFF, 0x83C2, 0x27FF, 0x83C2, 0x2955, 0x8D2C, 0x2955, 0x8D2C, 0x27FF, 0xFFFF, 0x83C2, 0x22AA, 0x83C2, 0x23FF, 0x8D2C, 0x23FF, 0x8D2C, 0x22AA, 0xFFFF, 0x7AC7, 0x0F4B, 0x7AC7, 0x134A, 0x855B, 0x134A, 0x855B, 0x1949, 0x7AC7, 0x1949, 0x7AC7, 0x4B40, 0x855B, 0x4D40, 0x855B, 0x533F, 0x88E2, 0x533F, 0x88E2, 0x653C, 0x8C69, 0x673C, 0x8C69, 0x533F, 0x8FF0, 0x533F, 0x8FF0, 0x4D40, 0x9A85, 0x4B40, 0x9A85, 0x1949, 0x8FF0, 0x1949, 0x8FF0, 0x134A, 0x9A85, 0x134A, 0x9A85, 0x0F4B, 0xFFFF, 0x88E2, 0x134A, 0x8C69, 0x134A, 0x8C69, 0x1949, 0x88E2, 0x1949, 0x88E2, 0x134A, 0xFFFF, 0x7E4D, 0x1B49, 0x96FE, 0x1B49, 0x96FE, 0x4941, 0x8C69, 0x4B40, 0x88E2, 0x4B40, 0x7E4D, 0x4941, 0x7E4D, 0x1B49}; +const PROGMEM uint16_t syringe_outline[] = {0x7AC7, 0x0F4B, 0x7AC7, 0x134A, 0x855B, 0x134A, 0x855B, 0x1949, 0x7AC7, 0x1949, 0x7AC7, 0x4B40, 0x855B, 0x4D40, 0x855B, 0x533F, 0x88E2, 0x533F, 0x88E2, 0x653C, 0x8C69, 0x673C, 0x8C69, 0x533F, 0x8FF0, 0x533F, 0x8FF0, 0x4D40, 0x9A85, 0x4B40, 0x9A85, 0x1949, 0x8FF0, 0x1949, 0x8FF0, 0x134A, 0x9A85, 0x134A, 0x9A85, 0x0F4B, 0x7AC7, 0x0F4B}; +const PROGMEM uint16_t padlock[] = {0x645A, 0x8017, 0x5F9E, 0x80A1, 0x5BBA, 0x821B, 0x5911, 0x844A, 0x580A, 0x86F7, 0x580A, 0x8931, 0x5970, 0x8A98, 0x5C49, 0x8A98, 0x5DB0, 0x8931, 0x5DB0, 0x8703, 0x5E3C, 0x858E, 0x5FAA, 0x845F, 0x61C5, 0x8394, 0x645A, 0x834A, 0x66F0, 0x8394, 0x690C, 0x845F, 0x6A7A, 0x858D, 0x6B07, 0x8703, 0x6B07, 0x8F23, 0x57C8, 0x8F23, 0x551E, 0x8FC3, 0x5404, 0x9145, 0x5404, 0x9C8F, 0x551E, 0x9E11, 0x57C8, 0x9EB1, 0x70EE, 0x9EB1, 0x7398, 0x9E11, 0x74B2, 0x9C8F, 0x74B2, 0x9145, 0x7398, 0x8FC3, 0x70EE, 0x8F23, 0x70AC, 0x86FA, 0x6FA5, 0x844A, 0x6CFD, 0x821B, 0x6917, 0x80A1}; +const PROGMEM uint16_t home_z[] = {0xD6C9, 0x80CC, 0xBB53, 0x905B, 0xC231, 0x905B, 0xC231, 0x9FEB, 0xCFEC, 0x9FEB, 0xCFEC, 0x9823, 0xDDA7, 0x9823, 0xDDA7, 0x9FEB, 0xEB62, 0x9FEB, 0xEB62, 0x905B, 0xF240, 0x905B, 0xE7A3, 0x8A58, 0xE7A3, 0x82CD, 0xE0C6, 0x82CD, 0xE0C6, 0x8674}; +const PROGMEM uint16_t home_e[] = {0xB94F, 0x25AA, 0x9DD8, 0x353A, 0xA4B6, 0x353A, 0xA4B6, 0x44C9, 0xB271, 0x44C9, 0xB271, 0x3D02, 0xC02C, 0x3D02, 0xC02C, 0x44C9, 0xCDE7, 0x44C9, 0xCDE7, 0x353A, 0xD4C5, 0x353A, 0xCA28, 0x2F36, 0xCA28, 0x27AB, 0xC34B, 0x27AB, 0xC34B, 0x2B53}; +const PROGMEM uint16_t bed_icon[] = {0x1764, 0x2C4C, 0x6135, 0x2C4C, 0x6135, 0x40A8, 0x1764, 0x40A8}; +const PROGMEM uint16_t actual_temp[] = {0x1764, 0x466F, 0x6135, 0x466F, 0x6135, 0x5ACB, 0x1764, 0x5ACB}; +const PROGMEM uint16_t target_temp[] = {0x1764, 0x1228, 0x6135, 0x1228, 0x6135, 0x2684, 0x1764, 0x2684}; +const PROGMEM uint16_t fine_label[] = {0x1AA7, 0xC6D2, 0x9387, 0xC6D2, 0x9387, 0xD316, 0x1AA7, 0xD316}; +const PROGMEM uint16_t fine_toggle[] = {0x9C10, 0xC6D2, 0xE4A3, 0xC6D2, 0xE4A3, 0xD316, 0x9C10, 0xD316}; +const PROGMEM uint16_t usb_btn[] = {0x0B68, 0xE880, 0x7B1A, 0xE880, 0x7B1A, 0xF94B, 0x0B68, 0xF94B, 0x0B68, 0xE880}; +const PROGMEM uint16_t menu_btn[] = {0x84E3, 0xE880, 0xF495, 0xE880, 0xF495, 0xF94B, 0x84E3, 0xF94B, 0x84E3, 0xE880}; +const PROGMEM uint16_t e_pos[] = {0xC9B1, 0x3B2D, 0xD990, 0x3B2D, 0xD990, 0x4D4B, 0xE17F, 0x4D4B, 0xD1A0, 0x565A, 0xC1C2, 0x4D4B, 0xC9B1, 0x4D4B, 0xC9B1, 0x3B2D}; +const PROGMEM uint16_t e_neg[] = {0xC9B1, 0x321E, 0xD990, 0x321E, 0xD990, 0x2000, 0xE17F, 0x2000, 0xD1A0, 0x16F1, 0xC1C2, 0x2000, 0xC9B1, 0x2000, 0xC9B1, 0x321E}; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/advanced_settings_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/advanced_settings_menu.cpp new file mode 100644 index 000000000000..7549e8d54e93 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/advanced_settings_menu.cpp @@ -0,0 +1,95 @@ +/***************************************** + * cocoa_press/advance_settings_menu.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_ADVANCED_SETTINGS_MENU + +using namespace FTDI; +using namespace ExtUI; +using namespace Theme; + +#define GRID_ROWS 4 +#define GRID_COLS 3 +#define STEPS_PER_MM_POS BTN_POS(1,1), BTN_SIZE(1,1) +#define TMC_CURRENT_POS BTN_POS(2,1), BTN_SIZE(1,1) +#define LIN_ADVANCE_POS BTN_POS(3,1), BTN_SIZE(1,1) +#define VELOCITY_POS BTN_POS(1,2), BTN_SIZE(1,1) +#define ACCELERATION_POS BTN_POS(2,2), BTN_SIZE(1,1) +#define JERK_POS BTN_POS(3,2), BTN_SIZE(1,1) +#define DISPLAY_POS BTN_POS(1,3), BTN_SIZE(1,1) +#define INTERFACE_POS BTN_POS(2,3), BTN_SIZE(1,1) +#define ENDSTOPS_POS BTN_POS(3,3), BTN_SIZE(1,1) +#define RESTORE_DEFAULTS_POS BTN_POS(1,4), BTN_SIZE(2,1) +#define BACK_POS BTN_POS(3,4), BTN_SIZE(1,1) + +void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { + if (what & BACKGROUND) { + CommandProcessor cmd; + cmd.cmd(CLEAR_COLOR_RGB(Theme::bg_color)) + .cmd(CLEAR(true,true,true)); + } + + if (what & FOREGROUND) { + CommandProcessor cmd; + cmd.colors(normal_btn) + .font(Theme::font_medium) + .tag(2) .button(STEPS_PER_MM_POS, GET_TEXT_F(MSG_STEPS_PER_MM)) + .enabled(ENABLED(HAS_TRINAMIC_CONFIG)) + .tag(3) .button(TMC_CURRENT_POS, GET_TEXT_F(MSG_TMC_CURRENT)) + .enabled(ENABLED(LIN_ADVANCE)) + .tag(4) .button(LIN_ADVANCE_POS, GET_TEXT_F(MSG_LINEAR_ADVANCE)) + .tag(5) .button(VELOCITY_POS, GET_TEXT_F(MSG_VELOCITY)) + .tag(6) .button(ACCELERATION_POS, GET_TEXT_F(MSG_ACCELERATION)) + .tag(7) .button(JERK_POS, GET_TEXT_F(TERN(HAS_JUNCTION_DEVIATION, MSG_JUNCTION_DEVIATION, MSG_JERK))) + .tag(8) .button(ENDSTOPS_POS, GET_TEXT_F(MSG_LCD_ENDSTOPS)) + .tag(9) .button(INTERFACE_POS, GET_TEXT_F(MSG_INTERFACE)) + .tag(10).button(DISPLAY_POS, GET_TEXT_F(MSG_DISPLAY_MENU)) + .tag(11).button(RESTORE_DEFAULTS_POS, GET_TEXT_F(MSG_RESTORE_DEFAULTS)) + .colors(action_btn) + .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BUTTON_DONE)); + } +} + +bool AdvancedSettingsMenu::onTouchEnd(uint8_t tag) { + switch (tag) { + case 1: SaveSettingsDialogBox::promptToSaveSettings(); break; + case 2: GOTO_SCREEN(StepsScreen); break; + #if HAS_TRINAMIC_CONFIG + case 3: GOTO_SCREEN(StepperCurrentScreen); break; + #endif + #if ENABLED(LIN_ADVANCE) + case 4: GOTO_SCREEN(LinearAdvanceScreen); break; + #endif + case 5: GOTO_SCREEN(MaxVelocityScreen); break; + case 6: GOTO_SCREEN(DefaultAccelerationScreen); break; + case 7: GOTO_SCREEN(TERN(HAS_JUNCTION_DEVIATION, JunctionDeviationScreen, JerkScreen)); break; + case 8: GOTO_SCREEN(EndstopStatesScreen); break; + case 9: GOTO_SCREEN(InterfaceSettingsScreen); LockScreen::check_passcode(); break; + case 10: GOTO_SCREEN(DisplayTuningScreen); break; + case 11: GOTO_SCREEN(RestoreFailsafeDialogBox); LockScreen::check_passcode(); break; + default: return false; + } + return true; +} +#endif // COCOA_ADVANCED_SETTINGS_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/advanced_settings_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/advanced_settings_menu.h new file mode 100644 index 000000000000..02f65572a29e --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/advanced_settings_menu.h @@ -0,0 +1,32 @@ +/*************************************** + * cocoa_press/advance_settings_menu.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_ADVANCED_SETTINGS_MENU +#define COCOA_ADVANCED_SETTINGS_MENU_CLASS AdvancedSettingsMenu + +class AdvancedSettingsMenu : public BaseScreen, public CachedScreen { + 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/cocoa_press_ui.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/cocoa_press_ui.h new file mode 100644 index 000000000000..f67961830fd8 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/cocoa_press_ui.h @@ -0,0 +1,61 @@ + +/**************************************************************************** + * 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 syringe_outline[] = {0xED96, 0x14F0, 0xE65D, 0x10E9, 0xDED2, 0x0F9C, 0xD74B, 0x110E, 0xD01B, 0x1543, 0xCE80, 0x1836, 0xCE0A, 0x1C3A, 0xCE0F, 0x27AD, 0xCF0A, 0x2BD3, 0xD127, 0x2E5B, 0xD2A1, 0x2FF0, 0xD2A2, 0x9FC9, 0xD407, 0xA97A, 0xD7B9, 0xB10C, 0xD7BF, 0xBB58, 0xD978, 0xC2BE, 0xDD55, 0xC6EB, 0xDD58, 0xD159, 0xDE3B, 0xD3A8, 0xDFCF, 0xD3AF, 0xE0B8, 0xD04C, 0xE0B8, 0xC6EB, 0xE4A7, 0xC299, 0xE652, 0xBAF6, 0xE652, 0xB10C, 0xEA2E, 0xA8EA, 0xEB6C, 0x9E86, 0xEB6C, 0x2F58, 0xEF3C, 0x2B4E, 0xF003, 0x2583, 0xEFFD, 0x1AC2, 0xED96, 0x14F0, 0xED96, 0x14F0}; +const PROGMEM uint16_t syringe_fluid[] = {0xDE73, 0x2512, 0xDA0C, 0x261D, 0xD5B8, 0x29A0, 0xD4AE, 0x2D87, 0xD4AE, 0x9F60, 0xD585, 0xA63B, 0xDE44, 0xA9DE, 0xE32A, 0xA942, 0xE7E3, 0xA6A5, 0xE930, 0xA342, 0xE95D, 0x9C1D, 0xE95B, 0x31B8, 0xE955, 0x2B63, 0xE867, 0x2A67, 0xE790, 0x28DE, 0xE342, 0x25CB, 0xDE73, 0x2512}; +const PROGMEM uint16_t syringe[] = {0xED91, 0x1502, 0xE658, 0x10FB, 0xDECE, 0x0FAE, 0xD746, 0x1120, 0xD016, 0x1555, 0xCE7B, 0x1848, 0xCE05, 0x1C4D, 0xCE0A, 0x27BF, 0xCF05, 0x2BE5, 0xD122, 0x2E6E, 0xD29C, 0x3002, 0xD29D, 0x9FDB, 0xD402, 0xA98C, 0xD7B4, 0xB11F, 0xD7BA, 0xBB6A, 0xD973, 0xC2D1, 0xDD50, 0xC6FD, 0xDD53, 0xD16C, 0xDE36, 0xD3BA, 0xDFCA, 0xD3C2, 0xE0B3, 0xD05E, 0xE0B3, 0xC6FD, 0xE4A2, 0xC2AB, 0xE64D, 0xBB09, 0xE64D, 0xB11F, 0xEA29, 0xA8FC, 0xEB67, 0x9E98, 0xEB67, 0x2F6B, 0xEF37, 0x2B60, 0xEFFE, 0x2595, 0xEFF8, 0x1AD5, 0xED91, 0x1502, 0xED91, 0x1502, 0xFFFF, 0xD1CF, 0x1A7E, 0xD84F, 0x16DB, 0xDF19, 0x15A9, 0xE5E0, 0x16EA, 0xEC5B, 0x1AA4, 0xEC9D, 0x1D34, 0xEC9D, 0x20CC, 0xE5F1, 0x1D41, 0xDF02, 0x1C12, 0xD812, 0x1D41, 0xD166, 0x20CC, 0xD16C, 0x1B45, 0xD1CF, 0x1A7E, 0xFFFF, 0xE3BD, 0xACFD, 0xDE8E, 0xAF4F, 0xD988, 0xAC0F, 0xD7CC, 0xA8CD, 0xDD1C, 0xAAA9, 0xE287, 0xAA5B, 0xE655, 0xA8BE, 0xE3BD, 0xACFD, 0xFFFF, 0xE802, 0x2DC5, 0xE809, 0x343C, 0xE808, 0x9FC8, 0xE7E3, 0xA296, 0xE70D, 0xA4B1, 0xE2C9, 0xA70E, 0xDE4E, 0xA790, 0xD6A1, 0xA457, 0xD5FF, 0x9F2B, 0xD5FF, 0x2DFD, 0xD6B2, 0x2B72, 0xDA78, 0x2861, 0xDE9D, 0x276F, 0xE300, 0x2824, 0xE70D, 0x2B13, 0xE7FF, 0x2DB6, 0xE800, 0x2DC5, 0xE802, 0x2DC5, 0xFFFF, 0xE2ED, 0xBA8B, 0xE1CC, 0xBF52, 0xDF1C, 0xC165, 0xDC64, 0xBF99, 0xDB1B, 0xBAFF, 0xDB19, 0xB433, 0xDF04, 0xB552, 0xE2EF, 0xB438, 0xE2ED, 0xBA8B, 0xFFFF, 0xEC09, 0x2893, 0xE925, 0x2A08, 0xE57D, 0x261D, 0xE149, 0x246F, 0xDBDE, 0x24A0, 0xD6BC, 0x2795, 0xD484, 0x2A46, 0xD1C0, 0x2853, 0xD166, 0x251E, 0xD80D, 0x2151, 0xDF02, 0x200C, 0xE5F6, 0x2151, 0xEC9D, 0x251E, 0xEC09, 0x2893}; +const PROGMEM uint16_t park_btn[] = {0x0AAA, 0x0E1E, 0x57FF, 0x0E1E, 0x57FF, 0x33C3, 0x0AAA, 0x33C3, 0x0AAA, 0x0E1E}; +const PROGMEM uint16_t pause_btn[] = {0x47FF, 0xCA58, 0x7FFF, 0xCA58, 0x7FFF, 0xEFFE, 0x47FF, 0xEFFE, 0x47FF, 0xCA58}; +const PROGMEM uint16_t load_chocolate_btn[] = {0x0AAA, 0x3D2C, 0x57FF, 0x3D2C, 0x57FF, 0x62D2, 0x0AAA, 0x62D2, 0x0AAA, 0x3D2C}; +const PROGMEM uint16_t preheat_chocolate_btn[] = {0x0AAA, 0x6C3B, 0x57FF, 0x6C3B, 0x57FF, 0x91E0, 0x0AAA, 0x91E0, 0x0AAA, 0x6C3B}; +const PROGMEM uint16_t menu_btn[] = {0x0AAA, 0x9B4A, 0x57FF, 0x9B4A, 0x57FF, 0xC0EF, 0x0AAA, 0xC0EF, 0x0AAA, 0x9B4A}; +const PROGMEM uint16_t print_btn[] = {0x0AAA, 0xCA58, 0x42AA, 0xCA58, 0x42AA, 0xEFFE, 0x0AAA, 0xEFFE, 0x0AAA, 0xCA58}; +const PROGMEM uint16_t stop_btn[] = {0x8554, 0xCA58, 0xBD53, 0xCA58, 0xBD53, 0xEFFE, 0x8554, 0xEFFE, 0x8554, 0xCA58}; +const PROGMEM uint16_t print_time_hms[] = {0x62A9, 0xA968, 0x8FFE, 0xA968, 0x8FFE, 0xC0EF, 0x62A9, 0xC0EF, 0x62A9, 0xA968}; +const PROGMEM uint16_t print_time_percent[] = {0x8FFE, 0xA968, 0xBD53, 0xA968, 0xBD53, 0xC0EF, 0x8FFE, 0xC0EF, 0x8FFE, 0xA968}; +const PROGMEM uint16_t print_time_label[] = {0x62A9, 0x91E0, 0xBD53, 0x91E0, 0xBD53, 0xA986, 0x62A9, 0xA986, 0x62A9, 0x91E0}; +const PROGMEM uint16_t h3_temp[] = {0x62A9, 0x75A4, 0x8FFE, 0x75A4, 0x8FFE, 0x8D2C, 0x62A9, 0x8D2C, 0x62A9, 0x75A4}; +const PROGMEM uint16_t h3_label[] = {0x62A9, 0x5E1D, 0x8FFE, 0x5E1D, 0x8FFE, 0x75A4, 0x62A9, 0x75A4, 0x62A9, 0x5E1D}; +const PROGMEM uint16_t chocolate_label[] = {0x62A9, 0x12D2, 0xBD53, 0x12D2, 0xBD53, 0x2A5A, 0x62A9, 0x2A5A, 0x62A9, 0x12D2}; +const PROGMEM uint16_t h0_label[] = {0x62A9, 0x2A5A, 0x8FFE, 0x2A5A, 0x8FFE, 0x41E1, 0x62A9, 0x41E1, 0x62A9, 0x2A5A}; +const PROGMEM uint16_t h0_temp[] = {0x62A9, 0x41E1, 0x8FFE, 0x41E1, 0x8FFE, 0x5968, 0x62A9, 0x5968, 0x62A9, 0x41E1}; +const PROGMEM uint16_t h1_label[] = {0x8FFE, 0x2A5A, 0xBD53, 0x2A5A, 0xBD53, 0x41E1, 0x8FFE, 0x41E1, 0x8FFE, 0x2A5A}; +const PROGMEM uint16_t h1_temp[] = {0x8FFE, 0x41E1, 0xBD53, 0x41E1, 0xBD53, 0x5968, 0x8FFE, 0x5968, 0x8FFE, 0x41E1}; +const PROGMEM uint16_t h2_label[] = {0x8FFE, 0x5E1D, 0xBD53, 0x5E1D, 0xBD53, 0x75A4, 0x8FFE, 0x75A4, 0x8FFE, 0x5E1D}; +const PROGMEM uint16_t h2_temp[] = {0x8FFE, 0x75A4, 0xBD53, 0x75A4, 0xBD53, 0x8D2C, 0x8FFE, 0x8D2C, 0x8FFE, 0x75A4}; +const PROGMEM uint16_t extrude_btn[] = {0xC859, 0xDD2B, 0xF5AE, 0xDD2B, 0xF5AE, 0xEFFE, 0xC859, 0xEFFE, 0xC859, 0xDD2B}; +const PROGMEM uint16_t load_screen_extrude[] = {0x25FB, 0x89AE, 0x2F58, 0x89AE, 0x2F58, 0xAAF6, 0x3406, 0xAAF6, 0x2AAA, 0xBB9A, 0x214D, 0xAAF6, 0x25FB, 0xAAF6, 0x25FB, 0x89AE}; +const PROGMEM uint16_t load_screen_retract[] = {0x25FC, 0x790A, 0x2F58, 0x790A, 0x2F58, 0x57C2, 0x3406, 0x57C2, 0x2AAA, 0x471D, 0x214D, 0x57C2, 0x25FC, 0x57C2, 0x25FC, 0x790A}; +const PROGMEM uint16_t load_screen_back_btn[] = {0x1555, 0xCA58, 0xC553, 0xCA58, 0xC553, 0xEFFE, 0x1555, 0xEFFE, 0x1555, 0xCA58}; +const PROGMEM uint16_t load_screen_unload_btn[] = {0x4AAA, 0x8EBD, 0xC553, 0x8EBD, 0xC553, 0xB463, 0x4AAA, 0xB463, 0x4AAA, 0x8EBD}; +const PROGMEM uint16_t load_screen_load_btn[] = {0x4AAA, 0x5322, 0xC553, 0x5322, 0xC553, 0x78C7, 0x4AAA, 0x78C7, 0x4AAA, 0x5322}; +const PROGMEM uint16_t load_sreen_title[] = {0x4AAA, 0x1787, 0xC553, 0x1787, 0xC553, 0x3D2C, 0x4AAA, 0x3D2C, 0x4AAA, 0x1787}; +const PROGMEM uint16_t load_screen_increment[] = {0x1555, 0x2E1D, 0x3FFF, 0x2E1D, 0x3FFF, 0x3D2C, 0x1555, 0x3D2C, 0x1555, 0x2E1D}; 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 new file mode 100644 index 000000000000..2e3472987eb3 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp @@ -0,0 +1,91 @@ +/********************************* + * cocoa_press/leveling_menu.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" + +#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_ROWS 5 +#define GRID_COLS 3 +#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) + +void LevelingMenu::onRedraw(draw_mode_t what) { + if (what & BACKGROUND) { + CommandProcessor cmd; + cmd.cmd(CLEAR_COLOR_RGB(Theme::bg_color)) + .cmd(CLEAR(true,true,true)) + .tag(0); + } + + if (what & FOREGROUND) { + CommandProcessor cmd; + cmd.font(font_large) + .cmd(COLOR_RGB(bg_text_enabled)) + .text(BED_MESH_TITLE_POS, GET_TEXT_F(MSG_BED_LEVELING)) + .text(BLTOUCH_TITLE_POS, GET_TEXT_F(MSG_BLTOUCH)) + .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_SHOW_MESH)) + .enabled(ENABLED(HAS_MESH)) + .tag(4).button(EDIT_MESH_POS, GET_TEXT_F(MSG_EDIT_MESH)) + #undef GRID_COLS + #define GRID_COLS 2 + .tag(5).button(BLTOUCH_RESET_POS, GET_TEXT_F(MSG_BLTOUCH_RESET)) + .tag(6).button(BLTOUCH_TEST_POS, GET_TEXT_F(MSG_BLTOUCH_SELFTEST)) + #undef GRID_COLS + #define GRID_COLS 3 + .colors(action_btn) + .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BUTTON_DONE)); + } +} + +bool LevelingMenu::onTouchEnd(uint8_t tag) { + switch (tag) { + case 1: GOTO_PREVIOUS(); break; + case 2: BedMeshViewScreen::doProbe(); break; + case 3: BedMeshViewScreen::show(); break; + case 4: BedMeshEditScreen::show(); break; + case 5: injectCommands_P(PSTR("M280 P0 S60")); break; + case 6: SpinnerDialogBox::enqueueAndWait(F("M280 P0 S90\nG4 P100\nM280 P0 S120")); break; + default: return false; + } + return true; +} + +#endif // COCOA_LEVELING_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.h new file mode 100644 index 000000000000..827538024989 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.h @@ -0,0 +1,32 @@ +/******************************* + * cocoa_press/leveling_menu.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_LEVELING_MENU +#define COCOA_LEVELING_MENU_CLASS LevelingMenu + +class LevelingMenu : public BaseScreen, public CachedScreen { + 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/load_chocolate.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/load_chocolate.cpp new file mode 100644 index 000000000000..d40b3be35460 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/load_chocolate.cpp @@ -0,0 +1,218 @@ +/********************************** + * cocoa_press/load_chocolate.cpp * + **********************************/ + +/**************************************************************************** + * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2020 - Cocoa Press * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#include "../config.h" +#include "../screens.h" +#include "../screen_data.h" + +#ifdef COCOA_LOAD_CHOCOLATE_SCREEN + +#include "cocoa_press_ui.h" + +#define POLY(A) PolyUI::poly_reader_t(A, sizeof(A)/sizeof(A[0])) + +const uint8_t shadow_depth = 5; + +using namespace ExtUI; +using namespace FTDI; +using namespace Theme; + +constexpr static LoadChocolateScreenData &mydata = screen_data.LoadChocolateScreen; + +void LoadChocolateScreen::draw_syringe(draw_mode_t what) { + #if ENABLED(COCOA_PRESS_CHOCOLATE_LEVEL_SENSOR) + const float fill_level = get_chocolate_fill_level(); + #else + constexpr float fill_level = 1.0f; + #endif + + CommandProcessor cmd; + PolyUI ui(cmd, what); + + if (what & BACKGROUND) { + // Paint the shadow for the syringe + ui.color(shadow_rgb); + ui.shadow(POLY(syringe_outline), shadow_depth); + } + + if (what & FOREGROUND) { + int16_t x, y, h, v; + + // Paint the syringe icon + ui.color(syringe_rgb); + ui.fill(POLY(syringe_outline)); + + ui.color(fluid_rgb); + ui.bounds(POLY(syringe_fluid), x, y, h, v); + cmd.cmd(SAVE_CONTEXT()); + cmd.cmd(SCISSOR_XY(x,y + v * (1.0 - fill_level))); + cmd.cmd(SCISSOR_SIZE(h, v * fill_level)); + ui.fill(POLY(syringe_fluid), false); + cmd.cmd(RESTORE_CONTEXT()); + + ui.color(stroke_rgb); + ui.fill(POLY(syringe)); + } +} + +void LoadChocolateScreen::draw_buttons(draw_mode_t what) { + int16_t x, y, h, v; + + CommandProcessor cmd; + PolyUI ui(cmd, what); + + cmd.font(font_medium).colors(normal_btn); + + ui.bounds(POLY(load_screen_unload_btn), x, y, h, v); + cmd.tag(2).button(x, y, h, v, GET_TEXT_F(MSG_FULL_UNLOAD)); + + ui.bounds(POLY(load_screen_load_btn), x, y, h, v); + cmd.tag(3).button(x, y, h, v, GET_TEXT_F(MSG_FULL_LOAD)); + + ui.bounds(POLY(load_screen_back_btn), x, y, h, v); + cmd.tag(1).colors(action_btn).button(x, y, h, v, GET_TEXT_F(MSG_BUTTON_DONE)); +} + +void LoadChocolateScreen::draw_text(draw_mode_t what) { + if (what & BACKGROUND) { + int16_t x, y, h, v; + + CommandProcessor cmd; + PolyUI ui(cmd, what); + + cmd.font(font_medium).cmd(COLOR_RGB(bg_text_enabled)); + + ui.bounds(POLY(load_sreen_title), x, y, h, v); + cmd.tag(2).text(x, y, h, v, GET_TEXT_F(MSG_LOAD_UNLOAD)); + + ui.bounds(POLY(load_screen_increment), x, y, h, v); + cmd.tag(3).text(x, y, h, v, GET_TEXT_F(MSG_INCREMENT)); + } +} + +void LoadChocolateScreen::draw_arrows(draw_mode_t what) { + CommandProcessor cmd; + PolyUI ui(cmd, what); + + ui.button_fill (fill_rgb); + ui.button_stroke(stroke_rgb, 28); + ui.button_shadow(shadow_rgb, shadow_depth); + + constexpr uint8_t style = PolyUI::REGULAR; + + ui.button(4, POLY(load_screen_extrude), style); + ui.button(5, POLY(load_screen_retract), style); +} + +void LoadChocolateScreen::onEntry() { + mydata.repeat_tag = 0; +} + +void LoadChocolateScreen::onRedraw(draw_mode_t what) { + if (what & BACKGROUND) { + CommandProcessor cmd; + cmd.cmd(CLEAR_COLOR_RGB(bg_color)) + .cmd(CLEAR(true,true,true)) + .tag(0); + } + + draw_syringe(what); + draw_arrows(what); + draw_buttons(what); + draw_text(what); +} + +bool LoadChocolateScreen::onTouchStart(uint8_t) { + mydata.repeat_tag = 0; + return true; +} + +bool LoadChocolateScreen::onTouchEnd(uint8_t tag) { + using namespace ExtUI; + switch (tag) { + case 2: + mydata.repeat_tag = (mydata.repeat_tag == 2) ? 0 : 2; + break; + case 3: + mydata.repeat_tag = (mydata.repeat_tag == 3) ? 0 : 3; + break; + case 1: GOTO_PREVIOUS(); break; + } + return true; +} + +void LoadChocolateScreen::setManualFeedrateAndIncrement(float feedrate_mm_s, float &increment_mm) { + // Compute increment so 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. + ExtUI::setFeedrate_mm_s(feedrate_mm_s); + increment_mm = feedrate_mm_s / ((TOUCH_REPEATS_PER_SECOND) * 0.80f); +} + +bool LoadChocolateScreen::onTouchHeld(uint8_t tag) { + if (ExtUI::isMoving()) return false; // Don't allow moves to accumulate + float increment; + setManualFeedrateAndIncrement(20, increment); + #define UI_INCREMENT_AXIS(axis) UI_INCREMENT(AxisPosition_mm, axis); + #define UI_DECREMENT_AXIS(axis) UI_DECREMENT(AxisPosition_mm, axis); + switch (tag) { + case 2: { + if (get_chocolate_fill_level() < 0.1) { + mydata.repeat_tag = 0; + return false; + } + UI_INCREMENT_AXIS(E0); + break; + } + case 3: { + if (get_chocolate_fill_level() > 0.75) { + mydata.repeat_tag = 0; + return false; + } + UI_DECREMENT_AXIS(E0); + break; + } + case 4: + UI_INCREMENT_AXIS(E0); + break; + case 5: + UI_DECREMENT_AXIS(E0); + break; + default: return false; + } + #undef UI_DECREMENT_AXIS + #undef UI_INCREMENT_AXIS + return false; +} + +void LoadChocolateScreen::onIdle() { + reset_menu_timeout(); + if (mydata.repeat_tag) onTouchHeld(mydata.repeat_tag); + if (refresh_timer.elapsed(STATUS_UPDATE_INTERVAL)) { + 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/load_chocolate.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/load_chocolate.h new file mode 100644 index 000000000000..4a582f0212f8 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/load_chocolate.h @@ -0,0 +1,47 @@ +/******************************** + * cocoa_press/load_chocolate.h * + ********************************/ + +/**************************************************************************** + * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2020 - Cocoa Press * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#pragma once + +#define COCOA_LOAD_CHOCOLATE_SCREEN +#define COCOA_LOAD_CHOCOLATE_SCREEN_CLASS LoadChocolateScreen + +struct LoadChocolateScreenData { + uint8_t repeat_tag; +}; + +class LoadChocolateScreen : public BaseScreen, public CachedScreen { + private: + static void draw_syringe(draw_mode_t what); + static void draw_arrows(draw_mode_t what); + static void draw_buttons(draw_mode_t what); + static void draw_text(draw_mode_t what); + public: + static void setManualFeedrateAndIncrement(float feedrate_mm_s, float &increment); + static void onEntry(); + static void onIdle(); + static void onRedraw(draw_mode_t); + static bool onTouchStart(uint8_t tag); + static bool onTouchEnd(uint8_t tag); + static bool onTouchHeld(uint8_t tag); +}; 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 new file mode 100644 index 000000000000..3fe17b72d5eb --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.cpp @@ -0,0 +1,100 @@ +/***************************** + * cocoa_press/main_menu.cpp * + *****************************/ + +/**************************************************************************** + * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2019 - Cocoa Press * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#include "../config.h" +#include "../screens.h" + +#ifdef COCOA_MAIN_MENU + +using namespace FTDI; +using namespace Theme; + +#define GRID_ROWS 6 +#define GRID_COLS 2 + +#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 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 DISABLE_STEPPERS_POS BTN_POS(2,4), BTN_SIZE(1,1) +#define LEVELING_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) + +void MainMenu::onRedraw(draw_mode_t what) { + if (what & BACKGROUND) { + CommandProcessor cmd; + cmd.cmd(CLEAR_COLOR_RGB(Theme::bg_color)) + .cmd(CLEAR(true,true,true)); + } + + if (what & FOREGROUND) { + CommandProcessor cmd; + cmd.colors(normal_btn) + .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)) + .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)) + .tag( 9).button(DISABLE_STEPPERS_POS, GET_TEXT_F(MSG_DISABLE_STEPPERS)) + .enabled(HAS_LEVELING) + .tag(10).button(LEVELING_POS, GET_TEXT_F(MSG_LEVELING)) + .tag(11).button(ABOUT_PRINTER_POS, GET_TEXT_F(MSG_INFO_MENU)) + .colors(action_btn) + .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BUTTON_DONE)); + } +} + +bool MainMenu::onTouchEnd(uint8_t tag) { + using namespace ExtUI; + + switch (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) + case 4: GOTO_SCREEN(ZOffsetScreen); break; + #endif + case 5: GOTO_SCREEN(MoveEScreen); break; + case 6: GOTO_SCREEN(FeedratePercentScreen); break; + case 7: GOTO_SCREEN(FlowPercentScreen); break; + case 8: GOTO_SCREEN(AdvancedSettingsMenu); break; + case 9: injectCommands_P(PSTR("M84")); break; + #if HAS_LEVELING + case 10: GOTO_SCREEN(LevelingMenu); break; + #endif + case 11: GOTO_SCREEN(AboutScreen); break; + default: + return false; + } + return true; +} + +#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 new file mode 100644 index 000000000000..460bb4b81a70 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.h @@ -0,0 +1,33 @@ +/*************************** + * cocoa_press/main_menu.h * + ***************************/ + +/**************************************************************************** + * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2019 - Cocoa Press * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#pragma once + +#define COCOA_MAIN_MENU +#define COCOA_MAIN_MENU_CLASS MainMenu + +class MainMenu : public BaseScreen, public CachedScreen { + 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/move_e_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_e_screen.cpp new file mode 100644 index 000000000000..f7dbc466c7de --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_e_screen.cpp @@ -0,0 +1,63 @@ +/********************************* + * cocoa_press/move_e_screen.cpp * + *********************************/ + +/**************************************************************************** + * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2019 - Cocoa Press * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#include "../config.h" +#include "../screens.h" +#include "../screen_data.h" + +#ifdef COCOA_MOVE_E_SCREEN + +using namespace FTDI; +using namespace ExtUI; + +constexpr static MoveAxisScreenData &mydata = screen_data.MoveAxisScreen; + +void MoveEScreen::onRedraw(draw_mode_t what) { + widgets_t w(what); + w.precision(1, DEFAULT_MIDRANGE); + w.units(GET_TEXT_F(MSG_UNITS_MM)); + w.heading( GET_TEXT_F(MSG_E_MOVE)); + w.color(Theme::e_axis); + #if EXTRUDERS == 1 + w.adjuster( 8, GET_TEXT_F(MSG_AXIS_E), mydata.e_rel[0], canMove(E0)); + #elif HAS_MULTI_EXTRUDER + w.adjuster( 8, GET_TEXT_F(MSG_AXIS_E1), mydata.e_rel[0], canMove(E0)); + w.adjuster( 10, GET_TEXT_F(MSG_AXIS_E2), mydata.e_rel[1], canMove(E1)); + #if EXTRUDERS > 2 + w.adjuster( 12, GET_TEXT_F(MSG_AXIS_E3), mydata.e_rel[2], canMove(E2)); + #endif + #if EXTRUDERS > 3 + w.adjuster( 14, GET_TEXT_F(MSG_AXIS_E4), mydata.e_rel[3], canMove(E3)); + #endif + #endif + w.increments(); +} + +void MoveEScreen::onIdle() { + if (refresh_timer.elapsed(STATUS_UPDATE_INTERVAL)) { + onRefresh(); + refresh_timer.start(); + } + BaseScreen::onIdle(); +} +#endif // COCOA_MOVE_E_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_e_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_e_screen.h new file mode 100644 index 000000000000..0cede6f0c5e2 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_e_screen.h @@ -0,0 +1,33 @@ +/******************************* + * cocoa_press/move_e_screen.h * + *******************************/ + +/**************************************************************************** + * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2019 - Cocoa Press * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#pragma once + +#define COCOA_MOVE_E_SCREEN +#define COCOA_MOVE_E_SCREEN_CLASS MoveEScreen + +class MoveEScreen : public BaseMoveAxisScreen, public CachedScreen { + public: + static void onRedraw(draw_mode_t); + static void onIdle(); +}; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_xyz_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_xyz_screen.cpp new file mode 100644 index 000000000000..8e80bd53a9e1 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_xyz_screen.cpp @@ -0,0 +1,52 @@ +/*********************************** + * cocoa_press/move_xyz_screen.cpp * + ***********************************/ + +/**************************************************************************** + * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2019 - Cocoa Press * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#include "../config.h" +#include "../screens.h" +#include "../screen_data.h" + +#ifdef COCOA_MOVE_XYZ_SCREEN + +using namespace FTDI; +using namespace ExtUI; + +void MoveXYZScreen::onRedraw(draw_mode_t what) { + widgets_t w(what); + w.precision(1); + w.units(GET_TEXT_F(MSG_UNITS_MM)); + w.heading( GET_TEXT_F(MSG_XYZ_MOVE)); + w.home_buttons(20); + w.color(Theme::x_axis).adjuster( 2, GET_TEXT_F(MSG_AXIS_X), getAxisPosition_mm(X), canMove(X)); + w.color(Theme::y_axis).adjuster( 4, GET_TEXT_F(MSG_AXIS_Y), getAxisPosition_mm(Y), canMove(Y)); + w.color(Theme::z_axis).adjuster( 6, GET_TEXT_F(MSG_AXIS_Z), getAxisPosition_mm(Z), canMove(Z)); + w.increments(); +} + +void MoveXYZScreen::onIdle() { + if (refresh_timer.elapsed(STATUS_UPDATE_INTERVAL)) { + onRefresh(); + refresh_timer.start(); + } + BaseScreen::onIdle(); +} +#endif // COCOA_MOVE_XYZ_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_xyz_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_xyz_screen.h new file mode 100644 index 000000000000..015f5b30e4a5 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_xyz_screen.h @@ -0,0 +1,33 @@ +/********************************* + * cocoa_press/move_xyz_screen.h * + *********************************/ + +/**************************************************************************** + * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2019 - Cocoa Press * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#pragma once + +#define COCOA_MOVE_XYZ_SCREEN +#define COCOA_MOVE_XYZ_SCREEN_CLASS MoveXYZScreen + +class MoveXYZScreen : public BaseMoveAxisScreen, public CachedScreen { + public: + static void onRedraw(draw_mode_t); + 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 new file mode 100644 index 000000000000..424e0afa7624 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_menu.cpp @@ -0,0 +1,116 @@ +/******************************** + * cocoa_press/preheat_menu.cpp * + ********************************/ + +/**************************************************************************** + * Written By Marcio Teixeira 2020 - Cocoa Press * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#include "../config.h" +#include "../screens.h" + +#ifdef COCOA_PREHEAT_MENU + +using namespace FTDI; +using namespace ExtUI; +using namespace Theme; + +#define GRID_ROWS 5 +#define GRID_COLS 2 + +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 + } + + 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)); + } +} + +bool PreheatMenu::onTouchEnd(uint8_t tag) { + switch (tag) { + case 1: GOTO_PREVIOUS(); break; + case 2: + #ifdef COCOA_PRESS_PREHEAT_DARK_CHOCOLATE_INT_SCRIPT + injectCommands_P(PSTR(COCOA_PRESS_PREHEAT_DARK_CHOCOLATE_INT_SCRIPT)); + #endif + GOTO_SCREEN(PreheatTimerScreen); + break; + case 3: + #ifdef COCOA_PRESS_PREHEAT_MILK_CHOCOLATE_INT_SCRIPT + injectCommands_P(PSTR(COCOA_PRESS_PREHEAT_MILK_CHOCOLATE_INT_SCRIPT)); + #endif + GOTO_SCREEN(PreheatTimerScreen); + break; + case 4: + #ifdef COCOA_PRESS_PREHEAT_WHITE_CHOCOLATE_INT_SCRIPT + injectCommands_P(PSTR(COCOA_PRESS_PREHEAT_WHITE_CHOCOLATE_INT_SCRIPT)); + #endif + GOTO_SCREEN(PreheatTimerScreen); + break; + case 5: + #ifdef COCOA_PRESS_PREHEAT_DARK_CHOCOLATE_EXT_SCRIPT + injectCommands_P(PSTR(COCOA_PRESS_PREHEAT_DARK_CHOCOLATE_EXT_SCRIPT)); + #endif + GOTO_SCREEN(PreheatTimerScreen); + break; + case 6: + #ifdef COCOA_PRESS_PREHEAT_MILK_CHOCOLATE_EXT_SCRIPT + injectCommands_P(PSTR(COCOA_PRESS_PREHEAT_MILK_CHOCOLATE_EXT_SCRIPT)); + #endif + GOTO_SCREEN(PreheatTimerScreen); + break; + case 7: + #ifdef COCOA_PRESS_PREHEAT_WHITE_CHOCOLATE_EXT_SCRIPT + injectCommands_P(PSTR(COCOA_PRESS_PREHEAT_WHITE_CHOCOLATE_EXT_SCRIPT)); + #endif + GOTO_SCREEN(PreheatTimerScreen); + break; + default: return false; + } + return true; +} + +#endif // COCOA_PREHEAT_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_menu.h new file mode 100644 index 000000000000..46bded7df490 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_menu.h @@ -0,0 +1,31 @@ +/****************************** + * cocoa_press/preheat_menu.h * + ******************************/ + +/**************************************************************************** + * Written By Marcio Teixeira 2020 - Cocoa Press * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#pragma once + +#define COCOA_PREHEAT_MENU +#define COCOA_PREHEAT_MENU_CLASS PreheatMenu + +class PreheatMenu : public BaseScreen, public CachedScreen { + 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/preheat_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.cpp new file mode 100644 index 000000000000..300878670e0b --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.cpp @@ -0,0 +1,161 @@ +/*************************************** + * cocoapress/preheat_timer_screen.cpp * + ***************************************/ + +/**************************************************************************** + * Written By Marcio Teixeira 2019 - Cocoa Press * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#include "../config.h" +#include "../screens.h" +#include "../screen_data.h" + +#ifdef COCOA_PREHEAT_SCREEN + +using namespace FTDI; +using namespace ExtUI; +using namespace Theme; + +constexpr static PreheatTimerScreenData &mydata = screen_data.PreheatTimerScreen; + +#define GRID_COLS 2 +#define GRID_ROWS 8 + +#define HEADER_POS BTN_POS(2,1), BTN_SIZE(1,2) +#define NOZZLE_ADJ_POS BTN_POS(2,3), BTN_SIZE(1,2) +#define BODY_ADJ_POS BTN_POS(2,5), BTN_SIZE(1,2) +#define CHAMBER_ADJ_POS BTN_POS(2,7), BTN_SIZE(1,2) +#define PROGRESS_POS BTN_POS(1,1), BTN_SIZE(1,7) +#define BACK_POS BTN_POS(1,8), BTN_SIZE(1,1) + +void PreheatTimerScreen::draw_message(draw_mode_t what) { + if (what & BACKGROUND) { + CommandProcessor cmd; + cmd.cmd(CLEAR_COLOR_RGB(bg_color)) + .cmd(CLEAR(true,true,true)) + .cmd(COLOR_RGB(bg_text_enabled)) + .tag(0); + draw_text_box(cmd, HEADER_POS, GET_TEXT_F(MSG_HEATING), OPT_CENTER, font_large); + } +} + +uint16_t PreheatTimerScreen::secondsRemaining() { + const uint32_t elapsed_sec = (millis() - mydata.start_ms) / 1000; + return (COCOA_PRESS_PREHEAT_SECONDS > elapsed_sec) ? COCOA_PRESS_PREHEAT_SECONDS - elapsed_sec : 0; +} + +void PreheatTimerScreen::draw_time_remaining(draw_mode_t what) { + if (what & FOREGROUND) { + const uint16_t elapsed_sec = secondsRemaining(); + const uint8_t min = elapsed_sec / 60, + sec = elapsed_sec % 60; + + char str[10]; + sprintf_P(str, PSTR("%02d:%02d"), min, sec); + + CommandProcessor cmd; + cmd.font(font_xlarge); + draw_circular_progress(cmd, PROGRESS_POS, float(secondsRemaining()) * 100 / COCOA_PRESS_PREHEAT_SECONDS, str, theme_dark, theme_darkest); + } +} + +void PreheatTimerScreen::draw_interaction_buttons(draw_mode_t what) { + if (what & FOREGROUND) { + CommandProcessor cmd; + cmd.colors(normal_btn) + .font(font_medium) + .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BUTTON_DONE)); + } +} + +void PreheatTimerScreen::draw_adjuster(draw_mode_t what, uint8_t tag, progmem_str label, float value, int16_t x, int16_t y, int16_t w, int16_t h) { + #define SUB_COLS 9 + #define SUB_ROWS 2 + + CommandProcessor cmd; + 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); + } + + 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("+")); + } +} + +void PreheatTimerScreen::onEntry() { + mydata.start_ms = millis(); +} + +void PreheatTimerScreen::onRedraw(draw_mode_t what) { + draw_message(what); + draw_time_remaining(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); +} + +bool PreheatTimerScreen::onTouchHeld(uint8_t tag) { + const float increment = (tag == 6 || tag == 7) ? 1 : 0.1; + switch (tag) { + case 2: UI_DECREMENT(TargetTemp_celsius, E0); break; + 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; + default: + return false; + } + return true; +} + +bool PreheatTimerScreen::onTouchEnd(uint8_t tag) { + switch (tag) { + case 1: GOTO_PREVIOUS(); return true; + default: return current_screen.onTouchHeld(tag); + } + return false; +} + +void PreheatTimerScreen::onIdle() { + if (secondsRemaining() == 0) { + AlertDialogBox::show(GET_TEXT_F(MSG_PREHEAT_FINISHED)); + // Remove SaveSettingsDialogBox from the stack + // so the alert box doesn't return to me. + current_screen.forget(); + } + + reset_menu_timeout(); + if (refresh_timer.elapsed(STATUS_UPDATE_INTERVAL)) { + onRefresh(); + refresh_timer.start(); + } + BaseScreen::onIdle(); +} + +#endif // COCOA_PREHEAT_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.h new file mode 100644 index 000000000000..9b8e2620dc69 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.h @@ -0,0 +1,46 @@ +/********************************* + * cocoapress/preheat_screen.cpp * + *********************************/ + +/**************************************************************************** + * Written By Marcio Teixeira 2019 - Cocoa Press * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#pragma once + +#define COCOA_PREHEAT_SCREEN +#define COCOA_PREHEAT_SCREEN_CLASS PreheatTimerScreen + +struct PreheatTimerScreenData { + uint32_t start_ms; +}; + +class PreheatTimerScreen : public BaseScreen, public CachedScreen { + private: + static uint16_t secondsRemaining(); + + static void draw_message(draw_mode_t); + static void draw_time_remaining(draw_mode_t); + static void draw_interaction_buttons(draw_mode_t); + static void draw_adjuster(draw_mode_t, uint8_t tag, progmem_str label, float value, int16_t x, int16_t y, int16_t w, int16_t h); + public: + static void onRedraw(draw_mode_t); + + static void onEntry(); + static void onIdle(); + static bool onTouchHeld(uint8_t tag); + static bool onTouchEnd(uint8_t tag); +}; 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 new file mode 100644 index 000000000000..8481e446c425 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/screens.h @@ -0,0 +1,134 @@ +/************* + * screens.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 + + +/********************************* DL CACHE SLOTS ******************************/ + +// In order to reduce SPI traffic, we cache display lists (DL) in RAMG. This +// is done using the CLCD::DLCache class, which takes a unique ID for each +// cache location. These IDs are defined here: + +enum { + STATUS_SCREEN_CACHE, + MENU_SCREEN_CACHE, + TUNE_SCREEN_CACHE, + ALERT_BOX_CACHE, + SPINNER_CACHE, + ADVANCED_SETTINGS_SCREEN_CACHE, + MOVE_AXIS_SCREEN_CACHE, + TEMPERATURE_SCREEN_CACHE, + STEPS_SCREEN_CACHE, + MAX_FEEDRATE_SCREEN_CACHE, + MAX_VELOCITY_SCREEN_CACHE, + MAX_ACCELERATION_SCREEN_CACHE, + DEFAULT_ACCELERATION_SCREEN_CACHE, + FLOW_PERCENT_SCREEN_CACHE, + LEVELING_SCREEN_CACHE, + ZOFFSET_SCREEN_CACHE, + BED_MESH_VIEW_SCREEN_CACHE, + BED_MESH_EDIT_SCREEN_CACHE, + STEPPER_CURRENT_SCREEN_CACHE, + #if HAS_JUNCTION_DEVIATION + JUNC_DEV_SCREEN_CACHE, + #else + JERK_SCREEN_CACHE, + #endif + CASE_LIGHT_SCREEN_CACHE, + FILAMENT_MENU_CACHE, + LINEAR_ADVANCE_SCREEN_CACHE, + PREHEAT_MENU_CACHE, + PREHEAT_TIMER_SCREEN_CACHE, + LOAD_CHOCOLATE_SCREEN_CACHE, + MOVE_XYZ_SCREEN_CACHE, + MOVE_E_SCREEN_CACHE, + FILES_SCREEN_CACHE, + INTERFACE_SETTINGS_SCREEN_CACHE, + INTERFACE_SOUNDS_SCREEN_CACHE, + LOCK_SCREEN_CACHE, + DISPLAY_TIMINGS_SCREEN_CACHE +}; + +// To save MCU RAM, the status message is "baked" in to the status screen +// cache, so we reserve a large chunk of memory for the DL cache + +#define STATUS_SCREEN_DL_SIZE 4096 +#define ALERT_BOX_DL_SIZE 3072 +#define SPINNER_DL_SIZE 3072 +#define FILE_SCREEN_DL_SIZE 4160 +#define PRINTING_SCREEN_DL_SIZE 2048 + +/************************* MENU SCREEN DECLARATIONS *************************/ + +#include "../generic/base_screen.h" +#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" +#include "../generic/restore_failsafe_dialog_box.h" +#include "../generic/save_settings_dialog_box.h" +#include "../generic/confirm_start_print_dialog_box.h" +#include "../generic/confirm_abort_print_dialog_box.h" +#include "../generic/confirm_user_request_alert_box.h" +#include "../generic/touch_calibration_screen.h" +#include "../generic/move_axis_screen.h" +#include "../generic/steps_screen.h" +#include "../generic/feedrate_percent_screen.h" +#include "../generic/max_velocity_screen.h" +#include "../generic/max_acceleration_screen.h" +#include "../generic/default_acceleration_screen.h" +#include "../generic/temperature_screen.h" +#include "../generic/interface_sounds_screen.h" +#include "../generic/interface_settings_screen.h" +#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/files_screen.h" +#include "../generic/move_axis_screen.h" +#include "../generic/flow_percent_screen.h" +#if HAS_JUNCTION_DEVIATION + #include "../generic/junction_deviation_screen.h" +#else + #include "../generic/jerk_screen.h" +#endif + +#include "status_screen.h" +#include "main_menu.h" +#include "advanced_settings_menu.h" +#include "preheat_menu.h" +#include "preheat_screen.h" +#include "load_chocolate.h" +#include "leveling_menu.h" +#include "move_xyz_screen.h" +#include "move_e_screen.h" 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 new file mode 100644 index 000000000000..af3875967d60 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.cpp @@ -0,0 +1,307 @@ +/********************************* + * cocoa_press/status_screen.cpp * + *********************************/ + +/**************************************************************************** + * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2019 - Cocoa Press * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#include "../config.h" +#include "../screens.h" + +#ifdef COCOA_STATUS_SCREEN + +#include "cocoa_press_ui.h" + +#define POLY(A) PolyUI::poly_reader_t(A, sizeof(A)/sizeof(A[0])) + +const uint8_t shadow_depth = 5; + +using namespace FTDI; +using namespace Theme; +using namespace ExtUI; + +float StatusScreen::increment; + +void StatusScreen::loadBitmaps() { + constexpr uint32_t base = ftdi_memory_map::RAM_G; + + // Load fonts for internationalization + #if ENABLED(TOUCH_UI_USE_UTF8) + load_utf8_data(base + UTF8_FONT_OFFSET); + #endif +} + +void StatusScreen::draw_progress(draw_mode_t what) { + CommandProcessor cmd; + PolyUI ui(cmd, what); + + int16_t x, y, h, v; + + cmd.cmd(COLOR_RGB(accent_color_1)); + cmd.font(font_medium); + + if (what & BACKGROUND) { + ui.bounds(POLY(print_time_label), x, y, h, v); + cmd.text(x, y, h, v, GET_TEXT_F(MSG_ELAPSED_PRINT)); + } + + if (what & FOREGROUND) { + const uint32_t elapsed = getProgress_seconds_elapsed(); + const uint8_t hrs = elapsed/3600; + const uint8_t min = (elapsed/60)%60; + + char str[10]; + sprintf_P(str, PSTR(" %02d : %02d"), hrs, min); + ui.bounds(POLY(print_time_hms), x, y, h, v); + cmd.text(x, y, h, v, str); + + sprintf_P(str, PSTR("%-3d%%"), getProgress_percent() ); + ui.bounds(POLY(print_time_percent), x, y, h, v); + cmd.text(x, y, h, v, str); + } +} + +void StatusScreen::draw_temperature(draw_mode_t what) { + CommandProcessor cmd; + PolyUI ui(cmd, what); + + int16_t x, y, h, v; + + if (what & BACKGROUND) { + cmd.cmd(COLOR_RGB(fluid_rgb)); + cmd.font(font_medium).tag(10); + + ui.bounds(POLY(chocolate_label), x, y, h, v); + cmd.text(x, y, h, v, GET_TEXT_F(MSG_CHOCOLATE)); + + ui.bounds(POLY(h0_label), x, y, h, v); + cmd.text(x, y, h, v, GET_TEXT_F(MSG_NOZZLE)); + + ui.bounds(POLY(h1_label), x, y, h, v); + cmd.text(x, y, h, v, GET_TEXT_F(MSG_BODY)); + + #if ENABLED(COCOA_PRESS_EXTRA_HEATER) + if (has_extra_heater()) { + ui.bounds(POLY(h2_label), x, y, h, v); + cmd.text(x, y, h, v, GET_TEXT_F(MSG_EXTERNAL)); + } + #endif + + ui.bounds(POLY(h3_label), x, y, h, v); + cmd.text(x, y, h, v, GET_TEXT_F(MSG_CHAMBER)); + + #if ENABLED(TOUCH_UI_USE_UTF8) + load_utf8_bitmaps(cmd); // Restore font bitmap handles + #endif + } + + if (what & FOREGROUND) { + char str[15]; + cmd.cmd(COLOR_RGB(fluid_rgb)); + + cmd.font(font_large).tag(10); + + format_temp(str, getActualTemp_celsius(E0)); + ui.bounds(POLY(h0_temp), x, y, h, v); + cmd.text(x, y, h, v, str); + + format_temp(str, getActualTemp_celsius(E1)); + ui.bounds(POLY(h1_temp), x, y, h, v); + cmd.text(x, y, h, v, str); + + #if ENABLED(COCOA_PRESS_EXTRA_HEATER) + if (has_extra_heater()) { + format_temp(str, getActualTemp_celsius(E2)); + ui.bounds(POLY(h2_temp), x, y, h, v); + cmd.text(x, y, h, v, str); + } + #endif + + format_temp(str, getActualTemp_celsius(CHAMBER)); + ui.bounds(POLY(h3_temp), x, y, h, v); + cmd.text(x, y, h, v, str); + } +} + +void StatusScreen::draw_syringe(draw_mode_t what) { + #if ENABLED(COCOA_PRESS_CHOCOLATE_LEVEL_SENSOR) + const float fill_level = get_chocolate_fill_level(); + #else + constexpr float fill_level = 1.0f; + #endif + + CommandProcessor cmd; + PolyUI ui(cmd, what); + + if (what & BACKGROUND) { + // Paint the shadow for the syringe + ui.color(shadow_rgb); + ui.shadow(POLY(syringe_outline), shadow_depth); + } + + if (what & FOREGROUND) { + int16_t x, y, h, v; + + // Paint the syringe icon + ui.color(syringe_rgb); + ui.fill(POLY(syringe_outline)); + + ui.color(fluid_rgb); + ui.bounds(POLY(syringe_fluid), x, y, h, v); + cmd.cmd(SAVE_CONTEXT()); + cmd.cmd(SCISSOR_XY(x,y + v * (1.0 - fill_level))); + cmd.cmd(SCISSOR_SIZE(h, v * fill_level)); + ui.fill(POLY(syringe_fluid), false); + cmd.cmd(RESTORE_CONTEXT()); + + ui.color(stroke_rgb); + ui.fill(POLY(syringe)); + } +} + +void StatusScreen::draw_buttons(draw_mode_t what) { + int16_t x, y, h, v; + + const bool can_print = isMediaInserted() && !isPrintingFromMedia(); + const bool sdOrHostPrinting = ExtUI::isPrinting(); + const bool sdOrHostPaused = ExtUI::isPrintingPaused(); + + CommandProcessor cmd; + PolyUI ui(cmd, what); + + cmd.font(font_medium).colors(normal_btn); + + ui.bounds(POLY(park_btn), x, y, h, v); + cmd.tag(1).button(x, y, h, v, GET_TEXT_F(MSG_FILAMENT_PARK_ENABLED)); + + ui.bounds(POLY(load_chocolate_btn), x, y, h, v); + cmd.tag(2).button(x, y, h, v, GET_TEXT_F(MSG_LOAD_UNLOAD)); + + ui.bounds(POLY(preheat_chocolate_btn), x, y, h, v); + cmd.tag(3).button(x, y, h, v, GET_TEXT_F(MSG_PREHEAT_CHOCOLATE)); + + ui.bounds(POLY(menu_btn), x, y, h, v); + cmd.tag(4).button(x, y, h, v, GET_TEXT_F(MSG_BUTTON_MENU)); + + ui.bounds(POLY(pause_btn), x, y, h, v); + cmd.tag(sdOrHostPaused ? 6 : 5).enabled(sdOrHostPrinting).button(x, y, h, v, sdOrHostPaused ? GET_TEXT_F(MSG_BUTTON_RESUME) : GET_TEXT_F(MSG_BUTTON_PAUSE)); + + ui.bounds(POLY(stop_btn), x, y, h, v); + cmd.tag(7).enabled(sdOrHostPrinting).button(x, y, h, v, GET_TEXT_F(MSG_BUTTON_STOP)); + + ui.bounds(POLY(extrude_btn), x, y, h, v); + cmd.tag(8).button(x, y, h, v, GET_TEXT_F(MSG_EXTRUDE)); + + ui.bounds(POLY(print_btn), x, y, h, v); + cmd.tag(9).colors(action_btn).enabled(can_print).button(x, y, h, v, GET_TEXT_F(MSG_BUTTON_PRINT)); +} + +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); + } + + draw_progress(what); + draw_syringe(what); + draw_temperature(what); + draw_buttons(what); +} + +bool StatusScreen::onTouchStart(uint8_t) { + increment = 0; + return true; +} + +bool StatusScreen::onTouchEnd(uint8_t tag) { + switch (tag) { + case 1: SpinnerDialogBox::enqueueAndWait(F("G28 O\nG27")); break; + case 2: GOTO_SCREEN(LoadChocolateScreen); break; + case 3: GOTO_SCREEN(PreheatMenu); break; + case 4: GOTO_SCREEN(MainMenu); break; + case 5: + sound.play(twinkle, PLAY_ASYNCHRONOUS); + if (ExtUI::isPrintingFromMedia()) + ExtUI::pausePrint(); + #ifdef ACTION_ON_PAUSE + else host_action_pause(); + #endif + GOTO_SCREEN(StatusScreen); + break; + case 6: + sound.play(twinkle, PLAY_ASYNCHRONOUS); + if (ExtUI::isPrintingFromMedia()) + ExtUI::resumePrint(); + #ifdef ACTION_ON_RESUME + else host_action_resume(); + #endif + GOTO_SCREEN(StatusScreen); + break; + case 7: + GOTO_SCREEN(ConfirmAbortPrintDialogBox); + current_screen.forget(); + PUSH_SCREEN(StatusScreen); + break; + case 9: GOTO_SCREEN(FilesScreen); break; + case 10: GOTO_SCREEN(TemperatureScreen); break; + default: return false; + } + // If a passcode is enabled, the LockScreen will prevent the + // user from proceeding. + LockScreen::check_passcode(); + return true; +} + +bool StatusScreen::onTouchHeld(uint8_t tag) { + if (tag == 8 && !ExtUI::isMoving()) { + LoadChocolateScreen::setManualFeedrateAndIncrement(1, increment); + UI_INCREMENT(AxisPosition_mm, E0); + current_screen.onRefresh(); + } + return false; +} + +void StatusScreen::setStatusMessage(progmem_str) { +} + +void StatusScreen::setStatusMessage(const char * const) { +} + +void StatusScreen::onIdle() { + reset_menu_timeout(); + if (refresh_timer.elapsed(STATUS_UPDATE_INTERVAL)) { + if (!EventLoop::is_touch_held()) + onRefresh(); + refresh_timer.start(); + } +} + +void StatusScreen::onMediaInserted() { + if (AT_SCREEN(StatusScreen)) + setStatusMessage(GET_TEXT_F(MSG_MEDIA_INSERTED)); +} + +void StatusScreen::onMediaRemoved() { + if (AT_SCREEN(StatusScreen) || ExtUI::isPrintingFromMedia()) + setStatusMessage(GET_TEXT_F(MSG_MEDIA_REMOVED)); +} + +#endif // COCOA_STATUS_SCREEN 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 new file mode 100644 index 000000000000..75b4333351c6 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.h @@ -0,0 +1,57 @@ +/******************************* + * cocoa_press/status_screen.h * + *******************************/ + +/**************************************************************************** + * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2019 - Cocoa Press * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#pragma once + +#define COCOA_STATUS_SCREEN +#define COCOA_STATUS_SCREEN_CLASS StatusScreen + +class StatusScreen : public BaseScreen, public CachedScreen { + private: + static float increment; + static bool jog_xy; + static bool fine_motion; + + static void draw_progress(draw_mode_t what); + static void draw_temperature(draw_mode_t what); + static void draw_syringe(draw_mode_t what); + static void draw_arrows(draw_mode_t what); + static void draw_overlay_icons(draw_mode_t what); + static void draw_fine_motion(draw_mode_t what); + static void draw_buttons(draw_mode_t what); + public: + static void loadBitmaps(); + static void unlockMotors(); + + static void setStatusMessage(const char *); + static void setStatusMessage(progmem_str); + + static void onRedraw(draw_mode_t); + + static bool onTouchStart(uint8_t tag); + static bool onTouchHeld(uint8_t tag); + static bool onTouchEnd(uint8_t tag); + static void onIdle(); + static void onMediaInserted(); + static void onMediaRemoved(); +}; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/compat.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/compat.h new file mode 100644 index 000000000000..dd25af1e74bd --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/compat.h @@ -0,0 +1,53 @@ +/************ + * compat.h * + ************/ + +/**************************************************************************** + * 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 + +/** + * This following provides compatibility whether compiling + * as a part of Marlin or outside it + */ + +#ifdef __has_include + #if __has_include("../ui_api.h") + #include "../ui_api.h" + #endif +#else + #include "../ui_api.h" +#endif + +#ifdef __MARLIN_FIRMWARE__ + // __MARLIN_FIRMWARE__ exists when compiled within Marlin. + #include "pin_mappings.h" + #undef max + #define max(a,b) ((a)>(b)?(a):(b)) + #undef min + #define min(a,b) ((a)<(b)?(a):(b)) +#else + namespace UI { + static inline uint32_t safe_millis() { return millis(); } + static inline void yield() {} + }; +#endif + +class __FlashStringHelper; +typedef const __FlashStringHelper *progmem_str; +extern const char G28_STR[]; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/config.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/config.h similarity index 93% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/config.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/config.h index 7476c9e67e4c..05e19b20e478 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/config.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/config.h @@ -16,11 +16,15 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once +// Configure this display with options in Configuration_adv.h +#include "../../../inc/MarlinConfigPre.h" +#if ENABLED(TOUCH_UI_FTDI_EVE) + #include "compat.h" -// Configure this display with options in Configuration_adv.h +#endif 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 new file mode 100644 index 000000000000..9faedae711d8 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp @@ -0,0 +1,157 @@ +/** + * 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 . + * + */ + +/** + * lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if ENABLED(TOUCH_UI_FTDI_EVE) + +#include "screens.h" + +namespace ExtUI { + using namespace Theme; + using namespace FTDI; + + void onStartup() { EventLoop::setup(); } + + void onIdle() { EventLoop::loop(); } + + void onPrinterKilled(PGM_P const error, PGM_P const component) { + char str[strlen_P(error) + strlen_P(component) + 3]; + sprintf_P(str, PSTR(S_FMT ": " S_FMT), error, component); + KillScreen::show(str); + } + + void onMediaInserted() { + #if ENABLED(SDSUPPORT) + sound.play(media_inserted, PLAY_ASYNCHRONOUS); + StatusScreen::onMediaInserted(); + #endif + } + + void onMediaRemoved() { + #if ENABLED(SDSUPPORT) + if (isPrintingFromMedia()) { + stopPrint(); + InterfaceSoundsScreen::playEventSound(InterfaceSoundsScreen::PRINTING_FAILED); + } + else + sound.play(media_removed, PLAY_ASYNCHRONOUS); + + StatusScreen::onMediaRemoved(); + FilesScreen::onMediaRemoved(); + #endif + } + + void onMediaError() { + sound.play(sad_trombone, PLAY_ASYNCHRONOUS); + AlertDialogBox::showError(F("Unable to read media.")); + } + + void onStatusChanged(const char *lcd_msg) { StatusScreen::setStatusMessage(lcd_msg); } + void onStatusChanged(progmem_str lcd_msg) { StatusScreen::setStatusMessage(lcd_msg); } + + void onPrintTimerStarted() { + InterfaceSoundsScreen::playEventSound(InterfaceSoundsScreen::PRINTING_STARTED); + } + void onPrintTimerStopped() { + InterfaceSoundsScreen::playEventSound(InterfaceSoundsScreen::PRINTING_FINISHED); + } + + void onPrintTimerPaused() {} + void onPrintFinished() {} + + void onFilamentRunout(const extruder_t extruder) { + char lcd_msg[30]; + sprintf_P(lcd_msg, PSTR("Extruder %d Filament Error"), extruder + 1); + StatusScreen::setStatusMessage(lcd_msg); + InterfaceSoundsScreen::playEventSound(InterfaceSoundsScreen::PRINTING_FAILED, FTDI::PLAY_SYNCHRONOUS); + } + + void onHomingStart() {} + void onHomingComplete() {} + + void onFactoryReset() { InterfaceSettingsScreen::defaultSettings(); } + void onStoreSettings(char *buff) { InterfaceSettingsScreen::saveSettings(buff); } + void onLoadSettings(const char *buff) { InterfaceSettingsScreen::loadSettings(buff); } + void onPostprocessSettings() {} // Called after loading or resetting stored settings + + void onConfigurationStoreWritten(bool success) { + #ifdef ARCHIM2_SPI_FLASH_EEPROM_BACKUP_SIZE + if (success && InterfaceSettingsScreen::backupEEPROM()) { + SERIAL_ECHOLNPGM("EEPROM backed up to SPI Flash"); + } + #else + UNUSED(success); + #endif + } + void onConfigurationStoreRead(bool) {} + + void onPlayTone(const uint16_t frequency, const uint16_t duration) { sound.play_tone(frequency, duration); } + + void onUserConfirmRequired(const char * const msg) { + if (msg) + ConfirmUserRequestAlertBox::show(msg); + else + ConfirmUserRequestAlertBox::hide(); + } + + #if HAS_LEVELING && HAS_MESH + void onMeshLevelingStart() {} + 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 + #endif + + #if HAS_PID_HEATING + void onPidTuning(const result_t rst) { + // Called for temperature PID tuning result + //SERIAL_ECHOLNPAIR("OnPidTuning:", rst); + switch (rst) { + case PID_BAD_EXTRUDER_NUM: + StatusScreen::setStatusMessage(GET_TEXT_F(MSG_PID_BAD_EXTRUDER_NUM)); + break; + case PID_TEMP_TOO_HIGH: + StatusScreen::setStatusMessage(GET_TEXT_F(MSG_PID_TEMP_TOO_HIGH)); + break; + case PID_TUNING_TIMEOUT: + StatusScreen::setStatusMessage(GET_TEXT_F(MSG_PID_TIMEOUT)); + break; + case PID_DONE: + StatusScreen::setStatusMessage(GET_TEXT_F(MSG_PID_AUTOTUNE_DONE)); + break; + } + GOTO_SCREEN(StatusScreen); + } + #endif // HAS_PID_HEATING + + void onSteppersDisabled() {} + void onSteppersEnabled() {} +} + +#endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/LICENSE.txt b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/LICENSE.txt similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/LICENSE.txt rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/LICENSE.txt diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/README.md b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/README.md similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/README.md rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/README.md 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 new file mode 100644 index 000000000000..19f926d8e086 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/boards.h @@ -0,0 +1,281 @@ +/************ + * boards.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 HAS_RESOLUTION (defined(TOUCH_UI_320x240) || defined(TOUCH_UI_480x272) || defined(TOUCH_UI_800x480)) + +#define IS_FT800 \ + constexpr uint16_t ftdi_chip = 800; \ + using namespace FTDI_FT800; \ + namespace DL { \ + using namespace FTDI_FT800_DL; \ + } \ + typedef ft800_memory_map ftdi_memory_map; \ + typedef ft800_registers ftdi_registers; + +#define IS_FT810 \ + constexpr uint16_t ftdi_chip = 810; \ + using namespace FTDI_FT810; \ + namespace DL { \ + using namespace FTDI_FT800_DL; \ + using namespace FTDI_FT810_DL; \ + } \ + typedef ft810_memory_map ftdi_memory_map; \ + typedef ft810_registers ftdi_registers; + +#ifdef LCD_FTDI_VM800B35A + #if !HAS_RESOLUTION + #define TOUCH_UI_320x240 + #endif + #ifndef FTDI_API_LEVEL + #define FTDI_API_LEVEL 800 + #endif + namespace FTDI { + IS_FT800 + constexpr bool Use_Crystal = true; // 0 = use internal oscillator, 1 = module has a crystal populated + constexpr bool GPIO_0_Audio_Enable = false; /* 1 = does use GPIO00 for amplifier control, 0 = not in use for Audio */ + constexpr bool GPIO_1_Audio_Shutdown = true; /* 1 = does use GPIO01 for amplifier control, 0 = not in use for Audio */ + constexpr uint8_t Swizzle = 2; + constexpr uint8_t CSpread = 1; + + constexpr uint16_t touch_threshold = 1200; /* touch-sensitivity */ + } + +/** + * Settings for the Haoyu Electronics, 4.3" Graphical LCD Touchscreen, 480x272, SPI, FT800 (FT800CB-HY43B) + * and 5" Graphical LCD Touchscreen, 480x272, SPI, FT800 (FT800CB-HY50B) + * http://www.hotmcu.com/43-graphical-lcd-touchscreen-480x272-spi-ft800-p-111.html?cPath=6_16 + * http://www.hotmcu.com/5-graphical-lcd-touchscreen-480x272-spi-ft800-p-124.html?cPath=6_16 + * Datasheet: + * https://www.hantronix.com/files/data/1278363262430-3.pdf + * https://www.haoyuelectronics.com/Attachment/HY43-LCD/LCD%20DataSheet.pdf + * https://www.haoyuelectronics.com/Attachment/HY5-LCD-HD/KD50G21-40NT-A1.pdf + */ +#elif defined(LCD_HAOYU_FT800CB) + #if !HAS_RESOLUTION + #define TOUCH_UI_480x272 + #endif + #ifndef FTDI_API_LEVEL + #define FTDI_API_LEVEL 800 + #endif + namespace FTDI { + IS_FT800 + constexpr bool Use_Crystal = true; // 0 = use internal oscillator, 1 = module has a crystal populated + constexpr bool GPIO_0_Audio_Enable = false; + constexpr bool GPIO_1_Audio_Shutdown = false; + constexpr uint8_t Swizzle = 0; + constexpr uint8_t CSpread = 1; + constexpr uint16_t touch_threshold = 2000; /* touch-sensitivity */ + } + +/** + * Settings for the Haoyu Electronics, 5" Graphical LCD Touchscreen, 800x480, SPI, FT810 + * http://www.hotmcu.com/5-graphical-lcd-touchscreen-800x480-spi-ft810-p-286.html + * Datasheet: + * https://www.haoyuelectronics.com/Attachment/HY5-LCD-HD/KD50G21-40NT-A1.pdf + */ +#elif defined(LCD_HAOYU_FT810CB) + #if !HAS_RESOLUTION + #define TOUCH_UI_800x480 + #endif + #ifndef FTDI_API_LEVEL + #define FTDI_API_LEVEL 810 + #endif + namespace FTDI { + IS_FT810 + constexpr bool Use_Crystal = true; // 0 = use internal oscillator, 1 = module has a crystal populated + constexpr bool GPIO_0_Audio_Enable = false; + constexpr bool GPIO_1_Audio_Shutdown = false; + constexpr uint8_t Swizzle = 0; + constexpr uint8_t CSpread = 1; + constexpr uint16_t touch_threshold = 2000; /* touch-sensitivity */ + } + +/** + * Settings for the 4D Systems, 4.3" Embedded SPI Display 480x272, SPI, FT800 (4DLCD-FT843) + * https://4dsystems.com.au/4dlcd-ft843 + * Datasheet: + * https://4dsystems.com.au/mwdownloads/download/link/id/52/ + */ +#elif defined(LCD_4DSYSTEMS_4DLCD_FT843) + #if !HAS_RESOLUTION + #define TOUCH_UI_480x272 + #endif + #ifndef FTDI_API_LEVEL + #define FTDI_API_LEVEL 800 + #endif + namespace FTDI { + IS_FT800 + constexpr bool Use_Crystal = true; // 0 = use internal oscillator, 1 = module has a crystal populated + constexpr bool GPIO_0_Audio_Enable = false; + constexpr bool GPIO_1_Audio_Shutdown = true; + constexpr uint8_t Swizzle = 0; + constexpr uint8_t CSpread = 1; + constexpr uint16_t touch_threshold = 1200; /* touch-sensitivity */ + } + +/** + * Settings for the Aleph Objects Color LCD User Interface + * Datasheet https://www.hantronix.com/files/data/s1501799605s500-gh7.pdf + */ +#elif defined(LCD_ALEPHOBJECTS_CLCD_UI) + #if !HAS_RESOLUTION + #define TOUCH_UI_800x480 + #endif + #ifndef FTDI_API_LEVEL + #define FTDI_API_LEVEL 810 + #endif + namespace FTDI { + IS_FT810 + constexpr bool Use_Crystal = false; // 0 = use internal oscillator, 1 = module has a crystal populated + constexpr bool GPIO_0_Audio_Enable = true; // The AO CLCD uses GPIO0 to enable audio + constexpr bool GPIO_1_Audio_Shutdown = false; + constexpr uint8_t Swizzle = 0; + constexpr uint8_t CSpread = 0; + constexpr uint16_t touch_threshold = 2000; /* touch-sensitivity */ + } + +/** + * FYSETC Color LCD + * https://www.aliexpress.com/item/4000627651757.html + * Product information: + * https://github.com/FYSETC/TFT81050 + */ +#elif defined(LCD_FYSETC_TFT81050) + #if !HAS_RESOLUTION + #define TOUCH_UI_800x480 + #endif + #ifndef FTDI_API_LEVEL + #define FTDI_API_LEVEL 810 + #endif + namespace FTDI { + IS_FT810 + constexpr bool Use_Crystal = false; // 0 = use internal oscillator, 1 = module has a crystal populated + constexpr bool GPIO_0_Audio_Enable = true; // The AO CLCD uses GPIO0 to enable audio + constexpr bool GPIO_1_Audio_Shutdown = false; + constexpr uint8_t Swizzle = 0; + constexpr uint8_t CSpread = 0; + constexpr uint16_t touch_threshold = 2000; /* touch-sensitivity */ + } + +/** + * Settings for EVE3-50G - Matrix Orbital 5.0" 800x480, BT815 + * https://www.matrixorbital.com/ftdi-eve/eve-bt815-bt816/eve3-50g + * use for example with: https://github.com/RudolphRiedel/EVE_display-adapter + */ +#elif defined(LCD_EVE3_50G) + #if !HAS_RESOLUTION + #define TOUCH_UI_800x480 + #define TOUCH_UI_800x480_GENERIC // use more common timing parameters as the original set + #endif + #ifndef FTDI_API_LEVEL + #define FTDI_API_LEVEL 810 + #endif + namespace FTDI { + IS_FT810 + constexpr bool Use_Crystal = true; // 0 = use internal oscillator, 1 = module has a crystal populated + constexpr bool GPIO_0_Audio_Enable = false; + constexpr bool GPIO_1_Audio_Shutdown = false; + #define USE_GT911 // this display uses an alternative touch-controller and we need to tell the init function to switch + constexpr uint8_t Swizzle = 0; + constexpr uint8_t CSpread = 1; + constexpr uint8_t Pclkpol = 1; + constexpr uint16_t touch_threshold = 1200; /* touch-sensitivity */ + + constexpr uint32_t default_transform_a = 0x000109E4; + constexpr uint32_t default_transform_b = 0x000007A6; + constexpr uint32_t default_transform_c = 0xFFEC1EBA; + constexpr uint32_t default_transform_d = 0x0000072C; + constexpr uint32_t default_transform_e = 0x0001096A; + constexpr uint32_t default_transform_f = 0xFFF469CF; + } + +/** + * Settings for EVE2-50G - Matrix Orbital 5.0" 800x480, FT813 + * https://www.matrixorbital.com/ftdi-eve/eve-bt815-bt816/eve3-50g + * use for example with: https://github.com/RudolphRiedel/EVE_display-adapter + */ +#elif defined(LCD_EVE2_50G) + #if !HAS_RESOLUTION + #define TOUCH_UI_800x480 + #define TOUCH_UI_800x480_GENERIC // use more common timing parameters as the original set + #endif + #ifndef FTDI_API_LEVEL + #define FTDI_API_LEVEL 810 + #endif + namespace FTDI { + IS_FT810 + constexpr bool Use_Crystal = false; // 0 = use internal oscillator, 1 = module has a crystal populated + constexpr bool GPIO_0_Audio_Enable = false; + constexpr bool GPIO_1_Audio_Shutdown = false; + #define PATCH_GT911 // this display uses an alternative touch-controller and we need to tell the init function to patch the FT813 for it + constexpr uint8_t Pclkpol = 1; + constexpr uint8_t Swizzle = 0; + constexpr uint8_t CSpread = 1; + constexpr uint16_t touch_threshold = 1200; /* touch-sensitivity */ + + constexpr uint32_t default_transform_a = 0x000109E4; + constexpr uint32_t default_transform_b = 0x000007A6; + constexpr uint32_t default_transform_c = 0xFFEC1EBA; + constexpr uint32_t default_transform_d = 0x0000072C; + constexpr uint32_t default_transform_e = 0x0001096A; + constexpr uint32_t default_transform_f = 0xFFF469CF; + } + +#else + + #error "Unknown or no TOUCH_UI_FTDI_EVE board specified. To add a new board, modify this file." + +#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[] = { + 26,255,255,255,32,32,48,0,4,0,0,0,2,0,0,0, + 34,255,255,255,0,176,48,0,120,218,237,84,221,111,84,69,20,63,51,179,93,160,148,101,111,76,5,44,141,123,111,161,11,219,154,16,9,16,17,229,156,75,26,11,13,21,227,3,16,252,184,179, + 45,219,143,45,41,125,144,72,67,100,150,71,189,113,18,36,17,165,100,165,198,16,32,17,149,196,240,128,161,16,164,38,54,240,0,209,72,130,15,38,125,48,66,82,30,76,19,31,172,103,46, + 139,24,255,4,227,157,204,156,51,115,102,206,231,239,220,5,170,94,129,137,75,194,216,98,94,103,117,115,121,76,131,177,125,89,125,82,123,60,243,58,142,242,204,185,243,188,118,156, + 227,155,203,238,238,195,251,205,229,71,92,28,169,190,184,84,143,113,137,53,244,103,181,237,87,253,113,137,233,48,12,198,165,181,104,139,25,84,253,155,114,74,191,0,54,138,163, + 12,62,131,207,129,23,217,34,91,31,128,65,246,163,175,213,8,147,213,107,35,203,94,108,3,111,40,171,83,24,15,165,177,222,116,97,23,188,140,206,150,42,102,181,87,78,86,182,170,134, + 215,241,121,26,243,252,2,76,115,217,139,222,206,173,136,132,81,61,35,185,39,113,23,46,199,76,178,54,151,183,224,0,40,189,28,149,182,58,131,79,152,30,76,34,98,234,162,216,133,141, + 102,39,170,40,192,101,53,201,146,191,37,77,44,177,209,74,211,5,206,187,5,6,216,47,53,96,123,22,50,103,251,192,84,17,74,227,185,56,106,51,91,161,96,182,163,48,171,141,139,65,152, + 66,66,11,102,43,158,75,36,80,147,184,147,139,112,17,235,216,103,111,239,245,92,10,175,194,40,44,58,125,5,59,112,50,103,245,4,78,192,5,156,194,51,60,191,134,75,110,173,237,46,192, + 121,156,192,115,184,218,120,67,63,115,46,11,102,10,97,232,50,235,114,182,148,118,178,41,188,12,135,77,202,124,12,96,238,35,161,234,189,129,23,249,212,139,230,25,53,48,205,52,93, + 163,117,53,154,170,81,85,163,178,70,69,66,167,241,14,46,241,1,226,136,152,179,197,59,184,148,254,49,132,48,15,176,137,192,76,131,196,105,104,162,86,81,160,165,255,26,173,162,137, + 86,145,210,183,192,55,175,194,211,60,91,120,230,184,174,27,41,131,155,40,224,29,87,179,232,16,55,55,7,165,147,81,23,165,49,101,54,224,75,180,81,108,18,29,226,69,225,110,175,224, + 42,212,25,47,130,193,110,234,192,215,252,56,74,162,24,46,251,174,54,106,68,245,14,9,155,160,22,120,207,104,240,29,90,178,140,28,24,220,47,166,112,61,251,208,192,111,56,239,238, + 93,255,251,62,99,32,193,75,61,190,235,123,229,110,218,194,85,79,225,59,98,20,238,227,235,220,11,221,149,25,180,116,194,159,111,96,192,24,213,59,139,179,156,215,69,230,19,24,35, + 135,117,206,171,206,162,67,129,234,61,235,11,104,103,84,64,223,167,254,40,163,101,92,84,43,150,46,249,219,205,7,116,11,91,104,61,57,75,223,8,48,25,28,119,252,222,113,49,86,249, + 74,180,211,156,181,61,215,168,157,7,251,199,150,242,250,91,58,132,94,121,7,53,151,139,98,6,165,153,69,214,32,110,211,100,101,31,89,45,81,98,23,205,205,197,209,109,186,198,35, + 141,191,249,25,60,132,223,153,251,98,20,239,146,139,20,217,250,41,250,137,58,177,90,57,79,51,108,233,20,253,194,187,49,222,205,114,141,96,48,175,219,107,54,111,138,22,154,103, + 108,79,58,252,179,178,79,164,195,2,153,36,39,170,199,201,167,197,85,106,8,59,177,81,46,56,2,230,75,114,17,55,112,188,65,208,137,77,114,10,115,55,58,208,197,173,122,87,6,140, + 110,42,208,124,163,70,108,241,104,18,245,98,214,187,134,53,42,221,22,182,133,211,116,148,177,194,209,192,85,90,199,58,55,203,2,229,19,137,187,161,228,154,112,203,145,125,244, + 188,220,118,228,41,201,181,41,195,144,215,183,51,80,250,21,217,16,217,200,235,109,227,188,122,218,142,60,170,224,112,240,184,130,229,224,113,5,223,148,163,80,165,183,130,187, + 132,116,64,238,161,85,220,115,139,205,98,227,244,29,102,125,7,37,243,123,223,11,26,92,63,243,116,61,191,138,123,244,160,84,186,74,31,5,174,247,119,135,199,248,253,135,242,97, + 102,145,190,144,14,85,238,221,231,193,158,48,205,25,120,248,15,220,29,158,9,70,185,30,103,229,33,254,23,237,160,172,62,193,90,222,224,232,14,200,56,90,104,142,227,120,110,6, + 21,211,203,65,150,99,151,220,247,87,164,50,159,49,239,234,58,142,0,109,108,123,18,79,227,36,100,248,222,205,96,127,120,26,171,228,69,63,36,17,252,200,17,116,242,187,227,88,143, + 247,2,75,191,6,130,59,188,11,55,240,31,243,122,152,226,183,207,154,73,188,39,219,43,105,222,87,41,143,141,140,175,73,112,184,252,61,184,16,90,250,35,168,82,119,176,57,116,94, + 200,150,22,190,179,44,104,12,235,84,149,102,252,89,154,193,99,228,106,242,125,248,64,194,255,223,127,242,83,11,255,2,70,214,226,128,0,0 + }; +#endif // PATCH_GT911 diff --git a/Marlin/src/lcd/extui/lib/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 similarity index 92% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp index bb95411e06fd..a10fdc3ede35 100644 --- a/Marlin/src/lcd/extui/lib/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 @@ -17,7 +17,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "ftdi_basic.h" @@ -211,6 +211,14 @@ void CLCD::mem_write_32(uint32_t reg_address, uint32_t data) { spi_ftdi_deselect(); } +// Fill area of len size with repeated data bytes +void CLCD::mem_write_fill(uint32_t reg_address, uint8_t data, uint16_t len) { + spi_ftdi_select(); + spi_write_addr(reg_address); + while (len--) spi_write_8(data); + spi_ftdi_deselect(); +} + /******************* FT800/810 Co-processor Commands *********************************/ #if FTDI_API_LEVEL == 800 @@ -221,7 +229,7 @@ void CLCD::CommandFifo::cmd(uint32_t cmd32) { write((void*)&cmd32, sizeof(uint32_t)); } -void CLCD::CommandFifo::cmd(void* data, uint16_t len) { +void CLCD::CommandFifo::cmd(void *data, uint16_t len) { write(data, len); } @@ -894,6 +902,7 @@ bool CLCD::CommandFifo::has_fault() { } #if FTDI_API_LEVEL == 800 + void CLCD::CommandFifo::start() { if (command_write_ptr == 0xFFFFFFFFul) { command_write_ptr = mem_read_32(REG::CMD_WRITE) & 0x0FFF; @@ -971,12 +980,13 @@ template bool CLCD::CommandFifo::_write_unaligned(T data, uint16_t len template bool CLCD::CommandFifo::write(T data, uint16_t len) { const uint8_t padding = MULTIPLE_OF_4(len) - len; - - uint8_t pad_bytes[] = {0, 0, 0, 0}; + const uint8_t pad_bytes[] = { 0, 0, 0, 0 }; return _write_unaligned(data, len) && _write_unaligned(pad_bytes, padding); } -#else + +#else // FTDI_API_LEVEL != 800 ... + void CLCD::CommandFifo::start() { } @@ -1034,13 +1044,29 @@ template bool CLCD::CommandFifo::write(T data, uint16_t len) { mem_write_bulk(REG::CMDB_WRITE, data, len, padding); return true; } -#endif + +#endif // ... FTDI_API_LEVEL != 800 template bool CLCD::CommandFifo::write(const void*, uint16_t); template bool CLCD::CommandFifo::write(progmem_str, uint16_t); // CO_PROCESSOR COMMANDS +void CLCD::CommandFifo::str(const char * data, size_t maxlen) { + // Write the string without the terminating '\0' + const size_t len = strnlen(data, maxlen); + write(data, len); + + // If padding was added by the previous write, then + // the string is terminated. Otherwise write four + // more zeros. + const uint8_t padding = MULTIPLE_OF_4(len) - len; + if (padding == 0) { + const uint8_t pad_bytes[] = {0, 0, 0, 0}; + write(pad_bytes, 4); + } +} + void CLCD::CommandFifo::str(const char * data) { write(data, strlen(data)+1); } @@ -1053,7 +1079,7 @@ void CLCD::CommandFifo::str(progmem_str data) { void CLCD::init() { spi_init(); // Set Up I/O Lines for SPI and FT800/810 Control - ftdi_reset(); // Power down/up the FT8xx with the apropriate delays + ftdi_reset(); // Power down/up the FT8xx with the appropriate delays host_cmd(Use_Crystal ? CLKEXT : CLKINT, 0); host_cmd(FTDI::ACTIVE, 0); // Activate the System Clock @@ -1065,40 +1091,48 @@ void CLCD::init() { for (counter = 0; counter < 250; counter++) { uint8_t device_id = mem_read_8(REG::ID); // Read Device ID, Should Be 0x7C; if (device_id == 0x7C) { - #if ENABLED(TOUCH_UI_DEBUG) - SERIAL_ECHO_MSG("FTDI chip initialized "); - #endif + if (ENABLED(TOUCH_UI_DEBUG)) SERIAL_ECHO_MSG("FTDI chip initialized "); break; } else delay(1); - if (counter == 249) { - #if ENABLED(TOUCH_UI_DEBUG) - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR("Timeout waiting for device ID, should be 124, got ", device_id); - #endif - } + if (TERN0(TOUCH_UI_DEBUG, counter > 248)) + SERIAL_ECHO_MSG("Timeout waiting for device ID, should be 124, got ", device_id); } - /* make sure that all units are in working conditions, usually the touch-controller needs a little more time */ + /* Ensure all units are in working condition, usually the touch-controller needs a little more time */ for (counter = 0; counter < 100; counter++) { uint8_t reset_status = mem_read_8(REG::CPURESET) & 0x03; if (reset_status == 0x00) { - #if ENABLED(TOUCH_UI_DEBUG) - SERIAL_ECHO_MSG("FTDI chip all units running "); - #endif + if (ENABLED(TOUCH_UI_DEBUG)) SERIAL_ECHO_MSG("FTDI chip all units running "); break; } else delay(1); - if (ENABLED(TOUCH_UI_DEBUG) && counter == 99) { - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR("Timeout waiting for reset status. Should be 0x00, got ", reset_status); - } + if (TERN0(TOUCH_UI_DEBUG, counter > 98)) + SERIAL_ECHO_MSG("Timeout waiting for reset status. Should be 0x00, got ", reset_status); } + #if ENABLED(USE_GT911) /* switch BT815 to use Goodix GT911 touch controller */ + mem_write_32(REG::TOUCH_CONFIG, 0x000005D1); + #endif + + #if ENABLED(PATCH_GT911) /* patch FT813 use Goodix GT911 touch controller */ + mem_write_pgm(REG::CMDB_WRITE, GT911_data, sizeof(GT911_data)); /* write binary blob to command-fifo */ + delay(10); + mem_write_8(REG::TOUCH_OVERSAMPLE, 0x0F); /* setup oversample to 0x0f as "hidden" in binary-blob for AN_336 */ + mem_write_16(REG::TOUCH_CONFIG, 0x05d0); /* write magic cookie as requested by AN_336 */ + + /* specific to the EVE2 modules from Matrix-Orbital we have to use GPIO3 to reset GT911 */ + mem_write_16(REG::GPIOX_DIR,0x8008); /* Reset-Value is 0x8000, adding 0x08 sets GPIO3 to output, default-value for REG_GPIOX is 0x8000 -> Low output on GPIO3 */ + delay(1); /* wait more than 100µs */ + mem_write_8(REG::CPURESET, 0x00); /* clear all resets */ + delay(56); /* wait more than 55ms */ + mem_write_16(REG::GPIOX_DIR,0x8000); /* setting GPIO3 back to input */ + #endif + mem_write_8(REG::PWM_DUTY, 0); // turn off Backlight, Frequency already is set to 250Hz default /* Configure the FT8xx Registers */ @@ -1135,13 +1169,13 @@ void CLCD::init() { if (GPIO_1_Audio_Shutdown) { mem_write_8(REG::GPIO_DIR, GPIO_DISP | GPIO_GP1); mem_write_8(REG::GPIO, GPIO_DISP | GPIO_GP1); - } else if (GPIO_0_Audio_Enable) { + } + else if (GPIO_0_Audio_Enable) { mem_write_8(REG::GPIO_DIR, GPIO_DISP | GPIO_GP0); mem_write_8(REG::GPIO, GPIO_DISP | GPIO_GP0); } - else { + else mem_write_8(REG::GPIO, GPIO_DISP); /* REG::GPIO_DIR is set to output for GPIO_DISP by default */ - } mem_write_8(REG::PCLK, Pclk); // Turns on Clock by setting PCLK Register to the value necessary for the module diff --git a/Marlin/src/lcd/extui/lib/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 similarity index 98% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.h index a9fdb5c5c73c..9fc5195fd4d3 100644 --- a/Marlin/src/lcd/extui/lib/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 @@ -17,7 +17,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ /**************************************************************************** @@ -70,7 +70,7 @@ * * CommandFifo::fgcolor Set Graphic Item Foreground Color * * CommandFifo::bgcolor Set Graphic Item Background Color * - * CommandFifo::begin() Begin Drawing a Primative * + * CommandFifo::begin() Begin Drawing a Primitive * * CommandFifo::mem_copy() Copy a Block of Memory * * CommandFifo::append() Append Commands to Current DL * * CommandFifo::gradient_color() Set 3D Button Highlight Color * @@ -115,6 +115,7 @@ class CLCD { static void mem_write_8 (uint32_t reg_address, uint8_t w_data); static void mem_write_16 (uint32_t reg_address, uint16_t w_data); static void mem_write_32 (uint32_t reg_address, uint32_t w_data); + 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_bulk (uint32_t reg_address, progmem_str str, uint16_t len, uint8_t padding = 0); @@ -195,7 +196,7 @@ class CLCD::CommandFifo { void execute(); void cmd(uint32_t cmd32); - void cmd(void* data, uint16_t len); + void cmd(void *data, uint16_t len); void dlstart() {cmd(FTDI::CMD_DLSTART);} void swap() {cmd(FTDI::CMD_SWAP);} @@ -247,6 +248,7 @@ class CLCD::CommandFifo { void keys (int16_t x, int16_t y, int16_t w, int16_t h, int16_t font, uint16_t options); // Sends the string portion of text, button, toggle and keys. + void str (const char * data, size_t maxlen); void str (const char * data); void str (progmem_str data); diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/constants.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/constants.h similarity index 99% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/constants.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/constants.h index 1e6642fedc19..20b1a3e9752e 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/constants.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/constants.h @@ -17,7 +17,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ /**************************************************************************** @@ -95,6 +95,7 @@ namespace FTDI_FT810 { namespace FTDI { constexpr uint8_t ARGB1555 = 0; constexpr uint8_t L1 = 1; + constexpr uint8_t L2 = 17; constexpr uint8_t L4 = 2; constexpr uint8_t L8 = 3; constexpr uint8_t RGB332 = 4; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/display_list.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/display_list.h similarity index 99% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/display_list.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/display_list.h index 99a9e0e81089..d6afe78f7cda 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/display_list.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/display_list.h @@ -64,14 +64,14 @@ namespace FTDI { inline uint32_t CLEAR_COLOR_A(uint8_t alpha) {return DL::CLEAR_COLOR_A|(alpha&255UL);} inline uint32_t CLEAR_COLOR_RGB(uint8_t red, uint8_t green, uint8_t blue) {return DL::CLEAR_COLOR_RGB|((red&255UL)<<16)|((green&255UL)<<8)|(blue&255UL);} - inline uint32_t CLEAR_COLOR_RGB(uint32_t rgb) {return DL::CLEAR_COLOR_RGB|rgb;} + inline uint32_t CLEAR_COLOR_RGB(uint32_t rgb) {return DL::CLEAR_COLOR_RGB|(rgb&0xFFFFFF);} inline uint32_t CLEAR_STENCIL(uint8_t s) {return DL::CLEAR_STENCIL|(s&255UL);} inline uint32_t CLEAR_TAG(uint8_t s) {return DL::CLEAR_TAG|(s&255UL);} inline uint32_t COLOR_A(uint8_t alpha) {return DL::COLOR_A|(alpha&255UL);} inline uint32_t COLOR_MASK(bool r, bool g, bool b, bool a) {return DL::COLOR_MASK|((r?1UL:0UL)<<3)|((g?1UL:0UL)<<2)|((b?1UL:0UL)<<1)|(a?1UL:0UL);} inline uint32_t COLOR_RGB(uint8_t red,uint8_t green,uint8_t blue) {return DL::COLOR_RGB|((red&255UL)<<16)|((green&255UL)<<8)|(blue&255UL);} - inline uint32_t COLOR_RGB(uint32_t rgb) {return DL::COLOR_RGB|rgb;} + inline uint32_t COLOR_RGB(uint32_t rgb) {return DL::COLOR_RGB|(rgb&0xFFFFFF);} /* inline uint32_t DISPLAY() {return (0UL<<24)) */ inline uint32_t END() {return DL::END;} inline uint32_t JUMP(uint16_t dest) {return DL::JUMP|(dest&65535UL);} diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/ftdi_basic.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/ftdi_basic.h similarity index 99% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/ftdi_basic.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/ftdi_basic.h index 75a2d54fca52..47cd698253c3 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/ftdi_basic.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/ftdi_basic.h @@ -17,7 +17,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/registers_ft800.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/registers_ft800.h similarity index 99% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/registers_ft800.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/registers_ft800.h index 4063bf2d5dc7..26053709d3ca 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/registers_ft800.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/registers_ft800.h @@ -17,7 +17,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ /**************************************************************************** diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/registers_ft810.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/registers_ft810.h similarity index 99% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/registers_ft810.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/registers_ft810.h index 448717b47834..e57d11c3a736 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/registers_ft810.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/registers_ft810.h @@ -17,7 +17,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ /**************************************************************************** diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/resolutions.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/resolutions.h new file mode 100644 index 000000000000..0c600fa0a580 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/resolutions.h @@ -0,0 +1,142 @@ +/***************** + * resolutions.h * + *****************/ + +/**************************************************************************** + * Written By Mark Pelletier 2019 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2019 - 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 + +/*** + * The FT8xx has odd registers that don't correspond to timing values in + * display datasheets. This macro computes the register values using the + * formulas given in the document: + * + * Bridgetek Application Note + * AN_336 FT8xx + * Selecting an LCD Display + * Version 2.1 + * Issue Date: 2017-11-14 + */ +#define COMPUTE_REGS_FROM_DATASHEET \ + constexpr uint16_t Hoffset = thfp + thb - 1; \ + constexpr uint16_t Hcycle = th; \ + constexpr uint16_t Hsync0 = thfp - 1 ; \ + constexpr uint16_t Hsync1 = thfp + thpw - 1; \ + constexpr uint16_t Voffset = tvfp + tvb - 1; \ + constexpr uint16_t Vcycle = tv; \ + constexpr uint16_t Vsync0 = tvfp - 1; \ + constexpr uint16_t Vsync1 = tvfp + tvpw - 1; \ + static_assert(thfp + thb + Hsize == th, "Mismatch in display th"); \ + static_assert(tvfp + tvb + Vsize == tv, "Mismatch in display tv") + +#if ENABLED(TOUCH_UI_320x240) + namespace FTDI { + constexpr uint8_t Pclk = 8; + constexpr uint8_t Pclkpol = 0; + constexpr uint16_t Hsize = 320; + constexpr uint16_t Vsize = 240; + constexpr uint16_t Vsync0 = 0; + constexpr uint16_t Vsync1 = 2; + constexpr uint16_t Voffset = 13; + constexpr uint16_t Vcycle = 263; + constexpr uint16_t Hsync0 = 0; + constexpr uint16_t Hsync1 = 10; + constexpr uint16_t Hoffset = 70; + constexpr uint16_t Hcycle = 408; + + constexpr uint32_t default_transform_a = 0x000054AD; + constexpr uint32_t default_transform_b = 0xFFFFFF52; + constexpr uint32_t default_transform_c = 0xFFF7F6E4; + constexpr uint32_t default_transform_d = 0x00000065; + constexpr uint32_t default_transform_e = 0xFFFFBE3B; + constexpr uint32_t default_transform_f = 0x00F68E75; + } + +#elif defined(TOUCH_UI_480x272) + namespace FTDI { + constexpr uint8_t Pclk = 7; + constexpr uint8_t Pclkpol = 1; + constexpr uint16_t Hsize = 480; + constexpr uint16_t Vsize = 272; + + constexpr uint16_t th = 525; // One horizontal line + constexpr uint16_t thfp = 43; // HS Front porch + constexpr uint16_t thb = 2; // HS Back porch (blanking) + constexpr uint16_t thpw = 41; // HS pulse width + + constexpr uint16_t tv = 286; // Vertical period time + constexpr uint16_t tvfp = 12; // VS Front porch + constexpr uint16_t tvb = 2; // VS Back porch (blanking) + constexpr uint16_t tvpw = 10; // VS pulse width + + COMPUTE_REGS_FROM_DATASHEET; + + constexpr uint32_t default_transform_a = 0x00008100; + constexpr uint32_t default_transform_b = 0x00000000; + constexpr uint32_t default_transform_c = 0xFFF18000; + constexpr uint32_t default_transform_d = 0x00000000; + constexpr uint32_t default_transform_e = 0xFFFFB100; + constexpr uint32_t default_transform_f = 0x0120D000; + } + +#elif defined(TOUCH_UI_800x480) + namespace FTDI { + #if defined(TOUCH_UI_800x480_GENERIC) + constexpr uint8_t Pclk = 2; + constexpr uint16_t Hsize = 800; + constexpr uint16_t Vsize = 480; + + constexpr uint16_t Vsync0 = 0; + constexpr uint16_t Vsync1 = 3; + constexpr uint16_t Voffset = 32; + constexpr uint16_t Vcycle = 525; + constexpr uint16_t Hsync0 = 0; + constexpr uint16_t Hsync1 = 48; + constexpr uint16_t Hoffset = 88; + constexpr uint16_t Hcycle = 928; + #else + constexpr uint8_t Pclk = 3; + constexpr uint8_t Pclkpol = 1; + constexpr uint16_t Hsize = 800; + constexpr uint16_t Vsize = 480; + + constexpr uint16_t th = 1056; // One horizontal line + constexpr uint16_t thfp = 210; // HS Front porch + constexpr uint16_t thb = 46; // HS Back porch (blanking) + constexpr uint16_t thpw = 23; // HS pulse width + + constexpr uint16_t tv = 525; // Vertical period time + constexpr uint16_t tvfp = 22; // VS Front porch + constexpr uint16_t tvb = 23; // VS Back porch (blanking) + constexpr uint16_t tvpw = 10; // VS pulse width + + COMPUTE_REGS_FROM_DATASHEET; + + constexpr uint32_t default_transform_a = 0x0000D8B9; + constexpr uint32_t default_transform_b = 0x00000124; + constexpr uint32_t default_transform_c = 0xFFE23926; + constexpr uint32_t default_transform_d = 0xFFFFFF51; + constexpr uint32_t default_transform_e = 0xFFFF7E4F; + constexpr uint32_t default_transform_f = 0x01F0AF70; + #endif + } + +#else + #error "Unknown or no TOUCH_UI_FTDI_EVE display resolution specified. To add a display resolution, modify 'ftdi_eve_resolutions.h'." +#endif diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp similarity index 97% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp index d91d08fbfa05..30f778e9f51c 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp @@ -17,7 +17,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "ftdi_basic.h" @@ -33,7 +33,7 @@ namespace FTDI { SPIClass EVE_SPI(CLCD_SPI_BUS); #endif #ifndef CLCD_HW_SPI_SPEED - #define CLCD_HW_SPI_SPEED 8000000 >> SPI_SPEED + #define CLCD_HW_SPI_SPEED 8000000 >> SD_SPI_SPEED #endif SPISettings SPI::spi_settings(CLCD_HW_SPI_SPEED, MSBFIRST, SPI_MODE0); #endif @@ -103,12 +103,12 @@ namespace FTDI { #endif void SPI::spi_read_bulk(void *data, uint16_t len) { - uint8_t* p = (uint8_t *)data; + uint8_t *p = (uint8_t *)data; while (len--) *p++ = spi_recv(); } bool SPI::spi_verify_bulk(const void *data, uint16_t len) { - const uint8_t* p = (const uint8_t *)data; + const uint8_t *p = (const uint8_t *)data; while (len--) if (*p++ != spi_recv()) return false; return true; } diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.h similarity index 98% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.h index 30ec786c60ae..7adf7e9c53a2 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.h @@ -17,7 +17,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once @@ -116,14 +116,14 @@ namespace FTDI { template void spi_write_bulk(const void *data, uint16_t len, uint8_t padding) { - const uint8_t* p = (const uint8_t *)data; + const uint8_t *p = (const uint8_t *)data; while (len--) spi_send(byte_op(p++)); while (padding--) spi_send(0); } template void spi_write_bulk(const void *data, uint16_t len) { - const uint8_t* p = (const uint8_t *)data; + const uint8_t *p = (const uint8_t *)data; while (len--) spi_send(byte_op(p++)); } 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 new file mode 100644 index 000000000000..b4438a92b976 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h @@ -0,0 +1,298 @@ +/**************************************************************************** + * 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 + +#include "../config.h" + +#ifdef __MARLIN_FIRMWARE__ + + // Marlin will define the I/O functions for us + #if ENABLED(TOUCH_UI_FTDI_EVE) + #define FTDI_BASIC + #define FTDI_EXTENDED + #endif + +#else // !__MARLIN_FIRMWARE__ + + #include + + #ifndef CLCD_USE_SOFT_SPI + #include + #endif + + namespace fast_io { + + template + struct port_pin { + typedef port_t port; + static inline void set_high() {port::port() = (port::port() | bits);} + static inline void set_low() {port::port() = (port::port() & (~bits));} + static inline void set_input() {port::ddr() = (port::ddr() & (~bits));} + static inline void set_input_pullup() {set_input(); set_high();} + static inline void set_output() {port::ddr() = (port::ddr() | bits);} + static inline uint8_t read() {return port::pin() & bits;} + static inline void write(bool v) {if (v) set_high(); else set_low();} + }; + + #define MAKE_AVR_PORT_PINS(ID) \ + struct port_##ID { \ + static volatile uint8_t &pin() {return PIN##ID;}; \ + static volatile uint8_t &port() {return PORT##ID;}; \ + static volatile uint8_t &ddr() {return DDR##ID;}; \ + }; \ + typedef port_pin AVR_##ID##0; \ + typedef port_pin AVR_##ID##1; \ + typedef port_pin AVR_##ID##2; \ + typedef port_pin AVR_##ID##3; \ + typedef port_pin AVR_##ID##4; \ + typedef port_pin AVR_##ID##5; \ + typedef port_pin AVR_##ID##6; \ + typedef port_pin AVR_##ID##7; + + #ifdef PORTA + MAKE_AVR_PORT_PINS(A); + #endif + #ifdef PORTB + MAKE_AVR_PORT_PINS(B); + #endif + #ifdef PORTC + MAKE_AVR_PORT_PINS(C); + #endif + #ifdef PORTD + MAKE_AVR_PORT_PINS(D); + #endif + #ifdef PORTE + MAKE_AVR_PORT_PINS(E); + #endif + #ifdef PORTF + MAKE_AVR_PORT_PINS(F); + #endif + #ifdef PORTG + MAKE_AVR_PORT_PINS(G); + #endif + #ifdef PORTH + MAKE_AVR_PORT_PINS(H); + #endif + #ifdef PORTJ + MAKE_AVR_PORT_PINS(J); + #endif + #ifdef PORTK + MAKE_AVR_PORT_PINS(K); + #endif + #ifdef PORTL + MAKE_AVR_PORT_PINS(L); + #endif + #ifdef PORTQ + MAKE_AVR_PORT_PINS(Q); + #endif + #ifdef PORTR + MAKE_AVR_PORT_PINS(R); + #endif + + #undef MAKE_AVR_PORT_PINS + + template + struct arduino_digital_pin { + static constexpr uint8_t pin = p; + static inline void set_high() {digitalWrite(p, HIGH);} + static inline void set_low() {digitalWrite(p, LOW);} + static inline void set_input() {pinMode(p, INPUT);} + static inline void set_input_pullup() {pinMode(p, INPUT_PULLUP);} + static inline void set_output() {pinMode(p, OUTPUT);} + static inline uint8_t read() {return digitalRead(p);} + static inline void write(bool v) {digitalWrite(p, v ? HIGH : LOW);} + }; + + #define MAKE_ARDUINO_PINS(ID) typedef arduino_digital_pin ARDUINO_DIGITAL_##ID; + MAKE_ARDUINO_PINS( 0); + MAKE_ARDUINO_PINS( 1); + MAKE_ARDUINO_PINS( 2); + MAKE_ARDUINO_PINS( 3); + MAKE_ARDUINO_PINS( 4); + MAKE_ARDUINO_PINS( 5); + MAKE_ARDUINO_PINS( 6); + MAKE_ARDUINO_PINS( 7); + MAKE_ARDUINO_PINS( 8); + MAKE_ARDUINO_PINS( 9); + MAKE_ARDUINO_PINS(10); + MAKE_ARDUINO_PINS(11); + MAKE_ARDUINO_PINS(12); + MAKE_ARDUINO_PINS(13); + MAKE_ARDUINO_PINS(14); + MAKE_ARDUINO_PINS(15); + MAKE_ARDUINO_PINS(16); + MAKE_ARDUINO_PINS(17); + MAKE_ARDUINO_PINS(18); + MAKE_ARDUINO_PINS(19); + MAKE_ARDUINO_PINS(10); + MAKE_ARDUINO_PINS(21); + MAKE_ARDUINO_PINS(22); + MAKE_ARDUINO_PINS(23); + MAKE_ARDUINO_PINS(24); + MAKE_ARDUINO_PINS(25); + MAKE_ARDUINO_PINS(26); + MAKE_ARDUINO_PINS(27); + MAKE_ARDUINO_PINS(28); + MAKE_ARDUINO_PINS(29); + MAKE_ARDUINO_PINS(30); + MAKE_ARDUINO_PINS(31); + MAKE_ARDUINO_PINS(32); + MAKE_ARDUINO_PINS(33); + MAKE_ARDUINO_PINS(34); + MAKE_ARDUINO_PINS(35); + MAKE_ARDUINO_PINS(36); + MAKE_ARDUINO_PINS(37); + MAKE_ARDUINO_PINS(38); + MAKE_ARDUINO_PINS(39); + MAKE_ARDUINO_PINS(40); + MAKE_ARDUINO_PINS(41); + MAKE_ARDUINO_PINS(42); + MAKE_ARDUINO_PINS(43); + MAKE_ARDUINO_PINS(44); + MAKE_ARDUINO_PINS(45); + MAKE_ARDUINO_PINS(46); + MAKE_ARDUINO_PINS(47); + MAKE_ARDUINO_PINS(48); + MAKE_ARDUINO_PINS(49); + MAKE_ARDUINO_PINS(50); + MAKE_ARDUINO_PINS(51); + MAKE_ARDUINO_PINS(52); + MAKE_ARDUINO_PINS(53); + #undef MAKE_ARDUINO_PINS + } // namespace fast_io + + #define SET_INPUT(pin) fast_io::pin::set_input() + #define SET_INPUT_PULLUP(pin) do{ fast_io::pin::set_input(); fast_io::pin::set_high(); }while(0) + #define SET_INPUT_PULLDOWN SET_INPUT + #define SET_OUTPUT(pin) fast_io::pin::set_output() + #define READ(pin) fast_io::pin::read() + #define WRITE(pin, value) fast_io::pin::write(value) + + #ifndef pgm_read_word_far + #define pgm_read_word_far pgm_read_word + #endif + + #ifndef pgm_read_dword_far + #define pgm_read_dword_far pgm_read_dword + #endif + + #ifndef pgm_read_ptr_far + #define pgm_read_ptr_far pgm_read_ptr + #endif + + // Use NUM_ARGS(__VA_ARGS__) to get the number of variadic arguments + #define _NUM_ARGS(_,Z,Y,X,W,V,U,T,S,R,Q,P,O,N,M,L,K,J,I,H,G,F,E,D,C,B,A,OUT,...) OUT + #define NUM_ARGS(V...) _NUM_ARGS(0,V,26,25,24,23,22,21,20,19,18,17,16,15,14,13,12,11,10,9,8,7,6,5,4,3,2,1,0) + + // SERIAL_ECHOPAIR / SERIAL_ECHOPAIR_P is used to output a key value pair. The key must be a string and the value can be anything + // Print up to 12 pairs of values. Odd elements auto-wrapped in PSTR(). + #define __SEP_N(N,V...) _SEP_##N(V) + #define _SEP_N(N,V...) __SEP_N(N,V) + #define _SEP_1(PRE) SERIAL_ECHOPGM(PRE) + #define _SEP_2(PRE,V) do{ Serial.print(F(PRE)); Serial.print(V); }while(0) + #define _SEP_3(a,b,c) do{ _SEP_2(a,b); SERIAL_ECHOPGM(c); }while(0) + #define _SEP_4(a,b,V...) do{ _SEP_2(a,b); _SEP_2(V); }while(0) + + // Print up to 1 pairs of values followed by newline + #define __SELP_N(N,V...) _SELP_##N(V) + #define _SELP_N(N,V...) __SELP_N(N,V) + #define _SELP_1(PRE) SERIAL_ECHOLNPGM(PRE) + #define _SELP_2(PRE,V) do{ Serial.print(F(PRE)); Serial.println(V); }while(0) + #define _SELP_3(a,b,c) do{ _SEP_2(a,b); SERIAL_ECHOLNPGM(c); }while(0) + #define _SELP_4(a,b,V...) do{ _SEP_2(a,b); _SELP_2(V); }while(0) + #define SERIAL_ECHO_START() + #define SERIAL_ECHOLNPGM(str) Serial.println(F(str)) + #define SERIAL_ECHOPGM(str) Serial.print(F(str)) + #define SERIAL_ECHO_MSG(V...) SERIAL_ECHOLNPAIR(V) + #define SERIAL_ECHOLNPAIR(V...) _SELP_N(NUM_ARGS(V),V) + #define SERIAL_ECHOPAIR(str, val) do{ Serial.print(F(str)); Serial.print(val); }while(0) + + #define safe_delay delay + + // Define macros for compatibility + + // Use NUM_ARGS(__VA_ARGS__) to get the number of variadic arguments + #define _NUM_ARGS(_,Z,Y,X,W,V,U,T,S,R,Q,P,O,N,M,L,K,J,I,H,G,F,E,D,C,B,A,OUT,...) OUT + #define NUM_ARGS(V...) _NUM_ARGS(0,V,26,25,24,23,22,21,20,19,18,17,16,15,14,13,12,11,10,9,8,7,6,5,4,3,2,1,0) + + #define _CAT(a,V...) a##V + #define CAT(a,V...) _CAT(a,V) + + #define FIRST(a,...) a + #define SECOND(a,b,...) b + #define THIRD(a,b,c,...) c + + #define IS_PROBE(V...) SECOND(V, 0) // Get the second item passed, or 0 + #define PROBE() ~, 1 // Second item will be 1 if this is passed + #define _NOT_0 PROBE() + #define NOT(x) IS_PROBE(_CAT(_NOT_, x)) // NOT('0') gets '1'. Anything else gets '0'. + #define _BOOL(x) NOT(NOT(x)) // NOT('0') gets '0'. Anything else gets '1'. + + #define _DO_1(W,C,A) (_##W##_1(A)) + #define _DO_2(W,C,A,B) (_##W##_1(A) C _##W##_1(B)) + #define _DO_3(W,C,A,V...) (_##W##_1(A) C _DO_2(W,C,V)) + #define _DO_4(W,C,A,V...) (_##W##_1(A) C _DO_3(W,C,V)) + #define _DO_5(W,C,A,V...) (_##W##_1(A) C _DO_4(W,C,V)) + #define _DO_6(W,C,A,V...) (_##W##_1(A) C _DO_5(W,C,V)) + #define _DO_7(W,C,A,V...) (_##W##_1(A) C _DO_6(W,C,V)) + #define _DO_8(W,C,A,V...) (_##W##_1(A) C _DO_7(W,C,V)) + #define _DO_9(W,C,A,V...) (_##W##_1(A) C _DO_8(W,C,V)) + #define _DO_10(W,C,A,V...) (_##W##_1(A) C _DO_9(W,C,V)) + #define _DO_11(W,C,A,V...) (_##W##_1(A) C _DO_10(W,C,V)) + #define _DO_12(W,C,A,V...) (_##W##_1(A) C _DO_11(W,C,V)) + #define __DO_N(W,C,N,V...) _DO_##N(W,C,V) + #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) + + #define _ISENA_ ~,1 + #define _ISENA_1 ~,1 + #define _ISENA_0x1 ~,1 + #define _ISENA_true ~,1 + #define _ISENA(V...) IS_PROBE(V) + #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 TERN(O,A,B) _TERN(_ENA_1(O),B,A) // OPTION converted to '0' or '1' + #define TERN0(O,A) _TERN(_ENA_1(O),0,A) // OPTION converted to A or '0' + #define TERN1(O,A) _TERN(_ENA_1(O),1,A) // OPTION converted to A or '1' + #define TERN_(O,A) _TERN(_ENA_1(O),,A) // OPTION converted to A or '' + #define _TERN(E,V...) __TERN(_CAT(T_,E),V) // Prepend 'T_' to get 'T_0' or 'T_1' + #define __TERN(T,V...) ___TERN(_CAT(_NO,T),V) // Prepend '_NO' to get '_NOT_0' or '_NOT_1' + #define ___TERN(P,V...) THIRD(P,V) // If first argument has a comma, A. Else B. + + #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) + + // Remove compiler warning on an unused variable + #ifndef UNUSED + #ifdef HAL_STM32 + #define UNUSED(X) (void)X + #else + #define UNUSED(x) ((void)(x)) + #endif + #endif + +#endif // !__MARLIN_FIRMWARE__ diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/adjuster_widget.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/adjuster_widget.cpp new file mode 100644 index 000000000000..3ef71f573f7d --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/adjuster_widget.cpp @@ -0,0 +1,60 @@ +/*********************** + * adjuster_widget.cpp * + ***********************/ + +/**************************************************************************** + * Written By Marcio Teixeira 2021 - Cocoa Press * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#include "ftdi_extended.h" + +#if ENABLED(FTDI_EXTENDED) + +#define SUB_COLS 9 +#define SUB_ROWS 1 +#define VAL_POS SUB_POS(1,1), SUB_SIZE(5,1) +#define INC_POS SUB_POS(6,1), SUB_SIZE(2,1) +#define DEC_POS SUB_POS(8,1), SUB_SIZE(2,1) + +namespace FTDI { + void draw_adjuster_value(CommandProcessor& cmd, int16_t x, int16_t y, int16_t w, int16_t h, float value, progmem_str units, int8_t width, uint8_t precision) { + char str[width + precision + 10 + (units ? strlen_P((const char*) units) : 0)]; + if (isnan(value)) + strcpy_P(str, PSTR("-")); + else + dtostrf(value, width, precision, str); + + if (units) { + strcat_P(str, PSTR(" ")); + strcat_P(str, (const char*) units); + } + + cmd.tag(0).text(VAL_POS, str); + } + + void draw_adjuster(CommandProcessor& cmd, int16_t x, int16_t y, int16_t w, int16_t h, uint8_t tag, float value, progmem_str units, int8_t width, uint8_t precision, draw_mode_t what) { + if (what & BACKGROUND) + cmd.tag(0).button(VAL_POS, F(""), FTDI::OPT_FLAT); + + if (what & FOREGROUND) { + draw_adjuster_value(cmd, x, y, w, h, value, units, width, precision); + cmd.tag(tag ).button(INC_POS, F("-")) + .tag(tag+1).button(DEC_POS, F("+")); + } + } +} // namespace FTDI + +#endif // FTDI_EXTENDED diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/adjuster_widget.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/adjuster_widget.h new file mode 100644 index 000000000000..71f7398694af --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/adjuster_widget.h @@ -0,0 +1,40 @@ +/********************* + * adjuster_widget.h * + *********************/ + +/**************************************************************************** + * Written By Marcio Teixeira 2021 - Cocoa Press * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#pragma once + +namespace FTDI { + void draw_adjuster_value( + CommandProcessor& cmd, + int16_t x, int16_t y, int16_t w, int16_t h, + float value, progmem_str units = nullptr, + int8_t width = 5, uint8_t precision = 1 + ); + + void draw_adjuster( + CommandProcessor& cmd, + int16_t x, int16_t y, int16_t w, int16_t h, + uint8_t tag, + float value, progmem_str units = nullptr, + int8_t width = 5, uint8_t precision = 1, + draw_mode_t what = BOTH + ); +} diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/bitmap_info.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/bitmap_info.h similarity index 99% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/bitmap_info.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/bitmap_info.h index b763c890c20b..73260703c2a0 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/bitmap_info.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/bitmap_info.h @@ -16,7 +16,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once 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 new file mode 100644 index 000000000000..32cc37d2e2f7 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/circular_progress.cpp @@ -0,0 +1,108 @@ +/************************* + * circular_progress.cpp * + *************************/ + +/**************************************************************************** + * Written By Marcio Teixeira 2019 - 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 "ftdi_extended.h" + +#if ENABLED(FTDI_EXTENDED) + +/* This function draws a circular progress "ring" */ +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 int ro = min(w,h) * 8; + const int rr = ro * rim; + const int cx = x * 16 + w * 8; + const int cy = y * 16 + h * 8; + + // Load a rim shape into stencil buffer + cmd.cmd(SAVE_CONTEXT()); + cmd.cmd(TAG_MASK(0)); + cmd.cmd(CLEAR(0,1,0)); + cmd.cmd(COLOR_MASK(0,0,0,0)); + cmd.cmd(STENCIL_OP(STENCIL_OP_KEEP, STENCIL_OP_INVERT)); + cmd.cmd(STENCIL_FUNC(STENCIL_FUNC_ALWAYS, 255, 255)); + cmd.cmd(BEGIN(POINTS)); + cmd.cmd(POINT_SIZE(ro)); + cmd.cmd(VERTEX2F(cx, cy)); + cmd.cmd(POINT_SIZE(ro - rr)); + cmd.cmd(VERTEX2F(cx, cy)); + cmd.cmd(RESTORE_CONTEXT()); + + // Mask further drawing by stencil buffer + cmd.cmd(SAVE_CONTEXT()); + cmd.cmd(STENCIL_FUNC(STENCIL_FUNC_NOTEQUAL, 0, 255)); + + // Fill the background + cmd.cmd(COLOR_RGB(bgcolor)); + cmd.cmd(BEGIN(POINTS)); + cmd.cmd(POINT_SIZE(ro)); + cmd.cmd(VERTEX2F(cx, cy)); + cmd.cmd(COLOR_RGB(fgcolor)); + + // Paint upper-right quadrant + cmd.cmd(BEGIN(EDGE_STRIP_A)); + cmd.cmd(VERTEX2F(cx, cy)); + cmd.cmd(VERTEX2F(cx + ro*sin(a1) + 16,cy - ro*cos(a1) + 8)); + + // Paint lower-right quadrant + if (a > 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) { + 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) { + cmd.cmd(BEGIN(EDGE_STRIP_L)); + cmd.cmd(VERTEX2F(cx, cy)); + cmd.cmd(VERTEX2F(cx - ro*cos(a4),cy - ro*sin(a4))); + } + cmd.cmd(RESTORE_CONTEXT()); + + // Draw the text + + cmd.cmd(SAVE_CONTEXT()); + cmd.cmd(COLOR_RGB(fgcolor)); + cmd.text(x,y,w,h,text, OPT_CENTERX | OPT_CENTERY); + cmd.cmd(RESTORE_CONTEXT()); + } + + void draw_circular_progress(CommandProcessor& cmd, int x, int y, int w, int h, float percent, uint32_t bgcolor, uint32_t fgcolor) { + char str[5]; + sprintf(str,"%d\%%",int(percent)); + draw_circular_progress(cmd, x, y, w, h, percent, str, bgcolor, fgcolor); + } +} // namespace FTDI + +#endif // FTDI_EXTENDED diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/circular_progress.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/circular_progress.h new file mode 100644 index 000000000000..68fc06b4d9e4 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/circular_progress.h @@ -0,0 +1,27 @@ +/*********************** + * circular_progress.h * + ***********************/ + +/**************************************************************************** + * Written By Marcio Teixeira 2019 - 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 + +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); + void draw_circular_progress(CommandProcessor& cmd, int x, int y, int w, int h, float percent, uint32_t bgcolor, uint32_t fgcolor); +} diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.cpp similarity index 80% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.cpp index 7224b681bba5..fd9c70ff3c5f 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.cpp @@ -16,14 +16,26 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "ftdi_extended.h" -#ifdef FTDI_EXTENDED +#if ENABLED(FTDI_EXTENDED) CommandProcessor::btn_style_func_t *CommandProcessor::_btn_style_callback = CommandProcessor::default_button_style_func; bool CommandProcessor::is_tracking = false; +uint32_t CommandProcessor::memcrc(uint32_t ptr, uint32_t num) { + const uint16_t x = CLCD::mem_read_16(CLCD::REG::CMD_WRITE); + memcrc(ptr, num, 0); + wait(); + return CLCD::mem_read_32(CLCD::MAP::RAM_CMD + x + 12); +} + +bool CommandProcessor::wait() { + while (is_processing() && !has_fault()) { /* nada */ } + return !has_fault(); +} + #endif // FTDI_EXTENDED diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h similarity index 92% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h index 94ccbb7a605b..7504a1387dda 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h @@ -16,7 +16,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once @@ -65,7 +65,7 @@ class CommandProcessor : public CLCD::CommandFifo { uint8_t _style = 0; protected: - // Returns the cannonical thickness of a widget (i.e. the height of a toggle element) + // Returns the canonical thickness of a widget (i.e. the height of a toggle element) uint16_t widget_thickness() { CLCD::FontMetrics fm(_font); return fm.height * 20.0/16; @@ -146,10 +146,13 @@ class CommandProcessor : public CLCD::CommandFifo { return *this; } + bool wait(); + uint32_t memcrc(uint32_t ptr, uint32_t num); + // Wrap all the CommandFifo routines to allow method chaining inline CommandProcessor& cmd (uint32_t cmd32) {CLCD::CommandFifo::cmd(cmd32); return *this;} - inline CommandProcessor& cmd (void* data, uint16_t len) {CLCD::CommandFifo::cmd(data, len); return *this;} + inline CommandProcessor& cmd (void *data, uint16_t len) {CLCD::CommandFifo::cmd(data, len); return *this;} inline CommandProcessor& execute() {CLCD::CommandFifo::execute(); return *this;} inline CommandProcessor& fgcolor (uint32_t rgb) {CLCD::CommandFifo::fgcolor(rgb); return *this;} @@ -206,8 +209,22 @@ class CommandProcessor : public CLCD::CommandFifo { inline CommandProcessor& rectangle(int16_t x, int16_t y, int16_t w, int16_t h) { using namespace FTDI; CLCD::CommandFifo::cmd(BEGIN(RECTS)); - CLCD::CommandFifo::cmd(VERTEX2F(x * 16, y * 16)); + CLCD::CommandFifo::cmd(VERTEX2F( x * 16, y * 16)); + CLCD::CommandFifo::cmd(VERTEX2F((x + w) * 16, (y + h) * 16)); + return *this; + } + + inline CommandProcessor& border(int16_t x, int16_t y, int16_t w, int16_t h) { + using namespace FTDI; + CLCD::CommandFifo::cmd(BEGIN(LINES)); + CLCD::CommandFifo::cmd(VERTEX2F( x * 16, y * 16)); + CLCD::CommandFifo::cmd(VERTEX2F((x + w) * 16, y * 16)); + CLCD::CommandFifo::cmd(VERTEX2F((x + w) * 16, y * 16)); + CLCD::CommandFifo::cmd(VERTEX2F((x + w) * 16, (y + h) * 16)); CLCD::CommandFifo::cmd(VERTEX2F((x + w) * 16, (y + h) * 16)); + CLCD::CommandFifo::cmd(VERTEX2F( x * 16, (y + h) * 16)); + CLCD::CommandFifo::cmd(VERTEX2F( x * 16, (y + h) * 16)); + CLCD::CommandFifo::cmd(VERTEX2F( x * 16, y * 16)); return *this; } @@ -215,13 +232,11 @@ class CommandProcessor : public CLCD::CommandFifo { FORCEDINLINE CommandProcessor& toggle(int16_t x, int16_t y, int16_t w, int16_t h, T text, bool state, uint16_t options = FTDI::OPT_3D) { CLCD::FontMetrics fm(_font); const int16_t widget_h = fm.height * 20.0 / 16; - //const int16_t outer_bar_r = widget_h / 2; - //const int16_t knob_r = outer_bar_r - 1.5; // The y coordinate of the toggle is the baseline of the text, // so we must introduce a fudge factor based on the line height to // actually center the control. const int16_t fudge_y = fm.height * 5 / 16; - CLCD::CommandFifo::toggle(x + h / 2, y + (h - widget_h) / 2 + fudge_y, w - h, _font, options, state); + CLCD::CommandFifo::toggle(x + widget_h, y + (h - widget_h) / 2 + fudge_y, w - widget_h, _font, options, state); CLCD::CommandFifo::str(text); return *this; } @@ -234,7 +249,7 @@ class CommandProcessor : public CLCD::CommandFifo { return toggle(x, y, w, h, text, state, options); } - // Contrained drawing routines. These constrain the widget inside a box for easier layout. + // Constrained drawing routines. These constrain the widget inside a box for easier layout. // The FORCEDINLINE ensures that the code is inlined so that all the math is done at compile time. FORCEDINLINE CommandProcessor& track_linear(int16_t x, int16_t y, int16_t w, int16_t h, int16_t tag) { @@ -312,12 +327,12 @@ class CommandProcessor : public CLCD::CommandFifo { int8_t apply_fit_text(int16_t w, int16_t h, T text) { using namespace FTDI; int8_t font = _font; - #ifdef TOUCH_UI_USE_UTF8 + #if ENABLED(TOUCH_UI_USE_UTF8) const bool is_utf8 = has_utf8_chars(text); #endif for (;font > 26;) { int16_t width, height; - #ifdef TOUCH_UI_USE_UTF8 + #if ENABLED(TOUCH_UI_USE_UTF8) if (is_utf8) { width = get_utf8_text_width(text, font_size_t::from_romfont(font)); height = font_size_t::from_romfont(font).get_height(); @@ -345,7 +360,7 @@ class CommandProcessor : public CLCD::CommandFifo { template uint16_t text_width(T text) { using namespace FTDI; - #ifdef TOUCH_UI_USE_UTF8 + #if ENABLED(TOUCH_UI_USE_UTF8) if (has_utf8_chars(text)) return get_utf8_text_width(text, font_size_t::from_romfont(_font)); #endif @@ -362,7 +377,7 @@ class CommandProcessor : public CLCD::CommandFifo { #else const int8_t font = _font; #endif - #ifdef TOUCH_UI_USE_UTF8 + #if ENABLED(TOUCH_UI_USE_UTF8) if (has_utf8_chars(text)) draw_utf8_text(*this, x, y, text, font_size_t::from_romfont(font), options); else @@ -401,7 +416,7 @@ class CommandProcessor : public CLCD::CommandFifo { const int8_t font = _font; #endif CLCD::CommandFifo::button(x, y, w, h, font, options); - #ifdef TOUCH_UI_USE_UTF8 + #if ENABLED(TOUCH_UI_USE_UTF8) if (has_utf8_chars(text)) { CLCD::CommandFifo::str(F("")); apply_text_alignment(x, y, w, h, OPT_CENTER); diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.cpp similarity index 99% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.cpp index baed9f8502fe..a13c36265ed8 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.cpp @@ -17,12 +17,12 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "ftdi_extended.h" -#ifdef FTDI_EXTENDED +#if ENABLED(FTDI_EXTENDED) /* The Display List Cache mechanism stores the display list corresponding * to a menu into RAM_G so that on subsequent calls drawing the menu does diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.h similarity index 91% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.h index da927aeae23a..73b4b0bbc868 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.h @@ -16,7 +16,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once @@ -29,15 +29,12 @@ * * The DLCache can be used like so: * - * void some_function() { - * DLCache dlcache(UNIQUE_ID); + * DLCache dlcache(UNIQUE_ID); * - * if (dlcache.hasData()) { - * dlcache.append(); - * } else { - * // Add stuff to the DL - * dlcache.store(); - * } + * if (dlcache.hasData()) + * dlcache.append(); + * else + * dlcache.store(); // Add stuff to the DL */ class DLCache { private: diff --git a/Marlin/src/lcd/extui/lib/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 similarity index 96% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp index 3dd2b88b19f7..7fccb309f56b 100644 --- a/Marlin/src/lcd/extui/lib/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 @@ -17,12 +17,12 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "ftdi_extended.h" -#ifdef FTDI_EXTENDED +#if ENABLED(FTDI_EXTENDED) using namespace FTDI; enum { @@ -108,7 +108,7 @@ namespace FTDI { * - Dispatches onTouchStart and onTouchEnd events to the active screen. * - Handles auto-repetition by sending onTouchHeld to the active screen periodically. * - Plays touch feedback "click" sounds when appropriate. - * - Performs debouncing to supress spurious touch events. + * - Performs debouncing to suppress spurious touch events. */ void EventLoop::process_events() { // If the LCD is processing commands, don't check @@ -124,8 +124,7 @@ namespace FTDI { case UNPRESSED: if (tag != 0) { #if ENABLED(TOUCH_UI_DEBUG) - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR("Touch start: ", tag); + SERIAL_ECHO_MSG("Touch start: ", tag); #endif pressed_tag = tag; @@ -186,8 +185,7 @@ namespace FTDI { if (UIData::flags.bits.touch_end_sound) sound.play(unpress_sound); #if ENABLED(TOUCH_UI_DEBUG) - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR("Touch end: ", pressed_tag); + SERIAL_ECHO_MSG("Touch end: ", pressed_tag); #endif const uint8_t saved_pressed_tag = pressed_tag; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.h similarity index 99% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.h index d9bede92dfbc..c5f08297bed5 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.h @@ -17,7 +17,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/ftdi_extended.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/ftdi_extended.h similarity index 92% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/ftdi_extended.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/ftdi_extended.h index 6e4d0668fe3e..bf9858f6eb91 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/ftdi_extended.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/ftdi_extended.h @@ -17,7 +17,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once @@ -29,11 +29,12 @@ #define FTDI_EXTENDED #endif -#ifdef FTDI_EXTENDED +#if ENABLED(FTDI_EXTENDED) #include "unicode/font_size_t.h" #include "unicode/unicode.h" #include "unicode/standard_char_set.h" #include "unicode/western_char_set.h" + #include "unicode/cyrillic_char_set.h" #include "unicode/font_bitmaps.h" #include "rgb_t.h" #include "bitmap_info.h" @@ -46,6 +47,9 @@ #include "sound_player.h" #include "sound_list.h" #include "polygon.h" + #include "poly_ui.h" #include "text_box.h" #include "text_ellipsis.h" + #include "adjuster_widget.h" + #include "circular_progress.h" #endif diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/grid_layout.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/grid_layout.h similarity index 76% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/grid_layout.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/grid_layout.h index e3c3ebb39d5a..dd94685c98ed 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/grid_layout.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/grid_layout.h @@ -16,7 +16,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once @@ -47,23 +47,25 @@ #define MARGIN_DEFAULT 3 #endif -// EDGE_R adds some black space on the right edge of the display -// This shifts some of the screens left to visually center them. +// The EDGE variables adds some space on the edges of the display +#define EDGE_T 0 +#define EDGE_B 0 +#define EDGE_L 0 #define EDGE_R 0 // GRID_X and GRID_Y computes the positions of the divisions on // the layout grid. -#define GRID_X(x) ((x)*(FTDI::display_width-EDGE_R)/GRID_COLS) -#define GRID_Y(y) ((y)*FTDI::display_height/GRID_ROWS) +#define GRID_X(x) ((x)*(FTDI::display_width-EDGE_R-EDGE_L)/GRID_COLS+EDGE_L) +#define GRID_Y(y) ((y)*(FTDI::display_height-EDGE_B-EDGE_T)/GRID_ROWS+EDGE_T) // BTN_X, BTN_Y, BTN_W and BTN_X returns the top-left and width // and height of a button, taking into account the button margins. #define BTN_X(x) (GRID_X((x)-1) + MARGIN_L) #define BTN_Y(y) (GRID_Y((y)-1) + MARGIN_T) -#define BTN_W(w) (GRID_X(w) - MARGIN_L - MARGIN_R) -#define BTN_H(h) (GRID_Y(h) - MARGIN_T - MARGIN_B) +#define BTN_W(w) (GRID_X(w) - GRID_X(0) - MARGIN_L - MARGIN_R) +#define BTN_H(h) (GRID_Y(h) - GRID_Y(0) - MARGIN_T - MARGIN_B) // Abbreviations for common phrases, to allow a button to be // defined in one line of source. @@ -87,8 +89,21 @@ cmd.cmd(LINE_WIDTH(16)); \ } +// Routines for subdividing a grid within a box (x,y,w,h) + +#define SUB_GRID_W(W) ((W)*w/SUB_COLS) +#define SUB_GRID_H(H) ((H)*h/SUB_ROWS) +#define SUB_GRID_X(X) (SUB_GRID_W((X)-1) + x) +#define SUB_GRID_Y(Y) (SUB_GRID_H((Y)-1) + y) +#define SUB_X(X) (SUB_GRID_X(X) + MARGIN_L) +#define SUB_Y(Y) (SUB_GRID_Y(Y) + MARGIN_T) +#define SUB_W(W) (SUB_GRID_W(W) - MARGIN_L - MARGIN_R) +#define SUB_H(H) (SUB_GRID_H(H) - MARGIN_T - MARGIN_B) +#define SUB_POS(X,Y) SUB_X(X), SUB_Y(Y) +#define SUB_SIZE(W,H) SUB_W(W), SUB_H(H) + namespace FTDI { - #ifdef TOUCH_UI_PORTRAIT + #if ENABLED(TOUCH_UI_PORTRAIT) constexpr uint16_t display_width = Vsize; constexpr uint16_t display_height = Hsize; #else diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/poly_ui.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/poly_ui.h similarity index 98% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/poly_ui.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/poly_ui.h index a501de20ba87..809e729a8f69 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/poly_ui.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/poly_ui.h @@ -90,7 +90,7 @@ class PolyReader { if (start_x != eol) close_loop(); else - p = NULL; + p = nullptr; } else { x = pgm_read_word_far(p++); @@ -106,7 +106,7 @@ class PolyReader { } } - bool has_more() { return p != NULL; } + bool has_more() { return p != nullptr; } bool end_of_loop() { return start_x == eol; } }; @@ -239,9 +239,11 @@ class DeduplicatedPolyReader : public POLY_READER { */ template> class GenericPolyUI { - private: + protected: CommandProcessor &cmd; + draw_mode_t mode; + private: // Attributes used to paint buttons uint32_t btn_fill_color = 0x000000; @@ -250,8 +252,6 @@ class GenericPolyUI { uint32_t btn_stroke_color = 0x000000; uint8_t btn_stroke_width = 28; - draw_mode_t mode; - public: enum ButtonStyle : uint8_t { FILL = 1, @@ -272,7 +272,7 @@ class GenericPolyUI { if (clip) { // Clipping reduces the number of pixels that are // filled, allowing more complex shapes to be drawn - // in the alloted time. + // in the allotted time. bounds(r, x, y, w, h); cmd.cmd(SAVE_CONTEXT()); cmd.cmd(SCISSOR_XY(x, y)); diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/polygon.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/polygon.h similarity index 96% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/polygon.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/polygon.h index 7da621321141..3dc80bb3bba0 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/polygon.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/polygon.h @@ -16,7 +16,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once @@ -41,7 +41,7 @@ * ... * p.end_fill(); * - * Based on the example from "Applicaton Note AN_334, FT801 Polygon Application": + * Based on the example from "Application Note AN_334, FT801 Polygon Application": * * https://brtchip.com/wp-content/uploads/Support/Documentation/Application_Notes/ICs/EVE/AN_334-FT801_Polygon_Application.pdf */ @@ -66,7 +66,7 @@ namespace FTDI { cmd.cmd(STENCIL_FUNC(STENCIL_FUNC_ALWAYS, 255, 255)); // Drawing the edge strip along scan lines // seems to yield the best performance - #ifdef TOUCH_UI_PORTRAIT + #if ENABLED(TOUCH_UI_PORTRAIT) path_initiator = EDGE_STRIP_B; #else path_initiator = EDGE_STRIP_R; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/rgb_t.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/rgb_t.h similarity index 99% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/rgb_t.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/rgb_t.h index 2b18244e22fb..62762ee964b2 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/rgb_t.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/rgb_t.h @@ -16,7 +16,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.cpp similarity index 92% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.cpp index 57a9e3e89b0a..4e318cef17ed 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.cpp @@ -16,17 +16,17 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "ftdi_extended.h" -#ifdef FTDI_EXTENDED +#if ENABLED(FTDI_EXTENDED) /********************** VIRTUAL DISPATCH DATA TYPE ******************************/ uint8_t ScreenRef::lookupScreen(onRedraw_func_t onRedraw_ptr) { - for (uint8_t type = 0; type < functionTableSize; type++) { + for (uint8_t type = 0; type < tableSize(); type++) { if (GET_METHOD(type, onRedraw) == onRedraw_ptr) { return type; } @@ -43,14 +43,13 @@ void ScreenRef::setScreen(onRedraw_func_t onRedraw_ptr) { if (type != 0xFF) { setType(type); #if ENABLED(TOUCH_UI_DEBUG) - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR("New screen: ", type); + SERIAL_ECHO_MSG("New screen: ", type); #endif } } void ScreenRef::initializeAll() { - for (uint8_t type = 0; type < functionTableSize; type++) + for (uint8_t type = 0; type < tableSize(); type++) GET_METHOD(type, onStartup)(); } diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.h similarity index 91% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.h index d1f84c8a6e86..486c4fe562a3 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.h @@ -16,7 +16,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once @@ -50,7 +50,11 @@ typedef enum { #define GET_METHOD(type, method) reinterpret_cast(pgm_read_ptr_far(&functionTable[type].method##_ptr)) #define SCREEN_TABLE PROGMEM const ScreenRef::table_t ScreenRef::functionTable[] = -#define SCREEN_TABLE_POST const uint8_t ScreenRef::functionTableSize = sizeof(ScreenRef::functionTable)/sizeof(ScreenRef::functionTable[0]); +#define SCREEN_TABLE_POST size_t ScreenRef::tableSize() { \ + constexpr size_t siz = sizeof(functionTable)/sizeof(functionTable[0]); \ + static_assert(siz > 0, "The screen table is empty!"); \ + return siz; \ + } class ScreenRef { protected: @@ -79,14 +83,12 @@ class ScreenRef { uint8_t type = 0; static PROGMEM const table_t functionTable[]; - static const uint8_t functionTableSize; public: - uint8_t getType() {return type;} + static size_t tableSize(); - void setType(uint8_t t) { - type = t; - } + uint8_t getType() {return type;} + void setType(uint8_t t) {type = t;} uint8_t lookupScreen(onRedraw_func_t onRedraw_ptr); @@ -150,7 +152,7 @@ class UIScreen { #define AT_SCREEN(screen) (current_screen.getType() == current_screen.lookupScreen(screen::onRedraw)) #define IS_PARENT_SCREEN(screen) (current_screen.peek() == current_screen.lookupScreen(screen::onRedraw)) -/************************** CACHED VS UNCHACHED SCREENS ***************************/ +/************************** CACHED VS UNCACHED SCREENS ***************************/ class UncachedScreen { public: @@ -158,7 +160,7 @@ class UncachedScreen { using namespace FTDI; CommandProcessor cmd; cmd.cmd(CMD_DLSTART); - #ifdef TOUCH_UI_USE_UTF8 + #if ENABLED(TOUCH_UI_USE_UTF8) load_utf8_bitmaps(cmd); #endif @@ -199,7 +201,7 @@ class CachedScreen { CommandProcessor cmd; cmd.cmd(CMD_DLSTART); - #ifdef TOUCH_UI_USE_UTF8 + #if ENABLED(TOUCH_UI_USE_UTF8) load_utf8_bitmaps(cmd); #endif current_screen.onRedraw(BACKGROUND); @@ -222,7 +224,7 @@ class CachedScreen { dlcache.append(); } else { - #ifdef TOUCH_UI_USE_UTF8 + #if ENABLED(TOUCH_UI_USE_UTF8) load_utf8_bitmaps(cmd); #endif current_screen.onRedraw(BACKGROUND); diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_list.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_list.h similarity index 97% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_list.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_list.h index fbdfe2fe998a..2ddab1b818b4 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_list.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_list.h @@ -16,7 +16,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once @@ -24,7 +24,7 @@ class SoundList { private: static PROGMEM const struct list_t { - const char *const PROGMEM name; + const char * const PROGMEM name; const FTDI::SoundPlayer::sound_t* data; } list[]; public: diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_player.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_player.cpp similarity index 92% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_player.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_player.cpp index 6a5b6e3cf879..47bf79e46743 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_player.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_player.cpp @@ -16,12 +16,12 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "ftdi_extended.h" -#ifdef FTDI_EXTENDED +#if ENABLED(FTDI_EXTENDED) namespace FTDI { SoundPlayer sound; // Global sound player object @@ -37,9 +37,7 @@ namespace FTDI { void SoundPlayer::play(effect_t effect, note_t note) { #if ENABLED(TOUCH_UI_DEBUG) - SERIAL_ECHO_START(); - SERIAL_ECHOPAIR ("Playing note ", int(note)); - SERIAL_ECHOLNPAIR(", instrument ", int(effect)); + SERIAL_ECHO_MSG("Playing note ", note, ", instrument ", effect); #endif // Play the note @@ -64,7 +62,7 @@ namespace FTDI { timer.start(); } - void SoundPlayer::play(const sound_t* seq, play_mode_t mode) { + void SoundPlayer::play(const sound_t *seq, play_mode_t mode) { sequence = seq; wait = 250; // Adding this delay causes the note to not be clipped, not sure why. timer.start(); @@ -75,9 +73,7 @@ namespace FTDI { while (has_more_notes()) { onIdle(); - #ifdef EXTENSIBLE_UI - ExtUI::yield(); - #endif + TERN_(TOUCH_UI_FTDI_EVE, ExtUI::yield()); } } diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_player.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_player.h similarity index 96% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_player.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_player.h index e2650b10aeff..3ba39b8c57bf 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_player.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_player.h @@ -17,7 +17,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once @@ -55,7 +55,7 @@ namespace FTDI { static void play(effect_t effect, note_t note = NOTE_C4); static bool is_sound_playing(); - void play(const sound_t* seq, play_mode_t mode = PLAY_SYNCHRONOUS); + void play(const sound_t *seq, play_mode_t mode = PLAY_SYNCHRONOUS); void play_tone(const uint16_t frequency_hz, const uint16_t duration_ms); bool has_more_notes() {return sequence != 0;}; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp new file mode 100644 index 000000000000..544c5fed050e --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp @@ -0,0 +1,141 @@ +/**************** + * text_box.cpp * + ****************/ + +/**************************************************************************** + * Written By Marcio Teixeira 2019 - 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 "ftdi_extended.h" + +#if ENABLED(FTDI_EXTENDED) + +namespace FTDI { + /** + * Given a str, end will be set to the position at which a line needs to + * be broken so that the display width is less than w. The line will also + * be broken after a '\n'. Returns the display width of the line. + */ + static uint16_t find_line_break(const FontMetrics &utf8_fm, const CLCD::FontMetrics &clcd_fm, const uint16_t w, const char *start, const char *&end, bool use_utf8) { + const char *p = start; + end = start; + uint16_t lw = 0, result = 0; + for (;;) { + const char *next = p; + const utf8_char_t c = get_utf8_char_and_inc(next); + // Decide whether to break the string at this location + if (c == '\n' || c == '\0' || c == ' ') { + end = p; + result = lw; + } + if (c == '\n' || c == '\0') break; + // Measure the next character + const uint16_t cw = use_utf8 ? utf8_fm.get_char_width(c) : clcd_fm.char_widths[(uint8_t)c]; + // Stop processing once string exceeds the display width + if (lw + cw > w) break; + // Now add the length of the current character to the tally. + lw += cw; + p = next; + } + if (end == start) { + end = p; + result = lw; + } + return result; + } + + /** + * This function returns a measurements of the word-wrapped text box. + */ + static void measure_text_box(const FontMetrics &utf8_fm, const CLCD::FontMetrics &clcd_fm, const char *str, uint16_t &width, uint16_t &height, bool use_utf8) { + const char *line_start = (const char*)str; + const char *line_end; + const uint16_t wrap_width = width; + width = height = 0; + for (;;) { + const uint16_t line_width = find_line_break(utf8_fm, clcd_fm, wrap_width, line_start, line_end, use_utf8); + width = max(width, line_width); + height += utf8_fm.get_height(); + if (*line_end == '\n' || *line_end == ' ') line_end++; + if (*line_end == '\0') break; + if (line_end == line_start) break; + line_start = line_end; + } + } + + /** + * This function draws text inside a bounding box, doing word wrapping and using the largest font that will fit. + */ + void draw_text_box(CommandProcessor& cmd, int x, int y, int w, int h, const char *str, uint16_t options, uint8_t font) { + #if ENABLED(TOUCH_UI_USE_UTF8) + const bool use_utf8 = has_utf8_chars(str); + #else + constexpr bool use_utf8 = false; + #endif + uint16_t box_width, box_height; + + FontMetrics utf8_fm(font); + CLCD::FontMetrics clcd_fm; + clcd_fm.load(font); + + // Shrink the font until we find a font that fits + for (;;) { + box_width = w; + measure_text_box(utf8_fm, clcd_fm, str, box_width, box_height, use_utf8); + if (box_width <= (uint16_t)w && box_height <= (uint16_t)h) break; + if (font == 26) break; + utf8_fm.load(--font); + clcd_fm.load(font); + } + + const uint16_t dx = (options & OPT_RIGHTX) ? w : + (options & OPT_CENTERX) ? w / 2 : 0, + dy = (options & OPT_BOTTOMY) ? (h - box_height) : + (options & OPT_CENTERY) ? (h - box_height) / 2 : 0; + + const char *line_start = str, *line_end; + for (;;) { + find_line_break(utf8_fm, clcd_fm, w, line_start, line_end, use_utf8); + + const size_t line_len = line_end - line_start; + if (line_len) { + #if ENABLED(TOUCH_UI_USE_UTF8) + if (use_utf8) + draw_utf8_text(cmd, x + dx, y + dy, line_start, utf8_fm.fs, options & ~(OPT_CENTERY | OPT_BOTTOMY), line_len); + else + #endif + { + cmd.CLCD::CommandFifo::text(x + dx, y + dy, font, options & ~(OPT_CENTERY | OPT_BOTTOMY)); + cmd.CLCD::CommandFifo::str(line_start, line_len); + } + } + y += utf8_fm.get_height(); + + if (*line_end == '\n' || *line_end == ' ') line_end++; + if (*line_end == '\0') break; + if (line_end == line_start) break; + line_start = line_end; + } + } + + void draw_text_box(CommandProcessor& cmd, int x, int y, int w, int h, progmem_str pstr, uint16_t options, uint8_t font) { + char str[strlen_P((const char*)pstr) + 1]; + strcpy_P(str, (const char*)pstr); + draw_text_box(cmd, x, y, w, h, (const char*) str, options, font); + } +} // namespace FTDI + +#endif // FTDI_EXTENDED diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.h similarity index 95% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.h index 261995147cd4..3b14b020c00c 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.h @@ -16,7 +16,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once @@ -25,6 +25,8 @@ * This function draws text inside a bounding box, doing word wrapping and using the largest font that will fit. */ namespace FTDI { + constexpr uint16_t OPT_BOTTOMY = 0x1000; // Non-standard + void draw_text_box(class CommandProcessor& cmd, int x, int y, int w, int h, progmem_str str, uint16_t options = 0, uint8_t font = 31); void draw_text_box(class CommandProcessor& cmd, int x, int y, int w, int h, const char *str, uint16_t options = 0, uint8_t font = 31); } diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.cpp similarity index 80% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.cpp index b2f62f060ccc..4262dd115576 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.cpp @@ -16,12 +16,12 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "ftdi_extended.h" -#ifdef FTDI_EXTENDED +#if ENABLED(FTDI_EXTENDED) namespace FTDI { @@ -29,18 +29,29 @@ namespace FTDI { * Helper function for drawing text with ellipses. The str buffer may be modified and should have space for up to two extra characters. */ static void _draw_text_with_ellipsis(CommandProcessor& cmd, int16_t x, int16_t y, int16_t w, int16_t h, char *str, uint16_t options, uint8_t font) { - FontMetrics fm(font); - const int16_t ellipsisWidth = fm.get_char_width('.') * 3; + #if ENABLED(TOUCH_UI_USE_UTF8) + const bool use_utf8 = has_utf8_chars(str); + #define CHAR_WIDTH(c) use_utf8 ? utf8_fm.get_char_width(c) : clcd_fm.char_widths[(uint8_t)c] + #else + #define CHAR_WIDTH(c) utf8_fm.get_char_width(c) + constexpr bool use_utf8 = false; + #endif + FontMetrics utf8_fm(font); + CLCD::FontMetrics clcd_fm; + clcd_fm.load(font); + const int16_t ellipsisWidth = utf8_fm.get_char_width('.') * 3; // Compute the total line length, as well as // the location in the string where it can // split and still allow the ellipsis to fit. int16_t lineWidth = 0; - char *breakPoint = str; - for (char* c = str; *c; c++) { - lineWidth += fm.get_char_width(*c); + char *breakPoint = str; + char *next = str; + while (*next) { + const utf8_char_t c = get_utf8_char_and_inc(next); + lineWidth += CHAR_WIDTH(c); if (lineWidth + ellipsisWidth < w) - breakPoint = c; + breakPoint = next; } if (lineWidth > w) { @@ -49,8 +60,8 @@ namespace FTDI { } cmd.apply_text_alignment(x, y, w, h, options); - #ifdef TOUCH_UI_USE_UTF8 - if (has_utf8_chars(str)) { + #if ENABLED(TOUCH_UI_USE_UTF8) + if (use_utf8) { draw_utf8_text(cmd, x, y, str, font_size_t::from_romfont(font), options); } else #endif diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.h similarity index 99% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.h index 7852b7ec3e38..a2d8aa944391 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.h @@ -16,7 +16,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/tiny_timer.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/tiny_timer.cpp similarity index 83% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/tiny_timer.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/tiny_timer.cpp index 58ec96ac15fb..5219c0d04180 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/tiny_timer.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/tiny_timer.cpp @@ -16,36 +16,24 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "ftdi_extended.h" -#ifdef FTDI_EXTENDED +#if ENABLED(FTDI_EXTENDED) bool tiny_timer_t::elapsed(tiny_time_t duration) { uint8_t now = tiny_time_t::tiny_time( - #ifdef __MARLIN_FIRMWARE__ - ExtUI::safe_millis() - #else - millis() - #endif + TERN(__MARLIN_FIRMWARE__, ExtUI::safe_millis(), millis()) ); uint8_t elapsed = now - _start; - if (elapsed >= duration._duration) { - return true; - } else { - return false; - } + return elapsed >= duration._duration; } void tiny_timer_t::start() { _start = tiny_time_t::tiny_time( - #ifdef __MARLIN_FIRMWARE__ - ExtUI::safe_millis() - #else - millis() - #endif + TERN(__MARLIN_FIRMWARE__, ExtUI::safe_millis(), millis()) ); } #endif // FTDI_EXTENDED diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/tiny_timer.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/tiny_timer.h similarity index 97% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/tiny_timer.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/tiny_timer.h index 700da7bcf2f9..576567cf4dee 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/tiny_timer.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/tiny_timer.h @@ -16,7 +16,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once @@ -28,7 +28,7 @@ /* tiny_interval_t downsamples a 32-bit millis() value into a 8-bit value which can record periods of - a few seconds with a rougly 1/16th of second + a few seconds with a roughly 1/16th of second resolution. This allows us to measure small intervals without needing to use four-byte counters. */ diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/README.txt b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/README.txt similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/README.txt rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/README.txt 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 new file mode 100644 index 000000000000..1c193ade4be1 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set.cpp @@ -0,0 +1,139 @@ +/************************ + * cyrillic_char_set.cpp * + ************************/ + +/**************************************************************************** + * Written By Kirill Shashlov 2020 * + * Marcio Teixeira 2019 - 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 "../ftdi_extended.h" + +#if ALL(FTDI_EXTENDED, TOUCH_UI_USE_UTF8, TOUCH_UI_UTF8_CYRILLIC_CHARSET) + + #include "cyrillic_char_set_bitmap_31.h" + + #define NUM_ELEMENTS(a) (sizeof(a)/sizeof(a[0])) + + #define UTF8(A) uint16_t(utf8(U##A)) + + using namespace FTDI; + + constexpr static uint8_t cyrillic_font_handle = 6; + + uint32_t FTDI::CyrillicCharSet::bitmap_addr; + + /** + * Load bitmap data into RAMG. This function is called once at the start + * of the program. + * + * Parameters: + * + * addr - Address in RAMG where the font data is written + * + * Returns: Last wrote address + */ + + uint32_t FTDI::CyrillicCharSet::load_data(uint32_t addr) { + if (addr % 4 != 0) + addr += 4 - (addr % 4); + + // Load the alternative font metrics + CLCD::FontMetrics cyrillic_fm; + cyrillic_fm.ptr = addr + 148; + cyrillic_fm.format = L4; + cyrillic_fm.stride = 20; + cyrillic_fm.width = 40; + cyrillic_fm.height = 49; + LOOP_L_N(i, 127) + 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)) { + cyrillic_fm.char_widths[i] = cyrillic_font_widths[i]; + } + CLCD::mem_write_bulk(addr, &cyrillic_fm, 148); + + // Decode the RLE data and load it into RAMG as a bitmap + uint32_t lastaddr = write_rle_data(addr + 148, cyrillic_font, sizeof(cyrillic_font)); + + bitmap_addr = addr; + + return lastaddr; + } + + /** + * Populates the bitmap handles for the custom into the display list. + * This function is called once at the start of each display list. + * + * Parameters: + * + * cmd - Object used for writing to the FTDI chip command queue. + */ + + void FTDI::CyrillicCharSet::load_bitmaps(CommandProcessor& cmd) { + CLCD::FontMetrics cyrillic_fm; + cyrillic_fm.ptr = bitmap_addr + 148; + cyrillic_fm.format = L4; + cyrillic_fm.stride = 20; + cyrillic_fm.width = 40; + cyrillic_fm.height = 49; + set_font_bitmap(cmd, cyrillic_fm, cyrillic_font_handle); + } + + /** + * Renders a character at location x and y. The x position is incremented + * by the width of the character. + * + * Parameters: + * + * cmd - If non-NULL the symbol is drawn to the screen. + * If NULL, only increment position for text measurement. + * + * x, y - The location at which to draw the character. On output, + * incremented to the location of the next character. + * + * fs - A scaling object used to scale the font. The display will + * already be configured to scale bitmaps, but positions + * must be scaled using fs.scale() + * + * c - The unicode code point to draw. If the renderer does not + * support the character, it should return false. + * + * Returns: Whether the character was supported. + */ + + bool FTDI::CyrillicCharSet::render_glyph(CommandProcessor* cmd, int &x, int &y, font_size_t fs, utf8_char_t c) { + // A supported character? + if ((c < UTF8('А') || c > UTF8('я')) && (c != UTF8('Ё')) && (c != UTF8('ё'))) return false; + + uint8_t idx = (c == UTF8('Ё')) ? 64 : + (c == UTF8('ё')) ? 65 : + (c < UTF8('р')) ? c - UTF8('А') : + c - UTF8('р') + 48 + ; + + uint8_t width = cyrillic_font_widths[idx]; + + // Draw the character + if (cmd) ext_vertex2ii(*cmd, x, y, cyrillic_font_handle, idx); + + // Increment X to the next character position + x += fs.scale(width); + return true; + } + +#endif // FTDI_EXTENDED && TOUCH_UI_USE_UTF8 && TOUCH_UI_UTF8_WESTERN_CHARSET diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set.h new file mode 100644 index 000000000000..63493b8bb977 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set.h @@ -0,0 +1,32 @@ +/********************** + * cyrillic_char_set.h * + **********************/ + +/**************************************************************************** + * Written By Kirill Shashlov 2020 * + * Marcio Teixeira 2019 - 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: . * + ****************************************************************************/ + +namespace FTDI { + class CyrillicCharSet { + private: + static uint32_t bitmap_addr; + public: + static uint32_t load_data(uint32_t addr); + static void load_bitmaps(CommandProcessor&); + static bool render_glyph(CommandProcessor*, int &x, int &y, font_size_t, utf8_char_t); + }; +} 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 new file mode 100644 index 000000000000..30b1f8439955 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set_bitmap_31.h @@ -0,0 +1,2529 @@ +/******************************** + * cyrillic_char_set_bitmap_31.h * + ********************************/ + +/**************************************************************************** + * Written By Kirill Shashlov 2020 * + * Marcio Teixeira 2019 - Aleph Objects, Inc. * + * * + * Used GNU FreeFont FreeSans font (licensed under the GPL) * + * * + * 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 + +const uint8_t cyrillic_font_widths[] PROGMEM = { + 27, // А (0) + 26, // Б + 26, // В + 24, // Г + 33, // Д + 25, // Е + 37, // Ж + 26, // З + + 28, // И (8) + 28, // Й + 26, // К + 25, // Л + 33, // М + 27, // Н + 31, // О + 27, // П + + 26, // Р (16) + 29, // С + 28, // Т + 26, // У + 34, // Ф + 27, // Х + 30, // Ц + 23, // Ч + + 32, // Ш (24) + 34, // Щ + 26, // Ь + 34, // Ы + 34, // Ъ + 28, // Э + 40, // Ю + 26, // Я + + 22, // а (32) + 21, // б + 20, // в + 16, // г + 24, // д + 21, // е + 31, // ж + 19, // з + + 21, // и (40) + 21, // й + 20, // к + 19, // л + 23, // м + 21, // н + 21, // о + 21, // п + + 22, // р (48) + 20, // с + 17, // т + 19, // у + 34, // ф + 19, // х + 23, // ц + 19, // ч + 26, // ш + 28, // щ + 20, // ь + 26, // ы + 26, // ъ + 20, // э + 30, // ю + 20, // я + + 26, // Ё + 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 + * bytes are then RLE compressed to yield (count, byte) pairs. + */ + +const unsigned char cyrillic_font[] PROGMEM = { + /* 0 */ + 0xB9, 0x00, 0x01, 0x2F, 0x02, 0xFF, 0x01, 0x30, 0x10, 0x00, 0x01, 0x7F, + 0x02, 0xFF, 0x01, 0x90, 0x10, 0x00, 0x01, 0xDF, 0x02, 0xFF, 0x01, 0xE0, + 0x0F, 0x00, 0x01, 0x03, 0x03, 0xFF, 0x01, 0xF4, 0x0F, 0x00, 0x01, 0x09, + 0x01, 0xFF, 0x01, 0xFB, 0x01, 0xFF, 0x01, 0xFA, 0x0F, 0x00, 0x01, 0x0E, + 0x01, 0xFF, 0x01, 0xF1, 0x02, 0xFF, 0x0F, 0x00, 0x01, 0x5F, 0x01, 0xFF, + 0x01, 0x90, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0x50, 0x0E, 0x00, 0x01, 0xAF, + 0x01, 0xFF, 0x01, 0x40, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0xB0, 0x0D, 0x00, + 0x01, 0x01, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x00, 0x01, 0x0F, 0x01, 0xFF, + 0x01, 0xF1, 0x0D, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF8, 0x01, 0x00, + 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF7, 0x0D, 0x00, 0x01, 0x0C, 0x01, 0xFF, + 0x01, 0xF2, 0x01, 0x00, 0x01, 0x04, 0x01, 0xFF, 0x01, 0xFC, 0x0D, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x02, 0x00, 0x01, 0xEF, 0x01, 0xFF, + 0x01, 0x20, 0x0C, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0x60, 0x02, 0x00, + 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x80, 0x0C, 0x00, 0x01, 0xDF, 0x01, 0xFF, + 0x01, 0x10, 0x02, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0xD0, 0x0B, 0x00, + 0x01, 0x03, 0x01, 0xFF, 0x01, 0xFA, 0x03, 0x00, 0x01, 0x0E, 0x01, 0xFF, + 0x01, 0xF3, 0x0B, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF5, 0x03, 0x00, + 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF9, 0x0B, 0x00, 0x01, 0x0E, 0x01, 0xFF, + 0x01, 0xE0, 0x03, 0x00, 0x01, 0x03, 0x01, 0xFF, 0x01, 0xFE, 0x0B, 0x00, + 0x01, 0x4F, 0x01, 0xFF, 0x01, 0xB4, 0x04, 0x44, 0x02, 0xFF, 0x01, 0x40, + 0x0A, 0x00, 0x01, 0xAF, 0x08, 0xFF, 0x01, 0xA0, 0x0A, 0x00, 0x09, 0xFF, + 0x01, 0xF0, 0x09, 0x00, 0x01, 0x06, 0x02, 0xFF, 0x05, 0xEE, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0xF5, 0x09, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF5, + 0x05, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xFB, 0x09, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xF0, 0x05, 0x00, 0x01, 0x02, 0x02, 0xFF, 0x01, 0x10, + 0x08, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0x90, 0x06, 0x00, 0x01, 0xDF, + 0x01, 0xFF, 0x01, 0x70, 0x08, 0x00, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0x40, + 0x06, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x03, + 0x01, 0xFF, 0x01, 0xFE, 0x07, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xF2, + 0x07, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF8, 0x07, 0x00, 0x01, 0x0C, + 0x01, 0xFF, 0x01, 0xF8, 0x07, 0x00, 0x01, 0x0E, 0x01, 0xFF, 0x01, 0xF2, + 0x07, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xFD, 0x07, 0x00, 0x01, 0x4F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x01, 0x02, 0xFF, 0x01, 0x30, + 0x06, 0x00, 0x01, 0x8D, 0x01, 0xDD, 0x01, 0x60, 0x08, 0x00, 0x01, 0xAD, + 0x01, 0xDD, 0x01, 0x70, 0xCE, 0x00, + + /* 1 */ + 0xB5, 0x00, 0x01, 0x1F, 0x09, 0xFF, 0x01, 0xF4, 0x09, 0x00, 0x01, 0x1F, + 0x09, 0xFF, 0x01, 0xF4, 0x09, 0x00, 0x01, 0x1F, 0x09, 0xFF, 0x01, 0xF4, + 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD5, 0x07, 0x55, 0x01, 0x51, + 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xFE, + 0x04, 0xEE, 0x01, 0xDB, 0x01, 0x84, 0x0B, 0x00, 0x01, 0x1F, 0x08, 0xFF, + 0x01, 0xE7, 0x0A, 0x00, 0x01, 0x1F, 0x09, 0xFF, 0x01, 0xD2, 0x09, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD6, 0x04, 0x66, 0x01, 0x68, 0x01, 0xCF, + 0x01, 0xFF, 0x01, 0xFD, 0x01, 0x10, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x05, 0x00, 0x01, 0x04, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x90, + 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x3F, + 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x06, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF5, 0x08, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF7, + 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x05, + 0x01, 0xFF, 0x01, 0xF9, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x06, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF8, 0x08, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF7, + 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x0C, + 0x01, 0xFF, 0x01, 0xF4, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x06, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0xE0, 0x08, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, 0x01, 0x05, 0x02, 0xFF, 0x01, 0x80, + 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xE7, 0x04, 0x77, 0x01, 0x89, + 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xFE, 0x09, 0x00, 0x01, 0x1F, 0x09, 0xFF, + 0x01, 0xE2, 0x09, 0x00, 0x01, 0x1F, 0x08, 0xFF, 0x01, 0xFB, 0x01, 0x10, + 0x09, 0x00, 0x01, 0x1D, 0x06, 0xDD, 0x01, 0xDC, 0x01, 0xB7, 0x01, 0x20, + 0xD1, 0x00, + + /* 2 */ + 0xB5, 0x00, 0x01, 0x1F, 0x06, 0xFF, 0x01, 0xEC, 0x01, 0x94, 0x0B, 0x00, + 0x01, 0x1F, 0x08, 0xFF, 0x01, 0xC3, 0x0A, 0x00, 0x01, 0x1F, 0x09, 0xFF, + 0x01, 0x40, 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD6, 0x03, 0x66, + 0x01, 0x67, 0x01, 0x9D, 0x02, 0xFF, 0x01, 0xE1, 0x09, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, 0x01, 0x4E, 0x01, 0xFF, 0x01, 0xF9, + 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, 0x01, 0x04, + 0x02, 0xFF, 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, + 0x01, 0xDF, 0x01, 0xFF, 0x01, 0x20, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x06, 0x00, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0x30, 0x08, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0xAF, 0x01, 0xFF, + 0x01, 0x20, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, + 0x01, 0xCF, 0x01, 0xFF, 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x05, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xFA, 0x09, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, 0x01, 0x1D, 0x01, 0xFF, 0x01, 0xF2, + 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD2, 0x03, 0x22, 0x01, 0x23, + 0x01, 0x59, 0x02, 0xFF, 0x01, 0x50, 0x09, 0x00, 0x01, 0x1F, 0x08, 0xFF, + 0x01, 0xD3, 0x0A, 0x00, 0x01, 0x1F, 0x08, 0xFF, 0x01, 0xB3, 0x0A, 0x00, + 0x01, 0x1F, 0x09, 0xFF, 0x01, 0xA0, 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xD4, 0x04, 0x44, 0x01, 0x45, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0xFD, + 0x01, 0x10, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, + 0x01, 0x01, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0xA0, 0x08, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xF1, + 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x09, + 0x01, 0xFF, 0x01, 0xF6, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x06, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF8, 0x08, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF9, + 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x07, + 0x01, 0xFF, 0x01, 0xF7, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x06, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF5, 0x08, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xF1, + 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, 0x01, 0x05, + 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x90, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xE7, 0x04, 0x77, 0x01, 0x79, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xFE, + 0x01, 0x10, 0x08, 0x00, 0x01, 0x1F, 0x09, 0xFF, 0x01, 0xE3, 0x09, 0x00, + 0x01, 0x1F, 0x08, 0xFF, 0x01, 0xFA, 0x01, 0x10, 0x09, 0x00, 0x01, 0x1D, + 0x07, 0xDD, 0x01, 0xB7, 0x01, 0x20, 0xD1, 0x00, + + /* 3 */ + 0xB5, 0x00, 0x01, 0x1F, 0x09, 0xFF, 0x01, 0xF4, 0x09, 0x00, 0x01, 0x1F, + 0x09, 0xFF, 0x01, 0xF4, 0x09, 0x00, 0x01, 0x1F, 0x09, 0xFF, 0x01, 0xF4, + 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD5, 0x07, 0x55, 0x01, 0x51, + 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1E, + 0x01, 0xEE, 0x01, 0xB0, 0xD8, 0x00, + + /* 4 */ + 0xB8, 0x00, 0x01, 0x08, 0x09, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x08, + 0x09, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x08, 0x09, 0xFF, 0x01, 0x30, + 0x09, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xFA, 0x05, 0x66, 0x01, 0xDF, + 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xF6, + 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x08, + 0x01, 0xFF, 0x01, 0xF6, 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, + 0x09, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xF6, 0x05, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xF6, + 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x09, + 0x01, 0xFF, 0x01, 0xF6, 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, + 0x09, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF6, 0x05, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF6, + 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x09, + 0x01, 0xFF, 0x01, 0xF6, 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, + 0x09, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF5, 0x05, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF5, + 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x0B, + 0x01, 0xFF, 0x01, 0xF4, 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, + 0x09, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF3, 0x05, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xF2, + 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x0F, + 0x01, 0xFF, 0x01, 0xF0, 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, + 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xF0, 0x05, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x6F, + 0x01, 0xFF, 0x01, 0xA0, 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, + 0x09, 0x00, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0x70, 0x05, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x30, + 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x08, 0x00, 0x01, 0x05, + 0x01, 0xFF, 0x01, 0xFE, 0x06, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, + 0x08, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF8, 0x06, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x30, 0x08, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xF1, + 0x06, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x05, 0x00, 0x01, 0x02, + 0x01, 0x22, 0x01, 0x28, 0x02, 0xFF, 0x01, 0xC7, 0x06, 0x77, 0x01, 0xDF, + 0x01, 0xFF, 0x01, 0x52, 0x01, 0x22, 0x04, 0x00, 0x01, 0x0F, 0x0F, 0xFF, + 0x04, 0x00, 0x01, 0x0F, 0x0F, 0xFF, 0x04, 0x00, 0x01, 0x0F, 0x01, 0xFF, + 0x01, 0xED, 0x0B, 0xDD, 0x01, 0xEF, 0x01, 0xFF, 0x04, 0x00, 0x01, 0x0F, + 0x01, 0xFF, 0x01, 0x50, 0x0B, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x04, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0x50, 0x0B, 0x00, 0x01, 0x5F, 0x01, 0xFF, + 0x04, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0x50, 0x0B, 0x00, 0x01, 0x5F, + 0x01, 0xFF, 0x04, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0x50, 0x0B, 0x00, + 0x01, 0x5F, 0x01, 0xFF, 0x04, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0x50, + 0x0B, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x04, 0x00, 0x01, 0x06, 0x01, 0x66, + 0x01, 0x20, 0x0B, 0x00, 0x01, 0x26, 0x01, 0x66, 0x54, 0x00, + + /* 5 */ + 0xB5, 0x00, 0x01, 0x1F, 0x0A, 0xFF, 0x09, 0x00, 0x01, 0x1F, 0x0A, 0xFF, + 0x09, 0x00, 0x01, 0x1F, 0x0A, 0xFF, 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xD6, 0x07, 0x66, 0x01, 0x65, 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC1, 0x07, 0x11, 0x01, 0x10, 0x09, 0x00, + 0x01, 0x1F, 0x09, 0xFF, 0x01, 0xF5, 0x09, 0x00, 0x01, 0x1F, 0x09, 0xFF, + 0x01, 0xF5, 0x09, 0x00, 0x01, 0x1F, 0x09, 0xFF, 0x01, 0xF5, 0x09, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD4, 0x07, 0x44, 0x01, 0x41, 0x09, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xE7, 0x08, 0x77, 0x01, 0x50, 0x08, 0x00, + 0x01, 0x1F, 0x0A, 0xFF, 0x01, 0xB0, 0x08, 0x00, 0x01, 0x1F, 0x0A, 0xFF, + 0x01, 0xB0, 0x08, 0x00, 0x01, 0x1E, 0x0A, 0xEE, 0x01, 0xA0, 0xCF, 0x00, + + /* 6 */ + 0xB5, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0xF3, 0x04, 0x00, 0x01, 0x4F, + 0x01, 0xFF, 0x01, 0x90, 0x04, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0xE1, + 0x03, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x10, 0x03, 0x00, + 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, 0x03, 0x00, 0x01, 0x0A, 0x02, 0xFF, + 0x01, 0x30, 0x03, 0x00, 0x01, 0x01, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xB0, + 0x03, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, 0x03, 0x00, 0x01, 0x7F, + 0x01, 0xFF, 0x01, 0xF5, 0x05, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xF8, + 0x03, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, 0x02, 0x00, 0x01, 0x03, + 0x02, 0xFF, 0x01, 0x80, 0x05, 0x00, 0x01, 0x05, 0x02, 0xFF, 0x01, 0x50, + 0x02, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, 0x02, 0x00, 0x01, 0x1E, + 0x01, 0xFF, 0x01, 0xFB, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0xF2, + 0x02, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, 0x02, 0x00, 0x01, 0xCF, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xFD, + 0x02, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, 0x01, 0x00, 0x01, 0x09, + 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x20, 0x07, 0x00, 0x01, 0x01, 0x01, 0xDF, + 0x01, 0xFF, 0x01, 0xB0, 0x01, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, + 0x01, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0xF4, 0x09, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0xF7, 0x01, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, + 0x01, 0x02, 0x02, 0xFF, 0x01, 0x70, 0x09, 0x00, 0x01, 0x05, 0x02, 0xFF, + 0x01, 0x40, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, 0x01, 0x1D, 0x01, 0xFF, + 0x01, 0xFA, 0x0B, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xE2, 0x01, 0x4F, + 0x01, 0xFF, 0x01, 0x90, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0xC0, 0x0B, 0x00, + 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xFC, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0x98, + 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x10, 0x0C, 0x00, 0x01, 0xDF, 0x01, 0xFF, + 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xF3, 0x0D, 0x00, + 0x01, 0x2E, 0x05, 0xFF, 0x01, 0x60, 0x0D, 0x00, 0x01, 0x07, 0x04, 0xFF, + 0x01, 0xFC, 0x0E, 0x00, 0x01, 0x2E, 0x05, 0xFF, 0x01, 0x60, 0x0C, 0x00, + 0x01, 0x01, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0xF4, 0x0C, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xFD, + 0x01, 0x5F, 0x01, 0xFF, 0x01, 0x9A, 0x02, 0xFF, 0x01, 0x30, 0x0B, 0x00, + 0x01, 0xBF, 0x01, 0xFF, 0x01, 0xE2, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, + 0x01, 0xBF, 0x01, 0xFF, 0x01, 0xE2, 0x0A, 0x00, 0x01, 0x09, 0x02, 0xFF, + 0x01, 0x30, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, 0x01, 0x0D, 0x01, 0xFF, + 0x01, 0xFD, 0x01, 0x10, 0x09, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xF4, + 0x01, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, 0x01, 0x01, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0xC0, 0x08, 0x00, 0x01, 0x06, 0x02, 0xFF, 0x01, 0x50, + 0x01, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, 0x01, 0x00, 0x01, 0x3F, + 0x01, 0xFF, 0x01, 0xFB, 0x08, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0xF7, + 0x02, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, 0x01, 0x00, 0x01, 0x04, + 0x02, 0xFF, 0x01, 0x90, 0x06, 0x00, 0x01, 0x03, 0x02, 0xFF, 0x01, 0x80, + 0x02, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, 0x02, 0x00, 0x01, 0x6F, + 0x01, 0xFF, 0x01, 0xF7, 0x06, 0x00, 0x01, 0x2E, 0x01, 0xFF, 0x01, 0xFA, + 0x03, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, 0x02, 0x00, 0x01, 0x08, + 0x02, 0xFF, 0x01, 0x50, 0x04, 0x00, 0x01, 0x01, 0x01, 0xDF, 0x01, 0xFF, + 0x01, 0xB0, 0x03, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, 0x03, 0x00, + 0x01, 0xAF, 0x01, 0xFF, 0x01, 0xF4, 0x04, 0x00, 0x01, 0x0C, 0x01, 0xFF, + 0x01, 0xFC, 0x04, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, 0x03, 0x00, + 0x01, 0x0B, 0x02, 0xFF, 0x01, 0x20, 0x03, 0x00, 0x01, 0xAF, 0x01, 0xFF, + 0x01, 0xD1, 0x04, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, 0x04, 0x00, + 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xE1, 0x02, 0x00, 0x01, 0x08, 0x01, 0xFF, + 0x01, 0xFE, 0x01, 0x20, 0x04, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, + 0x04, 0x00, 0x01, 0x2E, 0x01, 0xFF, 0x01, 0xFD, 0x01, 0x10, 0x01, 0x00, + 0x01, 0x5D, 0x01, 0xDD, 0x01, 0xD3, 0x05, 0x00, 0x01, 0x3D, 0x01, 0xDD, + 0x01, 0x80, 0x04, 0x00, 0x01, 0x03, 0x02, 0xDD, 0x01, 0x90, 0xC9, 0x00, + + /* 7 */ + 0xA5, 0x00, 0x01, 0x45, 0x01, 0x67, 0x01, 0x65, 0x01, 0x20, 0x0E, 0x00, + 0x01, 0x06, 0x01, 0xCF, 0x03, 0xFF, 0x01, 0xFE, 0x01, 0x92, 0x0C, 0x00, + 0x01, 0x04, 0x01, 0xEF, 0x06, 0xFF, 0x01, 0x90, 0x0B, 0x00, 0x01, 0x6F, + 0x02, 0xFF, 0x01, 0xFD, 0x01, 0xCB, 0x01, 0xCF, 0x02, 0xFF, 0x01, 0xFC, + 0x0A, 0x00, 0x01, 0x04, 0x02, 0xFF, 0x01, 0xD6, 0x01, 0x10, 0x02, 0x00, + 0x01, 0x39, 0x02, 0xFF, 0x01, 0xA0, 0x09, 0x00, 0x01, 0x0D, 0x01, 0xFF, + 0x01, 0xF9, 0x05, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0xF3, 0x09, 0x00, + 0x01, 0x4F, 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, 0x01, 0x06, 0x01, 0xFF, + 0x01, 0xF9, 0x09, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x06, 0x00, + 0x01, 0xFF, 0x01, 0xFE, 0x09, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x07, 0x00, + 0x01, 0xDF, 0x01, 0xFF, 0x09, 0x00, 0x01, 0xAC, 0x01, 0xCB, 0x07, 0x00, + 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x10, 0x10, 0x00, 0x01, 0x04, 0x02, 0xFF, + 0x11, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xFC, 0x10, 0x00, 0x01, 0x01, + 0x01, 0xBF, 0x01, 0xFF, 0x01, 0xF5, 0x10, 0x00, 0x01, 0x5D, 0x02, 0xFF, + 0x01, 0xA0, 0x0D, 0x00, 0x02, 0x99, 0x01, 0xBE, 0x02, 0xFF, 0x01, 0xF8, + 0x0E, 0x00, 0x05, 0xFF, 0x01, 0x40, 0x0E, 0x00, 0x05, 0xFF, 0x01, 0xF9, + 0x0E, 0x00, 0x02, 0xBB, 0x01, 0xCD, 0x03, 0xFF, 0x01, 0xD1, 0x10, 0x00, + 0x01, 0x16, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xFC, 0x11, 0x00, 0x01, 0x0A, + 0x02, 0xFF, 0x01, 0x60, 0x11, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0xC0, + 0x07, 0x00, 0x01, 0x07, 0x01, 0x99, 0x01, 0x80, 0x07, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0xF0, 0x07, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF0, + 0x07, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xF1, 0x07, 0x00, 0x01, 0x08, + 0x01, 0xFF, 0x01, 0xF2, 0x07, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF1, + 0x07, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF8, 0x07, 0x00, 0x01, 0x0F, + 0x01, 0xFF, 0x01, 0xE0, 0x07, 0x00, 0x01, 0x01, 0x02, 0xFF, 0x01, 0x20, + 0x06, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0xA0, 0x08, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0xD2, 0x05, 0x00, 0x01, 0x03, 0x02, 0xFF, 0x01, 0x30, + 0x08, 0x00, 0x01, 0x1E, 0x02, 0xFF, 0x01, 0x81, 0x03, 0x00, 0x01, 0x01, + 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xFA, 0x09, 0x00, 0x01, 0x03, 0x01, 0xEF, + 0x02, 0xFF, 0x01, 0xDA, 0x01, 0x98, 0x01, 0x9A, 0x01, 0xDF, 0x02, 0xFF, + 0x01, 0xC0, 0x0A, 0x00, 0x01, 0x2D, 0x07, 0xFF, 0x01, 0xFA, 0x0C, 0x00, + 0x01, 0x6D, 0x05, 0xFF, 0x01, 0xFB, 0x01, 0x30, 0x0D, 0x00, 0x01, 0x27, + 0x01, 0x9B, 0x01, 0xCD, 0x01, 0xBA, 0x01, 0x95, 0x01, 0x10, 0xBE, 0x00, + + /* 8 */ + 0xB5, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x07, 0x00, 0x01, 0xCF, + 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, + 0x06, 0x00, 0x01, 0x07, 0x02, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0x90, 0x06, 0x00, 0x01, 0x2F, 0x02, 0xFF, 0x01, 0xA0, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x06, 0x00, 0x01, 0xCF, + 0x02, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, + 0x05, 0x00, 0x01, 0x06, 0x03, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0x90, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, + 0x05, 0x00, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0xA0, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x04, 0x00, 0x01, 0x05, + 0x01, 0xFF, 0x01, 0xFA, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x04, 0x00, 0x01, 0x1E, 0x01, 0xFF, + 0x01, 0xE1, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0x90, 0x04, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x60, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x90, 0x03, 0x00, 0x01, 0x04, 0x01, 0xFF, 0x01, 0xFB, 0x01, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x90, 0x03, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xF2, 0x01, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x90, 0x03, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x70, 0x01, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x90, 0x02, 0x00, 0x01, 0x03, 0x01, 0xFF, 0x01, 0xFD, 0x02, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x90, 0x02, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF3, 0x02, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x90, 0x02, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0x80, 0x02, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x90, 0x01, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xFD, 0x03, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x90, 0x01, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF4, 0x03, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x90, 0x01, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0x90, 0x03, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x90, 0x01, 0x01, 0x01, 0xEF, 0x01, 0xFE, 0x01, 0x10, 0x03, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x90, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF5, 0x04, 0x00, 0x01, 0x0F, + 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, + 0x01, 0x5F, 0x01, 0xFF, 0x01, 0xB0, 0x04, 0x00, 0x01, 0x0F, 0x01, 0xFF, + 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0x10, 0x04, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x99, 0x01, 0xFF, 0x01, 0xF6, + 0x05, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, 0x01, 0x0F, + 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x03, 0xFF, 0x01, 0x20, + 0x05, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, + 0x02, 0xFF, 0x01, 0xF7, 0x06, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, + 0x07, 0x00, 0x01, 0x1F, 0x02, 0xFF, 0x01, 0xD0, 0x06, 0x00, 0x01, 0x0F, + 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x02, 0xFF, 0x01, 0x30, + 0x06, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1E, + 0x01, 0xEE, 0x01, 0xE8, 0x07, 0x00, 0x01, 0x0E, 0x01, 0xEE, 0x01, 0xA0, + 0xCE, 0x00, + + /* 9 */ + 0x2C, 0x00, 0x01, 0x7F, 0x01, 0xF1, 0x03, 0x00, 0x01, 0x9F, 0x01, 0xE0, + 0x0D, 0x00, 0x01, 0x5F, 0x01, 0xF8, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, + 0x01, 0xB0, 0x0D, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xB6, 0x01, 0x45, + 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x50, 0x0D, 0x00, 0x01, 0x05, 0x04, 0xFF, + 0x01, 0xFB, 0x0F, 0x00, 0x01, 0x5E, 0x03, 0xFF, 0x01, 0x90, 0x10, 0x00, + 0x01, 0x46, 0x01, 0x87, 0x01, 0x51, 0x20, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x90, 0x07, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x06, 0x00, 0x01, 0x07, 0x02, 0xFF, + 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x06, 0x00, + 0x01, 0x2F, 0x02, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x90, 0x06, 0x00, 0x01, 0xBF, 0x02, 0xFF, 0x01, 0xA0, 0x07, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x05, 0x00, 0x01, 0x06, 0x03, 0xFF, + 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x05, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x05, 0x00, 0x01, 0xAF, 0x01, 0xFF, + 0x01, 0x4F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x90, 0x04, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xFA, 0x01, 0x0F, + 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, + 0x04, 0x00, 0x01, 0x0E, 0x01, 0xFF, 0x01, 0xE1, 0x01, 0x0F, 0x01, 0xFF, + 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x04, 0x00, + 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x60, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x03, 0x00, 0x01, 0x04, + 0x01, 0xFF, 0x01, 0xFB, 0x01, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x03, 0x00, 0x01, 0x0D, + 0x01, 0xFF, 0x01, 0xF2, 0x01, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x03, 0x00, 0x01, 0x8F, + 0x01, 0xFF, 0x01, 0x70, 0x01, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x02, 0x00, 0x01, 0x03, + 0x01, 0xFF, 0x01, 0xFD, 0x02, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x02, 0x00, 0x01, 0x0C, + 0x01, 0xFF, 0x01, 0xF3, 0x02, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x02, 0x00, 0x01, 0x7F, + 0x01, 0xFF, 0x01, 0x80, 0x02, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x01, 0x00, 0x01, 0x02, + 0x01, 0xFF, 0x01, 0xFD, 0x03, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x01, 0x00, 0x01, 0x0B, + 0x01, 0xFF, 0x01, 0xF4, 0x03, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x01, 0x00, 0x01, 0x6F, + 0x01, 0xFF, 0x01, 0x90, 0x03, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x01, 0x01, 0x01, 0xEF, + 0x01, 0xFE, 0x01, 0x10, 0x03, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x01, 0x0A, 0x01, 0xFF, + 0x01, 0xF5, 0x04, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0xB0, + 0x04, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0x90, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x10, 0x04, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x99, 0x01, 0xFF, 0x01, 0xF6, 0x05, 0x00, 0x01, 0x0F, 0x01, 0xFF, + 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xDF, 0x01, 0xFF, + 0x01, 0xC0, 0x05, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, + 0x01, 0x1F, 0x03, 0xFF, 0x01, 0x20, 0x05, 0x00, 0x01, 0x0F, 0x01, 0xFF, + 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x02, 0xFF, 0x01, 0xF7, 0x06, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x02, 0xFF, + 0x01, 0xD0, 0x06, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, + 0x01, 0x1F, 0x02, 0xFF, 0x01, 0x30, 0x06, 0x00, 0x01, 0x0F, 0x01, 0xFF, + 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1E, 0x01, 0xEE, 0x01, 0xE8, 0x07, 0x00, + 0x01, 0x0E, 0x01, 0xEE, 0x01, 0xA0, 0xCE, 0x00, + + /* 10 */ + 0xB5, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, 0x01, 0x1D, + 0x01, 0xFF, 0x01, 0xFA, 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x04, 0x00, 0x01, 0x01, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xA0, 0x09, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x04, 0x00, 0x01, 0x1D, 0x01, 0xFF, + 0x01, 0xF9, 0x0A, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x03, 0x00, + 0x01, 0x01, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0x90, 0x0A, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x03, 0x00, 0x01, 0x2D, 0x01, 0xFF, 0x01, 0xF9, + 0x0B, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x02, 0x00, 0x01, 0x02, + 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x90, 0x0B, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x02, 0x00, 0x01, 0x2E, 0x01, 0xFF, 0x01, 0xF8, 0x0C, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x01, 0x00, 0x01, 0x02, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0x80, 0x0C, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x01, 0x00, 0x01, 0x2E, 0x01, 0xFF, 0x01, 0xF8, 0x0D, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x01, 0x02, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x80, + 0x0D, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x01, 0x2E, 0x01, 0xFF, + 0x01, 0xF7, 0x0E, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC3, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0x70, 0x0E, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xEE, + 0x01, 0xFF, 0x01, 0xF7, 0x0F, 0x00, 0x01, 0x1F, 0x03, 0xFF, 0x01, 0x70, + 0x0F, 0x00, 0x01, 0x1F, 0x03, 0xFF, 0x01, 0x20, 0x0F, 0x00, 0x01, 0x1F, + 0x03, 0xFF, 0x01, 0xE2, 0x0F, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xDD, + 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x20, 0x0E, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC1, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xE2, 0x0E, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x01, 0x1D, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x20, + 0x0D, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x01, 0x01, 0x01, 0xDF, + 0x01, 0xFF, 0x01, 0xE2, 0x0D, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x01, 0x00, 0x01, 0x1D, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x20, 0x0C, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x01, 0x00, 0x01, 0x01, 0x01, 0xDF, + 0x01, 0xFF, 0x01, 0xE2, 0x0C, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x02, 0x00, 0x01, 0x1D, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x20, 0x0B, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x02, 0x00, 0x01, 0x01, 0x01, 0xDF, + 0x01, 0xFF, 0x01, 0xE2, 0x0B, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x03, 0x00, 0x01, 0x1D, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x30, 0x0A, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x03, 0x00, 0x01, 0x02, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0xE3, 0x0A, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x04, 0x00, 0x01, 0x2E, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x30, 0x09, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x04, 0x00, 0x01, 0x02, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0xE3, 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x05, 0x00, 0x01, 0x2E, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x30, 0x08, 0x00, + 0x01, 0x1E, 0x01, 0xEE, 0x01, 0xB0, 0x05, 0x00, 0x01, 0x02, 0x01, 0xDE, + 0x01, 0xEE, 0x01, 0xD2, 0xCF, 0x00, + + /* 11 */ + 0xB6, 0x00, 0x01, 0x08, 0x09, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x08, + 0x09, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x08, 0x09, 0xFF, 0x01, 0x30, + 0x09, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xFA, 0x05, 0x66, 0x01, 0xDF, + 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xF6, + 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x08, + 0x01, 0xFF, 0x01, 0xF6, 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, + 0x09, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xF6, 0x05, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xF6, + 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x09, + 0x01, 0xFF, 0x01, 0xF6, 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, + 0x09, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF6, 0x05, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF6, + 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x09, + 0x01, 0xFF, 0x01, 0xF6, 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, + 0x09, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF5, 0x05, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF4, + 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x0A, + 0x01, 0xFF, 0x01, 0xF4, 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, + 0x09, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF3, 0x05, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xF1, + 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x0E, + 0x01, 0xFF, 0x01, 0xF0, 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, + 0x09, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xE0, 0x05, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xC0, + 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x4F, + 0x01, 0xFF, 0x01, 0x90, 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, + 0x09, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0x60, 0x05, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x20, + 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x08, 0x00, 0x01, 0x01, + 0x01, 0xFF, 0x01, 0xFE, 0x06, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, + 0x08, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xF9, 0x06, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x30, 0x08, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xF2, + 0x06, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x07, 0x00, 0x01, 0x1A, + 0x02, 0xFF, 0x01, 0xA0, 0x06, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, + 0x07, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x10, 0x06, 0x00, + 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x07, 0x00, 0x01, 0x2F, 0x01, 0xFF, + 0x01, 0xF4, 0x07, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x07, 0x00, + 0x01, 0x2F, 0x01, 0xFB, 0x01, 0x20, 0x07, 0x00, 0x01, 0xAE, 0x01, 0xEE, + 0x01, 0x30, 0x07, 0x00, 0x01, 0x03, 0x01, 0x10, 0xC6, 0x00, + + /* 12 */ + 0xB5, 0x00, 0x01, 0x1E, 0x02, 0xEE, 0x01, 0x70, 0x08, 0x00, 0x02, 0xEE, + 0x01, 0xE7, 0x05, 0x00, 0x01, 0x1F, 0x02, 0xFF, 0x01, 0xC0, 0x07, 0x00, + 0x01, 0x05, 0x02, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x02, 0xFF, + 0x01, 0xF2, 0x07, 0x00, 0x01, 0x0B, 0x02, 0xFF, 0x01, 0xF8, 0x05, 0x00, + 0x01, 0x1F, 0x02, 0xFF, 0x01, 0xF7, 0x07, 0x00, 0x01, 0x1F, 0x02, 0xFF, + 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x02, 0xFF, 0x01, 0xFD, 0x07, 0x00, + 0x01, 0x6F, 0x02, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x30, 0x06, 0x00, 0x01, 0xBF, 0x01, 0xFC, + 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x9D, + 0x01, 0xFF, 0x01, 0x80, 0x05, 0x00, 0x01, 0x01, 0x01, 0xFF, 0x01, 0xF7, + 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x98, + 0x01, 0xFF, 0x01, 0xE0, 0x05, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xE2, + 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x92, + 0x01, 0xFF, 0x01, 0xF3, 0x05, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0x92, + 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, + 0x01, 0xDF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x42, + 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, + 0x01, 0x7F, 0x01, 0xFE, 0x05, 0x00, 0x01, 0x6F, 0x01, 0xFE, 0x01, 0x02, + 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, + 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x40, 0x04, 0x00, 0x01, 0xCF, 0x01, 0xF9, + 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x90, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0x90, 0x03, 0x00, 0x01, 0x01, + 0x01, 0xFF, 0x01, 0xF3, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xE0, + 0x03, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xE0, 0x01, 0x02, 0x01, 0xFF, + 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x01, 0x01, + 0x01, 0xFF, 0x01, 0xF4, 0x03, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0x80, + 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x90, 0x01, 0x00, 0x01, 0xCF, 0x01, 0xFA, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0x30, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x01, 0x00, 0x01, 0x6F, 0x01, 0xFF, + 0x03, 0x00, 0x01, 0x7F, 0x01, 0xFD, 0x01, 0x00, 0x01, 0x02, 0x01, 0xFF, + 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x01, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x50, 0x02, 0x00, 0x01, 0xCF, 0x01, 0xF8, + 0x01, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0x90, 0x01, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xA0, + 0x01, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF3, 0x01, 0x00, 0x01, 0x02, + 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, + 0x01, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x01, 0x00, 0x01, 0x07, + 0x01, 0xFF, 0x01, 0xD0, 0x01, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF8, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x02, 0x00, 0x01, 0xFF, + 0x01, 0xF6, 0x01, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0x80, 0x01, 0x00, + 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x90, 0x02, 0x00, 0x01, 0xAF, 0x01, 0xFB, 0x01, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0x20, 0x01, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF8, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x02, 0x00, 0x01, 0x5F, + 0x01, 0xFF, 0x01, 0x10, 0x01, 0x7F, 0x01, 0xFD, 0x02, 0x00, 0x01, 0x02, + 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, + 0x02, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0x60, 0x01, 0xDF, 0x01, 0xF7, + 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0x90, 0x02, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xC2, + 0x01, 0xFF, 0x01, 0xF2, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF8, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x02, 0x00, 0x01, 0x04, + 0x01, 0xFF, 0x01, 0xFA, 0x01, 0xFF, 0x01, 0xC0, 0x02, 0x00, 0x01, 0x02, + 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, + 0x03, 0x00, 0x01, 0xEF, 0x02, 0xFF, 0x01, 0x70, 0x02, 0x00, 0x01, 0x02, + 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, + 0x03, 0x00, 0x01, 0x9F, 0x02, 0xFF, 0x01, 0x20, 0x02, 0x00, 0x01, 0x02, + 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, + 0x03, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0xFC, 0x03, 0x00, 0x01, 0x02, + 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1E, 0x01, 0xEE, 0x01, 0x80, + 0x03, 0x00, 0x01, 0x0D, 0x01, 0xEE, 0x01, 0xE6, 0x03, 0x00, 0x01, 0x02, + 0x01, 0xEE, 0x01, 0xE7, 0xCC, 0x00, + + /* 13 */ + 0xB5, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x8F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x0B, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x0B, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x0B, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD4, + 0x07, 0x44, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1E, + 0x01, 0xEE, 0x01, 0xB0, 0x07, 0x00, 0x01, 0x8E, 0x01, 0xEE, 0x01, 0x40, + 0xCE, 0x00, + + /* 14 */ + 0xA6, 0x00, 0x01, 0x13, 0x01, 0x56, 0x01, 0x64, 0x01, 0x31, 0x0E, 0x00, + 0x01, 0x02, 0x01, 0x8D, 0x04, 0xFF, 0x01, 0xC7, 0x01, 0x10, 0x0B, 0x00, + 0x01, 0x01, 0x01, 0x9F, 0x06, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0x3E, + 0x08, 0xFF, 0x01, 0xD2, 0x09, 0x00, 0x01, 0x04, 0x02, 0xFF, 0x01, 0xFC, + 0x01, 0x72, 0x01, 0x00, 0x01, 0x01, 0x01, 0x38, 0x01, 0xDF, 0x02, 0xFF, + 0x01, 0x30, 0x08, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x50, + 0x04, 0x00, 0x01, 0x07, 0x02, 0xFF, 0x01, 0xE2, 0x07, 0x00, 0x01, 0x01, + 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xD1, 0x06, 0x00, 0x01, 0x2E, 0x01, 0xFF, + 0x01, 0xFD, 0x07, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x10, + 0x06, 0x00, 0x01, 0x02, 0x02, 0xFF, 0x01, 0x60, 0x06, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xF4, 0x08, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xE0, + 0x06, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xA0, 0x08, 0x00, 0x01, 0x0C, + 0x01, 0xFF, 0x01, 0xF5, 0x06, 0x00, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0x30, + 0x08, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xFB, 0x05, 0x00, 0x01, 0x02, + 0x01, 0xFF, 0x01, 0xFD, 0x0A, 0x00, 0x02, 0xFF, 0x05, 0x00, 0x01, 0x06, + 0x01, 0xFF, 0x01, 0xF9, 0x0A, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x30, + 0x04, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xF5, 0x0A, 0x00, 0x01, 0x8F, + 0x01, 0xFF, 0x01, 0x50, 0x04, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF4, + 0x0A, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0x70, 0x04, 0x00, 0x01, 0x0B, + 0x01, 0xFF, 0x01, 0xF2, 0x0A, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0x80, + 0x04, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF2, 0x0A, 0x00, 0x01, 0x4F, + 0x01, 0xFF, 0x01, 0x90, 0x04, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF3, + 0x0A, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0x80, 0x04, 0x00, 0x01, 0x09, + 0x01, 0xFF, 0x01, 0xF4, 0x0A, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0x60, + 0x04, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF7, 0x0A, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x50, 0x04, 0x00, 0x01, 0x03, 0x01, 0xFF, 0x01, 0xFB, + 0x0A, 0x00, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0x10, 0x05, 0x00, 0x02, 0xFF, + 0x01, 0x10, 0x08, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xFD, 0x06, 0x00, + 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x70, 0x08, 0x00, 0x01, 0x09, 0x01, 0xFF, + 0x01, 0xF8, 0x06, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0xE1, 0x08, 0x00, + 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xF1, 0x06, 0x00, 0x01, 0x0C, 0x01, 0xFF, + 0x01, 0xFA, 0x08, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0xA0, 0x06, 0x00, + 0x01, 0x04, 0x02, 0xFF, 0x01, 0x80, 0x06, 0x00, 0x01, 0x0A, 0x01, 0xFF, + 0x01, 0xFE, 0x01, 0x10, 0x07, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xF9, + 0x05, 0x00, 0x01, 0x01, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0xF5, 0x08, 0x00, + 0x01, 0x0B, 0x02, 0xFF, 0x01, 0xE6, 0x01, 0x10, 0x02, 0x00, 0x01, 0x02, + 0x01, 0x8F, 0x02, 0xFF, 0x01, 0x80, 0x09, 0x00, 0x01, 0xAF, 0x02, 0xFF, + 0x01, 0xFC, 0x01, 0xA8, 0x01, 0x8A, 0x01, 0xDF, 0x02, 0xFF, 0x01, 0xF6, + 0x0A, 0x00, 0x01, 0x06, 0x01, 0xEF, 0x06, 0xFF, 0x01, 0xFD, 0x01, 0x40, + 0x0B, 0x00, 0x01, 0x18, 0x01, 0xEF, 0x04, 0xFF, 0x01, 0xFD, 0x01, 0x60, + 0x0D, 0x00, 0x01, 0x03, 0x01, 0x7A, 0x01, 0xCD, 0x01, 0xDC, 0x01, 0xA7, + 0x01, 0x30, 0xBD, 0x00, + + /* 15 */ + 0xB5, 0x00, 0x01, 0x1F, 0x0B, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x0B, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x0B, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xE6, 0x07, 0x66, 0x01, 0xCF, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1E, + 0x01, 0xEE, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9E, 0x01, 0xEE, 0x01, 0x40, + 0xCE, 0x00, + + /* 16 */ + 0xB5, 0x00, 0x01, 0x1E, 0x06, 0xEE, 0x01, 0xEC, 0x01, 0x95, 0x0B, 0x00, + 0x01, 0x1F, 0x08, 0xFF, 0x01, 0xE5, 0x0A, 0x00, 0x01, 0x1F, 0x09, 0xFF, + 0x01, 0x80, 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD6, 0x03, 0x66, + 0x01, 0x67, 0x01, 0x9D, 0x02, 0xFF, 0x01, 0xF5, 0x09, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, 0x01, 0x4E, 0x01, 0xFF, 0x01, 0xFE, + 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, 0x01, 0x03, + 0x02, 0xFF, 0x01, 0x50, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x06, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x90, 0x08, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0xB0, + 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x3F, + 0x01, 0xFF, 0x01, 0xD0, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x06, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0xC0, 0x08, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xA0, + 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0x70, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x05, 0x00, 0x01, 0x1B, 0x02, 0xFF, 0x01, 0x10, 0x08, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC1, 0x03, 0x11, 0x01, 0x12, 0x01, 0x48, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0xF9, 0x09, 0x00, 0x01, 0x1F, 0x09, 0xFF, 0x01, 0xC0, + 0x09, 0x00, 0x01, 0x1F, 0x08, 0xFF, 0x01, 0xFB, 0x01, 0x10, 0x09, 0x00, + 0x01, 0x1F, 0x07, 0xFF, 0x01, 0xFB, 0x01, 0x40, 0x0A, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD4, 0x04, 0x44, 0x01, 0x32, 0x0C, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x1E, 0x01, 0xEE, 0x01, 0xB0, 0xD8, 0x00, + + /* 17 */ + 0xA6, 0x00, 0x01, 0x35, 0x01, 0x66, 0x01, 0x54, 0x01, 0x10, 0x0E, 0x00, + 0x01, 0x06, 0x01, 0xCF, 0x03, 0xFF, 0x01, 0xFD, 0x01, 0x71, 0x0C, 0x00, + 0x01, 0x05, 0x01, 0xEF, 0x06, 0xFF, 0x01, 0x60, 0x0B, 0x00, 0x01, 0xAF, + 0x07, 0xFF, 0x01, 0xF8, 0x0A, 0x00, 0x01, 0x0A, 0x02, 0xFF, 0x01, 0xD7, + 0x01, 0x20, 0x01, 0x00, 0x01, 0x03, 0x01, 0x9F, 0x02, 0xFF, 0x01, 0x70, + 0x09, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xF8, 0x04, 0x00, 0x01, 0x01, + 0x01, 0xBF, 0x01, 0xFF, 0x01, 0xF2, 0x08, 0x00, 0x01, 0x02, 0x02, 0xFF, + 0x01, 0x60, 0x05, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xFA, 0x08, 0x00, + 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF8, 0x06, 0x00, 0x01, 0x02, 0x02, 0xFF, + 0x01, 0x10, 0x07, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, + 0x01, 0xAF, 0x01, 0xFF, 0x01, 0x60, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, + 0x01, 0x60, 0x07, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, + 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x10, 0x07, 0x00, 0x01, 0x05, 0x01, 0x55, + 0x01, 0x40, 0x06, 0x00, 0x01, 0x03, 0x01, 0xFF, 0x01, 0xFB, 0x11, 0x00, + 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF8, 0x11, 0x00, 0x01, 0x08, 0x01, 0xFF, + 0x01, 0xF5, 0x11, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF3, 0x11, 0x00, + 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF2, 0x11, 0x00, 0x01, 0x0B, 0x01, 0xFF, + 0x01, 0xF2, 0x11, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF3, 0x11, 0x00, + 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF4, 0x11, 0x00, 0x01, 0x07, 0x01, 0xFF, + 0x01, 0xF6, 0x11, 0x00, 0x01, 0x04, 0x01, 0xFF, 0x01, 0xFA, 0x08, 0x00, + 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF6, 0x06, 0x00, 0x01, 0x01, 0x01, 0xFF, + 0x01, 0xFE, 0x08, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xF3, 0x07, 0x00, + 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xF0, 0x07, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xB0, 0x07, 0x00, + 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xB0, 0x07, 0x00, 0x01, 0x1E, 0x01, 0xFF, + 0x01, 0xF5, 0x07, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x60, 0x07, 0x00, + 0x01, 0x07, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x20, 0x05, 0x00, 0x01, 0x08, + 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x10, 0x08, 0x00, 0x01, 0xDF, 0x01, 0xFF, + 0x01, 0xE3, 0x05, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xF7, 0x09, 0x00, + 0x01, 0x3F, 0x02, 0xFF, 0x01, 0x92, 0x03, 0x00, 0x01, 0x29, 0x02, 0xFF, + 0x01, 0xC0, 0x09, 0x00, 0x01, 0x04, 0x03, 0xFF, 0x01, 0xDA, 0x01, 0x88, + 0x01, 0x9C, 0x02, 0xFF, 0x01, 0xFE, 0x01, 0x10, 0x0A, 0x00, 0x01, 0x3D, + 0x07, 0xFF, 0x01, 0xC1, 0x0C, 0x00, 0x01, 0x7E, 0x05, 0xFF, 0x01, 0xD6, + 0x0E, 0x00, 0x01, 0x37, 0x01, 0xAC, 0x01, 0xDD, 0x01, 0xCA, 0x01, 0x73, + 0xBE, 0x00, + + /* 18 */ + 0xB4, 0x00, 0x01, 0x2F, 0x0B, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x2F, + 0x0B, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x2F, 0x0B, 0xFF, 0x01, 0xA0, + 0x07, 0x00, 0x01, 0x16, 0x04, 0x66, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xD6, + 0x04, 0x66, 0x01, 0x40, 0x0C, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, + 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, + 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, + 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, + 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, + 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, + 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, + 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, + 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, + 0x11, 0x00, 0x01, 0x2E, 0x01, 0xEE, 0x01, 0xA0, 0xD4, 0x00, + + /* 19 */ + 0xB4, 0x00, 0x01, 0x8E, 0x01, 0xEE, 0x01, 0xE2, 0x07, 0x00, 0x01, 0xDE, + 0x01, 0xEE, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xFA, + 0x06, 0x00, 0x01, 0x06, 0x02, 0xFF, 0x01, 0x30, 0x07, 0x00, 0x01, 0x08, + 0x02, 0xFF, 0x01, 0x20, 0x05, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xFA, + 0x08, 0x00, 0x01, 0x01, 0x02, 0xFF, 0x01, 0x90, 0x05, 0x00, 0x01, 0x6F, + 0x01, 0xFF, 0x01, 0xF2, 0x09, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xF2, + 0x05, 0x00, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xA0, 0x09, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xF9, 0x04, 0x00, 0x01, 0x06, 0x02, 0xFF, 0x01, 0x20, + 0x09, 0x00, 0x01, 0x08, 0x02, 0xFF, 0x01, 0x20, 0x03, 0x00, 0x01, 0x0D, + 0x01, 0xFF, 0x01, 0xFA, 0x0A, 0x00, 0x01, 0x01, 0x01, 0xEF, 0x01, 0xFF, + 0x01, 0x90, 0x03, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xF2, 0x0B, 0x00, + 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xF2, 0x03, 0x00, 0x01, 0xDF, 0x01, 0xFF, + 0x01, 0x90, 0x0B, 0x00, 0x01, 0x0E, 0x01, 0xFF, 0x01, 0xF9, 0x02, 0x00, + 0x01, 0x05, 0x02, 0xFF, 0x01, 0x20, 0x0B, 0x00, 0x01, 0x07, 0x02, 0xFF, + 0x01, 0x20, 0x01, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xF9, 0x0D, 0x00, + 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x90, 0x01, 0x00, 0x01, 0x5F, 0x01, 0xFF, + 0x01, 0xF1, 0x0D, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xF2, 0x01, 0x00, + 0x01, 0xDF, 0x01, 0xFF, 0x01, 0x80, 0x0D, 0x00, 0x01, 0x0E, 0x01, 0xFF, + 0x01, 0xF9, 0x01, 0x05, 0x02, 0xFF, 0x01, 0x10, 0x0D, 0x00, 0x01, 0x07, + 0x02, 0xFF, 0x01, 0x2D, 0x01, 0xFF, 0x01, 0xF8, 0x0F, 0x00, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xF1, 0x0F, 0x00, 0x01, 0x7F, + 0x03, 0xFF, 0x01, 0x80, 0x0F, 0x00, 0x01, 0x0E, 0x02, 0xFF, 0x01, 0xFE, + 0x01, 0x10, 0x0F, 0x00, 0x01, 0x06, 0x02, 0xFF, 0x01, 0xF7, 0x11, 0x00, + 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xE0, 0x10, 0x00, 0x01, 0x01, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0x70, 0x10, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xFE, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xF6, 0x11, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0xE0, 0x10, 0x00, 0x01, 0x02, 0x02, 0xFF, 0x01, 0x60, + 0x10, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xFE, 0x11, 0x00, 0x01, 0x3F, + 0x01, 0xFF, 0x01, 0xF6, 0x11, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0xD0, + 0x10, 0x00, 0x01, 0x05, 0x02, 0xFF, 0x01, 0x50, 0x10, 0x00, 0x01, 0x0C, + 0x01, 0xEE, 0x01, 0xEC, 0xD7, 0x00, + + /* 20 */ + 0xBB, 0x00, 0x01, 0x0B, 0x01, 0xEE, 0x01, 0xE2, 0x11, 0x00, 0x01, 0x0C, + 0x01, 0xFF, 0x01, 0xF2, 0x11, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF2, + 0x10, 0x00, 0x01, 0x01, 0x01, 0x2D, 0x01, 0xFF, 0x01, 0xF4, 0x01, 0x10, + 0x0D, 0x00, 0x01, 0x48, 0x01, 0xCE, 0x05, 0xFF, 0x01, 0xFD, 0x01, 0x96, + 0x01, 0x10, 0x09, 0x00, 0x01, 0x7D, 0x09, 0xFF, 0x01, 0xFA, 0x01, 0x20, + 0x07, 0x00, 0x01, 0x2D, 0x0B, 0xFF, 0x01, 0xF6, 0x06, 0x00, 0x01, 0x03, + 0x01, 0xEF, 0x02, 0xFF, 0x01, 0xFB, 0x01, 0x75, 0x01, 0x4D, 0x01, 0xFF, + 0x01, 0xF6, 0x01, 0x56, 0x01, 0x9D, 0x03, 0xFF, 0x01, 0x80, 0x05, 0x00, + 0x01, 0x1E, 0x02, 0xFF, 0x01, 0xE6, 0x02, 0x00, 0x01, 0x0C, 0x01, 0xFF, + 0x01, 0xF2, 0x02, 0x00, 0x01, 0x3B, 0x02, 0xFF, 0x01, 0xF5, 0x05, 0x00, + 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xFB, 0x01, 0x10, 0x02, 0x00, 0x01, 0x0C, + 0x01, 0xFF, 0x01, 0xF2, 0x03, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xFE, + 0x05, 0x00, 0x02, 0xFF, 0x01, 0xC0, 0x03, 0x00, 0x01, 0x0C, 0x01, 0xFF, + 0x01, 0xF2, 0x03, 0x00, 0x01, 0x07, 0x02, 0xFF, 0x01, 0x50, 0x03, 0x00, + 0x01, 0x05, 0x02, 0xFF, 0x01, 0x20, 0x03, 0x00, 0x01, 0x0C, 0x01, 0xFF, + 0x01, 0xF2, 0x04, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0xB0, 0x03, 0x00, + 0x01, 0x08, 0x01, 0xFF, 0x01, 0xFC, 0x04, 0x00, 0x01, 0x0C, 0x01, 0xFF, + 0x01, 0xF2, 0x04, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xE0, 0x03, 0x00, + 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF8, 0x04, 0x00, 0x01, 0x0C, 0x01, 0xFF, + 0x01, 0xF2, 0x04, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xF0, 0x03, 0x00, + 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF7, 0x04, 0x00, 0x01, 0x0C, 0x01, 0xFF, + 0x01, 0xF2, 0x04, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xF1, 0x03, 0x00, + 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF7, 0x04, 0x00, 0x01, 0x0C, 0x01, 0xFF, + 0x01, 0xF2, 0x04, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xF1, 0x03, 0x00, + 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF8, 0x04, 0x00, 0x01, 0x0C, 0x01, 0xFF, + 0x01, 0xF2, 0x04, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xF0, 0x03, 0x00, + 0x01, 0x08, 0x01, 0xFF, 0x01, 0xFC, 0x04, 0x00, 0x01, 0x0C, 0x01, 0xFF, + 0x01, 0xF2, 0x04, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xE0, 0x03, 0x00, + 0x01, 0x05, 0x02, 0xFF, 0x01, 0x30, 0x03, 0x00, 0x01, 0x0C, 0x01, 0xFF, + 0x01, 0xF2, 0x04, 0x00, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xB0, 0x04, 0x00, + 0x02, 0xFF, 0x01, 0xD1, 0x03, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF2, + 0x03, 0x00, 0x01, 0x08, 0x02, 0xFF, 0x01, 0x60, 0x04, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0xFC, 0x01, 0x10, 0x02, 0x00, 0x01, 0x0C, 0x01, 0xFF, + 0x01, 0xF2, 0x03, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xFE, 0x05, 0x00, + 0x01, 0x1E, 0x02, 0xFF, 0x01, 0xF7, 0x01, 0x10, 0x01, 0x00, 0x01, 0x0C, + 0x01, 0xFF, 0x01, 0xF2, 0x02, 0x00, 0x01, 0x4C, 0x02, 0xFF, 0x01, 0xF6, + 0x05, 0x00, 0x01, 0x04, 0x03, 0xFF, 0x01, 0xFB, 0x01, 0x86, 0x01, 0x5D, + 0x01, 0xFF, 0x01, 0xF6, 0x01, 0x67, 0x01, 0xAE, 0x03, 0xFF, 0x01, 0xA0, + 0x06, 0x00, 0x01, 0x4E, 0x0B, 0xFF, 0x01, 0xF8, 0x07, 0x00, 0x01, 0x01, + 0x01, 0x8E, 0x09, 0xFF, 0x01, 0xFB, 0x01, 0x30, 0x09, 0x00, 0x01, 0x48, + 0x01, 0xBE, 0x05, 0xFF, 0x01, 0xED, 0x01, 0xA6, 0x01, 0x10, 0x0D, 0x00, + 0x01, 0x1C, 0x01, 0xFF, 0x01, 0xF3, 0x01, 0x10, 0x10, 0x00, 0x01, 0x0C, + 0x01, 0xFF, 0x01, 0xF2, 0x11, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF2, + 0x11, 0x00, 0x01, 0x0B, 0x01, 0xEE, 0x01, 0xE2, 0xD2, 0x00, + + /* 21 */ + 0xB4, 0x00, 0x01, 0x0B, 0x01, 0xEE, 0x01, 0xEC, 0x07, 0x00, 0x01, 0x2E, + 0x01, 0xEE, 0x01, 0xE7, 0x07, 0x00, 0x01, 0x02, 0x02, 0xFF, 0x01, 0x80, + 0x06, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0xC0, 0x08, 0x00, 0x01, 0x6F, + 0x01, 0xFF, 0x01, 0xF3, 0x05, 0x00, 0x01, 0x06, 0x02, 0xFF, 0x01, 0x20, + 0x08, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xFD, 0x05, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0xF6, 0x09, 0x00, 0x01, 0x01, 0x01, 0xEF, 0x01, 0xFF, + 0x01, 0x80, 0x04, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0xB0, 0x0A, 0x00, + 0x01, 0x5F, 0x01, 0xFF, 0x01, 0xF3, 0x03, 0x00, 0x01, 0x06, 0x01, 0xFF, + 0x01, 0xFE, 0x01, 0x10, 0x0A, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xFD, + 0x03, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xF5, 0x0B, 0x00, 0x01, 0x01, + 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x80, 0x02, 0x00, 0x01, 0xBF, 0x01, 0xFF, + 0x01, 0x90, 0x0C, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0xF3, 0x01, 0x00, + 0x01, 0x06, 0x01, 0xFF, 0x01, 0xFD, 0x0D, 0x00, 0x01, 0x09, 0x01, 0xFF, + 0x01, 0xFD, 0x01, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xF3, 0x0E, 0x00, + 0x01, 0xDF, 0x01, 0xFF, 0x01, 0x80, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x70, + 0x0E, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xF9, 0x01, 0xFF, 0x01, 0xFC, + 0x0F, 0x00, 0x01, 0x08, 0x03, 0xFF, 0x01, 0xF2, 0x10, 0x00, 0x01, 0xCF, + 0x02, 0xFF, 0x01, 0x50, 0x10, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xFC, + 0x11, 0x00, 0x01, 0xAF, 0x02, 0xFF, 0x01, 0x30, 0x0F, 0x00, 0x01, 0x05, + 0x03, 0xFF, 0x01, 0xD0, 0x0F, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xFD, + 0x01, 0xFF, 0x01, 0xF9, 0x0F, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x91, + 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x50, 0x0D, 0x00, 0x01, 0x07, 0x01, 0xFF, + 0x01, 0xFD, 0x01, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xE1, 0x0D, 0x00, + 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xF3, 0x01, 0x00, 0x01, 0x0B, 0x01, 0xFF, + 0x01, 0xFB, 0x0D, 0x00, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0x80, 0x01, 0x00, + 0x01, 0x01, 0x02, 0xFF, 0x01, 0x60, 0x0B, 0x00, 0x01, 0x09, 0x01, 0xFF, + 0x01, 0xFD, 0x03, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xF2, 0x0B, 0x00, + 0x01, 0x4F, 0x01, 0xFF, 0x01, 0xF3, 0x03, 0x00, 0x01, 0x0B, 0x01, 0xFF, + 0x01, 0xFC, 0x0A, 0x00, 0x01, 0x01, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x80, + 0x03, 0x00, 0x01, 0x01, 0x02, 0xFF, 0x01, 0x80, 0x09, 0x00, 0x01, 0x0A, + 0x01, 0xFF, 0x01, 0xFD, 0x05, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xF4, + 0x09, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xF3, 0x05, 0x00, 0x01, 0x0B, + 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x10, 0x07, 0x00, 0x01, 0x02, 0x02, 0xFF, + 0x01, 0x80, 0x05, 0x00, 0x01, 0x01, 0x02, 0xFF, 0x01, 0xA0, 0x07, 0x00, + 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xFD, 0x07, 0x00, 0x01, 0x6F, 0x01, 0xFF, + 0x01, 0xF5, 0x07, 0x00, 0x01, 0x6E, 0x01, 0xEE, 0x01, 0xE3, 0x07, 0x00, + 0x01, 0x0B, 0x01, 0xEE, 0x01, 0xED, 0x01, 0x10, 0xCE, 0x00, + + /* 22 */ + 0xB5, 0x00, 0x01, 0x1E, 0x01, 0xEE, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9E, + 0x01, 0xEE, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xE6, 0x07, 0x66, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x51, + 0x01, 0x10, 0x06, 0x00, 0x01, 0x1F, 0x0C, 0xFF, 0x01, 0xF1, 0x06, 0x00, + 0x01, 0x1F, 0x0C, 0xFF, 0x01, 0xF1, 0x06, 0x00, 0x01, 0x1F, 0x0C, 0xFF, + 0x01, 0xF1, 0x11, 0x00, 0x01, 0x03, 0x01, 0xFF, 0x01, 0xF1, 0x11, 0x00, + 0x01, 0x03, 0x01, 0xFF, 0x01, 0xF1, 0x11, 0x00, 0x01, 0x03, 0x01, 0xFF, + 0x01, 0xF1, 0x11, 0x00, 0x01, 0x03, 0x01, 0xFF, 0x01, 0xF1, 0x11, 0x00, + 0x01, 0x03, 0x01, 0xFF, 0x01, 0xF1, 0x11, 0x00, 0x01, 0x01, 0x01, 0x77, + 0x01, 0x70, 0x55, 0x00, + + /* 23 */ + 0xB4, 0x00, 0x01, 0x04, 0x01, 0xEE, 0x01, 0xE8, 0x06, 0x00, 0x01, 0xBE, + 0x01, 0xEE, 0x01, 0x10, 0x08, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF8, + 0x06, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x10, 0x08, 0x00, 0x01, 0x05, + 0x01, 0xFF, 0x01, 0xF8, 0x06, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x10, + 0x08, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF8, 0x06, 0x00, 0x01, 0xCF, + 0x01, 0xFF, 0x01, 0x10, 0x08, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF8, + 0x06, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x10, 0x08, 0x00, 0x01, 0x05, + 0x01, 0xFF, 0x01, 0xF8, 0x06, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x10, + 0x08, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF8, 0x06, 0x00, 0x01, 0xCF, + 0x01, 0xFF, 0x01, 0x10, 0x08, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF8, + 0x06, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x10, 0x08, 0x00, 0x01, 0x05, + 0x01, 0xFF, 0x01, 0xF8, 0x06, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x10, + 0x08, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF8, 0x06, 0x00, 0x01, 0xCF, + 0x01, 0xFF, 0x01, 0x10, 0x08, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF8, + 0x06, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x10, 0x08, 0x00, 0x01, 0x05, + 0x01, 0xFF, 0x01, 0xF8, 0x06, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x10, + 0x08, 0x00, 0x01, 0x04, 0x01, 0xFF, 0x01, 0xF8, 0x06, 0x00, 0x01, 0xCF, + 0x01, 0xFF, 0x01, 0x10, 0x08, 0x00, 0x01, 0x03, 0x01, 0xFF, 0x01, 0xFA, + 0x06, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x10, 0x09, 0x00, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0x40, 0x05, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x10, + 0x09, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xFD, 0x01, 0xBA, 0x04, 0xAA, + 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x10, 0x09, 0x00, 0x01, 0x0B, 0x09, 0xFF, + 0x01, 0x10, 0x0A, 0x00, 0x01, 0x8F, 0x08, 0xFF, 0x01, 0x10, 0x0A, 0x00, + 0x01, 0x01, 0x01, 0x69, 0x05, 0xAA, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x10, + 0x11, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x10, 0x11, 0x00, 0x01, 0xCF, + 0x01, 0xFF, 0x01, 0x10, 0x11, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x10, + 0x11, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x10, 0x11, 0x00, 0x01, 0xCF, + 0x01, 0xFF, 0x01, 0x10, 0x11, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x10, + 0x11, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x10, 0x11, 0x00, 0x01, 0xCF, + 0x01, 0xFF, 0x01, 0x10, 0x11, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x10, + 0x11, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x10, 0x11, 0x00, 0x01, 0xBE, + 0x01, 0xEE, 0x01, 0x10, 0xD0, 0x00, + + /* 24 */ + 0xB5, 0x00, 0x01, 0x1E, 0x01, 0xEE, 0x01, 0xC0, 0x03, 0x00, 0x01, 0x1E, + 0x01, 0xEE, 0x01, 0xC0, 0x03, 0x00, 0x01, 0x1E, 0x01, 0xEE, 0x01, 0xC0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xE6, 0x03, 0x66, 0x01, 0x7F, + 0x01, 0xFF, 0x01, 0xE6, 0x03, 0x66, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x0D, 0xFF, 0x01, 0xD0, 0x05, 0x00, 0x01, 0x1F, + 0x0D, 0xFF, 0x01, 0xD0, 0x05, 0x00, 0x01, 0x1F, 0x0D, 0xFF, 0x01, 0xC0, + 0xCC, 0x00, + + /* 25 */ + 0xB5, 0x00, 0x01, 0x1E, 0x01, 0xEE, 0x01, 0xC0, 0x03, 0x00, 0x01, 0x1E, + 0x01, 0xEE, 0x01, 0xC0, 0x03, 0x00, 0x01, 0x1E, 0x01, 0xEE, 0x01, 0xC0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xE6, 0x03, 0x66, 0x01, 0x7F, + 0x01, 0xFF, 0x01, 0xE6, 0x03, 0x66, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xD1, + 0x01, 0x10, 0x04, 0x00, 0x01, 0x1F, 0x0E, 0xFF, 0x01, 0xFA, 0x04, 0x00, + 0x01, 0x1F, 0x0E, 0xFF, 0x01, 0xFA, 0x04, 0x00, 0x01, 0x1F, 0x0E, 0xFF, + 0x01, 0xFA, 0x12, 0x00, 0x01, 0xBF, 0x01, 0xFA, 0x12, 0x00, 0x01, 0xBF, + 0x01, 0xFA, 0x12, 0x00, 0x01, 0xBF, 0x01, 0xFA, 0x12, 0x00, 0x01, 0xBF, + 0x01, 0xFA, 0x12, 0x00, 0x01, 0xBF, 0x01, 0xFA, 0x12, 0x00, 0x01, 0x57, + 0x01, 0x74, 0x53, 0x00, + + /* 26 */ + 0xB5, 0x00, 0x01, 0x1E, 0x01, 0xEE, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xE8, + 0x03, 0x88, 0x01, 0x76, 0x01, 0x53, 0x0C, 0x00, 0x01, 0x1F, 0x07, 0xFF, + 0x01, 0xFB, 0x01, 0x50, 0x0A, 0x00, 0x01, 0x1F, 0x08, 0xFF, 0x01, 0xFD, + 0x01, 0x30, 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xFC, 0x03, 0xCC, + 0x01, 0xCD, 0x01, 0xEF, 0x02, 0xFF, 0x01, 0xF5, 0x09, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x04, 0x00, 0x01, 0x01, 0x01, 0x7E, 0x02, 0xFF, + 0x01, 0x20, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, + 0x01, 0x02, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xB0, 0x08, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xF1, + 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x0B, + 0x01, 0xFF, 0x01, 0xF6, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x06, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF8, 0x08, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x04, 0x01, 0xFF, 0x01, 0xF9, + 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x05, + 0x01, 0xFF, 0x01, 0xF8, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x06, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF6, 0x08, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x0E, 0x01, 0xFF, 0x01, 0xF2, + 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0xAF, + 0x01, 0xFF, 0x01, 0xC0, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x05, 0x00, 0x01, 0x1A, 0x02, 0xFF, 0x01, 0x40, 0x08, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD6, 0x04, 0x66, 0x01, 0x7B, 0x02, 0xFF, 0x01, 0xF9, + 0x09, 0x00, 0x01, 0x1F, 0x09, 0xFF, 0x01, 0xA0, 0x09, 0x00, 0x01, 0x1F, + 0x08, 0xFF, 0x01, 0xE6, 0x0A, 0x00, 0x01, 0x1E, 0x06, 0xEE, 0x01, 0xED, + 0x01, 0xA5, 0xD2, 0x00, + + /* 27 */ + 0xB5, 0x00, 0x01, 0x1E, 0x01, 0xEE, 0x01, 0xB0, 0x0A, 0x00, 0x01, 0x3E, + 0x01, 0xEE, 0x01, 0xA0, 0x04, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x0A, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x0A, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, + 0x04, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x0A, 0x00, 0x01, 0x3F, + 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x0A, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x0A, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, + 0x04, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x0A, 0x00, 0x01, 0x3F, + 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x0A, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x0A, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, + 0x04, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x0A, 0x00, 0x01, 0x3F, + 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x0A, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xE8, 0x03, 0x88, 0x01, 0x76, 0x01, 0x52, 0x05, 0x00, + 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, 0x01, 0x1F, 0x07, 0xFF, + 0x01, 0xFB, 0x01, 0x50, 0x03, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, + 0x04, 0x00, 0x01, 0x1F, 0x08, 0xFF, 0x01, 0xFD, 0x01, 0x30, 0x02, 0x00, + 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xFD, 0x04, 0xDD, 0x01, 0xEF, 0x02, 0xFF, 0x01, 0xF5, 0x02, 0x00, + 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x04, 0x00, 0x01, 0x01, 0x01, 0x7E, 0x02, 0xFF, 0x01, 0x20, + 0x01, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, 0x01, 0x02, 0x01, 0xDF, 0x01, 0xFF, + 0x01, 0xB0, 0x01, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x3F, 0x01, 0xFF, + 0x01, 0xF1, 0x01, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x0B, 0x01, 0xFF, + 0x01, 0xF6, 0x01, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x06, 0x01, 0xFF, + 0x01, 0xF8, 0x01, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x04, 0x01, 0xFF, + 0x01, 0xF9, 0x01, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x05, 0x01, 0xFF, + 0x01, 0xF8, 0x01, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x09, 0x01, 0xFF, + 0x01, 0xF6, 0x01, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x0E, 0x01, 0xFF, + 0x01, 0xF2, 0x01, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0xAF, 0x01, 0xFF, + 0x01, 0xC0, 0x01, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, 0x01, 0x1A, 0x02, 0xFF, + 0x01, 0x40, 0x01, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD6, 0x04, 0x66, 0x01, 0x7A, 0x02, 0xFF, + 0x01, 0xF9, 0x02, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, + 0x01, 0x1F, 0x09, 0xFF, 0x01, 0xA0, 0x02, 0x00, 0x01, 0x3F, 0x01, 0xFF, + 0x01, 0xA0, 0x04, 0x00, 0x01, 0x1F, 0x08, 0xFF, 0x01, 0xE6, 0x03, 0x00, + 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, 0x01, 0x1E, 0x06, 0xEE, + 0x01, 0xED, 0x01, 0xA5, 0x04, 0x00, 0x01, 0x3E, 0x01, 0xEE, 0x01, 0xA0, + 0xCB, 0x00, + + /* 28 */ + 0xB4, 0x00, 0x01, 0x2E, 0x06, 0xEE, 0x01, 0x50, 0x0C, 0x00, 0x01, 0x2F, + 0x06, 0xFF, 0x01, 0x50, 0x0C, 0x00, 0x01, 0x2F, 0x06, 0xFF, 0x01, 0x50, + 0x0C, 0x00, 0x01, 0x17, 0x04, 0x77, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x50, + 0x11, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x50, 0x11, 0x00, 0x01, 0x8F, + 0x01, 0xFF, 0x01, 0x50, 0x11, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x50, + 0x11, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x50, 0x11, 0x00, 0x01, 0x8F, + 0x01, 0xFF, 0x01, 0x50, 0x11, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x50, + 0x11, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x50, 0x11, 0x00, 0x01, 0x8F, + 0x01, 0xFF, 0x01, 0xB8, 0x03, 0x88, 0x01, 0x76, 0x01, 0x41, 0x0C, 0x00, + 0x01, 0x8F, 0x07, 0xFF, 0x01, 0xE8, 0x01, 0x20, 0x0A, 0x00, 0x01, 0x8F, + 0x08, 0xFF, 0x01, 0xF9, 0x0A, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xED, + 0x04, 0xDD, 0x03, 0xFF, 0x01, 0xC0, 0x09, 0x00, 0x01, 0x8F, 0x01, 0xFF, + 0x01, 0x50, 0x04, 0x00, 0x01, 0x03, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0xFB, + 0x09, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x50, 0x05, 0x00, 0x01, 0x07, + 0x02, 0xFF, 0x01, 0x40, 0x08, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x50, + 0x06, 0x00, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0xA0, 0x08, 0x00, 0x01, 0x8F, + 0x01, 0xFF, 0x01, 0x50, 0x06, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xE0, + 0x08, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x50, 0x06, 0x00, 0x01, 0x0E, + 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x50, + 0x06, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0x8F, + 0x01, 0xFF, 0x01, 0x50, 0x06, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF1, + 0x08, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x50, 0x06, 0x00, 0x01, 0x0F, + 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x50, + 0x06, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xB0, 0x08, 0x00, 0x01, 0x8F, + 0x01, 0xFF, 0x01, 0x50, 0x05, 0x00, 0x01, 0x02, 0x02, 0xFF, 0x01, 0x50, + 0x08, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x50, 0x05, 0x00, 0x01, 0x4E, + 0x01, 0xFF, 0x01, 0xFD, 0x09, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x96, + 0x04, 0x66, 0x01, 0x8D, 0x02, 0xFF, 0x01, 0xF3, 0x09, 0x00, 0x01, 0x8F, + 0x08, 0xFF, 0x01, 0xFE, 0x01, 0x40, 0x09, 0x00, 0x01, 0x8F, 0x08, 0xFF, + 0x01, 0xB2, 0x0A, 0x00, 0x01, 0x7E, 0x06, 0xEE, 0x01, 0xEC, 0x01, 0x83, + 0xCE, 0x00, + + /* 29 */ + 0xA5, 0x00, 0x01, 0x14, 0x01, 0x56, 0x01, 0x54, 0x01, 0x20, 0x0E, 0x00, + 0x01, 0x02, 0x01, 0x8E, 0x03, 0xFF, 0x01, 0xFE, 0x01, 0xA4, 0x0D, 0x00, + 0x01, 0x8F, 0x06, 0xFF, 0x01, 0xC2, 0x0B, 0x00, 0x01, 0x0C, 0x08, 0xFF, + 0x01, 0x50, 0x0A, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0xFD, 0x01, 0x73, + 0x01, 0x00, 0x01, 0x01, 0x01, 0x49, 0x02, 0xFF, 0x01, 0xF6, 0x09, 0x00, + 0x01, 0x05, 0x02, 0xFF, 0x01, 0x80, 0x04, 0x00, 0x01, 0x2C, 0x02, 0xFF, + 0x01, 0x30, 0x08, 0x00, 0x01, 0x0E, 0x01, 0xFF, 0x01, 0xF8, 0x06, 0x00, + 0x01, 0xAF, 0x01, 0xFF, 0x01, 0xD0, 0x08, 0x00, 0x01, 0x5F, 0x01, 0xFF, + 0x01, 0xD0, 0x06, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xF6, 0x08, 0x00, + 0x01, 0xAF, 0x01, 0xFF, 0x01, 0x60, 0x06, 0x00, 0x01, 0x03, 0x01, 0xFF, + 0x01, 0xFE, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x10, 0x07, 0x00, + 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x55, 0x01, 0x54, + 0x08, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0x90, 0x11, 0x00, 0x01, 0x0F, + 0x01, 0xFF, 0x01, 0xE0, 0x11, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF1, + 0x11, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF4, 0x0A, 0x00, 0x01, 0xBF, + 0x08, 0xFF, 0x01, 0xF5, 0x0A, 0x00, 0x01, 0xBF, 0x08, 0xFF, 0x01, 0xF6, + 0x0A, 0x00, 0x01, 0xBF, 0x08, 0xFF, 0x01, 0xF7, 0x0A, 0x00, 0x01, 0x35, + 0x06, 0x55, 0x01, 0x5A, 0x01, 0xFF, 0x01, 0xF6, 0x11, 0x00, 0x01, 0x08, + 0x01, 0xFF, 0x01, 0xF5, 0x11, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF3, + 0x06, 0x00, 0x01, 0x09, 0x01, 0xEE, 0x01, 0xE5, 0x08, 0x00, 0x01, 0x0E, + 0x01, 0xFF, 0x01, 0xF0, 0x06, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF8, + 0x08, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xD0, 0x06, 0x00, 0x01, 0x05, + 0x01, 0xFF, 0x01, 0xFD, 0x08, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x70, + 0x06, 0x00, 0x01, 0x01, 0x02, 0xFF, 0x01, 0x20, 0x07, 0x00, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0x20, 0x07, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x90, + 0x06, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xFB, 0x08, 0x00, 0x01, 0x5F, + 0x01, 0xFF, 0x01, 0xF3, 0x06, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0xF3, + 0x08, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x20, 0x04, 0x00, + 0x01, 0x06, 0x02, 0xFF, 0x01, 0xA0, 0x08, 0x00, 0x01, 0x03, 0x02, 0xFF, + 0x01, 0xE6, 0x03, 0x00, 0x01, 0x03, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0xFD, + 0x0A, 0x00, 0x01, 0x5F, 0x02, 0xFF, 0x01, 0xFB, 0x01, 0x87, 0x01, 0x8A, + 0x01, 0xEF, 0x02, 0xFF, 0x01, 0xD1, 0x0A, 0x00, 0x01, 0x04, 0x01, 0xEF, + 0x06, 0xFF, 0x01, 0xFB, 0x01, 0x10, 0x0B, 0x00, 0x01, 0x19, 0x05, 0xFF, + 0x01, 0xFC, 0x01, 0x50, 0x0D, 0x00, 0x01, 0x15, 0x01, 0x9B, 0x01, 0xDE, + 0x01, 0xDC, 0x01, 0xA7, 0x01, 0x20, 0xBE, 0x00, + + /* 30 */ + 0xAB, 0x00, 0x01, 0x13, 0x01, 0x56, 0x01, 0x54, 0x01, 0x20, 0x06, 0x00, + 0x01, 0x1E, 0x01, 0xEE, 0x01, 0xB0, 0x05, 0x00, 0x01, 0x02, 0x01, 0x8D, + 0x03, 0xFF, 0x01, 0xFE, 0x01, 0x93, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x04, 0x00, 0x01, 0x01, 0x01, 0x9F, 0x06, 0xFF, 0x01, 0xB2, + 0x04, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x04, 0x00, 0x01, 0x3E, + 0x08, 0xFF, 0x01, 0x50, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x03, 0x00, 0x01, 0x03, 0x02, 0xFF, 0x01, 0xFC, 0x01, 0x62, 0x01, 0x00, + 0x01, 0x02, 0x01, 0x6B, 0x02, 0xFF, 0x01, 0xF6, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x03, 0x00, 0x01, 0x1E, 0x01, 0xFF, 0x01, 0xFE, + 0x01, 0x40, 0x04, 0x00, 0x01, 0x3D, 0x02, 0xFF, 0x01, 0x30, 0x02, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x03, 0x00, 0x01, 0xBF, 0x01, 0xFF, + 0x01, 0xD1, 0x05, 0x00, 0x01, 0x01, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0xD0, + 0x02, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x02, 0x00, 0x01, 0x04, + 0x02, 0xFF, 0x01, 0x10, 0x06, 0x00, 0x01, 0x1E, 0x01, 0xFF, 0x01, 0xF7, + 0x02, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x02, 0x00, 0x01, 0x0C, + 0x01, 0xFF, 0x01, 0xF6, 0x07, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xFD, + 0x02, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x02, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xE0, 0x08, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x40, + 0x01, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x02, 0x00, 0x01, 0x7F, + 0x01, 0xFF, 0x01, 0x80, 0x08, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0x90, + 0x01, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x02, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x20, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x01, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x02, 0x00, 0x01, 0xEF, + 0x01, 0xFF, 0x09, 0x00, 0x01, 0x0E, 0x01, 0xFF, 0x01, 0xF0, 0x01, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x01, 0x00, 0x01, 0x01, 0x01, 0xFF, + 0x01, 0xFC, 0x09, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF3, 0x01, 0x00, + 0x01, 0x1F, 0x05, 0xFF, 0x01, 0xFB, 0x09, 0x00, 0x01, 0x09, 0x01, 0xFF, + 0x01, 0xF4, 0x01, 0x00, 0x01, 0x1F, 0x05, 0xFF, 0x01, 0xFA, 0x09, 0x00, + 0x01, 0x08, 0x01, 0xFF, 0x01, 0xF5, 0x01, 0x00, 0x01, 0x1F, 0x05, 0xFF, + 0x01, 0xF9, 0x09, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xF5, 0x01, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xE5, 0x01, 0x55, 0x01, 0x57, 0x01, 0xFF, + 0x01, 0xFA, 0x09, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xF4, 0x01, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x01, 0x00, 0x01, 0x01, 0x01, 0xFF, + 0x01, 0xFB, 0x09, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF3, 0x01, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x02, 0x00, 0x01, 0xFF, 0x01, 0xFD, + 0x09, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF1, 0x01, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x02, 0x00, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0x10, + 0x08, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xE0, 0x01, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x02, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x50, + 0x08, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x01, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x02, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0xB0, + 0x08, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x50, 0x01, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x02, 0x00, 0x01, 0x0E, 0x01, 0xFF, 0x01, 0xF2, + 0x07, 0x00, 0x01, 0x01, 0x01, 0xFF, 0x01, 0xFE, 0x02, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x02, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xFB, + 0x07, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF6, 0x02, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x02, 0x00, 0x01, 0x01, 0x02, 0xFF, 0x01, 0x70, + 0x06, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xD0, 0x02, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0xF7, + 0x05, 0x00, 0x01, 0x06, 0x02, 0xFF, 0x01, 0x30, 0x02, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x09, 0x02, 0xFF, 0x01, 0xC4, + 0x03, 0x00, 0x01, 0x03, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0xF6, 0x03, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x04, 0x00, 0x01, 0x9F, 0x02, 0xFF, + 0x01, 0xEA, 0x01, 0x87, 0x01, 0x8A, 0x01, 0xEF, 0x02, 0xFF, 0x01, 0x50, + 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x04, 0x00, 0x01, 0x06, + 0x07, 0xFF, 0x01, 0xD4, 0x04, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x19, 0x05, 0xFF, 0x01, 0xE7, 0x0E, 0x00, 0x01, 0x04, + 0x01, 0x9B, 0x01, 0xCE, 0x01, 0xDC, 0x01, 0x95, 0xB9, 0x00, + + /* 31 */ + 0xB7, 0x00, 0x01, 0x04, 0x01, 0x9C, 0x01, 0xDE, 0x06, 0xEE, 0x01, 0xC0, + 0x09, 0x00, 0x01, 0x04, 0x01, 0xDF, 0x08, 0xFF, 0x01, 0xD0, 0x09, 0x00, + 0x01, 0x6F, 0x09, 0xFF, 0x01, 0xD0, 0x08, 0x00, 0x01, 0x04, 0x02, 0xFF, + 0x01, 0xFB, 0x01, 0x87, 0x04, 0x77, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xD0, + 0x08, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xFC, 0x01, 0x20, 0x05, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xD0, 0x08, 0x00, 0x01, 0x4F, 0x01, 0xFF, + 0x01, 0xE1, 0x06, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xD0, 0x08, 0x00, + 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x60, 0x06, 0x00, 0x01, 0x0F, 0x01, 0xFF, + 0x01, 0xD0, 0x08, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x06, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xD0, 0x08, 0x00, 0x01, 0xCF, 0x01, 0xFF, + 0x01, 0x10, 0x06, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xD0, 0x08, 0x00, + 0x01, 0xAF, 0x01, 0xFF, 0x01, 0x20, 0x06, 0x00, 0x01, 0x0F, 0x01, 0xFF, + 0x01, 0xD0, 0x08, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0x50, 0x06, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xD0, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x06, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xD0, 0x08, 0x00, + 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xFA, 0x06, 0x00, 0x01, 0x0F, 0x01, 0xFF, + 0x01, 0xD0, 0x08, 0x00, 0x01, 0x02, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xE8, + 0x01, 0x54, 0x04, 0x44, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0xD0, 0x09, 0x00, + 0x01, 0x4F, 0x09, 0xFF, 0x01, 0xD0, 0x09, 0x00, 0x01, 0x03, 0x01, 0xDF, + 0x08, 0xFF, 0x01, 0xD0, 0x0A, 0x00, 0x01, 0x05, 0x01, 0xAE, 0x07, 0xFF, + 0x01, 0xD0, 0x0C, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x32, + 0x01, 0x22, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xD0, 0x0C, 0x00, 0x01, 0xAF, + 0x01, 0xFF, 0x01, 0xE2, 0x02, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xD0, + 0x0B, 0x00, 0x01, 0x08, 0x02, 0xFF, 0x01, 0x30, 0x02, 0x00, 0x01, 0x0F, + 0x01, 0xFF, 0x01, 0xD0, 0x0B, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xF5, + 0x03, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xD0, 0x0A, 0x00, 0x01, 0x04, + 0x02, 0xFF, 0x01, 0x60, 0x03, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xD0, + 0x0A, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xF7, 0x04, 0x00, 0x01, 0x0F, + 0x01, 0xFF, 0x01, 0xD0, 0x09, 0x00, 0x01, 0x02, 0x01, 0xEF, 0x01, 0xFF, + 0x01, 0x90, 0x04, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xD0, 0x09, 0x00, + 0x01, 0x1D, 0x01, 0xFF, 0x01, 0xFB, 0x05, 0x00, 0x01, 0x0F, 0x01, 0xFF, + 0x01, 0xD0, 0x09, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xD0, 0x08, 0x00, 0x01, 0x0B, 0x01, 0xFF, + 0x01, 0xFD, 0x01, 0x10, 0x05, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xD0, + 0x08, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0xE1, 0x06, 0x00, 0x01, 0x0F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x07, 0x02, 0xFF, 0x01, 0x20, + 0x06, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x5F, + 0x01, 0xFF, 0x01, 0xF4, 0x07, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xD0, + 0xCF, 0x00, + + /* 32 */ + 0xFF, 0x00, 0x45, 0x00, 0x01, 0x01, 0x01, 0x11, 0x10, 0x00, 0x01, 0x02, + 0x01, 0x8D, 0x02, 0xFF, 0x01, 0xFD, 0x01, 0x93, 0x0E, 0x00, 0x01, 0x9F, + 0x05, 0xFF, 0x01, 0xB0, 0x0C, 0x00, 0x01, 0x0B, 0x06, 0xFF, 0x01, 0xFB, + 0x0C, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0xF8, 0x01, 0x42, 0x01, 0x12, + 0x01, 0x4A, 0x02, 0xFF, 0x01, 0x50, 0x0B, 0x00, 0x01, 0xCF, 0x01, 0xFF, + 0x01, 0x30, 0x03, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0x90, 0x0B, 0x00, + 0x01, 0xFF, 0x01, 0xF9, 0x04, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xB0, + 0x0A, 0x00, 0x01, 0x02, 0x01, 0xDD, 0x01, 0xD5, 0x04, 0x00, 0x01, 0x0B, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0xC0, 0x0E, 0x00, 0x01, 0x02, + 0x01, 0x57, 0x01, 0xAD, 0x02, 0xFF, 0x01, 0xC0, 0x0C, 0x00, 0x01, 0x16, + 0x01, 0xAD, 0x05, 0xFF, 0x01, 0xC0, 0x0B, 0x00, 0x01, 0x09, 0x04, 0xFF, + 0x01, 0xFE, 0x01, 0x9D, 0x01, 0xFF, 0x01, 0xC0, 0x0B, 0x00, 0x01, 0xCF, + 0x02, 0xFF, 0x01, 0xC9, 0x01, 0x64, 0x01, 0x10, 0x01, 0x0B, 0x01, 0xFF, + 0x01, 0xC0, 0x0A, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x71, + 0x03, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xC0, 0x0A, 0x00, 0x01, 0x0E, + 0x01, 0xFF, 0x01, 0xF2, 0x04, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xC0, + 0x0A, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0x90, 0x04, 0x00, 0x01, 0x0B, + 0x01, 0xFF, 0x01, 0xC0, 0x0A, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x70, + 0x04, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x0A, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0x90, 0x04, 0x00, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0xC0, + 0x0A, 0x00, 0x01, 0x0E, 0x01, 0xFF, 0x01, 0xF2, 0x03, 0x00, 0x01, 0x0A, + 0x02, 0xFF, 0x01, 0xC0, 0x0A, 0x00, 0x01, 0x07, 0x02, 0xFF, 0x01, 0x83, + 0x01, 0x12, 0x01, 0x48, 0x01, 0xEF, 0x02, 0xFF, 0x01, 0xF4, 0x0B, 0x00, + 0x01, 0xCF, 0x05, 0xFF, 0x01, 0x76, 0x02, 0xFF, 0x01, 0xF6, 0x0A, 0x00, + 0x01, 0x1B, 0x04, 0xFF, 0x01, 0xC3, 0x01, 0x01, 0x01, 0xEF, 0x01, 0xFF, + 0x01, 0xF6, 0x0B, 0x00, 0x01, 0x39, 0x01, 0xCE, 0x01, 0xDC, 0x01, 0x94, + 0x02, 0x00, 0x01, 0x2A, 0x01, 0xDE, 0x01, 0xB3, 0xBD, 0x00, + + /* 33 */ + 0x93, 0x00, 0x01, 0x03, 0x01, 0xCC, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x0B, + 0x01, 0xFF, 0x01, 0xD0, 0x10, 0x00, 0x01, 0x26, 0x01, 0xDF, 0x01, 0xFF, + 0x01, 0xA0, 0x0D, 0x00, 0x01, 0x02, 0x01, 0x69, 0x01, 0xBE, 0x03, 0xFF, + 0x01, 0x40, 0x0C, 0x00, 0x01, 0x02, 0x01, 0xCF, 0x04, 0xFF, 0x01, 0xF6, + 0x0D, 0x00, 0x01, 0x3F, 0x03, 0xFF, 0x01, 0xFE, 0x01, 0xA6, 0x01, 0x10, + 0x0D, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xFC, 0x01, 0x85, 0x01, 0x10, + 0x0E, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF6, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0x40, 0x11, 0x00, 0x01, 0x7F, 0x01, 0xF7, 0x02, 0x00, + 0x01, 0x10, 0x0F, 0x00, 0x01, 0xDF, 0x01, 0xE0, 0x01, 0x3A, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0xFB, 0x01, 0x71, 0x0C, 0x00, 0x01, 0x01, 0x01, 0xFF, + 0x01, 0x99, 0x04, 0xFF, 0x01, 0xFE, 0x01, 0x60, 0x0B, 0x00, 0x01, 0x05, + 0x01, 0xFF, 0x01, 0xDF, 0x05, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0x08, + 0x02, 0xFF, 0x01, 0xFE, 0x01, 0x72, 0x01, 0x11, 0x01, 0x5B, 0x02, 0xFF, + 0x01, 0x50, 0x0A, 0x00, 0x01, 0x0B, 0x02, 0xFF, 0x01, 0xC1, 0x03, 0x00, + 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xE1, 0x0A, 0x00, 0x01, 0x0D, 0x01, 0xFF, + 0x01, 0xFE, 0x01, 0x10, 0x03, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF7, + 0x0A, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xF6, 0x04, 0x00, 0x01, 0x01, + 0x01, 0xFF, 0x01, 0xFD, 0x0A, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xF1, + 0x05, 0x00, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0x10, 0x09, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0x50, + 0x09, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x90, 0x05, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0x70, 0x09, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x80, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x80, 0x09, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0x70, 0x05, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0x90, + 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x80, 0x05, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0x80, 0x09, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0x90, + 0x05, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0x70, 0x09, 0x00, 0x01, 0x0E, + 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0x50, + 0x09, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF1, 0x05, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x10, 0x09, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF8, + 0x04, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xFD, 0x0B, 0x00, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0x20, 0x03, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF6, + 0x0B, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xE3, 0x03, 0x00, 0x01, 0xAF, + 0x01, 0xFF, 0x01, 0xD0, 0x0B, 0x00, 0x01, 0x0C, 0x02, 0xFF, 0x01, 0xA6, + 0x01, 0x45, 0x01, 0x8E, 0x02, 0xFF, 0x01, 0x30, 0x0B, 0x00, 0x01, 0x01, + 0x01, 0xCF, 0x05, 0xFF, 0x01, 0xF5, 0x0D, 0x00, 0x01, 0x08, 0x04, 0xFF, + 0x01, 0xFC, 0x01, 0x30, 0x0E, 0x00, 0x01, 0x16, 0x01, 0xAC, 0x01, 0xED, + 0x01, 0xC8, 0x01, 0x30, 0xC0, 0x00, + + /* 34 */ + 0xFF, 0x00, 0x56, 0x00, 0x01, 0x67, 0x04, 0x77, 0x01, 0x63, 0x0E, 0x00, + 0x01, 0xEF, 0x05, 0xFF, 0x01, 0xD5, 0x0D, 0x00, 0x01, 0xEF, 0x06, 0xFF, + 0x01, 0x60, 0x0C, 0x00, 0x01, 0xEF, 0x01, 0xFD, 0x02, 0x99, 0x01, 0xAC, + 0x02, 0xFF, 0x01, 0xF1, 0x0C, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x03, 0x00, + 0x01, 0x2D, 0x01, 0xFF, 0x01, 0xF5, 0x0C, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x03, 0x00, 0x01, 0x03, 0x01, 0xFF, 0x01, 0xF8, 0x0C, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x04, 0x00, 0x01, 0xFF, 0x01, 0xF7, 0x0C, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x03, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x0C, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x03, 0x00, 0x01, 0x2D, 0x01, 0xFF, 0x01, 0xE0, + 0x0C, 0x00, 0x01, 0xEF, 0x01, 0xFD, 0x02, 0x99, 0x01, 0xAC, 0x02, 0xFF, + 0x01, 0x40, 0x0C, 0x00, 0x01, 0xEF, 0x05, 0xFF, 0x01, 0xF3, 0x0D, 0x00, + 0x01, 0xEF, 0x05, 0xFF, 0x01, 0xFE, 0x01, 0x60, 0x0C, 0x00, 0x01, 0xEF, + 0x01, 0xFC, 0x03, 0x88, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0xF8, 0x0C, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x03, 0x00, 0x01, 0x02, 0x01, 0xDF, 0x01, 0xFF, + 0x01, 0x30, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x04, 0x00, 0x01, 0x5F, + 0x01, 0xFF, 0x01, 0x70, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x04, 0x00, + 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x90, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x04, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0x90, 0x0B, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x04, 0x00, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0x70, 0x0B, 0x00, + 0x01, 0xEF, 0x01, 0xFA, 0x03, 0x22, 0x01, 0x4B, 0x02, 0xFF, 0x01, 0x10, + 0x0B, 0x00, 0x01, 0xEF, 0x06, 0xFF, 0x01, 0xF8, 0x0C, 0x00, 0x01, 0xEF, + 0x06, 0xFF, 0x01, 0x80, 0x0C, 0x00, 0x01, 0xEF, 0x04, 0xFF, 0x01, 0xFD, + 0x01, 0x93, 0xD4, 0x00, + + /* 35 */ + 0xFF, 0x00, 0x56, 0x00, 0x06, 0x77, 0x01, 0x70, 0x0D, 0x00, 0x01, 0xEF, + 0x05, 0xFF, 0x01, 0xF0, 0x0D, 0x00, 0x01, 0xEF, 0x05, 0xFF, 0x01, 0xF0, + 0x0D, 0x00, 0x01, 0xEF, 0x01, 0xFD, 0x04, 0x99, 0x01, 0x90, 0x0D, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0xD9, 0x00, + + /* 36 */ + 0xFF, 0x00, 0x58, 0x00, 0x01, 0x57, 0x06, 0x77, 0x01, 0x20, 0x0C, 0x00, + 0x01, 0xCF, 0x06, 0xFF, 0x01, 0x50, 0x0C, 0x00, 0x01, 0xDF, 0x06, 0xFF, + 0x01, 0x50, 0x0C, 0x00, 0x01, 0xDF, 0x01, 0xFD, 0x03, 0x99, 0x01, 0xAF, + 0x01, 0xFF, 0x01, 0x50, 0x0C, 0x00, 0x01, 0xDF, 0x01, 0xFA, 0x03, 0x00, + 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x50, 0x0C, 0x00, 0x01, 0xEF, 0x01, 0xFA, + 0x03, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x50, 0x0C, 0x00, 0x01, 0xEF, + 0x01, 0xFA, 0x03, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x50, 0x0C, 0x00, + 0x01, 0xEF, 0x01, 0xFA, 0x03, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x50, + 0x0C, 0x00, 0x01, 0xFF, 0x01, 0xF9, 0x03, 0x00, 0x01, 0x2F, 0x01, 0xFF, + 0x01, 0x50, 0x0C, 0x00, 0x01, 0xFF, 0x01, 0xF9, 0x03, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0x50, 0x0B, 0x00, 0x01, 0x01, 0x01, 0xFF, 0x01, 0xF8, + 0x03, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x50, 0x0B, 0x00, 0x01, 0x03, + 0x01, 0xFF, 0x01, 0xF6, 0x03, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x50, + 0x0B, 0x00, 0x01, 0x04, 0x01, 0xFF, 0x01, 0xF5, 0x03, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0x50, 0x0B, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF3, + 0x03, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x50, 0x0B, 0x00, 0x01, 0x09, + 0x01, 0xFF, 0x01, 0xF0, 0x03, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x50, + 0x0B, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0x50, 0x0B, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, + 0x03, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x50, 0x0B, 0x00, 0x01, 0x6F, + 0x01, 0xFF, 0x01, 0x30, 0x03, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x50, + 0x0A, 0x00, 0x01, 0x01, 0x01, 0xEF, 0x01, 0xFD, 0x04, 0x22, 0x01, 0x4F, + 0x01, 0xFF, 0x01, 0x50, 0x09, 0x00, 0x01, 0x6A, 0x01, 0xAE, 0x08, 0xFF, + 0x01, 0xCA, 0x01, 0xA0, 0x08, 0x00, 0x01, 0x9F, 0x0A, 0xFF, 0x01, 0xF0, + 0x08, 0x00, 0x01, 0x9F, 0x0A, 0xFF, 0x01, 0xF0, 0x08, 0x00, 0x01, 0x9F, + 0x01, 0xF5, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF0, 0x08, 0x00, 0x01, 0x9F, + 0x01, 0xF5, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF0, 0x08, 0x00, 0x01, 0x9F, + 0x01, 0xF5, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF0, 0x08, 0x00, 0x01, 0x9F, + 0x01, 0xF5, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF0, 0x08, 0x00, 0x01, 0x8E, + 0x01, 0xE5, 0x08, 0x00, 0x01, 0xDE, 0x01, 0xE0, 0x6C, 0x00, + + /* 37 */ + 0xFF, 0x00, 0x58, 0x00, 0x01, 0x28, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xFC, + 0x01, 0x71, 0x0E, 0x00, 0x01, 0x09, 0x05, 0xFF, 0x01, 0x60, 0x0C, 0x00, + 0x01, 0x01, 0x01, 0xCF, 0x05, 0xFF, 0x01, 0xF8, 0x0C, 0x00, 0x01, 0x0B, + 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x73, 0x01, 0x11, 0x01, 0x5B, 0x02, 0xFF, + 0x01, 0x50, 0x0B, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xC1, 0x03, 0x00, + 0x01, 0x5F, 0x01, 0xFF, 0x01, 0xE0, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xFE, + 0x01, 0x10, 0x03, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF6, 0x0A, 0x00, + 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF5, 0x05, 0x00, 0x01, 0xDF, 0x01, 0xFC, + 0x0A, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xE0, 0x05, 0x00, 0x01, 0x7F, + 0x01, 0xFF, 0x0A, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xB0, 0x05, 0x00, + 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x0F, 0x01, 0xFF, + 0x01, 0xC6, 0x05, 0x66, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x60, 0x09, 0x00, + 0x01, 0x1F, 0x09, 0xFF, 0x01, 0x70, 0x09, 0x00, 0x01, 0x2F, 0x09, 0xFF, + 0x01, 0x80, 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xB6, 0x07, 0x66, + 0x01, 0x30, 0x09, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0x80, 0x11, 0x00, + 0x01, 0x0E, 0x01, 0xFF, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x0A, 0x01, 0xFF, + 0x01, 0xF0, 0x05, 0x00, 0x01, 0x48, 0x01, 0x88, 0x0A, 0x00, 0x01, 0x06, + 0x01, 0xFF, 0x01, 0xF6, 0x05, 0x00, 0x01, 0xEF, 0x01, 0xFC, 0x0B, 0x00, + 0x01, 0xEF, 0x01, 0xFE, 0x01, 0x10, 0x03, 0x00, 0x01, 0x07, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xD2, 0x03, 0x00, + 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xE1, 0x0B, 0x00, 0x01, 0x0C, 0x02, 0xFF, + 0x01, 0xA6, 0x01, 0x45, 0x01, 0x7C, 0x02, 0xFF, 0x01, 0x50, 0x0B, 0x00, + 0x01, 0x01, 0x01, 0xCF, 0x05, 0xFF, 0x01, 0xF6, 0x0D, 0x00, 0x01, 0x08, + 0x04, 0xFF, 0x01, 0xFD, 0x01, 0x40, 0x0E, 0x00, 0x01, 0x16, 0x01, 0xAD, + 0x01, 0xEE, 0x01, 0xC9, 0x01, 0x40, 0xC0, 0x00, + + /* 38 */ + 0xFF, 0x00, 0x55, 0x00, 0x01, 0x03, 0x02, 0x77, 0x03, 0x00, 0x01, 0x01, + 0x01, 0x77, 0x01, 0x71, 0x03, 0x00, 0x01, 0x06, 0x01, 0x77, 0x01, 0x73, + 0x06, 0x00, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0xB0, 0x02, 0x00, 0x01, 0x03, + 0x01, 0xFF, 0x01, 0xF4, 0x03, 0x00, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0xB0, + 0x06, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xFB, 0x02, 0x00, 0x01, 0x03, + 0x01, 0xFF, 0x01, 0xF4, 0x02, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xFB, + 0x08, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0xA0, 0x01, 0x00, 0x01, 0x03, + 0x01, 0xFF, 0x01, 0xF4, 0x02, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0xC0, + 0x08, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xFA, 0x01, 0x00, 0x01, 0x03, + 0x01, 0xFF, 0x01, 0xF4, 0x01, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xFC, + 0x0A, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0xA0, 0x01, 0x03, 0x01, 0xFF, + 0x01, 0xF4, 0x01, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0xC0, 0x0A, 0x00, + 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF9, 0x01, 0x03, 0x01, 0xFF, 0x01, 0xF4, + 0x01, 0x08, 0x01, 0xFF, 0x01, 0xFC, 0x0C, 0x00, 0x01, 0xBF, 0x01, 0xFF, + 0x01, 0x93, 0x01, 0xFF, 0x01, 0xF4, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xC1, + 0x0C, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xFB, 0x01, 0xFF, 0x01, 0xFB, + 0x01, 0xFF, 0x01, 0xFC, 0x01, 0x10, 0x0D, 0x00, 0x01, 0xCF, 0x04, 0xFF, + 0x01, 0xD1, 0x0E, 0x00, 0x01, 0x0D, 0x03, 0xFF, 0x01, 0xFD, 0x01, 0x10, + 0x0E, 0x00, 0x01, 0x5F, 0x04, 0xFF, 0x01, 0x60, 0x0D, 0x00, 0x01, 0x05, + 0x05, 0xFF, 0x01, 0xF6, 0x0D, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0xE5, + 0x01, 0xFF, 0x01, 0xF5, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0x60, 0x0B, 0x00, + 0x01, 0x06, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x23, 0x01, 0xFF, 0x01, 0xF4, + 0x01, 0x1D, 0x01, 0xFF, 0x01, 0xF7, 0x0B, 0x00, 0x01, 0x6F, 0x01, 0xFF, + 0x01, 0xE2, 0x01, 0x03, 0x01, 0xFF, 0x01, 0xF4, 0x01, 0x01, 0x01, 0xDF, + 0x01, 0xFF, 0x01, 0x70, 0x09, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xFD, + 0x01, 0x20, 0x01, 0x03, 0x01, 0xFF, 0x01, 0xF4, 0x01, 0x00, 0x01, 0x1D, + 0x01, 0xFF, 0x01, 0xF7, 0x09, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xD1, + 0x01, 0x00, 0x01, 0x03, 0x01, 0xFF, 0x01, 0xF4, 0x01, 0x00, 0x01, 0x01, + 0x01, 0xDF, 0x01, 0xFF, 0x01, 0x70, 0x07, 0x00, 0x01, 0x07, 0x01, 0xFF, + 0x01, 0xFD, 0x01, 0x10, 0x01, 0x00, 0x01, 0x03, 0x01, 0xFF, 0x01, 0xF4, + 0x02, 0x00, 0x01, 0x1C, 0x01, 0xFF, 0x01, 0xF8, 0x07, 0x00, 0x01, 0x7F, + 0x01, 0xFF, 0x01, 0xD1, 0x02, 0x00, 0x01, 0x03, 0x01, 0xFF, 0x01, 0xF4, + 0x02, 0x00, 0x01, 0x01, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x80, 0x05, 0x00, + 0x01, 0x07, 0x01, 0xFF, 0x01, 0xFD, 0x01, 0x10, 0x02, 0x00, 0x01, 0x03, + 0x01, 0xFF, 0x01, 0xF4, 0x03, 0x00, 0x01, 0x1C, 0x01, 0xFF, 0x01, 0xF8, + 0x05, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xD1, 0x03, 0x00, 0x01, 0x03, + 0x01, 0xFF, 0x01, 0xF4, 0x03, 0x00, 0x01, 0x01, 0x01, 0xCF, 0x01, 0xFF, + 0x01, 0x80, 0xCC, 0x00, + + /* 39 */ + 0xFF, 0x00, 0x45, 0x00, 0x01, 0x01, 0x11, 0x00, 0x01, 0x17, 0x01, 0xCF, + 0x01, 0xFF, 0x01, 0xFE, 0x01, 0xA5, 0x0E, 0x00, 0x01, 0x06, 0x05, 0xFF, + 0x01, 0xD3, 0x0D, 0x00, 0x01, 0x5F, 0x06, 0xFF, 0x01, 0x30, 0x0C, 0x00, + 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xC5, 0x01, 0x21, 0x01, 0x26, 0x01, 0xCF, + 0x01, 0xFF, 0x01, 0xD0, 0x0B, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xFB, + 0x03, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF5, 0x0B, 0x00, 0x01, 0x08, + 0x01, 0xFF, 0x01, 0xF3, 0x03, 0x00, 0x01, 0x01, 0x01, 0xFF, 0x01, 0xF9, + 0x0B, 0x00, 0x01, 0x05, 0x01, 0x88, 0x01, 0x80, 0x04, 0x00, 0x01, 0xFF, + 0x01, 0xFA, 0x11, 0x00, 0x01, 0x03, 0x01, 0xFF, 0x01, 0xF9, 0x11, 0x00, + 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF4, 0x0E, 0x00, 0x01, 0x01, 0x01, 0x33, + 0x01, 0x36, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xB0, 0x0E, 0x00, 0x01, 0x09, + 0x03, 0xFF, 0x01, 0xFA, 0x01, 0x10, 0x0E, 0x00, 0x01, 0x09, 0x03, 0xFF, + 0x01, 0xFA, 0x01, 0x10, 0x0E, 0x00, 0x01, 0x08, 0x01, 0xEE, 0x03, 0xFF, + 0x01, 0xE3, 0x10, 0x00, 0x01, 0x01, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xFD, + 0x11, 0x00, 0x01, 0x02, 0x02, 0xFF, 0x01, 0x40, 0x0A, 0x00, 0x01, 0x06, + 0x01, 0x66, 0x01, 0x30, 0x04, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0x70, + 0x0A, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xB0, 0x04, 0x00, 0x01, 0x4F, + 0x01, 0xFF, 0x01, 0x80, 0x0A, 0x00, 0x01, 0x0E, 0x01, 0xFF, 0x01, 0xF1, + 0x04, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0x60, 0x0A, 0x00, 0x01, 0x0A, + 0x01, 0xFF, 0x01, 0xFB, 0x03, 0x00, 0x01, 0x04, 0x02, 0xFF, 0x01, 0x10, + 0x0A, 0x00, 0x01, 0x02, 0x02, 0xFF, 0x01, 0xE8, 0x01, 0x53, 0x01, 0x46, + 0x01, 0xBF, 0x01, 0xFF, 0x01, 0xF8, 0x0C, 0x00, 0x01, 0x7F, 0x06, 0xFF, + 0x01, 0xB0, 0x0C, 0x00, 0x01, 0x06, 0x01, 0xEF, 0x04, 0xFF, 0x01, 0xF7, + 0x0E, 0x00, 0x01, 0x05, 0x01, 0x9C, 0x01, 0xDE, 0x01, 0xDC, 0x01, 0x95, + 0xC1, 0x00, + + /* 40 */ + 0xFF, 0x00, 0x56, 0x00, 0x01, 0x67, 0x01, 0x74, 0x04, 0x00, 0x01, 0x05, + 0x01, 0x77, 0x01, 0x76, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x04, 0x00, + 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x04, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x03, 0x00, 0x01, 0x05, 0x02, 0xFF, 0x01, 0xFE, 0x0B, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x03, 0x00, 0x01, 0x0E, 0x02, 0xFF, 0x01, 0xFE, + 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x03, 0x00, 0x01, 0x7F, 0x01, 0xFF, + 0x01, 0xCF, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, + 0x01, 0x01, 0x01, 0xFF, 0x01, 0xF9, 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xE1, + 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, + 0x01, 0x3F, 0x01, 0xFF, 0x01, 0x70, 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0xCF, 0x01, 0xFD, 0x01, 0x00, + 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x00, + 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF4, 0x01, 0x00, 0x01, 0x9F, 0x01, 0xFE, + 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x00, 0x01, 0x0E, 0x01, 0xFF, + 0x01, 0xB0, 0x01, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x01, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x20, 0x01, 0x00, + 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x02, + 0x01, 0xFF, 0x01, 0xF8, 0x02, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xE0, 0x02, 0x00, + 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x4F, + 0x01, 0xFF, 0x01, 0x60, 0x02, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x01, 0xDF, 0x01, 0xFC, 0x03, 0x00, 0x01, 0x9F, + 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x02, 0xFF, 0x01, 0xF3, 0x03, 0x00, + 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x02, 0xFF, 0x01, 0xA0, + 0x03, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x02, 0xFF, + 0x01, 0x10, 0x03, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0xF7, 0x04, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, + 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xE0, 0x04, 0x00, 0x01, 0x9F, 0x01, 0xFE, + 0xD2, 0x00, + + /* 41 */ + 0xCA, 0x00, 0x01, 0x2A, 0x01, 0xA2, 0x03, 0x00, 0x01, 0x3A, 0x01, 0xA2, + 0x0D, 0x00, 0x01, 0x2F, 0x01, 0xF9, 0x03, 0x00, 0x01, 0xAF, 0x01, 0xF1, + 0x0D, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0x82, 0x01, 0x00, 0x01, 0x29, + 0x01, 0xFF, 0x01, 0xC0, 0x0D, 0x00, 0x01, 0x05, 0x05, 0xFF, 0x01, 0x30, + 0x0E, 0x00, 0x01, 0x7F, 0x03, 0xFF, 0x01, 0xF6, 0x0F, 0x00, 0x01, 0x02, + 0x01, 0x8B, 0x01, 0xDD, 0x01, 0xB8, 0x01, 0x10, 0x21, 0x00, 0x01, 0x67, + 0x01, 0x74, 0x04, 0x00, 0x01, 0x05, 0x01, 0x77, 0x01, 0x76, 0x0B, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x04, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xFE, + 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x04, 0x00, 0x01, 0xCF, 0x01, 0xFF, + 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x03, 0x00, 0x01, 0x05, + 0x02, 0xFF, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x03, 0x00, + 0x01, 0x0E, 0x02, 0xFF, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x03, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xCF, 0x01, 0xFE, 0x0B, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x01, 0x01, 0xFF, 0x01, 0xF9, + 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, + 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF1, 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0x70, + 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, + 0x01, 0xCF, 0x01, 0xFD, 0x01, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF4, + 0x01, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x01, 0x00, 0x01, 0x0E, 0x01, 0xFF, 0x01, 0xB0, 0x01, 0x00, 0x01, 0x9F, + 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x00, 0x01, 0x8F, + 0x01, 0xFF, 0x01, 0x20, 0x01, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF8, 0x02, 0x00, + 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x0B, + 0x01, 0xFF, 0x01, 0xE0, 0x02, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x60, 0x02, 0x00, + 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x01, 0xDF, + 0x01, 0xFC, 0x03, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, + 0x02, 0xFF, 0x01, 0xF3, 0x03, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, + 0x01, 0xEF, 0x02, 0xFF, 0x01, 0xA0, 0x03, 0x00, 0x01, 0x9F, 0x01, 0xFE, + 0x0B, 0x00, 0x01, 0xEF, 0x02, 0xFF, 0x01, 0x10, 0x03, 0x00, 0x01, 0x9F, + 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xF7, 0x04, 0x00, + 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xE0, + 0x04, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0xD2, 0x00, + + /* 42 */ + 0xFF, 0x00, 0x56, 0x00, 0x01, 0x67, 0x01, 0x74, 0x04, 0x00, 0x01, 0x67, + 0x01, 0x77, 0x01, 0x10, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF8, 0x03, 0x00, + 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF6, 0x0C, 0x00, 0x01, 0xEF, 0x01, 0xF8, + 0x03, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x60, 0x0C, 0x00, 0x01, 0xEF, + 0x01, 0xF8, 0x02, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF5, 0x0D, 0x00, + 0x01, 0xEF, 0x01, 0xF8, 0x02, 0x00, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0x50, + 0x0D, 0x00, 0x01, 0xEF, 0x01, 0xF8, 0x01, 0x00, 0x01, 0x0A, 0x01, 0xFF, + 0x01, 0xF5, 0x0E, 0x00, 0x01, 0xEF, 0x01, 0xF8, 0x01, 0x00, 0x01, 0xAF, + 0x01, 0xFF, 0x01, 0x50, 0x0E, 0x00, 0x01, 0xEF, 0x01, 0xF8, 0x01, 0x0A, + 0x01, 0xFF, 0x01, 0xF4, 0x0F, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x40, 0x0F, 0x00, 0x01, 0xEF, 0x02, 0xFF, 0x01, 0xF4, + 0x10, 0x00, 0x01, 0xEF, 0x02, 0xFF, 0x01, 0x40, 0x10, 0x00, 0x01, 0xEF, + 0x02, 0xFF, 0x01, 0xA0, 0x10, 0x00, 0x01, 0xEF, 0x02, 0xFF, 0x01, 0xFA, + 0x10, 0x00, 0x01, 0xEF, 0x01, 0xF8, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0xB0, + 0x0F, 0x00, 0x01, 0xEF, 0x01, 0xF8, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xFB, + 0x0F, 0x00, 0x01, 0xEF, 0x01, 0xF8, 0x01, 0x00, 0x01, 0xAF, 0x01, 0xFF, + 0x01, 0xB0, 0x0E, 0x00, 0x01, 0xEF, 0x01, 0xF8, 0x01, 0x00, 0x01, 0x0A, + 0x01, 0xFF, 0x01, 0xFB, 0x0E, 0x00, 0x01, 0xEF, 0x01, 0xF8, 0x02, 0x00, + 0x01, 0x9F, 0x01, 0xFF, 0x01, 0xC0, 0x0D, 0x00, 0x01, 0xEF, 0x01, 0xF8, + 0x02, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xFC, 0x0D, 0x00, 0x01, 0xEF, + 0x01, 0xF8, 0x03, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0xC0, 0x0C, 0x00, + 0x01, 0xEF, 0x01, 0xF8, 0x03, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xFC, + 0x0C, 0x00, 0x01, 0xEF, 0x01, 0xF8, 0x04, 0x00, 0x01, 0x9F, 0x01, 0xFF, + 0x01, 0xC1, 0xD2, 0x00, + + /* 43 */ + 0xFF, 0x00, 0x56, 0x00, 0x01, 0x02, 0x06, 0x77, 0x01, 0x75, 0x0C, 0x00, + 0x01, 0x05, 0x06, 0xFF, 0x01, 0xFC, 0x0C, 0x00, 0x01, 0x05, 0x06, 0xFF, + 0x01, 0xFC, 0x0C, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xFB, 0x03, 0xAA, + 0x01, 0xEF, 0x01, 0xFC, 0x0C, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF2, + 0x03, 0x00, 0x01, 0xBF, 0x01, 0xFC, 0x0C, 0x00, 0x01, 0x05, 0x01, 0xFF, + 0x01, 0xF2, 0x03, 0x00, 0x01, 0xBF, 0x01, 0xFC, 0x0C, 0x00, 0x01, 0x05, + 0x01, 0xFF, 0x01, 0xF2, 0x03, 0x00, 0x01, 0xBF, 0x01, 0xFC, 0x0C, 0x00, + 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF2, 0x03, 0x00, 0x01, 0xBF, 0x01, 0xFC, + 0x0C, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x03, 0x00, 0x01, 0xBF, + 0x01, 0xFC, 0x0C, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x03, 0x00, + 0x01, 0xBF, 0x01, 0xFC, 0x0C, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF0, + 0x03, 0x00, 0x01, 0xBF, 0x01, 0xFC, 0x0C, 0x00, 0x01, 0x08, 0x01, 0xFF, + 0x01, 0xF0, 0x03, 0x00, 0x01, 0xBF, 0x01, 0xFC, 0x0C, 0x00, 0x01, 0x09, + 0x01, 0xFF, 0x01, 0xF0, 0x03, 0x00, 0x01, 0xBF, 0x01, 0xFC, 0x0C, 0x00, + 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0xBF, 0x01, 0xFC, + 0x0C, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xB0, 0x03, 0x00, 0x01, 0xBF, + 0x01, 0xFC, 0x0C, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0x80, 0x03, 0x00, + 0x01, 0xBF, 0x01, 0xFC, 0x0C, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0x40, + 0x03, 0x00, 0x01, 0xBF, 0x01, 0xFC, 0x0C, 0x00, 0x01, 0x9F, 0x01, 0xFF, + 0x01, 0x10, 0x03, 0x00, 0x01, 0xBF, 0x01, 0xFC, 0x0B, 0x00, 0x01, 0x04, + 0x01, 0xFF, 0x01, 0xF9, 0x04, 0x00, 0x01, 0xBF, 0x01, 0xFC, 0x0B, 0x00, + 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xF2, 0x04, 0x00, 0x01, 0xBF, 0x01, 0xFC, + 0x0B, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x70, 0x04, 0x00, 0x01, 0xBF, + 0x01, 0xFC, 0x0B, 0x00, 0x01, 0x9F, 0x01, 0xF6, 0x05, 0x00, 0x01, 0xBF, + 0x01, 0xFC, 0x0B, 0x00, 0x01, 0x34, 0xC7, 0x00, + + /* 44 */ + 0xFF, 0x00, 0x56, 0x00, 0x01, 0x67, 0x01, 0x77, 0x01, 0x30, 0x04, 0x00, + 0x01, 0x03, 0x02, 0x77, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xD0, + 0x04, 0x00, 0x01, 0x0B, 0x02, 0xFF, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFF, + 0x01, 0xF3, 0x04, 0x00, 0x01, 0x2F, 0x02, 0xFF, 0x0A, 0x00, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0xFA, 0x04, 0x00, 0x01, 0x9F, 0x02, 0xFF, 0x0A, 0x00, + 0x01, 0xEF, 0x02, 0xFF, 0x01, 0x10, 0x03, 0x00, 0x03, 0xFF, 0x0A, 0x00, + 0x01, 0xEF, 0x02, 0xFF, 0x01, 0x80, 0x02, 0x00, 0x01, 0x06, 0x03, 0xFF, + 0x0A, 0x00, 0x01, 0xEF, 0x02, 0xFF, 0x01, 0xE0, 0x02, 0x00, 0x01, 0x0D, + 0x03, 0xFF, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFD, 0x01, 0xFF, 0x01, 0xF5, + 0x02, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0xDF, 0x01, 0xFF, 0x0A, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x01, 0xDF, 0x01, 0xFC, 0x02, 0x00, 0x01, 0xAF, + 0x01, 0xFE, 0x01, 0x8F, 0x01, 0xFF, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x01, 0x7F, 0x01, 0xFF, 0x01, 0x30, 0x01, 0x01, 0x01, 0xFF, 0x01, 0xF8, + 0x01, 0x7F, 0x01, 0xFF, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0x90, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xF2, 0x01, 0x7F, + 0x01, 0xFF, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x0A, 0x01, 0xFF, + 0x01, 0xF1, 0x01, 0x0E, 0x01, 0xFF, 0x01, 0xB0, 0x01, 0x7F, 0x01, 0xFF, + 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x03, 0x01, 0xFF, 0x01, 0xF7, + 0x01, 0x5F, 0x01, 0xFF, 0x01, 0x40, 0x01, 0x7F, 0x01, 0xFF, 0x0A, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x00, 0x01, 0xCF, 0x01, 0xFD, 0x01, 0xCF, + 0x01, 0xFE, 0x01, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x0A, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x01, 0x00, 0x01, 0x6F, 0x02, 0xFF, 0x01, 0xF7, 0x01, 0x00, + 0x01, 0x7F, 0x01, 0xFF, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x00, + 0x01, 0x0F, 0x02, 0xFF, 0x01, 0xF1, 0x01, 0x00, 0x01, 0x7F, 0x01, 0xFF, + 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x00, 0x01, 0x09, 0x02, 0xFF, + 0x01, 0xA0, 0x01, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x0A, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x01, 0x00, 0x01, 0x02, 0x02, 0xFF, 0x01, 0x40, 0x01, 0x00, + 0x01, 0x7F, 0x01, 0xFF, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, + 0x01, 0xCF, 0x01, 0xFD, 0x02, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x0A, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x5F, 0x01, 0xF7, 0x02, 0x00, + 0x01, 0x7F, 0x01, 0xFF, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, + 0x01, 0x06, 0x01, 0x61, 0x02, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x0A, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x06, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0xD1, 0x00, + + /* 45 */ + 0xFF, 0x00, 0x56, 0x00, 0x01, 0x67, 0x01, 0x74, 0x05, 0x00, 0x01, 0x77, + 0x01, 0x73, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xFD, 0x05, 0xAA, 0x01, 0xFF, + 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x07, 0xFF, 0x01, 0xF8, 0x0B, 0x00, + 0x01, 0xEF, 0x07, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xFC, + 0x05, 0x77, 0x01, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x05, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x05, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x05, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x05, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x05, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x05, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x05, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x05, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x05, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0xD2, 0x00, + + /* 46 */ + 0xFF, 0x00, 0x58, 0x00, 0x01, 0x39, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xEB, + 0x01, 0x60, 0x0E, 0x00, 0x01, 0x1B, 0x04, 0xFF, 0x01, 0xFE, 0x01, 0x50, + 0x0C, 0x00, 0x01, 0x02, 0x01, 0xEF, 0x05, 0xFF, 0x01, 0xF8, 0x0C, 0x00, + 0x01, 0x0D, 0x02, 0xFF, 0x01, 0x83, 0x01, 0x12, 0x01, 0x5C, 0x02, 0xFF, + 0x01, 0x50, 0x0B, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0xD1, 0x03, 0x00, + 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xE1, 0x0A, 0x00, 0x01, 0x01, 0x01, 0xFF, + 0x01, 0xFE, 0x01, 0x10, 0x03, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF7, + 0x0A, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF7, 0x04, 0x00, 0x01, 0x01, + 0x01, 0xFF, 0x01, 0xFD, 0x0A, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF1, + 0x05, 0x00, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0x10, 0x09, 0x00, 0x01, 0x0E, + 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0x50, + 0x09, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0x90, 0x05, 0x00, 0x01, 0x3F, + 0x01, 0xFF, 0x01, 0x70, 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x80, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x80, 0x09, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0x70, 0x05, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0x90, + 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x80, 0x05, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0x80, 0x09, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0x90, + 0x05, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x70, 0x09, 0x00, 0x01, 0x0E, + 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0x50, + 0x09, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF1, 0x05, 0x00, 0x01, 0xAF, + 0x01, 0xFF, 0x01, 0x10, 0x09, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF8, + 0x04, 0x00, 0x01, 0x01, 0x01, 0xFF, 0x01, 0xFD, 0x0B, 0x00, 0x02, 0xFF, + 0x01, 0x20, 0x03, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF6, 0x0B, 0x00, + 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xE3, 0x03, 0x00, 0x01, 0xAF, 0x01, 0xFF, + 0x01, 0xD0, 0x0B, 0x00, 0x01, 0x0C, 0x02, 0xFF, 0x01, 0xA5, 0x01, 0x34, + 0x01, 0x7E, 0x02, 0xFF, 0x01, 0x30, 0x0B, 0x00, 0x01, 0x01, 0x01, 0xCF, + 0x05, 0xFF, 0x01, 0xF5, 0x0D, 0x00, 0x01, 0x19, 0x04, 0xFF, 0x01, 0xFC, + 0x01, 0x30, 0x0E, 0x00, 0x01, 0x27, 0x01, 0xBD, 0x01, 0xEE, 0x01, 0xC9, + 0x01, 0x40, 0xC0, 0x00, + + /* 47 */ + 0xFF, 0x00, 0x56, 0x00, 0x01, 0x67, 0x07, 0x77, 0x01, 0x73, 0x0B, 0x00, + 0x01, 0xEF, 0x07, 0xFF, 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x07, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xFD, 0x05, 0xAA, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0xD2, 0x00, + + /* 48 */ + 0xFF, 0x00, 0x56, 0x00, 0x01, 0x67, 0x01, 0x72, 0x01, 0x00, 0x01, 0x29, + 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xC7, 0x01, 0x10, 0x0C, 0x00, 0x01, 0xEF, + 0x01, 0xF4, 0x01, 0x08, 0x04, 0xFF, 0x01, 0xF6, 0x0C, 0x00, 0x01, 0xEF, + 0x01, 0xF4, 0x01, 0xAF, 0x05, 0xFF, 0x01, 0x80, 0x0B, 0x00, 0x01, 0xEF, + 0x01, 0xFC, 0x01, 0xFF, 0x01, 0xF9, 0x01, 0x42, 0x01, 0x37, 0x01, 0xDF, + 0x01, 0xFF, 0x01, 0xF6, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xFE, + 0x01, 0x30, 0x02, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x10, + 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xF3, 0x04, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x70, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x90, + 0x04, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x0A, 0x00, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0x30, 0x04, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF2, + 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFE, 0x05, 0x00, 0x01, 0x05, 0x01, 0xFF, + 0x01, 0xF5, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFB, 0x05, 0x00, 0x01, 0x02, + 0x01, 0xFF, 0x01, 0xF7, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFA, 0x06, 0x00, + 0x01, 0xFF, 0x01, 0xF8, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x06, 0x00, + 0x01, 0xFF, 0x01, 0xF9, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFA, 0x06, 0x00, + 0x01, 0xFF, 0x01, 0xF9, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFB, 0x05, 0x00, + 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF8, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFE, + 0x05, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF5, 0x0A, 0x00, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0x30, 0x04, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF2, + 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0xD0, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xF4, + 0x04, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x70, 0x0A, 0x00, 0x01, 0xEF, + 0x02, 0xFF, 0x01, 0x40, 0x02, 0x00, 0x01, 0x1B, 0x01, 0xFF, 0x01, 0xFE, + 0x01, 0x10, 0x0A, 0x00, 0x01, 0xEF, 0x02, 0xFF, 0x01, 0xFB, 0x01, 0x64, + 0x01, 0x58, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xF5, 0x0B, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x01, 0xAF, 0x05, 0xFF, 0x01, 0x70, 0x0B, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x01, 0x08, 0x04, 0xFF, 0x01, 0xE4, 0x0C, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x01, 0x00, 0x01, 0x28, 0x01, 0xCE, 0x01, 0xED, 0x01, 0xA5, + 0x0D, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xDE, 0x01, 0xE8, + 0x25, 0x00, + + /* 49 */ + 0xFF, 0x00, 0x58, 0x00, 0x01, 0x38, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xEA, + 0x01, 0x50, 0x0E, 0x00, 0x01, 0x19, 0x04, 0xFF, 0x01, 0xFD, 0x01, 0x20, + 0x0C, 0x00, 0x01, 0x01, 0x01, 0xCF, 0x05, 0xFF, 0x01, 0xF2, 0x0C, 0x00, + 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x73, 0x01, 0x12, 0x01, 0x6D, + 0x01, 0xFF, 0x01, 0xFD, 0x0C, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xC1, + 0x03, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x60, 0x0B, 0x00, 0x01, 0xEF, + 0x01, 0xFE, 0x01, 0x10, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xB0, + 0x0A, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF6, 0x04, 0x00, 0x01, 0x0A, + 0x01, 0xFF, 0x01, 0xF0, 0x0A, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF1, + 0x04, 0x00, 0x01, 0x04, 0x01, 0xBB, 0x01, 0xB1, 0x0A, 0x00, 0x01, 0x0D, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0x90, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x80, 0x11, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0x70, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x80, + 0x11, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0x90, 0x11, 0x00, 0x01, 0x0E, + 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, 0x01, 0x55, 0x01, 0x52, 0x0A, 0x00, + 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF1, 0x04, 0x00, 0x01, 0x04, 0x01, 0xFF, + 0x01, 0xF4, 0x0A, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF6, 0x04, 0x00, + 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF1, 0x0B, 0x00, 0x01, 0xFF, 0x01, 0xFE, + 0x01, 0x10, 0x03, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xC0, 0x0B, 0x00, + 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xD2, 0x02, 0x00, 0x01, 0x01, 0x01, 0xCF, + 0x01, 0xFF, 0x01, 0x60, 0x0B, 0x00, 0x01, 0x0C, 0x02, 0xFF, 0x01, 0x94, + 0x01, 0x34, 0x01, 0x8E, 0x01, 0xFF, 0x01, 0xFC, 0x0C, 0x00, 0x01, 0x01, + 0x01, 0xDF, 0x05, 0xFF, 0x01, 0xE1, 0x0D, 0x00, 0x01, 0x19, 0x04, 0xFF, + 0x01, 0xFA, 0x01, 0x10, 0x0E, 0x00, 0x01, 0x27, 0x01, 0xCD, 0x01, 0xEE, + 0x01, 0xC8, 0x01, 0x20, 0xC0, 0x00, + + /* 50 */ + 0xFF, 0x00, 0x55, 0x00, 0x01, 0x47, 0x06, 0x77, 0x01, 0x76, 0x0C, 0x00, + 0x01, 0x9F, 0x06, 0xFF, 0x01, 0xFE, 0x0C, 0x00, 0x01, 0x9F, 0x06, 0xFF, + 0x01, 0xFE, 0x0C, 0x00, 0x01, 0x6A, 0x02, 0xAA, 0x01, 0xDF, 0x01, 0xFF, + 0x02, 0xAA, 0x01, 0xA9, 0x0F, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x12, 0x00, + 0x01, 0x9F, 0x01, 0xFE, 0x12, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x12, 0x00, + 0x01, 0x9F, 0x01, 0xFE, 0x12, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x12, 0x00, + 0x01, 0x9F, 0x01, 0xFE, 0x12, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x12, 0x00, + 0x01, 0x9F, 0x01, 0xFE, 0x12, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x12, 0x00, + 0x01, 0x9F, 0x01, 0xFE, 0x12, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x12, 0x00, + 0x01, 0x9F, 0x01, 0xFE, 0x12, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x12, 0x00, + 0x01, 0x9F, 0x01, 0xFE, 0x12, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x12, 0x00, + 0x01, 0x9F, 0x01, 0xFE, 0x12, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x12, 0x00, + 0x01, 0x9F, 0x01, 0xFE, 0xD7, 0x00, + + /* 51 */ + 0xFF, 0x00, 0x55, 0x00, 0x01, 0x67, 0x01, 0x75, 0x05, 0x00, 0x01, 0x05, + 0x01, 0x77, 0x01, 0x70, 0x0A, 0x00, 0x01, 0xAF, 0x01, 0xFF, 0x05, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xB0, 0x0A, 0x00, 0x01, 0x5F, 0x01, 0xFF, + 0x01, 0x50, 0x04, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0x50, 0x0A, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xB0, 0x04, 0x00, 0x01, 0xBF, 0x01, 0xFF, + 0x0B, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF0, 0x03, 0x00, 0x01, 0x01, + 0x01, 0xFF, 0x01, 0xF9, 0x0B, 0x00, 0x01, 0x04, 0x01, 0xFF, 0x01, 0xF5, + 0x03, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF3, 0x0C, 0x00, 0x01, 0xEF, + 0x01, 0xFB, 0x03, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xD0, 0x0C, 0x00, + 0x01, 0x9F, 0x01, 0xFF, 0x03, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x70, + 0x0C, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x50, 0x02, 0x00, 0x01, 0x8F, + 0x01, 0xFF, 0x01, 0x20, 0x0C, 0x00, 0x01, 0x0E, 0x01, 0xFF, 0x01, 0xB0, + 0x02, 0x00, 0x01, 0xEF, 0x01, 0xFB, 0x0D, 0x00, 0x01, 0x09, 0x01, 0xFF, + 0x01, 0xF1, 0x01, 0x00, 0x01, 0x04, 0x01, 0xFF, 0x01, 0xF5, 0x0D, 0x00, + 0x01, 0x04, 0x01, 0xFF, 0x01, 0xF5, 0x01, 0x00, 0x01, 0x09, 0x01, 0xFF, + 0x01, 0xF0, 0x0E, 0x00, 0x01, 0xEF, 0x01, 0xFB, 0x01, 0x00, 0x01, 0x0E, + 0x01, 0xFF, 0x01, 0x90, 0x0E, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x10, + 0x01, 0x5F, 0x01, 0xFF, 0x01, 0x40, 0x0E, 0x00, 0x01, 0x3F, 0x01, 0xFF, + 0x01, 0x50, 0x01, 0xBF, 0x01, 0xFD, 0x0F, 0x00, 0x01, 0x0D, 0x01, 0xFF, + 0x01, 0xB1, 0x01, 0xFF, 0x01, 0xF8, 0x0F, 0x00, 0x01, 0x08, 0x01, 0xFF, + 0x01, 0xF7, 0x01, 0xFF, 0x01, 0xF2, 0x0F, 0x00, 0x01, 0x03, 0x03, 0xFF, + 0x01, 0xC0, 0x10, 0x00, 0x01, 0xDF, 0x02, 0xFF, 0x01, 0x60, 0x10, 0x00, + 0x01, 0x8F, 0x02, 0xFF, 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xFA, + 0x11, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xF4, 0x11, 0x00, 0x01, 0x0C, + 0x01, 0xFF, 0x01, 0xE0, 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x80, + 0x11, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x20, 0x11, 0x00, 0x01, 0xEF, + 0x01, 0xFC, 0x11, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xF6, 0x0F, 0x00, + 0x01, 0x05, 0x01, 0x76, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0xD0, 0x0F, 0x00, + 0x01, 0x09, 0x03, 0xFF, 0x01, 0x50, 0x0F, 0x00, 0x01, 0x09, 0x02, 0xFF, + 0x01, 0xF7, 0x10, 0x00, 0x01, 0x05, 0x01, 0xCE, 0x01, 0xDA, 0x01, 0x30, + 0x24, 0x00, + + /* 52 */ + 0xE3, 0x00, 0x01, 0x05, 0x01, 0x99, 0x01, 0x80, 0x11, 0x00, 0x01, 0x08, + 0x01, 0xFF, 0x01, 0xE0, 0x11, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xE0, + 0x11, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xE0, 0x11, 0x00, 0x01, 0x08, + 0x01, 0xFF, 0x01, 0xE0, 0x11, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xE0, + 0x0C, 0x00, 0x01, 0x01, 0x01, 0x8D, 0x01, 0xFF, 0x01, 0xEB, 0x01, 0x40, + 0x01, 0x08, 0x01, 0xFF, 0x01, 0xE0, 0x01, 0x02, 0x01, 0x9E, 0x01, 0xFF, + 0x01, 0xEA, 0x01, 0x50, 0x07, 0x00, 0x01, 0x6F, 0x03, 0xFF, 0x01, 0xFA, + 0x01, 0x08, 0x01, 0xFF, 0x01, 0xE0, 0x01, 0x5F, 0x03, 0xFF, 0x01, 0xFC, + 0x01, 0x20, 0x05, 0x00, 0x01, 0x06, 0x05, 0xFF, 0x01, 0x98, 0x01, 0xFF, + 0x01, 0xE4, 0x05, 0xFF, 0x01, 0xD1, 0x05, 0x00, 0x01, 0x3F, 0x01, 0xFF, + 0x01, 0xFC, 0x01, 0x53, 0x01, 0x36, 0x01, 0xCF, 0x01, 0xFC, 0x01, 0xFF, + 0x01, 0xFD, 0x01, 0xFF, 0x01, 0x83, 0x01, 0x24, 0x01, 0x9F, 0x01, 0xFF, + 0x01, 0xFB, 0x05, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x90, 0x02, 0x00, + 0x01, 0x0A, 0x03, 0xFF, 0x01, 0xE2, 0x02, 0x00, 0x01, 0x03, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0x40, 0x03, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xFC, + 0x04, 0x00, 0x01, 0xDF, 0x02, 0xFF, 0x01, 0x40, 0x03, 0x00, 0x01, 0x5F, + 0x01, 0xFF, 0x01, 0xB0, 0x03, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xF4, + 0x04, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0xFB, 0x04, 0x00, 0x01, 0x0C, + 0x01, 0xFF, 0x01, 0xF1, 0x03, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xE0, + 0x04, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xF6, 0x04, 0x00, 0x01, 0x07, + 0x01, 0xFF, 0x01, 0xF4, 0x03, 0x00, 0x01, 0x0E, 0x01, 0xFF, 0x01, 0xB0, + 0x04, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF2, 0x04, 0x00, 0x01, 0x03, + 0x01, 0xFF, 0x01, 0xF7, 0x03, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0x90, + 0x04, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF0, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF9, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x80, 0x04, 0x00, + 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF0, 0x05, 0x00, 0x01, 0xFF, 0x01, 0xFA, + 0x03, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x70, 0x04, 0x00, 0x01, 0x08, + 0x01, 0xFF, 0x01, 0xE0, 0x05, 0x00, 0x01, 0xEF, 0x01, 0xFB, 0x03, 0x00, + 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x80, 0x04, 0x00, 0x01, 0x09, 0x01, 0xFF, + 0x01, 0xF0, 0x05, 0x00, 0x01, 0xFF, 0x01, 0xFA, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0x90, 0x04, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF0, + 0x05, 0x00, 0x01, 0xFF, 0x01, 0xF9, 0x03, 0x00, 0x01, 0x0F, 0x01, 0xFF, + 0x01, 0xB0, 0x04, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF3, 0x04, 0x00, + 0x01, 0x03, 0x01, 0xFF, 0x01, 0xF7, 0x03, 0x00, 0x01, 0x0C, 0x01, 0xFF, + 0x01, 0xF0, 0x04, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xF7, 0x04, 0x00, + 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF4, 0x03, 0x00, 0x01, 0x09, 0x01, 0xFF, + 0x01, 0xF5, 0x04, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xFC, 0x04, 0x00, + 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xF1, 0x03, 0x00, 0x01, 0x04, 0x01, 0xFF, + 0x01, 0xFC, 0x04, 0x00, 0x01, 0xDF, 0x02, 0xFF, 0x01, 0x40, 0x03, 0x00, + 0x01, 0x5F, 0x01, 0xFF, 0x01, 0xB0, 0x04, 0x00, 0x01, 0xDF, 0x01, 0xFF, + 0x01, 0xA0, 0x02, 0x00, 0x01, 0x0B, 0x03, 0xFF, 0x01, 0xE3, 0x02, 0x00, + 0x01, 0x04, 0x02, 0xFF, 0x01, 0x40, 0x04, 0x00, 0x01, 0x5F, 0x01, 0xFF, + 0x01, 0xFD, 0x01, 0x74, 0x01, 0x47, 0x01, 0xDF, 0x01, 0xFE, 0x03, 0xFF, + 0x01, 0x95, 0x01, 0x45, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0xFB, 0x05, 0x00, + 0x01, 0x08, 0x05, 0xFF, 0x01, 0xB8, 0x01, 0xFF, 0x01, 0xE6, 0x05, 0xFF, + 0x01, 0xD1, 0x06, 0x00, 0x01, 0x7F, 0x03, 0xFF, 0x01, 0xFA, 0x01, 0x08, + 0x01, 0xFF, 0x01, 0xE0, 0x01, 0x6F, 0x03, 0xFF, 0x01, 0xFA, 0x01, 0x10, + 0x06, 0x00, 0x01, 0x02, 0x01, 0x8C, 0x01, 0xEF, 0x01, 0xDB, 0x01, 0x50, + 0x01, 0x08, 0x01, 0xFF, 0x01, 0xE0, 0x01, 0x02, 0x01, 0x8D, 0x01, 0xEE, + 0x01, 0xD9, 0x01, 0x30, 0x0C, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xE0, + 0x11, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xE0, 0x11, 0x00, 0x01, 0x08, + 0x01, 0xFF, 0x01, 0xE0, 0x11, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xE0, + 0x11, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xE0, 0x11, 0x00, 0x01, 0x08, + 0x01, 0xFF, 0x01, 0xE0, 0x11, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xE0, + 0x11, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xE0, 0x1E, 0x00, + + /* 53 */ + 0xFF, 0x00, 0x55, 0x00, 0x01, 0x37, 0x01, 0x77, 0x01, 0x30, 0x04, 0x00, + 0x01, 0x17, 0x01, 0x77, 0x01, 0x40, 0x0A, 0x00, 0x01, 0x0D, 0x01, 0xFF, + 0x01, 0xE1, 0x04, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x20, 0x0A, 0x00, + 0x01, 0x03, 0x01, 0xFF, 0x01, 0xFB, 0x03, 0x00, 0x01, 0x06, 0x01, 0xFF, + 0x01, 0xF6, 0x0C, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x50, 0x02, 0x00, + 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, 0x0C, 0x00, 0x01, 0x0D, 0x01, 0xFF, + 0x01, 0xE1, 0x02, 0x00, 0x01, 0xCF, 0x01, 0xFE, 0x01, 0x10, 0x0C, 0x00, + 0x01, 0x02, 0x01, 0xFF, 0x01, 0xFB, 0x01, 0x00, 0x01, 0x07, 0x01, 0xFF, + 0x01, 0xF5, 0x0E, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0x60, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0x90, 0x0E, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF2, + 0x01, 0xCF, 0x01, 0xFD, 0x0F, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xFE, + 0x01, 0xFF, 0x01, 0xF3, 0x10, 0x00, 0x01, 0x6F, 0x02, 0xFF, 0x01, 0x70, + 0x10, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xFC, 0x11, 0x00, 0x01, 0x09, + 0x01, 0xFF, 0x01, 0xFD, 0x11, 0x00, 0x01, 0x4F, 0x02, 0xFF, 0x01, 0x80, + 0x0F, 0x00, 0x01, 0x01, 0x01, 0xEF, 0x02, 0xFF, 0x01, 0xF3, 0x0F, 0x00, + 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xE3, 0x01, 0xEF, 0x01, 0xFD, 0x0F, 0x00, + 0x01, 0x6F, 0x01, 0xFF, 0x01, 0x50, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0x90, + 0x0D, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xFB, 0x01, 0x00, 0x01, 0x0A, + 0x01, 0xFF, 0x01, 0xF4, 0x0D, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xE1, + 0x01, 0x00, 0x01, 0x01, 0x01, 0xEF, 0x01, 0xFD, 0x0D, 0x00, 0x01, 0x8F, + 0x01, 0xFF, 0x01, 0x50, 0x02, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0x90, + 0x0B, 0x00, 0x01, 0x03, 0x01, 0xFF, 0x01, 0xFA, 0x03, 0x00, 0x01, 0x0B, + 0x01, 0xFF, 0x01, 0xF4, 0x0B, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xE1, + 0x03, 0x00, 0x01, 0x01, 0x01, 0xEF, 0x01, 0xFE, 0x01, 0x10, 0x0A, 0x00, + 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x50, 0x04, 0x00, 0x01, 0x6F, 0x01, 0xFF, + 0x01, 0xA0, 0x0A, 0x00, 0x02, 0x11, 0x05, 0x00, 0x01, 0x01, 0x01, 0x11, + 0x01, 0x10, 0xBE, 0x00, + + /* 54 */ + 0xFF, 0x00, 0x56, 0x00, 0x01, 0x67, 0x01, 0x74, 0x05, 0x00, 0x01, 0x77, + 0x01, 0x73, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x11, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x07, 0xFF, 0x01, 0xFC, 0x01, 0x99, + 0x0A, 0x00, 0x01, 0xEF, 0x09, 0xFF, 0x0A, 0x00, 0x01, 0xEF, 0x09, 0xFF, + 0x12, 0x00, 0x01, 0x0E, 0x01, 0xFF, 0x12, 0x00, 0x01, 0x0E, 0x01, 0xFF, + 0x12, 0x00, 0x01, 0x0E, 0x01, 0xFF, 0x12, 0x00, 0x01, 0x0E, 0x01, 0xFF, + 0x12, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x6D, 0x00, + + /* 55 */ + 0xFF, 0x00, 0x55, 0x00, 0x01, 0x02, 0x01, 0x77, 0x01, 0x71, 0x04, 0x00, + 0x01, 0x77, 0x01, 0x73, 0x0B, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF2, + 0x04, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0x05, 0x01, 0xFF, + 0x01, 0xF2, 0x04, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0x05, + 0x01, 0xFF, 0x01, 0xF2, 0x04, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x0B, 0x00, + 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF2, 0x04, 0x00, 0x01, 0xFF, 0x01, 0xF8, + 0x0B, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF2, 0x04, 0x00, 0x01, 0xFF, + 0x01, 0xF8, 0x0B, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF2, 0x04, 0x00, + 0x01, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF2, + 0x04, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0x05, 0x01, 0xFF, + 0x01, 0xF2, 0x04, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0x03, + 0x01, 0xFF, 0x01, 0xF6, 0x04, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x0C, 0x00, + 0x02, 0xFF, 0x01, 0x85, 0x03, 0x55, 0x01, 0xFF, 0x01, 0xF8, 0x0C, 0x00, + 0x01, 0x6F, 0x06, 0xFF, 0x01, 0xF8, 0x0C, 0x00, 0x01, 0x07, 0x06, 0xFF, + 0x01, 0xF8, 0x0D, 0x00, 0x01, 0x17, 0x01, 0xBC, 0x03, 0xCC, 0x01, 0xFF, + 0x01, 0xF8, 0x12, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x12, 0x00, 0x01, 0xFF, + 0x01, 0xF8, 0x12, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x12, 0x00, 0x01, 0xFF, + 0x01, 0xF8, 0x12, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x12, 0x00, 0x01, 0xFF, + 0x01, 0xF8, 0x12, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x12, 0x00, 0x01, 0xFF, + 0x01, 0xF8, 0x12, 0x00, 0x01, 0x11, 0x01, 0x10, 0xBF, 0x00, + + /* 56 */ + 0xFF, 0x00, 0x56, 0x00, 0x01, 0x66, 0x01, 0x64, 0x02, 0x00, 0x01, 0x01, + 0x01, 0x66, 0x01, 0x62, 0x02, 0x00, 0x01, 0x02, 0x01, 0x66, 0x01, 0x60, + 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, + 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, + 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, + 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, + 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, + 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, + 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, + 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, + 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, + 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, + 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, + 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, + 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, + 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, + 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, + 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, + 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, + 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, + 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, + 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, + 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, + 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, + 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x11, 0x01, 0x13, + 0x01, 0xFF, 0x01, 0xF6, 0x02, 0x11, 0x01, 0x17, 0x01, 0xFF, 0x01, 0xF1, + 0x08, 0x00, 0x01, 0xEF, 0x0A, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, + 0x0A, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x0A, 0xFF, 0x01, 0xF1, + 0xCF, 0x00, + + /* 57 */ + 0xFF, 0x00, 0x56, 0x00, 0x01, 0x66, 0x01, 0x63, 0x02, 0x00, 0x01, 0x01, + 0x01, 0x66, 0x01, 0x62, 0x02, 0x00, 0x01, 0x02, 0x01, 0x66, 0x01, 0x60, + 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, + 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, + 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, + 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, + 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, + 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, + 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, + 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, + 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, + 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, + 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, + 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, + 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, + 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, + 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, + 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, + 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, + 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, + 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, + 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, + 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, + 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, + 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x11, 0x01, 0x13, + 0x01, 0xFF, 0x01, 0xF6, 0x02, 0x11, 0x01, 0x17, 0x01, 0xFF, 0x01, 0xF1, + 0x08, 0x00, 0x01, 0xEF, 0x0A, 0xFF, 0x01, 0xF9, 0x01, 0x95, 0x07, 0x00, + 0x01, 0xEF, 0x0B, 0xFF, 0x01, 0xF9, 0x07, 0x00, 0x01, 0xEF, 0x0B, 0xFF, + 0x01, 0xF9, 0x12, 0x00, 0x01, 0x5F, 0x01, 0xF9, 0x12, 0x00, 0x01, 0x5F, + 0x01, 0xF9, 0x12, 0x00, 0x01, 0x5F, 0x01, 0xF9, 0x12, 0x00, 0x01, 0x5F, + 0x01, 0xF9, 0x12, 0x00, 0x01, 0x5F, 0x01, 0xF9, 0x6A, 0x00, + + /* 58 */ + 0xFF, 0x00, 0x56, 0x00, 0x01, 0x56, 0x01, 0x63, 0x12, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x02, 0xEE, 0x01, 0xED, + 0x01, 0xC9, 0x01, 0x60, 0x0D, 0x00, 0x01, 0xEF, 0x06, 0xFF, 0x01, 0x70, + 0x0C, 0x00, 0x01, 0xEF, 0x06, 0xFF, 0x01, 0xFA, 0x0C, 0x00, 0x01, 0xEF, + 0x01, 0xFA, 0x02, 0x33, 0x01, 0x34, 0x01, 0x6A, 0x02, 0xFF, 0x01, 0x50, + 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x04, 0x00, 0x01, 0x6F, 0x01, 0xFF, + 0x01, 0xD0, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x04, 0x00, 0x01, 0x0C, + 0x01, 0xFF, 0x01, 0xF1, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x04, 0x00, + 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF3, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x04, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xF4, 0x0B, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x04, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF2, 0x0B, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x04, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xE0, + 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x03, 0x11, 0x01, 0x38, 0x02, 0xFF, + 0x01, 0x70, 0x0B, 0x00, 0x01, 0xEF, 0x06, 0xFF, 0x01, 0xFC, 0x0C, 0x00, + 0x01, 0xEF, 0x06, 0xFF, 0x01, 0xC1, 0x0C, 0x00, 0x01, 0xEF, 0x05, 0xFF, + 0x01, 0xB5, 0x0D, 0x00, 0x05, 0x11, 0xC2, 0x00, + + /* 59 */ + 0xFF, 0x00, 0x56, 0x00, 0x01, 0x56, 0x01, 0x63, 0x07, 0x00, 0x01, 0x02, + 0x01, 0x66, 0x01, 0x60, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x07, 0x00, + 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x07, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x07, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x07, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF0, + 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x07, 0x00, 0x01, 0x07, 0x01, 0xFF, + 0x01, 0xF0, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x07, 0x00, 0x01, 0x07, + 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x07, 0x00, + 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xFF, + 0x02, 0xEE, 0x01, 0xED, 0x01, 0xC9, 0x01, 0x60, 0x02, 0x00, 0x01, 0x07, + 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, 0x01, 0xEF, 0x06, 0xFF, 0x01, 0x70, + 0x01, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, 0x01, 0xEF, + 0x06, 0xFF, 0x01, 0xFA, 0x01, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF0, + 0x08, 0x00, 0x01, 0xEF, 0x01, 0xFA, 0x02, 0x33, 0x01, 0x34, 0x01, 0x6B, + 0x02, 0xFF, 0x01, 0x50, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x04, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xD0, + 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x04, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF1, 0x01, 0x07, 0x01, 0xFF, + 0x01, 0xF0, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x04, 0x00, 0x01, 0x09, + 0x01, 0xFF, 0x01, 0xF3, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x04, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xF4, + 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x04, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF2, 0x01, 0x07, 0x01, 0xFF, + 0x01, 0xF0, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x04, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0xE0, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x03, 0x11, 0x01, 0x37, 0x02, 0xFF, 0x01, 0x70, + 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, 0x01, 0xEF, 0x06, 0xFF, + 0x01, 0xFC, 0x01, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, + 0x01, 0xEF, 0x06, 0xFF, 0x01, 0xC1, 0x01, 0x00, 0x01, 0x07, 0x01, 0xFF, + 0x01, 0xF0, 0x08, 0x00, 0x01, 0xEF, 0x05, 0xFF, 0x01, 0xB5, 0x02, 0x00, + 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, 0x05, 0x11, 0x05, 0x00, + 0x01, 0x11, 0x01, 0x10, 0xBB, 0x00, + + /* 60 */ + 0xFF, 0x00, 0x55, 0x00, 0x01, 0x36, 0x04, 0x66, 0x01, 0x63, 0x0E, 0x00, + 0x01, 0x9F, 0x04, 0xFF, 0x01, 0xF8, 0x0E, 0x00, 0x01, 0x9F, 0x04, 0xFF, + 0x01, 0xF8, 0x0E, 0x00, 0x01, 0x6A, 0x03, 0xAA, 0x01, 0xFF, 0x01, 0xF8, + 0x12, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x12, 0x00, 0x01, 0xFF, 0x01, 0xF8, + 0x12, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x12, 0x00, 0x01, 0xFF, 0x01, 0xF8, + 0x12, 0x00, 0x02, 0xFF, 0x02, 0xEE, 0x01, 0xED, 0x01, 0xC9, 0x01, 0x50, + 0x0D, 0x00, 0x06, 0xFF, 0x01, 0xFE, 0x01, 0x60, 0x0C, 0x00, 0x07, 0xFF, + 0x01, 0xF9, 0x0C, 0x00, 0x01, 0xFF, 0x01, 0xFA, 0x02, 0x33, 0x01, 0x34, + 0x01, 0x6B, 0x02, 0xFF, 0x01, 0x50, 0x0B, 0x00, 0x01, 0xFF, 0x01, 0xF8, + 0x04, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xC0, 0x0B, 0x00, 0x01, 0xFF, + 0x01, 0xF8, 0x04, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xF1, 0x0B, 0x00, + 0x01, 0xFF, 0x01, 0xF8, 0x04, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF3, + 0x0B, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x04, 0x00, 0x01, 0x09, 0x01, 0xFF, + 0x01, 0xF3, 0x0B, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x04, 0x00, 0x01, 0x0B, + 0x01, 0xFF, 0x01, 0xF2, 0x0B, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x04, 0x00, + 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xE0, 0x0B, 0x00, 0x01, 0xFF, 0x01, 0xF9, + 0x03, 0x11, 0x01, 0x38, 0x02, 0xFF, 0x01, 0x70, 0x0B, 0x00, 0x07, 0xFF, + 0x01, 0xFC, 0x0C, 0x00, 0x07, 0xFF, 0x01, 0xB1, 0x0C, 0x00, 0x06, 0xFF, + 0x01, 0xB5, 0x0D, 0x00, 0x05, 0x11, 0xBF, 0x00, + + /* 61 */ + 0xFF, 0x00, 0x57, 0x00, 0x01, 0x02, 0x01, 0x8C, 0x01, 0xFF, 0x01, 0xFD, + 0x01, 0x94, 0x0F, 0x00, 0x01, 0x9F, 0x04, 0xFF, 0x01, 0xB2, 0x0D, 0x00, + 0x01, 0x0C, 0x05, 0xFF, 0x01, 0xFE, 0x01, 0x20, 0x0C, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0xF8, 0x01, 0x42, 0x01, 0x36, 0x01, 0xDF, 0x01, 0xFF, + 0x01, 0xE1, 0x0B, 0x00, 0x01, 0x01, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x20, + 0x02, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xFA, 0x0B, 0x00, 0x01, 0x07, + 0x01, 0xFF, 0x01, 0xF5, 0x04, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x20, + 0x0A, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xE0, 0x04, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0x90, 0x0A, 0x00, 0x01, 0x0A, 0x01, 0xCC, 0x01, 0x80, + 0x04, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xE0, 0x11, 0x00, 0x01, 0x08, + 0x01, 0xFF, 0x01, 0xF1, 0x0D, 0x00, 0x01, 0x69, 0x03, 0x99, 0x01, 0x9B, + 0x01, 0xFF, 0x01, 0xF4, 0x0D, 0x00, 0x01, 0xAF, 0x05, 0xFF, 0x01, 0xF5, + 0x0D, 0x00, 0x01, 0xAF, 0x05, 0xFF, 0x01, 0xF6, 0x0D, 0x00, 0x01, 0x58, + 0x03, 0x88, 0x01, 0x8A, 0x01, 0xFF, 0x01, 0xF5, 0x11, 0x00, 0x01, 0x05, + 0x01, 0xFF, 0x01, 0xF4, 0x0A, 0x00, 0x01, 0x05, 0x01, 0x55, 0x01, 0x10, + 0x04, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF2, 0x0A, 0x00, 0x01, 0x0F, + 0x01, 0xFF, 0x01, 0x80, 0x04, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xE0, + 0x0A, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xD0, 0x04, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0xA0, 0x0A, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF5, + 0x04, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x40, 0x0A, 0x00, 0x01, 0x02, + 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x20, 0x02, 0x00, 0x01, 0x09, 0x01, 0xFF, + 0x01, 0xFC, 0x0C, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0xF9, 0x01, 0x42, + 0x01, 0x37, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xF2, 0x0C, 0x00, 0x01, 0x0B, + 0x06, 0xFF, 0x01, 0x40, 0x0D, 0x00, 0x01, 0x8F, 0x04, 0xFF, 0x01, 0xC2, + 0x0E, 0x00, 0x01, 0x01, 0x01, 0x8C, 0x01, 0xEF, 0x01, 0xED, 0x01, 0x94, + 0xC1, 0x00, + + /* 62 */ + 0xFF, 0x00, 0x56, 0x00, 0x01, 0x56, 0x01, 0x63, 0x04, 0x00, 0x01, 0x05, + 0x01, 0xAE, 0x01, 0xFF, 0x01, 0xED, 0x01, 0x83, 0x09, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x03, 0x00, 0x01, 0x03, 0x01, 0xDF, 0x04, 0xFF, 0x01, 0xA1, + 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x03, 0x00, 0x01, 0x6F, 0x05, 0xFF, + 0x01, 0xFE, 0x01, 0x20, 0x07, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, + 0x01, 0x04, 0x02, 0xFF, 0x01, 0xD6, 0x01, 0x32, 0x01, 0x48, 0x02, 0xFF, + 0x01, 0xE0, 0x07, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x0E, + 0x01, 0xFF, 0x01, 0xF9, 0x03, 0x00, 0x01, 0x1C, 0x01, 0xFF, 0x01, 0xF9, + 0x07, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x7F, 0x01, 0xFF, + 0x01, 0xB0, 0x03, 0x00, 0x01, 0x01, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x10, + 0x06, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0xDF, 0x01, 0xFF, + 0x01, 0x20, 0x04, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0x70, 0x06, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xFB, + 0x05, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xB0, 0x06, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x01, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF6, 0x05, 0x00, + 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xE0, 0x06, 0x00, 0x01, 0xEF, 0x01, 0xFD, + 0x01, 0x99, 0x01, 0x9C, 0x01, 0xFF, 0x01, 0xF3, 0x05, 0x00, 0x01, 0x09, + 0x01, 0xFF, 0x01, 0xF1, 0x06, 0x00, 0x01, 0xEF, 0x04, 0xFF, 0x01, 0xF2, + 0x05, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF2, 0x06, 0x00, 0x01, 0xEF, + 0x04, 0xFF, 0x01, 0xF1, 0x05, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF3, + 0x06, 0x00, 0x01, 0xEF, 0x01, 0xFC, 0x01, 0x88, 0x01, 0x8C, 0x01, 0xFF, + 0x01, 0xF2, 0x05, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF2, 0x06, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF3, + 0x05, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xF1, 0x06, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x01, 0x00, 0x01, 0x04, 0x01, 0xFF, 0x01, 0xF6, 0x05, 0x00, + 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF0, 0x06, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x01, 0x00, 0x01, 0x01, 0x01, 0xFF, 0x01, 0xFB, 0x05, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xB0, 0x06, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, + 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x20, 0x04, 0x00, 0x01, 0x7F, 0x01, 0xFF, + 0x01, 0x70, 0x06, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x6F, + 0x01, 0xFF, 0x01, 0xB0, 0x03, 0x00, 0x01, 0x01, 0x01, 0xEF, 0x01, 0xFF, + 0x01, 0x10, 0x06, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x0E, + 0x01, 0xFF, 0x01, 0xF9, 0x03, 0x00, 0x01, 0x2D, 0x01, 0xFF, 0x01, 0xF9, + 0x07, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x04, 0x02, 0xFF, + 0x01, 0xD7, 0x01, 0x32, 0x01, 0x49, 0x02, 0xFF, 0x01, 0xD0, 0x07, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x03, 0x00, 0x01, 0x6F, 0x05, 0xFF, 0x01, 0xFD, + 0x01, 0x20, 0x07, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x03, 0x00, 0x01, 0x03, + 0x01, 0xDF, 0x04, 0xFF, 0x01, 0xA1, 0x08, 0x00, 0x01, 0x11, 0x01, 0x10, + 0x04, 0x00, 0x01, 0x05, 0x01, 0xAD, 0x01, 0xFF, 0x01, 0xEC, 0x01, 0x82, + 0xBC, 0x00, + + /* 63 */ + 0xFF, 0x00, 0x58, 0x00, 0x01, 0x14, 0x05, 0x66, 0x01, 0x60, 0x0C, 0x00, + 0x01, 0x2B, 0x06, 0xFF, 0x01, 0xF2, 0x0B, 0x00, 0x01, 0x02, 0x01, 0xEF, + 0x06, 0xFF, 0x01, 0xF2, 0x0B, 0x00, 0x01, 0x0C, 0x02, 0xFF, 0x01, 0xEB, + 0x02, 0xAA, 0x01, 0xAC, 0x01, 0xFF, 0x01, 0xF2, 0x0B, 0x00, 0x01, 0x4F, + 0x01, 0xFF, 0x01, 0xF5, 0x03, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF2, + 0x0B, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x70, 0x03, 0x00, 0x01, 0x05, + 0x01, 0xFF, 0x01, 0xF2, 0x0B, 0x00, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0x30, + 0x03, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF2, 0x0B, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x20, 0x03, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF2, + 0x0B, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0x70, 0x03, 0x00, 0x01, 0x05, + 0x01, 0xFF, 0x01, 0xF2, 0x0B, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xF8, + 0x01, 0x20, 0x02, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF2, 0x0B, 0x00, + 0x01, 0x08, 0x07, 0xFF, 0x01, 0xF2, 0x0C, 0x00, 0x01, 0x8F, 0x06, 0xFF, + 0x01, 0xF2, 0x0C, 0x00, 0x01, 0x02, 0x01, 0x9D, 0x05, 0xFF, 0x01, 0xF2, + 0x0D, 0x00, 0x01, 0x01, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0x62, 0x01, 0x27, + 0x01, 0xFF, 0x01, 0xF2, 0x0D, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF7, + 0x01, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF2, 0x0D, 0x00, 0x01, 0xCF, + 0x01, 0xFF, 0x01, 0x80, 0x01, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF2, + 0x0C, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x05, + 0x01, 0xFF, 0x01, 0xF2, 0x0C, 0x00, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0xA0, + 0x02, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF2, 0x0B, 0x00, 0x01, 0x09, + 0x01, 0xFF, 0x01, 0xFA, 0x03, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF2, + 0x0B, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xB0, 0x03, 0x00, 0x01, 0x05, + 0x01, 0xFF, 0x01, 0xF2, 0x0A, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xFB, + 0x04, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF2, 0x0A, 0x00, 0x01, 0x7F, + 0x01, 0xFF, 0x01, 0xC0, 0x04, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF2, + 0x0A, 0x00, 0x02, 0x11, 0x06, 0x00, 0x01, 0x11, 0x01, 0x10, 0xBE, 0x00, + + /* 64 */ + 0x2C, 0x00, 0x01, 0xBD, 0x01, 0xDD, 0x01, 0x60, 0x01, 0x05, 0x01, 0xDD, + 0x01, 0xDC, 0x0E, 0x00, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0x70, 0x01, 0x06, + 0x01, 0xFF, 0x01, 0xFE, 0x0E, 0x00, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0x70, + 0x01, 0x06, 0x01, 0xFF, 0x01, 0xFE, 0x0E, 0x00, 0x01, 0xDF, 0x01, 0xFF, + 0x01, 0x70, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xFE, 0x0E, 0x00, 0x01, 0x67, + 0x01, 0x77, 0x01, 0x30, 0x01, 0x02, 0x01, 0x77, 0x01, 0x76, 0x33, 0x00, + 0x01, 0x1C, 0x0A, 0xCC, 0x09, 0x00, 0x01, 0x1F, 0x0A, 0xFF, 0x09, 0x00, + 0x01, 0x1F, 0x0A, 0xFF, 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xE8, + 0x08, 0x88, 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xFE, 0x07, 0xEE, + 0x01, 0xE4, 0x09, 0x00, 0x01, 0x1F, 0x09, 0xFF, 0x01, 0xF5, 0x09, 0x00, + 0x01, 0x1F, 0x09, 0xFF, 0x01, 0xF5, 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xE7, 0x07, 0x77, 0x01, 0x72, 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xD4, 0x08, 0x44, 0x01, 0x30, 0x08, 0x00, 0x01, 0x1F, 0x0A, 0xFF, + 0x01, 0xB0, 0x08, 0x00, 0x01, 0x1F, 0x0A, 0xFF, 0x01, 0xB0, 0x08, 0x00, + 0x01, 0x1F, 0x0A, 0xFF, 0x01, 0xB0, 0x08, 0x00, 0x01, 0x01, 0x0A, 0x11, + 0xBC, 0x00, + + /* 65 */ + 0xB6, 0x00, 0x01, 0x01, 0x02, 0x55, 0x01, 0x00, 0x01, 0x04, 0x01, 0x55, + 0x01, 0x52, 0x0D, 0x00, 0x01, 0x05, 0x02, 0xFF, 0x01, 0x00, 0x01, 0x0D, + 0x01, 0xFF, 0x01, 0xF7, 0x0D, 0x00, 0x01, 0x05, 0x02, 0xFF, 0x01, 0x00, + 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xF7, 0x0D, 0x00, 0x01, 0x05, 0x02, 0xFF, + 0x01, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xF7, 0x0D, 0x00, 0x01, 0x04, + 0x02, 0xEE, 0x01, 0x00, 0x01, 0x0C, 0x01, 0xEE, 0x01, 0xE6, 0x4A, 0x00, + 0x01, 0x17, 0x01, 0xBE, 0x01, 0xFF, 0x01, 0xDB, 0x01, 0x60, 0x0E, 0x00, + 0x01, 0x07, 0x04, 0xFF, 0x01, 0xFE, 0x01, 0x50, 0x0D, 0x00, 0x01, 0xBF, + 0x05, 0xFF, 0x01, 0xF7, 0x0C, 0x00, 0x01, 0x0A, 0x02, 0xFF, 0x01, 0x94, + 0x01, 0x23, 0x01, 0x6C, 0x02, 0xFF, 0x01, 0x50, 0x0B, 0x00, 0x01, 0x6F, + 0x01, 0xFF, 0x01, 0xD2, 0x03, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xD0, + 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xFE, 0x01, 0x10, 0x03, 0x00, 0x01, 0x07, + 0x01, 0xFF, 0x01, 0xF6, 0x0A, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF6, + 0x05, 0x00, 0x01, 0xEF, 0x01, 0xFB, 0x0A, 0x00, 0x01, 0x09, 0x01, 0xFF, + 0x01, 0xF0, 0x05, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x0A, 0x00, 0x01, 0x0D, + 0x01, 0xFF, 0x01, 0xB0, 0x05, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x30, + 0x09, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xB5, 0x05, 0x55, 0x01, 0x7F, + 0x01, 0xFF, 0x01, 0x50, 0x09, 0x00, 0x01, 0x1F, 0x09, 0xFF, 0x01, 0x70, + 0x09, 0x00, 0x01, 0x2F, 0x09, 0xFF, 0x01, 0x70, 0x09, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xB7, 0x07, 0x77, 0x01, 0x40, 0x09, 0x00, 0x01, 0x0F, + 0x01, 0xFF, 0x01, 0x80, 0x11, 0x00, 0x01, 0x0E, 0x01, 0xFF, 0x01, 0xB0, + 0x11, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xE0, 0x05, 0x00, 0x01, 0x37, + 0x01, 0x77, 0x0A, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF5, 0x05, 0x00, + 0x01, 0xDF, 0x01, 0xFD, 0x0B, 0x00, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x10, + 0x03, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0x8F, + 0x01, 0xFF, 0x01, 0xC1, 0x03, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0xF1, + 0x0B, 0x00, 0x01, 0x0C, 0x02, 0xFF, 0x01, 0x94, 0x01, 0x23, 0x01, 0x6B, + 0x02, 0xFF, 0x01, 0x60, 0x0B, 0x00, 0x01, 0x01, 0x01, 0xCF, 0x05, 0xFF, + 0x01, 0xF8, 0x0D, 0x00, 0x01, 0x19, 0x04, 0xFF, 0x01, 0xFE, 0x01, 0x50, + 0x0E, 0x00, 0x01, 0x27, 0x01, 0xCE, 0x01, 0xFF, 0x01, 0xDA, 0x01, 0x50, + 0xC0, 0x00, + + /* 48 */ + 0xFF, 0x00, 0x56, 0x00, 0x01, 0x67, 0x01, 0x72, 0x01, 0x00, 0x01, 0x29, + 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xC7, 0x01, 0x10, 0x0C, 0x00, 0x01, 0xEF, + 0x01, 0xF4, 0x01, 0x08, 0x04, 0xFF, 0x01, 0xF6, 0x0C, 0x00, 0x01, 0xEF, + 0x01, 0xF4, 0x01, 0xAF, 0x05, 0xFF, 0x01, 0x80, 0x0B, 0x00, 0x01, 0xEF, + 0x01, 0xFC, 0x01, 0xFF, 0x01, 0xF9, 0x01, 0x42, 0x01, 0x37, 0x01, 0xDF, + 0x01, 0xFF, 0x01, 0xF6, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xFE, + 0x01, 0x30, 0x02, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x10, + 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xF3, 0x04, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x70, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x90, + 0x04, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x0A, 0x00, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0x30, 0x04, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF2, + 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFE, 0x05, 0x00, 0x01, 0x05, 0x01, 0xFF, + 0x01, 0xF5, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFB, 0x05, 0x00, 0x01, 0x02, + 0x01, 0xFF, 0x01, 0xF7, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFA, 0x06, 0x00, + 0x01, 0xFF, 0x01, 0xF8, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x06, 0x00, + 0x01, 0xFF, 0x01, 0xF9, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFA, 0x06, 0x00, + 0x01, 0xFF, 0x01, 0xF9, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFB, 0x05, 0x00, + 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF8, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFE, + 0x05, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF5, 0x0A, 0x00, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0x30, 0x04, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF2, + 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0xD0, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xF4, + 0x04, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x70, 0x0A, 0x00, 0x01, 0xEF, + 0x02, 0xFF, 0x01, 0x40, 0x02, 0x00, 0x01, 0x1B, 0x01, 0xFF, 0x01, 0xFE, + 0x01, 0x10, 0x0A, 0x00, 0x01, 0xEF, 0x02, 0xFF, 0x01, 0xFB, 0x01, 0x64, + 0x01, 0x58, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xF5, 0x0B, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x01, 0xAF, 0x05, 0xFF, 0x01, 0x70, 0x0B, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x01, 0x08, 0x04, 0xFF, 0x01, 0xE4, 0x0C, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x01, 0x00, 0x01, 0x28, 0x01, 0xCE, 0x01, 0xED, 0x01, 0xA5, + 0x0D, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xDE, 0x01, 0xE8, + 0x25, 0x00, +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps.cpp similarity index 91% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps.cpp index c5126721abb2..d9acb4f67a43 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps.cpp @@ -16,21 +16,23 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../ftdi_extended.h" -#ifdef FTDI_EXTENDED +#if ENABLED(FTDI_EXTENDED) namespace FTDI { - void write_rle_data(uint16_t addr, const uint8_t *data, size_t n) { + uint32_t write_rle_data(uint32_t addr, const uint8_t *data, size_t n) { for (; n >= 2; n -= 2) { uint8_t count = pgm_read_byte(data++); uint8_t value = pgm_read_byte(data++); - while (count--) CLCD::mem_write_8(addr++, value); + CLCD::mem_write_fill(addr, value, count); + addr += count; } + return addr; } void set_font_bitmap(CommandProcessor& cmd, CLCD::FontMetrics &fm, uint8_t handle) { diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps.h similarity index 94% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps.h index f1e22e17ddf5..2b0a533084d8 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps.h @@ -16,7 +16,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once @@ -24,7 +24,7 @@ class CommandProcessor; namespace FTDI { - void write_rle_data(uint16_t addr, const uint8_t *data, size_t n); + uint32_t write_rle_data(uint32_t addr, const uint8_t *data, size_t n); void set_font_bitmap(CommandProcessor& cmd, CLCD::FontMetrics &fm, uint8_t handle); void ext_vertex2ii(CommandProcessor &cmd, int x, int y, uint8_t handle, uint8_t cell); } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/cyrillic_char_set_bitmap_31.png b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/cyrillic_char_set_bitmap_31.png new file mode 100644 index 000000000000..bc46ebe6aa07 Binary files /dev/null and b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/cyrillic_char_set_bitmap_31.png differ diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/cyrillic_char_set_bitmap_31.svg b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/cyrillic_char_set_bitmap_31.svg new file mode 100644 index 000000000000..25893f52767b --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/cyrillic_char_set_bitmap_31.svg @@ -0,0 +1,535 @@ + + + + + + + + + + + + image/svg+xml + + + + + + + + + АБВГДЕЖЗИЙКЛМНОПРСТУФХЦЧШЩЬЫЪЭЮЯабвгдежзийклмнопрстуфхцчшщьыъэюяЁё + + + + + + + + + diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/romfont_31.pbm b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/romfont_31.pbm similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/romfont_31.pbm rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/romfont_31.pbm diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/romfont_31.png b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/romfont_31.png new file mode 100644 index 000000000000..baafc82171ce Binary files /dev/null and b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/romfont_31.png differ diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/western_char_set_bitmap_31.png b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/western_char_set_bitmap_31.png similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/western_char_set_bitmap_31.png rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/western_char_set_bitmap_31.png diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/western_char_set_bitmap_31.svg b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/western_char_set_bitmap_31.svg similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/western_char_set_bitmap_31.svg rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/western_char_set_bitmap_31.svg diff --git a/Marlin/src/lcd/extui/lib/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 similarity index 99% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_size_t.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_size_t.cpp index 733cf8f6603a..0e251f7bb1c7 100644 --- a/Marlin/src/lcd/extui/lib/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 @@ -16,7 +16,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../ftdi_extended.h" diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_size_t.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_size_t.h similarity index 99% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_size_t.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_size_t.h index f5bf644ef9e7..a2cb8b25c97a 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_size_t.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_size_t.h @@ -16,7 +16,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once diff --git a/Marlin/src/lcd/extui/lib/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 similarity index 97% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/standard_char_set.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/standard_char_set.cpp index b50c12fc6df1..d12bf9711907 100644 --- a/Marlin/src/lcd/extui/lib/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 @@ -16,7 +16,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../ftdi_extended.h" @@ -48,7 +48,8 @@ * addr - Address in RAMG where the font data is written */ - void FTDI::StandardCharSet::load_data(uint32_t) { + uint32_t FTDI::StandardCharSet::load_data(uint32_t addr) { + return addr; } /** diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/standard_char_set.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/standard_char_set.h similarity index 96% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/standard_char_set.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/standard_char_set.h index 7decdfd38f66..48794d475f85 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/standard_char_set.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/standard_char_set.h @@ -16,14 +16,14 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ namespace FTDI { class StandardCharSet { public: static uint8_t std_char_width(char); - static void load_data(uint32_t addr); + static uint32_t load_data(uint32_t addr); static void load_bitmaps(CommandProcessor&); static bool render_glyph(CommandProcessor*, int &x, int &y, font_size_t, utf8_char_t); }; diff --git a/Marlin/src/lcd/extui/lib/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 similarity index 79% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp index 09473c1c263d..2da5d55ff0c8 100644 --- a/Marlin/src/lcd/extui/lib/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 @@ -16,7 +16,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../ftdi_extended.h" @@ -68,8 +68,17 @@ utf8_char_t FTDI::get_utf8_char_and_inc(const char *&c) { utf8_char_t val = *(uint8_t*)c++; - while ((*c & 0xC0) == 0x80) - val = (val << 8) | *(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(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; } @@ -88,10 +97,13 @@ * fs - A scaling object used to specify the font size. */ - static uint16_t render_utf8_text(CommandProcessor* cmd, int x, int y, const char *str, font_size_t fs) { + static uint16_t render_utf8_text(CommandProcessor* cmd, int x, int y, const char *str, font_size_t fs, size_t maxlen=SIZE_MAX) { const int start_x = x; - while (*str) { + while (*str && maxlen--) { const utf8_char_t c = get_utf8_char_and_inc(str); + #ifdef TOUCH_UI_UTF8_CYRILLIC_CHARSET + CyrillicCharSet::render_glyph(cmd, x, y, fs, c) || + #endif #ifdef TOUCH_UI_UTF8_WESTERN_CHARSET WesternCharSet::render_glyph(cmd, x, y, fs, c) || #endif @@ -108,11 +120,14 @@ * addr - Address in RAMG where the font data is written */ - void FTDI::load_utf8_data(uint16_t addr) { + void FTDI::load_utf8_data(uint32_t addr) { + #ifdef TOUCH_UI_UTF8_CYRILLIC_CHARSET + addr = CyrillicCharSet::load_data(addr); + #endif #ifdef TOUCH_UI_UTF8_WESTERN_CHARSET - WesternCharSet::load_data(addr); + addr = WesternCharSet::load_data(addr); #endif - StandardCharSet::load_data(addr); + addr = StandardCharSet::load_data(addr); } /** @@ -125,10 +140,15 @@ */ void FTDI::load_utf8_bitmaps(CommandProcessor &cmd) { + cmd.cmd(SAVE_CONTEXT()); + #ifdef TOUCH_UI_UTF8_CYRILLIC_CHARSET + CyrillicCharSet::load_bitmaps(cmd); + #endif #ifdef TOUCH_UI_UTF8_WESTERN_CHARSET WesternCharSet::load_bitmaps(cmd); #endif StandardCharSet::load_bitmaps(cmd); + cmd.cmd(RESTORE_CONTEXT()); } /** @@ -145,10 +165,13 @@ uint16_t FTDI::get_utf8_char_width(utf8_char_t c, font_size_t fs) { int x = 0, y = 0; + #ifdef TOUCH_UI_UTF8_CYRILLIC_CHARSET + CyrillicCharSet::render_glyph(nullptr, x, y, fs, c) || + #endif #ifdef TOUCH_UI_UTF8_WESTERN_CHARSET - WesternCharSet::render_glyph(NULL, x, y, fs, c) || + WesternCharSet::render_glyph(nullptr, x, y, fs, c) || #endif - StandardCharSet::render_glyph(NULL, x, y, fs, c); + StandardCharSet::render_glyph(nullptr, x, y, fs, c); return x; } @@ -164,8 +187,8 @@ * Returns: A width in pixels */ - uint16_t FTDI::get_utf8_text_width(const char *str, font_size_t fs) { - return render_utf8_text(NULL, 0, 0, str, fs); + uint16_t FTDI::get_utf8_text_width(const char *str, font_size_t fs, size_t maxlen) { + return render_utf8_text(nullptr, 0, 0, str, fs, maxlen); } uint16_t FTDI::get_utf8_text_width(progmem_str pstr, font_size_t fs) { @@ -189,9 +212,10 @@ * * options - Text alignment options (i.e. OPT_CENTERX, OPT_CENTERY, OPT_CENTER or OPT_RIGHTX) * + * maxlen - Maximum characters to draw */ - void FTDI::draw_utf8_text(CommandProcessor& cmd, int x, int y, const char *str, font_size_t fs, uint16_t options) { + void FTDI::draw_utf8_text(CommandProcessor& cmd, int x, int y, const char *str, font_size_t fs, uint16_t options, size_t maxlen) { cmd.cmd(SAVE_CONTEXT()); cmd.cmd(BITMAP_TRANSFORM_A(fs.get_coefficient())); cmd.cmd(BITMAP_TRANSFORM_E(fs.get_coefficient())); @@ -199,14 +223,14 @@ // Apply alignment options if (options & OPT_CENTERX) - x -= get_utf8_text_width(str, fs) / 2; + x -= get_utf8_text_width(str, fs, maxlen) / 2; else if (options & OPT_RIGHTX) - x -= get_utf8_text_width(str, fs); + x -= get_utf8_text_width(str, fs, maxlen); if (options & OPT_CENTERY) y -= fs.get_height()/2; // Render the text - render_utf8_text(&cmd, x, y, str, fs); + render_utf8_text(&cmd, x, y, str, fs, maxlen); cmd.cmd(RESTORE_CONTEXT()); } diff --git a/Marlin/src/lcd/extui/lib/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 similarity index 88% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.h index 16f7e197b589..3ca6dfd563ea 100644 --- a/Marlin/src/lcd/extui/lib/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 @@ -16,7 +16,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once @@ -24,7 +24,7 @@ class CommandProcessor; namespace FTDI { - #ifdef TOUCH_UI_USE_UTF8 + #if ENABLED(TOUCH_UI_USE_UTF8) typedef uint16_t utf8_char_t; /** @@ -47,41 +47,42 @@ 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 */ inline utf8_char_t get_utf8_char(const char *c) {return get_utf8_char_and_inc(c);} - void load_utf8_data(uint16_t addr); + void load_utf8_data(uint32_t addr); #else typedef char utf8_char_t; inline utf8_char_t get_utf8_char_and_inc(const char *&c) {return *c++;} inline utf8_char_t get_utf8_char(const char *c) {return *c;} - inline void load_utf8_data(uint16_t) {} + inline void load_utf8_data(uint32_t) {} #endif void load_utf8_bitmaps(CommandProcessor& cmd); uint16_t get_utf8_char_width(utf8_char_t, font_size_t); uint16_t get_utf8_text_width(progmem_str, font_size_t); - uint16_t get_utf8_text_width(const char *, font_size_t); + uint16_t get_utf8_text_width(const char *, font_size_t, size_t maxlen=SIZE_MAX); void draw_utf8_text(CommandProcessor&, int x, int y, progmem_str, font_size_t, uint16_t options = 0); - void draw_utf8_text(CommandProcessor&, int x, int y, const char *, font_size_t, uint16_t options = 0); + void draw_utf8_text(CommandProcessor&, int x, int y, const char *, font_size_t, uint16_t options = 0, size_t maxlen=SIZE_MAX); // Similar to CLCD::FontMetrics, but can be used with UTF8 encoded strings. struct FontMetrics { - #ifdef TOUCH_UI_USE_UTF8 + #if ENABLED(TOUCH_UI_USE_UTF8) font_size_t fs; #else CLCD::FontMetrics fm; #endif inline void load(uint8_t rom_font_size) { - #ifdef TOUCH_UI_USE_UTF8 + #if ENABLED(TOUCH_UI_USE_UTF8) fs = font_size_t::from_romfont(rom_font_size); #else fm.load(rom_font_size); @@ -89,7 +90,7 @@ namespace FTDI { } inline uint16_t get_char_width(utf8_char_t c) const { - #ifdef TOUCH_UI_USE_UTF8 + #if ENABLED(TOUCH_UI_USE_UTF8) return get_utf8_char_width(c, fs); #else return fm.char_widths[(uint8_t)c]; @@ -97,7 +98,7 @@ namespace FTDI { } inline uint8_t get_height() const { - #ifdef TOUCH_UI_USE_UTF8 + #if ENABLED(TOUCH_UI_USE_UTF8) return fs.get_height(); #else return fm.height; diff --git a/Marlin/src/lcd/extui/lib/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 similarity index 96% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.cpp index 4aa2580c633a..4fb2f8fdbf24 100644 --- a/Marlin/src/lcd/extui/lib/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 @@ -16,7 +16,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../ftdi_extended.h" @@ -32,7 +32,7 @@ constexpr static uint8_t std_font = 31; constexpr static uint8_t alt_font = 1; - static uint32_t bitmap_addr; + uint32_t FTDI::WesternCharSet::bitmap_addr; /* Glyphs in the WesternCharSet bitmap */ @@ -71,9 +71,9 @@ YEN_SIGN, #endif #if ENABLED(TOUCH_UI_UTF8_SUPERSCRIPTS) - SUPERSCRIPT_ONE, - SUPERSCRIPT_TWO, - SUPERSCRIPT_THREE, + SUPERSCRIPT_1, + SUPERSCRIPT_2, + SUPERSCRIPT_3, #endif #if ENABLED(TOUCH_UI_UTF8_ORDINALS) MASCULINE_ORDINAL, @@ -177,15 +177,15 @@ {UTF8('±'), 0 , NOT_SIGN, 32 }, #endif #if ENABLED(TOUCH_UI_UTF8_SUPERSCRIPTS) - {UTF8('²'), 0 , SUPERSCRIPT_TWO, 16 }, - {UTF8('³'), 0 , SUPERSCRIPT_THREE, 16 }, + {UTF8('²'), 0 , SUPERSCRIPT_2, 16 }, + {UTF8('³'), 0 , SUPERSCRIPT_3, 16 }, #endif #if ENABLED(TOUCH_UI_UTF8_SYMBOLS) {UTF8('µ'), 0 , MICRON_SIGN, 28 }, {UTF8('¶'), 0 , PILCROW_SIGN, 24 }, #endif #if ENABLED(TOUCH_UI_UTF8_SUPERSCRIPTS) - {UTF8('¹'), 0 , SUPERSCRIPT_ONE, 16 }, + {UTF8('¹'), 0 , SUPERSCRIPT_1, 16 }, #endif #if ENABLED(TOUCH_UI_UTF8_ORDINALS) {UTF8('º'), 0 , MASCULINE_ORDINAL, 19 }, @@ -286,7 +286,7 @@ #if ENABLED(TOUCH_UI_UTF8_SCANDINAVIAN) {UTF8('þ'), 0 , SML_THORN, 25 }, #endif - {UTF8('ÿ'), 'y', DIAERESIS, mid_y} + {UTF8('ÿ'), 'y', DIAERESIS, mid_y}, }; static_assert(UTF8('¡') == 0xC2A1, "Incorrect encoding for character"); @@ -331,7 +331,10 @@ * addr - Address in RAMG where the font data is written */ - void FTDI::WesternCharSet::load_data(uint32_t addr) { + uint32_t FTDI::WesternCharSet::load_data(uint32_t addr) { + if (addr % 4 != 0) + addr += 4 - (addr % 4); + // Load the alternative font metrics CLCD::FontMetrics alt_fm; alt_fm.ptr = addr + 148; @@ -352,9 +355,11 @@ CLCD::mem_write_bulk(addr, &alt_fm, 148); // Decode the RLE data and load it into RAMG as a bitmap - write_rle_data(addr + 148, font, sizeof(font)); + uint32_t lastaddr = write_rle_data(addr + 148, font, sizeof(font)); bitmap_addr = addr; + + return lastaddr; } /** @@ -394,7 +399,7 @@ * * c - The unicode code point to draw. If the renderer does not * support the character, it should return false. - + * * Returns: Whether the character was supported. */ @@ -435,7 +440,7 @@ base_char = base_special ? NO_DOT_I : std_char; } - // If cmd != NULL, draw the glyph to the screen + // If cmd != nullptr, draw the glyph to the screen if (cmd) { ext_vertex2ii(*cmd, x, y, base_special ? alt_font : std_font, base_char); if (accent_char) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.h similarity index 93% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.h index 2adad2327afa..683093d866be 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.h @@ -16,13 +16,15 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ namespace FTDI { class WesternCharSet { + private: + static uint32_t bitmap_addr; public: - static void load_data(uint32_t addr); + static uint32_t load_data(uint32_t addr); static void load_bitmaps(CommandProcessor&); static bool render_glyph(CommandProcessor*, int &x, int &y, font_size_t, utf8_char_t); }; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set_bitmap_31.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set_bitmap_31.h similarity index 99% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set_bitmap_31.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set_bitmap_31.h index 3426e1377dbf..3f85cf02aa61 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set_bitmap_31.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set_bitmap_31.h @@ -16,7 +16,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/ftdi_eve_lib.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/ftdi_eve_lib.h similarity index 98% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/ftdi_eve_lib.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/ftdi_eve_lib.h index 5c1a74f66e9d..c5ddbb4a6114 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/ftdi_eve_lib.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/ftdi_eve_lib.h @@ -17,7 +17,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once 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 new file mode 100755 index 000000000000..6aa8947b9858 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/file2cpp.py @@ -0,0 +1,47 @@ +#!/usr/bin/python + +# Written By Marcio Teixeira 2021 - SynDaver Labs, 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: . + +from __future__ import print_function +import argparse +import textwrap +import os +import zlib + +def deflate(data): + return zlib.compress(data) + +if __name__ == "__main__": + parser = argparse.ArgumentParser(description='Converts a file into a packed C array for use as data') + parser.add_argument("input") + 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]; + + with open(args.input, "rb") as in_file: + data = in_file.read() + if args.deflate: + data = deflate(data) + data = bytearray(data) + data = list(map(lambda a: "0x" + format(a, '02x'), data)) + nElements = len(data) + data = ', '.join(data) + data = textwrap.fill(data, 75, initial_indent = ' ', subsequent_indent = ' ') + + print("const unsigned char " + varname + "[" + format(nElements) + "] PROGMEM = {") + print(data) + print("};") 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 new file mode 100755 index 000000000000..0c4499e9aadf --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/font2cpp.py @@ -0,0 +1,108 @@ +#!/usr/bin/python + +# Written By Marcio Teixeira 2019 - 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: . + +from __future__ import print_function +from PIL import Image +import argparse +import textwrap + +def pack_rle(data): + """Use run-length encoding to pack the bytes""" + rle = [] + value = data[0] + count = 0 + for i in data: + if i != value or count == 255: + rle.append(count) + rle.append(value) + value = i + count = 1 + else: + count += 1 + rle.append(count) + rle.append(value) + return rle + +class WriteSource: + def __init__(self, lines_in_blocks): + self.blocks = [] + self.values = [] + self.block_size = lines_in_blocks + self.rows = 0 + + def add_pixel(self, value): + self.values.append(value) + + def convert_to_4bpp(self, data, chunk_size = 0): + # Invert the image + data = list(map(lambda i: 255 - i, data)) + # Quanitize 8-bit values into 4-bits + data = list(map(lambda i: i >> 4, data)) + # Make sure there is an even number of elements + if (len(data) & 1) == 1: + data.append(0) + # Combine each two adjacent values into one + i = iter(data) + data = list(map(lambda a, b: a << 4 | b, i ,i)) + # Pack the data + data = pack_rle(data) + # Convert values into hex strings + return list(map(lambda a: "0x" + format(a, '02x'), data)) + + def end_row(self, y): + # Pad each row into even number of values + if len(self.values) & 1: + self.values.append(0) + + self.rows += 1 + if self.block_size and (self.rows % self.block_size) == 0: + self.blocks.append(self.values) + self.values = [] + + def write(self): + if len(self.values): + self.blocks.append(self.values) + + block_strs = []; + for b in self.blocks: + data = self.convert_to_4bpp(b) + data = ', '.join(data) + data = textwrap.fill(data, 75, initial_indent = ' ', subsequent_indent = ' ') + block_strs.append(data) + + print("const unsigned char font[] PROGMEM = {") + for i, b in enumerate(block_strs): + if i: + print(',') + print('\n /* {} */'.format(i)) + print(b, end='') + print("\n};") + +if __name__ == "__main__": + parser = argparse.ArgumentParser(description='Converts a grayscale bitmap into a 16-level RLE packed C array for use as font data') + parser.add_argument("input") + parser.add_argument('--char_height', help='Adds a separator every so many lines', type=int) + args = parser.parse_args() + + writer = WriteSource(args.char_height) + + img = Image.open(args.input).convert('L') + for y in range(img.height): + for x in range(img.width): + writer.add_pixel(img.getpixel((x,y))) + writer.end_row(y) + writer.write() 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 new file mode 100755 index 000000000000..74be57430049 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/img2cpp.py @@ -0,0 +1,113 @@ +#!/usr/bin/python + +# Written By Marcio Teixeira 2021 - SynDaver Labs, 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: . + +from __future__ import print_function +from PIL import Image +import argparse +import textwrap +import os +import sys +import zlib + +class WriteSource: + def __init__(self, mode): + self.values = [] + self.mode = mode + self.offset = 8 + self.byte = 0 + + def finish_byte(self): + if self.offset != 8: + self.values.append(self.byte) + self.offset = 8 + self.byte = 0 + + def add_bits_to_byte(self, value, size = 1): + self.offset -= size + self.byte = self.byte | value << self.offset + if self.offset == 0: + self.finish_byte() + + 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); + + def append_rgb332(self, color): + value = (color[0] & 0xE0) + ((color[1] & 0xE0) >> 3) + ((color[2] & 0xC0) >> 6) + self.values.append(value); + + def append_grayscale(self, color, bits): + luminance = int(0.2126 * color[0] + 0.7152 * color[1] + 0.0722 * color[2]) + self.add_bits_to_byte(luminance >> (8 - bits), bits) + + def deflate(self, data): + return zlib.compress(data) + + def add_pixel(self, color): + if self.mode == "l1": + self.append_grayscale(color, 1) + elif self.mode == "l2": + self.append_grayscale(color, 2) + elif self.mode == "l4": + self.append_grayscale(color, 4) + elif self.mode == "l8": + self.append_grayscale(color, 8) + elif self.mode == "rgb565": + self.append_rgb565(color) + elif self.mode == "rgb332": + self.append_rgb332(color) + + def end_row(self, y): + if self.mode in ["l1", "l2", "l3"]: + self.finish_byte() + + def write(self, varname, deflate): + print("Length of uncompressed data: ", len(self.values), file=sys.stderr) + data = bytes(bytearray(self.values)) + if deflate: + data = self.deflate(data) + print("Length of data after compression: ", len(data), file=sys.stderr) + data = bytearray(data) + data = list(map(lambda a: "0x" + format(a, '02x'), data)) + nElements = len(data) + data = ', '.join(data) + data = textwrap.fill(data, 75, initial_indent = ' ', subsequent_indent = ' ') + + print("const unsigned char " + varname + "[" + format(nElements) + "] PROGMEM = {") + print(data) + print("};") + +if __name__ == "__main__": + parser = argparse.ArgumentParser(description='Converts a bitmap into a C array') + parser.add_argument("input") + parser.add_argument("-d", "--deflate", action="store_true", help="Packs the data using the deflate algorithm") + 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]; + + writer = WriteSource(args.mode) + + img = Image.open(args.input) + print("Image height: ", img.height, file=sys.stderr) + print("Image width: ", img.width, file=sys.stderr) + for y in range(img.height): + for x in range(img.width): + writer.add_pixel(img.getpixel((x,y))) + writer.end_row(y) + writer.write(varname, args.deflate) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/svg2cpp.py b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/svg2cpp.py similarity index 98% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/svg2cpp.py rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/svg2cpp.py index da08014e893e..cfc262545356 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/svg2cpp.py +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/svg2cpp.py @@ -16,7 +16,7 @@ # location: . from __future__ import print_function -import argparse, re, sys +import argparse,re,sys usage = ''' This program extracts line segments from a SVG file and writes @@ -56,7 +56,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ /** @@ -164,7 +164,7 @@ def process_svg_path_L_or_M(self, cmd, x, y): def process_svg_path_data_cmd(self, id, cmd, a, b): """Converts the various types of moves into L or M commands - and dispatches to process_svg_path_L_or_M for futher processing.""" + and dispatches to process_svg_path_L_or_M for further processing.""" if cmd == "Z" or cmd == "z": self.process_svg_path_L_or_M("L", self.initial_x, self.initial_y) elif cmd == "H": diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/about_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp similarity index 78% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/about_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp index 9cd17637bd52..d2aec0baf77c 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/about_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp @@ -17,17 +17,16 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) - -#include "screens.h" +#ifdef FTDI_ABOUT_SCREEN #define GRID_COLS 4 -#define GRID_ROWS 7 +#define GRID_ROWS 8 using namespace FTDI; using namespace Theme; @@ -45,15 +44,12 @@ void AboutScreen::onRedraw(draw_mode_t) { .cmd(COLOR_RGB(bg_text_enabled)) .tag(0); - #define HEADING_POS BTN_POS(1,2), BTN_SIZE(4,1) + #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,2) - #define STATS_POS BTN_POS(1,7), BTN_SIZE(2,1) - #define BACK_POS BTN_POS(3,7), BTN_SIZE(2,1) - - #define _INSET_POS(x,y,w,h) x + w/10, y, w - w/5, h - #define INSET_POS(pos) _INSET_POS(pos) + #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)) @@ -80,7 +76,9 @@ void AboutScreen::onRedraw(draw_mode_t) { #endif , OPT_CENTER, font_xlarge ); - cmd.tag(3); + #if BOTH(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) @@ -90,22 +88,24 @@ void AboutScreen::onRedraw(draw_mode_t) { , OPT_CENTER, font_medium); cmd.tag(0); draw_text_box(cmd, FW_INFO_POS, about_str, OPT_CENTER, font_medium); - draw_text_box(cmd, INSET_POS(LICENSE_POS), GET_TEXT_F(MSG_LICENSE), OPT_CENTER, font_tiny); + draw_text_box(cmd, LICENSE_POS, GET_TEXT_F(MSG_LICENSE), OPT_CENTER, font_tiny); - cmd.font(font_medium) - .colors(normal_btn) - .tag(2).button(STATS_POS, GET_TEXT_F(MSG_INFO_STATS_MENU)) - .colors(action_btn) - .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BACK)); + cmd.font(font_medium); + #if BOTH(PRINTCOUNTER, FTDI_STATISTICS_SCREEN) + 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) + #if BOTH(PRINTCOUNTER, FTDI_STATISTICS_SCREEN) case 2: GOTO_SCREEN(StatisticsScreen); break; #endif - #if ENABLED(TOUCH_UI_DEVELOPER_MENU) + #if BOTH(TOUCH_UI_DEVELOPER_MENU, FTDI_DEVELOPER_MENU) case 3: GOTO_SCREEN(DeveloperMenu); break; #endif default: return false; @@ -113,4 +113,4 @@ bool AboutScreen::onTouchEnd(uint8_t tag) { return true; } -#endif // TOUCH_UI_FTDI_EVE +#endif // FTDI_ABOUT_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.h new file mode 100644 index 000000000000..b9d94f08b3cf --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/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 FTDI_ABOUT_SCREEN +#define FTDI_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/generic/advanced_settings_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.cpp new file mode 100644 index 000000000000..a83cc075156c --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.cpp @@ -0,0 +1,155 @@ +/***************************** + * advance_settings_menu.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 FTDI_ADVANCED_SETTINGS_MENU + +using namespace FTDI; +using namespace ExtUI; +using namespace Theme; + +void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { + if (what & BACKGROUND) { + CommandProcessor cmd; + cmd.cmd(CLEAR_COLOR_RGB(Theme::bg_color)) + .cmd(CLEAR(true,true,true)); + } + + #if ENABLED(TOUCH_UI_PORTRAIT) + #if EITHER(HAS_MULTI_HOTEND, SENSORLESS_HOMING) + #define GRID_ROWS 9 + #else + #define GRID_ROWS 8 + #endif + #define GRID_COLS 2 + #define RESTORE_DEFAULTS_POS BTN_POS(1,1), BTN_SIZE(2,1) + #define DISPLAY_POS BTN_POS(1,2), BTN_SIZE(1,1) + #define INTERFACE_POS BTN_POS(2,2), BTN_SIZE(1,1) + #define ZPROBE_ZOFFSET_POS BTN_POS(1,3), BTN_SIZE(1,1) + #define STEPS_PER_MM_POS BTN_POS(2,3), BTN_SIZE(1,1) + #define FILAMENT_POS BTN_POS(1,4), BTN_SIZE(1,1) + #define VELOCITY_POS BTN_POS(2,4), BTN_SIZE(1,1) + #define TMC_CURRENT_POS BTN_POS(1,5), BTN_SIZE(1,1) + #define ACCELERATION_POS BTN_POS(2,5), BTN_SIZE(1,1) + #define ENDSTOPS_POS BTN_POS(1,6), BTN_SIZE(1,1) + #define JERK_POS BTN_POS(2,6), BTN_SIZE(1,1) + #define CASE_LIGHT_POS BTN_POS(1,7), BTN_SIZE(1,1) + #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) + #define BACK_POS BTN_POS(1,9), BTN_SIZE(2,1) + #else + #define BACK_POS BTN_POS(1,8), BTN_SIZE(2,1) + #endif + #else + #define GRID_ROWS 6 + #define GRID_COLS 3 + #define ZPROBE_ZOFFSET_POS BTN_POS(1,1), BTN_SIZE(1,1) + #define CASE_LIGHT_POS BTN_POS(1,4), BTN_SIZE(1,1) + #define STEPS_PER_MM_POS BTN_POS(2,1), BTN_SIZE(1,1) + #define TMC_CURRENT_POS BTN_POS(3,1), BTN_SIZE(1,1) + #define TMC_HOMING_THRS_POS BTN_POS(3,2), BTN_SIZE(1,1) + #define BACKLASH_POS BTN_POS(3,3), BTN_SIZE(1,1) + #define FILAMENT_POS BTN_POS(1,3), BTN_SIZE(1,1) + #define ENDSTOPS_POS BTN_POS(3,4), BTN_SIZE(1,1) + #define DISPLAY_POS BTN_POS(3,5), BTN_SIZE(1,1) + #define INTERFACE_POS BTN_POS(1,5), BTN_SIZE(2,1) + #define RESTORE_DEFAULTS_POS BTN_POS(1,6), BTN_SIZE(2,1) + #define VELOCITY_POS BTN_POS(2,2), BTN_SIZE(1,1) + #define ACCELERATION_POS BTN_POS(2,3), BTN_SIZE(1,1) + #define JERK_POS BTN_POS(2,4), BTN_SIZE(1,1) + #define OFFSETS_POS BTN_POS(1,2), BTN_SIZE(1,1) + #define BACK_POS BTN_POS(3,6), BTN_SIZE(1,1) + #endif + + if (what & FOREGROUND) { + CommandProcessor cmd; + cmd.colors(normal_btn) + .font(Theme::font_medium) + .enabled(ENABLED(HAS_BED_PROBE)) + .tag(2) .button(ZPROBE_ZOFFSET_POS, GET_TEXT_F(MSG_ZPROBE_ZOFFSET)) + .enabled(ENABLED(CASE_LIGHT_ENABLE)) + .tag(16).button(CASE_LIGHT_POS, GET_TEXT_F(MSG_CASE_LIGHT)) + .tag(3) .button(STEPS_PER_MM_POS, GET_TEXT_F(MSG_STEPS_PER_MM)) + .enabled(ENABLED(HAS_TRINAMIC_CONFIG)) + .tag(13).button(TMC_CURRENT_POS, GET_TEXT_F(MSG_TMC_CURRENT)) + .enabled(ENABLED(SENSORLESS_HOMING)) + .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)) + .tag(11).button(FILAMENT_POS, GET_TEXT_F(MSG_FILAMENT)) + .tag(12).button(ENDSTOPS_POS, GET_TEXT_F(MSG_LCD_ENDSTOPS)) + .tag(15).button(DISPLAY_POS, GET_TEXT_F(MSG_DISPLAY_MENU)) + .tag(9) .button(INTERFACE_POS, GET_TEXT_F(MSG_INTERFACE)) + .tag(10).button(RESTORE_DEFAULTS_POS, GET_TEXT_F(MSG_RESTORE_DEFAULTS)) + .tag(5) .button(VELOCITY_POS, GET_TEXT_F(MSG_VELOCITY)) + .tag(6) .button(ACCELERATION_POS, GET_TEXT_F(MSG_ACCELERATION)) + .tag(7) .button(JERK_POS, GET_TEXT_F(TERN(HAS_JUNCTION_DEVIATION, MSG_JUNCTION_DEVIATION, MSG_JERK))) + .enabled(ENABLED(BACKLASH_GCODE)) + .tag(8).button(BACKLASH_POS, GET_TEXT_F(MSG_BACKLASH)) + .colors(action_btn) + .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BUTTON_DONE)); + } +} + +bool AdvancedSettingsMenu::onTouchEnd(uint8_t tag) { + switch (tag) { + case 1: SaveSettingsDialogBox::promptToSaveSettings(); break; + #if HAS_BED_PROBE + case 2: GOTO_SCREEN(ZOffsetScreen); break; + #endif + case 3: GOTO_SCREEN(StepsScreen); break; + #if HAS_MULTI_HOTEND + case 4: GOTO_SCREEN(NozzleOffsetScreen); break; + #endif + case 5: GOTO_SCREEN(MaxVelocityScreen); break; + case 6: GOTO_SCREEN(DefaultAccelerationScreen); break; + case 7: GOTO_SCREEN(TERN(HAS_JUNCTION_DEVIATION, JunctionDeviationScreen, JerkScreen)); break; + #if ENABLED(BACKLASH_GCODE) + case 8: GOTO_SCREEN(BacklashCompensationScreen); break; + #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) + case 11: GOTO_SCREEN(FilamentMenu); break; + #endif + case 12: GOTO_SCREEN(EndstopStatesScreen); break; + #if HAS_TRINAMIC_CONFIG + case 13: GOTO_SCREEN(StepperCurrentScreen); break; + #endif + #if ENABLED(SENSORLESS_HOMING) + case 14: GOTO_SCREEN(StepperBumpSensitivityScreen); break; + #endif + case 15: GOTO_SCREEN(DisplayTuningScreen); break; + #if ENABLED(CASE_LIGHT_ENABLE) + case 16: GOTO_SCREEN(CaseLightScreen); break; + #endif + default: return false; + } + return true; +} + +#endif // FTDI_ADVANCED_SETTINGS_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.h new file mode 100644 index 000000000000..a7e34fe6fe6e --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.h @@ -0,0 +1,32 @@ +/*************************** + * advance_settings_menu.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 FTDI_ADVANCED_SETTINGS_MENU +#define FTDI_ADVANCED_SETTINGS_MENU_CLASS AdvancedSettingsMenu + +class AdvancedSettingsMenu : public BaseScreen, public CachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchEnd(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/alert_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/alert_dialog_box.cpp similarity index 79% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/alert_dialog_box.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/alert_dialog_box.cpp index bd09d2a5cd20..0d309bff7552 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/alert_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/alert_dialog_box.cpp @@ -17,22 +17,23 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" +#include "../screen_data.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) +#ifdef FTDI_ALERT_DIALOG_BOX -#include "screens.h" -#include "screen_data.h" +constexpr static AlertDialogBoxData &mydata = screen_data.AlertDialogBox; using namespace FTDI; using namespace Theme; void AlertDialogBox::onEntry() { BaseScreen::onEntry(); - sound.play(screen_data.AlertDialogBox.isError ? sad_trombone : twinkle, PLAY_ASYNCHRONOUS); + sound.play(mydata.isError ? sad_trombone : twinkle, PLAY_ASYNCHRONOUS); } void AlertDialogBox::onRedraw(draw_mode_t what) { @@ -42,18 +43,18 @@ void AlertDialogBox::onRedraw(draw_mode_t what) { } template -void AlertDialogBox::show(const T message) { +void AlertDialogBox::show(T message) { drawMessage(message); storeBackground(); - screen_data.AlertDialogBox.isError = false; + mydata.isError = false; GOTO_SCREEN(AlertDialogBox); } template -void AlertDialogBox::showError(const T message) { +void AlertDialogBox::showError(T message) { drawMessage(message); storeBackground(); - screen_data.AlertDialogBox.isError = true; + mydata.isError = true; GOTO_SCREEN(AlertDialogBox); } @@ -63,8 +64,8 @@ void AlertDialogBox::hide() { } template void AlertDialogBox::show(const char *); -template void AlertDialogBox::show(const progmem_str); +template void AlertDialogBox::show(progmem_str); template void AlertDialogBox::showError(const char *); -template void AlertDialogBox::showError(const progmem_str); +template void AlertDialogBox::showError(progmem_str); -#endif // TOUCH_UI_FTDI_EVE +#endif // FTDI_ALERT_DIALOG_BOX diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/alert_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/alert_dialog_box.h new file mode 100644 index 000000000000..0186acf7a088 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/alert_dialog_box.h @@ -0,0 +1,39 @@ +/********************** + * alert_dialog_box.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 FTDI_ALERT_DIALOG_BOX +#define FTDI_ALERT_DIALOG_BOX_CLASS AlertDialogBox + +struct AlertDialogBoxData { + bool isError; +}; + +class AlertDialogBox : public DialogBoxBaseClass, public CachedScreen { + public: + static void onEntry(); + static void onRedraw(draw_mode_t); + template static void show(T); + template static void showError(T); + static void hide(); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/backlash_compensation_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/backlash_compensation_screen.cpp similarity index 96% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/backlash_compensation_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/backlash_compensation_screen.cpp index 8d65518455dd..c3fcb25f4385 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/backlash_compensation_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/backlash_compensation_screen.cpp @@ -17,14 +17,13 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" -#if BOTH(TOUCH_UI_FTDI_EVE, BACKLASH_GCODE) - -#include "screens.h" +#ifdef FTDI_BACKLASH_COMP_SCREEN using namespace FTDI; using namespace ExtUI; @@ -73,4 +72,4 @@ bool BacklashCompensationScreen::onTouchHeld(uint8_t tag) { return true; } -#endif // TOUCH_UI_FTDI_EVE +#endif // FTDI_BACKLASH_COMP_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/backlash_compensation_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/backlash_compensation_screen.h new file mode 100644 index 000000000000..b9e46eb27f38 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/backlash_compensation_screen.h @@ -0,0 +1,32 @@ +/********************************** + * backlash_compensation_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 FTDI_BACKLASH_COMP_SCREEN +#define FTDI_BACKLASH_COMP_SCREEN_CLASS BacklashCompensationScreen + +class BacklashCompensationScreen : public BaseNumericAdjustmentScreen, public CachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchHeld(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_numeric_adjustment_screen.cpp similarity index 90% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_numeric_adjustment_screen.cpp index 1c4ef594bb4e..d0ba74721cc4 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_numeric_adjustment_screen.cpp @@ -17,20 +17,21 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" +#include "../screen_data.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) - -#include "screens.h" -#include "screen_data.h" +#ifdef FTDI_BASE_NUMERIC_ADJ_SCREEN using namespace FTDI; using namespace Theme; -#ifdef TOUCH_UI_PORTRAIT +constexpr static BaseNumericAdjustmentScreenData &mydata = screen_data.BaseNumericAdjustmentScreen; + +#if ENABLED(TOUCH_UI_PORTRAIT) #define GRID_COLS 13 #define GRID_ROWS 10 #define LAYOUT_FONT font_small @@ -50,15 +51,17 @@ BaseNumericAdjustmentScreen::widgets_t::widgets_t(draw_mode_t what) : _what(what .cmd(COLOR_RGB(bg_text_enabled)) .tag(0); } + else + cmd.colors(normal_btn); cmd.font(font_medium); _button(cmd, 1, - #ifdef TOUCH_UI_PORTRAIT + #if ENABLED(TOUCH_UI_PORTRAIT) BTN_POS(1,10), BTN_SIZE(13,1), #else BTN_POS(15,7), BTN_SIZE(4,1), #endif - GET_TEXT_F(MSG_BACK), true, true + GET_TEXT_F(MSG_BUTTON_DONE), true, true ); _line = 1; @@ -116,8 +119,8 @@ void BaseNumericAdjustmentScreen::widgets_t::_button(CommandProcessor &cmd, uint BaseNumericAdjustmentScreen::widgets_t &BaseNumericAdjustmentScreen::widgets_t::precision(uint8_t decimals, precision_default_t initial) { _decimals = decimals; - if (screen_data.BaseNumericAdjustmentScreen.increment == 0) { - screen_data.BaseNumericAdjustmentScreen.increment = 243 + (initial - DEFAULT_LOWEST) - _decimals; + if (mydata.increment == 0) { + mydata.increment = 243 + (initial - DEFAULT_LOWEST) - _decimals; } return *this; } @@ -129,7 +132,7 @@ void BaseNumericAdjustmentScreen::widgets_t::heading(progmem_str label) { cmd.font(font_medium) .tag(0) .text( - #ifdef TOUCH_UI_PORTRAIT + #if ENABLED(TOUCH_UI_PORTRAIT) BTN_POS(1, _line), BTN_SIZE(12,1), #else BTN_POS(5, _line), BTN_SIZE(8,1), @@ -141,7 +144,7 @@ void BaseNumericAdjustmentScreen::widgets_t::heading(progmem_str label) { _line++; } -#ifdef TOUCH_UI_PORTRAIT +#if ENABLED(TOUCH_UI_PORTRAIT) #ifdef TOUCH_UI_800x480 #undef EDGE_R #define EDGE_R 20 @@ -154,7 +157,7 @@ void BaseNumericAdjustmentScreen::widgets_t::heading(progmem_str label) { void BaseNumericAdjustmentScreen::widgets_t::_draw_increment_btn(CommandProcessor &cmd, uint8_t, const uint8_t tag) { const char *label = PSTR("?"); uint8_t pos; - uint8_t & increment = screen_data.BaseNumericAdjustmentScreen.increment; + uint8_t & increment = mydata.increment; if (increment == 0) { increment = tag; // Set the default value to be the first. @@ -172,7 +175,7 @@ void BaseNumericAdjustmentScreen::widgets_t::_draw_increment_btn(CommandProcesso const bool highlight = (_what & FOREGROUND) && (increment == tag); switch (pos) { - #ifdef TOUCH_UI_PORTRAIT + #if ENABLED(TOUCH_UI_PORTRAIT) case 0: _button(cmd, tag, BTN_POS(5,_line), BTN_SIZE(2,1), progmem_str(label), true, highlight); break; case 1: _button(cmd, tag, BTN_POS(7,_line), BTN_SIZE(2,1), progmem_str(label), true, highlight); break; case 2: _button(cmd, tag, BTN_POS(9,_line), BTN_SIZE(2,1), progmem_str(label), true, highlight); break; @@ -192,7 +195,7 @@ void BaseNumericAdjustmentScreen::widgets_t::increments() { if (_what & BACKGROUND) { _button_style(cmd, TEXT_LABEL); cmd.tag(0).text( - #ifdef TOUCH_UI_PORTRAIT + #if ENABLED(TOUCH_UI_PORTRAIT) BTN_POS(1, _line), BTN_SIZE(4,1), #else BTN_POS(15, 1), BTN_SIZE(4,1), @@ -205,7 +208,7 @@ void BaseNumericAdjustmentScreen::widgets_t::increments() { _draw_increment_btn(cmd, _line+1, 244 - _decimals); _draw_increment_btn(cmd, _line+1, 243 - _decimals); - #ifdef TOUCH_UI_PORTRAIT + #if ENABLED(TOUCH_UI_PORTRAIT) _line++; #endif } @@ -219,7 +222,7 @@ void BaseNumericAdjustmentScreen::widgets_t::adjuster_sram_val(uint8_t tag, prog .font(font_small) .text( BTN_POS(1,_line), BTN_SIZE(4,1), label); _button_style(cmd, TEXT_AREA); - cmd.fgcolor(_color).button( BTN_POS(5,_line), BTN_SIZE(5,1), F(""), OPT_FLAT); + cmd.fgcolor(_color).button(BTN_POS(5,_line), BTN_SIZE(5,1), F(""), OPT_FLAT); } cmd.font(font_medium); @@ -282,7 +285,7 @@ void BaseNumericAdjustmentScreen::widgets_t::text_field(uint8_t tag, progmem_str _button_style(cmd, TEXT_AREA); cmd.fgcolor(_color) .tag(tag) - .button( BTN_POS(5,_line), BTN_SIZE(9,1), F(""), OPT_FLAT); + .button(BTN_POS(5,_line), BTN_SIZE(9,1), F(""), OPT_FLAT); } if (_what & FOREGROUND) { @@ -308,7 +311,7 @@ void BaseNumericAdjustmentScreen::widgets_t::toggle(uint8_t tag, progmem_str lab _button_style(cmd, TEXT_LABEL); cmd.font(font_small) .text( - #ifdef TOUCH_UI_PORTRAIT + #if ENABLED(TOUCH_UI_PORTRAIT) BTN_POS(1, _line), BTN_SIZE( 8,1), #else BTN_POS(1, _line), BTN_SIZE(10,1), @@ -318,12 +321,12 @@ void BaseNumericAdjustmentScreen::widgets_t::toggle(uint8_t tag, progmem_str lab } if (_what & FOREGROUND) { - _button_style(cmd, BTN_TOGGLE); + _button_style(cmd, is_enabled ? BTN_TOGGLE : BTN_DISABLED); cmd.tag(is_enabled ? tag : 0) .enabled(is_enabled) .font(font_small) .toggle2( - #ifdef TOUCH_UI_PORTRAIT + #if ENABLED(TOUCH_UI_PORTRAIT) BTN_POS( 9,_line), BTN_SIZE(5,1), #else BTN_POS(10,_line), BTN_SIZE(4,1), @@ -358,7 +361,7 @@ void BaseNumericAdjustmentScreen::widgets_t::home_buttons(uint8_t tag) { } void BaseNumericAdjustmentScreen::onEntry() { - screen_data.BaseNumericAdjustmentScreen.increment = 0; // This will force the increment to be picked while drawing. + mydata.increment = 0; // This will force the increment to be picked while drawing. BaseScreen::onEntry(); CommandProcessor cmd; cmd.set_button_style_callback(nullptr); @@ -367,14 +370,14 @@ void BaseNumericAdjustmentScreen::onEntry() { bool BaseNumericAdjustmentScreen::onTouchEnd(uint8_t tag) { switch (tag) { case 1: GOTO_PREVIOUS(); return true; - case 240 ... 245: screen_data.BaseNumericAdjustmentScreen.increment = tag; break; + case 240 ... 245: mydata.increment = tag; break; default: return current_screen.onTouchHeld(tag); } return true; } float BaseNumericAdjustmentScreen::getIncrement() { - switch (screen_data.BaseNumericAdjustmentScreen.increment) { + switch (mydata.increment) { case 240: return 0.001; case 241: return 0.01; case 242: return 0.1; @@ -385,4 +388,4 @@ float BaseNumericAdjustmentScreen::getIncrement() { } } -#endif // TOUCH_UI_FTDI_EVE +#endif // FTDI_BASE_NUMERIC_ADJ_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_numeric_adjustment_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_numeric_adjustment_screen.h new file mode 100644 index 000000000000..c097752674a8 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_numeric_adjustment_screen.h @@ -0,0 +1,87 @@ +/************************************ + * base_numeric_adjustment_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 FTDI_BASE_NUMERIC_ADJ_SCREEN +#define FTDI_BASE_NUMERIC_ADJ_SCREEN_CLASS BaseNumericAdjustmentScreen + +struct BaseNumericAdjustmentScreenData { + uint8_t increment; +}; + +class BaseNumericAdjustmentScreen : public BaseScreen { + public: + enum precision_default_t { + DEFAULT_LOWEST, + DEFAULT_MIDRANGE, + DEFAULT_HIGHEST + }; + + protected: + class widgets_t { + private: + draw_mode_t _what; + uint8_t _line; + uint32_t _color; + uint8_t _decimals; + progmem_str _units; + enum style_t { + BTN_NORMAL, + BTN_ACTION, + BTN_TOGGLE, + BTN_DISABLED, + TEXT_AREA, + TEXT_LABEL + } _style; + + protected: + void _draw_increment_btn(CommandProcessor &, uint8_t line, const uint8_t tag); + void _button(CommandProcessor &, uint8_t tag, int16_t x, int16_t y, int16_t w, int16_t h, progmem_str, bool enabled = true, bool highlight = false); + void _button_style(CommandProcessor &cmd, style_t style); + public: + widgets_t(draw_mode_t); + + widgets_t &color(uint32_t color) {_color = color; return *this;} + widgets_t &units(progmem_str units) {_units = units; return *this;} + widgets_t &draw_mode(draw_mode_t what) {_what = what; return *this;} + widgets_t &precision(uint8_t decimals, precision_default_t = DEFAULT_HIGHEST); + + void heading (progmem_str label); + void adjuster_sram_val (uint8_t tag, progmem_str label, const char *value, bool is_enabled = true); + void adjuster (uint8_t tag, progmem_str label, const char *value, bool is_enabled = true); + void adjuster (uint8_t tag, progmem_str label, float value=0, bool is_enabled = true); + void button (uint8_t tag, progmem_str label, bool is_enabled = true); + void text_field (uint8_t tag, progmem_str label, const char *value, bool is_enabled = true); + void two_buttons (uint8_t tag1, progmem_str label1, + uint8_t tag2, progmem_str label2, bool is_enabled = true); + void toggle (uint8_t tag, progmem_str label, bool value, bool is_enabled = true); + void home_buttons (uint8_t tag); + void increments (); + }; + + static float getIncrement(); + + public: + static void onEntry(); + static bool onTouchEnd(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_screen.cpp similarity index 90% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_screen.cpp index c84dd45f004f..0a8bebea3c9d 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_screen.cpp @@ -17,14 +17,13 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) - -#include "screens.h" +#ifdef FTDI_BASE_SCREEN using namespace FTDI; using namespace Theme; @@ -46,7 +45,7 @@ bool BaseScreen::buttonStyleCallback(CommandProcessor &cmd, uint8_t tag, uint8_t return false; } - #if LCD_TIMEOUT_TO_STATUS > 0 + #if SCREENS_CAN_TIME_OUT if (EventLoop::get_pressed_tag() != 0) { reset_menu_timeout(); } @@ -66,7 +65,7 @@ bool BaseScreen::buttonStyleCallback(CommandProcessor &cmd, uint8_t tag, uint8_t } void BaseScreen::onIdle() { - #if LCD_TIMEOUT_TO_STATUS > 0 + #if SCREENS_CAN_TIME_OUT if ((millis() - last_interaction) > LCD_TIMEOUT_TO_STATUS) { reset_menu_timeout(); #if ENABLED(TOUCH_UI_DEBUG) @@ -78,13 +77,11 @@ void BaseScreen::onIdle() { } void BaseScreen::reset_menu_timeout() { - #if LCD_TIMEOUT_TO_STATUS > 0 - last_interaction = millis(); - #endif + TERN_(SCREENS_CAN_TIME_OUT, last_interaction = millis()); } -#if LCD_TIMEOUT_TO_STATUS > 0 +#if SCREENS_CAN_TIME_OUT uint32_t BaseScreen::last_interaction; #endif -#endif // TOUCH_UI_FTDI_EVE +#endif // FTDI_BASE_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_screen.h new file mode 100644 index 000000000000..030fa51a2aaf --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_screen.h @@ -0,0 +1,43 @@ +/***************** + * base_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 FTDI_BASE_SCREEN +#define FTDI_BASE_SCREEN_CLASS BaseScreen + +class BaseScreen : public UIScreen { + protected: + #if SCREENS_CAN_TIME_OUT + static uint32_t last_interaction; + #endif + + static bool buttonIsPressed(uint8_t tag); + + public: + static bool buttonStyleCallback(CommandProcessor &, uint8_t, uint8_t &, uint16_t &, bool); + + static void reset_menu_timeout(); + + static void onEntry(); + static void onIdle(); +}; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_base.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_base.cpp new file mode 100644 index 000000000000..14f219645337 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_base.cpp @@ -0,0 +1,224 @@ +/********************* + * bed_mesh_base.cpp * + *********************/ + +/**************************************************************************** + * Written By Marcio Teixeira 2020 * + * * + * 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 FTDI_BED_MESH_BASE + +using namespace FTDI; + +void BedMeshBase::_drawMesh(CommandProcessor &cmd, int16_t x, int16_t y, int16_t w, int16_t h, uint8_t opts, float autoscale_max, uint8_t highlightedTag, mesh_getter_ptr func, void *data) { + constexpr uint8_t rows = GRID_MAX_POINTS_Y; + constexpr uint8_t cols = GRID_MAX_POINTS_X; + + #define VALUE(X,Y) (func ? func(X,Y,data) : 0) + #define ISVAL(X,Y) (func ? !isnan(VALUE(X,Y)) : true) + #define HEIGHT(X,Y) (ISVAL(X,Y) ? (VALUE(X,Y) - val_min) * scale_z : 0) + + // Compute the mean, min and max for the points + + float val_mean = 0; + float val_max = -INFINITY; + float val_min = INFINITY; + uint8_t val_cnt = 0; + + if (opts & USE_AUTOSCALE) { + for (uint8_t y = 0; y < rows; y++) { + for (uint8_t x = 0; x < cols; x++) { + if (ISVAL(x,y)) { + const float val = VALUE(x,y); + val_mean += val; + val_max = max(val_max, val); + val_min = min(val_min, val); + val_cnt++; + } + } + } + } + if (val_cnt) + val_mean /= val_cnt; + else { + val_mean = 0; + val_min = 0; + val_max = 0; + } + + const float scale_z = ((val_max == val_min) ? 1 : 1/(val_max - val_min)) * autoscale_max; + + /** + * The 3D points go through a 3D graphics pipeline to determine the final 2D point on the screen. + * This is written out as a stack of macros that each apply an affine transformation to the point. + * At compile time, the compiler should be able to reduce these expressions. + * + * The last transformation in the chain (TRANSFORM_5) is initially set to a no-op so we can measure + * the dimensions of the grid, but is later replaced with a scaling transform that scales the grid + * to fit. + */ + + #define TRANSFORM_5(X,Y,Z) (X), (Y) // No transform + #define TRANSFORM_4(X,Y,Z) TRANSFORM_5((X)/(Z),(Y)/-(Z), 0) // Perspective + #define TRANSFORM_3(X,Y,Z) TRANSFORM_4((X), (Z), (Y)) // Swap Z and Y + #define TRANSFORM_2(X,Y,Z) TRANSFORM_3((X), (Y) + 2.5, (Z) - 1) // Translate + #define TRANSFORM(X,Y,Z) TRANSFORM_2(float(X)/(cols-1) - 0.5, float(Y)/(rows-1) - 0.5, (Z)) // Normalize + + // Compute the bounding box for the grid prior to scaling. Do this at compile-time by + // transforming the four corner points via the transformation equations and finding + // the min and max for each axis. + + constexpr float bounds[][3] = {{TRANSFORM(0 , 0 , 0)}, + {TRANSFORM(cols-1, 0 , 0)}, + {TRANSFORM(0 , rows-1, 0)}, + {TRANSFORM(cols-1, rows-1, 0)}}; + #define APPLY(FUNC, AXIS) FUNC(FUNC(bounds[0][AXIS], bounds[1][AXIS]), FUNC(bounds[2][AXIS], bounds[3][AXIS])) + constexpr float grid_x = APPLY(min,0); + constexpr float grid_y = APPLY(min,1); + constexpr float grid_w = APPLY(max,0) - grid_x; + constexpr float grid_h = APPLY(max,1) - grid_y; + constexpr float grid_cx = grid_x + grid_w/2; + constexpr float grid_cy = grid_y + grid_h/2; + + // Figure out scale and offset such that the grid fits within the rectangle given by (x,y,w,h) + + const float scale_x = float(w)/grid_w; + const float scale_y = float(h)/grid_h; + const float center_x = x + w/2; + const float center_y = y + h/2; + + // Now replace the last transformation in the chain with a scaling operation. + + #undef TRANSFORM_5 + #define TRANSFORM_6(X,Y,Z) (X)*16, (Y)*16 // Scale to 1/16 pixel units + #define TRANSFORM_5(X,Y,Z) TRANSFORM_6( center_x + ((X) - grid_cx) * scale_x, \ + center_y + ((Y) - grid_cy) * scale_y, 0) // Scale to bounds + + // Draw the grid + + const uint16_t basePointSize = min(w,h) / max(cols,rows); + + cmd.cmd(SAVE_CONTEXT()) + .cmd(TAG_MASK(false)) + .cmd(SAVE_CONTEXT()); + + for (uint8_t y = 0; y < rows; y++) { + for (uint8_t x = 0; x < cols; x++) { + if (ISVAL(x,y)) { + const bool hasLeftSegment = x < cols - 1 && ISVAL(x+1,y); + const bool hasRightSegment = y < rows - 1 && ISVAL(x,y+1); + if (hasLeftSegment || hasRightSegment) { + cmd.cmd(BEGIN(LINE_STRIP)); + if (hasLeftSegment) cmd.cmd(VERTEX2F(TRANSFORM(x + 1, y , HEIGHT(x + 1, y )))); + cmd.cmd( VERTEX2F(TRANSFORM(x , y , HEIGHT(x , y )))); + if (hasRightSegment) cmd.cmd(VERTEX2F(TRANSFORM(x , y + 1, HEIGHT(x , y + 1)))); + } + } + } + + if (opts & USE_POINTS) { + const float sq_min = sq(val_min - val_mean); + const float sq_max = sq(val_max - val_mean); + cmd.cmd(POINT_SIZE(basePointSize * 2)); + cmd.cmd(BEGIN(POINTS)); + for (uint8_t x = 0; x < cols; x++) { + if (ISVAL(x,y)) { + if (opts & USE_COLORS) { + const float val_dev = sq(VALUE(x, y) - val_mean); + float r = 0, b = 0; + if (sq_min != sq_max) { + if (VALUE(x, y) < 0) + r = val_dev / sq_min; + else + b = val_dev / sq_max; + } + #ifdef BED_MESH_POINTS_GRAY + cmd.cmd(COLOR_RGB((1.0f - b + r) * 0x7F, (1.0f - b - r) * 0x7F, (1.0f - r + b) * 0x7F)); + #else + cmd.cmd(COLOR_RGB((1.0f - b) * 0xFF, (1.0f - b - r) * 0xFF, (1.0f - r) * 0xFF)); + #endif + } + cmd.cmd(VERTEX2F(TRANSFORM(x, y, HEIGHT(x, y)))); + } + } + if (opts & USE_COLORS) { + cmd.cmd(RESTORE_CONTEXT()) + .cmd(SAVE_CONTEXT()); + } + } + } + cmd.cmd(RESTORE_CONTEXT()) + .cmd(TAG_MASK(true)); + + if (opts & USE_TAGS) { + cmd.cmd(COLOR_MASK(false, false, false, false)) + .cmd(POINT_SIZE(basePointSize * 10)) + .cmd(BEGIN(POINTS)); + for (uint8_t y = 0; y < rows; y++) { + for (uint8_t x = 0; x < cols; x++) { + const uint8_t tag = pointToTag(x, y); + cmd.tag(tag).cmd(VERTEX2F(TRANSFORM(x, y, HEIGHT(x, y)))); + } + } + cmd.cmd(COLOR_MASK(true, true, true, true)); + } + + if (opts & USE_HIGHLIGHT) { + const uint8_t tag = highlightedTag; + xy_uint8_t pt; + if (tagToPoint(tag, pt)) { + cmd.cmd(COLOR_A(128)) + .cmd(POINT_SIZE(basePointSize * 6)) + .cmd(BEGIN(POINTS)) + .tag(tag).cmd(VERTEX2F(TRANSFORM(pt.x, pt.y, HEIGHT(pt.x, pt.y)))); + } + } + cmd.cmd(END()); + cmd.cmd(RESTORE_CONTEXT()); +} + +uint8_t BedMeshBase::pointToTag(uint8_t x, uint8_t y) { + return x >= 0 && x < GRID_MAX_POINTS_X && y >= 0 && y < GRID_MAX_POINTS_Y ? y * (GRID_MAX_POINTS_X) + x + 10 : 0; +} + +bool BedMeshBase::tagToPoint(uint8_t tag, xy_uint8_t &pt) { + if (tag < 10) return false; + pt.x = (tag - 10) % (GRID_MAX_POINTS_X); + pt.y = (tag - 10) / (GRID_MAX_POINTS_X); + return true; +} + +void BedMeshBase::drawMeshBackground(CommandProcessor &cmd, int16_t x, int16_t y, int16_t w, int16_t h) { + cmd.cmd(COLOR_RGB(Theme::bed_mesh_shadow_rgb)); + _drawMesh(cmd, x, y, w, h, USE_POINTS | USE_TAGS, 0.1, 0, nullptr, nullptr); +} + +void BedMeshBase::drawMeshForeground(CommandProcessor &cmd, int16_t x, int16_t y, int16_t w, int16_t h, mesh_getter_ptr func, void *data, uint8_t highlightedTag, float progress) { + constexpr float autoscale_max_amplitude = 0.03; + + cmd.cmd(COLOR_RGB(Theme::bed_mesh_lines_rgb)); + _drawMesh(cmd, x, y, w, h, + USE_POINTS | USE_HIGHLIGHT | USE_AUTOSCALE | (progress > 0.95 ? USE_COLORS : 0), + autoscale_max_amplitude * progress, + highlightedTag, + func, data + ); +} + +#endif // FTDI_BED_MESH_BASE diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_base.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_base.h new file mode 100644 index 000000000000..7cc92793febf --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_base.h @@ -0,0 +1,46 @@ +/******************* + * bed_mesh_base.h * + *******************/ + +/**************************************************************************** + * Written By Marcio Teixeira 2020 * + * * + * 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 FTDI_BED_MESH_BASE + +class BedMeshBase : public BaseScreen { + protected: + typedef float (*mesh_getter_ptr)(uint8_t x, uint8_t y, void *data); + + private: + enum MeshOpts { + USE_POINTS = 0x01, + USE_COLORS = 0x02, + USE_TAGS = 0x04, + USE_HIGHLIGHT = 0x08, + USE_AUTOSCALE = 0x10 + }; + + static void _drawMesh(CommandProcessor &, int16_t x, int16_t y, int16_t w, int16_t h, uint8_t opts, float autoscale_max, uint8_t highlightedTag, mesh_getter_ptr func, void *data); + + protected: + static void drawMeshForeground(CommandProcessor &cmd, int16_t x, int16_t y, int16_t w, int16_t h, mesh_getter_ptr func, void *data, uint8_t highlightedTag = 0, float progress = 1.0); + static void drawMeshBackground(CommandProcessor &cmd, int16_t x, int16_t y, int16_t w, int16_t h); + static uint8_t pointToTag(uint8_t x, uint8_t y); + static bool tagToPoint(uint8_t tag, xy_uint8_t &pt); +}; 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 new file mode 100644 index 000000000000..c7d0cc3f7314 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp @@ -0,0 +1,200 @@ +/**************************** + * bed_mesh_edit_screen.cpp * + ****************************/ + +/**************************************************************************** + * Written By Marcio Teixeira 2020 * + * * + * 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 FTDI_BED_MESH_EDIT_SCREEN + +using namespace FTDI; +using namespace Theme; +using namespace ExtUI; + +constexpr static BedMeshEditScreenData &mydata = screen_data.BedMeshEditScreen; +constexpr static float gaugeThickness = 0.1; + +#if ENABLED(TOUCH_UI_PORTRAIT) + #define GRID_COLS 3 + #define GRID_ROWS 10 + + #define MESH_POS BTN_POS(1, 2), BTN_SIZE(3,5) + #define MESSAGE_POS BTN_POS(1, 7), BTN_SIZE(3,1) + #define Z_LABEL_POS BTN_POS(1, 8), BTN_SIZE(1,1) + #define Z_VALUE_POS BTN_POS(2, 8), BTN_SIZE(2,1) + #define BACK_POS BTN_POS(1,10), BTN_SIZE(2,1) + #define SAVE_POS BTN_POS(3,10), BTN_SIZE(1,1) +#else + #define GRID_COLS 5 + #define GRID_ROWS 5 + + #define MESH_POS BTN_POS(1,1), BTN_SIZE(3,5) + #define MESSAGE_POS BTN_POS(4,1), BTN_SIZE(2,1) + #define Z_LABEL_POS BTN_POS(4,2), BTN_SIZE(2,1) + #define Z_VALUE_POS BTN_POS(4,3), BTN_SIZE(2,1) + #define BACK_POS BTN_POS(4,5), BTN_SIZE(1,1) + #define SAVE_POS BTN_POS(5,5), BTN_SIZE(1,1) +#endif + +constexpr uint8_t NONE = 255; + +static float meshGetter(uint8_t x, uint8_t y, void*) { + xy_uint8_t pos; + pos.x = x; + pos.y = y; + return ExtUI::getMeshPoint(pos) + (mydata.highlight.x != NONE && mydata.highlight == pos ? mydata.zAdjustment : 0); +} + +void BedMeshEditScreen::onEntry() { + mydata.needSave = false; + mydata.highlight.x = NONE; + mydata.zAdjustment = 0; + mydata.savedMeshLevelingState = ExtUI::getLevelingActive(); + mydata.savedEndstopState = ExtUI::getSoftEndstopState(); + makeMeshValid(); + BaseScreen::onEntry(); +} + +void BedMeshEditScreen::makeMeshValid() { + bed_mesh_t &mesh = ExtUI::getMeshArray(); + GRID_LOOP(x, y) { + if (isnan(mesh[x][y])) mesh[x][y] = 0; + } +} + +void BedMeshEditScreen::onExit() { + ExtUI::setLevelingActive(mydata.savedMeshLevelingState); + ExtUI::setSoftEndstopState(mydata.savedEndstopState); +} + +float BedMeshEditScreen::getHighlightedValue() { + const float val = ExtUI::getMeshPoint(mydata.highlight); + return (isnan(val) ? 0 : val) + mydata.zAdjustment; +} + +void BedMeshEditScreen::setHighlightedValue(float value) { + ExtUI::setMeshPoint(mydata.highlight, value); +} + +void BedMeshEditScreen::moveToHighlightedValue() { + if (ExtUI::getMeshValid()) { + ExtUI::setLevelingActive(true); + ExtUI::setSoftEndstopState(false); + ExtUI::moveToMeshPoint(mydata.highlight, gaugeThickness + mydata.zAdjustment); + } +} + +void BedMeshEditScreen::adjustHighlightedValue(float increment) { + if (mydata.highlight.x != NONE) { + mydata.zAdjustment += increment; + moveToHighlightedValue(); + mydata.needSave = true; + } +} + +void BedMeshEditScreen::saveAdjustedHighlightedValue() { + if (mydata.zAdjustment && mydata.highlight.x != -1) { + setHighlightedValue(getHighlightedValue()); + mydata.zAdjustment = 0; + } +} + +bool BedMeshEditScreen::changeHighlightedValue(uint8_t tag) { + saveAdjustedHighlightedValue(); + if (tagToPoint(tag, mydata.highlight)) { + moveToHighlightedValue(); + return true; + } + return false; +} + +void BedMeshEditScreen::drawHighlightedPointValue() { + CommandProcessor cmd; + cmd.font(Theme::font_medium) + .cmd(COLOR_RGB(bg_text_enabled)) + .text(Z_LABEL_POS, GET_TEXT_F(MSG_MESH_EDIT_Z)) + .colors(normal_btn) + .font(font_small); + if (mydata.highlight.x != NONE) + draw_adjuster(cmd, Z_VALUE_POS, 3, getHighlightedValue(), GET_TEXT_F(MSG_UNITS_MM), 4, 3); + cmd.colors(mydata.needSave ? normal_btn : action_btn) + .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BUTTON_DONE)) + .colors(mydata.needSave ? action_btn : normal_btn) + .enabled(mydata.needSave) + .tag(2).button(SAVE_POS, GET_TEXT_F(MSG_TOUCHMI_SAVE)); +} + +void BedMeshEditScreen::onRedraw(draw_mode_t what) { + #define _INSET_POS(x,y,w,h) x + min(w,h)/10, y + min(w,h)/10, w - min(w,h)/5, h - min(w,h)/5 + #define INSET_POS(pos) _INSET_POS(pos) + + CommandProcessor cmd; + + if (what & BACKGROUND) { + cmd.cmd(CLEAR_COLOR_RGB(bg_color)) + .cmd(CLEAR(true,true,true)); + drawMeshBackground(cmd, INSET_POS(MESH_POS)); + } + + if (what & FOREGROUND) { + drawHighlightedPointValue(); + drawMeshForeground(cmd, INSET_POS(MESH_POS), meshGetter, nullptr, pointToTag(mydata.highlight.x,mydata.highlight.y)); + } +} + +bool BedMeshEditScreen::onTouchHeld(uint8_t tag) { + constexpr float increment = 0.01; + switch (tag) { + case 3: adjustHighlightedValue(-increment); return true; + case 4: adjustHighlightedValue( increment); return true; + } + return false; +} + +bool BedMeshEditScreen::onTouchEnd(uint8_t tag) { + switch (tag) { + case 1: + // On Cancel, reload saved mesh, discarding changes + GOTO_PREVIOUS(); + injectCommands_P(PSTR("G29 L1")); + return true; + case 2: + saveAdjustedHighlightedValue(); + injectCommands_P(PSTR("G29 S1")); + mydata.needSave = false; + return true; + case 3: + case 4: + return onTouchHeld(tag); + default: return changeHighlightedValue(tag); + } + return true; +} + +void BedMeshEditScreen::show() { + // On entry, always home (to account for possible Z offset changes) and save current mesh + SpinnerDialogBox::enqueueAndWait(F("G28\nG29 S1")); + // After the spinner, go to this screen. + current_screen.forget(); + PUSH_SCREEN(BedMeshEditScreen); +} + +#endif // FTDI_BED_MESH_EDIT_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.h new file mode 100644 index 000000000000..45a53f0f1372 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.h @@ -0,0 +1,50 @@ +/************************** + * bed_mesh_edit_screen.h * + *************************/ + +/**************************************************************************** + * Written By Marcio Teixeira 2020 * + * * + * 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 FTDI_BED_MESH_EDIT_SCREEN +#define FTDI_BED_MESH_EDIT_SCREEN_CLASS BedMeshEditScreen + +struct BedMeshEditScreenData { + bool needSave, savedMeshLevelingState, savedEndstopState; + xy_uint8_t highlight; + float zAdjustment; +}; + +class BedMeshEditScreen : public BedMeshBase, public CachedScreen { + private: + static void makeMeshValid(); + static float getHighlightedValue(); + static void setHighlightedValue(float value); + static void moveToHighlightedValue(); + static void adjustHighlightedValue(float increment); + static void saveAdjustedHighlightedValue(); + static bool changeHighlightedValue(uint8_t tag); + static void drawHighlightedPointValue(); + public: + static void onEntry(); + static void onExit(); + static void onRedraw(draw_mode_t); + static bool onTouchHeld(uint8_t tag); + static bool onTouchEnd(uint8_t tag); + static void show(); +}; 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 new file mode 100644 index 000000000000..552cd831ea17 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.cpp @@ -0,0 +1,171 @@ +/**************************** + * bed_mesh_view_screen.cpp * + ****************************/ + +/**************************************************************************** + * Written By Marcio Teixeira 2020 * + * * + * 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 FTDI_BED_MESH_VIEW_SCREEN + +using namespace FTDI; +using namespace Theme; +using namespace ExtUI; + +constexpr static BedMeshViewScreenData &mydata = screen_data.BedMeshViewScreen; +constexpr static float gaugeThickness = 0.25; + +#if ENABLED(TOUCH_UI_PORTRAIT) + #define GRID_COLS 3 + #define GRID_ROWS 10 + + #define MESH_POS BTN_POS(1, 2), BTN_SIZE(3,5) + #define MESSAGE_POS BTN_POS(1, 7), BTN_SIZE(3,1) + #define Z_LABEL_POS BTN_POS(1, 8), BTN_SIZE(1,1) + #define Z_VALUE_POS BTN_POS(2, 8), BTN_SIZE(2,1) + #define OKAY_POS BTN_POS(1,10), BTN_SIZE(3,1) +#else + #define GRID_COLS 5 + #define GRID_ROWS 5 + + #define MESH_POS BTN_POS(1,1), BTN_SIZE(3,5) + #define MESSAGE_POS BTN_POS(4,1), BTN_SIZE(2,1) + #define Z_LABEL_POS BTN_POS(4,2), BTN_SIZE(2,1) + #define Z_VALUE_POS BTN_POS(4,3), BTN_SIZE(2,1) + #define OKAY_POS BTN_POS(4,5), BTN_SIZE(2,1) +#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); +} + +void BedMeshViewScreen::onEntry() { + mydata.highlight.x = -1; + mydata.count = GRID_MAX_POINTS; + mydata.message = nullptr; + BaseScreen::onEntry(); +} + +void BedMeshViewScreen::drawHighlightedPointValue() { + CommandProcessor cmd; + cmd.font(Theme::font_medium) + .cmd(COLOR_RGB(bg_text_enabled)) + .text(Z_LABEL_POS, GET_TEXT_F(MSG_MESH_EDIT_Z)) + .font(font_small); + + if (mydata.highlight.x != -1) + draw_adjuster_value(cmd, Z_VALUE_POS, ExtUI::getMeshPoint(mydata.highlight), GET_TEXT_F(MSG_UNITS_MM), 4, 3); + + cmd.colors(action_btn) + .tag(1).button(OKAY_POS, GET_TEXT_F(MSG_BUTTON_OKAY)) + .tag(0); + + if (mydata.message) cmd.text(MESSAGE_POS, mydata.message); +} + +void BedMeshViewScreen::onRedraw(draw_mode_t what) { + #define _INSET_POS(x,y,w,h) x + min(w,h)/10, y + min(w,h)/10, w - min(w,h)/5, h - min(w,h)/5 + #define INSET_POS(pos) _INSET_POS(pos) + + CommandProcessor cmd; + + if (what & BACKGROUND) { + cmd.cmd(CLEAR_COLOR_RGB(bg_color)) + .cmd(CLEAR(true,true,true)); + drawMeshBackground(cmd, INSET_POS(MESH_POS)); + } + + if (what & FOREGROUND) { + const float progress = sq(float(mydata.count) / GRID_MAX_POINTS); + if (progress >= 1.0) + drawHighlightedPointValue(); + drawMeshForeground(cmd, INSET_POS(MESH_POS), meshGetter, nullptr, pointToTag(mydata.highlight.x, mydata.highlight.y), progress); + } +} + +bool BedMeshViewScreen::onTouchEnd(uint8_t tag) { + switch (tag) { + case 1: GOTO_PREVIOUS(); return true; + default: return tagToPoint(tag, mydata.highlight); + } + return true; +} + +void BedMeshViewScreen::onMeshUpdate(const int8_t, const int8_t, const float) { + if (AT_SCREEN(BedMeshViewScreen)) { + onRefresh(); + ExtUI::yield(); + } +} + +void BedMeshViewScreen::onMeshUpdate(const int8_t x, const int8_t y, const ExtUI::probe_state_t state) { + switch (state) { + case ExtUI::G29_START: + mydata.message = nullptr; + mydata.count = 0; + break; + case ExtUI::G29_FINISH: + if (mydata.count == GRID_MAX_POINTS && ExtUI::getMeshValid()) + mydata.message = GET_TEXT_F(MSG_BED_MAPPING_DONE); + else + mydata.message = GET_TEXT_F(MSG_BED_MAPPING_INCOMPLETE); + mydata.count = GRID_MAX_POINTS; + break; + case ExtUI::G26_START: + mydata.message = nullptr; + mydata.count = 0; + break; + case ExtUI::G26_FINISH: + GOTO_SCREEN(StatusScreen); + break; + case ExtUI::G29_POINT_START: + case ExtUI::G26_POINT_START: + mydata.highlight.x = x; + mydata.highlight.y = y; + break; + case ExtUI::G29_POINT_FINISH: + case ExtUI::G26_POINT_FINISH: + mydata.count++; + break; + } + BedMeshViewScreen::onMeshUpdate(x, y, 0); +} + +void BedMeshViewScreen::doProbe() { + GOTO_SCREEN(BedMeshViewScreen); + mydata.count = 0; + injectCommands_P(PSTR(BED_LEVELING_COMMANDS)); +} + +void BedMeshViewScreen::doMeshValidation() { + mydata.count = 0; + GOTO_SCREEN(StatusScreen); + injectCommands_P(PSTR("G28\nM117 Heating...\nG26 R X0 Y0\nG27")); +} + +void BedMeshViewScreen::show() { + injectCommands_P(PSTR("G29 L1")); + GOTO_SCREEN(BedMeshViewScreen); +} + +#endif // FTDI_BED_MESH_VIEW_SCREEN 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 new file mode 100644 index 000000000000..0bb88f7f9659 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.h @@ -0,0 +1,48 @@ +/************************** + * bed_mesh_view_screen.h * + *************************/ + +/**************************************************************************** + * Written By Marcio Teixeira 2020 * + * * + * 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 FTDI_BED_MESH_VIEW_SCREEN +#define FTDI_BED_MESH_VIEW_SCREEN_CLASS BedMeshViewScreen + +struct BedMeshViewScreenData { + progmem_str message; + uint8_t count; + xy_uint8_t highlight; +}; + +class BedMeshViewScreen : public BedMeshBase, public CachedScreen { + private: + static float getHighlightedValue(); + static bool changeHighlightedValue(uint8_t tag); + static void drawHighlightedPointValue(); + public: + static void onMeshUpdate(const int8_t x, const int8_t y, const float val); + static void onMeshUpdate(const int8_t x, const int8_t y, const ExtUI::probe_state_t); + static void onEntry(); + static void onRedraw(draw_mode_t); + static bool onTouchEnd(uint8_t tag); + + static void doProbe(); + static void doMeshValidation(); + static void show(); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/boot_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/boot_screen.cpp similarity index 91% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/boot_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/boot_screen.cpp index 4ce8f608f123..c0940bed5ce4 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/boot_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/boot_screen.cpp @@ -18,26 +18,24 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) +#ifdef FTDI_BOOT_SCREEN -#include "screens.h" - -#include "../ftdi_eve_lib/extras/poly_ui.h" #include "../archim2-flash/flash_storage.h" -#ifdef SHOW_CUSTOM_BOOTSCREEN - #ifdef TOUCH_UI_PORTRAIT +#if ENABLED(SHOW_CUSTOM_BOOTSCREEN) + #if ENABLED(TOUCH_UI_PORTRAIT) #include "../theme/bootscreen_logo_portrait.h" #else #include "../theme/_bootscreen_landscape.h" #endif #else - #ifdef TOUCH_UI_PORTRAIT + #if ENABLED(TOUCH_UI_PORTRAIT) #include "../theme/marlin_bootscreen_portrait.h" #else #include "../theme/marlin_bootscreen_landscape.h" @@ -72,7 +70,8 @@ void BootScreen::onIdle() { GOTO_SCREEN(TouchCalibrationScreen); current_screen.forget(); PUSH_SCREEN(StatusScreen); - } else { + } + else { if (!UIFlashStorage::is_valid()) { StatusScreen::loadBitmaps(); SpinnerDialogBox::show(GET_TEXT_F(MSG_PLEASE_WAIT)); @@ -84,14 +83,16 @@ void BootScreen::onIdle() { if (UIData::animations_enabled()) { // If there is a startup video in the flash SPI, play // that, otherwise show a static splash screen. - if (!MediaPlayerScreen::playBootMedia()) - showSplashScreen(); + #ifdef FTDI_MEDIA_PLAYER_SCREEN + if (!MediaPlayerScreen::playBootMedia()) + #endif + showSplashScreen(); } #endif StatusScreen::loadBitmaps(); - #ifdef TOUCH_UI_LULZBOT_BIO + #if ENABLED(TOUCH_UI_LULZBOT_BIO) GOTO_SCREEN(BioConfirmHomeXYZ); current_screen.forget(); PUSH_SCREEN(StatusScreen); @@ -126,4 +127,4 @@ void BootScreen::showSplashScreen() { ExtUI::delay_ms(2500); } -#endif // TOUCH_UI_FTDI_EVE +#endif // FTDI_BOOT_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/boot_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/boot_screen.h new file mode 100644 index 000000000000..a267faba6a53 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/boot_screen.h @@ -0,0 +1,35 @@ +/***************** + * boot_screen.h * + *****************/ + +/**************************************************************************** + * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2019 - Cocoa Press * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#pragma once + +#define FTDI_BOOT_SCREEN +#define FTDI_BOOT_SCREEN_CLASS BootScreen + +class BootScreen : public BaseScreen, public UncachedScreen { + private: + static void showSplashScreen(); + public: + static void onRedraw(draw_mode_t); + static void onIdle(); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/case_light_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/case_light_screen.cpp similarity index 95% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/case_light_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/case_light_screen.cpp index 776a9fe5f716..8fbb400a681b 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/case_light_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/case_light_screen.cpp @@ -16,14 +16,13 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" -#if BOTH(TOUCH_UI_FTDI_EVE, CASE_LIGHT_ENABLE) - -#include "screens.h" +#ifdef FTDI_CASE_LIGHT_SCREEN using namespace FTDI; using namespace ExtUI; @@ -59,4 +58,4 @@ bool CaseLightScreen::onTouchHeld(uint8_t tag) { return true; } -#endif // TOUCH_UI_FTDI_EVE +#endif // FTDI_CASE_LIGHT_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/case_light_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/case_light_screen.h new file mode 100644 index 000000000000..55d5fe902f53 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/case_light_screen.h @@ -0,0 +1,31 @@ +/*********************** + * case_light_screen.h * + ***********************/ + +/**************************************************************************** + * Written By Marcio Teixeira 2019 - Cocoa Press * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#pragma once + +#define FTDI_CASE_LIGHT_SCREEN +#define FTDI_CASE_LIGHT_SCREEN_CLASS CaseLightScreen + +class CaseLightScreen : 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/generic/change_filament_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.cpp new file mode 100644 index 000000000000..fa0748c17b37 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.cpp @@ -0,0 +1,331 @@ +/****************************** + * change_filament_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 FTDI_CHANGE_FILAMENT_SCREEN + +using namespace ExtUI; +using namespace FTDI; +using namespace Theme; + +constexpr static ChangeFilamentScreenData &mydata = screen_data.ChangeFilamentScreen; + +#ifdef TOUCH_UI_PORTRAIT + #define GRID_COLS 2 + #define GRID_ROWS 11 + #define E_TEMP_POS BTN_POS(2,7), BTN_SIZE(1,1) + #define E_TEMP_LBL_POS BTN_POS(1,7), BTN_SIZE(1,1) + #define UNLD_LABL_POS BTN_POS(1,8), BTN_SIZE(1,1) + #define LOAD_LABL_POS BTN_POS(2,8), BTN_SIZE(1,1) + #define UNLD_MOMN_POS BTN_POS(1,9), BTN_SIZE(1,1) + #define LOAD_MOMN_POS BTN_POS(2,9), BTN_SIZE(1,1) + #define UNLD_CONT_POS BTN_POS(1,10), BTN_SIZE(1,1) + #define LOAD_CONT_POS BTN_POS(2,10), BTN_SIZE(1,1) + #define BACK_POS BTN_POS(1,11), BTN_SIZE(2,1) +#else + #define GRID_COLS 4 + #define GRID_ROWS 6 + #define E_TEMP_POS BTN_POS(3,2), BTN_SIZE(2,1) + #define E_TEMP_LBL_POS BTN_POS(3,1), BTN_SIZE(2,1) + #define UNLD_LABL_POS BTN_POS(3,3), BTN_SIZE(1,1) + #define LOAD_LABL_POS BTN_POS(4,3), BTN_SIZE(1,1) + #define UNLD_MOMN_POS BTN_POS(3,4), BTN_SIZE(1,1) + #define LOAD_MOMN_POS BTN_POS(4,4), BTN_SIZE(1,1) + #define UNLD_CONT_POS BTN_POS(3,5), BTN_SIZE(1,1) + #define LOAD_CONT_POS BTN_POS(4,5), BTN_SIZE(1,1) + #define BACK_POS BTN_POS(3,6), BTN_SIZE(2,1) +#endif +#define REMOVAL_TEMP_LBL_POS BTN_POS(1,3), BTN_SIZE(2,1) +#define GRADIENT_POS BTN_POS(1,4), BTN_SIZE(1,3) +#define LOW_TEMP_POS BTN_POS(2,6), BTN_SIZE(1,1) +#define MED_TEMP_POS BTN_POS(2,5), BTN_SIZE(1,1) +#define HIG_TEMP_POS BTN_POS(2,4), BTN_SIZE(1,1) +#define HEATING_LBL_POS BTN_POS(1,6), BTN_SIZE(1,1) +#define CAUTION_LBL_POS BTN_POS(1,4), BTN_SIZE(1,1) +#define HOT_LBL_POS BTN_POS(1,6), BTN_SIZE(1,1) +#define E_SEL_LBL_POS BTN_POS(1,1), BTN_SIZE(2,1) +#define E1_SEL_POS BTN_POS(1,2), BTN_SIZE(1,1) +#define E2_SEL_POS BTN_POS(2,2), BTN_SIZE(1,1) + +#define COOL_TEMP 40 +#define LOW_TEMP 180 +#define MED_TEMP 200 +#define HIGH_TEMP 220 + +/****************** COLOR SCALE ***********************/ + +uint32_t ChangeFilamentScreen::getWarmColor(uint16_t temp, uint16_t cool, uint16_t low, uint16_t med, uint16_t high) { + rgb_t R0, R1, mix; + + float t; + if (temp < cool) { + R0 = cool_rgb; + R1 = low_rgb; + t = 0; + } + else if (temp < low) { + R0 = cool_rgb; + R1 = low_rgb; + t = (float(temp)-cool)/(low-cool); + } + else if (temp < med) { + R0 = low_rgb; + R1 = med_rgb; + t = (float(temp)-low)/(med-low); + } + else if (temp < high) { + R0 = med_rgb; + R1 = high_rgb; + t = (float(temp)-med)/(high-med); + } + else if (temp >= high) { + R0 = med_rgb; + R1 = high_rgb; + t = 1; + } + rgb_t::lerp(t, R0, R1, mix); + return mix; +} + +void ChangeFilamentScreen::drawTempGradient(uint16_t x, uint16_t y, uint16_t w, uint16_t h) { + CommandProcessor cmd; + cmd.cmd(SCISSOR_XY (x, y)) + .cmd(SCISSOR_SIZE (w, h/2)) + .gradient (x, y, high_rgb, x, y+h/2, med_rgb) + .cmd(SCISSOR_XY (x, y+h/2)) + .cmd(SCISSOR_SIZE (w, h/2)) + .gradient (x, y+h/2, med_rgb, x, y+h, low_rgb) + .cmd(SCISSOR_XY ()) + .cmd(SCISSOR_SIZE ()); +} + +void ChangeFilamentScreen::onEntry() { + BaseScreen::onEntry(); + mydata.e_tag = ExtUI::getActiveTool() + 10; + mydata.t_tag = 0; + mydata.repeat_tag = 0; + mydata.saved_extruder = getActiveTool(); + #if FILAMENT_UNLOAD_PURGE_LENGTH > 0 + mydata.need_purge = true; + #endif +} + +void ChangeFilamentScreen::onExit() { + setActiveTool(mydata.saved_extruder, true); +} + +void ChangeFilamentScreen::onRedraw(draw_mode_t what) { + CommandProcessor cmd; + + if (what & BACKGROUND) { + cmd.cmd(CLEAR_COLOR_RGB(bg_color)) + .cmd(CLEAR(true,true,true)) + .cmd(COLOR_RGB(bg_text_enabled)) + .tag(0) + .font(TERN(TOUCH_UI_PORTRAIT, font_large, font_medium)) + .text(E_SEL_LBL_POS, GET_TEXT_F(MSG_EXTRUDER_SELECTION)) + .text(E_TEMP_LBL_POS, GET_TEXT_F(MSG_CURRENT_TEMPERATURE)) + .text(REMOVAL_TEMP_LBL_POS, GET_TEXT_F(MSG_REMOVAL_TEMPERATURE)); + drawTempGradient(GRADIENT_POS); + } + + if (what & FOREGROUND) { + char str[15]; + const extruder_t e = getExtruder(); + + if (isHeaterIdle(e)) + format_temp_and_idle(str, getActualTemp_celsius(e)); + else + format_temp_and_temp(str, getActualTemp_celsius(e), getTargetTemp_celsius(e)); + + const rgb_t tcol = getWarmColor(getActualTemp_celsius(e), COOL_TEMP, LOW_TEMP, MED_TEMP, HIGH_TEMP); + cmd.cmd(COLOR_RGB(tcol)) + .tag(15) + .rectangle(E_TEMP_POS) + .cmd(COLOR_RGB(tcol.luminance() > 128 ? 0x000000 : 0xFFFFFF)) + .font(font_medium) + .text(E_TEMP_POS, str) + .colors(normal_btn); + + const bool t_ok = getActualTemp_celsius(e) > getSoftenTemp() - 10; + + if (mydata.t_tag && !t_ok) { + cmd.text(HEATING_LBL_POS, GET_TEXT_F(MSG_HEATING)); + } else if (getActualTemp_celsius(e) > 100) { + cmd.cmd(COLOR_RGB(0xFF0000)) + .text(CAUTION_LBL_POS, GET_TEXT_F(MSG_CAUTION)) + .colors(normal_btn) + .text(HOT_LBL_POS, GET_TEXT_F(MSG_HOT)); + } + + #define TOG_STYLE(A) colors(A ? action_btn : normal_btn) + + const bool tog2 = mydata.t_tag == 2; + const bool tog3 = mydata.t_tag == 3; + const bool tog4 = mydata.t_tag == 4; + const bool tog10 = mydata.e_tag == 10; + #if HAS_MULTI_HOTEND + const bool tog11 = mydata.e_tag == 11; + #endif + + cmd.TOG_STYLE(tog10) + .tag(10).button (E1_SEL_POS, F("1")) + #if HOTENDS < 2 + .enabled(false) + #else + .TOG_STYLE(tog11) + #endif + .tag(11).button (E2_SEL_POS, F("2")); + + if (!t_ok) reset_menu_timeout(); + + const bool tog7 = mydata.repeat_tag == 7; + const bool tog8 = mydata.repeat_tag == 8; + + { + char str[30]; + format_temp(str, LOW_TEMP); + cmd.tag(2) .TOG_STYLE(tog2).button (LOW_TEMP_POS, str); + + format_temp(str, MED_TEMP); + cmd.tag(3) .TOG_STYLE(tog3).button (MED_TEMP_POS, str); + + format_temp(str, HIGH_TEMP); + cmd.tag(4) .TOG_STYLE(tog4).button (HIG_TEMP_POS, str); + } + + cmd.cmd(COLOR_RGB(t_ok ? bg_text_enabled : bg_text_disabled)) + .tag(0) .text (UNLD_LABL_POS, GET_TEXT_F(MSG_UNLOAD_FILAMENT)) + .text (LOAD_LABL_POS, GET_TEXT_F(MSG_LOAD_FILAMENT)) + .colors(normal_btn) + .tag(5) .enabled(t_ok).button (UNLD_MOMN_POS, GET_TEXT_F(MSG_MOMENTARY)) + .tag(6) .enabled(t_ok).button (LOAD_MOMN_POS, GET_TEXT_F(MSG_MOMENTARY)) + .tag(7).TOG_STYLE(tog7).enabled(t_ok).button (UNLD_CONT_POS, GET_TEXT_F(MSG_CONTINUOUS)) + .tag(8).TOG_STYLE(tog8).enabled(t_ok).button (LOAD_CONT_POS, GET_TEXT_F(MSG_CONTINUOUS)) + .tag(1).colors(action_btn) .button (BACK_POS, GET_TEXT_F(MSG_BUTTON_DONE)); + } +} + +uint8_t ChangeFilamentScreen::getSoftenTemp() { + switch (mydata.t_tag) { + case 2: return LOW_TEMP; + case 3: return MED_TEMP; + case 4: return HIGH_TEMP; + default: return EXTRUDE_MINTEMP; + } +} + +ExtUI::extruder_t ChangeFilamentScreen::getExtruder() { + switch (mydata.e_tag) { + case 13: return ExtUI::E3; + case 12: return ExtUI::E2; + case 11: return ExtUI::E1; + default: return ExtUI::E0; + } +} + +void ChangeFilamentScreen::doPurge() { + #if FILAMENT_UNLOAD_PURGE_LENGTH > 0 + constexpr float purge_distance_mm = FILAMENT_UNLOAD_PURGE_LENGTH; + if (mydata.need_purge) { + mydata.need_purge = false; + MoveAxisScreen::setManualFeedrate(getExtruder(), purge_distance_mm); + ExtUI::setAxisPosition_mm(ExtUI::getAxisPosition_mm(getExtruder()) + purge_distance_mm, getExtruder()); + } + #endif +} + +bool ChangeFilamentScreen::onTouchStart(uint8_t tag) { + // Make the Momentary and Continuous buttons slightly more responsive + switch (tag) { + case 5: case 6: case 7: case 8: + #if FILAMENT_UNLOAD_PURGE_LENGTH > 0 + if (tag == 5 || tag == 7) doPurge(); + #endif + return ChangeFilamentScreen::onTouchHeld(tag); + default: + return false; + } +} + +bool ChangeFilamentScreen::onTouchEnd(uint8_t tag) { + using namespace ExtUI; + switch (tag) { + case 1: GOTO_PREVIOUS(); break; + case 2: + case 3: + case 4: + // Change temperature + mydata.t_tag = tag; + setTargetTemp_celsius(getSoftenTemp(), getExtruder()); + break; + case 7: + mydata.repeat_tag = (mydata.repeat_tag == 7) ? 0 : 7; + break; + case 8: + mydata.repeat_tag = (mydata.repeat_tag == 8) ? 0 : 8; + break; + case 10: + case 11: + // Change extruder + mydata.e_tag = tag; + mydata.t_tag = 0; + mydata.repeat_tag = 0; + #if FILAMENT_UNLOAD_PURGE_LENGTH > 0 + mydata.need_purge = true; + #endif + setActiveTool(getExtruder(), true); + break; + case 15: GOTO_SCREEN(TemperatureScreen); break; + } + return true; +} + +bool ChangeFilamentScreen::onTouchHeld(uint8_t tag) { + if (ExtUI::isMoving()) return false; // Don't allow moves to accumulate + constexpr float increment = 1; + #define UI_INCREMENT_AXIS(axis) UI_INCREMENT(AxisPosition_mm, axis); + #define UI_DECREMENT_AXIS(axis) UI_DECREMENT(AxisPosition_mm, axis); + switch (tag) { + case 5: case 7: UI_DECREMENT_AXIS(getExtruder()); break; + case 6: case 8: UI_INCREMENT_AXIS(getExtruder()); break; + default: return false; + } + #undef UI_DECREMENT_AXIS + #undef UI_INCREMENT_AXIS + return false; +} + +void ChangeFilamentScreen::onIdle() { + reset_menu_timeout(); + if (mydata.repeat_tag) onTouchHeld(mydata.repeat_tag); + if (refresh_timer.elapsed(STATUS_UPDATE_INTERVAL)) { + onRefresh(); + refresh_timer.start(); + } + BaseScreen::onIdle(); +} + +#endif // FTDI_CHANGE_FILAMENT_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.h new file mode 100644 index 000000000000..42eaf25f4ae3 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.h @@ -0,0 +1,51 @@ +/**************************** + * change_filament_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 FTDI_CHANGE_FILAMENT_SCREEN +#define FTDI_CHANGE_FILAMENT_SCREEN_CLASS ChangeFilamentScreen + +struct ChangeFilamentScreenData { + uint8_t e_tag, t_tag, repeat_tag; + ExtUI::extruder_t saved_extruder; + #if FILAMENT_UNLOAD_PURGE_LENGTH > 0 + bool need_purge; + #endif +}; + +class ChangeFilamentScreen : public BaseScreen, public CachedScreen { + private: + static uint8_t getSoftenTemp(); + static ExtUI::extruder_t getExtruder(); + static void drawTempGradient(uint16_t x, uint16_t y, uint16_t w, uint16_t h); + static void doPurge(); + public: + static uint32_t getWarmColor(uint16_t temp, uint16_t cool, uint16_t low, uint16_t med, uint16_t high); + static void onEntry(); + static void onExit(); + static void onRedraw(draw_mode_t); + static bool onTouchStart(uint8_t tag); + static bool onTouchEnd(uint8_t tag); + static bool onTouchHeld(uint8_t tag); + static void onIdle(); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_abort_print_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_abort_print_dialog_box.cpp similarity index 85% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_abort_print_dialog_box.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_abort_print_dialog_box.cpp index e23592a46e9f..02e48efa01d6 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_abort_print_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_abort_print_dialog_box.cpp @@ -17,14 +17,15 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) +#ifdef FTDI_CONFIRM_ABORT_PRINT_DIALOG_BOX -#include "screens.h" +#include "../../../../feature/host_actions.h" using namespace ExtUI; @@ -37,11 +38,15 @@ bool ConfirmAbortPrintDialogBox::onTouchEnd(uint8_t tag) { switch (tag) { case 1: GOTO_PREVIOUS(); - stopPrint(); + if (ExtUI::isPrintingFromMedia()) + ExtUI::stopPrint(); + #ifdef ACTION_ON_CANCEL + else host_action_cancel(); + #endif return true; default: return DialogBoxBaseClass::onTouchEnd(tag); } } -#endif // TOUCH_UI_FTDI_EVE +#endif // FTDI_CONFIRM_ABORT_PRINT_DIALOG_BOX diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_abort_print_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_abort_print_dialog_box.h new file mode 100644 index 000000000000..a97a2000a093 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_abort_print_dialog_box.h @@ -0,0 +1,32 @@ +/************************************ + * confirm_abort_print_dialog_box.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 FTDI_CONFIRM_ABORT_PRINT_DIALOG_BOX +#define FTDI_CONFIRM_ABORT_PRINT_DIALOG_BOX_CLASS ConfirmAbortPrintDialogBox + +class ConfirmAbortPrintDialogBox : public DialogBoxBaseClass, public UncachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchEnd(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_auto_calibration_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_auto_calibration_dialog_box.cpp similarity index 93% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_auto_calibration_dialog_box.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_auto_calibration_dialog_box.cpp index 7e1a82025ddc..748cc1d7ef7b 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_auto_calibration_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_auto_calibration_dialog_box.cpp @@ -17,14 +17,13 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" -#if BOTH(TOUCH_UI_FTDI_EVE, CALIBRATION_GCODE) - -#include "screens.h" +#ifdef FTDI_CONFIRM_AUTO_CALIBRATION_DIALOG_BOX using namespace ExtUI; using namespace Theme; @@ -45,4 +44,4 @@ bool ConfirmAutoCalibrationDialogBox::onTouchEnd(uint8_t tag) { } } -#endif // TOUCH_UI_FTDI_EVE +#endif // FTDI_CONFIRM_AUTO_CALIBRATION_DIALOG_BOX diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_auto_calibration_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_auto_calibration_dialog_box.h new file mode 100644 index 000000000000..5093b68c7342 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_auto_calibration_dialog_box.h @@ -0,0 +1,32 @@ +/***************************************** + * confirm_auto_calibration_dialog_box.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 FTDI_CONFIRM_AUTO_CALIBRATION_DIALOG_BOX +#define FTDI_CONFIRM_AUTO_CALIBRATION_DIALOG_BOX_CLASS ConfirmAutoCalibrationDialogBox + +class ConfirmAutoCalibrationDialogBox : public DialogBoxBaseClass, public UncachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchEnd(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_erase_flash_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_erase_flash_dialog_box.cpp similarity index 94% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_erase_flash_dialog_box.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_erase_flash_dialog_box.cpp index 574de2108829..b4ddebea5ef4 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_erase_flash_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_erase_flash_dialog_box.cpp @@ -17,14 +17,13 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" -#if BOTH(TOUCH_UI_FTDI_EVE, TOUCH_UI_DEVELOPER_MENU) - -#include "screens.h" +#ifdef FTDI_CONFIRM_ERASE_FLASH_DIALOG_BOX #include "../archim2-flash/flash_storage.h" @@ -51,4 +50,4 @@ bool ConfirmEraseFlashDialogBox::onTouchEnd(uint8_t tag) { } } -#endif // TOUCH_UI_FTDI_EVE +#endif // FTDI_CONFIRM_ERASE_FLASH_DIALOG_BOX diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_erase_flash_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_erase_flash_dialog_box.h new file mode 100644 index 000000000000..a06f886176ed --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_erase_flash_dialog_box.h @@ -0,0 +1,32 @@ +/************************************ + * confirm_erase_flash_dialog_box.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 FTDI_CONFIRM_ERASE_FLASH_DIALOG_BOX +#define FTDI_CONFIRM_ERASE_FLASH_DIALOG_BOX_CLASS ConfirmEraseFlashDialogBox + +class ConfirmEraseFlashDialogBox : public DialogBoxBaseClass, public UncachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchEnd(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_start_print_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_start_print_dialog_box.cpp similarity index 88% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_start_print_dialog_box.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_start_print_dialog_box.cpp index 4e5b174d53f0..47aac6286022 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_start_print_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_start_print_dialog_box.cpp @@ -17,20 +17,21 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" +#include "../screen_data.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) - -#include "screens.h" -#include "screen_data.h" +#ifdef FTDI_CONFIRM_START_PRINT_DIALOG_BOX using namespace FTDI; using namespace Theme; using namespace ExtUI; +constexpr static ConfirmStartPrintDialogBoxData &mydata = screen_data.ConfirmStartPrintDialogBox; + void ConfirmStartPrintDialogBox::onRedraw(draw_mode_t) { const char *filename = getLongFilename(); char buffer[strlen_P(GET_TEXT(MSG_START_PRINT_CONFIRMATION)) + strlen(filename) + 1]; @@ -53,13 +54,13 @@ bool ConfirmStartPrintDialogBox::onTouchEnd(uint8_t tag) { const char *ConfirmStartPrintDialogBox::getFilename(bool longName) { FileList files; - files.seek(screen_data.ConfirmStartPrintDialogBox.file_index, true); + files.seek(mydata.file_index, true); return longName ? files.longFilename() : files.shortFilename(); } void ConfirmStartPrintDialogBox::show(uint8_t file_index) { - screen_data.ConfirmStartPrintDialogBox.file_index = file_index; + mydata.file_index = file_index; GOTO_SCREEN(ConfirmStartPrintDialogBox); } -#endif // TOUCH_UI_FTDI_EVE +#endif // FTDI_CONFIRM_START_PRINT_DIALOG_BOX diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_start_print_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_start_print_dialog_box.h new file mode 100644 index 000000000000..e073ed55fa3a --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_start_print_dialog_box.h @@ -0,0 +1,43 @@ +/************************************ + * confirm_start_print_dialog_box.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 FTDI_CONFIRM_START_PRINT_DIALOG_BOX +#define FTDI_CONFIRM_START_PRINT_DIALOG_BOX_CLASS ConfirmStartPrintDialogBox + +struct ConfirmStartPrintDialogBoxData { + uint8_t file_index; +}; + +class ConfirmStartPrintDialogBox : public DialogBoxBaseClass, public UncachedScreen { + private: + inline static const char *getShortFilename() {return getFilename(false);} + inline static const char *getLongFilename() {return getFilename(true);} + + static const char *getFilename(bool longName); + public: + static void onRedraw(draw_mode_t); + static bool onTouchEnd(uint8_t); + + static void show(uint8_t file_index); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_user_request_alert_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_user_request_alert_box.cpp similarity index 76% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_user_request_alert_box.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_user_request_alert_box.cpp index 6b6affadd569..8c06fa9a9e0e 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_user_request_alert_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_user_request_alert_box.cpp @@ -17,15 +17,14 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" +#include "../screen_data.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) - -#include "screens.h" -#include "screen_data.h" +#ifdef FTDI_CONFIRM_USER_REQUEST_ALERT_BOX using namespace FTDI; @@ -36,23 +35,35 @@ void ConfirmUserRequestAlertBox::onRedraw(draw_mode_t mode) { bool ConfirmUserRequestAlertBox::onTouchEnd(uint8_t tag) { switch (tag) { case 1: - ExtUI::setUserConfirmed(); - GOTO_PREVIOUS(); + #ifdef FTDI_TUNE_MENU + if (ExtUI::isPrintingPaused()) { + // The TuneMenu will call ExtUI::setUserConfirmed() + GOTO_SCREEN(TuneMenu); + current_screen.forget(); + } + else + #endif + { + ExtUI::setUserConfirmed(); + GOTO_PREVIOUS(); + } return true; case 2: GOTO_PREVIOUS(); return true; default: return false; } } -void ConfirmUserRequestAlertBox::show(const char* msg) { +void ConfirmUserRequestAlertBox::show(const char *msg) { drawMessage(msg); storeBackground(); screen_data.AlertDialogBox.isError = false; - GOTO_SCREEN(ConfirmUserRequestAlertBox); + if (!AT_SCREEN(ConfirmUserRequestAlertBox)) + GOTO_SCREEN(ConfirmUserRequestAlertBox); } void ConfirmUserRequestAlertBox::hide() { if (AT_SCREEN(ConfirmUserRequestAlertBox)) GOTO_PREVIOUS(); } -#endif // TOUCH_UI_FTDI_EVE + +#endif // FTDI_CONFIRM_USER_REQUEST_ALERT_BOX diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_user_request_alert_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_user_request_alert_box.h new file mode 100644 index 000000000000..f83b1a24f5d5 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_user_request_alert_box.h @@ -0,0 +1,34 @@ +/************************************ + * confirm_user_request_alert_box.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 FTDI_CONFIRM_USER_REQUEST_ALERT_BOX +#define FTDI_CONFIRM_USER_REQUEST_ALERT_BOX_CLASS ConfirmUserRequestAlertBox + +class ConfirmUserRequestAlertBox : public AlertDialogBox { + public: + static void onRedraw(draw_mode_t); + static bool onTouchEnd(uint8_t); + static void hide(); + static void show(const char*); +}; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/custom_user_menus.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/custom_user_menus.cpp new file mode 100644 index 000000000000..880748089772 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/custom_user_menus.cpp @@ -0,0 +1,211 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../config.h" +#include "../screens.h" + +#ifdef FTDI_CUSTOM_USER_MENUS + +using namespace FTDI; +using namespace ExtUI; +using namespace Theme; + +#define _ITEM_TAG(N) (10+N) +#define _USER_DESC(N) MAIN_MENU_ITEM_##N##_DESC +#define _USER_GCODE(N) MAIN_MENU_ITEM_##N##_GCODE +#define _USER_ITEM(N) .tag(_ITEM_TAG(N)).button(USER_ITEM_POS(N), _USER_DESC(N)) +#define _USER_ACTION(N) case _ITEM_TAG(N): injectCommands_P(PSTR(_USER_GCODE(N))); TERN_(USER_SCRIPT_RETURN, GOTO_SCREEN(StatusScreen)); break; + +void CustomUserMenus::onRedraw(draw_mode_t what) { + if (what & BACKGROUND) { + CommandProcessor cmd; + cmd.cmd(CLEAR_COLOR_RGB(Theme::bg_color)) + .cmd(CLEAR(true, true, true)); + } + + #if HAS_USER_ITEM(16, 17, 18, 19, 20) + #define _MORE_THAN_FIFTEEN 1 + #else + #define _MORE_THAN_FIFTEEN 0 + #endif + #if _MORE_THAN_FIFTEEN || HAS_USER_ITEM(11, 12, 13, 14, 15) + #define _MORE_THAN_TEN 1 + #else + #define _MORE_THAN_TEN 0 + #endif + + #if ENABLED(TOUCH_UI_PORTRAIT) + #define GRID_ROWS 11 + #define GRID_COLS (1 + _MORE_THAN_TEN) + #define USER_ITEM_POS(N) BTN_POS((1+((N-1)/10)), ((N-1) % 10 + 1)), BTN_SIZE(1,1) + #define BACK_POS BTN_POS(1,11), BTN_SIZE(1,1) + #else + #if _MORE_THAN_TEN || HAS_USER_ITEM(6, 7, 8, 9, 10) + #define _MORE_THAN_FIVE 1 + #else + #define _MORE_THAN_FIVE 0 + #endif + #define GRID_ROWS 6 + #define GRID_COLS (1 + _MORE_THAN_FIVE + _MORE_THAN_TEN + _MORE_THAN_FIFTEEN) + #define USER_ITEM_POS(N) BTN_POS((1+((N-1)/5)), ((N-1) % 5 + 1)), BTN_SIZE(1,1) + #define BACK_POS BTN_POS(1,6), BTN_SIZE(GRID_COLS,1) + #endif + + if (what & FOREGROUND) { + CommandProcessor cmd; + cmd.colors(normal_btn) + .font(Theme::font_medium) + #if HAS_USER_ITEM(1) + _USER_ITEM(1) + #endif + #if HAS_USER_ITEM(2) + _USER_ITEM(2) + #endif + #if HAS_USER_ITEM(3) + _USER_ITEM(3) + #endif + #if HAS_USER_ITEM(4) + _USER_ITEM(4) + #endif + #if HAS_USER_ITEM(5) + _USER_ITEM(5) + #endif + #if HAS_USER_ITEM(6) + _USER_ITEM(6) + #endif + #if HAS_USER_ITEM(7) + _USER_ITEM(7) + #endif + #if HAS_USER_ITEM(8) + _USER_ITEM(8) + #endif + #if HAS_USER_ITEM(9) + _USER_ITEM(9) + #endif + #if HAS_USER_ITEM(10) + _USER_ITEM(10) + #endif + #if HAS_USER_ITEM(11) + _USER_ITEM(11) + #endif + #if HAS_USER_ITEM(12) + _USER_ITEM(12) + #endif + #if HAS_USER_ITEM(13) + _USER_ITEM(13) + #endif + #if HAS_USER_ITEM(14) + _USER_ITEM(14) + #endif + #if HAS_USER_ITEM(15) + _USER_ITEM(15) + #endif + #if HAS_USER_ITEM(16) + _USER_ITEM(16) + #endif + #if HAS_USER_ITEM(17) + _USER_ITEM(17) + #endif + #if HAS_USER_ITEM(18) + _USER_ITEM(18) + #endif + #if HAS_USER_ITEM(19) + _USER_ITEM(19) + #endif + #if HAS_USER_ITEM(20) + _USER_ITEM(20) + #endif + .colors(action_btn) + .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BUTTON_DONE)); + } +} + +bool CustomUserMenus::onTouchEnd(uint8_t tag) { + switch (tag) { + #if HAS_USER_ITEM(1) + _USER_ACTION(1) + #endif + #if HAS_USER_ITEM(2) + _USER_ACTION(2) + #endif + #if HAS_USER_ITEM(3) + _USER_ACTION(3) + #endif + #if HAS_USER_ITEM(4) + _USER_ACTION(4) + #endif + #if HAS_USER_ITEM(5) + _USER_ACTION(5) + #endif + #if HAS_USER_ITEM(6) + _USER_ACTION(6) + #endif + #if HAS_USER_ITEM(7) + _USER_ACTION(7) + #endif + #if HAS_USER_ITEM(8) + _USER_ACTION(8) + #endif + #if HAS_USER_ITEM(9) + _USER_ACTION(9) + #endif + #if HAS_USER_ITEM(10) + _USER_ACTION(10) + #endif + #if HAS_USER_ITEM(11) + _USER_ACTION(11) + #endif + #if HAS_USER_ITEM(12) + _USER_ACTION(12) + #endif + #if HAS_USER_ITEM(13) + _USER_ACTION(13) + #endif + #if HAS_USER_ITEM(14) + _USER_ACTION(14) + #endif + #if HAS_USER_ITEM(15) + _USER_ACTION(15) + #endif + #if HAS_USER_ITEM(16) + _USER_ACTION(16) + #endif + #if HAS_USER_ITEM(17) + _USER_ACTION(17) + #endif + #if HAS_USER_ITEM(18) + _USER_ACTION(18) + #endif + #if HAS_USER_ITEM(19) + _USER_ACTION(19) + #endif + #if HAS_USER_ITEM(20) + _USER_ACTION(20) + #endif + + case 1: GOTO_PREVIOUS(); break; + default: return false; + } + return true; +} + +#endif // FTDI_CUSTOM_USER_MENUS diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/custom_user_menus.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/custom_user_menus.h new file mode 100644 index 000000000000..e46a280369b8 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/custom_user_menus.h @@ -0,0 +1,32 @@ +/** + * 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 FTDI_CUSTOM_USER_MENUS +#define FTDI_CUSTOM_USER_MENUS_CLASS CustomUserMenus + +class CustomUserMenus : public BaseScreen, public CachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchEnd(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/default_acceleration_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/default_acceleration_screen.cpp similarity index 94% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/default_acceleration_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/default_acceleration_screen.cpp index 8496955f732c..07473d66a121 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/default_acceleration_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/default_acceleration_screen.cpp @@ -17,14 +17,13 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) - -#include "screens.h" +#ifdef FTDI_DEFAULT_ACCELERATION_SCREEN using namespace FTDI; using namespace ExtUI; @@ -40,7 +39,7 @@ void DefaultAccelerationScreen::onRedraw(draw_mode_t what) { w.adjuster( 4, GET_TEXT_F(MSG_ACCEL_TRAVEL), getTravelAcceleration_mm_s2() ); w.adjuster( 6, GET_TEXT_F(MSG_ACCEL_RETRACT), getRetractAcceleration_mm_s2() ); w.increments(); - w.button( 8, GET_TEXT_F(MSG_SET_MAXIMUM)); + w.button( 8, GET_TEXT_F(MSG_SET_MAXIMUM)); } bool DefaultAccelerationScreen::onTouchHeld(uint8_t tag) { @@ -60,4 +59,4 @@ bool DefaultAccelerationScreen::onTouchHeld(uint8_t tag) { return true; } -#endif // TOUCH_UI_FTDI_EVE +#endif // FTDI_DEFAULT_ACCELERATION_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/default_acceleration_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/default_acceleration_screen.h new file mode 100644 index 000000000000..9042f6d2b846 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/default_acceleration_screen.h @@ -0,0 +1,32 @@ +/********************************* + * default_acceleration_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 FTDI_DEFAULT_ACCELERATION_SCREEN +#define FTDI_DEFAULT_ACCELERATION_SCREEN_CLASS DefaultAccelerationScreen + +class DefaultAccelerationScreen : 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/generic/developer_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/developer_menu.cpp new file mode 100644 index 000000000000..34c754d53566 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/developer_menu.cpp @@ -0,0 +1,149 @@ +/********************** + * developer_menu.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 FTDI_DEVELOPER_MENU + +#include "../archim2-flash/flash_storage.h" + +using namespace FTDI; +using namespace Theme; + +void DeveloperMenu::onRedraw(draw_mode_t what) { + if (what & BACKGROUND) { + CommandProcessor cmd; + cmd.cmd(CLEAR_COLOR_RGB(bg_color)) + .cmd(CLEAR(true,true,true)) + .font(font_medium) + .tag(0); + + #ifdef SPI_FLASH_SS + constexpr bool has_flash = true; + #else + constexpr bool has_flash = false; + #endif + + #if ENABLED(SDSUPPORT) + constexpr bool has_media = true; + #else + constexpr bool has_media = false; + #endif + + cmd.cmd(COLOR_RGB(bg_text_enabled)); + #if ENABLED(TOUCH_UI_PORTRAIT) + #define GRID_ROWS 10 + #define GRID_COLS 1 + cmd.font(font_large) .text ( BTN_POS(1,1), BTN_SIZE(1,1), F("Developer Menu")) + .colors(normal_btn) + .tag(2).font(font_medium) .button(BTN_POS(1,2), BTN_SIZE(1,1), F("Show All Widgets")) + .tag(3) .button(BTN_POS(1,3), BTN_SIZE(1,1), F("Stress Test")) + .tag(4) .button(BTN_POS(1,4), BTN_SIZE(1,1), F("Show Touch Registers")) + .tag(5) .button(BTN_POS(1,5), BTN_SIZE(1,1), F("Play Song")) + .tag(6).enabled(has_media).button(BTN_POS(1,6), BTN_SIZE(1,1), F("Play Video from Media")) + .tag(7).enabled(has_flash).button(BTN_POS(1,7), BTN_SIZE(1,1), F("Play Video from SPI Flash")) + .tag(8).enabled(has_flash).button(BTN_POS(1,8), BTN_SIZE(1,1), F("Load Video to SPI Flash")) + .tag(9).enabled(has_flash).button(BTN_POS(1,9), BTN_SIZE(1,1), F("Erase SPI Flash")) + + .tag(1).colors(action_btn) + .button(BTN_POS(1,10), BTN_SIZE(1,1), F("Back")); + #else + #define GRID_ROWS 6 + #define GRID_COLS 2 + cmd.font(font_medium) .text ( BTN_POS(1,1), BTN_SIZE(2,1), F("Developer Menu")) + .colors(normal_btn) + .tag(2).font(font_small) .button(BTN_POS(1,2), BTN_SIZE(1,1), F("Show All Widgets")) + .tag(3) .button(BTN_POS(1,3), BTN_SIZE(1,1), F("Show Touch Registers")) + .tag(9) .button(BTN_POS(1,4), BTN_SIZE(1,1), F("Show Pin States")) + .tag(4) .button(BTN_POS(1,5), BTN_SIZE(1,1), F("Play Song")) + .tag(5).enabled(has_media).button(BTN_POS(2,2), BTN_SIZE(1,1), F("Play Video from Media")) + .tag(6).enabled(has_flash).button(BTN_POS(2,3), BTN_SIZE(1,1), F("Play Video from SPI Flash")) + .tag(7).enabled(has_flash).button(BTN_POS(2,4), BTN_SIZE(1,1), F("Load Video to SPI Flash")) + .tag(8).enabled(has_flash).button(BTN_POS(2,5), BTN_SIZE(1,1), F("Erase SPI Flash")) + .tag(1).colors(action_btn) + .button(BTN_POS(1,6), BTN_SIZE(2,1), F("Back")); + #endif + } +} + +bool DeveloperMenu::onTouchEnd(uint8_t tag) { + using namespace Theme; + switch (tag) { + case 1: GOTO_PREVIOUS(); break; + case 2: GOTO_SCREEN(WidgetsScreen); break; + case 3: + PUSH_SCREEN(StressTestScreen); + AlertDialogBox::show(F("Please do not run this test unattended as it may cause your printer to malfunction.")); + current_screen.forget(); + break; + case 4: GOTO_SCREEN(TouchRegistersScreen); break; + case 5: sound.play(js_bach_joy, PLAY_ASYNCHRONOUS); break; + #if ENABLED(SDSUPPORT) + case 6: + if (!MediaPlayerScreen::playCardMedia()) + AlertDialogBox::showError(F("Cannot open STARTUP.AVI")); + break; + #endif + #ifdef SPI_FLASH_SS + case 7: + if (!MediaPlayerScreen::playBootMedia()) + AlertDialogBox::showError(F("No boot media available")); + break; + case 8: + { + SpinnerDialogBox::show(F("Saving...")); + UIFlashStorage::error_t res = UIFlashStorage::write_media_file(F("STARTUP.AVI")); + SpinnerDialogBox::hide(); + reset_menu_timeout(); + switch (res) { + case UIFlashStorage::SUCCESS: + AlertDialogBox::show(F("File copied!")); + break; + + case UIFlashStorage::READ_ERROR: + AlertDialogBox::showError(F("Failed to read file")); + break; + + case UIFlashStorage::VERIFY_ERROR: + AlertDialogBox::showError(F("Failed to verify file")); + break; + + case UIFlashStorage::FILE_NOT_FOUND: + AlertDialogBox::showError(F("Cannot open STARTUP.AVI")); + break; + + case UIFlashStorage::WOULD_OVERWRITE: + AlertDialogBox::showError(F("Cannot overwrite existing media.")); + break; + } + break; + } + case 9: GOTO_SCREEN(ConfirmEraseFlashDialogBox); break; + #endif + case 10: GOTO_SCREEN(EndstopStatesScreen); break; + default: return false; + } + return true; +} + +#endif // FTDI_DEVELOPER_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/developer_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/developer_menu.h new file mode 100644 index 000000000000..87572483295f --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/developer_menu.h @@ -0,0 +1,32 @@ +/******************** + * developer_menu.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 FTDI_DEVELOPER_MENU +#define FTDI_DEVELOPER_MENU_CLASS DeveloperMenu + +class DeveloperMenu : public BaseScreen, public UncachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchEnd(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/dialog_box_base_class.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.cpp similarity index 78% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/dialog_box_base_class.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.cpp index 782ae7bbc7f8..1811779297e3 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/dialog_box_base_class.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.cpp @@ -17,14 +17,13 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) - -#include "screens.h" +#ifdef FTDI_DIALOG_BOX_BASE_CLASS using namespace FTDI; using namespace Theme; @@ -33,14 +32,14 @@ using namespace Theme; #define GRID_ROWS 8 template -void DialogBoxBaseClass::drawMessage(const T message, int16_t font) { +void DialogBoxBaseClass::drawMessage(T message, int16_t font) { CommandProcessor cmd; cmd.cmd(CMD_DLSTART) .cmd(CLEAR_COLOR_RGB(bg_color)) .cmd(CLEAR(true,true,true)) .cmd(COLOR_RGB(bg_text_enabled)) .tag(0); - draw_text_box(cmd, BTN_POS(1,1), BTN_SIZE(2,3), message, OPT_CENTER, font ? font : font_large); + draw_text_box(cmd, BTN_POS(1,1), BTN_SIZE(2,6), message, OPT_CENTER, font ? font : font_large); cmd.colors(normal_btn); } @@ -50,27 +49,25 @@ template void DialogBoxBaseClass::drawMessage(progmem_str, int16_t font); void DialogBoxBaseClass::drawYesNoButtons(uint8_t default_btn) { CommandProcessor cmd; cmd.font(font_medium) - .colors(default_btn == 1 ? action_btn : normal_btn).tag(1).button( BTN_POS(1,8), BTN_SIZE(1,1), GET_TEXT_F(MSG_YES)) - .colors(default_btn == 2 ? action_btn : normal_btn).tag(2).button( BTN_POS(2,8), BTN_SIZE(1,1), GET_TEXT_F(MSG_NO)); + .colors(default_btn == 1 ? action_btn : normal_btn).tag(1).button(BTN_POS(1,8), BTN_SIZE(1,1), GET_TEXT_F(MSG_YES)) + .colors(default_btn == 2 ? action_btn : normal_btn).tag(2).button(BTN_POS(2,8), BTN_SIZE(1,1), GET_TEXT_F(MSG_NO)); } void DialogBoxBaseClass::drawOkayButton() { CommandProcessor cmd; cmd.font(font_medium) - .tag(1).button( BTN_POS(1,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_BUTTON_OKAY)); + .tag(1).button(BTN_POS(1,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_BUTTON_OKAY)); } -void DialogBoxBaseClass::drawButton(const progmem_str label) { +template +void DialogBoxBaseClass::drawButton(T label) { CommandProcessor cmd; cmd.font(font_medium) - .tag(1).button( BTN_POS(1,8), BTN_SIZE(2,1), label); + .tag(1).button(BTN_POS(1,8), BTN_SIZE(2,1), label); } -void DialogBoxBaseClass::drawSpinner() { - CommandProcessor cmd; - cmd.cmd(COLOR_RGB(bg_text_enabled)) - .spinner(BTN_POS(1,4), BTN_SIZE(2,3)).execute(); -} +template void DialogBoxBaseClass::drawButton(const char *); +template void DialogBoxBaseClass::drawButton(progmem_str); bool DialogBoxBaseClass::onTouchEnd(uint8_t tag) { switch (tag) { @@ -84,4 +81,4 @@ void DialogBoxBaseClass::onIdle() { reset_menu_timeout(); } -#endif // TOUCH_UI_FTDI_EVE +#endif // FTDI_DIALOG_BOX_BASE_CLASS diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.h new file mode 100644 index 000000000000..c87640992866 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.h @@ -0,0 +1,39 @@ +/*************************** + * dialog_box_base_class.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 FTDI_DIALOG_BOX_BASE_CLASS +#define FTDI_DIALOG_BOX_BASE_CLASS_CLASS DialogBoxBaseClass + +class DialogBoxBaseClass : public BaseScreen { + protected: + template static void drawMessage(T, int16_t font = 0); + template static void drawButton(T); + static void drawYesNoButtons(uint8_t default_btn = 0); + static void drawOkayButton(); + + static void onRedraw(draw_mode_t) {}; + public: + static bool onTouchEnd(uint8_t tag); + static void onIdle(); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/display_tuning_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/display_tuning_screen.cpp similarity index 95% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/display_tuning_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/display_tuning_screen.cpp index 8845dfb5c0aa..504ebde1695c 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/display_tuning_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/display_tuning_screen.cpp @@ -17,14 +17,13 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) - -#include "screens.h" +#ifdef FTDI_DISPLAY_TUNING_SCREEN using namespace FTDI; using namespace Theme; @@ -58,4 +57,4 @@ bool DisplayTuningScreen::onTouchHeld(uint8_t tag) { return true; } -#endif // TOUCH_UI_FTDI_EVE +#endif // FTDI_DISPLAY_TUNING_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/display_tuning_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/display_tuning_screen.h new file mode 100644 index 000000000000..3de840b82e2f --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/display_tuning_screen.h @@ -0,0 +1,32 @@ +/*************************** + * display_tuning_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 FTDI_DISPLAY_TUNING_SCREEN +#define FTDI_DISPLAY_TUNING_SCREEN_CLASS DisplayTuningScreen + +class DisplayTuningScreen : public BaseNumericAdjustmentScreen, public CachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchHeld(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/endstop_state_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/endstop_state_screen.cpp similarity index 92% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/endstop_state_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/endstop_state_screen.cpp index 7f3f507fd64f..c7042e760e48 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/endstop_state_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/endstop_state_screen.cpp @@ -17,14 +17,13 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) - -#include "screens.h" +#ifdef FTDI_ENDSTOP_STATE_SCREEN using namespace FTDI; using namespace Theme; @@ -53,7 +52,7 @@ void EndstopStatesScreen::onRedraw(draw_mode_t) { #define PIN_DISABLED(X,Y,LABEL,PIN) cmd.enabled(0).PIN_BTN(X,Y,PIN,LABEL); cmd.font( - #ifdef TOUCH_UI_PORTRAIT + #if ENABLED(TOUCH_UI_PORTRAIT) font_large #else font_medium @@ -61,43 +60,43 @@ void EndstopStatesScreen::onRedraw(draw_mode_t) { ) .text(BTN_POS(1,1), BTN_SIZE(6,1), GET_TEXT_F(MSG_LCD_ENDSTOPS)) .font(font_tiny); - #if PIN_EXISTS(X_MAX) + #if HAS_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 PIN_EXISTS(Y_MAX) + #if HAS_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 PIN_EXISTS(Z_MAX) + #if HAS_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 PIN_EXISTS(X_MIN) + #if HAS_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 PIN_EXISTS(Y_MIN) + #if HAS_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 PIN_EXISTS(Z_MIN) + #if HAS_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) #endif #if ENABLED(FILAMENT_RUNOUT_SENSOR) && PIN_EXISTS(FIL_RUNOUT) - PIN_ENABLED (1, 4, GET_TEXT_F(MSG_RUNOUT_1), FIL_RUNOUT, FIL_RUNOUT_STATE) + PIN_ENABLED (1, 4, GET_TEXT_F(MSG_RUNOUT_1), FIL_RUNOUT, FIL_RUNOUT1_STATE) #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) - PIN_ENABLED (3, 4, GET_TEXT_F(MSG_RUNOUT_2), FIL_RUNOUT2, FIL_RUNOUT_STATE) + 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) #endif @@ -121,7 +120,7 @@ void EndstopStatesScreen::onRedraw(draw_mode_t) { cmd.font(font_medium) .colors(action_btn) - .tag(1).button( BTN_POS(1,7), BTN_SIZE(6,1), GET_TEXT_F(MSG_BACK)); + .tag(1).button(BTN_POS(1,7), BTN_SIZE(6,1), GET_TEXT_F(MSG_BUTTON_DONE)); #undef GRID_COLS #undef GRID_ROWS } @@ -149,4 +148,4 @@ void EndstopStatesScreen::onIdle() { BaseScreen::onIdle(); } -#endif // TOUCH_UI_FTDI_EVE +#endif // FTDI_ENDSTOP_STATE_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/endstop_state_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/endstop_state_screen.h new file mode 100644 index 000000000000..c0eaccbe014c --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/endstop_state_screen.h @@ -0,0 +1,35 @@ +/************************** + * endstop_state_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 FTDI_ENDSTOP_STATE_SCREEN +#define FTDI_ENDSTOP_STATE_SCREEN_CLASS EndstopStatesScreen + +class EndstopStatesScreen : public BaseScreen, public UncachedScreen { + public: + static void onEntry(); + static void onExit(); + static void onRedraw(draw_mode_t); + static bool onTouchEnd(uint8_t tag); + static void onIdle(); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/feedrate_percent_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/feedrate_percent_screen.cpp similarity index 94% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/feedrate_percent_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/feedrate_percent_screen.cpp index 2698708e51ba..80eb295f6481 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/feedrate_percent_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/feedrate_percent_screen.cpp @@ -17,14 +17,13 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) - -#include "screens.h" +#ifdef FTDI_FEEDRATE_PERCENT_SCREEN using namespace FTDI; using namespace ExtUI; @@ -49,4 +48,4 @@ bool FeedratePercentScreen::onTouchHeld(uint8_t tag) { return true; } -#endif // TOUCH_UI_FTDI_EVE +#endif // FTDI_FEEDRATE_PERCENT_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/feedrate_percent_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/feedrate_percent_screen.h new file mode 100644 index 000000000000..076cfe97ca96 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/feedrate_percent_screen.h @@ -0,0 +1,32 @@ +/***************************** + * feedrate_percent_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 FTDI_FEEDRATE_PERCENT_SCREEN +#define FTDI_FEEDRATE_PERCENT_SCREEN_CLASS FeedratePercentScreen + +class FeedratePercentScreen : public BaseNumericAdjustmentScreen, public CachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchHeld(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/filament_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/filament_menu.cpp similarity index 93% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/filament_menu.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/filament_menu.cpp index 82ee118e4c68..9c9e70cebfc1 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/filament_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/filament_menu.cpp @@ -17,20 +17,19 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) && ANY(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) - -#include "screens.h" +#ifdef FTDI_FILAMENT_MENU using namespace FTDI; using namespace ExtUI; using namespace Theme; -#ifdef TOUCH_UI_PORTRAIT +#if ENABLED(TOUCH_UI_PORTRAIT) #define GRID_ROWS 9 #define GRID_COLS 2 #define TITLE_POS BTN_POS(1,1), BTN_SIZE(2,1) @@ -64,7 +63,7 @@ void FilamentMenu::onRedraw(draw_mode_t what) { .enabled(ENABLED(LIN_ADVANCE)) .tag(3).button(LIN_ADVANCE_POS, GET_TEXT_F(MSG_LINEAR_ADVANCE)) .colors(action_btn) - .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BACK)); + .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BUTTON_DONE)); } } @@ -82,4 +81,4 @@ bool FilamentMenu::onTouchEnd(uint8_t tag) { return true; } -#endif // TOUCH_UI_FTDI_EVE +#endif // FTDI_FILAMENT_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/filament_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/filament_menu.h new file mode 100644 index 000000000000..73ceec29a5e0 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/filament_menu.h @@ -0,0 +1,32 @@ +/******************* + * filament_menu.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 FTDI_FILAMENT_MENU +#define FTDI_FILAMENT_MENU_CLASS FilamentMenu + +class FilamentMenu : public BaseNumericAdjustmentScreen, public CachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchEnd(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/filament_runout_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/filament_runout_screen.cpp similarity index 94% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/filament_runout_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/filament_runout_screen.cpp index f1808bf20e69..37ab70f7ac8d 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/filament_runout_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/filament_runout_screen.cpp @@ -17,14 +17,13 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" -#if BOTH(TOUCH_UI_FTDI_EVE, FILAMENT_RUNOUT_SENSOR) - -#include "screens.h" +#ifdef FTDI_FILAMENT_RUNOUT_SCREEN using namespace FTDI; using namespace ExtUI; @@ -36,7 +35,6 @@ void FilamentRunoutScreen::onRedraw(draw_mode_t what) { w.toggle( 2, GET_TEXT_F(MSG_RUNOUT_SENSOR), getFilamentRunoutEnabled()); #if HAS_FILAMENT_RUNOUT_DISTANCE - extern const char NUL_STR[]; w.heading(GET_TEXT_F(MSG_RUNOUT_DISTANCE_MM)); w.units(GET_TEXT_F(MSG_UNITS_MM)); w.precision(0); @@ -63,4 +61,4 @@ bool FilamentRunoutScreen::onTouchHeld(uint8_t tag) { return true; } -#endif // TOUCH_UI_FTDI_EVE +#endif // FTDI_FILAMENT_RUNOUT_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/filament_runout_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/filament_runout_screen.h new file mode 100644 index 000000000000..ebe7d020cbaf --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/filament_runout_screen.h @@ -0,0 +1,32 @@ +/**************************** + * filament_runout_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 FTDI_FILAMENT_RUNOUT_SCREEN +#define FTDI_FILAMENT_RUNOUT_SCREEN_CLASS FilamentRunoutScreen + +class FilamentRunoutScreen : 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/generic/files_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.cpp new file mode 100644 index 000000000000..aa54e88967da --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.cpp @@ -0,0 +1,269 @@ +/******************** + * files_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 FTDI_FILES_SCREEN + +using namespace FTDI; +using namespace ExtUI; +using namespace Theme; + +constexpr static FilesScreenData &mydata = screen_data.FilesScreen; + +void FilesScreen::onEntry() { + mydata.cur_page = 0; + mydata.selected_tag = 0xFF; + #if ENABLED(SCROLL_LONG_FILENAMES) && (FTDI_API_LEVEL >= 810) + CLCD::mem_write_32(CLCD::REG::MACRO_0,DL::NOP); + #endif + gotoPage(0); + BaseScreen::onEntry(); +} + +const char *FilesScreen::getSelectedFilename(bool longName) { + FileList files; + files.seek(getSelectedFileIndex(), true); + return longName ? files.longFilename() : files.shortFilename(); +} + +void FilesScreen::drawSelectedFile() { + FileList files; + files.seek(getSelectedFileIndex(), true); + mydata.flags.is_dir = files.isDir(); + drawFileButton( + files.filename(), + mydata.selected_tag, + mydata.flags.is_dir, + true + ); +} + +uint16_t FilesScreen::getSelectedFileIndex() { + return getFileForTag(mydata.selected_tag); +} + +uint16_t FilesScreen::getFileForTag(uint8_t tag) { + return mydata.cur_page * files_per_page + tag - 2; +} + +#if ENABLED(TOUCH_UI_PORTRAIT) + #define GRID_COLS 6 + #define GRID_ROWS (files_per_page + header_h + footer_h) +#else + #define GRID_COLS 6 + #define GRID_ROWS (files_per_page + header_h + footer_h) +#endif + +void FilesScreen::drawFileButton(const char *filename, uint8_t tag, bool is_dir, bool is_highlighted) { + const uint8_t line = getLineForTag(tag)+1; + CommandProcessor cmd; + cmd.tag(tag); + cmd.cmd(COLOR_RGB(is_highlighted ? fg_action : bg_color)); + cmd.font(font_medium) + .rectangle( 0, BTN_Y(header_h+line), display_width, BTN_H(1)); + cmd.cmd(COLOR_RGB(is_highlighted ? normal_btn.rgb : bg_text_enabled)); + constexpr uint16_t dim[2] = {BTN_SIZE(6,1)}; + #define POS_AND_SHORTEN(SHORTEN) BTN_POS(1,header_h+line), dim[0] - (SHORTEN), dim[1] + #define POS_AND_SIZE POS_AND_SHORTEN(0) + #if ENABLED(SCROLL_LONG_FILENAMES) + if (is_highlighted) { + cmd.cmd(SAVE_CONTEXT()); + cmd.cmd(MACRO(0)); + cmd.text(POS_AND_SIZE, filename, OPT_CENTERY | OPT_NOFIT); + } else + #endif + draw_text_with_ellipsis(cmd, POS_AND_SHORTEN(is_dir ? 20 : 0), filename, OPT_CENTERY, font_medium); + if (is_dir && !is_highlighted) { + cmd.text(POS_AND_SIZE, F("> "), OPT_CENTERY | OPT_RIGHTX); + } + #if ENABLED(SCROLL_LONG_FILENAMES) + if (is_highlighted) { + cmd.cmd(RESTORE_CONTEXT()); + } + #endif +} + +void FilesScreen::drawFileList() { + FileList files; + mydata.num_page = max(1,ceil(float(files.count()) / files_per_page)); + mydata.cur_page = min(mydata.cur_page, mydata.num_page-1); + mydata.flags.is_root = files.isAtRootDir(); + + #undef MARGIN_T + #undef MARGIN_B + #define MARGIN_T 0 + #define MARGIN_B 0 + uint16_t fileIndex = mydata.cur_page * files_per_page; + for (uint8_t i = 0; i < files_per_page; i++, fileIndex++) { + if (files.seek(fileIndex)) { + drawFileButton(files.filename(), getTagForLine(i), files.isDir(), false); + } + else { + break; + } + } +} + +void FilesScreen::drawHeader() { + const bool prev_enabled = mydata.cur_page > 0; + const bool next_enabled = mydata.cur_page < (mydata.num_page - 1); + + #undef MARGIN_T + #undef MARGIN_B + #define MARGIN_T 0 + #define MARGIN_B 2 + + char str[16]; + sprintf_P(str, PSTR("Page %d of %d"), + mydata.cur_page + 1, mydata.num_page); + + CommandProcessor cmd; + cmd.colors(normal_btn) + .font(font_small) + .tag(0).button(BTN_POS(2,1), BTN_SIZE(4,header_h), str, OPT_CENTER | OPT_FLAT) + .font(font_medium) + .colors(action_btn) + .tag(241).enabled(prev_enabled).button(BTN_POS(1,1), BTN_SIZE(1,header_h), F("<")) + .tag(242).enabled(next_enabled).button(BTN_POS(6,1), BTN_SIZE(1,header_h), F(">")); +} + +void FilesScreen::drawFooter() { + #undef MARGIN_T + #undef MARGIN_B + #if ENABLED(TOUCH_UI_PORTRAIT) + #define MARGIN_T 15 + #define MARGIN_B 5 + #else + #define MARGIN_T 5 + #define MARGIN_B 5 + #endif + const bool has_selection = mydata.selected_tag != 0xFF; + const uint8_t back_tag = mydata.flags.is_root ? 240 : 245; + const uint8_t y = GRID_ROWS - footer_h + 1; + const uint8_t h = footer_h; + + CommandProcessor cmd; + cmd.colors(normal_btn) + .font(font_medium) + .colors(has_selection ? normal_btn : action_btn) + .tag(back_tag).button(BTN_POS(4,y), BTN_SIZE(3,h), GET_TEXT_F(MSG_BUTTON_DONE)) + .enabled(has_selection) + .colors(has_selection ? action_btn : normal_btn); + + if (mydata.flags.is_dir) + cmd.tag(244).button(BTN_POS(1, y), BTN_SIZE(3,h), GET_TEXT_F(MSG_BUTTON_OPEN)); + else + cmd.tag(243).button(BTN_POS(1, y), BTN_SIZE(3,h), GET_TEXT_F(MSG_BUTTON_PRINT)); +} + +void FilesScreen::onRedraw(draw_mode_t what) { + if (what & FOREGROUND) { + drawHeader(); + drawSelectedFile(); + drawFooter(); + } +} + +void FilesScreen::gotoPage(uint8_t page) { + mydata.selected_tag = 0xFF; + mydata.cur_page = page; + CommandProcessor cmd; + cmd.cmd(CMD_DLSTART) + .cmd(CLEAR_COLOR_RGB(bg_color)) + .cmd(CLEAR(true,true,true)) + .colors(normal_btn); + drawFileList(); + storeBackground(); +} + +bool FilesScreen::onTouchEnd(uint8_t tag) { + switch (tag) { + case 240: GOTO_PREVIOUS(); return true; + case 241: + if (mydata.cur_page > 0) { + gotoPage(mydata.cur_page-1); + } + break; + case 242: + if (mydata.cur_page < (mydata.num_page-1)) { + gotoPage(mydata.cur_page+1); + } + break; + case 243: + ConfirmStartPrintDialogBox::show(getSelectedFileIndex()); + return true; + case 244: + { + FileList files; + files.changeDir(getSelectedShortFilename()); + gotoPage(0); + } + break; + case 245: + { + FileList files; + files.upDir(); + gotoPage(0); + } + break; + default: + if (tag < 240) { + mydata.selected_tag = tag; + #if ENABLED(SCROLL_LONG_FILENAMES) && (FTDI_API_LEVEL >= 810) + if (FTDI::ftdi_chip >= 810) { + const char *longFilename = getSelectedLongFilename(); + if (longFilename[0]) { + CommandProcessor cmd; + uint16_t text_width = cmd.font(font_medium).text_width(longFilename); + mydata.scroll_pos = 0; + if (text_width > display_width) + mydata.scroll_max = text_width - display_width + MARGIN_L + MARGIN_R; + else + mydata.scroll_max = 0; + } + } + #endif + } + break; + } + return true; +} + +void FilesScreen::onIdle() { + #if ENABLED(SCROLL_LONG_FILENAMES) && (FTDI_API_LEVEL >= 810) + if (FTDI::ftdi_chip >= 810) { + CLCD::mem_write_32(CLCD::REG::MACRO_0, + VERTEX_TRANSLATE_X(-int32_t(mydata.scroll_pos))); + if (mydata.scroll_pos < mydata.scroll_max * 16) + mydata.scroll_pos++; + } + #endif +} + +void FilesScreen::onMediaRemoved() { + if (AT_SCREEN(FilesScreen)) GOTO_SCREEN(StatusScreen); +} + +#endif // FTDI_FILES_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.h new file mode 100644 index 000000000000..be75684ceb90 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.h @@ -0,0 +1,76 @@ +/****************** + * files_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 FTDI_FILES_SCREEN +#define FTDI_FILES_SCREEN_CLASS FilesScreen + +struct FilesScreenData { + struct { + uint8_t is_dir : 1; + uint8_t is_root : 1; + } flags; + uint8_t selected_tag; + uint8_t num_page; + uint8_t cur_page; + #if ENABLED(SCROLL_LONG_FILENAMES) && (FTDI_API_LEVEL >= 810) + uint16_t scroll_pos; + uint16_t scroll_max; + #endif +}; + +class FilesScreen : public BaseScreen, public CachedScreen { + private: + #if ENABLED(TOUCH_UI_PORTRAIT) + static constexpr uint8_t header_h = 2; + static constexpr uint8_t footer_h = 2; + static constexpr uint8_t files_per_page = 11; + #else + static constexpr uint8_t header_h = 1; + static constexpr uint8_t footer_h = 1; + static constexpr uint8_t files_per_page = 6; + #endif + + static uint8_t getTagForLine(uint8_t line) {return line + 2;} + static uint8_t getLineForTag(uint8_t tag) {return tag - 2;} + static uint16_t getFileForTag(uint8_t tag); + static uint16_t getSelectedFileIndex(); + + inline static const char *getSelectedShortFilename() {return getSelectedFilename(false);} + inline static const char *getSelectedLongFilename() {return getSelectedFilename(true);} + static const char *getSelectedFilename(bool longName); + + static void drawFileButton(const char *filename, uint8_t tag, bool is_dir, bool is_highlighted); + static void drawFileList(); + static void drawHeader(); + static void drawFooter(); + static void drawSelectedFile(); + + static void gotoPage(uint8_t); + public: + static void onEntry(); + static void onRedraw(draw_mode_t); + static bool onTouchEnd(uint8_t tag); + static void onIdle(); + static void onMediaRemoved(); +}; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/flow_percent_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/flow_percent_screen.cpp new file mode 100644 index 000000000000..be350bd9a7f3 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/flow_percent_screen.cpp @@ -0,0 +1,50 @@ +/*************************** + * flow_percent_screen.cpp * + ***************************/ + +/**************************************************************************** + * Written By Marcio Teixeira 2021 - Cocoa Press * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#include "../config.h" +#include "../screens.h" + +#ifdef FTDI_FLOW_PERCENT_SCREEN + +using namespace FTDI; +using namespace ExtUI; + +void FlowPercentScreen::onRedraw(draw_mode_t what) { + widgets_t w(what); + w.precision(0).units(GET_TEXT_F(MSG_UNITS_PERCENT)); + + w.heading(GET_TEXT_F(MSG_FLOW)); + w.adjuster(4, GET_TEXT_F(MSG_FLOW), getFlow_percent(E0)); + w.increments(); +} + +bool FlowPercentScreen::onTouchHeld(uint8_t tag) { + const float increment = getIncrement(); + switch (tag) { + case 4: UI_DECREMENT(Flow_percent, E0); break; + case 5: UI_INCREMENT(Flow_percent, E0); break; + default: + return false; + } + return true; +} + +#endif // FTDI_FLOW_PERCENT_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/flow_percent_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/flow_percent_screen.h new file mode 100644 index 000000000000..3e37531d1d6a --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/flow_percent_screen.h @@ -0,0 +1,31 @@ +/************************* + * flow_percent_screen.h * + *************************/ + +/**************************************************************************** + * Written By Marcio Teixeira 2021 - Cocoa Press * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#pragma once + +#define FTDI_FLOW_PERCENT_SCREEN +#define FTDI_FLOW_PERCENT_SCREEN_CLASS FlowPercentScreen + +class FlowPercentScreen : public BaseNumericAdjustmentScreen, public CachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchHeld(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_settings_screen.cpp similarity index 81% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_settings_screen.cpp index c806ef499b65..5b160c80dfa6 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_settings_screen.cpp @@ -17,22 +17,21 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" +#include "../screen_data.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) - -#include "screens.h" -#include "screen_data.h" +#ifdef FTDI_INTERFACE_SETTINGS_SCREEN #include "../archim2-flash/flash_storage.h" -#include "../../../../../module/settings.h" +#include "../../../../module/settings.h" #if ENABLED(LULZBOT_PRINTCOUNTER) - #include "../../../../../module/printcounter.h" + #include "../../../../module/printcounter.h" #endif bool restoreEEPROM(); @@ -42,13 +41,14 @@ using namespace ExtUI; using namespace Theme; constexpr bool PERSISTENT_STORE_SUCCESS = false; // persistentStore uses true for error +constexpr static InterfaceSettingsScreenData &mydata = screen_data.InterfaceSettingsScreen; void InterfaceSettingsScreen::onStartup() { } void InterfaceSettingsScreen::onEntry() { - screen_data.InterfaceSettingsScreen.brightness = CLCD::get_brightness(); - screen_data.InterfaceSettingsScreen.volume = SoundPlayer::get_volume(); + mydata.brightness = CLCD::get_brightness(); + mydata.volume = SoundPlayer::get_volume(); BaseScreen::onEntry(); } @@ -58,11 +58,7 @@ void InterfaceSettingsScreen::onRedraw(draw_mode_t what) { if (what & BACKGROUND) { #define GRID_COLS 4 - #ifdef TOUCH_UI_PORTRAIT - #define GRID_ROWS 7 - #else - #define GRID_ROWS 6 - #endif + #define GRID_ROWS TERN(TOUCH_UI_PORTRAIT, 7, 6) cmd.cmd(CLEAR_COLOR_RGB(bg_color)) .cmd(CLEAR(true,true,true)) @@ -77,44 +73,46 @@ void InterfaceSettingsScreen::onRedraw(draw_mode_t what) { #if DISABLED(LCD_FYSETC_TFT81050) .text(BTN_POS(1,2), BTN_SIZE(2,1), GET_TEXT_F(MSG_LCD_BRIGHTNESS), OPT_RIGHTX | OPT_CENTERY) #endif - .text(BTN_POS(1,3), BTN_SIZE(2,1), GET_TEXT_F(MSG_SOUND_VOLUME), OPT_RIGHTX | OPT_CENTERY) - .text(BTN_POS(1,4), BTN_SIZE(2,1), GET_TEXT_F(MSG_SCREEN_LOCK), OPT_RIGHTX | OPT_CENTERY); + .text(BTN_POS(1,3), BTN_SIZE(2,1), GET_TEXT_F(MSG_SOUND_VOLUME), OPT_RIGHTX | OPT_CENTERY); + #if ENABLED(FTDI_LOCK_SCREEN) + cmd.text(BTN_POS(1,4), BTN_SIZE(2,1), GET_TEXT_F(MSG_SCREEN_LOCK), OPT_RIGHTX | OPT_CENTERY); + #endif #if DISABLED(TOUCH_UI_NO_BOOTSCREEN) - cmd.text(BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_BOOT_SCREEN), OPT_RIGHTX | OPT_CENTERY); + cmd.text(BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_BOOT_SCREEN), OPT_RIGHTX | OPT_CENTERY); #endif #undef EDGE_R } if (what & FOREGROUND) { - #ifdef TOUCH_UI_PORTRAIT - constexpr uint8_t w = 2; - #else - constexpr uint8_t w = 1; + #if ENABLED(FTDI_LOCK_SCREEN) || DISABLED(TOUCH_UI_NO_BOOTSCREEN) + constexpr uint8_t w = TERN(TOUCH_UI_PORTRAIT, 2, 1); #endif cmd.font(font_medium) #define EDGE_R 30 .colors(ui_slider) #if DISABLED(LCD_FYSETC_TFT81050) - .tag(2).slider(BTN_POS(3,2), BTN_SIZE(2,1), screen_data.InterfaceSettingsScreen.brightness, 128) + .tag(2).slider(BTN_POS(3,2), BTN_SIZE(2,1), mydata.brightness, 128) #endif - .tag(3).slider(BTN_POS(3,3), BTN_SIZE(2,1), screen_data.InterfaceSettingsScreen.volume, 0xFF) + .tag(3).slider(BTN_POS(3,3), BTN_SIZE(2,1), mydata.volume, 0xFF) + #if ENABLED(FTDI_LOCK_SCREEN) .colors(ui_toggle) .tag(4).toggle2(BTN_POS(3,4), BTN_SIZE(w,1), GET_TEXT_F(MSG_NO), GET_TEXT_F(MSG_YES), LockScreen::is_enabled()) + #endif #if DISABLED(TOUCH_UI_NO_BOOTSCREEN) .tag(5).toggle2(BTN_POS(3,5), BTN_SIZE(w,1), GET_TEXT_F(MSG_NO), GET_TEXT_F(MSG_YES), UIData::animations_enabled()) #endif #undef EDGE_R #define EDGE_R 0 - #ifdef TOUCH_UI_PORTRAIT .colors(normal_btn) + #if ENABLED(TOUCH_UI_PORTRAIT) .tag(6).button (BTN_POS(1,6), BTN_SIZE(4,1), GET_TEXT_F(MSG_SOUNDS)) .colors(action_btn) - .tag(1).button (BTN_POS(1,7), BTN_SIZE(4,1), GET_TEXT_F(MSG_BACK)); + .tag(1).button (BTN_POS(1,7), BTN_SIZE(4,1), GET_TEXT_F(MSG_BUTTON_DONE)); #else .tag(6).button (BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_SOUNDS)) .colors(action_btn) - .tag(1).button (BTN_POS(3,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_BACK)); + .tag(1).button (BTN_POS(3,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_BUTTON_DONE)); #endif } } @@ -122,12 +120,14 @@ void InterfaceSettingsScreen::onRedraw(draw_mode_t what) { bool InterfaceSettingsScreen::onTouchEnd(uint8_t tag) { switch (tag) { case 1: GOTO_PREVIOUS(); return true; - case 4: - if (!LockScreen::is_enabled()) - LockScreen::enable(); - else - LockScreen::disable(); - break; + #if ENABLED(FTDI_LOCK_SCREEN) + case 4: + if (!LockScreen::is_enabled()) + LockScreen::enable(); + else + LockScreen::disable(); + break; + #endif case 5: UIData::enable_animations(!UIData::animations_enabled());; break; case 6: GOTO_SCREEN(InterfaceSoundsScreen); return true; default: @@ -161,13 +161,13 @@ void InterfaceSettingsScreen::onIdle() { CommandProcessor cmd; switch (cmd.track_tag(value)) { case 2: - screen_data.InterfaceSettingsScreen.brightness = max(11, (value * 128UL) / 0xFFFF); - CLCD::set_brightness(screen_data.InterfaceSettingsScreen.brightness); + mydata.brightness = max(11, (value * 128UL) / 0xFFFF); + CLCD::set_brightness(mydata.brightness); SaveSettingsDialogBox::settingsChanged(); break; case 3: - screen_data.InterfaceSettingsScreen.volume = value >> 8; - SoundPlayer::set_volume(screen_data.InterfaceSettingsScreen.volume); + mydata.volume = value >> 8; + SoundPlayer::set_volume(mydata.volume); SaveSettingsDialogBox::settingsChanged(); break; default: @@ -179,8 +179,7 @@ void InterfaceSettingsScreen::onIdle() { } void InterfaceSettingsScreen::failSafeSettings() { - // Reset settings that may make the printer interface - // unusable. + // Reset settings that may make the printer interface unusable. CLCD::mem_write_32(CLCD::REG::ROTATE, 0); CLCD::default_touch_transform(); CLCD::default_display_orientation(); @@ -191,7 +190,7 @@ void InterfaceSettingsScreen::failSafeSettings() { } void InterfaceSettingsScreen::defaultSettings() { - LockScreen::passcode = 0; + TERN_(FTDI_LOCK_SCREEN, LockScreen::passcode = 0); SoundPlayer::set_volume(255); CLCD::set_brightness(255); UIData::reset_persistent_data(); @@ -210,7 +209,7 @@ void InterfaceSettingsScreen::saveSettings(char *buff) { persistent_data_t eeprom; - eeprom.passcode = LockScreen::passcode; + eeprom.passcode = TERN0(FTDI_LOCK_SCREEN, LockScreen::passcode); eeprom.sound_volume = SoundPlayer::get_volume(); eeprom.display_brightness = CLCD::get_brightness(); eeprom.bit_flags = UIData::get_persistent_data(); @@ -239,7 +238,9 @@ void InterfaceSettingsScreen::loadSettings(const char *buff) { SERIAL_ECHOLNPGM("Loading setting from EEPROM"); - LockScreen::passcode = eeprom.passcode; + #if ENABLED(FTDI_LOCK_SCREEN) + LockScreen::passcode = eeprom.passcode; + #endif SoundPlayer::set_volume(eeprom.sound_volume); UIData::set_persistent_data(eeprom.bit_flags); CLCD::set_brightness(eeprom.display_brightness); @@ -258,7 +259,7 @@ void InterfaceSettingsScreen::loadSettings(const char *buff) { } #ifdef ARCHIM2_SPI_FLASH_EEPROM_BACKUP_SIZE - #include "../../../../../HAL/shared/eeprom_api.h" + #include "../../../../HAL/shared/eeprom_api.h" bool restoreEEPROM() { uint8_t data[ARCHIM2_SPI_FLASH_EEPROM_BACKUP_SIZE]; @@ -268,10 +269,7 @@ void InterfaceSettingsScreen::loadSettings(const char *buff) { if (success) success = persistentStore.write_data(0, data, ARCHIM2_SPI_FLASH_EEPROM_BACKUP_SIZE) == PERSISTENT_STORE_SUCCESS; - if (success) - StatusScreen::setStatusMessage(GET_TEXT_F(MSG_EEPROM_RESTORED)); - else - StatusScreen::setStatusMessage(GET_TEXT_F(MSG_EEPROM_RESET)); + StatusScreen::setStatusMessage(success ? GET_TEXT_F(MSG_EEPROM_RESTORED) : GET_TEXT_F(MSG_EEPROM_RESET)); return success; } @@ -288,4 +286,4 @@ void InterfaceSettingsScreen::loadSettings(const char *buff) { } #endif -#endif // TOUCH_UI_FTDI_EVE +#endif // FTDI_INTERFACE_SETTINGS_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_settings_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_settings_screen.h new file mode 100644 index 000000000000..f5ddbb10043a --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_settings_screen.h @@ -0,0 +1,67 @@ +/******************************* + * interface_settings_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 FTDI_INTERFACE_SETTINGS_SCREEN +#define FTDI_INTERFACE_SETTINGS_SCREEN_CLASS InterfaceSettingsScreen + +struct InterfaceSettingsScreenData { + uint8_t volume; + uint8_t brightness; +}; + +class InterfaceSettingsScreen : public BaseScreen, public CachedScreen { + private: + struct persistent_data_t { + uint32_t touch_transform_a; + uint32_t touch_transform_b; + uint32_t touch_transform_c; + uint32_t touch_transform_d; + uint32_t touch_transform_e; + uint32_t touch_transform_f; + uint16_t passcode; + uint8_t display_brightness; + int8_t display_h_offset_adj; + int8_t display_v_offset_adj; + uint8_t sound_volume; + uint8_t bit_flags; + uint8_t event_sounds[InterfaceSoundsScreen::NUM_EVENTS]; + }; + + public: + #ifdef ARCHIM2_SPI_FLASH_EEPROM_BACKUP_SIZE + static bool backupEEPROM(); + #endif + + static void saveSettings(char *); + static void loadSettings(const char *); + static void defaultSettings(); + static void failSafeSettings(); + + static void onStartup(); + static void onEntry(); + static void onRedraw(draw_mode_t); + static bool onTouchStart(uint8_t tag); + static bool onTouchEnd(uint8_t tag); + static void onIdle(); +}; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_sounds_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_sounds_screen.cpp new file mode 100644 index 000000000000..889fd606840c --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_sounds_screen.cpp @@ -0,0 +1,125 @@ +/******************************* + * interface_sounds_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 FTDI_INTERFACE_SOUNDS_SCREEN + +using namespace FTDI; +using namespace Theme; +using namespace ExtUI; + +uint8_t InterfaceSoundsScreen::event_sounds[]; + +const char* InterfaceSoundsScreen::getSoundSelection(event_t event) { + return SoundList::name(event_sounds[event]); +} + +void InterfaceSoundsScreen::toggleSoundSelection(event_t event) { + event_sounds[event] = (event_sounds[event]+1) % SoundList::n; + playEventSound(event); +} + +void InterfaceSoundsScreen::setSoundSelection(event_t event, const SoundPlayer::sound_t* sound) { + for (uint8_t i = 0; i < SoundList::n; i++) + if (SoundList::data(i) == sound) + event_sounds[event] = i; +} + +void InterfaceSoundsScreen::playEventSound(event_t event, play_mode_t mode) { + sound.play(SoundList::data(event_sounds[event]), mode); +} + +void InterfaceSoundsScreen::defaultSettings() { + setSoundSelection(PRINTING_STARTED, twinkle); + setSoundSelection(PRINTING_FINISHED, fanfare); + setSoundSelection(PRINTING_FAILED, sad_trombone); +} + +void InterfaceSoundsScreen::onRedraw(draw_mode_t what) { + CommandProcessor cmd; + + if (what & BACKGROUND) { + cmd.cmd(CLEAR_COLOR_RGB(bg_color)) + .cmd(CLEAR(true,true,true)) + .cmd(COLOR_RGB(bg_text_enabled)) + .tag(0) + + #define GRID_COLS 4 + #define GRID_ROWS 9 + + .font(font_medium) + .text(BTN_POS(1,1), BTN_SIZE(4,1), GET_TEXT_F(MSG_SOUNDS)) + #undef EDGE_R + #define EDGE_R 30 + .font(font_small) + .tag(0).text (BTN_POS(1,3), BTN_SIZE(2,1), GET_TEXT_F(MSG_CLICK_SOUNDS), OPT_RIGHTX | OPT_CENTERY) + .text (BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_PRINT_STARTING), OPT_RIGHTX | OPT_CENTERY) + .text (BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_PRINT_FINISHED), OPT_RIGHTX | OPT_CENTERY) + .text (BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_PRINT_ERROR), OPT_RIGHTX | OPT_CENTERY); + #undef EDGE_R + } + + if (what & FOREGROUND) { + #if ENABLED(TOUCH_UI_PORTRAIT) + constexpr uint8_t w = 2; + #else + constexpr uint8_t w = 1; + #endif + + cmd.font(font_small) + #define EDGE_R 30 + .colors(ui_toggle) + .tag(2).toggle2 (BTN_POS(3,3), BTN_SIZE(w,1), GET_TEXT_F(MSG_NO), GET_TEXT_F(MSG_YES), UIData::touch_sounds_enabled()) + #undef EDGE_R + .colors(normal_btn) + #define EDGE_R 0 + .tag(3).button (BTN_POS(3,5), BTN_SIZE(2,1), getSoundSelection(PRINTING_STARTED)) + .tag(4).button (BTN_POS(3,6), BTN_SIZE(2,1), getSoundSelection(PRINTING_FINISHED)) + .tag(5).button (BTN_POS(3,7), BTN_SIZE(2,1), getSoundSelection(PRINTING_FAILED)) + .colors(action_btn) + .tag(1).button (BTN_POS(1,9), BTN_SIZE(4,1), GET_TEXT_F(MSG_BUTTON_DONE)); + } +} + +void InterfaceSoundsScreen::onEntry() { + screen_data.InterfaceSettingsScreen.volume = SoundPlayer::get_volume(); + BaseScreen::onEntry(); +} + +bool InterfaceSoundsScreen::onTouchEnd(uint8_t tag) { + switch (tag) { + case 1: GOTO_PREVIOUS(); return true; + case 2: UIData::enable_touch_sounds(!UIData::touch_sounds_enabled()); break; + case 3: toggleSoundSelection(PRINTING_STARTED); break; + case 4: toggleSoundSelection(PRINTING_FINISHED); break; + case 5: toggleSoundSelection(PRINTING_FAILED); break; + default: + return false; + } + SaveSettingsDialogBox::settingsChanged(); + return true; +} + +#endif // FTDI_INTERFACE_SOUNDS_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_sounds_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_sounds_screen.h new file mode 100644 index 000000000000..258fc77c26c0 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_sounds_screen.h @@ -0,0 +1,55 @@ +/***************************** + * interface_sounds_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 FTDI_INTERFACE_SOUNDS_SCREEN +#define FTDI_INTERFACE_SOUNDS_SCREEN_CLASS InterfaceSoundsScreen + +class InterfaceSoundsScreen : public BaseScreen, public CachedScreen { + public: + enum event_t { + PRINTING_STARTED = 0, + PRINTING_FINISHED = 1, + PRINTING_FAILED = 2, + + NUM_EVENTS + }; + + private: + friend class InterfaceSettingsScreen; + + static uint8_t event_sounds[NUM_EVENTS]; + + static const char* getSoundSelection(event_t); + static void toggleSoundSelection(event_t); + static void setSoundSelection(event_t, const FTDI::SoundPlayer::sound_t*); + + public: + static void playEventSound(event_t, FTDI::play_mode_t = FTDI::PLAY_ASYNCHRONOUS); + + static void defaultSettings(); + + static void onEntry(); + static void onRedraw(draw_mode_t); + static bool onTouchEnd(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/jerk_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/jerk_screen.cpp similarity index 95% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/jerk_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/jerk_screen.cpp index b96c2be7c80c..4331cb7089cb 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/jerk_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/jerk_screen.cpp @@ -17,14 +17,13 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" -#if BOTH(TOUCH_UI_FTDI_EVE, CLASSIC_JERK) - -#include "screens.h" +#ifdef FTDI_JERK_SCREEN using namespace FTDI; using namespace ExtUI; @@ -62,4 +61,4 @@ bool JerkScreen::onTouchHeld(uint8_t tag) { return true; } -#endif // TOUCH_UI_FTDI_EVE && CLASSIC_JERK +#endif // FTDI_JERK_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/jerk_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/jerk_screen.h new file mode 100644 index 000000000000..5f7acb29608d --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/jerk_screen.h @@ -0,0 +1,32 @@ +/***************** + * jerk_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 FTDI_JERK_SCREEN +#define FTDI_JERK_SCREEN_CLASS JerkScreen + +class JerkScreen : public BaseNumericAdjustmentScreen, public CachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchHeld(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/junction_deviation_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/junction_deviation_screen.cpp similarity index 90% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/junction_deviation_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/junction_deviation_screen.cpp index d365b12eb143..98e48167908f 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/junction_deviation_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/junction_deviation_screen.cpp @@ -1,6 +1,6 @@ -/******************* - * boot_screen.cpp * - *******************/ +/********************************* + * junction_deviation_screen.cpp * + *********************************/ /**************************************************************************** * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * @@ -17,14 +17,13 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" -#if BOTH(TOUCH_UI_FTDI_EVE, HAS_JUNCTION_DEVIATION) - -#include "screens.h" +#ifdef FTDI_JUNCTION_DEVIATION_SCREEN using namespace FTDI; using namespace ExtUI; @@ -51,4 +50,4 @@ bool JunctionDeviationScreen::onTouchHeld(uint8_t tag) { return true; } -#endif // TOUCH_UI_FTDI_EVE && !CLASSIC_JERK +#endif // FTDI_JUNCTION_DEVIATION_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/junction_deviation_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/junction_deviation_screen.h new file mode 100644 index 000000000000..2239e2a4500e --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/junction_deviation_screen.h @@ -0,0 +1,32 @@ +/******************************* + * junction_deviation_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 FTDI_JUNCTION_DEVIATION_SCREEN +#define FTDI_JUNCTION_DEVIATION_SCREEN_CLASS JunctionDeviationScreen + +class JunctionDeviationScreen : public BaseNumericAdjustmentScreen, public CachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchHeld(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/kill_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/kill_screen.cpp similarity index 96% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/kill_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/kill_screen.cpp index d98324623c28..bb44a8717693 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/kill_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/kill_screen.cpp @@ -17,14 +17,13 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) - -#include "screens.h" +#ifdef FTDI_KILL_SCREEN using namespace FTDI; @@ -59,4 +58,4 @@ void KillScreen::show(const char *message) { InterfaceSoundsScreen::playEventSound(InterfaceSoundsScreen::PRINTING_FAILED, PLAY_SYNCHRONOUS); } -#endif // TOUCH_UI_FTDI_EVE +#endif // FTDI_KILL_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/kill_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/kill_screen.h new file mode 100644 index 000000000000..b6d94958848a --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/kill_screen.h @@ -0,0 +1,33 @@ +/***************** + * kill_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 FTDI_KILL_SCREEN +#define FTDI_KILL_SCREEN_CLASS KillScreen + +class KillScreen { + // The KillScreen is behaves differently than the + // others, so we do not bother extending UIScreen. + public: + static void show(const char*); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/language_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/language_menu.cpp similarity index 95% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/language_menu.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/language_menu.cpp index 5b4c1c917536..ce6045018b10 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/language_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/language_menu.cpp @@ -17,15 +17,15 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" -#include "../language/language.h" +#include "../screens.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) && NUM_LANGUAGES > 1 +#ifdef FTDI_LANGUAGE_MENU -#include "screens.h" +#include "../language/language.h" using namespace FTDI; using namespace Theme; @@ -63,4 +63,4 @@ bool LanguageMenu::onTouchEnd(uint8_t tag) { return false; } -#endif // TOUCH_UI_FTDI_EVE +#endif // FTDI_LANGUAGE_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/language_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/language_menu.h new file mode 100644 index 000000000000..a86333363f4b --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/language_menu.h @@ -0,0 +1,32 @@ +/******************* + * language_menu.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 FTDI_LANGUAGE_MENU +#define FTDI_LANGUAGE_MENU_CLASS LanguageMenu + +class LanguageMenu : 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/generic/leveling_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp new file mode 100644 index 000000000000..fe5324ae6226 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp @@ -0,0 +1,137 @@ +/********************* + * leveling_menu.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 FTDI_LEVELING_MENU + +#if BOTH(HAS_BED_PROBE,BLTOUCH) + #include "../../../../feature/bltouch.h" +#endif + +using namespace FTDI; +using namespace ExtUI; +using namespace Theme; + +#if ENABLED(TOUCH_UI_PORTRAIT) + #define GRID_ROWS 8 + #define GRID_COLS 2 + #define LEVELING_TITLE_POS BTN_POS(1,1), BTN_SIZE(2,1) + #define LEVEL_AXIS_POS BTN_POS(1,2), BTN_SIZE(2,1) + #define BED_MESH_TITLE_POS BTN_POS(1,3), BTN_SIZE(2,1) + #define PROBE_BED_POS BTN_POS(1,4), BTN_SIZE(1,1) + #define TEST_MESH_POS BTN_POS(2,4), BTN_SIZE(1,1) + #define SHOW_MESH_POS BTN_POS(1,5), BTN_SIZE(1,1) + #define EDIT_MESH_POS BTN_POS(2,5), BTN_SIZE(1,1) + #define BLTOUCH_TITLE_POS BTN_POS(1,6), BTN_SIZE(2,1) + #define BLTOUCH_RESET_POS BTN_POS(1,7), BTN_SIZE(1,1) + #define BLTOUCH_TEST_POS BTN_POS(2,7), BTN_SIZE(1,1) + #define BACK_POS BTN_POS(1,8), BTN_SIZE(2,1) +#else + #define GRID_ROWS 6 + #define GRID_COLS 3 + #define LEVELING_TITLE_POS BTN_POS(1,1), BTN_SIZE(3,1) + #define LEVEL_AXIS_POS BTN_POS(1,2), BTN_SIZE(3,1) + #define BED_MESH_TITLE_POS BTN_POS(1,3), BTN_SIZE(2,1) + #define PROBE_BED_POS BTN_POS(1,4), BTN_SIZE(1,1) + #define TEST_MESH_POS BTN_POS(2,4), BTN_SIZE(1,1) + #define SHOW_MESH_POS BTN_POS(1,5), BTN_SIZE(1,1) + #define EDIT_MESH_POS BTN_POS(2,5), BTN_SIZE(1,1) + #define BLTOUCH_TITLE_POS BTN_POS(3,3), BTN_SIZE(1,1) + #define BLTOUCH_RESET_POS BTN_POS(3,4), BTN_SIZE(1,1) + #define BLTOUCH_TEST_POS BTN_POS(3,5), BTN_SIZE(1,1) + #define BACK_POS BTN_POS(1,6), BTN_SIZE(3,1) +#endif + +void LevelingMenu::onRedraw(draw_mode_t what) { + if (what & BACKGROUND) { + CommandProcessor cmd; + cmd.cmd(CLEAR_COLOR_RGB(Theme::bg_color)) + .cmd(CLEAR(true,true,true)) + .tag(0); + } + + if (what & FOREGROUND) { + CommandProcessor cmd; + cmd.font(font_large) + .cmd(COLOR_RGB(bg_text_enabled)) + .text(LEVELING_TITLE_POS, GET_TEXT_F(MSG_AXIS_LEVELING)) + .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) + .enabled(EITHER(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)) + .enabled(ENABLED(HAS_MESH)) + .tag(4).button(SHOW_MESH_POS, GET_TEXT_F(MSG_SHOW_MESH)) + .enabled(ENABLED(HAS_MESH)) + .tag(5).button(EDIT_MESH_POS, GET_TEXT_F(MSG_EDIT_MESH)) + .enabled(ENABLED(G26_MESH_VALIDATION)) + .tag(6).button(TEST_MESH_POS, GET_TEXT_F(MSG_PRINT_TEST)) + #if ENABLED(BLTOUCH) + .tag(7).button(BLTOUCH_RESET_POS, GET_TEXT_F(MSG_BLTOUCH_RESET)) + .tag(8).button(BLTOUCH_TEST_POS, GET_TEXT_F(MSG_BLTOUCH_SELFTEST)) + #endif + .colors(action_btn) + .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BUTTON_DONE)); + } +} + +bool LevelingMenu::onTouchEnd(uint8_t tag) { + switch (tag) { + case 1: GOTO_PREVIOUS(); break; + #if EITHER(Z_STEPPER_AUTO_ALIGN,MECHANICAL_GANTRY_CALIBRATION) + case 2: SpinnerDialogBox::enqueueAndWait(F("G34")); break; + #endif + #if HAS_BED_PROBE + case 3: + #ifndef BED_LEVELING_COMMANDS + #define BED_LEVELING_COMMANDS "G29" + #endif + #if ENABLED(AUTO_BED_LEVELING_UBL) + BedMeshViewScreen::doProbe(); + #else + SpinnerDialogBox::enqueueAndWait(F(BED_LEVELING_COMMANDS)); + #endif + break; + #endif + #if ENABLED(AUTO_BED_LEVELING_UBL) + case 4: BedMeshViewScreen::show(); break; + case 5: BedMeshEditScreen::show(); break; + #endif + #if ENABLED(G26_MESH_VALIDATION) + case 6: BedMeshViewScreen::doMeshValidation(); break; + #endif + #if ENABLED(BLTOUCH) + case 7: injectCommands_P(PSTR("M280 P0 S60")); break; + case 8: SpinnerDialogBox::enqueueAndWait(F("M280 P0 S90\nG4 P100\nM280 P0 S120")); break; + #endif + default: return false; + } + return true; +} + +#endif // FTDI_LEVELING_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.h new file mode 100644 index 000000000000..aaf852be6cf6 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.h @@ -0,0 +1,32 @@ +/******************* + * leveling_menu.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 FTDI_LEVELING_MENU +#define FTDI_LEVELING_MENU_CLASS LevelingMenu + +class LevelingMenu : public BaseScreen, public CachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchEnd(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/linear_advance_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/linear_advance_screen.cpp similarity index 96% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/linear_advance_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/linear_advance_screen.cpp index 8a5c675facc4..e3b59eef5ce3 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/linear_advance_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/linear_advance_screen.cpp @@ -17,14 +17,13 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" -#if BOTH(TOUCH_UI_FTDI_EVE, LIN_ADVANCE) - -#include "screens.h" +#ifdef FTDI_LINEAR_ADVANCE_SCREEN using namespace FTDI; using namespace ExtUI; @@ -74,4 +73,4 @@ bool LinearAdvanceScreen::onTouchHeld(uint8_t tag) { return true; } -#endif // TOUCH_UI_FTDI_EVE +#endif // FTDI_LINEAR_ADVANCE_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/linear_advance_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/linear_advance_screen.h new file mode 100644 index 000000000000..8c083c8aebaf --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/linear_advance_screen.h @@ -0,0 +1,32 @@ +/*************************** + * linear_advance_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 FTDI_LINEAR_ADVANCE_SCREEN +#define FTDI_LINEAR_ADVANCE_SCREEN_CLASS LinearAdvanceScreen + +class LinearAdvanceScreen : public BaseNumericAdjustmentScreen, public CachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchHeld(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/lock_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/lock_screen.cpp similarity index 80% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/lock_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/lock_screen.cpp index 7854ce5e395c..4e44f26d91fb 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/lock_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/lock_screen.cpp @@ -17,25 +17,25 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" +#include "../screen_data.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) - -#include "screens.h" -#include "screen_data.h" +#ifdef FTDI_LOCK_SCREEN using namespace FTDI; using namespace Theme; uint16_t LockScreen::passcode = 0; +constexpr static LockScreenData &mydata = screen_data.LockScreen; void LockScreen::onEntry() { - const uint8_t siz = sizeof(screen_data.LockScreen.passcode); - memset(screen_data.LockScreen.passcode, '_', siz-1); - screen_data.LockScreen.passcode[siz-1] = '\0'; + const uint8_t siz = sizeof(mydata.passcode); + memset(mydata.passcode, '_', siz-1); + mydata.passcode[siz-1] = '\0'; BaseScreen::onEntry(); } @@ -50,7 +50,7 @@ void LockScreen::onRedraw(draw_mode_t what) { } if (what & FOREGROUND) { - #ifdef TOUCH_UI_PORTRAIT + #if ENABLED(TOUCH_UI_PORTRAIT) #define GRID_COLS 1 #define GRID_ROWS 10 #else @@ -81,14 +81,14 @@ void LockScreen::onRedraw(draw_mode_t what) { const uint8_t pressed = EventLoop::get_pressed_tag(); cmd.font(font_large) - #ifdef TOUCH_UI_PORTRAIT + #if ENABLED(TOUCH_UI_PORTRAIT) .text(BTN_POS(1,2), BTN_SIZE(1,1), message) .font(font_xlarge) - .text(BTN_POS(1,4), BTN_SIZE(1,1), screen_data.LockScreen.passcode) + .text(BTN_POS(1,4), BTN_SIZE(1,1), mydata.passcode) #else .text(BTN_POS(1,1), BTN_SIZE(1,1), message) .font(font_xlarge) - .text(BTN_POS(1,2), BTN_SIZE(1,1), screen_data.LockScreen.passcode) + .text(BTN_POS(1,2), BTN_SIZE(1,1), mydata.passcode) #endif .font(font_large) .colors(normal_btn) @@ -117,41 +117,38 @@ void LockScreen::onRedraw(draw_mode_t what) { char &LockScreen::message_style() { // We use the last byte of the passcode string as a flag to indicate, // which message to show. - constexpr uint8_t last_char = sizeof(screen_data.LockScreen.passcode)-1; - return screen_data.LockScreen.passcode[last_char]; + constexpr uint8_t last_char = sizeof(mydata.passcode)-1; + return mydata.passcode[last_char]; } void LockScreen::onPasscodeEntered() { - if (passcode == 0) { - // We are defining a passcode + if (passcode == 0) { // We are defining a passcode message_style() = 0; onRefresh(); sound.play(twinkle, PLAY_SYNCHRONOUS); passcode = compute_checksum(); GOTO_PREVIOUS(); - } else { - // We are verifying a passcode - if (passcode == compute_checksum()) { - message_style() = 'g'; - onRefresh(); - sound.play(twinkle, PLAY_SYNCHRONOUS); - GOTO_PREVIOUS(); - } - else { - message_style() = 'w'; - onRefresh(); - sound.play(sad_trombone, PLAY_SYNCHRONOUS); - current_screen.forget(); // Discard the screen the user was trying to go to. - GOTO_PREVIOUS(); - } + } + else if (passcode == compute_checksum()) { // We are verifying a passcode + message_style() = 'g'; + onRefresh(); + sound.play(twinkle, PLAY_SYNCHRONOUS); + GOTO_PREVIOUS(); + } + else { + message_style() = 'w'; + onRefresh(); + sound.play(sad_trombone, PLAY_SYNCHRONOUS); + current_screen.forget(); // Discard the screen the user was trying to go to. + GOTO_PREVIOUS(); } } bool LockScreen::onTouchEnd(uint8_t tag) { - char *c = strchr(screen_data.LockScreen.passcode,'_'); + char *c = strchr(mydata.passcode,'_'); if (c) { if (tag == '<') { - if (c != screen_data.LockScreen.passcode) { + if (c != mydata.passcode) { // Backspace deletes previous entered characters. *--c = '_'; } @@ -170,7 +167,7 @@ bool LockScreen::onTouchEnd(uint8_t tag) { uint16_t LockScreen::compute_checksum() { uint16_t checksum = 0; - const char* c = screen_data.LockScreen.passcode; + const char* c = mydata.passcode; while (*c) { checksum = (checksum << 2) ^ *c++; } @@ -205,4 +202,4 @@ void LockScreen::enable() { GOTO_SCREEN(LockScreen); } -#endif // TOUCH_UI_FTDI_EVE +#endif // FTDI_LOCK_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/lock_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/lock_screen.h new file mode 100644 index 000000000000..b73424fc5a5f --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/lock_screen.h @@ -0,0 +1,53 @@ +/***************** + * lock_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 FTDI_LOCK_SCREEN +#define FTDI_LOCK_SCREEN_CLASS LockScreen + +struct LockScreenData { + char passcode[5]; +}; + +class LockScreen : public BaseScreen, public CachedScreen { + private: + friend InterfaceSettingsScreen; + + static uint16_t passcode; + + static char & message_style(); + static uint16_t compute_checksum(); + static void onPasscodeEntered(); + public: + static bool is_enabled(); + static void check_passcode(); + static void enable(); + static void disable(); + + static void set_hash(uint16_t pass) { passcode = pass; } + static uint16_t get_hash() { return passcode; } + + 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/generic/main_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/main_menu.cpp new file mode 100644 index 000000000000..a6c39db79606 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/main_menu.cpp @@ -0,0 +1,130 @@ +/***************** + * main_menu.cpp * + *****************/ + +/**************************************************************************** + * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2019 - Cocoa Press * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#include "../config.h" +#include "../screens.h" + +#ifdef FTDI_MAIN_MENU + +using namespace FTDI; +using namespace Theme; + +void MainMenu::onRedraw(draw_mode_t what) { + if (what & BACKGROUND) { + CommandProcessor cmd; + cmd.cmd(CLEAR_COLOR_RGB(Theme::bg_color)) + .cmd(CLEAR(true,true,true)); + } + + #if ENABLED(TOUCH_UI_PORTRAIT) + #define GRID_ROWS 8 + #define GRID_COLS 2 + #define ABOUT_PRINTER_POS BTN_POS(1,1), BTN_SIZE(2,1) + #define ADVANCED_SETTINGS_POS BTN_POS(1,2), BTN_SIZE(2,1) + #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) + #else + #define FILAMENTCHANGE_POS BTN_POS(1,3), BTN_SIZE(2,1) + #endif + #define TEMPERATURE_POS BTN_POS(1,4), BTN_SIZE(2,1) + #define DISABLE_STEPPERS_POS BTN_POS(1,5), BTN_SIZE(2,1) + #define MOVE_AXIS_POS BTN_POS(1,6), BTN_SIZE(1,1) + #define LEVELING_POS BTN_POS(2,6), BTN_SIZE(1,1) + #define AUTO_HOME_POS BTN_POS(1,7), BTN_SIZE(1,1) + #define CLEAN_NOZZLE_POS BTN_POS(2,7), BTN_SIZE(1,1) + #define BACK_POS BTN_POS(1,8), BTN_SIZE(2,1) + #else + #define GRID_ROWS 5 + #define GRID_COLS 6 + #define ADVANCED_SETTINGS_POS BTN_POS(1,1), BTN_SIZE(3,1) + #define ABOUT_PRINTER_POS BTN_POS(4,1), BTN_SIZE(3,1) + #define AUTO_HOME_POS BTN_POS(1,2), BTN_SIZE(3,1) + #define CLEAN_NOZZLE_POS BTN_POS(4,2), BTN_SIZE(3,1) + #define MOVE_AXIS_POS BTN_POS(1,3), BTN_SIZE(3,1) + #define DISABLE_STEPPERS_POS BTN_POS(4,3), BTN_SIZE(3,1) + #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) + #else + #define TEMPERATURE_POS BTN_POS(1,4), BTN_SIZE(3,1) + #define FILAMENTCHANGE_POS BTN_POS(4,4), BTN_SIZE(3,1) + #endif + #define LEVELING_POS BTN_POS(1,5), BTN_SIZE(3,1) + #define BACK_POS BTN_POS(4,5), BTN_SIZE(3,1) + #endif + + if (what & FOREGROUND) { + CommandProcessor cmd; + cmd.colors(normal_btn) + .font(Theme::font_medium) + .tag( 2).button(AUTO_HOME_POS, GET_TEXT_F(MSG_AUTO_HOME)) + .enabled(ENABLED(NOZZLE_CLEAN_FEATURE)) + .tag( 3).button(CLEAN_NOZZLE_POS, GET_TEXT_F(MSG_CLEAN_NOZZLE)) + .tag( 4).button(MOVE_AXIS_POS, GET_TEXT_F(MSG_MOVE_AXIS)) + .tag( 5).button(DISABLE_STEPPERS_POS,GET_TEXT_F(MSG_DISABLE_STEPPERS)) + .tag( 6).button(TEMPERATURE_POS, GET_TEXT_F(MSG_TEMPERATURE)) + .enabled(IF_DISABLED(TOUCH_UI_LULZBOT_BIO, 1)) + .tag( 7).button(FILAMENTCHANGE_POS, GET_TEXT_F(MSG_FILAMENTCHANGE)) + .tag( 8).button(ADVANCED_SETTINGS_POS, GET_TEXT_F(MSG_ADVANCED_SETTINGS)) + .enabled(TERN_(HAS_LEVELING, 1)) + .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)) + #endif + .colors(action_btn) + .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BUTTON_DONE)); + } +} + +bool MainMenu::onTouchEnd(uint8_t tag) { + using namespace ExtUI; + + switch (tag) { + case 1: SaveSettingsDialogBox::promptToSaveSettings(); break; + case 2: SpinnerDialogBox::enqueueAndWait(F("G28")); break; + #if ENABLED(NOZZLE_CLEAN_FEATURE) + case 3: injectCommands_P(PSTR("G12")); GOTO_SCREEN(StatusScreen); break; + #endif + case 4: GOTO_SCREEN(MoveAxisScreen); break; + case 5: injectCommands_P(PSTR("M84")); break; + case 6: GOTO_SCREEN(TemperatureScreen); break; + case 7: GOTO_SCREEN(ChangeFilamentScreen); break; + case 8: GOTO_SCREEN(AdvancedSettingsMenu); break; + #if HAS_LEVELING + case 9: GOTO_SCREEN(LevelingMenu); break; + #endif + case 10: GOTO_SCREEN(AboutScreen); break; + #if ENABLED(CUSTOM_MENU_MAIN) + case 11: GOTO_SCREEN(CustomUserMenus); break; + #endif + + default: + return false; + } + return true; +} + +#endif // FTDI_MAIN_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/main_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/main_menu.h new file mode 100644 index 000000000000..ac1300e1b8e4 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/main_menu.h @@ -0,0 +1,33 @@ +/*************** + * main_menu.h * + ***************/ + +/**************************************************************************** + * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2019 - Cocoa Press * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#pragma once + +#define FTDI_MAIN_MENU +#define FTDI_MAIN_MENU_CLASS MainMenu + +class MainMenu : public BaseScreen, public CachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchEnd(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/max_acceleration_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_acceleration_screen.cpp similarity index 97% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/max_acceleration_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_acceleration_screen.cpp index 29ac2f1b4038..be3a24438018 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/max_acceleration_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_acceleration_screen.cpp @@ -17,14 +17,13 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) - -#include "screens.h" +#ifdef FTDI_MAX_ACCELERATION_SCREEN using namespace FTDI; using namespace ExtUI; @@ -83,4 +82,4 @@ bool MaxAccelerationScreen::onTouchHeld(uint8_t tag) { return true; } -#endif // TOUCH_UI_FTDI_EVE +#endif // FTDI_MAX_ACCELERATION_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_acceleration_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_acceleration_screen.h new file mode 100644 index 000000000000..87a79b3bd9bc --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_acceleration_screen.h @@ -0,0 +1,32 @@ +/***************************** + * max_acceleration_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 FTDI_MAX_ACCELERATION_SCREEN +#define FTDI_MAX_ACCELERATION_SCREEN_CLASS MaxAccelerationScreen + +class MaxAccelerationScreen : public BaseNumericAdjustmentScreen, public CachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchHeld(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/max_velocity_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_velocity_screen.cpp similarity index 97% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/max_velocity_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_velocity_screen.cpp index 2316f93ee236..bca533c94f19 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/max_velocity_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_velocity_screen.cpp @@ -17,14 +17,13 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) - -#include "screens.h" +#ifdef FTDI_MAX_VELOCITY_SCREEN using namespace FTDI; using namespace ExtUI; @@ -87,4 +86,4 @@ bool MaxVelocityScreen::onTouchHeld(uint8_t tag) { return true; } -#endif // TOUCH_UI_FTDI_EVE +#endif // FTDI_MAX_VELOCITY_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_velocity_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_velocity_screen.h new file mode 100644 index 000000000000..e904a2c05899 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_velocity_screen.h @@ -0,0 +1,32 @@ +/************************* + * max_velocity_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 FTDI_MAX_VELOCITY_SCREEN +#define FTDI_MAX_VELOCITY_SCREEN_CLASS MaxVelocityScreen + +class MaxVelocityScreen : public BaseNumericAdjustmentScreen, public CachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchHeld(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/media_player_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/media_player_screen.cpp similarity index 97% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/media_player_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/media_player_screen.cpp index d7e476e04ef5..061c8555df54 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/media_player_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/media_player_screen.cpp @@ -17,10 +17,11 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" /** * The MediaPlayerScreen allows an AVI to be played. @@ -39,9 +40,7 @@ * ffmpeg -i video.avi -i silence.wav -c copy -map 0:v:0 -map 1:a:0 startup.avi */ -#if ENABLED(TOUCH_UI_FTDI_EVE) - -#include "screens.h" +#ifdef FTDI_MEDIA_PLAYER_SCREEN #include "../archim2-flash/flash_storage.h" #include "../archim2-flash/media_file_reader.h" @@ -151,7 +150,7 @@ void MediaPlayerScreen::playStream(void *obj, media_streamer_func_t *data_stream SERIAL_ECHO_MSG("Done playing video"); exit: - spiInit(SPI_SPEED); // Restore default speed + spiInit(SD_SPI_SPEED); // Restore default speed // Since playing media overwrites RAMG, we need to reinitialize // everything that is stored in RAMG. @@ -165,4 +164,4 @@ void MediaPlayerScreen::playStream(void *obj, media_streamer_func_t *data_stream #endif // FTDI_API_LEVEL >= 810 } -#endif // TOUCH_UI_FTDI_EVE +#endif // FTDI_MEDIA_PLAYER_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/media_player_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/media_player_screen.h new file mode 100644 index 000000000000..510d5a938634 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/media_player_screen.h @@ -0,0 +1,40 @@ +/************************* + * media_player_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 FTDI_MEDIA_PLAYER_SCREEN +#define FTDI_MEDIA_PLAYER_SCREEN_CLASS MediaPlayerScreen + +class MediaPlayerScreen : public BaseScreen, public UncachedScreen { + private: + typedef int16_t media_streamer_func_t(void *obj, void *buff, size_t bytes); + + public: + static bool playCardMedia(); + static bool playBootMedia(); + + static void onEntry(); + static void onRedraw(draw_mode_t); + + static void playStream(void *obj, media_streamer_func_t*); +}; 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 new file mode 100644 index 000000000000..a3c3b503d89c --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/move_axis_screen.cpp @@ -0,0 +1,143 @@ +/************************ + * move_axis_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 FTDI_MOVE_AXIS_SCREEN + +using namespace FTDI; +using namespace ExtUI; + +constexpr static MoveAxisScreenData &mydata = screen_data.MoveAxisScreen; + +void BaseMoveAxisScreen::onEntry() { + // Since Marlin keeps only one absolute position for all the extruders, + // we have to keep track of the relative motion of individual extruders + // ourselves. The relative distances are reset to zero whenever this + // screen is entered. + + LOOP_L_N(i, ExtUI::extruderCount) { + mydata.e_rel[i] = 0; + } + BaseNumericAdjustmentScreen::onEntry(); +} + +void MoveAxisScreen::onRedraw(draw_mode_t what) { + widgets_t w(what); + w.precision(1); + w.units(GET_TEXT_F(MSG_UNITS_MM)); + w.heading( GET_TEXT_F(MSG_MOVE_AXIS)); + w.home_buttons(20); + w.color(Theme::x_axis).adjuster( 2, GET_TEXT_F(MSG_AXIS_X), getAxisPosition_mm(X), canMove(X)); + w.color(Theme::y_axis).adjuster( 4, GET_TEXT_F(MSG_AXIS_Y), getAxisPosition_mm(Y), canMove(Y)); + w.color(Theme::z_axis).adjuster( 6, GET_TEXT_F(MSG_AXIS_Z), getAxisPosition_mm(Z), canMove(Z)); + + w.color(Theme::e_axis); + #if EXTRUDERS == 1 + w.adjuster( 8, GET_TEXT_F(MSG_AXIS_E), mydata.e_rel[0], canMove(E0)); + #elif HAS_MULTI_EXTRUDER + w.adjuster( 8, GET_TEXT_F(MSG_AXIS_E1), mydata.e_rel[0], canMove(E0)); + w.adjuster( 10, GET_TEXT_F(MSG_AXIS_E2), mydata.e_rel[1], canMove(E1)); + #if EXTRUDERS > 2 + w.adjuster( 12, GET_TEXT_F(MSG_AXIS_E3), mydata.e_rel[2], canMove(E2)); + #endif + #if EXTRUDERS > 3 + w.adjuster( 14, GET_TEXT_F(MSG_AXIS_E4), mydata.e_rel[3], canMove(E3)); + #endif + #endif + #if Z_HOME_TO_MIN + w.button(24, GET_TEXT_F(MSG_MOVE_Z_TO_TOP), !axis_should_home(Z_AXIS)); + #endif + w.increments(); +} + +bool BaseMoveAxisScreen::onTouchHeld(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; + case 4: UI_DECREMENT_AXIS(Y); break; + case 5: UI_INCREMENT_AXIS(Y); break; + case 6: UI_DECREMENT_AXIS(Z); break; + case 7: UI_INCREMENT_AXIS(Z); break; + // For extruders, also update relative distances. + case 8: UI_DECREMENT_AXIS(E0); mydata.e_rel[0] -= increment; break; + case 9: UI_INCREMENT_AXIS(E0); mydata.e_rel[0] += increment; break; + #if HAS_MULTI_EXTRUDER + case 10: UI_DECREMENT_AXIS(E1); mydata.e_rel[1] -= increment; break; + case 11: UI_INCREMENT_AXIS(E1); mydata.e_rel[1] += increment; break; + #endif + #if EXTRUDERS > 2 + case 12: UI_DECREMENT_AXIS(E2); mydata.e_rel[2] -= increment; break; + case 13: UI_INCREMENT_AXIS(E2); mydata.e_rel[2] += increment; break; + #endif + #if EXTRUDERS > 3 + case 14: UI_DECREMENT_AXIS(E3); mydata.e_rel[3] -= increment; break; + case 15: UI_INCREMENT_AXIS(E3); mydata.e_rel[3] += increment; break; + #endif + case 20: SpinnerDialogBox::enqueueAndWait(F("G28X")); break; + case 21: SpinnerDialogBox::enqueueAndWait(F("G28Y")); break; + case 22: SpinnerDialogBox::enqueueAndWait(F("G28Z")); break; + case 23: SpinnerDialogBox::enqueueAndWait(F("G28")); break; + case 24: raiseZtoTop(); break; + default: + return false; + } + #undef UI_DECREMENT_AXIS + #undef UI_INCREMENT_AXIS + return true; +} + +void BaseMoveAxisScreen::raiseZtoTop() { + constexpr xyze_feedrate_t homing_feedrate = HOMING_FEEDRATE_MM_M; + setAxisPosition_mm(Z_MAX_POS - 5, Z, homing_feedrate[Z_AXIS]); +} + +float BaseMoveAxisScreen::getManualFeedrate(uint8_t axis, float 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)); +} + +void BaseMoveAxisScreen::setManualFeedrate(ExtUI::axis_t axis, float increment_mm) { + ExtUI::setFeedrate_mm_s(getManualFeedrate(X_AXIS + (axis - ExtUI::X), increment_mm)); +} + +void BaseMoveAxisScreen::setManualFeedrate(ExtUI::extruder_t, float increment_mm) { + ExtUI::setFeedrate_mm_s(getManualFeedrate(E_AXIS, increment_mm)); +} + +void MoveAxisScreen::onIdle() { + if (refresh_timer.elapsed(STATUS_UPDATE_INTERVAL)) { + onRefresh(); + refresh_timer.start(); + } + BaseScreen::onIdle(); +} + +#endif // FTDI_MOVE_AXIS_SCREEN 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 new file mode 100644 index 000000000000..16723cfc13bc --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/move_axis_screen.h @@ -0,0 +1,49 @@ +/********************** + * move_axis_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 FTDI_MOVE_AXIS_SCREEN +#define FTDI_MOVE_AXIS_SCREEN_CLASS MoveAxisScreen + +struct MoveAxisScreenData { + struct BaseNumericAdjustmentScreenData placeholder; + float e_rel[ExtUI::extruderCount]; +}; + +class BaseMoveAxisScreen : public BaseNumericAdjustmentScreen { + private: + static float getManualFeedrate(uint8_t axis, float 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 onEntry(); + static bool onTouchHeld(uint8_t tag); +}; + +class MoveAxisScreen : public BaseMoveAxisScreen, public CachedScreen { + public: + static void onRedraw(draw_mode_t); + static void onIdle(); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/nozzle_offsets_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/nozzle_offsets_screen.cpp similarity index 96% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/nozzle_offsets_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/nozzle_offsets_screen.cpp index 07d6900c16f4..288d06ea8e76 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/nozzle_offsets_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/nozzle_offsets_screen.cpp @@ -17,14 +17,13 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" -#if BOTH(TOUCH_UI_FTDI_EVE, HAS_MULTI_HOTEND) - -#include "screens.h" +#ifdef FTDI_NOZZLE_OFFSETS_SCREEN using namespace FTDI; using namespace ExtUI; @@ -70,4 +69,4 @@ bool NozzleOffsetScreen::onTouchHeld(uint8_t tag) { return true; } -#endif // TOUCH_UI_FTDI_EVE +#endif // FTDI_NOZZLE_OFFSETS_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/nozzle_offsets_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/nozzle_offsets_screen.h new file mode 100644 index 000000000000..763f3364ce3a --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/nozzle_offsets_screen.h @@ -0,0 +1,33 @@ +/*************************** + * nozzle_offsets_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 FTDI_NOZZLE_OFFSETS_SCREEN +#define FTDI_NOZZLE_OFFSETS_SCREEN_CLASS NozzleOffsetScreen + +class NozzleOffsetScreen : public BaseNumericAdjustmentScreen, public CachedScreen { + public: + static void onEntry(); + static void onRedraw(draw_mode_t); + static bool onTouchHeld(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/nudge_nozzle_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/nudge_nozzle_screen.cpp new file mode 100644 index 000000000000..c1611100a98e --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/nudge_nozzle_screen.cpp @@ -0,0 +1,124 @@ +/******************** + * nudge_nozzle.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 FTDI_NUDGE_NOZZLE_SCREEN + +using namespace FTDI; +using namespace Theme; +using namespace ExtUI; + +constexpr static NudgeNozzleScreenData &mydata = screen_data.NudgeNozzleScreen; + +void NudgeNozzleScreen::onEntry() { + mydata.show_offsets = false; + #if HAS_MULTI_EXTRUDER + mydata.link_nozzles = true; + #endif + mydata.rel.reset(); + + BaseNumericAdjustmentScreen::onEntry(); +} + +void NudgeNozzleScreen::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_NUDGE_NOZZLE)); + #if ENABLED(BABYSTEP_XY) + w.color(x_axis).adjuster(2, GET_TEXT_F(MSG_AXIS_X), mydata.rel.x / getAxisSteps_per_mm(X)); + w.color(y_axis).adjuster(4, GET_TEXT_F(MSG_AXIS_Y), mydata.rel.y / getAxisSteps_per_mm(Y)); + #endif + w.color(z_axis).adjuster(6, GET_TEXT_F(MSG_AXIS_Z), mydata.rel.z / getAxisSteps_per_mm(Z)); + w.increments(); + #if HAS_MULTI_EXTRUDER + w.toggle(8, GET_TEXT_F(MSG_ADJUST_BOTH_NOZZLES), mydata.link_nozzles); + #endif + + #if HAS_MULTI_EXTRUDER || HAS_BED_PROBE + w.toggle(9, GET_TEXT_F(MSG_SHOW_OFFSETS), mydata.show_offsets); + + if (mydata.show_offsets) { + char str[19]; + + w.draw_mode(BOTH); + w.color(other); + + #if HAS_BED_PROBE + dtostrf(getZOffset_mm(), 4, 2, str); + strcat(str, " "); + strcat_P(str, GET_TEXT(MSG_UNITS_MM)); + w.text_field(0, GET_TEXT_F(MSG_ZPROBE_ZOFFSET), str); + #endif + + #if HAS_MULTI_HOTEND + format_position(str, getNozzleOffset_mm(X, E1), getNozzleOffset_mm(Y, E1), getNozzleOffset_mm(Z, E1)); + w.text_field(0, GET_TEXT_F(MSG_OFFSETS_MENU), str); + #endif + } + #endif +} + +bool NudgeNozzleScreen::onTouchHeld(uint8_t tag) { + const float inc = getIncrement(); + #if HAS_MULTI_EXTRUDER + const bool link = mydata.link_nozzles; + #else + constexpr bool link = true; + #endif + int16_t steps; + switch (tag) { + case 2: steps = mmToWholeSteps(inc, X); smartAdjustAxis_steps(-steps, X, link); mydata.rel.x -= steps; break; + case 3: steps = mmToWholeSteps(inc, X); smartAdjustAxis_steps( steps, X, link); mydata.rel.x += steps; break; + case 4: steps = mmToWholeSteps(inc, Y); smartAdjustAxis_steps(-steps, Y, link); mydata.rel.y -= steps; break; + case 5: steps = mmToWholeSteps(inc, Y); smartAdjustAxis_steps( steps, Y, link); mydata.rel.y += steps; break; + case 6: steps = mmToWholeSteps(inc, Z); smartAdjustAxis_steps(-steps, Z, link); mydata.rel.z -= steps; break; + case 7: steps = mmToWholeSteps(inc, Z); smartAdjustAxis_steps( steps, Z, link); mydata.rel.z += steps; break; + #if HAS_MULTI_EXTRUDER + case 8: mydata.link_nozzles = !link; break; + #endif + case 9: mydata.show_offsets = !mydata.show_offsets; break; + default: return false; + } + #if HAS_MULTI_EXTRUDER || HAS_BED_PROBE + SaveSettingsDialogBox::settingsChanged(); + #endif + return true; +} + +bool NudgeNozzleScreen::onTouchEnd(uint8_t tag) { + if (tag == 1) { + SaveSettingsDialogBox::promptToSaveSettings(); + return true; + } + else + return BaseNumericAdjustmentScreen::onTouchEnd(tag); +} + +void NudgeNozzleScreen::onIdle() { + reset_menu_timeout(); +} + +#endif // FTDI_NUDGE_NOZZLE_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/nudge_nozzle_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/nudge_nozzle_screen.h new file mode 100644 index 000000000000..c490a25fea40 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/nudge_nozzle_screen.h @@ -0,0 +1,44 @@ +/****************** + * nudge_nozzle.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 FTDI_NUDGE_NOZZLE_SCREEN +#define FTDI_NUDGE_NOZZLE_SCREEN_CLASS NudgeNozzleScreen + +struct NudgeNozzleScreenData { + struct BaseNumericAdjustmentScreenData placeholder; + xyz_int_t rel; + #if HAS_MULTI_EXTRUDER + bool link_nozzles; + #endif + bool show_offsets; +}; + +class NudgeNozzleScreen : public BaseNumericAdjustmentScreen, public CachedScreen { + public: + static void onEntry(); + static void onRedraw(draw_mode_t); + static bool onTouchEnd(uint8_t tag); + static bool onTouchHeld(uint8_t tag); + static void onIdle(); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/restore_failsafe_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/restore_failsafe_dialog_box.cpp similarity index 94% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/restore_failsafe_dialog_box.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/restore_failsafe_dialog_box.cpp index 94b8ac0fb50f..2dfd64fa5b1c 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/restore_failsafe_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/restore_failsafe_dialog_box.cpp @@ -17,14 +17,13 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) - -#include "screens.h" +#ifdef FTDI_RESTORE_FAILSAFE_DIALOG_BOX using namespace ExtUI; @@ -48,4 +47,4 @@ bool RestoreFailsafeDialogBox::onTouchEnd(uint8_t tag) { } } -#endif // TOUCH_UI_FTDI_EVE +#endif // FTDI_RESTORE_FAILSAFE_DIALOG_BOX diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/restore_failsafe_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/restore_failsafe_dialog_box.h new file mode 100644 index 000000000000..84a994730d32 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/restore_failsafe_dialog_box.h @@ -0,0 +1,32 @@ +/********************************* + * restore_failsafe_dialog_box.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 FTDI_RESTORE_FAILSAFE_DIALOG_BOX +#define FTDI_RESTORE_FAILSAFE_DIALOG_BOX_CLASS RestoreFailsafeDialogBox + +class RestoreFailsafeDialogBox : public DialogBoxBaseClass, public UncachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchEnd(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/save_settings_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/save_settings_dialog_box.cpp similarity index 89% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/save_settings_dialog_box.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/save_settings_dialog_box.cpp index f4a99accd63d..5d92052aceaa 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/save_settings_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/save_settings_dialog_box.cpp @@ -17,14 +17,13 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) - -#include "screens.h" +#ifdef FTDI_SAVE_SETTINGS_DIALOG_BOX using namespace ExtUI; @@ -56,10 +55,13 @@ void SaveSettingsDialogBox::promptToSaveSettings() { // so SaveSettingsDialogBox doesn't return here. GOTO_SCREEN(SaveSettingsDialogBox); current_screen.forget(); - } else { - // No save needed. - GOTO_PREVIOUS(); } + else + GOTO_PREVIOUS(); // No save needed. +} + +void SaveSettingsDialogBox::promptToSaveAndStay() { + if (needs_save) GOTO_SCREEN(SaveSettingsDialogBox); } -#endif // TOUCH_UI_FTDI_EVE +#endif // FTDI_SAVE_SETTINGS_DIALOG_BOX diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/save_settings_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/save_settings_dialog_box.h new file mode 100644 index 000000000000..0cbadfbbe6c9 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/save_settings_dialog_box.h @@ -0,0 +1,39 @@ +/****************************** + * save_settings_dialog_box.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 FTDI_SAVE_SETTINGS_DIALOG_BOX +#define FTDI_SAVE_SETTINGS_DIALOG_BOX_CLASS SaveSettingsDialogBox + +class SaveSettingsDialogBox : public DialogBoxBaseClass, public UncachedScreen { + private: + static bool needs_save; + + public: + static void onRedraw(draw_mode_t); + static bool onTouchEnd(uint8_t tag); + + static void promptToSaveSettings(); + static void promptToSaveAndStay(); + static void settingsChanged() {needs_save = true;} +}; 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 new file mode 100644 index 000000000000..b88e51757690 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/screens.h @@ -0,0 +1,224 @@ +/************* + * screens.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 + +/********************************* DL CACHE SLOTS ******************************/ + +// In order to reduce SPI traffic, we cache display lists (DL) in RAMG. This +// is done using the CLCD::DLCache class, which takes a unique ID for each +// cache location. These IDs are defined here: + +enum { + STATUS_SCREEN_CACHE, + MENU_SCREEN_CACHE, + TUNE_SCREEN_CACHE, + ALERT_BOX_CACHE, + SPINNER_CACHE, + ADVANCED_SETTINGS_SCREEN_CACHE, + MOVE_AXIS_SCREEN_CACHE, + TEMPERATURE_SCREEN_CACHE, + STEPS_SCREEN_CACHE, + MAX_FEEDRATE_SCREEN_CACHE, + MAX_VELOCITY_SCREEN_CACHE, + MAX_ACCELERATION_SCREEN_CACHE, + DEFAULT_ACCELERATION_SCREEN_CACHE, + FLOW_PERCENT_SCREEN_CACHE, + #if HAS_LEVELING + LEVELING_SCREEN_CACHE, + #if HAS_BED_PROBE + ZOFFSET_SCREEN_CACHE, + #endif + #if HAS_MESH + BED_MESH_VIEW_SCREEN_CACHE, + BED_MESH_EDIT_SCREEN_CACHE, + #endif + #endif + #if ENABLED(BABYSTEPPING) + ADJUST_OFFSETS_SCREEN_CACHE, + #endif + #if HAS_TRINAMIC_CONFIG + STEPPER_CURRENT_SCREEN_CACHE, + STEPPER_BUMP_SENSITIVITY_SCREEN_CACHE, + #endif + #if HAS_MULTI_HOTEND + NOZZLE_OFFSET_SCREEN_CACHE, + #endif + #if ENABLED(BACKLASH_GCODE) + BACKLASH_COMPENSATION_SCREEN_CACHE, + #endif + #if HAS_JUNCTION_DEVIATION + JUNC_DEV_SCREEN_CACHE, + #else + JERK_SCREEN_CACHE, + #endif + #if ENABLED(CASE_LIGHT_ENABLE) + CASE_LIGHT_SCREEN_CACHE, + #endif + #if EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) + FILAMENT_MENU_CACHE, + #endif + #if ENABLED(LIN_ADVANCE) + LINEAR_ADVANCE_SCREEN_CACHE, + #endif + #if ENABLED(FILAMENT_RUNOUT_SENSOR) + FILAMENT_RUNOUT_SCREEN_CACHE, + #endif + #if ENABLED(SDSUPPORT) + FILES_SCREEN_CACHE, + #endif + #if ENABLED(CUSTOM_MENU_MAIN) + CUSTOM_USER_MENUS_SCREEN_CACHE, + #endif + CHANGE_FILAMENT_SCREEN_CACHE, + INTERFACE_SETTINGS_SCREEN_CACHE, + INTERFACE_SOUNDS_SCREEN_CACHE, + LOCK_SCREEN_CACHE, + DISPLAY_TIMINGS_SCREEN_CACHE +}; + +// To save MCU RAM, the status message is "baked" in to the status screen +// cache, so we reserve a large chunk of memory for the DL cache + +#define STATUS_SCREEN_DL_SIZE 4096 +#define ALERT_BOX_DL_SIZE 3072 +#define SPINNER_DL_SIZE 3072 +#define FILE_SCREEN_DL_SIZE 4160 +#define PRINTING_SCREEN_DL_SIZE 2048 + +/************************* MENU SCREEN DECLARATIONS *************************/ + +#include "base_screen.h" +#include "base_numeric_adjustment_screen.h" +#include "dialog_box_base_class.h" +#include "status_screen.h" +#include "main_menu.h" +#include "advanced_settings_menu.h" +#include "tune_menu.h" +#include "boot_screen.h" +#include "about_screen.h" +#include "kill_screen.h" +#include "alert_dialog_box.h" +#include "spinner_dialog_box.h" +#include "restore_failsafe_dialog_box.h" +#include "save_settings_dialog_box.h" +#include "confirm_start_print_dialog_box.h" +#include "confirm_abort_print_dialog_box.h" +#include "confirm_user_request_alert_box.h" +#include "touch_calibration_screen.h" +#include "touch_registers_screen.h" +#include "change_filament_screen.h" +#include "move_axis_screen.h" +#include "steps_screen.h" +#include "feedrate_percent_screen.h" +#include "max_velocity_screen.h" +#include "max_acceleration_screen.h" +#include "default_acceleration_screen.h" +#include "temperature_screen.h" +#include "interface_sounds_screen.h" +#include "interface_settings_screen.h" +#include "lock_screen.h" +#include "endstop_state_screen.h" +#include "display_tuning_screen.h" +#include "media_player_screen.h" + +#if ENABLED(PRINTCOUNTER) + #include "statistics_screen.h" +#endif + +#if HAS_TRINAMIC_CONFIG + #include "stepper_current_screen.h" + #include "stepper_bump_sensitivity_screen.h" +#endif + +#if HAS_MULTI_HOTEND + #include "nozzle_offsets_screen.h" +#endif + +#if HAS_LEVELING + #if ENABLED(TOUCH_UI_SYNDAVER_LEVEL) + #include "syndaver_level/leveling_menu.h" + #else + #include "leveling_menu.h" + #endif + #if HAS_BED_PROBE + #include "z_offset_screen.h" + #endif + #if HAS_MESH + #include "bed_mesh_base.h" + #include "bed_mesh_view_screen.h" + #include "bed_mesh_edit_screen.h" + #endif +#endif + +#if ENABLED(CALIBRATION_GCODE) + #include "confirm_auto_calibration_dialog_box.h" +#endif + +#if ENABLED(BABYSTEPPING) + #include "nudge_nozzle_screen.h" +#endif + +#if ENABLED(BACKLASH_GCODE) + #include "backlash_compensation_screen.h" +#endif + +#if HAS_JUNCTION_DEVIATION + #include "junction_deviation_screen.h" +#else + #include "jerk_screen.h" +#endif + +#if ENABLED(CASE_LIGHT_ENABLE) + #include "case_light_screen.h" +#endif + +#if EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) + #include "filament_menu.h" +#endif + +#if ENABLED(FILAMENT_RUNOUT_SENSOR) + #include "filament_runout_screen.h" +#endif + +#if ENABLED(LIN_ADVANCE) + #include "linear_advance_screen.h" +#endif + +#if ENABLED(SDSUPPORT) + #include "files_screen.h" +#endif + +#if ENABLED(CUSTOM_MENU_MAIN) + #include "custom_user_menus.h" +#endif + +#if ENABLED(TOUCH_UI_DEVELOPER_MENU) + #include "developer_menu.h" + #include "confirm_erase_flash_dialog_box.h" + #include "widget_demo_screen.h" + #include "stress_test_screen.h" +#endif + +#if NUM_LANGUAGES > 1 + #include "language_menu.h" +#endif diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp new file mode 100644 index 000000000000..830a0238fef3 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp @@ -0,0 +1,108 @@ +/************************** + * spinner_dialog_box.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 FTDI_SPINNER_DIALOG_BOX + +#define GRID_COLS 2 +#define GRID_ROWS 8 + +using namespace FTDI; +using namespace ExtUI; +using namespace Theme; + +constexpr static SpinnerDialogBoxData &mydata = screen_data.SpinnerDialogBox; + +void SpinnerDialogBox::onEntry() { + UIScreen::onEntry(); + mydata.auto_hide = true; +} + +void SpinnerDialogBox::onExit() { + CommandProcessor cmd; + cmd.stop().execute(); +} + +void SpinnerDialogBox::onRefresh() { + using namespace FTDI; + DLCache dlcache(SPINNER_CACHE); + CommandProcessor cmd; + cmd.cmd(CMD_DLSTART); + if (dlcache.has_data()) + dlcache.append(); + else + dlcache.store(SPINNER_DL_SIZE); + cmd.spinner(BTN_POS(1,4), BTN_SIZE(2,3)).execute(); +} + +void SpinnerDialogBox::onRedraw(draw_mode_t) { +} + +void SpinnerDialogBox::show(progmem_str message) { + CommandProcessor cmd; + if (AT_SCREEN(SpinnerDialogBox)) cmd.stop().execute(); + cmd.cmd(CMD_DLSTART) + .cmd(CLEAR_COLOR_RGB(bg_color)) + .cmd(CLEAR(true,true,true)) + .cmd(COLOR_RGB(bg_text_enabled)) + .tag(0); + draw_text_box(cmd, BTN_POS(1,1), BTN_SIZE(2,3), message, OPT_CENTER, font_large); + DLCache dlcache(SPINNER_CACHE); + if (!dlcache.store(SPINNER_DL_SIZE)) { + SERIAL_ECHO_MSG("CachedScreen::storeBackground() failed: not enough DL cache space"); + cmd.cmd(CMD_DLSTART).cmd(CLEAR(true,true,true)); + dlcache.store(SPINNER_DL_SIZE); + } + if (AT_SCREEN(SpinnerDialogBox)) + cmd.spinner(BTN_POS(1,4), BTN_SIZE(2,3)).execute(); + else + GOTO_SCREEN(SpinnerDialogBox); + mydata.auto_hide = false; +} + +void SpinnerDialogBox::hide() { + GOTO_PREVIOUS(); +} + +void SpinnerDialogBox::enqueueAndWait(progmem_str message, progmem_str commands) { + show(message); + ExtUI::injectCommands_P((const char*)commands); + mydata.auto_hide = true; +} + +void SpinnerDialogBox::enqueueAndWait(progmem_str message, char *commands) { + show(message); + ExtUI::injectCommands(commands); + mydata.auto_hide = true; +} + +void SpinnerDialogBox::onIdle() { + if (mydata.auto_hide && !commandsInQueue() && TERN1(HOST_KEEPALIVE_FEATURE, GcodeSuite::busy_state == GcodeSuite::NOT_BUSY)) { + mydata.auto_hide = false; + hide(); + } +} + +#endif // FTDI_SPINNER_DIALOG_BOX diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.h new file mode 100644 index 000000000000..23e31d1a91ab --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.h @@ -0,0 +1,48 @@ +/************************ + * spinner_dialog_box.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 FTDI_SPINNER_DIALOG_BOX +#define FTDI_SPINNER_DIALOG_BOX_CLASS SpinnerDialogBox + +struct SpinnerDialogBoxData { + bool auto_hide; +}; + +class SpinnerDialogBox : public UIScreen { + public: + static void onEntry(); + static void onExit(); + static void onRedraw(draw_mode_t); + static void onRefresh(); + static void onIdle(); + + static void show(progmem_str); + static void hide(); + + template + static void enqueueAndWait(T commands) {enqueueAndWait(GET_TEXT_F(MSG_PLEASE_WAIT), commands);} + + static void enqueueAndWait(progmem_str message, char *commands); + static void enqueueAndWait(progmem_str message, progmem_str commands); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/statistics_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/statistics_screen.cpp similarity index 96% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/statistics_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/statistics_screen.cpp index cb263248088e..b6d9770e9d2d 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/statistics_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/statistics_screen.cpp @@ -17,14 +17,13 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" -#if BOTH(TOUCH_UI_FTDI_EVE, PRINTCOUNTER) - -#include "screens.h" +#ifdef FTDI_STATISTICS_SCREEN using namespace FTDI; using namespace ExtUI; @@ -64,7 +63,7 @@ void StatisticsScreen::onRedraw(draw_mode_t what) { 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_BACK)); + .tag(1).button(BTN_POS(1,7), BTN_SIZE(4,1), GET_TEXT_F(MSG_BUTTON_DONE)); } } @@ -75,4 +74,4 @@ bool StatisticsScreen::onTouchEnd(uint8_t tag) { } } -#endif // TOUCH_UI_FTDI_EVE && PRINTCOUNTER +#endif // FTDI_STATISTICS_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/statistics_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/statistics_screen.h new file mode 100644 index 000000000000..4176f54101e0 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/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 FTDI_STATISTICS_SCREEN +#define FTDI_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/generic/status_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.cpp new file mode 100644 index 000000000000..23ac90107b6d --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.cpp @@ -0,0 +1,474 @@ +/********************* + * status_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 FTDI_STATUS_SCREEN + +#include "../archim2-flash/flash_storage.h" + +using namespace FTDI; +using namespace Theme; + +#if ENABLED(TOUCH_UI_PORTRAIT) + #define GRID_ROWS 16 +#else + #define GRID_ROWS 16 +#endif + +void StatusScreen::draw_axis_position(draw_mode_t what) { + CommandProcessor cmd; + + #define GRID_COLS 3 + + #if ENABLED(TOUCH_UI_PORTRAIT) + #define X_LBL_POS BTN_POS(1, 9), BTN_SIZE(1,2) + #define Y_LBL_POS BTN_POS(1,11), BTN_SIZE(1,2) + #define Z_LBL_POS BTN_POS(1,13), BTN_SIZE(1,2) + #define X_VAL_POS BTN_POS(2, 9), BTN_SIZE(2,2) + #define Y_VAL_POS BTN_POS(2,11), BTN_SIZE(2,2) + #define Z_VAL_POS BTN_POS(2,13), BTN_SIZE(2,2) + #else + #define X_LBL_POS BTN_POS(1, 9), BTN_SIZE(1,2) + #define Y_LBL_POS BTN_POS(2, 9), BTN_SIZE(1,2) + #define Z_LBL_POS BTN_POS(3, 9), BTN_SIZE(1,2) + #define X_VAL_POS BTN_POS(1,11), BTN_SIZE(1,2) + #define Y_VAL_POS BTN_POS(2,11), BTN_SIZE(1,2) + #define Z_VAL_POS BTN_POS(3,11), BTN_SIZE(1,2) + #endif + + #define _UNION_POS(x1,y1,w1,h1,x2,y2,w2,h2) x1,y1,max(x1+w1,x2+w2)-x1,max(y1+h1,y2+h2)-y1 + #define UNION_POS(p1, p2) _UNION_POS(p1, p2) + + if (what & BACKGROUND) { + cmd.tag(6) + .fgcolor(Theme::axis_label) + .font(Theme::font_large) + .button(UNION_POS(X_LBL_POS, X_VAL_POS), F(""), OPT_FLAT) + .button(UNION_POS(Y_LBL_POS, Y_VAL_POS), F(""), OPT_FLAT) + .button(UNION_POS(Z_LBL_POS, Z_VAL_POS), F(""), OPT_FLAT) + .font(Theme::font_medium) + .fgcolor(Theme::x_axis) .button(X_VAL_POS, F(""), OPT_FLAT) + .fgcolor(Theme::y_axis) .button(Y_VAL_POS, F(""), OPT_FLAT) + .fgcolor(Theme::z_axis) .button(Z_VAL_POS, F(""), OPT_FLAT) + .font(Theme::font_small) + .text ( X_LBL_POS, GET_TEXT_F(MSG_AXIS_X)) + .text ( Y_LBL_POS, GET_TEXT_F(MSG_AXIS_Y)) + .text ( Z_LBL_POS, GET_TEXT_F(MSG_AXIS_Z)) + .colors(normal_btn); + } + + if (what & FOREGROUND) { + using namespace ExtUI; + char x_str[15]; + char y_str[15]; + char z_str[15]; + + if (isAxisPositionKnown(X)) + format_position(x_str, getAxisPosition_mm(X)); + else + strcpy_P(x_str, PSTR("?")); + + if (isAxisPositionKnown(Y)) + format_position(y_str, getAxisPosition_mm(Y)); + else + strcpy_P(y_str, PSTR("?")); + + if (isAxisPositionKnown(Z)) + format_position(z_str, getAxisPosition_mm(Z), 2); + else + strcpy_P(z_str, PSTR("?")); + + cmd.tag(6) + .font(Theme::font_medium) + .text(X_VAL_POS, x_str) + .text(Y_VAL_POS, y_str) + .text(Z_VAL_POS, z_str); + } + + #undef GRID_COLS +} + +#if ENABLED(TOUCH_UI_PORTRAIT) + #define GRID_COLS 8 +#else + #define GRID_COLS 12 +#endif + +void StatusScreen::draw_temperature(draw_mode_t what) { + using namespace Theme; + + #define TEMP_RECT_1 BTN_POS(1,1), BTN_SIZE(4,4) + #define TEMP_RECT_2 BTN_POS(1,1), BTN_SIZE(8,2) + #define NOZ_1_POS BTN_POS(1,1), BTN_SIZE(4,2) + #define NOZ_2_POS BTN_POS(5,1), BTN_SIZE(4,2) + #define BED_POS BTN_POS(1,3), BTN_SIZE(4,2) + #define FAN_POS BTN_POS(5,3), BTN_SIZE(4,2) + + #define _ICON_POS(x,y,w,h) x, y, w/4, h + #define _TEXT_POS(x,y,w,h) x + w/4, y, w - w/4, h + #define ICON_POS(pos) _ICON_POS(pos) + #define TEXT_POS(pos) _TEXT_POS(pos) + + CommandProcessor cmd; + + if (what & BACKGROUND) { + cmd.font(Theme::font_small) + .tag(5) + .fgcolor(temp) .button(TEMP_RECT_1, F(""), OPT_FLAT) + .button(TEMP_RECT_2, F(""), OPT_FLAT) + .fgcolor(fan_speed).button(FAN_POS, F(""), OPT_FLAT) + .tag(0); + + // Draw Extruder Bitmap on Extruder Temperature Button + + cmd.tag(5) + .cmd (BITMAP_SOURCE(Extruder_Icon_Info)) + .cmd (BITMAP_LAYOUT(Extruder_Icon_Info)) + .cmd (BITMAP_SIZE (Extruder_Icon_Info)) + .icon(ICON_POS(NOZ_1_POS), Extruder_Icon_Info, icon_scale) + .icon(ICON_POS(NOZ_2_POS), Extruder_Icon_Info, icon_scale); + + // Draw Bed Heat Bitmap on Bed Heat Button + cmd.cmd (BITMAP_SOURCE(Bed_Heat_Icon_Info)) + .cmd (BITMAP_LAYOUT(Bed_Heat_Icon_Info)) + .cmd (BITMAP_SIZE (Bed_Heat_Icon_Info)) + .icon(ICON_POS(BED_POS), Bed_Heat_Icon_Info, icon_scale); + + // Draw Fan Percent Bitmap on Bed Heat Button + + cmd.cmd (BITMAP_SOURCE(Fan_Icon_Info)) + .cmd (BITMAP_LAYOUT(Fan_Icon_Info)) + .cmd (BITMAP_SIZE (Fan_Icon_Info)) + .icon(ICON_POS(FAN_POS), Fan_Icon_Info, icon_scale); + + TERN_(TOUCH_UI_USE_UTF8, load_utf8_bitmaps(cmd)); // Restore font bitmap handles + } + + if (what & FOREGROUND) { + using namespace ExtUI; + char e0_str[20], e1_str[20], bed_str[20], fan_str[20]; + + sprintf_P(fan_str, PSTR("%-3d %%"), int8_t(getActualFan_percent(FAN0))); + + if (isHeaterIdle(BED)) + format_temp_and_idle(bed_str, getActualTemp_celsius(BED)); + else + format_temp_and_temp(bed_str, getActualTemp_celsius(BED), getTargetTemp_celsius(BED)); + + if (isHeaterIdle(H0)) + format_temp_and_idle(e0_str, getActualTemp_celsius(H0)); + else + format_temp_and_temp(e0_str, getActualTemp_celsius(H0), getTargetTemp_celsius(H0)); + + #if HAS_MULTI_EXTRUDER + if (isHeaterIdle(H1)) + format_temp_and_idle(e1_str, getActualTemp_celsius(H1)); + else + format_temp_and_temp(e1_str, getActualTemp_celsius(H1), getTargetTemp_celsius(H1)); + #else + strcpy_P(e1_str, PSTR("-")); + #endif + + cmd.tag(5) + .font(font_medium) + .text(TEXT_POS(NOZ_1_POS), e0_str) + .text(TEXT_POS(NOZ_2_POS), e1_str) + .text(TEXT_POS(BED_POS), bed_str) + .text(TEXT_POS(FAN_POS), fan_str); + } +} + +void StatusScreen::_format_time(char *outstr, uint32_t time) { + const uint8_t hrs = time / 3600, + min = (time / 60) % 60, + sec = time % 60; + if (hrs) + sprintf_P(outstr, PSTR("%02d:%02d"), hrs, min); + else + sprintf_P(outstr, PSTR("%02d:%02ds"), min, sec); +} + +void StatusScreen::draw_progress(draw_mode_t what) { + using namespace ExtUI; + using namespace Theme; + + CommandProcessor cmd; + + #undef GRID_COLS + #if ENABLED(TOUCH_UI_PORTRAIT) + #define GRID_COLS 3 + #define PROGRESSZONE_POS BTN_POS(1,5), BTN_SIZE(3,2) + #define TIME_POS_X BTN_X(1) + #define TIME_POS_W BTN_W(1) + #define REMAINING_POS_X BTN_X(2) + #define REMAINING_POS_W BTN_W(1) + #define PROGRESS_POS_X BTN_X(3) + #define PROGRESS_POS_W BTN_W(1) + #define PROGRESSZONE_FIRSTLINE_Y BTN_Y(5) + #define PROGRESSBAR_POS BTN_POS(1,6), BTN_SIZE(3,1) + #else + #define GRID_COLS 6 + #define PROGRESSZONE_POS BTN_POS(5,1), BTN_SIZE(2,4) + #if ENABLED(SHOW_REMAINING_TIME) + #define TIME_POS BTN_POS(5,1), BTN_SIZE(1,2) + #define REMAINING_POS BTN_POS(6,1), BTN_SIZE(1,2) + #else + #define TIME_POS BTN_POS(5,1), BTN_SIZE(2,2) + #endif + #define PROGRESS_POS BTN_POS(5,3), BTN_SIZE(2,2) + #define PROGRESSBAR_POS BTN_POS(5,2), BTN_SIZE(2,2) + #endif + + if (what & BACKGROUND) { + cmd.tag(0).font(font_medium) + .fgcolor(progress).button(PROGRESSZONE_POS, F(""), OPT_FLAT); + } + + if (what & FOREGROUND) { + const uint32_t elapsed = getProgress_seconds_elapsed(); + char elapsed_str[10]; + _format_time(elapsed_str, elapsed); + + #if ENABLED(SHOW_REMAINING_TIME) + const uint32_t remaining = getProgress_seconds_remaining(); + char remaining_str[10]; + _format_time(remaining_str, remaining); + #endif + + const uint16_t current_progress = TERN(HAS_PRINT_PROGRESS_PERMYRIAD, getProgress_permyriad(), getProgress_percent() * 100); + constexpr uint16_t progress_range = 10000U; + + const bool show_progress_bar = current_progress > 0 && current_progress < progress_range + 1; + if (show_progress_bar) { + cmd.tag(0).font(font_medium) + .bgcolor(progress) + .progress(PROGRESSBAR_POS, current_progress, progress_range, OPT_FLAT); + } + + 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 + ); + + #if ENABLED(TOUCH_UI_PORTRAIT) + const uint16_t texts_pos_h = show_progress_bar ? (BTN_H(1)) : (BTN_H(2)); + cmd.font(font_medium) + .tag(7).text(TIME_POS_X, PROGRESSZONE_FIRSTLINE_Y, TIME_POS_W, texts_pos_h, elapsed_str) + #if ENABLED(SHOW_REMAINING_TIME) + .text(REMAINING_POS_X, PROGRESSZONE_FIRSTLINE_Y, REMAINING_POS_W, texts_pos_h, remaining_str) + #endif + .text(PROGRESS_POS_X, PROGRESSZONE_FIRSTLINE_Y, PROGRESS_POS_W, texts_pos_h, progress_str); + #else + cmd.font(font_medium) + .tag(7).text(TIME_POS, elapsed_str) + #if ENABLED(SHOW_REMAINING_TIME) + .text(REMAINING_POS, remaining_str) + #endif + .text(PROGRESS_POS, progress_str); + #endif + } + + #undef GRID_COLS +} + +void StatusScreen::draw_interaction_buttons(draw_mode_t what) { + #define GRID_COLS 4 + if (what & FOREGROUND) { + using namespace ExtUI; + + #if ENABLED(TOUCH_UI_PORTRAIT) + #define MEDIA_BTN_POS BTN_POS(1,15), BTN_SIZE(2,2) + #define MENU_BTN_POS BTN_POS(3,15), BTN_SIZE(2,2) + #else + #define MEDIA_BTN_POS BTN_POS(1,13), BTN_SIZE(2,4) + #define MENU_BTN_POS BTN_POS(3,13), BTN_SIZE(2,4) + #endif + + const bool has_media = isMediaInserted() && !isPrintingFromMedia(); + + CommandProcessor cmd; + cmd.colors(normal_btn) + .font(Theme::font_medium) + .colors(has_media ? action_btn : normal_btn) + .enabled(has_media && !isPrinting()) + .tag(3).button(MEDIA_BTN_POS, isPrinting() ? GET_TEXT_F(MSG_PRINTING) : GET_TEXT_F(MSG_BUTTON_MEDIA)) + .colors(!has_media ? action_btn : normal_btn) + .tag(4).button(MENU_BTN_POS, GET_TEXT_F(MSG_BUTTON_MENU)); + } + #undef GRID_COLS +} + +void StatusScreen::draw_status_message(draw_mode_t what, const char *message) { + #define GRID_COLS 1 + + #if ENABLED(TOUCH_UI_PORTRAIT) + #define STATUS_POS BTN_POS(1,7), BTN_SIZE(1,2) + #else + #define STATUS_POS BTN_POS(1,5), BTN_SIZE(1,4) + #endif + + if (what & BACKGROUND) { + CommandProcessor cmd; + cmd.fgcolor(Theme::status_msg) + .tag(0) + .button(STATUS_POS, F(""), OPT_FLAT); + + draw_text_box(cmd, STATUS_POS, message, OPT_CENTER, font_large); + } + #undef GRID_COLS +} + +void StatusScreen::setStatusMessage(progmem_str 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 *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(Theme::bg_color)) + .cmd(CLEAR(true,true,true)); + + draw_temperature(BACKGROUND); + draw_status_message(BACKGROUND, message); + draw_interaction_buttons(BACKGROUND); + draw_progress(BACKGROUND); + draw_axis_position(BACKGROUND); + + storeBackground(); + + #if ENABLED(TOUCH_UI_DEBUG) + SERIAL_ECHO_MSG("New status message: ", message); + #endif + + if (AT_SCREEN(StatusScreen)) { + current_screen.onRefresh(); + } +} + +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)); + + // Load fonts for internationalization + #if ENABLED(TOUCH_UI_USE_UTF8) + load_utf8_data(base + UTF8_FONT_OFFSET); + #endif +} + +void StatusScreen::onStartup() { + UIFlashStorage::initialize(); +} + +void StatusScreen::onRedraw(draw_mode_t what) { + if (what & FOREGROUND) { + draw_temperature(FOREGROUND); + draw_progress(FOREGROUND); + draw_axis_position(FOREGROUND); + draw_interaction_buttons(FOREGROUND); + } +} + +void StatusScreen::onEntry() { + BaseScreen::onEntry(); + onRefresh(); +} + +void StatusScreen::onIdle() { + if (refresh_timer.elapsed(STATUS_UPDATE_INTERVAL)) { + onRefresh(); + refresh_timer.start(); + } + BaseScreen::onIdle(); +} + +bool StatusScreen::onTouchEnd(uint8_t tag) { + using namespace ExtUI; + + switch (tag) { + #if ENABLED(SDSUPPORT) + case 3: GOTO_SCREEN(FilesScreen); break; + #endif + case 4: + if (isPrinting()) { + GOTO_SCREEN(TuneMenu); + } + else { + GOTO_SCREEN(MainMenu); + } + break; + case 5: GOTO_SCREEN(TemperatureScreen); break; + case 6: + if (isPrinting()) { + #if ENABLED(BABYSTEPPING) + GOTO_SCREEN(NudgeNozzleScreen); + #elif HAS_BED_PROBE + GOTO_SCREEN(ZOffsetScreen); + #else + return false; + #endif + } + else { + GOTO_SCREEN(MoveAxisScreen); + } + break; + case 7: GOTO_SCREEN(FeedratePercentScreen); break; + default: + return true; + } + // If a passcode is enabled, the LockScreen will prevent the + // user from proceeding. + LockScreen::check_passcode(); + return true; +} + +void StatusScreen::onMediaInserted() { + if (AT_SCREEN(StatusScreen)) + setStatusMessage(GET_TEXT_F(MSG_MEDIA_INSERTED)); +} + +void StatusScreen::onMediaRemoved() { + if (AT_SCREEN(StatusScreen) || ExtUI::isPrintingFromMedia()) + setStatusMessage(GET_TEXT_F(MSG_MEDIA_REMOVED)); +} + +#endif // FTDI_STATUS_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.h new file mode 100644 index 000000000000..6033ba1ad99f --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.h @@ -0,0 +1,47 @@ +/******************* + * status_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 FTDI_STATUS_SCREEN +#define FTDI_STATUS_SCREEN_CLASS StatusScreen + +class StatusScreen : public BaseScreen, public CachedScreen { + private: + static void draw_axis_position(draw_mode_t); + static void draw_temperature(draw_mode_t); + static void draw_progress(draw_mode_t); + static void draw_interaction_buttons(draw_mode_t); + static void draw_status_message(draw_mode_t, const char * const); + static void _format_time(char *outstr, uint32_t time); + public: + static void loadBitmaps(); + static void setStatusMessage(const char *); + static void setStatusMessage(progmem_str); + static void onRedraw(draw_mode_t); + static void onStartup(); + static void onEntry(); + static void onIdle(); + static bool onTouchEnd(uint8_t tag); + static void onMediaInserted(); + static void onMediaRemoved(); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_bump_sensitivity_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stepper_bump_sensitivity_screen.cpp similarity index 92% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_bump_sensitivity_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stepper_bump_sensitivity_screen.cpp index 693d125fbf48..ddbe648c32f3 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_bump_sensitivity_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stepper_bump_sensitivity_screen.cpp @@ -1,5 +1,5 @@ -/************************************** - * stepper_bump_sensiivity_screen.cpp * +/*************************************** + * stepper_bump_sensitivity_screen.cpp * **************************************/ /**************************************************************************** @@ -17,14 +17,13 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" -#if BOTH(TOUCH_UI_FTDI_EVE, HAS_TRINAMIC_CONFIG) - -#include "screens.h" +#ifdef FTDI_STEPPER_BUMP_SENSITIVITY_SCREEN using namespace FTDI; using namespace ExtUI; @@ -56,4 +55,4 @@ bool StepperBumpSensitivityScreen::onTouchHeld(uint8_t tag) { return true; } -#endif // TOUCH_UI_FTDI_EVE && HAS_TRINAMIC_CONFIG +#endif // FTDI_STEPPER_BUMP_SENSITIVITY_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stepper_bump_sensitivity_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stepper_bump_sensitivity_screen.h new file mode 100644 index 000000000000..b37b8014e8e9 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stepper_bump_sensitivity_screen.h @@ -0,0 +1,32 @@ +/************************************* + * stepper_bump_sensitivity_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 FTDI_STEPPER_BUMP_SENSITIVITY_SCREEN +#define FTDI_STEPPER_BUMP_SENSITIVITY_SCREEN_CLASS StepperBumpSensitivityScreen + +class StepperBumpSensitivityScreen : public BaseNumericAdjustmentScreen, public CachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchHeld(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_current_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stepper_current_screen.cpp similarity index 97% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_current_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stepper_current_screen.cpp index 136582f09aa7..ddd273aa4719 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_current_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stepper_current_screen.cpp @@ -17,14 +17,13 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" -#if BOTH(TOUCH_UI_FTDI_EVE, HAS_TRINAMIC_CONFIG) - -#include "screens.h" +#ifdef FTDI_STEPPER_CURRENT_SCREEN using namespace FTDI; using namespace ExtUI; @@ -124,4 +123,4 @@ bool StepperCurrentScreen::onTouchHeld(uint8_t tag) { return true; } -#endif // TOUCH_UI_FTDI_EVE +#endif // FTDI_STEPPER_CURRENT_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stepper_current_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stepper_current_screen.h new file mode 100644 index 000000000000..9186eb1637bb --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stepper_current_screen.h @@ -0,0 +1,32 @@ +/**************************** + * stepper_current_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 FTDI_STEPPER_CURRENT_SCREEN +#define FTDI_STEPPER_CURRENT_SCREEN_CLASS StepperCurrentScreen + +class StepperCurrentScreen : public BaseNumericAdjustmentScreen, public CachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchHeld(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/steps_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/steps_screen.cpp similarity index 97% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/steps_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/steps_screen.cpp index 92035d1b1c04..c73c49493e0b 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/steps_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/steps_screen.cpp @@ -17,14 +17,13 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) - -#include "screens.h" +#ifdef FTDI_STEPS_SCREEN using namespace FTDI; using namespace ExtUI; @@ -83,4 +82,4 @@ bool StepsScreen::onTouchHeld(uint8_t tag) { return true; } -#endif // TOUCH_UI_FTDI_EVE +#endif // FTDI_STEPS_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/steps_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/steps_screen.h new file mode 100644 index 000000000000..68a3ced8fae3 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/steps_screen.h @@ -0,0 +1,32 @@ +/****************** + * steps_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 FTDI_STEPS_SCREEN +#define FTDI_STEPS_SCREEN_CLASS StepsScreen + +class StepsScreen : public BaseNumericAdjustmentScreen, public CachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchHeld(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stress_test_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stress_test_screen.cpp similarity index 82% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stress_test_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stress_test_screen.cpp index 44ee453f15e6..09f2088240f6 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stress_test_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stress_test_screen.cpp @@ -17,15 +17,14 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" +#include "../screen_data.h" -#if BOTH(TOUCH_UI_FTDI_EVE, TOUCH_UI_DEVELOPER_MENU) - -#include "screens.h" -#include "screen_data.h" +#ifdef FTDI_STRESS_TEST_SCREEN #define STRESS_TEST_CHANGE_INTERVAL 6000 @@ -36,6 +35,8 @@ using namespace FTDI; using namespace Theme; using namespace ExtUI; +constexpr static StressTestScreenData &mydata = screen_data.StressTestScreen; + void StressTestScreen::drawDots(uint16_t x, uint16_t y, uint16_t w, uint16_t h) { CommandProcessor cmd; for (uint8_t i = 0; i < 100; i++) { @@ -47,8 +48,8 @@ void StressTestScreen::drawDots(uint16_t x, uint16_t y, uint16_t w, uint16_t h) } bool StressTestScreen::watchDogTestNow() { - return screen_data.StressTestScreen.next_watchdog_trigger && - ELAPSED(millis(), screen_data.StressTestScreen.next_watchdog_trigger); + return mydata.next_watchdog_trigger && + ELAPSED(millis(), mydata.next_watchdog_trigger); } void StressTestScreen::onRedraw(draw_mode_t) { @@ -58,7 +59,7 @@ void StressTestScreen::onRedraw(draw_mode_t) { .cmd(CLEAR(true,true,true)) .cmd(COLOR_RGB(bg_text_enabled)) .font(font_medium) - .text(BTN_POS(1,1), BTN_SIZE(4,1), progmem_str(screen_data.StressTestScreen.message)); + .text(BTN_POS(1,1), BTN_SIZE(4,1), progmem_str(mydata.message)); drawDots(BTN_POS(1,3), BTN_SIZE(4,4)); @@ -92,25 +93,23 @@ void StressTestScreen::startupCheck() { } void StressTestScreen::onEntry() { - screen_data.StressTestScreen.next_watchdog_trigger = millis() + 10000 + random(40000); - screen_data.StressTestScreen.message = PSTR("Test 1: Stress testing..."); + mydata.next_watchdog_trigger = millis() + 10000 + random(40000); + mydata.message = PSTR("Test 1: Stress testing..."); // Turn off heaters. - setTargetTemp_celsius(0, E0); - setTargetTemp_celsius(0, E1); - setTargetTemp_celsius(0, BED); + coolDown(); runTestOnBootup(true); } void StressTestScreen::recursiveLockup() { - screen_data.StressTestScreen.message = PSTR("Test 2: Printer will restart."); + mydata.message = PSTR("Test 2: Printer will restart."); current_screen.onRefresh(); recursiveLockup(); } void StressTestScreen::iterativeLockup() { - screen_data.StressTestScreen.message = PSTR("Test 3: Printer will restart."); + mydata.message = PSTR("Test 3: Printer will restart."); for (;;) current_screen.onRefresh(); } @@ -120,7 +119,6 @@ void StressTestScreen::onIdle() { if (!commandsInQueue()) { if (!isPositionKnown()) { - extern const char G28_STR[]; injectCommands_P(G28_STR); } else { @@ -147,4 +145,4 @@ void StressTestScreen::onIdle() { BaseScreen::onIdle(); } -#endif // TOUCH_UI_FTDI_EVE +#endif // FTDI_STRESS_TEST_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stress_test_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stress_test_screen.h new file mode 100644 index 000000000000..f35f11adb6d0 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stress_test_screen.h @@ -0,0 +1,48 @@ +/************************ + * stress_test_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 FTDI_STRESS_TEST_SCREEN +#define FTDI_STRESS_TEST_SCREEN_CLASS StressTestScreen + +struct StressTestScreenData { + uint32_t next_watchdog_trigger; + const char* message; +}; + +class StressTestScreen : public BaseScreen, public UncachedScreen { + private: + static void drawDots(uint16_t x, uint16_t y, uint16_t h, uint16_t v); + static bool watchDogTestNow(); + static void recursiveLockup(); + static void iterativeLockup(); + static void runTestOnBootup(bool enable); + + public: + static void startupCheck(); + + static void onEntry(); + 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/generic/string_format.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/string_format.cpp new file mode 100644 index 000000000000..1f3640e3a14f --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/string_format.cpp @@ -0,0 +1,108 @@ +/********************* + * string_format.cpp * + *********************/ + +/**************************************************************************** + * 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" + +#if ENABLED(TOUCH_UI_FTDI_EVE) + +#include "../screens.h" + +#define ROUND(val) uint16_t((val)+0.5) + +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wno-format" + +/** + * Formats a temperature string (e.g. "100°C") + */ +void format_temp(char *str, const_celsius_float_t t1) { + #ifdef TOUCH_UI_LCD_TEMP_PRECISION + char num1[7]; + dtostrf(t1, 4 + TOUCH_UI_LCD_TEMP_PRECISION, TOUCH_UI_LCD_TEMP_PRECISION, num1); + sprintf_P(str, PSTR("%s" S_FMT), num1, GET_TEXT(MSG_UNITS_C)); + #else + sprintf_P(str, PSTR("%3d" S_FMT), ROUND(t1), GET_TEXT(MSG_UNITS_C)); + #endif +} + +/** + * Formats a temperature string for an idle heater (e.g. "100 °C / idle") + */ +void format_temp_and_idle(char *str, const_celsius_float_t t1) { + #ifdef TOUCH_UI_LCD_TEMP_PRECISION + char num1[7]; + dtostrf(t1, 4 + TOUCH_UI_LCD_TEMP_PRECISION, TOUCH_UI_LCD_TEMP_PRECISION, num1); + sprintf_P(str, PSTR("%s" S_FMT " / " S_FMT), num1, GET_TEXT(MSG_UNITS_C), GET_TEXT(MSG_IDLE)); + #else + sprintf_P(str, PSTR("%3d" S_FMT " / " S_FMT), ROUND(t1), GET_TEXT(MSG_UNITS_C), GET_TEXT(MSG_IDLE)); + #endif +} + +/** + * Formats a temperature string for an active heater (e.g. "100 / 200°C") + */ +void format_temp_and_temp(char *str, const_celsius_float_t t1, const_celsius_float_t t2) { + #ifdef TOUCH_UI_LCD_TEMP_PRECISION + char num1[7], num2[7]; + dtostrf(t1, 4 + TOUCH_UI_LCD_TEMP_PRECISION, TOUCH_UI_LCD_TEMP_PRECISION, num1); + dtostrf(t2, 4 + TOUCH_UI_LCD_TEMP_PRECISION, TOUCH_UI_LCD_TEMP_PRECISION, num2); + sprintf_P(str, PSTR("%s / %s" S_FMT), num1, num2, GET_TEXT(MSG_UNITS_C)); + #else + sprintf_P(str, PSTR("%3d / %3d" S_FMT), ROUND(t1), ROUND(t2), GET_TEXT(MSG_UNITS_C)); + #endif +} + +/** + * Formats a temperature string for a material (e.g. "100°C (PLA)") + */ +void format_temp_and_material(char *str, const_celsius_float_t t1, const char *material) { + #ifdef TOUCH_UI_LCD_TEMP_PRECISION + char num1[7]; + dtostrf(t1, 4 + TOUCH_UI_LCD_TEMP_PRECISION, TOUCH_UI_LCD_TEMP_PRECISION, num1); + sprintf_P(str, PSTR("%s" S_FMT " (" S_FMT ")"), num1, GET_TEXT(MSG_UNITS_C), material); + #else + sprintf_P(str, PSTR("%3d" S_FMT " (" S_FMT ")"), ROUND(t1), GET_TEXT(MSG_UNITS_C), material); + #endif +} + +/** + * Formats a position value (e.g. "10 mm") + */ +void format_position(char *str, float p, uint8_t decimals) { + dtostrf(p, 4 + decimals, decimals, str); + strcat_P(str, PSTR(" ")); + strcat_P(str, GET_TEXT(MSG_UNITS_MM)); +} + +/** + * Formats a position vector (e.g. "10; 20; 30 mm") + */ +void format_position(char *str, float x, float y, float z) { + char num1[7], num2[7], num3[7]; + dtostrf(x, 4, 2, num1); + dtostrf(y, 4, 2, num2); + dtostrf(z, 4, 2, num3); + sprintf_P(str, PSTR("%s; %s; %s " S_FMT), num1, num2, num3, GET_TEXT(MSG_UNITS_MM)); +} + +#pragma GCC diagnostic pop + +#endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/string_format.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/string_format.h similarity index 82% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/string_format.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/string_format.h index e37a82d28a5f..44583f08ecbe 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/string_format.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/string_format.h @@ -16,14 +16,14 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once -void format_temp(char *str, float t1); -void format_temp_and_idle(char *str, float t1); -void format_temp_and_temp(char *str, float t1, float t2); -void format_temp_and_material(char *str, float t1, const char *material); +void format_temp(char *str, const_celsius_float_t t1); +void format_temp_and_idle(char *str, const_celsius_float_t t1); +void format_temp_and_temp(char *str, const_celsius_float_t t1, const_celsius_float_t t2); +void format_temp_and_material(char *str, const_celsius_float_t t1, const char *material); void format_position(char *str, float p, uint8_t decimals = 1); void format_position(char *str, float x, float y, float z); diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/temperature_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/temperature_screen.cpp similarity index 85% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/temperature_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/temperature_screen.cpp index c254d2997f62..ee53a82bee18 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/temperature_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/temperature_screen.cpp @@ -1,6 +1,6 @@ -/******************* - * boot_screen.cpp * - *******************/ +/************************** + * temperature_screen.cpp * + **************************/ /**************************************************************************** * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * @@ -17,14 +17,13 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) - -#include "screens.h" +#ifdef FTDI_TEMPERATURE_SCREEN using namespace FTDI; using namespace Theme; @@ -33,7 +32,7 @@ using namespace ExtUI; void TemperatureScreen::onRedraw(draw_mode_t what) { widgets_t w(what); #if TOUCH_UI_LCD_TEMP_SCALING == 10 - w.precision(1) + w.precision(1, DEFAULT_MIDRANGE) #else w.precision(0, getTargetTemp_celsius(E0) == 0 ? DEFAULT_HIGHEST : DEFAULT_MIDRANGE) #endif @@ -41,7 +40,14 @@ void TemperatureScreen::onRedraw(draw_mode_t what) { w.heading(GET_TEXT_F(MSG_TEMPERATURE)); w.button(30, GET_TEXT_F(MSG_COOLDOWN)); #ifndef NO_TOOLHEAD_HEATER_GCODE - #if HOTENDS == 1 + #if ENABLED(TOUCH_UI_COCOA_PRESS) + w.adjuster( 2, GET_TEXT_F(MSG_NOZZLE), getTargetTemp_celsius(E0)); + w.adjuster( 4, GET_TEXT_F(MSG_BODY), getTargetTemp_celsius(E1)); + #if ENABLED(COCOA_PRESS_EXTRA_HEATER) + if (has_extra_heater()) + w.adjuster(6, GET_TEXT_F(MSG_EXTERNAL), getTargetTemp_celsius(E2)); + #endif + #elif HOTENDS == 1 w.adjuster( 2, GET_TEXT_F(MSG_NOZZLE), getTargetTemp_celsius(E0)); #else w.adjuster( 2, F(LCD_STR_E0), getTargetTemp_celsius(E0)); @@ -95,13 +101,8 @@ bool TemperatureScreen::onTouchHeld(uint8_t tag) { case 11: UI_INCREMENT(TargetFan_percent, FAN0); break; #endif case 30: - #define _HOTEND_OFF(N) setTargetTemp_celsius(0,E##N); - REPEAT(HOTENDS, _HOTEND_OFF); - TERN_(HAS_HEATED_BED, setTargetTemp_celsius(0,BED)); - TERN_(HAS_HEATED_CHAMBER, setTargetTemp_celsius(0,CHAMBER)); - #if HAS_FAN - setTargetFan_percent(0,FAN0); - #endif + coolDown(); + TERN_(HAS_HEATED_CHAMBER, setTargetTemp_celsius(0, CHAMBER)); break; default: return false; @@ -109,4 +110,4 @@ bool TemperatureScreen::onTouchHeld(uint8_t tag) { return true; } -#endif // TOUCH_UI_FTDI_EVE +#endif // FTDI_TEMPERATURE_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/temperature_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/temperature_screen.h new file mode 100644 index 000000000000..de928c8978cc --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/temperature_screen.h @@ -0,0 +1,32 @@ +/************************ + * temperature_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 FTDI_TEMPERATURE_SCREEN +#define FTDI_TEMPERATURE_SCREEN_CLASS TemperatureScreen + +class TemperatureScreen : public BaseNumericAdjustmentScreen, public CachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchHeld(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/touch_calibration_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/touch_calibration_screen.cpp similarity index 93% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/touch_calibration_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/touch_calibration_screen.cpp index 436445024a2f..c7c21368dfc4 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/touch_calibration_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/touch_calibration_screen.cpp @@ -17,14 +17,13 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) - -#include "screens.h" +#ifdef FTDI_TOUCH_CALIBRATION_SCREEN using namespace FTDI; using namespace Theme; @@ -85,7 +84,10 @@ void TouchCalibrationScreen::onRedraw(draw_mode_t) { void TouchCalibrationScreen::onIdle() { if (!CLCD::is_touching() && !CommandProcessor::is_processing()) { GOTO_PREVIOUS(); + #if ENABLED(TOUCH_UI_DEBUG) + SERIAL_ECHO_MSG("Calibration routine finished"); + #endif } } -#endif // TOUCH_UI_FTDI_EVE +#endif // FTDI_TOUCH_CALIBRATION_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/touch_calibration_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/touch_calibration_screen.h new file mode 100644 index 000000000000..b4e6cfb66cf1 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/touch_calibration_screen.h @@ -0,0 +1,34 @@ +/****************************** + * touch_calibration_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 FTDI_TOUCH_CALIBRATION_SCREEN +#define FTDI_TOUCH_CALIBRATION_SCREEN_CLASS TouchCalibrationScreen + +class TouchCalibrationScreen : public BaseScreen, public UncachedScreen { + public: + static void onRefresh(); + static void onEntry(); + static void onRedraw(draw_mode_t); + static void onIdle(); +}; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/touch_registers_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/touch_registers_screen.cpp new file mode 100644 index 000000000000..5475d67a80b7 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/touch_registers_screen.cpp @@ -0,0 +1,85 @@ +/****************************** + * touch_registers_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 FTDI_TOUCH_REGISTERS_SCREEN + +using namespace FTDI; +using namespace Theme; + +void TouchRegistersScreen::onRedraw(draw_mode_t) { + const uint32_t T_Transform_A = CLCD::mem_read_32(CLCD::REG::TOUCH_TRANSFORM_A); + const uint32_t T_Transform_B = CLCD::mem_read_32(CLCD::REG::TOUCH_TRANSFORM_B); + const uint32_t T_Transform_C = CLCD::mem_read_32(CLCD::REG::TOUCH_TRANSFORM_C); + const uint32_t T_Transform_D = CLCD::mem_read_32(CLCD::REG::TOUCH_TRANSFORM_D); + const uint32_t T_Transform_E = CLCD::mem_read_32(CLCD::REG::TOUCH_TRANSFORM_E); + const uint32_t T_Transform_F = CLCD::mem_read_32(CLCD::REG::TOUCH_TRANSFORM_F); + char b[20]; + + CommandProcessor cmd; + cmd.cmd(CLEAR_COLOR_RGB(bg_color)) + .cmd(CLEAR(true,true,true)) + .tag(0); + + #define GRID_ROWS 7 + #define GRID_COLS 2 + cmd.tag(0) + .font(font_xsmall) + .fgcolor(transformA) .button(BTN_POS(1,1), BTN_SIZE(1,1), F("TOUCH_XFORM_A")) + .fgcolor(transformB) .button(BTN_POS(1,2), BTN_SIZE(1,1), F("TOUCH_XFORM_B")) + .fgcolor(transformC) .button(BTN_POS(1,3), BTN_SIZE(1,1), F("TOUCH_XFORM_C")) + .fgcolor(transformD) .button(BTN_POS(1,4), BTN_SIZE(1,1), F("TOUCH_XFORM_D")) + .fgcolor(transformE) .button(BTN_POS(1,5), BTN_SIZE(1,1), F("TOUCH_XFORM_E")) + .fgcolor(transformF) .button(BTN_POS(1,6), BTN_SIZE(1,1), F("TOUCH_XFORM_F")) + + .fgcolor(transformVal).button(BTN_POS(2,1), BTN_SIZE(1,1), F(""), OPT_FLAT) + .fgcolor(transformVal).button(BTN_POS(2,2), BTN_SIZE(1,1), F(""), OPT_FLAT) + .fgcolor(transformVal).button(BTN_POS(2,3), BTN_SIZE(1,1), F(""), OPT_FLAT) + .fgcolor(transformVal).button(BTN_POS(2,4), BTN_SIZE(1,1), F(""), OPT_FLAT) + .fgcolor(transformVal).button(BTN_POS(2,5), BTN_SIZE(1,1), F(""), OPT_FLAT) + .fgcolor(transformVal).button(BTN_POS(2,6), BTN_SIZE(1,1), F(""), OPT_FLAT); + + sprintf_P(b, PSTR("0x%08lX"), T_Transform_A); cmd.text( BTN_POS(2,1), BTN_SIZE(1,1), b); + sprintf_P(b, PSTR("0x%08lX"), T_Transform_B); cmd.text( BTN_POS(2,2), BTN_SIZE(1,1), b); + sprintf_P(b, PSTR("0x%08lX"), T_Transform_C); cmd.text( BTN_POS(2,3), BTN_SIZE(1,1), b); + sprintf_P(b, PSTR("0x%08lX"), T_Transform_D); cmd.text( BTN_POS(2,4), BTN_SIZE(1,1), b); + sprintf_P(b, PSTR("0x%08lX"), T_Transform_E); cmd.text( BTN_POS(2,5), BTN_SIZE(1,1), b); + sprintf_P(b, PSTR("0x%08lX"), T_Transform_F); cmd.text( BTN_POS(2,6), BTN_SIZE(1,1), b); + + cmd.colors(action_btn).font(font_medium) + .tag(1).button(BTN_POS(2,7), BTN_SIZE(1,1), F("Back")); + #undef GRID_COLS + #undef GRID_ROWS + } + + bool TouchRegistersScreen::onTouchEnd(uint8_t tag) { + switch (tag) { + case 1: GOTO_PREVIOUS(); break; + default: + return false; + } + return true; + } + +#endif // FTDI_TOUCH_REGISTERS_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/touch_registers_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/touch_registers_screen.h new file mode 100644 index 000000000000..b6d4ba8e00cd --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/touch_registers_screen.h @@ -0,0 +1,32 @@ +/**************************** + * touch_registers_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 FTDI_TOUCH_REGISTERS_SCREEN +#define FTDI_TOUCH_REGISTERS_SCREEN_CLASS TouchRegistersScreen + +class TouchRegistersScreen : 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/generic/tune_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/tune_menu.cpp new file mode 100644 index 000000000000..6f4beb66731c --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/tune_menu.cpp @@ -0,0 +1,158 @@ +/******************* + * tune_menu.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 FTDI_TUNE_MENU + +#include "../../../../feature/host_actions.h" + +using namespace FTDI; +using namespace Theme; + +void TuneMenu::onRedraw(draw_mode_t what) { + if (what & BACKGROUND) { + CommandProcessor cmd; + cmd.cmd(CLEAR_COLOR_RGB(bg_color)) + .cmd(CLEAR(true,true,true)); + } + + #if ENABLED(TOUCH_UI_PORTRAIT) + #define GRID_ROWS 9 + #define GRID_COLS 2 + #define TEMPERATURE_POS BTN_POS(1,1), BTN_SIZE(2,1) + #define FIL_CHANGE_POS BTN_POS(1,2), BTN_SIZE(2,1) + #define FILAMENT_POS BTN_POS(1,3), BTN_SIZE(2,1) + #define NUDGE_NOZ_POS BTN_POS(1,4), BTN_SIZE(2,1) + #define SPEED_POS BTN_POS(1,5), BTN_SIZE(2,1) + #define PAUSE_POS BTN_POS(1,6), BTN_SIZE(2,1) + #define STOP_POS BTN_POS(1,7), BTN_SIZE(2,1) + #define CASE_LIGHT_POS BTN_POS(1,8), BTN_SIZE(2,1) + #define ADVANCED_SETTINGS_POS BTN_POS(1,9), BTN_SIZE(1,1) + #define BACK_POS BTN_POS(2,9), BTN_SIZE(1,1) + #else + #define GRID_ROWS 5 + #define GRID_COLS 2 + #define TEMPERATURE_POS BTN_POS(1,1), BTN_SIZE(1,1) + #define NUDGE_NOZ_POS BTN_POS(2,1), BTN_SIZE(1,1) + #define FIL_CHANGE_POS BTN_POS(1,2), BTN_SIZE(1,1) + #define SPEED_POS BTN_POS(2,2), BTN_SIZE(1,1) + #define PAUSE_POS BTN_POS(1,3), BTN_SIZE(1,1) + #define STOP_POS BTN_POS(2,3), BTN_SIZE(1,1) + #define FILAMENT_POS BTN_POS(1,4), BTN_SIZE(1,1) + #define CASE_LIGHT_POS BTN_POS(2,4), BTN_SIZE(1,1) + #define ADVANCED_SETTINGS_POS BTN_POS(1,5), BTN_SIZE(1,1) + #define BACK_POS BTN_POS(2,5), BTN_SIZE(1,1) + #endif + + if (what & FOREGROUND) { + const bool sdOrHostPrinting = ExtUI::isPrinting(); + const bool sdOrHostPaused = ExtUI::isPrintingPaused(); + + CommandProcessor cmd; + cmd.colors(normal_btn) + .font(font_medium) + .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)) + .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) + .tag(4).button(NUDGE_NOZ_POS, GET_TEXT_F(MSG_ZPROBE_ZOFFSET)) + #endif + .tag(5).button(SPEED_POS, GET_TEXT_F(MSG_PRINT_SPEED)) + .enabled(sdOrHostPrinting) + .tag(sdOrHostPaused ? 7 : 6) + .button(PAUSE_POS, sdOrHostPaused ? GET_TEXT_F(MSG_RESUME_PRINT) : GET_TEXT_F(MSG_PAUSE_PRINT)) + .enabled(sdOrHostPrinting) + .tag(8).button(STOP_POS, GET_TEXT_F(MSG_STOP_PRINT)) + .enabled(ENABLED(CASE_LIGHT_ENABLE)) + .tag(10).button(CASE_LIGHT_POS, GET_TEXT_F(MSG_CASE_LIGHT)) + .tag(11).button(ADVANCED_SETTINGS_POS, GET_TEXT_F(MSG_ADVANCED_SETTINGS)) + .tag(1).colors(action_btn) + .button(BACK_POS, GET_TEXT_F(MSG_BUTTON_DONE)); + } + #undef GRID_COLS + #undef GRID_ROWS +} + +bool TuneMenu::onTouchEnd(uint8_t tag) { + using namespace Theme; + using namespace ExtUI; + switch (tag) { + case 1: SaveSettingsDialogBox::promptToSaveSettings(); break; + case 2: GOTO_SCREEN(TemperatureScreen); break; + case 3: GOTO_SCREEN(ChangeFilamentScreen); break; + case 4: + #if ENABLED(BABYSTEPPING) && HAS_MULTI_HOTEND + GOTO_SCREEN(NudgeNozzleScreen); + #elif BOTH(HAS_LEVELING, HAS_BED_PROBE) + GOTO_SCREEN(ZOffsetScreen); + #endif + break; + case 5: GOTO_SCREEN(FeedratePercentScreen); break; + case 6: pausePrint(); break; + case 7: resumePrint(); break; + case 8: + GOTO_SCREEN(ConfirmAbortPrintDialogBox); + current_screen.forget(); + PUSH_SCREEN(StatusScreen); + break; + #if EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) + case 9: GOTO_SCREEN(FilamentMenu); break; + #endif + #if ENABLED(CASE_LIGHT_ENABLE) + case 10: GOTO_SCREEN(CaseLightScreen); break; + #endif + case 11: GOTO_SCREEN(AdvancedSettingsMenu); break; + default: + return false; + } + return true; +} + +void TuneMenu::pausePrint() { + sound.play(twinkle, PLAY_ASYNCHRONOUS); + if (ExtUI::isPrintingFromMedia()) + ExtUI::pausePrint(); + #ifdef ACTION_ON_PAUSE + else host_action_pause(); + #endif + GOTO_SCREEN(StatusScreen); +} + +void TuneMenu::resumePrint() { + sound.play(twinkle, PLAY_ASYNCHRONOUS); + if (ExtUI::awaitingUserConfirm()) + ExtUI::setUserConfirmed(); + else if (ExtUI::isPrintingFromMedia()) + ExtUI::resumePrint(); + #ifdef ACTION_ON_RESUME + else host_action_resume(); + #endif + GOTO_SCREEN(StatusScreen); +} + +#endif // FTDI_TUNE_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/tune_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/tune_menu.h new file mode 100644 index 000000000000..b8f9373b1902 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/tune_menu.h @@ -0,0 +1,35 @@ +/*************** + * tune_menu.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 FTDI_TUNE_MENU +#define FTDI_TUNE_MENU_CLASS TuneMenu + +class TuneMenu : public BaseScreen, public CachedScreen { + private: + static void pausePrint(); + static void resumePrint(); + public: + static void onRedraw(draw_mode_t); + static bool onTouchEnd(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/widget_demo_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/widget_demo_screen.cpp similarity index 96% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/widget_demo_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/widget_demo_screen.cpp index d7c456204123..d02397abf907 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/widget_demo_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/widget_demo_screen.cpp @@ -17,14 +17,13 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../config.h" +#include "../screens.h" -#if BOTH(TOUCH_UI_FTDI_EVE, TOUCH_UI_DEVELOPER_MENU) - -#include "screens.h" +#ifdef FTDI_WIDGET_DEMO_SCREEN using namespace FTDI; using namespace ExtUI; @@ -51,7 +50,7 @@ void WidgetsScreen::onRedraw(draw_mode_t) { const uint16_t m = (slider_val*12*60/0xFFFFU)%60; const uint16_t s = (slider_val*12*60*60/0xFFFFU)%60; - #ifdef TOUCH_UI_PORTRAIT + #if ENABLED(TOUCH_UI_PORTRAIT) #define GRID_COLS 3 #define GRID_ROWS 8 cmd.font(font_large) @@ -113,7 +112,7 @@ bool WidgetsScreen::onTouchStart(uint8_t tag) { CommandProcessor cmd; switch (tag) { case 1: GOTO_PREVIOUS(); break; - #ifdef TOUCH_UI_PORTRAIT + #if ENABLED(TOUCH_UI_PORTRAIT) case 2: cmd.track_circular (BTN_POS(1,2), BTN_SIZE(1,2), 2).execute(); break; case 4: cmd.track_linear (BTN_POS(2,3), BTN_SIZE(2,1), 4).execute(); break; case 5: cmd.track_linear (BTN_POS(2,4), BTN_SIZE(2,1), 5).execute(); break; @@ -155,4 +154,4 @@ void WidgetsScreen::onIdle() { BaseScreen::onIdle(); } -#endif // TOUCH_UI_FTDI_EVE && TOUCH_UI_DEVELOPER_MENU +#endif // FTDI_WIDGET_DEMO_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/widget_demo_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/widget_demo_screen.h new file mode 100644 index 000000000000..e0f7422d1211 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/widget_demo_screen.h @@ -0,0 +1,34 @@ +/************************ + * widget_demo_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 FTDI_WIDGET_DEMO_SCREEN +#define FTDI_WIDGET_DEMO_SCREEN_CLASS WidgetsScreen + +class WidgetsScreen : public BaseScreen, public UncachedScreen { + public: + static void onEntry(); + static void onRedraw(draw_mode_t); + static bool onTouchStart(uint8_t tag); + static void onIdle(); +}; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.cpp new file mode 100644 index 000000000000..eb367987940e --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.cpp @@ -0,0 +1,111 @@ +/*********************** + * 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 FTDI_Z_OFFSET_SCREEN + +using namespace FTDI; +using namespace ExtUI; +using namespace Theme; + +#define SHEET_THICKNESS 0.1 + +constexpr static ZOffsetScreenData &mydata = screen_data.ZOffsetScreen; + +void ZOffsetScreen::onEntry() { + mydata.z = SHEET_THICKNESS; + mydata.softEndstopState = getSoftEndstopState(); + BaseNumericAdjustmentScreen::onEntry(); + if (wizardRunning()) + setSoftEndstopState(false); +} + +void ZOffsetScreen::onExit() { + setSoftEndstopState(mydata.softEndstopState); +} + +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() && !wizardRunning()); +} + +void ZOffsetScreen::move(float mm, int16_t steps) { + if (wizardRunning()) { + mydata.z += mm; + setAxisPosition_mm(mydata.z, Z); + } + else { + // Otherwise doing a manual adjustment, possibly during a print. + TERN(BABYSTEPPING, babystepAxis_steps(steps, Z), UNUSED(steps)); + } +} + +void ZOffsetScreen::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("After the printer finishes homing, adjust the Z Offset so that a sheet of paper can pass between the nozzle and bed with slight resistance.")); +} + +bool ZOffsetScreen::wizardRunning() { + // We can't store state after the call to the AlertBox, so + // check whether the current Z position equals mydata.z in order + // to know whether the user started the wizard. + return getAxisPosition_mm(Z) == mydata.z; +} + +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: runWizard(); break; + case 4: UI_DECREMENT(ZOffset_mm); move(-increment, -steps); break; + case 5: UI_INCREMENT(ZOffset_mm); move( increment, steps); break; + default: + return false; + } + SaveSettingsDialogBox::settingsChanged(); + return true; +} + +#endif // FTDI_Z_OFFSET_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.h new file mode 100644 index 000000000000..0df9209b1fdd --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.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 FTDI_Z_OFFSET_SCREEN +#define FTDI_Z_OFFSET_SCREEN_CLASS ZOffsetScreen + +struct ZOffsetScreenData : public BaseNumericAdjustmentScreenData { + float z; + bool softEndstopState; +}; + +class ZOffsetScreen : public BaseNumericAdjustmentScreen, public CachedScreen { + private: + static void move(float mm, int16_t steps); + static void runWizard(); + static bool wizardRunning(); + public: + static void onEntry(); + static void onExit(); + static void onRedraw(draw_mode_t); + static bool onTouchHeld(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language.cpp similarity index 96% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language.cpp index 912c95731d12..d9097675265e 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language.cpp @@ -16,11 +16,11 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ -#include "../../../../../MarlinCore.h" +#include "../../../../MarlinCore.h" #include "language.h" diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language.h similarity index 98% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language.h index 873e84455ad0..cbc05c5aa3b0 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language.h @@ -16,7 +16,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language_en.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language_en.h similarity index 85% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language_en.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language_en.h index cc96c8b9cda7..0d883d8d02c0 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language_en.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language_en.h @@ -16,7 +16,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once @@ -29,12 +29,6 @@ #define COPYRIGHT_SIGN u8"(c)" #endif -#if ENABLED(TOUCH_UI_UTF8_SUPERSCRIPTS) - #define SUPERSCRIPT_TWO u8"²" -#else - #define SUPERSCRIPT_TWO u8"^2" -#endif - #if ENABLED(TOUCH_UI_UTF8_WESTERN_CHARSET) #define DEGREE_SIGN u8"°" #else @@ -76,7 +70,7 @@ namespace Language_en { PROGMEM Language_Str MSG_ABOUT_TOUCH_PANEL_2 = WEBSITE_URL; PROGMEM Language_Str MSG_LICENSE = u8"This program is free software: you can redistribute it and/or modify it under the terms of " "the GNU General Public License as published by the Free Software Foundation, either version 3 " - "of the License, or (at your option) any later version.\n\nTo view a copy of the GNU General " + "of the License, or (at your option) any later version. To view a copy of the GNU General " "Public License, go to the following location: https://www.gnu.org/licenses."; PROGMEM Language_Str MSG_RUNOUT_1 = u8"Runout 1"; PROGMEM Language_Str MSG_RUNOUT_2 = u8"Runout 2"; @@ -119,7 +113,7 @@ namespace Language_en { PROGMEM Language_Str MSG_CAUTION = u8"Caution:"; PROGMEM Language_Str MSG_HOT = u8"Hot!"; PROGMEM Language_Str MSG_UNLOAD_FILAMENT = u8"Unload/Retract"; - PROGMEM Language_Str MSG_LOAD_FILAMENT = u8"Load/Extruder"; + PROGMEM Language_Str MSG_LOAD_FILAMENT = u8"Load/Extrude"; PROGMEM Language_Str MSG_MOMENTARY = u8"Momentary"; PROGMEM Language_Str MSG_CONTINUOUS = u8"Continuous"; PROGMEM Language_Str MSG_PLEASE_WAIT = u8"Please wait..."; @@ -136,7 +130,7 @@ namespace Language_en { PROGMEM Language_Str MSG_EEPROM_RESTORED = u8"Settings restored from backup"; PROGMEM Language_Str MSG_EEPROM_RESET = u8"Settings restored to default"; PROGMEM Language_Str MSG_EEPROM_SAVED = u8"Settings saved!"; - PROGMEM Language_Str MSG_EEPROM_SAVE_PROMPT = u8"Do you wish to save these settings as defaults?"; + PROGMEM Language_Str MSG_EEPROM_SAVE_PROMPT = u8"Settings applied. Save these settings for next power-on?"; PROGMEM Language_Str MSG_EEPROM_RESET_WARNING = u8"Are you sure? Customizations will be lost."; PROGMEM Language_Str MSG_PASSCODE_REJECTED = u8"Wrong passcode!"; @@ -146,13 +140,16 @@ namespace Language_en { PROGMEM Language_Str MSG_TOUCH_CALIBRATION_START = u8"Release to begin screen calibration"; PROGMEM Language_Str MSG_TOUCH_CALIBRATION_PROMPT = u8"Touch the dots to calibrate"; - PROGMEM Language_Str MSG_AUTOLEVEL_X_AXIS = u8"Level X Axis"; PROGMEM Language_Str MSG_BED_MAPPING_DONE = u8"Bed mapping finished"; PROGMEM Language_Str MSG_BED_MAPPING_INCOMPLETE = u8"Not all points probed"; PROGMEM Language_Str MSG_LEVELING = u8"Leveling"; - PROGMEM Language_Str MSG_SHOW_MESH = u8"Show Bed Mesh"; + PROGMEM Language_Str MSG_AXIS_LEVELING = u8"Axis Leveling"; + PROGMEM Language_Str MSG_PROBE_BED = u8"Probe Mesh"; + PROGMEM Language_Str MSG_SHOW_MESH = u8"View Mesh"; + PROGMEM Language_Str MSG_PRINT_TEST = u8"Print Test (PLA)"; + PROGMEM Language_Str MSG_MOVE_Z_TO_TOP = u8"Raise Z to Top"; - #ifdef TOUCH_UI_LULZBOT_BIO + #if ENABLED(TOUCH_UI_LULZBOT_BIO) PROGMEM Language_Str MSG_MOVE_TO_HOME = u8"Move to Home"; PROGMEM Language_Str MSG_RAISE_PLUNGER = u8"Raise Plunger"; PROGMEM Language_Str MSG_RELEASE_XY_AXIS = u8"Release X and Y Axis"; @@ -162,9 +159,21 @@ namespace Language_en { #endif #ifdef TOUCH_UI_COCOA_PRESS - PROGMEM Language_Str MSG_ZONE_1 = u8"Zone 1:"; - PROGMEM Language_Str MSG_ZONE_2 = u8"Zone 2:"; - PROGMEM Language_Str MSG_ZONE_3 = u8"Zone 3:"; + PROGMEM Language_Str MSG_BODY = u8"Body"; + PROGMEM Language_Str MSG_SELECT_CHOCOLATE_TYPE = u8"Select Chocolate Type"; + PROGMEM Language_Str MSG_EXTERNAL = u8"External"; + PROGMEM Language_Str MSG_CHOCOLATE = u8"Chocolate"; + PROGMEM Language_Str MSG_UNLOAD_CARTRIDGE = u8"Unload Cartridge"; + PROGMEM Language_Str MSG_LOAD_UNLOAD = u8"Load/Unload"; + PROGMEM Language_Str MSG_FULL_LOAD = u8"Full Load"; + PROGMEM Language_Str MSG_FULL_UNLOAD = u8"Full Unload"; + PROGMEM Language_Str MSG_PREHEAT_CHOCOLATE = u8"Preheat Chocolate"; PROGMEM Language_Str MSG_PREHEAT_FINISHED = u8"Preheat finished"; + PROGMEM Language_Str MSG_PREHEAT = u8"Preheat"; + PROGMEM Language_Str MSG_BUTTON_PAUSE = u8"Pause"; + PROGMEM Language_Str MSG_BUTTON_RESUME = u8"Resume"; + PROGMEM Language_Str MSG_ELAPSED_PRINT = u8"Elapsed Print"; + PROGMEM Language_Str MSG_XYZ_MOVE = u8"XYZ Move"; + PROGMEM Language_Str MSG_E_MOVE = u8"Extrusion Move"; #endif }; // namespace Language_en diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/pin_mappings.h similarity index 99% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/pin_mappings.h index 5ad84c60b0ff..04cdbe96db9d 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/pin_mappings.h @@ -16,7 +16,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once @@ -27,7 +27,7 @@ * without adding new pin definitions to the board. */ -#include "../../../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #if ENABLED(F6_TFT_PINMAP) // FYSETC F6 - ATmega2560 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 new file mode 100644 index 000000000000..057054a6af17 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screen_data.h @@ -0,0 +1,69 @@ +/***************** + * screen_data.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 + +#include "ftdi_eve_lib/ftdi_eve_lib.h" + +// To save RAM, store state information related to a particular screen +// in a union. The values should be initialized in the onEntry method. + +/** + * The DECL_DATA_IF_INCLUDED macro: + * + * union screen_data_t { + * DECL_DATA_IF_INCLUDED(FTDI_EXAMPLE_SCREEN) + * } + * + * Is a shorthand for: + * + * union screen_data_t { + * #ifdef FTDI_EXAMPLE_SCREEN + * struct ExampleScreenData ExampleScreen; + * #endif + * } + * + */ +#define __DECL_DATA_IF_INCLUDED(CLASS) struct CLASS ## Data CLASS ; +#define _DECL_DATA_IF_INCLUDED(CLASS) __DECL_DATA_IF_INCLUDED(CLASS) +#define DECL_DATA_IF_INCLUDED(HEADER) TERN(HEADER, _DECL_DATA_IF_INCLUDED(HEADER ## _CLASS), ) + +union screen_data_t { + DECL_DATA_IF_INCLUDED(FTDI_INTERFACE_SETTINGS_SCREEN) + DECL_DATA_IF_INCLUDED(FTDI_LOCK_SCREEN) + DECL_DATA_IF_INCLUDED(FTDI_SPINNER_DIALOG_BOX) + DECL_DATA_IF_INCLUDED(FTDI_CONFIRM_START_PRINT_DIALOG_BOX) + DECL_DATA_IF_INCLUDED(FTDI_CHANGE_FILAMENT_SCREEN) + DECL_DATA_IF_INCLUDED(FTDI_FILES_SCREEN) + DECL_DATA_IF_INCLUDED(FTDI_MOVE_AXIS_SCREEN) + DECL_DATA_IF_INCLUDED(FTDI_BED_MESH_VIEW_SCREEN) + DECL_DATA_IF_INCLUDED(FTDI_BED_MESH_EDIT_SCREEN) + DECL_DATA_IF_INCLUDED(FTDI_STRESS_TEST_SCREEN) + DECL_DATA_IF_INCLUDED(FTDI_NUDGE_NOZZLE_SCREEN) + 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_PREHEAT_SCREEN) + DECL_DATA_IF_INCLUDED(COCOA_LOAD_CHOCOLATE_SCREEN) +}; + +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 new file mode 100644 index 000000000000..ec627e313b13 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.cpp @@ -0,0 +1,126 @@ +/*************** + * screens.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" + +#if ENABLED(TOUCH_UI_FTDI_EVE) +#include "screens.h" +tiny_timer_t refresh_timer; + + +/** + * DECL_SCREEN_IF_INCLUDED allows for a concise + * definition of SCREEN_TABLE: + * + * SCREEN_TABLE { + * DECL_SCREEN_IF_INCLUDED(MY_HEADER) + * } + * + * Is a shorthand for: + * + * SCREEN_TABLE { + * #ifdef MY_HEADER + * DECL_SCREEN(MY_HEADER), + * #endif + * } + * + */ +#define COMMA , +#define __DECL_SCREEN_IF_INCLUDED(O,C) THIRD(O, DECL_SCREEN(C) COMMA,) +#define _DECL_SCREEN_IF_INCLUDED(O,C) __DECL_SCREEN_IF_INCLUDED(O ## COMMA, C) +#define DECL_SCREEN_IF_INCLUDED(H) _DECL_SCREEN_IF_INCLUDED(H, H ## _CLASS) + +SCREEN_TABLE { + DECL_SCREEN_IF_INCLUDED(FTDI_BOOT_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_LANGUAGE_MENU) + DECL_SCREEN_IF_INCLUDED(FTDI_TOUCH_CALIBRATION_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_STATUS_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_MAIN_MENU) + DECL_SCREEN_IF_INCLUDED(FTDI_TUNE_MENU) + DECL_SCREEN_IF_INCLUDED(FTDI_ADVANCED_SETTINGS_MENU) + DECL_SCREEN_IF_INCLUDED(FTDI_ALERT_DIALOG_BOX) + DECL_SCREEN_IF_INCLUDED(FTDI_CONFIRM_USER_REQUEST_ALERT_BOX) + DECL_SCREEN_IF_INCLUDED(FTDI_RESTORE_FAILSAFE_DIALOG_BOX) + DECL_SCREEN_IF_INCLUDED(FTDI_SAVE_SETTINGS_DIALOG_BOX) + DECL_SCREEN_IF_INCLUDED(FTDI_CONFIRM_START_PRINT_DIALOG_BOX) + DECL_SCREEN_IF_INCLUDED(FTDI_CONFIRM_ABORT_PRINT_DIALOG_BOX) + DECL_SCREEN_IF_INCLUDED(FTDI_CONFIRM_AUTO_CALIBRATION_DIALOG_BOX) + DECL_SCREEN_IF_INCLUDED(FTDI_CUSTOM_USER_MENUS) + DECL_SCREEN_IF_INCLUDED(FTDI_SPINNER_DIALOG_BOX) + DECL_SCREEN_IF_INCLUDED(FTDI_ABOUT_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_STATISTICS_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_NUDGE_NOZZLE_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_MOVE_AXIS_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_STEPS_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_STEPPER_CURRENT_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_STEPPER_BUMP_SENSITIVITY_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_LEVELING_MENU) + DECL_SCREEN_IF_INCLUDED(FTDI_Z_OFFSET_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_BED_MESH_VIEW_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_BED_MESH_EDIT_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_NOZZLE_OFFSETS_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_BACKLASH_COMP_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_FEEDRATE_PERCENT_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_FLOW_PERCENT_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_MAX_VELOCITY_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_MAX_ACCELERATION_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_DEFAULT_ACCELERATION_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_JUNCTION_DEVIATION_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_JERK_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_CASE_LIGHT_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_FILAMENT_MENU) + DECL_SCREEN_IF_INCLUDED(FTDI_FILAMENT_RUNOUT_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_LINEAR_ADVANCE_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_TEMPERATURE_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_CHANGE_FILAMENT_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_INTERFACE_SETTINGS_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_INTERFACE_SOUNDS_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_LOCK_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_FILES_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_ENDSTOP_STATE_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_BIO_PRINTING_DIALOG_BOX) + DECL_SCREEN_IF_INCLUDED(FTDI_BIO_CONFIRMOME_XYZ) + DECL_SCREEN_IF_INCLUDED(FTDI_BIO_CONFIRMOME_E) + DECL_SCREEN_IF_INCLUDED(FTDI_DEVELOPER_MENU) + DECL_SCREEN_IF_INCLUDED(FTDI_CONFIRM_ERASE_FLASH_DIALOG_BOX) + DECL_SCREEN_IF_INCLUDED(FTDI_WIDGET_DEMO_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_TOUCH_REGISTERS_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_STRESS_TEST_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_MEDIA_PLAYER_SCREEN) + DECL_SCREEN_IF_INCLUDED(FTDI_DISPLAY_TUNING_SCREEN) + DECL_SCREEN_IF_INCLUDED(COCOA_STATUS_SCREEN) + DECL_SCREEN_IF_INCLUDED(COCOA_MAIN_MENU) + DECL_SCREEN_IF_INCLUDED(COCOA_ADVANCED_SETTINGS_MENU) + DECL_SCREEN_IF_INCLUDED(COCOA_PREHEAT_MENU) + DECL_SCREEN_IF_INCLUDED(COCOA_PREHEAT_SCREEN) + DECL_SCREEN_IF_INCLUDED(COCOA_LOAD_CHOCOLATE_SCREEN) + DECL_SCREEN_IF_INCLUDED(COCOA_LEVELING_MENU) + DECL_SCREEN_IF_INCLUDED(COCOA_MOVE_XYZ_SCREEN) + DECL_SCREEN_IF_INCLUDED(COCOA_MOVE_E_SCREEN) +}; + +SCREEN_TABLE_POST + +#include "screen_data.h" +screen_data_t screen_data; + +#endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.h new file mode 100644 index 000000000000..fb3e909d2f24 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.h @@ -0,0 +1,50 @@ +/************* + * screens.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 + +#include "config.h" + +#if ENABLED(TOUCH_UI_FTDI_EVE) + +#include "ftdi_eve_lib/ftdi_eve_lib.h" +#include "language/language.h" +#include "theme/theme.h" +#include "generic/string_format.h" + +#ifndef BED_LEVELING_COMMANDS + #define BED_LEVELING_COMMANDS "G29" +#endif + +extern tiny_timer_t refresh_timer; + +#if ENABLED(TOUCH_UI_LULZBOT_BIO) + #include "bioprinter/screens.h" +#elif ENABLED(TOUCH_UI_COCOA_PRESS) + #include "cocoa_press/screens.h" +#elif ENABLED(TOUCH_UI_SYNDAVER_LEVEL) + #include "syndaver_level/screens.h" +#else + #include "generic/screens.h" +#endif + +#endif // TOUCH_UI_FTDI_EVE 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 new file mode 100644 index 000000000000..f7cb63125f4b --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bitmaps.h @@ -0,0 +1,233 @@ +/************* + * bitmaps.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 + +namespace Theme { + using namespace FTDI; + + constexpr PROGMEM bitmap_info_t Extruder_Icon_Info = { + .format = L1, + .linestride = 3, + .filter = BILINEAR, + .wrapx = BORDER, + .wrapy = BORDER, + .RAMG_offset = 8000, + .width = 24, + .height = 23, + }; + + 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, + 0x00, 0xC3, 0x00, + 0x00, 0x66, 0x00, + 0x00, 0x3C, 0x00, + 0x00, 0x3C, 0x00 + }; + + constexpr PROGMEM bitmap_info_t Bed_Heat_Icon_Info = { + .format = L1, + .linestride = 4, + .filter = BILINEAR, + .wrapx = BORDER, + .wrapy = BORDER, + .RAMG_offset = 8069, + .width = 32, + .height = 23, + }; + + 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, + 0x00, 0x00, 0x00, 0x00, + 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, + 0xC0, 0x00, 0x00, 0x03, + 0xFF, 0xFF, 0xFF, 0xFF + }; + + constexpr PROGMEM bitmap_info_t Fan_Icon_Info = { + .format = L1, + .linestride = 4, + .filter = BILINEAR, + .wrapx = BORDER, + .wrapy = BORDER, + .RAMG_offset = 8161, + .width = 32, + .height = 32, + }; + + 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, + 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF + }; + + constexpr PROGMEM bitmap_info_t TD_Icon_Info = { + .format = L1, + .linestride = 7, + .filter = BILINEAR, + .wrapx = BORDER, + .wrapy = BORDER, + .RAMG_offset = 8289, + .width = 50, + .height = 20, + }; + + 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 + }; + + constexpr PROGMEM bitmap_info_t File_Icon_Info = { + .format = L1, + .linestride = 4, + .filter = BILINEAR, + .wrapx = BORDER, + .wrapy = BORDER, + .RAMG_offset = 8429, + .width = 25, + .height = 32, + }; + + 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 + }; + + constexpr PROGMEM bitmap_info_t Clock_Icon_Info = { + .format = L1, + .linestride = 4, + .filter = BILINEAR, + .wrapx = BORDER, + .wrapy = BORDER, + .RAMG_offset = 8557, + .width = 32, + .height = 32, + }; + + 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 + }; + + constexpr PROGMEM uint32_t UTF8_FONT_OFFSET = 10000; +}; // namespace Theme diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/bootscreen_logo_portrait.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bootscreen_logo_portrait.h similarity index 99% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/bootscreen_logo_portrait.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bootscreen_logo_portrait.h index 6ea317dbc3cd..5d9735892deb 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/bootscreen_logo_portrait.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bootscreen_logo_portrait.h @@ -10,7 +10,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ /** diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/colors.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/colors.h similarity index 96% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/colors.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/colors.h index 4e2fde6ab333..995379fcdab7 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/colors.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/colors.h @@ -18,7 +18,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once @@ -85,6 +85,9 @@ namespace Theme { constexpr uint32_t logo_bg_rgb = accent_color_1; constexpr uint32_t logo_fill_rgb = accent_color_0; constexpr uint32_t logo_stroke_rgb = accent_color_4; + + constexpr uint32_t bed_mesh_lines_rgb = 0xFFFFFF; + constexpr uint32_t bed_mesh_shadow_rgb = 0x444444; #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; @@ -102,6 +105,10 @@ namespace Theme { constexpr uint32_t logo_bg_rgb = accent_color_5; constexpr uint32_t logo_fill_rgb = accent_color_6; constexpr uint32_t logo_stroke_rgb = accent_color_2; + + constexpr uint32_t bed_mesh_lines_rgb = accent_color_6; + constexpr uint32_t bed_mesh_shadow_rgb = 0x444444; + #define BED_MESH_POINTS_GRAY #else constexpr uint32_t theme_darkest = gray_color_1; constexpr uint32_t theme_dark = gray_color_2; @@ -119,6 +126,9 @@ namespace Theme { constexpr uint32_t logo_bg_rgb = accent_color_4; constexpr uint32_t logo_fill_rgb = accent_color_3; constexpr uint32_t logo_stroke_rgb = 0x000000; + + constexpr uint32_t bed_mesh_lines_rgb = 0xFFFFFF; + constexpr uint32_t bed_mesh_shadow_rgb = 0x444444; #endif constexpr uint32_t shadow_rgb = gray_color_6; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/fonts.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/fonts.h similarity index 95% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/fonts.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/fonts.h index 63115b418730..63ecdfcb3c7e 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/fonts.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/fonts.h @@ -17,14 +17,14 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once namespace Theme { #ifdef TOUCH_UI_800x480 - #ifdef TOUCH_UI_PORTRAIT + #if ENABLED(TOUCH_UI_PORTRAIT) constexpr int16_t font_tiny = 26; constexpr int16_t font_xsmall = 28; constexpr int16_t font_small = 29; @@ -41,7 +41,7 @@ namespace Theme { #endif constexpr float icon_scale = 1.0; #elif defined(TOUCH_UI_480x272) - #ifdef TOUCH_UI_PORTRAIT + #if ENABLED(TOUCH_UI_PORTRAIT) constexpr int16_t font_tiny = 26; constexpr int16_t font_xsmall = 26; constexpr int16_t font_small = 26; @@ -55,11 +55,11 @@ namespace Theme { constexpr int16_t font_small = 27; constexpr int16_t font_medium = 28; constexpr int16_t font_large = 30; - constexpr int16_t font_xlarge = 31; + constexpr int16_t font_xlarge = 30; constexpr float icon_scale = 0.6; #endif #elif defined(TOUCH_UI_320x240) - #ifdef TOUCH_UI_PORTRAIT + #if ENABLED(TOUCH_UI_PORTRAIT) constexpr int16_t font_tiny = 26; constexpr int16_t font_xsmall = 26; constexpr int16_t font_small = 26; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_landscape.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/marlin_bootscreen_landscape.h similarity index 99% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_landscape.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/marlin_bootscreen_landscape.h index eb9cadeba1e4..e023599a27c1 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_landscape.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/marlin_bootscreen_landscape.h @@ -11,7 +11,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ /** diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_portrait.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/marlin_bootscreen_portrait.h similarity index 99% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_portrait.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/marlin_bootscreen_portrait.h index dd5088e0ce2b..e3a30a6dfeff 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_portrait.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/marlin_bootscreen_portrait.h @@ -11,7 +11,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ /** diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/sounds.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/sounds.cpp similarity index 99% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/sounds.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/sounds.cpp index f4a80bcc09fd..1ed712ded1bc 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/sounds.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/sounds.cpp @@ -17,10 +17,10 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ -#include "../compat.h" +#include "../config.h" #if ENABLED(TOUCH_UI_FTDI_EVE) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/sounds.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/sounds.h similarity index 99% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/sounds.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/sounds.h index b2b889038650..66c1cb810ca8 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/sounds.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/sounds.h @@ -17,7 +17,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/theme.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/theme.h similarity index 98% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/theme.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/theme.h index df7782ce87dd..e0f0f31da509 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/theme.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/theme.h @@ -17,7 +17,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once diff --git a/Marlin/src/lcd/extui/lib/anycubic_chiron/FileNavigator.cpp b/Marlin/src/lcd/extui/lib/anycubic_chiron/FileNavigator.cpp deleted file mode 100644 index fb4c84abb485..000000000000 --- a/Marlin/src/lcd/extui/lib/anycubic_chiron/FileNavigator.cpp +++ /dev/null @@ -1,162 +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 . - * - */ - -/** - * lcd/extui/lib/FileNavigator.cpp - * - * Extensible_UI implementation for Anycubic Chiron - * Written By Nick Wells, 2020 [https://github.com/SwiftNick] - * (not affiliated with Anycubic, Ltd.) - */ - -/*************************************************************************** - * The AC panel wants files in block of 4 and can only display a flat list * - * This library allows full folder traversal. * - ***************************************************************************/ - -#include "../../../../inc/MarlinConfigPre.h" - -#if ENABLED(ANYCUBIC_LCD_CHIRON) - -#include "FileNavigator.h" -#include "chiron_tft.h" - -using namespace ExtUI; - -namespace Anycubic { - - FileList FileNavigator::filelist; // Instance of the Marlin file API - char FileNavigator::currentfoldername[MAX_PATH_LEN]; // Current folder path - uint16_t FileNavigator::lastindex; - uint8_t FileNavigator::folderdepth; - uint16_t FileNavigator::currentindex; // override the panel request - - FileNavigator::FileNavigator() { reset(); } - - void FileNavigator::reset() { - currentfoldername[0] = '\0'; - folderdepth = 0; - currentindex = 0; - lastindex = 0; - // Start at root folder - while (!filelist.isAtRootDir()) filelist.upDir(); - refresh(); - } - - void FileNavigator::refresh() { filelist.refresh(); } - - void FileNavigator::getFiles(uint16_t index) { - uint8_t files = 4; - if (index == 0) currentindex = 0; - - // Each time we change folder we reset the file index to 0 and keep track - // of the current position as the TFT panel isnt aware of folders trees. - if (index > 0) { - --currentindex; // go back a file to take account off the .. we added to the root. - if (index > lastindex) - currentindex += files; - else - currentindex = currentindex < 4 ? 0 : currentindex - files; - } - lastindex = index; - - #if ACDEBUG(AC_FILE) - SERIAL_ECHOLNPAIR("index=", index, " currentindex=", currentindex); - #endif - - if (currentindex == 0 && folderdepth > 0) { // Add a link to go up a folder - TFTSer.println("<<"); - TFTSer.println(".."); - files--; - } - - for (uint16_t seek = currentindex; seek < currentindex + files; seek++) { - if (filelist.seek(seek)) { - sendFile(); - #if ACDEBUG(AC_FILE) - SERIAL_ECHOLNPAIR("-", seek, " '", filelist.longFilename(), "' '", currentfoldername, "", filelist.shortFilename(), "'\n"); - #endif - } - } - } - - void FileNavigator::sendFile() { - // send the file and folder info to the panel - // this info will be returned when the file is selected - // Permitted special characters in file name -_*#~ - // Panel can display 22 characters per line - if (filelist.isDir()) { - //TFTSer.print(currentfoldername); - TFTSer.println(filelist.shortFilename()); - TFTSer.print(filelist.shortFilename()); - TFTSer.println("/"); - } - else { - // Logical Name - TFTSer.print("/"); - if (folderdepth > 0) TFTSer.print(currentfoldername); - - TFTSer.println(filelist.shortFilename()); - - // Display Name - TFTSer.println(filelist.longFilename()); - } - } - void FileNavigator::changeDIR(char *folder) { - #if ACDEBUG(AC_FILE) - SERIAL_ECHOLNPAIR("currentfolder: ", currentfoldername, " New: ", folder); - #endif - if (folderdepth >= MAX_FOLDER_DEPTH) return; // limit the folder depth - strcat(currentfoldername, folder); - strcat(currentfoldername, "/"); - filelist.changeDir(folder); - refresh(); - folderdepth++; - currentindex = 0; - } - - void FileNavigator::upDIR() { - filelist.upDir(); - refresh(); - folderdepth--; - currentindex = 0; - // Remove the last child folder from the stored path - if (folderdepth == 0) { - currentfoldername[0] = '\0'; - reset(); - } - else { - char *pos = nullptr; - for (uint8_t f = 0; f < folderdepth; f++) - pos = strchr(currentfoldername, '/'); - - *(pos + 1) = '\0'; - } - #if ACDEBUG(AC_FILE) - SERIAL_ECHOLNPAIR("depth: ", folderdepth, " currentfoldername: ", currentfoldername); - #endif - } - - char* FileNavigator::getCurrentFolderName() { return currentfoldername; } -} - -#endif // ANYCUBIC_LCD_CHIRON diff --git a/Marlin/src/lcd/extui/lib/anycubic_chiron/FileNavigator.h b/Marlin/src/lcd/extui/lib/anycubic_chiron/FileNavigator.h deleted file mode 100644 index 8e03614a4649..000000000000 --- a/Marlin/src/lcd/extui/lib/anycubic_chiron/FileNavigator.h +++ /dev/null @@ -1,56 +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 - -/** - * lcd/extui/lib/FileNavigator.h - * - * Extensible_UI implementation for Anycubic Chiron - * Written By Nick Wells, 2020 [https://github.com/SwiftNick] - * (not affiliated with Anycubic, Ltd.) - */ - -#include "chiron_tft_defs.h" -#include "../../ui_api.h" - -using namespace ExtUI; - -namespace Anycubic { - class FileNavigator { - public: - FileNavigator(); - void reset(); - void getFiles(uint16_t); - void upDIR(); - void changeDIR(char *); - void sendFile(); - void refresh(); - char * getCurrentFolderName(); - private: - static FileList filelist; - static char currentfoldername[MAX_PATH_LEN]; - static uint16_t lastindex; - static uint8_t folderdepth; - static uint16_t currentindex; - }; - extern FileNavigator filenavigator; -} diff --git a/Marlin/src/lcd/extui/lib/anycubic_chiron/chiron_tft.cpp b/Marlin/src/lcd/extui/lib/anycubic_chiron/chiron_tft.cpp deleted file mode 100644 index 5e492573e70a..000000000000 --- a/Marlin/src/lcd/extui/lib/anycubic_chiron/chiron_tft.cpp +++ /dev/null @@ -1,896 +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 . - * - */ - -/** - * lcd/extui/lib/chiron_tft.cpp - * - * Extensible_UI implementation for Anycubic Chiron - * Written By Nick Wells, 2020 [https://github.com/SwiftNick] - * (not affiliated with Anycubic, Ltd.) - */ - -#include "../../../../inc/MarlinConfigPre.h" - -#if ENABLED(ANYCUBIC_LCD_CHIRON) - -#include "chiron_tft.h" -#include "Tunes.h" -#include "FileNavigator.h" - -#include "../../../../gcode/queue.h" -#include "../../../../sd/cardreader.h" -#include "../../../../libs/numtostr.h" -#include "../../../../MarlinCore.h" -namespace Anycubic { - - printer_state_t ChironTFT::printer_state; - paused_state_t ChironTFT::pause_state; - heater_state_t ChironTFT::hotend_state; - heater_state_t ChironTFT::hotbed_state; - xy_uint8_t ChironTFT::selectedmeshpoint; - char ChironTFT::selectedfile[MAX_PATH_LEN]; - char ChironTFT::panel_command[MAX_CMND_LEN]; - uint8_t ChironTFT::command_len; - float ChironTFT::live_Zoffset; - file_menu_t ChironTFT::file_menu; - - ChironTFT::ChironTFT(){} - - void ChironTFT::Startup() { - selectedfile[0] = '\0'; - panel_command[0] = '\0'; - command_len = 0; - printer_state = AC_printer_idle; - pause_state = AC_paused_idle; - hotend_state = AC_heater_off; - hotbed_state = AC_heater_off; - live_Zoffset = 0.0; - file_menu = AC_menu_file; - - // Setup pins for powerloss detection - // Two IO pins are connected on the Trigorilla Board - // On a power interruption the OUTAGECON_PIN goes low. - - #if ENABLED(POWER_LOSS_RECOVERY) - OUT_WRITE(OUTAGECON_PIN, HIGH); - #endif - - // Filament runout is handled by Marlin settings in Configuration.h - // set FIL_RUNOUT_STATE HIGH // Pin state indicating that filament is NOT present. - // enable FIL_RUNOUT_PULLUP - - TFTSer.begin(115200); - - // Signal Board has reset - SendtoTFTLN(AC_msg_main_board_has_reset); - - safe_delay(200); - - // Enable levelling and Disable end stops during print - // as Z home places nozzle above the bed so we need to allow it past the end stops - injectCommands_P(AC_cmnd_enable_levelling); //M211 S0\n")); - - // Startup tunes are defined in Tunes.h - //PlayTune(BEEPER_PIN, Anycubic_PowerOn, 1); - PlayTune(BEEPER_PIN, GB_PowerOn, 1); - #if ACDEBUGLEVEL - SERIAL_ECHOLNPAIR("AC Debug Level ", ACDEBUGLEVEL); - #endif - SendtoTFTLN(AC_msg_ready); - } - - void ChironTFT::IdleLoop() { - if (ReadTFTCommand()) { - ProcessPanelRequest(); - command_len = 0; - } - CheckHeaters(); - } - - void ChironTFT::PrinterKilled(PGM_P error,PGM_P component) { - SendtoTFTLN(AC_msg_kill_lcd); - #if ACDEBUG(AC_MARLIN) - SERIAL_ECHOLNPAIR("PrinterKilled()\nerror: ", error , "\ncomponent: ", component); - #endif - } - - void ChironTFT::MediaEvent(media_event_t event) { - #if ACDEBUG(AC_MARLIN) - SERIAL_ECHOLNPAIR("ProcessMediaStatus() ", event); - #endif - switch (event) { - case AC_media_inserted: - SendtoTFTLN(AC_msg_sd_card_inserted); - break; - - case AC_media_removed: - SendtoTFTLN(AC_msg_sd_card_removed); - break; - - case AC_media_error: - SendtoTFTLN(AC_msg_no_sd_card); - break; - } - } - - void ChironTFT::TimerEvent(timer_event_t event) { - #if ACDEBUG(AC_MARLIN) - SERIAL_ECHOLNPAIR("TimerEvent() ", event); - SERIAL_ECHOLNPAIR("Printer State: ", printer_state); - #endif - - switch (event) { - case AC_timer_started: { - live_Zoffset = 0.0; // reset print offset - setSoftEndstopState(false); // disable endstops to print - printer_state = AC_printer_printing; - SendtoTFTLN(AC_msg_print_from_sd_card); - } break; - - case AC_timer_paused: { - printer_state = AC_printer_paused; - pause_state = AC_paused_idle; - SendtoTFTLN(AC_msg_paused); - } break; - - case AC_timer_stopped: { - if (printer_state != AC_printer_idle) { - printer_state = AC_printer_stopping; - SendtoTFTLN(AC_msg_print_complete); - } - setSoftEndstopState(true); // enable endstops - } break; - } - } - - void ChironTFT::FilamentRunout() { - #if ACDEBUG(AC_MARLIN) - SERIAL_ECHOLNPAIR("FilamentRunout() printer_state ", printer_state); - #endif - // 1 Signal filament out - SendtoTFTLN(isPrintingFromMedia() ? AC_msg_filament_out_alert : AC_msg_filament_out_block); - //printer_state = AC_printer_filament_out; - PlayTune(BEEPER_PIN, FilamentOut, 1); - } - - void ChironTFT::ConfirmationRequest(const char * const msg) { - // M108 continue - #if ACDEBUG(AC_MARLIN) - SERIAL_ECHOLNPAIR("ConfirmationRequest() ", msg, " printer_state:", printer_state); - #endif - switch (printer_state) { - case AC_printer_pausing: { - if ( (strcmp_P(msg, MARLIN_msg_print_paused) == 0 ) || (strcmp_P(msg, MARLIN_msg_nozzle_parked) == 0 ) ) { - SendtoTFTLN(AC_msg_paused); // enable continue button - printer_state = AC_printer_paused; - } - } break; - - case AC_printer_resuming_from_power_outage: - case AC_printer_printing: - case AC_printer_paused: { - // Heater timout, send acknowledgement - if (strcmp_P(msg, MARLIN_msg_heater_timeout) == 0 ) { - pause_state = AC_paused_heater_timed_out; - SendtoTFTLN(AC_msg_paused); // enable continue button - PlayTune(BEEPER_PIN,Heater_Timedout,1); - } - // Reheat finished, send acknowledgement - else if (strcmp_P(msg, MARLIN_msg_reheat_done) == 0 ) { - pause_state = AC_paused_idle; - SendtoTFTLN(AC_msg_paused); // enable continue button - } - // Filament Purging, send acknowledgement enter run mode - else if (strcmp_P(msg, MARLIN_msg_filament_purging) == 0 ) { - pause_state = AC_paused_purging_filament; - SendtoTFTLN(AC_msg_paused); // enable continue button - } - } break; - default: - break; - } - } - - void ChironTFT::StatusChange(const char * const msg) { - #if ACDEBUG(AC_MARLIN) - SERIAL_ECHOLNPAIR("StatusChange() ", msg); - SERIAL_ECHOLNPAIR("printer_state:", printer_state); - #endif - bool msg_matched = false; - // The only way to get printer status is to parse messages - // Use the state to minimise the work we do here. - switch (printer_state) { - case AC_printer_probing: { - // If probing completes ok save the mesh and park - if (strcmp_P(msg, MARLIN_msg_ready) == 0 ) { - injectCommands_P(PSTR("M500\nG27")); - SendtoTFTLN(AC_msg_probing_complete); - printer_state = AC_printer_idle; - msg_matched = true; - } - // If probing fails dont save the mesh raise the probe above the bad point - if (strcmp_P(msg, MARLIN_msg_probing_failed) == 0 ) { - PlayTune(BEEPER_PIN, BeepBeepBeeep, 1); - injectCommands_P(PSTR("G1 Z50 F500")); - SendtoTFTLN(AC_msg_probing_complete); - printer_state = AC_printer_idle; - msg_matched = true; - } - } break; - - case AC_printer_printing: { - if (strcmp_P(msg, MARLIN_msg_reheating) == 0 ) { - SendtoTFTLN(AC_msg_paused); // enable continue button - msg_matched = true; - } - } break; - - case AC_printer_pausing: { - if (strcmp_P(msg, MARLIN_msg_print_paused) == 0 ) { - SendtoTFTLN(AC_msg_paused); - printer_state = AC_printer_paused; - pause_state = AC_paused_idle; - msg_matched = true; - } - } break; - - case AC_printer_stopping: { - if (strcmp_P(msg, MARLIN_msg_print_aborted) == 0 ) { - SendtoTFTLN(AC_msg_stop); - printer_state = AC_printer_idle; - msg_matched = true; - } - } break; - default: - break; - } - - // If not matched earlier see if this was a heater message - if (!msg_matched) { - if (strcmp_P(msg, MARLIN_msg_extruder_heating) == 0) { - SendtoTFTLN(AC_msg_nozzle_heating); - hotend_state = AC_heater_temp_set; - } - else if (strcmp_P(msg, MARLIN_msg_bed_heating) == 0) { - SendtoTFTLN(AC_msg_bed_heating); - hotbed_state = AC_heater_temp_set; - } - } - } - - void ChironTFT::PowerLossRecovery() { - printer_state = AC_printer_resuming_from_power_outage; // Play tune to notify user we can recover. - PlayTune(BEEPER_PIN, SOS, 1); - SERIAL_ECHOLNPGM("Resuming from power outage..."); - SERIAL_ECHOLNPGM("Select SD file then press resume"); - } - - void ChironTFT::SendtoTFT(PGM_P str) { // A helper to print PROGMEN string to the panel - #if ACDEBUG(AC_SOME) - serialprintPGM(str); - #endif - while (const char c = pgm_read_byte(str++)) TFTSer.print(c); - } - - void ChironTFT::SendtoTFTLN(PGM_P str = nullptr) { - if (str != nullptr) { - #if ACDEBUG(AC_SOME) - SERIAL_ECHO("> "); - #endif - SendtoTFT(str); - #if ACDEBUG(AC_SOME) - SERIAL_EOL(); - #endif - } - TFTSer.println(""); - } - - bool ChironTFT::ReadTFTCommand() { - bool command_ready = false; - while( (TFTSer.available() > 0) && (command_len < MAX_CMND_LEN) ) { - panel_command[command_len] = TFTSer.read(); - if(panel_command[command_len] == '\n') { - command_ready = true; - break; - } - command_len++; - } - - if(command_ready) { - panel_command[command_len] = 0x00; - #if ACDEBUG(AC_ALL) - SERIAL_ECHOLNPAIR("< ", panel_command); - #endif - #if ACDEBUG(AC_SOME) - // Ignore status request commands - uint8_t req = atoi(&panel_command[1]); - if (req > 7 && req != 20) { - SERIAL_ECHOLNPAIR("> ", panel_command); - SERIAL_ECHOLNPAIR("printer_state:", printer_state); - } - #endif - } - return command_ready; - } - - int8_t ChironTFT::Findcmndpos(const char * buff, char q) { - bool found = false; - int8_t pos = 0; - do { - if (buff[pos] == q) { - found = true; - break; - } - pos ++; - } while(pos < MAX_CMND_LEN); - if (found) return pos; - return -1; - } - - void ChironTFT::CheckHeaters() { - uint8_t faultDuration = 0; float temp = 0; - - // if the hotend temp is abnormal, confirm state before signalling panel - temp = getActualTemp_celsius(E0); - if ( (temp <= HEATER_0_MINTEMP) || (temp >= HEATER_0_MAXTEMP) ) { - do { - faultDuration ++; - if (faultDuration >= AC_HEATER_FAULT_VALIDATION_TIME) { - SendtoTFTLN(AC_msg_nozzle_temp_abnormal); - SERIAL_ECHOLNPAIR("Extruder temp abnormal! : ", temp); - break; - } - delay_ms(500); - temp = getActualTemp_celsius(E0); - } while ((temp <= HEATER_0_MINTEMP) || (temp >= HEATER_0_MAXTEMP) ); - } - - // if the hotbed temp is abnormal, confirm state before signalling panel - faultDuration = 0; - temp = getActualTemp_celsius(BED); - if ( (temp <= BED_MINTEMP) || (temp >= BED_MAXTEMP) ) { - do { - faultDuration ++; - if (faultDuration >= AC_HEATER_FAULT_VALIDATION_TIME) { - SendtoTFTLN(AC_msg_nozzle_temp_abnormal); - SERIAL_ECHOLNPAIR_P("Bed temp abnormal! : ", temp); - break; - } - delay_ms(500); - temp = getActualTemp_celsius(E0); - } while ((temp <= BED_MINTEMP) || (temp >= BED_MAXTEMP) ); - } - - // Update panel with hotend heater status - if (hotend_state != AC_heater_temp_reached) { - if ( WITHIN( getActualTemp_celsius(E0) - getTargetTemp_celsius(E0), -1, 1 ) ) { - SendtoTFTLN(AC_msg_nozzle_heating_done); - hotend_state = AC_heater_temp_reached; - } - } - - // Update panel with bed heater status - if (hotbed_state != AC_heater_temp_reached) { - if ( WITHIN( getActualTemp_celsius(BED) - getTargetTemp_celsius(BED), -0.5, 0.5 ) ) { - SendtoTFTLN(AC_msg_bed_heating_done); - hotbed_state = AC_heater_temp_reached; - } - } - } - - void ChironTFT::SendFileList(int8_t startindex) { - // respond to panel request for 4 files starting at index - #if ACDEBUG(AC_INFO) - SERIAL_ECHOLNPAIR("## SendFileList ## ", startindex); - #endif - SendtoTFTLN(PSTR("FN ")); - filenavigator.getFiles(startindex); - SendtoTFTLN(PSTR("END")); - } - - void ChironTFT::SelectFile() { - strncpy(selectedfile,panel_command+4,command_len-4); - selectedfile[command_len-5] = '\0'; - #if ACDEBUG(AC_FILE) - SERIAL_ECHOLNPAIR_F(" Selected File: ",selectedfile); - #endif - switch (selectedfile[0]) { - case '/': // Valid file selected - SendtoTFTLN(AC_msg_sd_file_open_success); - break; - - case '<': // .. (go up folder level) - filenavigator.upDIR(); - SendtoTFTLN(AC_msg_sd_file_open_failed); - SendFileList( 0 ); - break; - default: // enter sub folder - filenavigator.changeDIR(selectedfile); - SendtoTFTLN(AC_msg_sd_file_open_failed); - SendFileList( 0 ); - break; - } - } - - void ChironTFT::InjectCommandandWait(PGM_P cmd) { - //injectCommands_P(cmnd); queue.enqueue_now_P(cmd); - //SERIAL_ECHOLN(PSTR("Inject>")); - } - - void ChironTFT::ProcessPanelRequest() { - // Break these up into logical blocks // as its easier to navigate than one huge switch case! - int8_t req = atoi(&panel_command[1]); - - // Information requests A0 - A8 and A33 - if (req <= 8 || req == 33) PanelInfo(req); - - // Simple Actions A9 - A28 - else if ( req <= 28) PanelAction(req); - - // Process Initiation - else if (req <= 34) PanelProcess(req); - - else SendtoTFTLN(); - } - - void ChironTFT::PanelInfo(uint8_t req) { - // information requests A0-A8 and A33 - switch (req) { - case 0: // A0 Get HOTEND Temp - SendtoTFT(PSTR("A0V ")); - TFTSer.println(getActualTemp_celsius(E0)); - break; - - case 1: // A1 Get HOTEND Target Temp - SendtoTFT(PSTR("A1V ")); - TFTSer.println(getTargetTemp_celsius(E0)); - break; - - case 2: // A2 Get BED Temp - SendtoTFT(PSTR("A2V ")); - TFTSer.println(getActualTemp_celsius(BED)); - break; - - case 3: // A3 Get BED Target Temp - SendtoTFT(PSTR("A3V ")); - TFTSer.println(getTargetTemp_celsius(BED)); - break; - - case 4: // A4 Get FAN Speed - SendtoTFT(PSTR("A4V ")); - TFTSer.println(getActualFan_percent(FAN0)); - break; - - case 5: // A5 Get Current Coordinates - SendtoTFT(PSTR("A5V X: ")); - TFTSer.print(getAxisPosition_mm(X)); - SendtoTFT(PSTR(" Y: ")); - TFTSer.print(getAxisPosition_mm(Y)); - SendtoTFT(PSTR(" Z: ")); - TFTSer.println(getAxisPosition_mm(Z)); - break; - - case 6: // A6 Get printing progress - if (isPrintingFromMedia()) { - SendtoTFT(PSTR("A6V ")); - TFTSer.println(ui8tostr2(getProgress_percent())); - - } - else - SendtoTFTLN(PSTR("A6V ---")); - break; - - case 7: { // A7 Get Printing Time - uint32_t time = getProgress_seconds_elapsed() / 60; - SendtoTFT(PSTR("A7V ")); - TFTSer.print(ui8tostr2(time / 60)); - SendtoTFT(PSTR(" H ")); - TFTSer.print(ui8tostr2(time % 60)); - SendtoTFT(PSTR(" M")); - #if ACDEBUG(AC_ALL) - SERIAL_ECHOLNPAIR("Print time ", ui8tostr2(time / 60), ":", ui8tostr2(time % 60)); - #endif - } break; - - case 8: // A8 Get SD Card list A8 S0 - if (!isMediaInserted()) safe_delay(500); - if (!isMediaInserted()) // Make sure the card is removed - SendtoTFTLN(AC_msg_no_sd_card); - else if (panel_command[3] == 'S') - SendFileList( atoi( &panel_command[4] ) ); - break; - - case 33: // A33 Get firmware info - SendtoTFT(PSTR("J33 ")); - SendtoTFTLN(PSTR(SHORT_BUILD_VERSION)); - break; - } - } - - void ChironTFT::PanelAction(uint8_t req) { - switch (req) { - case 9: // A9 Pause SD print - if (isPrintingFromMedia()) { - SendtoTFTLN(AC_msg_pause); - pausePrint(); - printer_state = AC_printer_pausing; - } - else - SendtoTFTLN(AC_msg_stop); - break; - - case 10: // A10 Resume SD Print - if (pause_state == AC_paused_idle || printer_state == AC_printer_resuming_from_power_outage) - resumePrint(); - else - setUserConfirmed(); - break; - - case 11: // A11 Stop SD print - if (isPrintingFromMedia()) { - printer_state = AC_printer_stopping; - stopPrint(); - } - else { - if (printer_state == AC_printer_resuming_from_power_outage) - injectCommands_P(PSTR("M1000 C\n")); // Cancel recovery - SendtoTFTLN(AC_msg_stop); - printer_state = AC_printer_idle; - } - break; - - case 12: // A12 Kill printer - kill(); // from marlincore.h - break; - - case 13: // A13 Select file - SelectFile(); - break; - - case 14: { // A14 Start Printing - // Allows printer to restart the job if we dont want to recover - if (printer_state == AC_printer_resuming_from_power_outage) { - injectCommands_P(PSTR("M1000 C\n")); // Cancel recovery - printer_state = AC_printer_idle; - } - #if ACDebugLevel >= 1 - SERIAL_ECHOLNPAIR_F("Print: ", selectedfile); - #endif - // the card library needs a path starting // but the File api doesn't... - char file[MAX_PATH_LEN]; - file[0] = '/'; - strcpy(file + 1, selectedfile); - printFile(file); - SendtoTFTLN(AC_msg_print_from_sd_card); - } break; - - case 15: // A15 Resuming from outage - if (printer_state == AC_printer_resuming_from_power_outage) - // Need to home here to restore the Z position - injectCommands_P(AC_cmnd_power_loss_recovery); - - injectCommands_P(PSTR("M1000\n")); // home and start recovery - break; - - case 16: { // A16 Set HotEnd temp A17 S170 - const float set_Htemp = atof(&panel_command[5]); - hotend_state = set_Htemp ? AC_heater_temp_set : AC_heater_off; - switch ((char)panel_command[4]) { - // Set Temp - case 'S': case 'C': setTargetTemp_celsius(set_Htemp, E0); - } - } break; - - case 17: { // A17 Set bed temp - const float set_Btemp = atof(&panel_command[5]); - hotbed_state = set_Btemp ? AC_heater_temp_set : AC_heater_off; - if (panel_command[4] == 'S') - setTargetTemp_celsius(set_Btemp, BED); - } break; - - case 18: // A18 Set Fan Speed - if (panel_command[4] == 'S') - setTargetFan_percent(atof(&panel_command[5]), FAN0); - break; - - case 19: // A19 Motors off - if (!isPrinting()) { - disable_all_steppers(); // from marlincore.h - SendtoTFTLN(AC_msg_ready); - } - break; - - case 20: // A20 Read/write print speed - if (panel_command[4] == 'S') - setFeedrate_percent(atoi(&panel_command[5])); - else { - SendtoTFT(PSTR("A20V ")); - TFTSer.println(getFeedrate_percent()); - } - break; - - case 21: // A21 Home Axis A21 X - if (!isPrinting()) { - switch ((char)panel_command[4]) { - case 'X': injectCommands_P(PSTR("G28 X\n")); break; - case 'Y': injectCommands_P(PSTR("G28 Y\n")); break; - case 'Z': injectCommands_P(PSTR("G28 Z\n")); break; - case 'C': injectCommands_P(PSTR("G28\n")); break; - } - } - break; - - case 22: // A22 Move Axis A22 Y +10F3000 - // Ignore request if printing - if (!isPrinting()) { - // setAxisPosition_mm() uses pre defined manual feedrates so ignore the feedrate from the panel - setSoftEndstopState(true); // enable endstops - float newposition = atof(&panel_command[6]); - - #if ACDEBUG(AC_ACTION) - SERIAL_ECHOLNPAIR("Nudge ", panel_command[4], " axis ", newposition); - #endif - - switch (panel_command[4]) { - case 'X': setAxisPosition_mm(getAxisPosition_mm(X) + newposition, X); break; - case 'Y': setAxisPosition_mm(getAxisPosition_mm(Y) + newposition, Y); break; - case 'Z': setAxisPosition_mm(getAxisPosition_mm(Z) + newposition, Z); break; - case 'E': // The only time we get this command is from the filament load/unload menu - // the standard movement is too slow so we will use the load unlod GCode to speed it up a bit - if (canMove(E0) && !commandsInQueue()) - injectCommands_P(newposition > 0 ? AC_cmnd_manual_load_filament : AC_cmnd_manual_unload_filament); - break; - } - } - break; - - case 23: // A23 Preheat PLA - // Ignore request if printing - if (!isPrinting()) { - // Temps defined in configuration.h - setTargetTemp_celsius(PREHEAT_1_TEMP_BED, BED); - setTargetTemp_celsius(PREHEAT_1_TEMP_HOTEND, E0); - SendtoTFTLN(); - hotbed_state = AC_heater_temp_set; - hotend_state = AC_heater_temp_set; - } - break; - - case 24: // A24 Preheat ABS - // Ignore request if printing - if (!isPrinting()) { - setTargetTemp_celsius(PREHEAT_2_TEMP_BED, BED); - setTargetTemp_celsius(PREHEAT_2_TEMP_HOTEND, E0); - SendtoTFTLN(); - hotbed_state = AC_heater_temp_set; - hotend_state = AC_heater_temp_set; - } - break; - - case 25: // A25 Cool Down - // Ignore request if printing - if (!isPrinting()) { - setTargetTemp_celsius(0, E0); - setTargetTemp_celsius(0, BED); - SendtoTFTLN(AC_msg_ready); - hotbed_state = AC_heater_off; - hotend_state = AC_heater_off; - } - break; - - case 26: // A26 Refresh SD - // M22 M21 maybe needed here to reset sd card - filenavigator.reset(); - break; - - case 27: // A27 Servo Angles adjust - break; - - case 28: // A28 Filament set A28 O/C - // Ignore request if printing - if (isPrinting()) break; - SendtoTFTLN(); - break; - } - } - - void ChironTFT::PanelProcess(uint8_t req) { - switch (req) { - case 29: { // A29 Read Mesh Point A29 X1 Y1 - xy_uint8_t pos; - float pos_z; - pos.x = atoi(&panel_command[5]); - pos.y = atoi(&panel_command[8]); - pos_z = getMeshPoint(pos); - - SendtoTFT(PSTR("A29V ")); - TFTSer.println(pos_z * 100); - if (!isPrinting()) { - setSoftEndstopState(true); // disable endstops - // If the same meshpoint is selected twice in a row, move the head to that ready for adjustment - if ((selectedmeshpoint.x == pos.x) && (selectedmeshpoint.y == pos.y)) { - if (!isPositionKnown()) - injectCommands_P(PSTR("G28\n")); // home - - if (isPositionKnown()) { - #if ACDEBUG(AC_INFO) - SERIAL_ECHOLNPAIR("Moving to mesh point at x: ", pos.x, " y: ", pos.y, " z: ", pos_z); - #endif - // Go up before moving - setAxisPosition_mm(3.0,Z); - - setAxisPosition_mm(17 + (93 * pos.x), X); - setAxisPosition_mm(20 + (93 * pos.y), Y); - setAxisPosition_mm(0.0, Z); - #if ACDEBUG(AC_INFO) - SERIAL_ECHOLNPAIR("Current Z: ", getAxisPosition_mm(Z)); - #endif - } - } - selectedmeshpoint.x = pos.x; - selectedmeshpoint.y = pos.y; - } - } break; - - case 30: { // A30 Auto leveling - if (panel_command[3] == 'S') { // Start probing - // Ignore request if printing - if (isPrinting()) - SendtoTFTLN(AC_msg_probing_not_allowed); // forbid auto leveling - else { - injectCommands_P(isMachineHomed() ? PSTR("G29") : PSTR("G28\nG29")); - printer_state = AC_printer_probing; - SendtoTFTLN(AC_msg_start_probing); - } - } - else SendtoTFTLN(AC_msg_start_probing); - } break; - - case 31: { // A31 Adjust all Probe Points - switch (panel_command[3]) { - case 'C': // Restore and apply original offsets - if (!isPrinting()) { - injectCommands_P(PSTR("M501\nM420 S1\n")); - selectedmeshpoint.x = 99; - selectedmeshpoint.y = 99; - } - break; - case 'D': // Save Z Offset tables and restore levelling state - if (!isPrinting()) { - setAxisPosition_mm(1.0,Z); - injectCommands_P(PSTR("M500\n")); - selectedmeshpoint.x = 99; - selectedmeshpoint.y = 99; - } - break; - case 'G': // Get current offset - SendtoTFT(PSTR("A31V ")); - // When printing use the live z Offset position - // we will use babystepping to move the print head - if (isPrinting()) - TFTSer.println(live_Zoffset); - else { - TFTSer.println(getZOffset_mm()); - selectedmeshpoint.x = 99; - selectedmeshpoint.y = 99; - } - break; - case 'S': { // Set offset (adjusts all points by value) - float Zshift = atof(&panel_command[4]); - setSoftEndstopState(false); // disable endstops - // Allow temporary Z position nudging during print - // From the levelling panel use the all points UI to adjust the print pos. - if (isPrinting()) { - #if ACDEBUG(AC_INFO) - SERIAL_ECHOLNPAIR("Change Zoffset from:", live_Zoffset, " to ", live_Zoffset + Zshift); - #endif - if (isAxisPositionKnown(Z)) { - #if ACDEBUG(AC_INFO) - const float currZpos = getAxisPosition_mm(Z); - SERIAL_ECHOLNPAIR("Nudge Z pos from ", currZpos, " to ", currZpos + constrain(Zshift, -0.05, 0.05)); - #endif - // Use babystepping to adjust the head position - int16_t steps = mmToWholeSteps(constrain(Zshift,-0.05,0.05), Z); - #if ACDEBUG(AC_INFO) - SERIAL_ECHOLNPAIR("Steps to move Z: ", steps); - #endif - babystepAxis_steps(steps, Z); - live_Zoffset += Zshift; - } - SendtoTFT(PSTR("A31V ")); - TFTSer.println(live_Zoffset); - } - else { - GRID_LOOP(x, y) { - const xy_uint8_t pos { x, y }; - const float currval = getMeshPoint(pos); - setMeshPoint(pos, constrain(currval + Zshift, AC_LOWEST_MESHPOINT_VAL, 2)); - } - const float currZOffset = getZOffset_mm(); - #if ACDEBUG(AC_INFO) - SERIAL_ECHOLNPAIR("Change probe offset from ", currZOffset, " to ", currZOffset + Zshift); - #endif - - setZOffset_mm(currZOffset + Zshift); - SendtoTFT(PSTR("A31V ")); - TFTSer.println(getZOffset_mm()); - - if (isAxisPositionKnown(Z)) { - // Move Z axis - const float currZpos = getAxisPosition_mm(Z); - #if ACDEBUG(AC_INFO) - SERIAL_ECHOLNPAIR("Move Z pos from ", currZpos, " to ", currZpos + constrain(Zshift, -0.05, 0.05)); - #endif - setAxisPosition_mm(currZpos+constrain(Zshift,-0.05,0.05),Z); - } - } - } break; - } // end switch - } break; - - case 32: { // A32 clean leveling beep flag - // Ignore request if printing - //if (isPrinting()) break; - //injectCommands_P(PSTR("M500\nM420 S1\nG1 Z10 F240\nG1 X0 Y0 F6000")); - //TFTSer.println(""); - } break; - - // A33 firmware info request seet PanelInfo() - - case 34: { // A34 Adjust single mesh point A34 C/S X1 Y1 V123 - if (panel_command[3] == 'C') { // Restore original offsets - injectCommands_P(PSTR("M501\nM420 S1")); - selectedmeshpoint.x = 99; - selectedmeshpoint.y = 99; - //printer_state = AC_printer_idle; - } - else { - xy_uint8_t pos; - pos.x = atoi(&panel_command[5]); - pos.y = atoi(&panel_command[8]); - - float currmesh = getMeshPoint(pos); - float newval = atof(&panel_command[11])/100; - #if ACDEBUG(AC_INFO) - SERIAL_ECHOLNPAIR("Change mesh point x:", pos.x, " y:", pos.y); - SERIAL_ECHOLNPAIR("from ", currmesh, " to ", newval); - #endif - // Update Meshpoint - setMeshPoint(pos,newval); - if ( (printer_state == AC_printer_idle) || (printer_state == AC_printer_probing) ) {//!isPrinting()) { - // if we are at the current mesh point indicated on the panel Move Z pos +/- 0.05mm ( The panel changes the mesh value by +/- 0.05mm on each button press) - if ((selectedmeshpoint.x == pos.x) && (selectedmeshpoint.y == pos.y)) { - setSoftEndstopState(false); - float currZpos = getAxisPosition_mm(Z); - #if ACDEBUG(AC_INFO) - SERIAL_ECHOLNPAIR("Move Z pos from ", currZpos, " to ", currZpos + constrain(newval - currmesh, -0.05, 0.05)); - #endif - setAxisPosition_mm(currZpos + constrain(newval - currmesh, -0.05, 0.05), Z); - } - } - } - } break; - } - } -} // namespace - -#endif // ANYCUBIC_LCD_CHIRON diff --git a/Marlin/src/lcd/extui/lib/anycubic_chiron/chiron_tft.h b/Marlin/src/lcd/extui/lib/anycubic_chiron/chiron_tft.h deleted file mode 100644 index 267f2fe9783f..000000000000 --- a/Marlin/src/lcd/extui/lib/anycubic_chiron/chiron_tft.h +++ /dev/null @@ -1,77 +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 - -/** - * lcd/extui/lib/chiron_tft.h - * - * Extensible_UI implementation for Anycubic Chiron - * Written By Nick Wells, 2020 [https://github.com/SwiftNick] - * (not affiliated with Anycubic, Ltd.) - */ - -#include "chiron_tft_defs.h" -#include "../../../../inc/MarlinConfigPre.h" -#include "../../ui_api.h" -namespace Anycubic { - - class ChironTFT { - static printer_state_t printer_state; - static paused_state_t pause_state; - static heater_state_t hotend_state; - static heater_state_t hotbed_state; - static xy_uint8_t selectedmeshpoint; - static char panel_command[MAX_CMND_LEN]; - static uint8_t command_len; - static char selectedfile[MAX_PATH_LEN]; - static float live_Zoffset; - static file_menu_t file_menu; - public: - ChironTFT(); - void Startup(); - void IdleLoop(); - void PrinterKilled(PGM_P,PGM_P); - void MediaEvent(media_event_t); - void TimerEvent(timer_event_t); - void FilamentRunout(); - void ConfirmationRequest(const char * const ); - void StatusChange(const char * const ); - void PowerLossRecovery(); - - private: - void SendtoTFT(PGM_P); - void SendtoTFTLN(PGM_P); - bool ReadTFTCommand(); - int8_t Findcmndpos(const char *, char); - void CheckHeaters(); - void SendFileList(int8_t); - void SelectFile(); - void InjectCommandandWait(PGM_P); - void ProcessPanelRequest(); - void PanelInfo(uint8_t); - void PanelAction(uint8_t); - void PanelProcess(uint8_t); - }; - - extern ChironTFT Chiron; - -} diff --git a/Marlin/src/lcd/extui/lib/anycubic_chiron/chiron_tft_defs.h b/Marlin/src/lcd/extui/lib/anycubic_chiron/chiron_tft_defs.h deleted file mode 100644 index 937bdfde33b3..000000000000 --- a/Marlin/src/lcd/extui/lib/anycubic_chiron/chiron_tft_defs.h +++ /dev/null @@ -1,151 +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 . - * - */ - -/** - * lcd/extui/lib/chiron_defs.h - * - * Extensible_UI implementation for Anycubic Chiron - * Written By Nick Wells, 2020 [https://github.com/SwiftNick] - * (not affiliated with Anycubic, Ltd.) - */ - -#pragma once -#include "../../../../inc/MarlinConfigPre.h" -//#define ACDEBUGLEVEL 255 - -#if ACDEBUGLEVEL - // Bit-masks for selective debug: - enum ACDebugMask : uint8_t { - AC_INFO = 1, - AC_ACTION = 2, - AC_FILE = 4, - AC_PANEL = 8, - AC_MARLIN = 16, - AC_SOME = 32, - AC_ALL = 64 - }; - #define ACDEBUG(mask) ( ((mask) & ACDEBUGLEVEL) == mask ) // Debug flag macro -#else - #define ACDEBUG(mask) false -#endif - -#define TFTSer LCD_SERIAL // Serial interface for TFT panel now uses marlinserial -#define MAX_FOLDER_DEPTH 4 // Limit folder depth TFT has a limit for the file path -#define MAX_CMND_LEN 16 * MAX_FOLDER_DEPTH // Maximum Length for a Panel command -#define MAX_PATH_LEN 16 * MAX_FOLDER_DEPTH // Maximum number of characters in a SD file path - -#define AC_HEATER_FAULT_VALIDATION_TIME 5 // number of 1/2 second loops before signalling a heater fault -#define AC_LOWEST_MESHPOINT_VAL -7.00 // The lowest value you can set for a single mesh point offset - - // TFT panel commands -#define AC_msg_sd_card_inserted PSTR("J00") -#define AC_msg_sd_card_removed PSTR("J01") -#define AC_msg_no_sd_card PSTR("J02") -#define AC_msg_usb_connected PSTR("J03") -#define AC_msg_print_from_sd_card PSTR("J04") -#define AC_msg_pause PSTR("J05") -#define AC_msg_nozzle_heating PSTR("J06") -#define AC_msg_nozzle_heating_done PSTR("J07") -#define AC_msg_bed_heating PSTR("J08") -#define AC_msg_bed_heating_done PSTR("J09") -#define AC_msg_nozzle_temp_abnormal PSTR("J10") -#define AC_msg_kill_lcd PSTR("J11") -#define AC_msg_ready PSTR("J12") -#define AC_msg_low_nozzle_temp PSTR("J13") -#define AC_msg_print_complete PSTR("J14") -#define AC_msg_filament_out_alert PSTR("J15") -#define AC_msg_stop PSTR("J16") -#define AC_msg_main_board_has_reset PSTR("J17") -#define AC_msg_paused PSTR("J18") -#define AC_msg_j19_unknown PSTR("J19") -#define AC_msg_sd_file_open_success PSTR("J20") -#define AC_msg_sd_file_open_failed PSTR("J21") -#define AC_msg_level_monitor_finished PSTR("J22") -#define AC_msg_filament_out_block PSTR("J23") -#define AC_msg_probing_not_allowed PSTR("J24") -#define AC_msg_probing_complete PSTR("J25") -#define AC_msg_start_probing PSTR("J26") -#define AC_msg_version PSTR("J27") - -#define MARLIN_msg_start_probing PSTR("Probing Point 1/25") -#define MARLIN_msg_probing_failed PSTR("Probing Failed") -#define MARLIN_msg_ready PSTR("3D Printer Ready.") -#define MARLIN_msg_print_paused PSTR("Print Paused") -#define MARLIN_msg_print_aborted PSTR("Print Aborted") -#define MARLIN_msg_extruder_heating PSTR("E Heating...") -#define MARLIN_msg_bed_heating PSTR("Bed Heating...") - -#define MARLIN_msg_nozzle_parked PSTR("Nozzle Parked") -#define MARLIN_msg_heater_timeout PSTR("Heater Timeout") -#define MARLIN_msg_reheating PSTR("Reheating...") -#define MARLIN_msg_reheat_done PSTR("Reheat finished.") -#define MARLIN_msg_filament_purging PSTR("Filament Purging...") -#define MARLIN_msg_special_pause PSTR("PB") -#define AC_cmnd_auto_unload_filament PSTR("M701") // Use Marlin unload routine -#define AC_cmnd_auto_load_filament PSTR("M702 M0 PB") // Use Marlin load routing then pause for user to clean nozzle - -#define AC_cmnd_manual_load_filament PSTR("M83\nG1 E50 F700\nM82") // replace the manual panel commands with something a little faster -#define AC_cmnd_manual_unload_filament PSTR("M83\nG1 E-50 F1200\nM82") -#define AC_cmnd_enable_levelling PSTR("M420 S1 V1") -#define AC_cmnd_power_loss_recovery PSTR("G28 X Y R5\nG28 Z") // Lift, home X and Y then home Z when in 'safe' position - -namespace Anycubic { - enum heater_state_t : uint8_t { - AC_heater_off, - AC_heater_temp_set, - AC_heater_temp_reached - }; - - enum paused_state_t : uint8_t { - AC_paused_heater_timed_out, - AC_paused_purging_filament, - AC_paused_idle - }; - - enum printer_state_t : uint8_t { - AC_printer_idle, - AC_printer_probing, - AC_printer_printing, - AC_printer_pausing, - AC_printer_paused, - AC_printer_stopping, - AC_printer_resuming_from_power_outage - }; - - enum timer_event_t : uint8_t { - AC_timer_started, - AC_timer_paused, - AC_timer_stopped - }; - - enum media_event_t : uint8_t { - AC_media_inserted, - AC_media_removed, - AC_media_error - }; - enum file_menu_t : uint8_t { - AC_menu_file, - AC_menu_command, - AC_menu_change_to_file, - AC_menu_change_to_command - }; -} diff --git a/Marlin/src/lcd/extui/lib/anycubic_i3mega/anycubic_i3mega_lcd.cpp b/Marlin/src/lcd/extui/lib/anycubic_i3mega/anycubic_i3mega_lcd.cpp deleted file mode 100644 index efbc57e68a80..000000000000 --- a/Marlin/src/lcd/extui/lib/anycubic_i3mega/anycubic_i3mega_lcd.cpp +++ /dev/null @@ -1,1032 +0,0 @@ -/** - * anycubic_i3mega_lcd.cpp --- Support for Anycubic i3 Mega TFT - * Created by Christian Hopp on 09.12.17. - * Improved by David Ramiro - * Converted to ext_iu by John BouAntoun 21 June 2020 - * - * 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 "../../../../inc/MarlinConfigPre.h" - -#if ENABLED(ANYCUBIC_LCD_I3MEGA) - -#include "anycubic_i3mega_lcd.h" -#include "../../ui_api.h" - -#include "../../../../libs/numtostr.h" -#include "../../../../module/motion.h" // for A20 read printing speed feedrate_percentage -#include "../../../../MarlinCore.h" // for quickstop_stepper and disable_steppers -#include "../../../../inc/MarlinConfig.h" - -// command sending macro's with debugging capability -#define SEND_PGM(x) send_P(PSTR(x)) -#define SENDLINE_PGM(x) sendLine_P(PSTR(x)) -#define SEND_PGM_VAL(x,y) (send_P(PSTR(x)), sendLine(i16tostr3rj(y))) -#define SEND(x) send(x) -#define SENDLINE(x) sendLine(x) -#if ENABLED(ANYCUBIC_LCD_DEBUG) - #define SENDLINE_DBG_PGM(x,y) (sendLine_P(PSTR(x)), SERIAL_ECHOLNPGM(y)) - #define SENDLINE_DBG_PGM_VAL(x,y,z) (sendLine_P(PSTR(x)), SERIAL_ECHOPGM(y), SERIAL_ECHOLN(z)) -#else - #define SENDLINE_DBG_PGM(x,y) sendLine_P(PSTR(x)) - #define SENDLINE_DBG_PGM_VAL(x,y,z) sendLine_P(PSTR(x)) -#endif - -AnycubicTFTClass AnycubicTFT; - -static void sendNewLine(void) { - LCD_SERIAL.write('\r'); - LCD_SERIAL.write('\n'); -} - -static void send(const char *str) { - LCD_SERIAL.print(str); -} - -static void sendLine(const char *str) { - send(str); - sendNewLine(); -} - -static void send_P(PGM_P str) { - while (const char c = pgm_read_byte(str++)) - LCD_SERIAL.write(c); -} - -static void sendLine_P(PGM_P str) { - send_P(str); - sendNewLine(); -} - -AnycubicTFTClass::AnycubicTFTClass() {} - -void AnycubicTFTClass::OnSetup() { - #ifndef LCD_BAUDRATE - #define LCD_BAUDRATE 115200 - #endif - LCD_SERIAL.begin(LCD_BAUDRATE); - - SENDLINE_DBG_PGM("J17", "TFT Serial Debug: Main board reset... J17"); // J17 Main board reset - ExtUI::delay_ms(10); - - // initialise the state of the key pins running on the tft - #if ENABLED(SDSUPPORT) && PIN_EXISTS(SD_DETECT) - SET_INPUT_PULLUP(SD_DETECT_PIN); - #endif - #if ENABLED(FILAMENT_RUNOUT_SENSOR) - SET_INPUT_PULLUP(FIL_RUNOUT_PIN); - #endif - - mediaPrintingState = AMPRINTSTATE_NOT_PRINTING; - mediaPauseState = AMPAUSESTATE_NOT_PAUSED; - - // DoSDCardStateCheck(); - SENDLINE_DBG_PGM("J12", "TFT Serial Debug: Ready... J12"); // J12 Ready - ExtUI::delay_ms(10); - - DoFilamentRunoutCheck(); - SelectedFile[0] = 0; - - #if ENABLED(STARTUP_CHIME) - ExtUI::injectCommands_P(PSTR("M300 P250 S554\nM300 P250 S554\nM300 P250 S740\nM300 P250 S554\nM300 P250 S740\nM300 P250 S554\nM300 P500 S831")); - #endif - #if ENABLED(ANYCUBIC_LCD_DEBUG) - SERIAL_ECHOLNPGM("TFT Serial Debug: Finished startup"); - #endif -} - -void AnycubicTFTClass::OnCommandScan() { - static millis_t nextStopCheck = 0; // used to slow the stopped print check down to reasonable times - const millis_t ms = millis(); - if (ELAPSED(ms, nextStopCheck)) { - nextStopCheck = ms + 1000UL; - if (mediaPrintingState == AMPRINTSTATE_STOP_REQUESTED && IsNozzleHomed()) { - #if ENABLED(ANYCUBIC_LCD_DEBUG) - SERIAL_ECHOLNPGM("TFT Serial Debug: Finished stopping print, releasing motors ..."); - #endif - mediaPrintingState = AMPRINTSTATE_NOT_PRINTING; - mediaPauseState = AMPAUSESTATE_NOT_PAUSED; - ExtUI::injectCommands_P(PSTR("M84\nM27")); // disable stepper motors and force report of SD status - ExtUI::delay_ms(200); - // tell printer to release resources of print to indicate it is done - SENDLINE_DBG_PGM("J14", "TFT Serial Debug: SD Print Stopped... J14"); - } - } - - if (TFTbuflen < (TFTBUFSIZE - 1)) - GetCommandFromTFT(); - - if (TFTbuflen) { - TFTbuflen = (TFTbuflen - 1); - TFTbufindr = (TFTbufindr + 1) % TFTBUFSIZE; - } -} - -void AnycubicTFTClass::OnKillTFT() { - SENDLINE_DBG_PGM("J11", "TFT Serial Debug: Kill command... J11"); -} - -void AnycubicTFTClass::OnSDCardStateChange(bool isInserted) { - #if ENABLED(ANYCUBIC_LCD_DEBUG) - SERIAL_ECHOPGM("TFT Serial Debug: OnSDCardStateChange event triggered..."); - SERIAL_ECHO(ui8tostr2(isInserted)); - SERIAL_EOL(); - #endif - DoSDCardStateCheck(); -} - -void AnycubicTFTClass::OnSDCardError() { - #if ENABLED(ANYCUBIC_LCD_DEBUG) - SERIAL_ECHOLNPGM("TFT Serial Debug: OnSDCardError event triggered..."); - #endif - SENDLINE_DBG_PGM("J21", "TFT Serial Debug: On SD Card Error ... J21"); -} - -void AnycubicTFTClass::OnFilamentRunout() { - #if ENABLED(ANYCUBIC_LCD_DEBUG) - SERIAL_ECHOLNPGM("TFT Serial Debug: FilamentRunout triggered..."); - #endif - DoFilamentRunoutCheck(); -} - -void AnycubicTFTClass::OnUserConfirmRequired(const char * const msg) { - #if ENABLED(ANYCUBIC_LCD_DEBUG) - SERIAL_ECHOPGM("TFT Serial Debug: OnUserConfirmRequired triggered... "); - SERIAL_ECHOLN(msg); - #endif - - #if ENABLED(SDSUPPORT) - /** - * Need to handle the process of following states - * "Nozzle Parked" - * "Load Filament" - * "Filament Purging..." - * "HeaterTimeout" - * "Reheat finished." - * - * NOTE: The only way to handle these states is strcmp_P with the msg unfortunately (very expensive) - */ - if (strcmp_P(msg, PSTR("Nozzle Parked")) == 0) { - mediaPrintingState = AMPRINTSTATE_PAUSED; - mediaPauseState = AMPAUSESTATE_PARKED; - // enable continue button - SENDLINE_DBG_PGM("J18", "TFT Serial Debug: UserConfirm SD print paused done... J18"); - } - else if (strcmp_P(msg, PSTR("Load Filament")) == 0) { - mediaPrintingState = AMPRINTSTATE_PAUSED; - mediaPauseState = AMPAUSESTATE_FILAMENT_OUT; - // enable continue button - SENDLINE_DBG_PGM("J18", "TFT Serial Debug: UserConfirm Filament is out... J18"); - SENDLINE_DBG_PGM("J23", "TFT Serial Debug: UserConfirm Blocking filament prompt... J23"); - } - else if (strcmp_P(msg, PSTR("Filament Purging...")) == 0) { - mediaPrintingState = AMPRINTSTATE_PAUSED; - mediaPauseState = AMPAUSESTATE_PARKING; - // TODO: JBA I don't think J05 just disables the continue button, i think it injects a rogue M25. So taking this out - // disable continue button - // SENDLINE_DBG_PGM("J05", "TFT Serial Debug: UserConfirm SD Filament Purging... J05"); // J05 printing pause - - // enable continue button - SENDLINE_DBG_PGM("J18", "TFT Serial Debug: UserConfirm Filament is purging... J18"); - } - else if (strcmp_P(msg, PSTR("HeaterTimeout")) == 0) { - mediaPrintingState = AMPRINTSTATE_PAUSED; - mediaPauseState = AMPAUSESTATE_HEATER_TIMEOUT; - // enable continue button - SENDLINE_DBG_PGM("J18", "TFT Serial Debug: UserConfirm SD Heater timeout... J18"); - } - else if (strcmp_P(msg, PSTR("Reheat finished.")) == 0) { - mediaPrintingState = AMPRINTSTATE_PAUSED; - mediaPauseState = AMPAUSESTATE_REHEAT_FINISHED; - // enable continue button - SENDLINE_DBG_PGM("J18", "TFT Serial Debug: UserConfirm SD Reheat done... J18"); - } - #endif -} - -float AnycubicTFTClass::CodeValue() { - return (strtod(&TFTcmdbuffer[TFTbufindr][TFTstrchr_pointer - TFTcmdbuffer[TFTbufindr] + 1], NULL)); -} - -bool AnycubicTFTClass::CodeSeen(char code) { - TFTstrchr_pointer = strchr(TFTcmdbuffer[TFTbufindr], code); - return (TFTstrchr_pointer != NULL); // Return True if a character was found -} - -bool AnycubicTFTClass::IsNozzleHomed() { - const float xPosition = ExtUI::getAxisPosition_mm((ExtUI::axis_t) ExtUI::X); - const float yPosition = ExtUI::getAxisPosition_mm((ExtUI::axis_t) ExtUI::Y); - return WITHIN(xPosition, X_MIN_POS - 0.1, X_MIN_POS + 0.1) && - WITHIN(yPosition, Y_MIN_POS - 0.1, Y_MIN_POS + 0.1); -} - -void AnycubicTFTClass::HandleSpecialMenu() { - /** - * NOTE: that the file selection command actual lowercases the entire selected file/foldername, so charracter comparisons need to be lowercase. - */ - if (SelectedDirectory[0] == '<') { - switch (SelectedDirectory[1]) { - case 'e': // "" - SpecialMenu = false; - return; - break; - - #if ENABLED(PROBE_MANUALLY) - case '0': - switch (SelectedDirectory[2]) { - case '1': // "<01ZUp0.1>" - SERIAL_ECHOLNPGM("Special Menu: Z Up 0.1"); - ExtUI::injectCommands_P(PSTR("G91\nG1 Z+0.1\nG90")); - break; - - case '2': // "<02ZUp0.02>" - SERIAL_ECHOLNPGM("Special Menu: Z Up 0.02"); - ExtUI::injectCommands_P(PSTR("G91\nG1 Z+0.02\nG90")); - break; - - case '3': // "<03ZDn0.02>" - SERIAL_ECHOLNPGM("Special Menu: Z Down 0.02"); - ExtUI::injectCommands_P(PSTR("G91\nG1 Z-0.02\nG90")); - break; - - case '4': // "<04ZDn0.1>" - SERIAL_ECHOLNPGM("Special Menu: Z Down 0.1"); - ExtUI::injectCommands_P(PSTR("G91\nG1 Z-0.1\nG90")); - break; - - case '5': // "<05PrehtBed>" - SERIAL_ECHOLNPGM("Special Menu: Preheat Bed"); - ExtUI::injectCommands_P(PSTR("M140 S65")); - break; - - case '6': // "<06SMeshLvl>" - SERIAL_ECHOLNPGM("Special Menu: Start Mesh Leveling"); - ExtUI::injectCommands_P(PSTR("G29 S1")); - break; - - case '7': // "<07MeshNPnt>" - SERIAL_ECHOLNPGM("Special Menu: Next Mesh Point"); - ExtUI::injectCommands_P(PSTR("G29 S2")); - break; - - case '8': // "<08HtEndPID>" - SERIAL_ECHOLNPGM("Special Menu: Auto Tune Hotend PID"); - // need to dwell for half a second to give the fan a chance to start before the pid tuning starts - ExtUI::injectCommands_P(PSTR("M106 S204\nG4 P500\nM303 E0 S215 C15 U1")); - break; - - case '9': // "<09HtBedPID>" - SERIAL_ECHOLNPGM("Special Menu: Auto Tune Hotbed Pid"); - ExtUI::injectCommands_P(PSTR("M303 E-1 S65 C6 U1")); - break; - - default: - break; - } - break; - - case '1': - switch (SelectedDirectory[2]) { - case '0': // "<10FWDeflts>" - SERIAL_ECHOLNPGM("Special Menu: Load FW Defaults"); - ExtUI::injectCommands_P(PSTR("M502\nM300 P105 S1661\nM300 P210 S1108")); - break; - - case '1': // "<11SvEEPROM>" - SERIAL_ECHOLNPGM("Special Menu: Save EEPROM"); - ExtUI::injectCommands_P(PSTR("M500\nM300 P105 S1108\nM300 P210 S1661")); - break; - - default: - break; - } - break; - #else // if ENABLED(PROBE_MANUALLY) - case '0': - switch (SelectedDirectory[2]) { - case '1': // "<01PrehtBed>" - SERIAL_ECHOLNPGM("Special Menu: Preheat Bed"); - ExtUI::injectCommands_P(PSTR("M140 S65")); - break; - - case '2': // "<02ABL>" - SERIAL_ECHOLNPGM("Special Menu: Auto Bed Leveling"); - ExtUI::injectCommands_P(PSTR("G28\nG29")); - break; - - case '3': // "<03HtendPID>" - SERIAL_ECHOLNPGM("Special Menu: Auto Tune Hotend PID"); - // need to dwell for half a second to give the fan a chance to start before the pid tuning starts - ExtUI::injectCommands_P(PSTR("M106 S204\nG4 P500\nM303 E0 S215 C15 U1")); - break; - - case '4': // "<04HtbedPID>" - SERIAL_ECHOLNPGM("Special Menu: Auto Tune Hotbed Pid"); - ExtUI::injectCommands_P(PSTR("M303 E-1 S65 C6 U1")); - break; - - case '5': // "<05FWDeflts>" - SERIAL_ECHOLNPGM("Special Menu: Load FW Defaults"); - ExtUI::injectCommands_P(PSTR("M502\nM300 P105 S1661\nM300 P210 S1108")); - break; - - case '6': // "<06SvEEPROM>" - SERIAL_ECHOLNPGM("Special Menu: Save EEPROM"); - ExtUI::injectCommands_P(PSTR("M500\nM300 P105 S1108\nM300 P210 S1661")); - break; - - case '7': // <07SendM108> - SERIAL_ECHOLNPGM("Special Menu: Send User Confirmation"); - ExtUI::injectCommands_P(PSTR("M108")); - break; - - default: - break; - } - break; - #endif // PROBE_MANUALLY - - default: - break; - } - #if ENABLED(ANYCUBIC_LCD_DEBUG) - } - else { - SERIAL_ECHOPGM("TFT Serial Debug: Attempted to HandleSpecialMenu on non-special menu... "); - SERIAL_ECHOLN(SelectedDirectory); - #endif - } -} - -void AnycubicTFTClass::RenderCurrentFileList() { - #if ENABLED(SDSUPPORT) - uint16_t selectedNumber = 0; - SelectedDirectory[0] = 0; - SelectedFile[0] = 0; - ExtUI::FileList currentFileList; - - SENDLINE_PGM("FN "); // Filelist start - - if (!ExtUI::isMediaInserted() && !SpecialMenu) { - SENDLINE_DBG_PGM("J02", "TFT Serial Debug: No SD Card mounted to render Current File List... J02"); - - SENDLINE_PGM(""); - SENDLINE_PGM(""); - } - else { - if (CodeSeen('S')) - selectedNumber = CodeValue(); - - if (SpecialMenu) - RenderSpecialMenu(selectedNumber); - else if (selectedNumber <= currentFileList.count()) - RenderCurrentFolder(selectedNumber); - } - SENDLINE_PGM("END"); // Filelist stop - #endif // SDSUPPORT -} - -void AnycubicTFTClass::RenderSpecialMenu(uint16_t selectedNumber) { - switch (selectedNumber) { - #if ENABLED(PROBE_MANUALLY) - case 0: // First Page - SENDLINE_PGM("<01ZUp0.1>"); - SENDLINE_PGM(""); - SENDLINE_PGM("<02ZUp0.02>"); - SENDLINE_PGM(""); - SENDLINE_PGM("<03ZDn0.02>"); - SENDLINE_PGM(""); - SENDLINE_PGM("<04ZDn0.1>"); - SENDLINE_PGM(""); - break; - - case 4: // Second Page - SENDLINE_PGM("<05PrehtBed>"); - SENDLINE_PGM(""); - SENDLINE_PGM("<06SMeshLvl>"); - SENDLINE_PGM(""); - SENDLINE_PGM("<07MeshNPnt>"); - SENDLINE_PGM(""); - SENDLINE_PGM("<08HtEndPID>"); - SENDLINE_PGM(""); - break; - - case 8: // Third Page - SENDLINE_PGM("<09HtBedPID>"); - SENDLINE_PGM(""); - SENDLINE_PGM("<10FWDeflts>"); - SENDLINE_PGM(""); - SENDLINE_PGM("<11SvEEPROM>"); - SENDLINE_PGM(""); - SENDLINE_PGM(""); - SENDLINE_PGM(""); - break; - #else - case 0: // First Page - SENDLINE_PGM("<01PrehtBed>"); - SENDLINE_PGM(""); - SENDLINE_PGM("<02ABL>"); - SENDLINE_PGM(""); - SENDLINE_PGM("<03HtEndPID>"); - SENDLINE_PGM(""); - SENDLINE_PGM("<04HtBedPID>"); - SENDLINE_PGM(""); - break; - - case 4: // Second Page - SENDLINE_PGM("<05FWDeflts>"); - SENDLINE_PGM(""); - SENDLINE_PGM("<06SvEEPROM>"); - SENDLINE_PGM(""); - SENDLINE_PGM("<07SendM108>"); - SENDLINE_PGM(""); - SENDLINE_PGM(""); - SENDLINE_PGM(""); - break; - - #endif // PROBE_MANUALLY - - default: - break; - } -} - -void AnycubicTFTClass::RenderCurrentFolder(uint16_t selectedNumber) { - ExtUI::FileList currentFileList; - uint16_t cnt = selectedNumber; - uint16_t max_files; - uint16_t dir_files = currentFileList.count(); - - if ((dir_files - selectedNumber) < 4) - max_files = dir_files; - else - max_files = selectedNumber + 3; - - for (cnt = selectedNumber; cnt <= max_files; cnt++) { - if (cnt == 0) { // Special Entry - if (currentFileList.isAtRootDir()) { - SENDLINE_PGM(""); - SENDLINE_PGM(""); - } - else { - SENDLINE_PGM("/.."); - SENDLINE_PGM("/.."); - } - } - else { - currentFileList.seek(cnt - 1, false); - - #if ENABLED(ANYCUBIC_LCD_DEBUG) - SERIAL_ECHOLN(currentFileList.filename()); - #endif - if (currentFileList.isDir()) { - SEND_PGM("/"); - SENDLINE(currentFileList.shortFilename()); - SEND_PGM("/"); - SENDLINE(currentFileList.filename()); - - } - else { - SENDLINE(currentFileList.shortFilename()); - SENDLINE(currentFileList.filename()); - } - } - } -} - -void AnycubicTFTClass::OnPrintTimerStarted() { - #if ENABLED(SDSUPPORT) - if (mediaPrintingState == AMPRINTSTATE_PRINTING) - SENDLINE_DBG_PGM("J04", "TFT Serial Debug: Starting SD Print... J04"); // J04 Starting Print - - #endif -} - -void AnycubicTFTClass::OnPrintTimerPaused() { - #if ENABLED(SDSUPPORT) - if (ExtUI::isPrintingFromMedia()) { - mediaPrintingState = AMPRINTSTATE_PAUSED; - mediaPauseState = AMPAUSESTATE_PARKING; - } - #endif -} - -void AnycubicTFTClass::OnPrintTimerStopped() { - #if ENABLED(SDSUPPORT) - if (mediaPrintingState == AMPRINTSTATE_PRINTING) { - mediaPrintingState = AMPRINTSTATE_NOT_PRINTING; - mediaPauseState = AMPAUSESTATE_NOT_PAUSED; - SENDLINE_DBG_PGM("J14", "TFT Serial Debug: SD Print Completed... J14"); - } - // otherwise it was stopped by the printer so don't send print completed signal to TFT - #endif -} - -void AnycubicTFTClass::GetCommandFromTFT() { - char *starpos = NULL; - while (LCD_SERIAL.available() > 0 && TFTbuflen < TFTBUFSIZE) { - serial3_char = LCD_SERIAL.read(); - if (serial3_char == '\n' || - serial3_char == '\r' || - serial3_char == ':' || - serial3_count >= (TFT_MAX_CMD_SIZE - 1) - ) { - - if (!serial3_count) return; // if empty line - - TFTcmdbuffer[TFTbufindw][serial3_count] = 0; // terminate string - - if ((strchr(TFTcmdbuffer[TFTbufindw], 'A') != NULL)) { - int16_t a_command; - TFTstrchr_pointer = strchr(TFTcmdbuffer[TFTbufindw], 'A'); - a_command = ((int)((strtod(&TFTcmdbuffer[TFTbufindw][TFTstrchr_pointer - TFTcmdbuffer[TFTbufindw] + 1], NULL)))); - - #if ENABLED(ANYCUBIC_LCD_DEBUG) - if ((a_command > 7) && (a_command != 20)) { // No debugging of status polls, please! - SERIAL_ECHOPGM("TFT Serial Command: "); - SERIAL_ECHOLN(TFTcmdbuffer[TFTbufindw]); - } - #endif - - switch (a_command) { - case 0: { // A0 GET HOTEND TEMP - float hotendActualTemp = ExtUI::getActualTemp_celsius((ExtUI::extruder_t) (ExtUI::extruder_t) ExtUI::E0); - SEND_PGM_VAL("A0V ", int(hotendActualTemp + 0.5)); - } - break; - - case 1: { // A1 GET HOTEND TARGET TEMP - float hotendTargetTemp = ExtUI::getTargetTemp_celsius((ExtUI::extruder_t) (ExtUI::extruder_t) ExtUI::E0); - SEND_PGM_VAL("A1V ", int(hotendTargetTemp + 0.5)); - } - break; - - case 2: { // A2 GET HOTBED TEMP - float heatedBedActualTemp = ExtUI::getActualTemp_celsius((ExtUI::heater_t) ExtUI::BED); - SEND_PGM_VAL("A2V ", int(heatedBedActualTemp + 0.5)); - } - break; - - case 3: { // A3 GET HOTBED TARGET TEMP - float heatedBedTargetTemp = ExtUI::getTargetTemp_celsius((ExtUI::heater_t) ExtUI::BED); - SEND_PGM_VAL("A3V ", int(heatedBedTargetTemp + 0.5)); - } break; - - case 4: { // A4 GET FAN SPEED - float fanPercent = ExtUI::getActualFan_percent(ExtUI::FAN0); - fanPercent = constrain(fanPercent, 0, 100); - SEND_PGM_VAL("A4V ", int(fanPercent)); - } break; - - case 5: { // A5 GET CURRENT COORDINATE - float xPostition = ExtUI::getAxisPosition_mm(ExtUI::X); - float yPostition = ExtUI::getAxisPosition_mm(ExtUI::Y); - float zPostition = ExtUI::getAxisPosition_mm(ExtUI::Z); - SEND_PGM("A5V X: "); - LCD_SERIAL.print(xPostition); - SEND_PGM(" Y: "); - LCD_SERIAL.print(yPostition); - SEND_PGM(" Z: "); - LCD_SERIAL.print(zPostition); - SENDLINE_PGM(""); - } break; - - case 6: // A6 GET SD CARD PRINTING STATUS - #if ENABLED(SDSUPPORT) - if (ExtUI::isPrintingFromMedia()) { - SEND_PGM("A6V "); - if (ExtUI::isMediaInserted()) - SENDLINE(ui8tostr3rj(ExtUI::getProgress_percent())); - else - SENDLINE_DBG_PGM("J02", "TFT Serial Debug: No SD Card mounted to return printing status... J02"); - } - else - SENDLINE_PGM("A6V ---"); - #endif - break; - - case 7: { // A7 GET PRINTING TIME - const uint32_t elapsedSeconds = ExtUI::getProgress_seconds_elapsed(); - SEND_PGM("A7V "); - if (elapsedSeconds != 0) { // print time - const uint32_t elapsedMinutes = elapsedSeconds / 60; - SEND(ui8tostr2(elapsedMinutes / 60)); - SEND_PGM(" H "); - SEND(ui8tostr2(elapsedMinutes % 60)); - SENDLINE_PGM(" M"); - } - else - SENDLINE_PGM(" 999:999"); - } - break; - - case 8: // A8 GET SD LIST - #if ENABLED(SDSUPPORT) - SelectedFile[0] = 0; - RenderCurrentFileList(); - #endif - break; - - case 9: // A9 pause sd print - #if ENABLED(SDSUPPORT) - if (ExtUI::isPrintingFromMedia()) - PausePrint(); - #endif - break; - - case 10: // A10 resume sd print - #if ENABLED(SDSUPPORT) - if (ExtUI::isPrintingFromMediaPaused()) - ResumePrint(); - #endif - break; - - case 11: // A11 STOP SD PRINT - TERN_(SDSUPPORT, StopPrint()); - break; - - case 12: // A12 kill - kill(PSTR(STR_ERR_KILLED)); - break; - - case 13: // A13 SELECTION FILE - #if ENABLED(SDSUPPORT) - if (ExtUI::isMediaInserted()) { - starpos = (strchr(TFTstrchr_pointer + 4, '*')); - if (TFTstrchr_pointer[4] == '/') { - strcpy(SelectedDirectory, TFTstrchr_pointer + 5); - SelectedFile[0] = 0; - SENDLINE_DBG_PGM("J21", "TFT Serial Debug: Clear file selection... J21 "); // J21 Not File Selected - SENDLINE_PGM(""); - } - else if (TFTstrchr_pointer[4] == '<') { - strcpy(SelectedDirectory, TFTstrchr_pointer + 4); - SpecialMenu = true; - SelectedFile[0] = 0; - SENDLINE_DBG_PGM("J21", "TFT Serial Debug: Clear file selection... J21 "); // J21 Not File Selected - SENDLINE_PGM(""); - } - else { - SelectedDirectory[0] = 0; - - if (starpos != NULL) - *(starpos - 1) = '\0'; - - strcpy(SelectedFile, TFTstrchr_pointer + 4); - SENDLINE_DBG_PGM_VAL("J20", "TFT Serial Debug: File Selected... J20 ", SelectedFile); // J20 File Selected - } - } - #endif - break; - - case 14: // A14 START PRINTING - #if ENABLED(SDSUPPORT) - if (!ExtUI::isPrinting() && strlen(SelectedFile) > 0) - StartPrint(); - #endif - break; - - case 15: // A15 RESUMING FROM OUTAGE - // TODO: JBA implement resume form outage - break; - - case 16: { // A16 set hotend temp - unsigned int tempvalue; - if (CodeSeen('S')) { - tempvalue = constrain(CodeValue(), 0, 275); - ExtUI::setTargetTemp_celsius(tempvalue, (ExtUI::extruder_t) ExtUI::E0); - } - else if (CodeSeen('C') && !ExtUI::isPrinting()) { - if (ExtUI::getAxisPosition_mm(ExtUI::Z) < 10) - ExtUI::injectCommands_P(PSTR("G1 Z10")); // RASE Z AXIS - tempvalue = constrain(CodeValue(), 0, 275); - ExtUI::setTargetTemp_celsius(tempvalue, (ExtUI::extruder_t) ExtUI::E0); - } - } - break; - - case 17: { // A17 set heated bed temp - unsigned int tempbed; - if (CodeSeen('S')) { - tempbed = constrain(CodeValue(), 0, 100); - ExtUI::setTargetTemp_celsius(tempbed, (ExtUI::heater_t)ExtUI::BED); - } - } - break; - - case 18: { // A18 set fan speed - float fanPercent; - if (CodeSeen('S')) { - fanPercent = CodeValue(); - fanPercent = constrain(fanPercent, 0, 100); - ExtUI::setTargetFan_percent(fanPercent, ExtUI::FAN0); - } - else - fanPercent = 100; - - ExtUI::setTargetFan_percent(fanPercent, ExtUI::FAN0); - SENDLINE_PGM(""); - } - break; - - case 19: // A19 stop stepper drivers - sent on stop extrude command and on turn motors off command - if (!ExtUI::isPrinting()) { - quickstop_stepper(); - disable_all_steppers(); - } - - SENDLINE_PGM(""); - break; - - case 20: // A20 read printing speed - if (CodeSeen('S')) - feedrate_percentage = constrain(CodeValue(), 40, 999); - else - SEND_PGM_VAL("A20V ", feedrate_percentage); - break; - - case 21: // A21 all home - if (!ExtUI::isPrinting() && !ExtUI::isPrintingFromMediaPaused()) { - if (CodeSeen('X') || CodeSeen('Y') || CodeSeen('Z')) { - if (CodeSeen('X')) - ExtUI::injectCommands_P(PSTR("G28 X")); - if (CodeSeen('Y')) - ExtUI::injectCommands_P(PSTR("G28 Y")); - if (CodeSeen('Z')) - ExtUI::injectCommands_P(PSTR("G28 Z")); - } - else if (CodeSeen('C')) { - ExtUI::injectCommands_P(PSTR("G28")); - } - } - break; - - case 22: // A22 move X/Y/Z or extrude - if (!ExtUI::isPrinting()) { - float coorvalue; - unsigned int movespeed = 0; - char commandStr[30]; - char fullCommandStr[38]; - - commandStr[0] = 0; // empty string - if (CodeSeen('F')) // Set feedrate - movespeed = CodeValue(); - - if (CodeSeen('X')) { // Move in X direction - coorvalue = CodeValue(); - if ((coorvalue <= 0.2) && coorvalue > 0) - sprintf_P(commandStr, PSTR("G1 X0.1F%i"), movespeed); - else if ((coorvalue <= -0.1) && coorvalue > -1) - sprintf_P(commandStr, PSTR("G1 X-0.1F%i"), movespeed); - else - sprintf_P(commandStr, PSTR("G1 X%iF%i"), int(coorvalue), movespeed); - } - else if (CodeSeen('Y')) { // Move in Y direction - coorvalue = CodeValue(); - if ((coorvalue <= 0.2) && coorvalue > 0) - sprintf_P(commandStr, PSTR("G1 Y0.1F%i"), movespeed); - else if ((coorvalue <= -0.1) && coorvalue > -1) - sprintf_P(commandStr, PSTR("G1 Y-0.1F%i"), movespeed); - else - sprintf_P(commandStr, PSTR("G1 Y%iF%i"), int(coorvalue), movespeed); - } - else if (CodeSeen('Z')) { // Move in Z direction - coorvalue = CodeValue(); - if ((coorvalue <= 0.2) && coorvalue > 0) - sprintf_P(commandStr, PSTR("G1 Z0.1F%i"), movespeed); - else if ((coorvalue <= -0.1) && coorvalue > -1) - sprintf_P(commandStr, PSTR("G1 Z-0.1F%i"), movespeed); - else - sprintf_P(commandStr, PSTR("G1 Z%iF%i"), int(coorvalue), movespeed); - } - else if (CodeSeen('E')) { // Extrude - coorvalue = CodeValue(); - if ((coorvalue <= 0.2) && coorvalue > 0) - sprintf_P(commandStr, PSTR("G1 E0.1F%i"), movespeed); - else if ((coorvalue <= -0.1) && coorvalue > -1) - sprintf_P(commandStr, PSTR("G1 E-0.1F%i"), movespeed); - else - sprintf_P(commandStr, PSTR("G1 E%iF500"), int(coorvalue)); - } - - if (strlen(commandStr) > 0) { - sprintf_P(fullCommandStr, PSTR("G91\n%s\nG90"), commandStr); - #if ENABLED(ANYCUBIC_LCD_DEBUG) - SERIAL_ECHOPGM("TFT Serial Debug: A22 Move final request with gcode... "); - SERIAL_ECHOLN(fullCommandStr); - #endif - ExtUI::injectCommands(fullCommandStr); - } - } - SENDLINE_PGM(""); - break; - - case 23: // A23 preheat pla - if (!ExtUI::isPrinting()) { - if (ExtUI::getAxisPosition_mm(ExtUI::Z) < 10) - ExtUI::injectCommands_P(PSTR("G1 Z10")); // RASE Z AXIS - - ExtUI::setTargetTemp_celsius(PREHEAT_1_TEMP_BED, (ExtUI::heater_t) ExtUI::BED); - ExtUI::setTargetTemp_celsius(PREHEAT_1_TEMP_HOTEND, (ExtUI::extruder_t) ExtUI::E0); - SENDLINE_PGM("OK"); - } - break; - - case 24:// A24 preheat abs - if (!ExtUI::isPrinting()) { - if (ExtUI::getAxisPosition_mm(ExtUI::Z) < 10) - ExtUI::injectCommands_P(PSTR("G1 Z10")); // RASE Z AXIS - - ExtUI::setTargetTemp_celsius(PREHEAT_2_TEMP_BED, (ExtUI::heater_t) ExtUI::BED); - ExtUI::setTargetTemp_celsius(PREHEAT_2_TEMP_HOTEND, (ExtUI::extruder_t) ExtUI::E0); - SENDLINE_PGM("OK"); - } - break; - - case 25: // A25 cool down - if (!ExtUI::isPrinting()) { - ExtUI::setTargetTemp_celsius(0, (ExtUI::heater_t) ExtUI::BED); - ExtUI::setTargetTemp_celsius(0, (ExtUI::extruder_t) ExtUI::E0); - - SENDLINE_DBG_PGM("J12", "TFT Serial Debug: Cooling down... J12"); // J12 cool down - } - break; - - case 26: // A26 refresh SD - #if ENABLED(SDSUPPORT) - if (ExtUI::isMediaInserted()) { - if (strlen(SelectedDirectory) > 0) { - ExtUI::FileList currentFileList; - if ((SelectedDirectory[0] == '.') && (SelectedDirectory[1] == '.')) { - currentFileList.upDir(); - } - else { - if (SelectedDirectory[0] == '<') - HandleSpecialMenu(); - else - currentFileList.changeDir(SelectedDirectory); - } - } - } - else { - SENDLINE_DBG_PGM("J02", "TFT Serial Debug: No SD Card mounted to refresh SD A26... J02"); - } - - SelectedDirectory[0] = 0; - #endif - break; - - #if ENABLED(SERVO_ENDSTOPS) - case 27: break; // A27 servos angles adjust - #endif - - case 28: // A28 filament test - if (CodeSeen('O')) - NOOP; - else if (CodeSeen('C')) - NOOP; - SENDLINE_PGM(""); - break; - - case 33: // A33 get version info - SEND_PGM("J33 "); - SENDLINE_PGM(DETAILED_BUILD_VERSION); - break; - - default: - break; - } - } - - TFTbufindw = (TFTbufindw + 1) % TFTBUFSIZE; - TFTbuflen += 1; - serial3_count = 0; // clear buffer - } - else { - TFTcmdbuffer[TFTbufindw][serial3_count++] = serial3_char; - } - } -} - -void AnycubicTFTClass::DoSDCardStateCheck() { - #if ENABLED(SDSUPPORT) && PIN_EXISTS(SD_DETECT) - bool isInserted = ExtUI::isMediaInserted(); - if (isInserted) - SENDLINE_DBG_PGM("J00", "TFT Serial Debug: SD card state changed... isInserted"); - else - SENDLINE_DBG_PGM("J01", "TFT Serial Debug: SD card state changed... !isInserted"); - - #endif -} - -void AnycubicTFTClass::DoFilamentRunoutCheck() { - #if ENABLED(FILAMENT_RUNOUT_SENSOR) - // NOTE: ExtUI::getFilamentRunoutState() only returns the runout state if the job is printing - // we want to actually check the status of the pin here, regardless of printstate - if (READ(FIL_RUNOUT_PIN)) { - if (mediaPrintingState == AMPRINTSTATE_PRINTING || mediaPrintingState == AMPRINTSTATE_PAUSED || mediaPrintingState == AMPRINTSTATE_PAUSE_REQUESTED) { - // play tone to indicate filament is out - ExtUI::injectCommands_P(PSTR("\nM300 P200 S1567\nM300 P200 S1174\nM300 P200 S1567\nM300 P200 S1174\nM300 P2000 S1567")); - - // tell the user that the filament has run out and wait - SENDLINE_DBG_PGM("J23", "TFT Serial Debug: Blocking filament prompt... J23"); - } - else { - SENDLINE_DBG_PGM("J15", "TFT Serial Debug: Non blocking filament runout... J15"); - } - } - #endif // FILAMENT_RUNOUT_SENSOR -} - -void AnycubicTFTClass::StartPrint() { - #if ENABLED(SDSUPPORT) - if (!ExtUI::isPrinting() && strlen(SelectedFile) > 0) { - #if ENABLED(ANYCUBIC_LCD_DEBUG) - SERIAL_ECHOPGM("TFT Serial Debug: About to print file ... "); - SERIAL_ECHO(ExtUI::isPrinting()); - SERIAL_ECHOPGM(" "); - SERIAL_ECHOLN(SelectedFile); - #endif - mediaPrintingState = AMPRINTSTATE_PRINTING; - mediaPauseState = AMPAUSESTATE_NOT_PAUSED; - ExtUI::printFile(SelectedFile); - } - #endif // SDUPPORT -} - -void AnycubicTFTClass::PausePrint() { - #if ENABLED(SDSUPPORT) - if (ExtUI::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 - SENDLINE_DBG_PGM("J05", "TFT Serial Debug: SD print pause started... J05"); // J05 printing pause - - // for some reason pausing the print doesn't retract the extruder so force a manual one here - ExtUI::injectCommands_P(PSTR("G91\nG1 E-2 F1800\nG90")); - ExtUI::pausePrint(); - } - #endif -} - -void AnycubicTFTClass::ResumePrint() { - #if ENABLED(SDSUPPORT) - #if ENABLED(FILAMENT_RUNOUT_SENSOR) - if (READ(FIL_RUNOUT_PIN)) { - #if ENABLED(ANYCUBIC_LCD_DEBUG) - SERIAL_ECHOLNPGM("TFT Serial Debug: Resume Print with filament sensor still tripped... "); - #endif - - // trigger the user message box - DoFilamentRunoutCheck(); - - // re-enable the continue button - SENDLINE_DBG_PGM("J18", "TFT Serial Debug: Resume Print with filament sensor still tripped... J18"); - return; - } - #endif - - if (mediaPauseState == AMPAUSESTATE_HEATER_TIMEOUT) { - mediaPauseState = AMPAUSESTATE_REHEATING; - // TODO: JBA I don't think J05 just disables the continue button, i think it injects a rogue M25. So taking this out - // // disable the continue button - // SENDLINE_DBG_PGM("J05", "TFT Serial Debug: Resume called with heater timeout... J05"); // J05 printing pause - - // reheat the nozzle - ExtUI::setUserConfirmed(); - } - else { - mediaPrintingState = AMPRINTSTATE_PRINTING; - mediaPauseState = AMPAUSESTATE_NOT_PAUSED; - - SENDLINE_DBG_PGM("J04", "TFT Serial Debug: SD print resumed... J04"); // J04 printing form sd card now - ExtUI::resumePrint(); - } - #endif -} - -void AnycubicTFTClass::StopPrint() { - #if ENABLED(SDSUPPORT) - mediaPrintingState = AMPRINTSTATE_STOP_REQUESTED; - mediaPauseState = AMPAUSESTATE_NOT_PAUSED; - SENDLINE_DBG_PGM("J16", "TFT Serial Debug: SD print stop called... J16"); - - // for some reason stopping the print doesn't retract the extruder so force a manual one here - ExtUI::injectCommands_P(PSTR("G91\nG1 E-2 F1800\nG90")); - ExtUI::stopPrint(); - #endif -} - -#endif // ANYCUBIC_LCD_I3MEGA diff --git a/Marlin/src/lcd/extui/lib/anycubic_i3mega/anycubic_i3mega_lcd.h b/Marlin/src/lcd/extui/lib/anycubic_i3mega/anycubic_i3mega_lcd.h deleted file mode 100644 index a4ecf5604f9e..000000000000 --- a/Marlin/src/lcd/extui/lib/anycubic_i3mega/anycubic_i3mega_lcd.h +++ /dev/null @@ -1,96 +0,0 @@ -/** - * anycubic_i3mega_lcd.h --- Support for Anycubic i3 Mega TFT - * Created by Christian Hopp on 09.12.17. - * Improved by David Ramiro - * Converted to ext_iu by John BouAntoun 21 June 2020 - * - * 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 - */ -#pragma once - -#include "../../../../inc/MarlinConfigPre.h" -#include "../../../../sd/SdFatConfig.h" // for the FILENAME_LENGTH macro - -#define TFTBUFSIZE 4 -#define TFT_MAX_CMD_SIZE 96 - -enum AnycubicMediaPrintState { - AMPRINTSTATE_NOT_PRINTING, - AMPRINTSTATE_PRINTING, - AMPRINTSTATE_PAUSE_REQUESTED, - AMPRINTSTATE_PAUSED, - AMPRINTSTATE_STOP_REQUESTED -}; - -enum AnycubicMediaPauseState { - AMPAUSESTATE_NOT_PAUSED, - AMPAUSESTATE_PARKING, - AMPAUSESTATE_PARKED, - AMPAUSESTATE_FILAMENT_OUT, - AMPAUSESTATE_FIAMENT_PRUGING, - AMPAUSESTATE_HEATER_TIMEOUT, - AMPAUSESTATE_REHEATING, - AMPAUSESTATE_REHEAT_FINISHED -}; - -class AnycubicTFTClass { -public: - AnycubicTFTClass(); - void OnSetup(); - void OnCommandScan(); - void OnKillTFT(); - void OnSDCardStateChange(bool); - void OnSDCardError(); - void OnFilamentRunout(); - void OnUserConfirmRequired(const char *); - void OnPrintTimerStarted(); - void OnPrintTimerPaused(); - void OnPrintTimerStopped(); - -private: - char TFTcmdbuffer[TFTBUFSIZE][TFT_MAX_CMD_SIZE]; - int TFTbuflen=0; - int TFTbufindr = 0; - int TFTbufindw = 0; - char serial3_char; - int serial3_count = 0; - char *TFTstrchr_pointer; - uint8_t SpecialMenu = false; - AnycubicMediaPrintState mediaPrintingState = AMPRINTSTATE_NOT_PRINTING; - AnycubicMediaPauseState mediaPauseState = AMPAUSESTATE_NOT_PAUSED; - - float CodeValue(); - bool CodeSeen(char); - bool IsNozzleHomed(); - void RenderCurrentFileList(); - void RenderSpecialMenu(uint16_t); - void RenderCurrentFolder(uint16_t); - void GetCommandFromTFT(); - void CheckSDCardChange(); - void CheckPauseState(); - void CheckPrintCompletion(); - void HandleSpecialMenu(); - void DoSDCardStateCheck(); - void DoFilamentRunoutCheck(); - void StartPrint(); - void PausePrint(); - void ResumePrint(); - void StopPrint(); - - char SelectedDirectory[30]; - char SelectedFile[FILENAME_LENGTH]; -}; - -extern AnycubicTFTClass AnycubicTFT; diff --git a/Marlin/src/lcd/extui/lib/dgus/DGUSDisplayDef.h b/Marlin/src/lcd/extui/lib/dgus/DGUSDisplayDef.h deleted file mode 100644 index b34a04875d1a..000000000000 --- a/Marlin/src/lcd/extui/lib/dgus/DGUSDisplayDef.h +++ /dev/null @@ -1,54 +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 - -/* DGUS implementation written by coldtobi in 2019 for Marlin */ - -#include "DGUSVPVariable.h" - -#include - -// This file defines the interaction between Marlin and the display firmware. - -// information on which screen which VP is displayed -// As this is a sparse table, two arrays are needed: -// one to list the VPs of one screen and one to map screens to the lists. -// (Strictly this would not be necessary, but allows to only send data the display needs and reducing load on Marlin) -struct VPMapping { - const uint8_t screen; - const uint16_t *VPList; // The list is null-terminated. -}; - -extern const struct VPMapping VPMap[]; - -// List of VPs handled by Marlin / The Display. -extern const struct DGUS_VP_Variable ListOfVP[]; - -#include "../../../../inc/MarlinConfig.h" - -#if ENABLED(DGUS_LCD_UI_ORIGIN) - #include "origin/DGUSDisplayDef.h" -#elif ENABLED(DGUS_LCD_UI_FYSETC) - #include "fysetc/DGUSDisplayDef.h" -#elif ENABLED(DGUS_LCD_UI_HIPRECY) - #include "hiprecy/DGUSDisplayDef.h" -#endif diff --git a/Marlin/src/lcd/extui/lib/dgus/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/lib/dgus/DGUSScreenHandler.cpp deleted file mode 100644 index 7988985c2e4b..000000000000 --- a/Marlin/src/lcd/extui/lib/dgus/DGUSScreenHandler.cpp +++ /dev/null @@ -1,1140 +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 . - * - */ - -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_DGUS_LCD - -#include "DGUSScreenHandler.h" -#include "DGUSDisplay.h" -#include "DGUSVPVariable.h" -#include "DGUSDisplayDef.h" - -#include "../../ui_api.h" -#include "../../../../MarlinCore.h" -#include "../../../../module/temperature.h" -#include "../../../../module/motion.h" -#include "../../../../gcode/queue.h" -#include "../../../../module/planner.h" -#include "../../../../sd/cardreader.h" -#include "../../../../libs/duration_t.h" -#include "../../../../module/printcounter.h" - -#if ENABLED(POWER_LOSS_RECOVERY) - #include "../../../../feature/powerloss.h" -#endif - -uint16_t DGUSScreenHandler::ConfirmVP; - -#if ENABLED(SDSUPPORT) - int16_t DGUSScreenHandler::top_file = 0; - int16_t DGUSScreenHandler::file_to_print = 0; - static ExtUI::FileList filelist; -#endif - -void (*DGUSScreenHandler::confirm_action_cb)() = nullptr; - -//DGUSScreenHandler ScreenHandler; - -DGUSLCD_Screens DGUSScreenHandler::current_screen; -DGUSLCD_Screens DGUSScreenHandler::past_screens[NUM_PAST_SCREENS]; -uint8_t DGUSScreenHandler::update_ptr; -uint16_t DGUSScreenHandler::skipVP; -bool DGUSScreenHandler::ScreenComplete; - -//DGUSDisplay dgusdisplay; - -// endianness swap -uint16_t swap16(const uint16_t value) { return (value & 0xffU) << 8U | (value >> 8U); } - -void DGUSScreenHandler::sendinfoscreen(const char* line1, const char* line2, const char* line3, const char* line4, bool l1inflash, bool l2inflash, bool l3inflash, bool l4inflash) { - DGUS_VP_Variable ramcopy; - if (populate_VPVar(VP_MSGSTR1, &ramcopy)) { - ramcopy.memadr = (void*) line1; - l1inflash ? DGUSScreenHandler::DGUSLCD_SendStringToDisplayPGM(ramcopy) : DGUSScreenHandler::DGUSLCD_SendStringToDisplay(ramcopy); - } - if (populate_VPVar(VP_MSGSTR2, &ramcopy)) { - ramcopy.memadr = (void*) line2; - l2inflash ? DGUSScreenHandler::DGUSLCD_SendStringToDisplayPGM(ramcopy) : DGUSScreenHandler::DGUSLCD_SendStringToDisplay(ramcopy); - } - if (populate_VPVar(VP_MSGSTR3, &ramcopy)) { - ramcopy.memadr = (void*) line3; - l3inflash ? DGUSScreenHandler::DGUSLCD_SendStringToDisplayPGM(ramcopy) : DGUSScreenHandler::DGUSLCD_SendStringToDisplay(ramcopy); - } - if (populate_VPVar(VP_MSGSTR4, &ramcopy)) { - ramcopy.memadr = (void*) line4; - l4inflash ? DGUSScreenHandler::DGUSLCD_SendStringToDisplayPGM(ramcopy) : DGUSScreenHandler::DGUSLCD_SendStringToDisplay(ramcopy); - } -} - -void DGUSScreenHandler::HandleUserConfirmationPopUp(uint16_t VP, const char* line1, const char* line2, const char* line3, const char* line4, bool l1, bool l2, bool l3, bool l4) { - if (current_screen == DGUSLCD_SCREEN_CONFIRM) { - // Already showing a pop up, so we need to cancel that first. - PopToOldScreen(); - } - - ConfirmVP = VP; - sendinfoscreen(line1, line2, line3, line4, l1, l2, l3, l4); - ScreenHandler.GotoScreen(DGUSLCD_SCREEN_CONFIRM); -} - -void DGUSScreenHandler::setstatusmessage(const char *msg) { - DGUS_VP_Variable ramcopy; - if (populate_VPVar(VP_M117, &ramcopy)) { - ramcopy.memadr = (void*) msg; - DGUSLCD_SendStringToDisplay(ramcopy); - } -} - -void DGUSScreenHandler::setstatusmessagePGM(PGM_P const msg) { - DGUS_VP_Variable ramcopy; - if (populate_VPVar(VP_M117, &ramcopy)) { - ramcopy.memadr = (void*) msg; - DGUSLCD_SendStringToDisplayPGM(ramcopy); - } -} - -// Send an 8 bit or 16 bit value to the display. -void DGUSScreenHandler::DGUSLCD_SendWordValueToDisplay(DGUS_VP_Variable &var) { - if (var.memadr) { - //DEBUG_ECHOPAIR(" DGUS_LCD_SendWordValueToDisplay ", var.VP); - //DEBUG_ECHOLNPAIR(" data ", *(uint16_t *)var.memadr); - if (var.size > 1) - dgusdisplay.WriteVariable(var.VP, *(int16_t*)var.memadr); - else - dgusdisplay.WriteVariable(var.VP, *(int8_t*)var.memadr); - } -} - -// Send an uint8_t between 0 and 255 to the display, but scale to a percentage (0..100) -void DGUSScreenHandler::DGUSLCD_SendPercentageToDisplay(DGUS_VP_Variable &var) { - if (var.memadr) { - //DEBUG_ECHOPAIR(" DGUS_LCD_SendWordValueToDisplay ", var.VP); - //DEBUG_ECHOLNPAIR(" data ", *(uint16_t *)var.memadr); - uint16_t tmp = *(uint8_t *) var.memadr +1 ; // +1 -> avoid rounding issues for the display. - tmp = map(tmp, 0, 255, 0, 100); - dgusdisplay.WriteVariable(var.VP, tmp); - } -} - -// Send the current print progress to the display. -void DGUSScreenHandler::DGUSLCD_SendPrintProgressToDisplay(DGUS_VP_Variable &var) { - //DEBUG_ECHOPAIR(" DGUSLCD_SendPrintProgressToDisplay ", var.VP); - uint16_t tmp = ExtUI::getProgress_percent(); - //DEBUG_ECHOLNPAIR(" data ", tmp); - dgusdisplay.WriteVariable(var.VP, tmp); -} - -// Send the current print time to the display. -// It is using a hex display for that: It expects BSD coded data in the format xxyyzz -void DGUSScreenHandler::DGUSLCD_SendPrintTimeToDisplay(DGUS_VP_Variable &var) { - duration_t elapsed = print_job_timer.duration(); - char buf[32]; - elapsed.toString(buf); - dgusdisplay.WriteVariable(VP_PrintTime, buf, var.size, true); -} - -// Send an uint8_t between 0 and 100 to a variable scale to 0..255 -void DGUSScreenHandler::DGUSLCD_PercentageToUint8(DGUS_VP_Variable &var, void *val_ptr) { - if (var.memadr) { - uint16_t value = swap16(*(uint16_t*)val_ptr); - *(uint8_t*)var.memadr = map(constrain(value, 0, 100), 0, 100, 0, 255); - } -} - -// Sends a (RAM located) string to the DGUS Display -// (Note: The DGUS Display does not clear after the \0, you have to -// overwrite the remainings with spaces.// var.size has the display buffer size! -void DGUSScreenHandler::DGUSLCD_SendStringToDisplay(DGUS_VP_Variable &var) { - char *tmp = (char*) var.memadr; - dgusdisplay.WriteVariable(var.VP, tmp, var.size, true); -} - -// Sends a (flash located) string to the DGUS Display -// (Note: The DGUS Display does not clear after the \0, you have to -// overwrite the remainings with spaces.// var.size has the display buffer size! -void DGUSScreenHandler::DGUSLCD_SendStringToDisplayPGM(DGUS_VP_Variable &var) { - char *tmp = (char*) var.memadr; - dgusdisplay.WriteVariablePGM(var.VP, tmp, var.size, true); -} - -#if HAS_PID_HEATING - void DGUSScreenHandler::DGUSLCD_SendTemperaturePID(DGUS_VP_Variable &var) { - float value = *(float *)var.memadr; - float valuesend = 0; - switch (var.VP) { - default: return; - #if HOTENDS >= 1 - case VP_E0_PID_P: valuesend = value; break; - case VP_E0_PID_I: valuesend = unscalePID_i(value); break; - case VP_E0_PID_D: valuesend = unscalePID_d(value); break; - #endif - #if HOTENDS >= 2 - case VP_E1_PID_P: valuesend = value; break; - case VP_E1_PID_I: valuesend = unscalePID_i(value); break; - case VP_E1_PID_D: valuesend = unscalePID_d(value); break; - #endif - #if HAS_HEATED_BED - case VP_BED_PID_P: valuesend = value; break; - case VP_BED_PID_I: valuesend = unscalePID_i(value); break; - case VP_BED_PID_D: valuesend = unscalePID_d(value); break; - #endif - } - - valuesend *= cpow(10, 1); - union { int16_t i; char lb[2]; } endian; - - char tmp[2]; - endian.i = valuesend; - tmp[0] = endian.lb[1]; - tmp[1] = endian.lb[0]; - dgusdisplay.WriteVariable(var.VP, tmp, 2); - } -#endif - -#if ENABLED(PRINTCOUNTER) - - // Send the accumulate print time to the display. - // It is using a hex display for that: It expects BSD coded data in the format xxyyzz - void DGUSScreenHandler::DGUSLCD_SendPrintAccTimeToDisplay(DGUS_VP_Variable &var) { - printStatistics state = print_job_timer.getStats(); - char buf[21]; - duration_t elapsed = state.printTime; - elapsed.toString(buf); - dgusdisplay.WriteVariable(VP_PrintAccTime, buf, var.size, true); - } - - void DGUSScreenHandler::DGUSLCD_SendPrintsTotalToDisplay(DGUS_VP_Variable &var) { - printStatistics state = print_job_timer.getStats(); - char buf[21]; - sprintf_P(buf, PSTR("%u"), state.totalPrints); - dgusdisplay.WriteVariable(VP_PrintsTotal, buf, var.size, true); - } - -#endif - -// Send fan status value to the display. -#if HAS_FAN - void DGUSScreenHandler::DGUSLCD_SendFanStatusToDisplay(DGUS_VP_Variable &var) { - if (var.memadr) { - DEBUG_ECHOPAIR(" DGUSLCD_SendFanStatusToDisplay ", var.VP); - DEBUG_ECHOLNPAIR(" data ", *(uint8_t *)var.memadr); - uint16_t data_to_send = 0; - if (*(uint8_t *) var.memadr) data_to_send = 1; - dgusdisplay.WriteVariable(var.VP, data_to_send); - } - } -#endif - -// Send heater status value to the display. -void DGUSScreenHandler::DGUSLCD_SendHeaterStatusToDisplay(DGUS_VP_Variable &var) { - if (var.memadr) { - DEBUG_ECHOPAIR(" DGUSLCD_SendHeaterStatusToDisplay ", var.VP); - DEBUG_ECHOLNPAIR(" data ", *(int16_t *)var.memadr); - uint16_t data_to_send = 0; - if (*(int16_t *) var.memadr) data_to_send = 1; - dgusdisplay.WriteVariable(var.VP, data_to_send); - } -} - -#if ENABLED(DGUS_UI_WAITING) - void DGUSScreenHandler::DGUSLCD_SendWaitingStatusToDisplay(DGUS_VP_Variable &var) { - // In FYSETC UI design there are 10 statuses to loop - static uint16_t period = 0; - static uint16_t index = 0; - //DEBUG_ECHOPAIR(" DGUSLCD_SendWaitingStatusToDisplay ", var.VP); - //DEBUG_ECHOLNPAIR(" data ", swap16(index)); - if (period++ > DGUS_UI_WAITING_STATUS_PERIOD) { - dgusdisplay.WriteVariable(var.VP, index); - //DEBUG_ECHOLNPAIR(" data ", swap16(index)); - if (++index >= DGUS_UI_WAITING_STATUS) index = 0; - period = 0; - } - } -#endif - -#if ENABLED(SDSUPPORT) - - void DGUSScreenHandler::ScreenChangeHookIfSD(DGUS_VP_Variable &var, void *val_ptr) { - // default action executed when there is a SD card, but not printing - if (ExtUI::isMediaInserted() && !ExtUI::isPrintingFromMedia()) { - ScreenChangeHook(var, val_ptr); - dgusdisplay.RequestScreen(current_screen); - return; - } - - // if we are printing, we jump to two screens after the requested one. - // This should host e.g a print pause / print abort / print resume dialog. - // This concept allows to recycle this hook for other file - if (ExtUI::isPrintingFromMedia() && !card.flag.abort_sd_printing) { - GotoScreen(DGUSLCD_SCREEN_SDPRINTMANIPULATION); - return; - } - - // Don't let the user in the dark why there is no reaction. - if (!ExtUI::isMediaInserted()) { - setstatusmessagePGM(GET_TEXT(MSG_NO_MEDIA)); - return; - } - if (card.flag.abort_sd_printing) { - setstatusmessagePGM(GET_TEXT(MSG_MEDIA_ABORTING)); - return; - } - } - - void DGUSScreenHandler::DGUSLCD_SD_ScrollFilelist(DGUS_VP_Variable& var, void *val_ptr) { - auto old_top = top_file; - const int16_t scroll = (int16_t)swap16(*(uint16_t*)val_ptr); - if (scroll) { - top_file += scroll; - DEBUG_ECHOPAIR("new topfile calculated:", top_file); - if (top_file < 0) { - top_file = 0; - DEBUG_ECHOLNPGM("Top of filelist reached"); - } - else { - int16_t max_top = filelist.count() - DGUS_SD_FILESPERSCREEN; - NOLESS(max_top, 0); - NOMORE(top_file, max_top); - } - DEBUG_ECHOPAIR("new topfile adjusted:", top_file); - } - else if (!filelist.isAtRootDir()) { - filelist.upDir(); - top_file = 0; - ForceCompleteUpdate(); - } - - if (old_top != top_file) ForceCompleteUpdate(); - } - - void DGUSScreenHandler::DGUSLCD_SD_FileSelected(DGUS_VP_Variable &var, void *val_ptr) { - uint16_t touched_nr = (int16_t)swap16(*(uint16_t*)val_ptr) + top_file; - if (touched_nr > filelist.count()) return; - if (!filelist.seek(touched_nr)) return; - if (filelist.isDir()) { - filelist.changeDir(filelist.filename()); - top_file = 0; - ForceCompleteUpdate(); - return; - } - - #if ENABLED(DGUS_PRINT_FILENAME) - // Send print filename - dgusdisplay.WriteVariable(VP_SD_Print_Filename, filelist.filename(), VP_SD_FileName_LEN, true); - #endif - - // Setup Confirmation screen - file_to_print = touched_nr; - HandleUserConfirmationPopUp(VP_SD_FileSelectConfirm, nullptr, PSTR("Print file"), filelist.filename(), PSTR("from SD Card?"), true, true, false, true); - } - - void DGUSScreenHandler::DGUSLCD_SD_StartPrint(DGUS_VP_Variable &var, void *val_ptr) { - if (!filelist.seek(file_to_print)) return; - ExtUI::printFile(filelist.shortFilename()); - ScreenHandler.GotoScreen( - #if ENABLED(DGUS_LCD_UI_ORIGIN) - DGUSLCD_SCREEN_STATUS - #else - DGUSLCD_SCREEN_SDPRINTMANIPULATION - #endif - ); - } - - void DGUSScreenHandler::DGUSLCD_SD_ResumePauseAbort(DGUS_VP_Variable &var, void *val_ptr) { - if (!ExtUI::isPrintingFromMedia()) return; // avoid race condition when user stays in this menu and printer finishes. - switch (swap16(*(uint16_t*)val_ptr)) { - case 0: // Resume - if (ExtUI::isPrintingFromMediaPaused()) ExtUI::resumePrint(); - break; - case 1: // Pause - if (!ExtUI::isPrintingFromMediaPaused()) ExtUI::pausePrint(); - break; - case 2: // Abort - ScreenHandler.HandleUserConfirmationPopUp(VP_SD_AbortPrintConfirmed, nullptr, PSTR("Abort printing"), filelist.filename(), PSTR("?"), true, true, false, true); - break; - } - } - - void DGUSScreenHandler::DGUSLCD_SD_ReallyAbort(DGUS_VP_Variable &var, void *val_ptr) { - ExtUI::stopPrint(); - GotoScreen(DGUSLCD_SCREEN_MAIN); - } - - void DGUSScreenHandler::DGUSLCD_SD_PrintTune(DGUS_VP_Variable &var, void *val_ptr) { - if (!ExtUI::isPrintingFromMedia()) return; // avoid race condition when user stays in this menu and printer finishes. - GotoScreen(DGUSLCD_SCREEN_SDPRINTTUNE); - } - - void DGUSScreenHandler::DGUSLCD_SD_SendFilename(DGUS_VP_Variable& var) { - uint16_t target_line = (var.VP - VP_SD_FileName0) / VP_SD_FileName_LEN; - if (target_line > DGUS_SD_FILESPERSCREEN) return; - char tmpfilename[VP_SD_FileName_LEN + 1] = ""; - var.memadr = (void*)tmpfilename; - if (filelist.seek(top_file + target_line)) - snprintf_P(tmpfilename, VP_SD_FileName_LEN, PSTR("%s%c"), filelist.filename(), filelist.isDir() ? '/' : 0); - DGUSLCD_SendStringToDisplay(var); - } - - void DGUSScreenHandler::SDCardInserted() { - top_file = 0; - filelist.refresh(); - auto cs = ScreenHandler.getCurrentScreen(); - if (cs == DGUSLCD_SCREEN_MAIN || cs == DGUSLCD_SCREEN_STATUS) - ScreenHandler.GotoScreen(DGUSLCD_SCREEN_SDFILELIST); - } - - void DGUSScreenHandler::SDCardRemoved() { - if (current_screen == DGUSLCD_SCREEN_SDFILELIST - || (current_screen == DGUSLCD_SCREEN_CONFIRM && (ConfirmVP == VP_SD_AbortPrintConfirmed || ConfirmVP == VP_SD_FileSelectConfirm)) - || current_screen == DGUSLCD_SCREEN_SDPRINTMANIPULATION - ) ScreenHandler.GotoScreen(DGUSLCD_SCREEN_MAIN); - } - - void DGUSScreenHandler::SDCardError() { - DGUSScreenHandler::SDCardRemoved(); - ScreenHandler.sendinfoscreen(PSTR("NOTICE"), nullptr, PSTR("SD card error"), nullptr, true, true, true, true); - ScreenHandler.SetupConfirmAction(nullptr); - ScreenHandler.GotoScreen(DGUSLCD_SCREEN_POPUP); - } - -#endif // SDSUPPORT - -void DGUSScreenHandler::ScreenConfirmedOK(DGUS_VP_Variable &var, void *val_ptr) { - DGUS_VP_Variable ramcopy; - if (!populate_VPVar(ConfirmVP, &ramcopy)) return; - if (ramcopy.set_by_display_handler) ramcopy.set_by_display_handler(ramcopy, val_ptr); -} - -const uint16_t* DGUSLCD_FindScreenVPMapList(uint8_t screen) { - const uint16_t *ret; - const struct VPMapping *map = VPMap; - while (ret = (uint16_t*) pgm_read_ptr(&(map->VPList))) { - if (pgm_read_byte(&(map->screen)) == screen) return ret; - map++; - } - return nullptr; -} - -const DGUS_VP_Variable* DGUSLCD_FindVPVar(const uint16_t vp) { - const DGUS_VP_Variable *ret = ListOfVP; - do { - const uint16_t vpcheck = pgm_read_word(&(ret->VP)); - if (vpcheck == 0) break; - if (vpcheck == vp) return ret; - ++ret; - } while (1); - - DEBUG_ECHOLNPAIR("FindVPVar NOT FOUND ", vp); - return nullptr; -} - -void DGUSScreenHandler::ScreenChangeHookIfIdle(DGUS_VP_Variable &var, void *val_ptr) { - if (!ExtUI::isPrinting()) { - ScreenChangeHook(var, val_ptr); - dgusdisplay.RequestScreen(current_screen); - } -} - -void DGUSScreenHandler::ScreenChangeHook(DGUS_VP_Variable &var, void *val_ptr) { - uint8_t *tmp = (uint8_t*)val_ptr; - - // The keycode in target is coded as , so 0x0100A means - // from screen 1 (main) to 10 (temperature). DGUSLCD_SCREEN_POPUP is special, - // meaning "return to previous screen" - DGUSLCD_Screens target = (DGUSLCD_Screens)tmp[1]; - - if (target == DGUSLCD_SCREEN_POPUP) { - // special handling for popup is to return to previous menu - if (current_screen == DGUSLCD_SCREEN_POPUP && confirm_action_cb) confirm_action_cb(); - PopToOldScreen(); - return; - } - - UpdateNewScreen(target); - - #ifdef DEBUG_DGUSLCD - if (!DGUSLCD_FindScreenVPMapList(target)) DEBUG_ECHOLNPAIR("WARNING: No screen Mapping found for ", target); - #endif -} - -void DGUSScreenHandler::HandleAllHeatersOff(DGUS_VP_Variable &var, void *val_ptr) { - thermalManager.disable_all_heaters(); - ScreenHandler.ForceCompleteUpdate(); // hint to send all data. -} - -void DGUSScreenHandler::HandleTemperatureChanged(DGUS_VP_Variable &var, void *val_ptr) { - uint16_t newvalue = swap16(*(uint16_t*)val_ptr); - uint16_t acceptedvalue; - - switch (var.VP) { - default: return; - #if HOTENDS >= 1 - case VP_T_E0_Set: - thermalManager.setTargetHotend(newvalue, 0); - acceptedvalue = thermalManager.temp_hotend[0].target; - break; - #endif - #if HOTENDS >= 2 - case VP_T_E1_Set: - thermalManager.setTargetHotend(newvalue, 1); - acceptedvalue = thermalManager.temp_hotend[1].target; - break; - #endif - #if HAS_HEATED_BED - case VP_T_Bed_Set: - thermalManager.setTargetBed(newvalue); - acceptedvalue = thermalManager.temp_bed.target; - break; - #endif - } - - // reply to display the new value to update the view if the new value was rejected by the Thermal Manager. - if (newvalue != acceptedvalue && var.send_to_display_handler) var.send_to_display_handler(var); - ScreenHandler.skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel -} - -void DGUSScreenHandler::HandleFlowRateChanged(DGUS_VP_Variable &var, void *val_ptr) { - #if EXTRUDERS - uint16_t newvalue = swap16(*(uint16_t*)val_ptr); - uint8_t target_extruder; - switch (var.VP) { - default: return; - #if HOTENDS >= 1 - case VP_Flowrate_E0: target_extruder = 0; break; - #endif - #if HOTENDS >= 2 - case VP_Flowrate_E1: target_extruder = 1; break; - #endif - } - - planner.set_flow(target_extruder, newvalue); - ScreenHandler.skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel - #else - UNUSED(var); UNUSED(val_ptr); - #endif -} - -void DGUSScreenHandler::HandleManualExtrude(DGUS_VP_Variable &var, void *val_ptr) { - DEBUG_ECHOLNPGM("HandleManualExtrude"); - - int16_t movevalue = swap16(*(uint16_t*)val_ptr); - float target = movevalue * 0.01f; - ExtUI::extruder_t target_extruder; - - switch (var.VP) { - #if HOTENDS >= 1 - case VP_MOVE_E0: target_extruder = ExtUI::extruder_t::E0; break; - #endif - #if HOTENDS >= 2 - case VP_MOVE_E1: target_extruder = ExtUI::extruder_t::E1; break; - #endif - default: return; - } - - target += ExtUI::getAxisPosition_mm(target_extruder); - ExtUI::setAxisPosition_mm(target, target_extruder); - skipVP = var.VP; -} - -#if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - void DGUSScreenHandler::HandleManualMoveOption(DGUS_VP_Variable &var, void *val_ptr) { - DEBUG_ECHOLNPGM("HandleManualMoveOption"); - *(uint16_t*)var.memadr = swap16(*(uint16_t*)val_ptr); - } -#endif - -void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { - DEBUG_ECHOLNPGM("HandleManualMove"); - - int16_t movevalue = swap16(*(uint16_t*)val_ptr); - #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - if (movevalue) { - const uint16_t choice = *(uint16_t*)var.memadr; - movevalue = movevalue < 0 ? -choice : choice; - } - #endif - char axiscode; - unsigned int speed = 1500; //FIXME: get default feedrate for manual moves, dont hardcode. - - switch (var.VP) { - default: return; - - case VP_MOVE_X: - axiscode = 'X'; - if (!ExtUI::canMove(ExtUI::axis_t::X)) goto cannotmove; - break; - - case VP_MOVE_Y: - axiscode = 'Y'; - if (!ExtUI::canMove(ExtUI::axis_t::Y)) goto cannotmove; - break; - - case VP_MOVE_Z: - axiscode = 'Z'; - speed = 300; // default to 5mm/s - if (!ExtUI::canMove(ExtUI::axis_t::Z)) goto cannotmove; - break; - - case VP_HOME_ALL: // only used for homing - axiscode = '\0'; - movevalue = 0; // ignore value sent from display, this VP is _ONLY_ for homing. - break; - } - - if (!movevalue) { - // homing - DEBUG_ECHOPAIR(" homing ", axiscode); - char buf[6] = "G28 X"; - buf[4] = axiscode; - //DEBUG_ECHOPAIR(" ", buf); - queue.enqueue_one_now(buf); - //DEBUG_ECHOLNPGM(" ✓"); - ScreenHandler.ForceCompleteUpdate(); - return; - } - else { - //movement - DEBUG_ECHOPAIR(" move ", axiscode); - bool old_relative_mode = relative_mode; - if (!relative_mode) { - //DEBUG_ECHOPGM(" G91"); - queue.enqueue_now_P(PSTR("G91")); - //DEBUG_ECHOPGM(" ✓ "); - } - char buf[32]; // G1 X9999.99 F12345 - unsigned int backup_speed = MMS_TO_MMM(feedrate_mm_s); - char sign[]="\0"; - int16_t value = movevalue / 100; - if (movevalue < 0) { value = -value; sign[0] = '-'; } - int16_t fraction = ABS(movevalue) % 100; - snprintf_P(buf, 32, PSTR("G0 %c%s%d.%02d F%d"), axiscode, sign, value, fraction, speed); - //DEBUG_ECHOPAIR(" ", buf); - queue.enqueue_one_now(buf); - //DEBUG_ECHOLNPGM(" ✓ "); - if (backup_speed != speed) { - snprintf_P(buf, 32, PSTR("G0 F%d"), backup_speed); - queue.enqueue_one_now(buf); - //DEBUG_ECHOPAIR(" ", buf); - } - //while (!enqueue_and_echo_command(buf)) idle(); - //DEBUG_ECHOLNPGM(" ✓ "); - if (!old_relative_mode) { - //DEBUG_ECHOPGM("G90"); - queue.enqueue_now_P(PSTR("G90")); - //DEBUG_ECHOPGM(" ✓ "); - } - } - - ScreenHandler.ForceCompleteUpdate(); - DEBUG_ECHOLNPGM("manmv done."); - return; - - cannotmove: - DEBUG_ECHOLNPAIR(" cannot move ", axiscode); - return; -} - -void DGUSScreenHandler::HandleMotorLockUnlock(DGUS_VP_Variable &var, void *val_ptr) { - DEBUG_ECHOLNPGM("HandleMotorLockUnlock"); - - char buf[4]; - const int16_t lock = swap16(*(uint16_t*)val_ptr); - strcpy_P(buf, lock ? PSTR("M18") : PSTR("M17")); - - //DEBUG_ECHOPAIR(" ", buf); - queue.enqueue_one_now(buf); -} - -#if ENABLED(POWER_LOSS_RECOVERY) - - void DGUSScreenHandler::HandlePowerLossRecovery(DGUS_VP_Variable &var, void *val_ptr) { - uint16_t value = swap16(*(uint16_t*)val_ptr); - if (value) { - queue.inject_P(PSTR("M1000")); - ScreenHandler.GotoScreen(DGUSLCD_SCREEN_SDPRINTMANIPULATION); - } - else { - recovery.cancel(); - ScreenHandler.GotoScreen(DGUSLCD_SCREEN_STATUS); - } - } - -#endif - -void DGUSScreenHandler::HandleSettings(DGUS_VP_Variable &var, void *val_ptr) { - DEBUG_ECHOLNPGM("HandleSettings"); - uint16_t value = swap16(*(uint16_t*)val_ptr); - switch (value) { - default: break; - case 1: - TERN_(PRINTCOUNTER, print_job_timer.initStats()); - queue.inject_P(PSTR("M502\nM500")); - break; - case 2: queue.inject_P(PSTR("M501")); break; - case 3: queue.inject_P(PSTR("M500")); break; - } -} - -void DGUSScreenHandler::HandleStepPerMMChanged(DGUS_VP_Variable &var, void *val_ptr) { - DEBUG_ECHOLNPGM("HandleStepPerMMChanged"); - - uint16_t value_raw = swap16(*(uint16_t*)val_ptr); - DEBUG_ECHOLNPAIR("value_raw:", value_raw); - float value = (float)value_raw/10; - ExtUI::axis_t axis; - switch (var.VP) { - case VP_X_STEP_PER_MM: axis = ExtUI::axis_t::X; break; - case VP_Y_STEP_PER_MM: axis = ExtUI::axis_t::Y; break; - case VP_Z_STEP_PER_MM: axis = ExtUI::axis_t::Z; break; - default: return; - } - DEBUG_ECHOLNPAIR_F("value:", value); - ExtUI::setAxisSteps_per_mm(value, axis); - DEBUG_ECHOLNPAIR_F("value_set:", ExtUI::getAxisSteps_per_mm(axis)); - ScreenHandler.skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel - return; -} - -void DGUSScreenHandler::HandleStepPerMMExtruderChanged(DGUS_VP_Variable &var, void *val_ptr) { - DEBUG_ECHOLNPGM("HandleStepPerMMExtruderChanged"); - - uint16_t value_raw = swap16(*(uint16_t*)val_ptr); - DEBUG_ECHOLNPAIR("value_raw:", value_raw); - float value = (float)value_raw/10; - ExtUI::extruder_t extruder; - switch (var.VP) { - default: return; - #if HOTENDS >= 1 - case VP_E0_STEP_PER_MM: extruder = ExtUI::extruder_t::E0; break; - #endif - #if HOTENDS >= 2 - case VP_E1_STEP_PER_MM: extruder = ExtUI::extruder_t::E1; break; - #endif - } - DEBUG_ECHOLNPAIR_F("value:", value); - ExtUI::setAxisSteps_per_mm(value,extruder); - DEBUG_ECHOLNPAIR_F("value_set:", ExtUI::getAxisSteps_per_mm(extruder)); - ScreenHandler.skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel - return; -} - -#if HAS_PID_HEATING - void DGUSScreenHandler::HandleTemperaturePIDChanged(DGUS_VP_Variable &var, void *val_ptr) { - uint16_t rawvalue = swap16(*(uint16_t*)val_ptr); - DEBUG_ECHOLNPAIR("V1:", rawvalue); - float value = (float)rawvalue / 10; - DEBUG_ECHOLNPAIR("V2:", value); - float newvalue = 0; - - switch (var.VP) { - default: return; - #if HOTENDS >= 1 - case VP_E0_PID_P: newvalue = value; break; - case VP_E0_PID_I: newvalue = scalePID_i(value); break; - case VP_E0_PID_D: newvalue = scalePID_d(value); break; - #endif - #if HOTENDS >= 2 - case VP_E1_PID_P: newvalue = value; break; - case VP_E1_PID_I: newvalue = scalePID_i(value); break; - case VP_E1_PID_D: newvalue = scalePID_d(value); break; - #endif - #if HAS_HEATED_BED - case VP_BED_PID_P: newvalue = value; break; - case VP_BED_PID_I: newvalue = scalePID_i(value); break; - case VP_BED_PID_D: newvalue = scalePID_d(value); break; - #endif - } - - DEBUG_ECHOLNPAIR_F("V3:", newvalue); - *(float *)var.memadr = newvalue; - ScreenHandler.skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel - } - - void DGUSScreenHandler::HandlePIDAutotune(DGUS_VP_Variable &var, void *val_ptr) { - DEBUG_ECHOLNPGM("HandlePIDAutotune"); - - char buf[32] = {0}; - - switch (var.VP) { - default: break; - #if ENABLED(PIDTEMP) - #if HOTENDS >= 1 - case VP_PID_AUTOTUNE_E0: // Autotune Extruder 0 - sprintf(buf, "M303 E%d C5 S210 U1", ExtUI::extruder_t::E0); - break; - #endif - #if HOTENDS >= 2 - case VP_PID_AUTOTUNE_E1: - sprintf(buf, "M303 E%d C5 S210 U1", ExtUI::extruder_t::E1); - break; - #endif - #endif - #if ENABLED(PIDTEMPBED) - case VP_PID_AUTOTUNE_BED: - sprintf(buf, "M303 E-1 C5 S70 U1"); - break; - #endif - } - - if (buf[0]) queue.enqueue_one_now(buf); - - #if ENABLED(DGUS_UI_WAITING) - sendinfoscreen(PSTR("PID is autotuning"), PSTR("please wait"), NUL_STR, NUL_STR, true, true, true, true); - GotoScreen(DGUSLCD_SCREEN_WAITING); - #endif - } -#endif - -#if HAS_BED_PROBE - void DGUSScreenHandler::HandleProbeOffsetZChanged(DGUS_VP_Variable &var, void *val_ptr) { - DEBUG_ECHOLNPGM("HandleProbeOffsetZChanged"); - - const float offset = float(int16_t(swap16(*(uint16_t*)val_ptr))) / 100.0f; - ExtUI::setZOffset_mm(offset); - ScreenHandler.skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel - return; - } -#endif - -#if ENABLED(BABYSTEPPING) - void DGUSScreenHandler::HandleLiveAdjustZ(DGUS_VP_Variable &var, void *val_ptr) { - DEBUG_ECHOLNPGM("HandleLiveAdjustZ"); - - int16_t flag = swap16(*(uint16_t*)val_ptr); - int16_t steps = flag ? -20 : 20; - ExtUI::smartAdjustAxis_steps(steps, ExtUI::axis_t::Z, true); - ScreenHandler.ForceCompleteUpdate(); - return; - } -#endif - -#if HAS_FAN - void DGUSScreenHandler::HandleFanControl(DGUS_VP_Variable &var, void *val_ptr) { - DEBUG_ECHOLNPGM("HandleFanControl"); - *(uint8_t*)var.memadr = *(uint8_t*)var.memadr > 0 ? 0 : 255; - } -#endif - -void DGUSScreenHandler::HandleHeaterControl(DGUS_VP_Variable &var, void *val_ptr) { - DEBUG_ECHOLNPGM("HandleHeaterControl"); - - uint8_t preheat_temp = 0; - switch (var.VP) { - #if HOTENDS >= 1 - case VP_E0_CONTROL: - #endif - #if HOTENDS >= 2 - case VP_E1_CONTROL: - #endif - #if HOTENDS >= 3 - case VP_E2_CONTROL: - #endif - preheat_temp = PREHEAT_1_TEMP_HOTEND; - break; - - case VP_BED_CONTROL: - preheat_temp = PREHEAT_1_TEMP_BED; - break; - } - - *(int16_t*)var.memadr = *(int16_t*)var.memadr > 0 ? 0 : preheat_temp; -} - -#if ENABLED(DGUS_PREHEAT_UI) - - void DGUSScreenHandler::HandlePreheat(DGUS_VP_Variable &var, void *val_ptr) { - DEBUG_ECHOLNPGM("HandlePreheat"); - - uint8_t e_temp = 0; - TERN_(HAS_HEATED_BED, uint8_t bed_temp = 0); - const uint16_t preheat_option = swap16(*(uint16_t*)val_ptr); - switch (preheat_option) { - default: - case 0: // Preheat PLA - #if defined(PREHEAT_1_TEMP_HOTEND) && defined(PREHEAT_1_TEMP_BED) - e_temp = PREHEAT_1_TEMP_HOTEND; - TERN_(HAS_HEATED_BED, bed_temp = PREHEAT_1_TEMP_BED); - #endif - break; - case 1: // Preheat ABS - #if defined(PREHEAT_2_TEMP_HOTEND) && defined(PREHEAT_2_TEMP_BED) - e_temp = PREHEAT_2_TEMP_HOTEND; - TERN_(HAS_HEATED_BED, bed_temp = PREHEAT_2_TEMP_BED); - #endif - break; - case 2: // Preheat PET - #if defined(PREHEAT_3_TEMP_HOTEND) && defined(PREHEAT_3_TEMP_BED) - e_temp = PREHEAT_3_TEMP_HOTEND; - TERN_(HAS_HEATED_BED, bed_temp = PREHEAT_3_TEMP_BED); - #endif - break; - case 3: // Preheat FLEX - #if defined(PREHEAT_4_TEMP_HOTEND) && defined(PREHEAT_4_TEMP_BED) - e_temp = PREHEAT_4_TEMP_HOTEND; - TERN_(HAS_HEATED_BED, bed_temp = PREHEAT_4_TEMP_BED); - #endif - break; - case 7: break; // Custom preheat - case 9: break; // Cool down - } - - switch (var.VP) { - default: return; - #if HOTENDS >= 1 - case VP_E0_BED_PREHEAT: - thermalManager.setTargetHotend(e_temp, 0); - TERN_(HAS_HEATED_BED, thermalManager.setTargetBed(bed_temp)); - break; - #endif - #if HOTENDS >= 2 - case VP_E1_BED_PREHEAT: - thermalManager.setTargetHotend(e_temp, 1); - TERN_(HAS_HEATED_BED, thermalManager.setTargetBed(bed_temp)); - break; - #endif - } - - // Go to the preheat screen to show the heating progress - GotoScreen(DGUSLCD_SCREEN_PREHEAT); - } - -#endif - -#if ENABLED(DGUS_FILAMENT_LOADUNLOAD) - - typedef struct { - ExtUI::extruder_t extruder; // which extruder to operate - uint8_t action; // load or unload - bool heated; // heating done ? - float purge_length; // the length to extrude before unload, prevent filament jam - } filament_data_t; - - static filament_data_t filament_data; - - void DGUSScreenHandler::HandleFilamentOption(DGUS_VP_Variable &var, void *val_ptr) { - DEBUG_ECHOLNPGM("HandleFilamentOption"); - - uint8_t e_temp = 0; - filament_data.heated = false; - uint16_t preheat_option = swap16(*(uint16_t*)val_ptr); - if (preheat_option <= 8) // Load filament type - filament_data.action = 1; - else if (preheat_option >= 10) { // Unload filament type - preheat_option -= 10; - filament_data.action = 2; - filament_data.purge_length = DGUS_FILAMENT_PURGE_LENGTH; - } - else // Cancel filament operation - filament_data.action = 0; - - switch (preheat_option) { - case 0: // Load PLA - #ifdef PREHEAT_1_TEMP_HOTEND - e_temp = PREHEAT_1_TEMP_HOTEND; - #endif - break; - case 1: // Load ABS - TERN_(PREHEAT_2_TEMP_HOTEND, e_temp = PREHEAT_2_TEMP_HOTEND); - break; - case 2: // Load PET - #ifdef PREHEAT_3_TEMP_HOTEND - e_temp = PREHEAT_3_TEMP_HOTEND; - #endif - break; - case 3: // Load FLEX - #ifdef PREHEAT_4_TEMP_HOTEND - e_temp = PREHEAT_4_TEMP_HOTEND; - #endif - break; - case 9: // Cool down - default: - e_temp = 0; - break; - } - - if (filament_data.action == 0) { // Go back to utility screen - #if HOTENDS >= 1 - thermalManager.setTargetHotend(e_temp, ExtUI::extruder_t::E0); - #endif - #if HOTENDS >= 2 - thermalManager.setTargetHotend(e_temp, ExtUI::extruder_t::E1); - #endif - GotoScreen(DGUSLCD_SCREEN_UTILITY); - } - else { // Go to the preheat screen to show the heating progress - switch (var.VP) { - default: return; - #if HOTENDS >= 1 - case VP_E0_FILAMENT_LOAD_UNLOAD: - filament_data.extruder = ExtUI::extruder_t::E0; - thermalManager.setTargetHotend(e_temp, filament_data.extruder); - break; - #endif - #if HOTENDS >= 2 - case VP_E1_FILAMENT_LOAD_UNLOAD: - filament_data.extruder = ExtUI::extruder_t::E1; - thermalManager.setTargetHotend(e_temp, filament_data.extruder); - break; - #endif - } - GotoScreen(DGUSLCD_SCREEN_FILAMENT_HEATING); - } - } - - void DGUSScreenHandler::HandleFilamentLoadUnload(DGUS_VP_Variable &var) { - DEBUG_ECHOLNPGM("HandleFilamentLoadUnload"); - if (filament_data.action <= 0) return; - - // If we close to the target temperature, we can start load or unload the filament - if (thermalManager.hotEnoughToExtrude(filament_data.extruder) && \ - thermalManager.targetHotEnoughToExtrude(filament_data.extruder)) { - float movevalue = DGUS_FILAMENT_LOAD_LENGTH_PER_TIME; - - if (filament_data.action == 1) { // load filament - if (!filament_data.heated) { - GotoScreen(DGUSLCD_SCREEN_FILAMENT_LOADING); - filament_data.heated = true; - } - movevalue = ExtUI::getAxisPosition_mm(filament_data.extruder)+movevalue; - } - else { // unload filament - if (!filament_data.heated) { - GotoScreen(DGUSLCD_SCREEN_FILAMENT_UNLOADING); - filament_data.heated = true; - } - // Before unloading extrude to prevent jamming - if (filament_data.purge_length >= 0) { - movevalue = ExtUI::getAxisPosition_mm(filament_data.extruder) + movevalue; - filament_data.purge_length -= movevalue; - } - else - movevalue = ExtUI::getAxisPosition_mm(filament_data.extruder) - movevalue; - } - ExtUI::setAxisPosition_mm(movevalue, filament_data.extruder); - } - } -#endif - -void DGUSScreenHandler::UpdateNewScreen(DGUSLCD_Screens newscreen, bool popup) { - DEBUG_ECHOLNPAIR("SetNewScreen: ", newscreen); - - if (!popup) { - memmove(&past_screens[1], &past_screens[0], sizeof(past_screens) - 1); - past_screens[0] = current_screen; - } - - current_screen = newscreen; - skipVP = 0; - ForceCompleteUpdate(); -} - -void DGUSScreenHandler::PopToOldScreen() { - DEBUG_ECHOLNPAIR("PopToOldScreen s=", past_screens[0]); - GotoScreen(past_screens[0], true); - memmove(&past_screens[0], &past_screens[1], sizeof(past_screens) - 1); - past_screens[sizeof(past_screens) - 1] = DGUSLCD_SCREEN_MAIN; -} - -void DGUSScreenHandler::UpdateScreenVPData() { - DEBUG_ECHOPAIR(" UpdateScreenVPData Screen: ", current_screen); - - const uint16_t *VPList = DGUSLCD_FindScreenVPMapList(current_screen); - if (!VPList) { - DEBUG_ECHOLNPAIR(" NO SCREEN FOR: ", current_screen); - ScreenComplete = true; - return; // nothing to do, likely a bug or boring screen. - } - - // Round-robin updating of all VPs. - VPList += update_ptr; - - bool sent_one = false; - do { - uint16_t VP = pgm_read_word(VPList); - DEBUG_ECHOPAIR(" VP: ", VP); - if (!VP) { - update_ptr = 0; - DEBUG_ECHOLNPGM(" UpdateScreenVPData done"); - ScreenComplete = true; - return; // Screen completed. - } - - if (VP == skipVP) { skipVP = 0; continue; } - - DGUS_VP_Variable rcpy; - if (populate_VPVar(VP, &rcpy)) { - uint8_t expected_tx = 6 + rcpy.size; // expected overhead is 6 bytes + payload. - // Send the VP to the display, but try to avoid overrunning the Tx Buffer. - // But send at least one VP, to avoid getting stalled. - if (rcpy.send_to_display_handler && (!sent_one || expected_tx <= dgusdisplay.GetFreeTxBuffer())) { - //DEBUG_ECHOPAIR(" calling handler for ", rcpy.VP); - sent_one = true; - rcpy.send_to_display_handler(rcpy); - } - else { - //auto x=dgusdisplay.GetFreeTxBuffer(); - //DEBUG_ECHOLNPAIR(" tx almost full: ", x); - //DEBUG_ECHOPAIR(" update_ptr ", update_ptr); - ScreenComplete = false; - return; // please call again! - } - } - - } while (++update_ptr, ++VPList, true); -} - -void DGUSScreenHandler::GotoScreen(DGUSLCD_Screens screen, bool ispopup) { - dgusdisplay.RequestScreen(screen); - UpdateNewScreen(screen, ispopup); -} - -bool DGUSScreenHandler::loop() { - dgusdisplay.loop(); - - const millis_t ms = millis(); - static millis_t next_event_ms = 0; - - if (!IsScreenComplete() || ELAPSED(ms, next_event_ms)) { - next_event_ms = ms + DGUS_UPDATE_INTERVAL_MS; - UpdateScreenVPData(); - } - - #if ENABLED(SHOW_BOOTSCREEN) - static bool booted = false; - if (!booted && TERN0(POWER_LOSS_RECOVERY, recovery.valid())) - booted = true; - if (!booted && ELAPSED(ms, BOOTSCREEN_TIMEOUT)) { - booted = true; - GotoScreen(DGUSLCD_SCREEN_MAIN); - } - #endif - return IsScreenComplete(); -} - -void DGUSDisplay::RequestScreen(DGUSLCD_Screens screen) { - DEBUG_ECHOLNPAIR("GotoScreen ", screen); - const unsigned char gotoscreen[] = { 0x5A, 0x01, (unsigned char) (screen >> 8U), (unsigned char) (screen & 0xFFU) }; - WriteVariable(0x84, gotoscreen, sizeof(gotoscreen)); -} - -#endif // HAS_DGUS_LCD diff --git a/Marlin/src/lcd/extui/lib/dgus/DGUSScreenHandler.h b/Marlin/src/lcd/extui/lib/dgus/DGUSScreenHandler.h deleted file mode 100644 index df738dbfd144..000000000000 --- a/Marlin/src/lcd/extui/lib/dgus/DGUSScreenHandler.h +++ /dev/null @@ -1,232 +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 - -#include "DGUSDisplay.h" -#include "DGUSVPVariable.h" - -#include "../../../../inc/MarlinConfig.h" - -enum DGUSLCD_Screens : uint8_t; - -class DGUSScreenHandler { -public: - DGUSScreenHandler() = default; - - static bool loop(); - - /// Send all 4 strings that are displayed on the infoscreen, confirmation screen and kill screen - /// The bools specifing whether the strings are in RAM or FLASH. - static void sendinfoscreen(const char* line1, const char* line2, const char* line3, const char* line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); - - static void HandleUserConfirmationPopUp(uint16_t ConfirmVP, const char* line1, const char* line2, const char* line3, const char* line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); - - /// "M117" Message -- msg is a RAM ptr. - static void setstatusmessage(const char* msg); - /// The same for messages from Flash - static void setstatusmessagePGM(PGM_P const msg); - // Callback for VP "Display wants to change screen on idle printer" - static void ScreenChangeHookIfIdle(DGUS_VP_Variable &var, void *val_ptr); - // Callback for VP "Screen has been changed" - static void ScreenChangeHook(DGUS_VP_Variable &var, void *val_ptr); - // Callback for VP "All Heaters Off" - static void HandleAllHeatersOff(DGUS_VP_Variable &var, void *val_ptr); - // Hook for "Change this temperature" - static void HandleTemperatureChanged(DGUS_VP_Variable &var, void *val_ptr); - // Hook for "Change Flowrate" - static void HandleFlowRateChanged(DGUS_VP_Variable &var, void *val_ptr); - #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - // Hook for manual move option - static void HandleManualMoveOption(DGUS_VP_Variable &var, void *val_ptr); - #endif - // Hook for manual move. - static void HandleManualMove(DGUS_VP_Variable &var, void *val_ptr); - // Hook for manual extrude. - static void HandleManualExtrude(DGUS_VP_Variable &var, void *val_ptr); - // Hook for motor lock and unlook - static void HandleMotorLockUnlock(DGUS_VP_Variable &var, void *val_ptr); - #if ENABLED(POWER_LOSS_RECOVERY) - // Hook for power loss recovery. - static void HandlePowerLossRecovery(DGUS_VP_Variable &var, void *val_ptr); - #endif - // Hook for settings - static void HandleSettings(DGUS_VP_Variable &var, void *val_ptr); - static void HandleStepPerMMChanged(DGUS_VP_Variable &var, void *val_ptr); - static void HandleStepPerMMExtruderChanged(DGUS_VP_Variable &var, void *val_ptr); - #if HAS_PID_HEATING - // Hook for "Change this temperature PID para" - static void HandleTemperaturePIDChanged(DGUS_VP_Variable &var, void *val_ptr); - // Hook for PID autotune - static void HandlePIDAutotune(DGUS_VP_Variable &var, void *val_ptr); - #endif - #if HAS_BED_PROBE - // Hook for "Change probe offset z" - static void HandleProbeOffsetZChanged(DGUS_VP_Variable &var, void *val_ptr); - #endif - #if ENABLED(BABYSTEPPING) - // Hook for live z adjust action - static void HandleLiveAdjustZ(DGUS_VP_Variable &var, void *val_ptr); - #endif - #if HAS_FAN - // Hook for fan control - static void HandleFanControl(DGUS_VP_Variable &var, void *val_ptr); - #endif - // Hook for heater control - static void HandleHeaterControl(DGUS_VP_Variable &var, void *val_ptr); - #if ENABLED(DGUS_PREHEAT_UI) - // Hook for preheat - static void HandlePreheat(DGUS_VP_Variable &var, void *val_ptr); - #endif - #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) - // Hook for filament load and unload filament option - static void HandleFilamentOption(DGUS_VP_Variable &var, void *val_ptr); - // Hook for filament load and unload - static void HandleFilamentLoadUnload(DGUS_VP_Variable &var); - #endif - - #if ENABLED(SDSUPPORT) - // 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. - static void DGUSLCD_SD_ScrollFilelist(DGUS_VP_Variable &var, void *val_ptr); - /// File touched. - static void DGUSLCD_SD_FileSelected(DGUS_VP_Variable &var, void *val_ptr); - /// start print after confirmation received. - static void DGUSLCD_SD_StartPrint(DGUS_VP_Variable &var, void *val_ptr); - /// User hit the pause, resume or abort button. - static void DGUSLCD_SD_ResumePauseAbort(DGUS_VP_Variable &var, void *val_ptr); - /// User confirmed the abort action - static void DGUSLCD_SD_ReallyAbort(DGUS_VP_Variable &var, void *val_ptr); - /// User hit the tune button - static void DGUSLCD_SD_PrintTune(DGUS_VP_Variable &var, void *val_ptr); - /// Send a single filename to the display. - static void DGUSLCD_SD_SendFilename(DGUS_VP_Variable &var); - /// Marlin informed us that a new SD has been inserted. - static void SDCardInserted(); - /// Marlin informed us that the SD Card has been removed(). - static void SDCardRemoved(); - /// Marlin informed us about a bad SD Card. - static void SDCardError(); - #endif - - // OK Button the Confirm screen. - static void ScreenConfirmedOK(DGUS_VP_Variable &var, void *val_ptr); - - // Update data after went to new screen (by display or by GotoScreen) - // remember: store the last-displayed screen, so it can get returned to. - // (e.g for pop up messages) - static void UpdateNewScreen(DGUSLCD_Screens newscreen, bool popup=false); - - // Recall the remembered screen. - static void PopToOldScreen(); - - // Make the display show the screen and update all VPs in it. - static void GotoScreen(DGUSLCD_Screens screen, bool ispopup = false); - - static void UpdateScreenVPData(); - - // Helpers to convert and transfer data to the display. - static void DGUSLCD_SendWordValueToDisplay(DGUS_VP_Variable &var); - static void DGUSLCD_SendStringToDisplay(DGUS_VP_Variable &var); - static void DGUSLCD_SendStringToDisplayPGM(DGUS_VP_Variable &var); - static void DGUSLCD_SendTemperaturePID(DGUS_VP_Variable &var); - static void DGUSLCD_SendPercentageToDisplay(DGUS_VP_Variable &var); - static void DGUSLCD_SendPrintProgressToDisplay(DGUS_VP_Variable &var); - static void DGUSLCD_SendPrintTimeToDisplay(DGUS_VP_Variable &var); - #if ENABLED(PRINTCOUNTER) - static void DGUSLCD_SendPrintAccTimeToDisplay(DGUS_VP_Variable &var); - static void DGUSLCD_SendPrintsTotalToDisplay(DGUS_VP_Variable &var); - #endif - #if HAS_FAN - static void DGUSLCD_SendFanStatusToDisplay(DGUS_VP_Variable &var); - #endif - static void DGUSLCD_SendHeaterStatusToDisplay(DGUS_VP_Variable &var); - #if ENABLED(DGUS_UI_WAITING) - static void DGUSLCD_SendWaitingStatusToDisplay(DGUS_VP_Variable &var); - #endif - - /// Send a value from 0..100 to a variable with a range from 0..255 - static void DGUSLCD_PercentageToUint8(DGUS_VP_Variable &var, void *val_ptr); - - template - static void DGUSLCD_SetValueDirectly(DGUS_VP_Variable &var, void *val_ptr) { - if (!var.memadr) return; - union { unsigned char tmp[sizeof(T)]; T t; } x; - unsigned char *ptr = (unsigned char*)val_ptr; - LOOP_L_N(i, sizeof(T)) x.tmp[i] = ptr[sizeof(T) - i - 1]; - *(T*)var.memadr = x.t; - } - - /// Send a float value to the display. - /// Display will get a 4-byte integer scaled to the number of digits: - /// Tell the display the number of digits and it cheats by displaying a dot between... - template - static void DGUSLCD_SendFloatAsLongValueToDisplay(DGUS_VP_Variable &var) { - if (var.memadr) { - float f = *(float *)var.memadr; - f *= cpow(10, decimals); - dgusdisplay.WriteVariable(var.VP, (long)f); - } - } - - /// Send a float value to the display. - /// Display will get a 2-byte integer scaled to the number of digits: - /// Tell the display the number of digits and it cheats by displaying a dot between... - template - static void DGUSLCD_SendFloatAsIntValueToDisplay(DGUS_VP_Variable &var) { - if (var.memadr) { - float f = *(float *)var.memadr; - DEBUG_ECHOLNPAIR_F(" >> ", f, 6); - f *= cpow(10, decimals); - dgusdisplay.WriteVariable(var.VP, (int16_t)f); - } - } - - /// Force an update of all VP on the current screen. - static inline void ForceCompleteUpdate() { update_ptr = 0; ScreenComplete = false; } - /// Has all VPs sent to the screen - static inline bool IsScreenComplete() { return ScreenComplete; } - - static inline DGUSLCD_Screens getCurrentScreen() { return current_screen; } - - static inline void SetupConfirmAction( void (*f)()) { confirm_action_cb = f; } - -private: - static DGUSLCD_Screens current_screen; ///< currently on screen - static constexpr uint8_t NUM_PAST_SCREENS = 4; - static DGUSLCD_Screens past_screens[NUM_PAST_SCREENS]; ///< LIFO with past screens for the "back" button. - - static uint8_t update_ptr; ///< Last sent entry in the VPList for the actual screen. - static uint16_t skipVP; ///< When updating the screen data, skip this one, because the user is interacting with it. - static bool ScreenComplete; ///< All VPs sent to screen? - - static uint16_t ConfirmVP; ///< context for confirm screen (VP that will be emulated-sent on "OK"). - - #if ENABLED(SDSUPPORT) - static int16_t top_file; ///< file on top of file chooser - static int16_t file_to_print; ///< touched file to be confirmed - #endif - - static void (*confirm_action_cb)(); -}; - -extern DGUSScreenHandler ScreenHandler; diff --git a/Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSDisplayDef.cpp deleted file mode 100644 index 3beed892e35b..000000000000 --- a/Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSDisplayDef.cpp +++ /dev/null @@ -1,486 +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 . - * - */ - -/* DGUS VPs changed by George Fu in 2019 for Marlin */ - -#include "../../../../../inc/MarlinConfigPre.h" - -#if ENABLED(DGUS_LCD_UI_FYSETC) - -#include "../DGUSDisplayDef.h" -#include "../DGUSDisplay.h" -#include "../DGUSScreenHandler.h" - -#include "../../../../../module/temperature.h" -#include "../../../../../module/motion.h" -#include "../../../../../module/planner.h" - -#include "../../../ui_api.h" -#include "../../../../ultralcd.h" - -#if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - uint16_t distanceToMove = 10; -#endif - -const uint16_t VPList_Boot[] PROGMEM = { - VP_MARLIN_VERSION, - 0x0000 -}; - -const uint16_t VPList_Main[] PROGMEM = { - /* VP_M117, for completeness, but it cannot be auto-uploaded. */ - #if HOTENDS >= 1 - VP_T_E0_Is, VP_T_E0_Set, VP_E0_STATUS, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, - #endif - #if HAS_HEATED_BED - VP_T_Bed_Is, VP_T_Bed_Set, VP_BED_STATUS, - #endif - #if HAS_FAN - VP_Fan0_Percentage, VP_FAN0_STATUS, - #endif - VP_XPos, VP_YPos, VP_ZPos, - VP_Fan0_Percentage, - VP_Feedrate_Percentage, - #if ENABLED(LCD_SET_PROGRESS_MANUALLY) - VP_PrintProgress_Percentage, - #endif - 0x0000 -}; - -const uint16_t VPList_Temp[] PROGMEM = { - #if HOTENDS >= 1 - VP_T_E0_Is, VP_T_E0_Set, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, - #endif - #if HAS_HEATED_BED - VP_T_Bed_Is, VP_T_Bed_Set, - #endif - 0x0000 -}; - -const uint16_t VPList_Status[] PROGMEM = { - /* VP_M117, for completeness, but it cannot be auto-uploaded */ - #if HOTENDS >= 1 - VP_T_E0_Is, VP_T_E0_Set, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, - #endif - #if HAS_HEATED_BED - VP_T_Bed_Is, VP_T_Bed_Set, - #endif - #if HAS_FAN - VP_Fan0_Percentage, - #endif - VP_XPos, VP_YPos, VP_ZPos, - VP_Fan0_Percentage, - VP_Feedrate_Percentage, - VP_PrintProgress_Percentage, - 0x0000 -}; - -const uint16_t VPList_Status2[] PROGMEM = { - /* VP_M117, for completeness, but it cannot be auto-uploaded */ - #if HOTENDS >= 1 - VP_Flowrate_E0, - #endif - #if HOTENDS >= 2 - VP_Flowrate_E1, - #endif - VP_PrintProgress_Percentage, - VP_PrintTime, - 0x0000 -}; - -const uint16_t VPList_Preheat[] PROGMEM = { - #if HOTENDS >= 1 - VP_T_E0_Is, VP_T_E0_Set, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, - #endif - #if HAS_HEATED_BED - VP_T_Bed_Is, VP_T_Bed_Set, - #endif - 0x0000 -}; - -const uint16_t VPList_ManualMove[] PROGMEM = { - VP_XPos, VP_YPos, VP_ZPos, - 0x0000 -}; - -const uint16_t VPList_ManualExtrude[] PROGMEM = { - #if HOTENDS >= 1 - VP_T_E0_Is, VP_T_E0_Set, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, - #endif - VP_EPos, - 0x0000 -}; - -const uint16_t VPList_FanAndFeedrate[] PROGMEM = { - VP_Feedrate_Percentage, VP_Fan0_Percentage, - 0x0000 -}; - -const uint16_t VPList_SD_FlowRates[] PROGMEM = { - VP_Flowrate_E0, VP_Flowrate_E1, - 0x0000 -}; - -const uint16_t VPList_Filament_heating[] PROGMEM = { - #if HOTENDS >= 1 - VP_T_E0_Is, VP_T_E0_Set, - VP_E0_FILAMENT_LOAD_UNLOAD, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, - VP_E1_FILAMENT_LOAD_UNLOAD, - #endif - 0x0000 -}; - -const uint16_t VPList_Filament_load_unload[] PROGMEM = { - #if HOTENDS >= 1 - VP_E0_FILAMENT_LOAD_UNLOAD, - #endif - #if HOTENDS >= 2 - VP_E1_FILAMENT_LOAD_UNLOAD, - #endif - 0x0000 -}; - -const uint16_t VPList_SDFileList[] PROGMEM = { - VP_SD_FileName0, VP_SD_FileName1, VP_SD_FileName2, VP_SD_FileName3, VP_SD_FileName4, - 0x0000 -}; - -const uint16_t VPList_SD_PrintManipulation[] PROGMEM = { - VP_PrintProgress_Percentage, VP_PrintTime, - #if HOTENDS >= 1 - VP_T_E0_Is, VP_T_E0_Set, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, - #endif - #if HAS_HEATED_BED - VP_T_Bed_Is, VP_T_Bed_Set, - #endif - #if HAS_FAN - VP_Fan0_Percentage, - #if FAN_COUNT > 1 - VP_Fan1_Percentage, - #endif - #endif - VP_Flowrate_E0, - 0x0000 -}; - -const uint16_t VPList_SDPrintTune[] PROGMEM = { - #if HOTENDS >= 1 - VP_T_E0_Is, VP_T_E0_Set, VP_Flowrate_E0, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, VP_Flowrate_E1, - #endif - #if HAS_HEATED_BED - VP_T_Bed_Is, VP_T_Bed_Set, - #endif - VP_Feedrate_Percentage, - VP_SD_Print_ProbeOffsetZ, - 0x0000 -}; - -const uint16_t VPList_StepPerMM[] PROGMEM = { - VP_X_STEP_PER_MM, - VP_Y_STEP_PER_MM, - VP_Z_STEP_PER_MM, - #if HOTENDS >= 1 - VP_E0_STEP_PER_MM, - #endif - #if HOTENDS >= 2 - VP_E1_STEP_PER_MM, - #endif - 0x0000 -}; - -const uint16_t VPList_PIDE0[] PROGMEM = { - #if ENABLED(PIDTEMP) - VP_E0_PID_P, - VP_E0_PID_I, - VP_E0_PID_D, - #endif - 0x0000 -}; - -const uint16_t VPList_PIDBED[] PROGMEM = { - #if ENABLED(PIDTEMP) - VP_BED_PID_P, - VP_BED_PID_I, - VP_BED_PID_D, - #endif - 0x0000 -}; - -const uint16_t VPList_Infos[] PROGMEM = { - VP_MARLIN_VERSION, - VP_PrintTime, - #if ENABLED(PRINTCOUNTER) - VP_PrintAccTime, - VP_PrintsTotal, - #endif - 0x0000 -}; - -const uint16_t VPList_PIDTuningWaiting[] PROGMEM = { - VP_WAITING_STATUS, - 0x0000 -}; - -const uint16_t VPList_FLCPreheat[] PROGMEM = { - #if HOTENDS >= 1 - VP_T_E0_Is, VP_T_E0_Set, - #endif - #if HAS_HEATED_BED - VP_T_Bed_Is, VP_T_Bed_Set, - #endif - 0x0000 -}; - -const uint16_t VPList_FLCPrinting[] PROGMEM = { - #if HOTENDS >= 1 - VP_SD_Print_ProbeOffsetZ, - #endif - 0x0000 -}; - -const uint16_t VPList_Z_Offset[] PROGMEM = { - #if HOTENDS >= 1 - VP_SD_Print_ProbeOffsetZ, - #endif - 0x0000 -}; - -const struct VPMapping VPMap[] PROGMEM = { - { DGUSLCD_SCREEN_BOOT, VPList_Boot }, - { DGUSLCD_SCREEN_MAIN, VPList_Main }, - { DGUSLCD_SCREEN_TEMPERATURE, VPList_Temp }, - { DGUSLCD_SCREEN_STATUS, VPList_Status }, - { DGUSLCD_SCREEN_STATUS2, VPList_Status2 }, - { DGUSLCD_SCREEN_PREHEAT, VPList_Preheat }, - { DGUSLCD_SCREEN_MANUALMOVE, VPList_ManualMove }, - { DGUSLCD_SCREEN_MANUALEXTRUDE, VPList_ManualExtrude }, - { DGUSLCD_SCREEN_FILAMENT_HEATING, VPList_Filament_heating }, - { DGUSLCD_SCREEN_FILAMENT_LOADING, VPList_Filament_load_unload }, - { DGUSLCD_SCREEN_FILAMENT_UNLOADING, VPList_Filament_load_unload }, - { DGUSLCD_SCREEN_SDPRINTMANIPULATION, VPList_SD_PrintManipulation }, - { DGUSLCD_SCREEN_SDFILELIST, VPList_SDFileList }, - { DGUSLCD_SCREEN_SDPRINTTUNE, VPList_SDPrintTune }, - { DGUSLCD_SCREEN_WAITING, VPList_PIDTuningWaiting }, - { DGUSLCD_SCREEN_FLC_PREHEAT, VPList_FLCPreheat }, - { DGUSLCD_SCREEN_FLC_PRINTING, VPList_FLCPrinting }, - { DGUSLCD_SCREEN_Z_OFFSET, VPList_Z_Offset }, - { DGUSLCD_SCREEN_STEPPERMM, VPList_StepPerMM }, - { DGUSLCD_SCREEN_PID_E, VPList_PIDE0 }, - { DGUSLCD_SCREEN_PID_BED, VPList_PIDBED }, - { DGUSLCD_SCREEN_INFOS, VPList_Infos }, - { 0 , nullptr } // List is terminated with an nullptr as table entry. -}; - -const char MarlinVersion[] PROGMEM = SHORT_BUILD_VERSION; - -// Helper to define a DGUS_VP_Variable for common use cases. -#define VPHELPER(VPADR, VPADRVAR, RXFPTR, TXFPTR ) { .VP=VPADR, .memadr=VPADRVAR, .size=sizeof(VPADRVAR), \ - .set_by_display_handler = RXFPTR, .send_to_display_handler = TXFPTR } - -// Helper to define a DGUS_VP_Variable when the sizeo of the var cannot be determined automaticalyl (eg. a string) -#define VPHELPER_STR(VPADR, VPADRVAR, STRLEN, RXFPTR, TXFPTR ) { .VP=VPADR, .memadr=VPADRVAR, .size=STRLEN, \ - .set_by_display_handler = RXFPTR, .send_to_display_handler = TXFPTR } - -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) - VPHELPER(VP_SCREENCHANGE_WHENSD, nullptr, ScreenHandler.ScreenChangeHookIfSD, nullptr), - #endif - VPHELPER(VP_CONFIRMED, nullptr, ScreenHandler.ScreenConfirmedOK, nullptr), - - VPHELPER(VP_TEMP_ALL_OFF, nullptr, &ScreenHandler.HandleAllHeatersOff, nullptr), - #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - VPHELPER(VP_MOVE_OPTION, &distanceToMove, &ScreenHandler.HandleManualMoveOption, nullptr), - #endif - #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - VPHELPER(VP_MOVE_X, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Y, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Z, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_HOME_ALL, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), - #else - VPHELPER(VP_MOVE_X, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Y, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Z, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_HOME_ALL, nullptr, &ScreenHandler.HandleManualMove, nullptr), - #endif - VPHELPER(VP_MOTOR_LOCK_UNLOK, nullptr, &ScreenHandler.HandleMotorLockUnlock, nullptr), - #if ENABLED(POWER_LOSS_RECOVERY) - VPHELPER(VP_POWER_LOSS_RECOVERY, nullptr, &ScreenHandler.HandlePowerLossRecovery, nullptr), - #endif - VPHELPER(VP_SETTINGS, nullptr, &ScreenHandler.HandleSettings, nullptr), - #if ENABLED(SINGLE_Z_CALIBRATION) - VPHELPER(VP_Z_CALIBRATE, nullptr, &ScreenHandler.HandleZCalibration, nullptr), - #endif - - #if ENABLED(FIRST_LAYER_CAL) - VPHELPER(VP_Z_FIRST_LAYER_CAL, nullptr, &ScreenHandler.HandleFirstLayerCal, nullptr), - #endif - - { .VP = VP_MARLIN_VERSION, .memadr = (void*)MarlinVersion, .size = VP_MARLIN_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler =&ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - // M117 LCD String (We don't need the string in memory but "just" push it to the display on demand, hence the nullptr - { .VP = VP_M117, .memadr = nullptr, .size = VP_M117_LEN, .set_by_display_handler = nullptr, .send_to_display_handler =&ScreenHandler.DGUSLCD_SendStringToDisplay }, - - // Temperature Data - #if HOTENDS >= 1 - VPHELPER(VP_T_E0_Is, &thermalManager.temp_hotend[0].celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), - VPHELPER(VP_T_E0_Set, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleTemperatureChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Flowrate_E0, &planner.flow_percentage[ExtUI::extruder_t::E0], ScreenHandler.HandleFlowRateChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_EPos, &destination.e, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), - VPHELPER(VP_MOVE_E0, nullptr, &ScreenHandler.HandleManualExtrude, nullptr), - VPHELPER(VP_E0_CONTROL, &thermalManager.temp_hotend[0].target, &ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_E0_STATUS, &thermalManager.temp_hotend[0].target, nullptr, &ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), - #if ENABLED(DGUS_PREHEAT_UI) - VPHELPER(VP_E0_BED_PREHEAT, nullptr, &ScreenHandler.HandlePreheat, nullptr), - #endif - #if ENABLED(PIDTEMP) - VPHELPER(VP_E0_PID_P, &thermalManager.temp_hotend[0].pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_E0_PID_I, &thermalManager.temp_hotend[0].pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_E0_PID_D, &thermalManager.temp_hotend[0].pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_PID_AUTOTUNE_E0, nullptr, &ScreenHandler.HandlePIDAutotune, nullptr), - #endif - #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) - VPHELPER(VP_E0_FILAMENT_LOAD_UNLOAD, nullptr, &ScreenHandler.HandleFilamentOption, &ScreenHandler.HandleFilamentLoadUnload), - #endif - #endif - #if HOTENDS >= 2 - VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), - VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleTemperatureChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Flowrate_E1, &planner.flow_percentage[ExtUI::extruder_t::E1], ScreenHandler.HandleFlowRateChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_MOVE_E1, nullptr, &ScreenHandler.HandleManualExtrude, nullptr), - VPHELPER(VP_E1_CONTROL, &thermalManager.temp_hotend[1].target, &ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_E1_STATUS, &thermalManager.temp_hotend[1].target, nullptr, &ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), - #if ENABLED(PIDTEMP) - VPHELPER(VP_PID_AUTOTUNE_E1, nullptr, &ScreenHandler.HandlePIDAutotune, nullptr), - #endif - VPHELPER(VP_E1_FILAMENT_LOAD_UNLOAD, nullptr, &ScreenHandler.HandleFilamentOption, &ScreenHandler.HandleFilamentLoadUnload), - #endif - #if HAS_HEATED_BED - VPHELPER(VP_T_Bed_Is, &thermalManager.temp_bed.celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), - VPHELPER(VP_T_Bed_Set, &thermalManager.temp_bed.target, ScreenHandler.HandleTemperatureChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_BED_CONTROL, &thermalManager.temp_bed.target, &ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_BED_STATUS, &thermalManager.temp_bed.target, nullptr, &ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), - #if ENABLED(PIDTEMPBED) - VPHELPER(VP_BED_PID_P, &thermalManager.temp_bed.pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_BED_PID_I, &thermalManager.temp_bed.pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_BED_PID_D, &thermalManager.temp_bed.pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_PID_AUTOTUNE_BED, nullptr, &ScreenHandler.HandlePIDAutotune, nullptr), - #endif - #endif - - // Fan Data - #if HAS_FAN - #define FAN_VPHELPER(N) \ - VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], ScreenHandler.DGUSLCD_PercentageToUint8, &ScreenHandler.DGUSLCD_SendPercentageToDisplay), \ - VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], &ScreenHandler.HandleFanControl, nullptr), \ - VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, &ScreenHandler.DGUSLCD_SendFanStatusToDisplay), - REPEAT(FAN_COUNT, FAN_VPHELPER) - #endif - - // Feedrate - VPHELPER(VP_Feedrate_Percentage, &feedrate_percentage, ScreenHandler.DGUSLCD_SetValueDirectly, &ScreenHandler.DGUSLCD_SendWordValueToDisplay ), - - // Position Data - VPHELPER(VP_XPos, ¤t_position.x, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), - VPHELPER(VP_YPos, ¤t_position.y, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), - VPHELPER(VP_ZPos, ¤t_position.z, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), - - // Print Progress - VPHELPER(VP_PrintProgress_Percentage, nullptr, nullptr, ScreenHandler.DGUSLCD_SendPrintProgressToDisplay ), - - // Print Time - VPHELPER_STR(VP_PrintTime, nullptr, VP_PrintTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintTimeToDisplay), - #if ENABLED(PRINTCOUNTER) - VPHELPER_STR(VP_PrintAccTime, nullptr, VP_PrintAccTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintAccTimeToDisplay), - VPHELPER_STR(VP_PrintsTotal, nullptr, VP_PrintsTotal_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintsTotalToDisplay), - #endif - - VPHELPER(VP_X_STEP_PER_MM, &planner.settings.axis_steps_per_mm[X_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), - VPHELPER(VP_Y_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Y_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), - VPHELPER(VP_Z_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Z_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), - #if HOTENDS >= 1 - VPHELPER(VP_E0_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(0)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), - #endif - #if HOTENDS >= 2 - VPHELPER(VP_E1_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(1)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), - #endif - - // SDCard File listing. - #if ENABLED(SDSUPPORT) - VPHELPER(VP_SD_ScrollEvent, nullptr, ScreenHandler.DGUSLCD_SD_ScrollFilelist, nullptr), - VPHELPER(VP_SD_FileSelected, nullptr, ScreenHandler.DGUSLCD_SD_FileSelected, nullptr), - VPHELPER(VP_SD_FileSelectConfirm, nullptr, ScreenHandler.DGUSLCD_SD_StartPrint, nullptr), - VPHELPER_STR(VP_SD_FileName0, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), - VPHELPER_STR(VP_SD_FileName1, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), - VPHELPER_STR(VP_SD_FileName2, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), - VPHELPER_STR(VP_SD_FileName3, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), - VPHELPER_STR(VP_SD_FileName4, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), - VPHELPER(VP_SD_ResumePauseAbort, nullptr, ScreenHandler.DGUSLCD_SD_ResumePauseAbort, nullptr), - VPHELPER(VP_SD_AbortPrintConfirmed, nullptr, ScreenHandler.DGUSLCD_SD_ReallyAbort, nullptr), - VPHELPER(VP_SD_Print_Setting, nullptr, ScreenHandler.DGUSLCD_SD_PrintTune, nullptr), - #if HAS_BED_PROBE - VPHELPER(VP_SD_Print_ProbeOffsetZ, &probe.offset.z, ScreenHandler.HandleProbeOffsetZChanged, &ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<2>), - #if ENABLED(BABYSTEPPING) - VPHELPER(VP_SD_Print_LiveAdjustZ, nullptr, ScreenHandler.HandleLiveAdjustZ, nullptr), - #endif - #endif - #endif - - #if ENABLED(DGUS_UI_WAITING) - VPHELPER(VP_WAITING_STATUS, nullptr, nullptr, ScreenHandler.DGUSLCD_SendWaitingStatusToDisplay), - #endif - - // Messages for the User, shared by the popup and the kill screen. They cant be autouploaded as we do not buffer content. - { .VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - - VPHELPER(0, 0, 0, 0) // must be last entry. -}; - -#endif // DGUS_LCD_UI_FYSETC diff --git a/Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSDisplayDef.h b/Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSDisplayDef.h deleted file mode 100644 index f6a65fe8a061..000000000000 --- a/Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSDisplayDef.h +++ /dev/null @@ -1,294 +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 - -enum DGUSLCD_Screens : uint8_t { - DGUSLCD_SCREEN_BOOT = 0, - DGUSLCD_SCREEN_MAIN = 1, - DGUSLCD_SCREEN_STATUS = 1, - DGUSLCD_SCREEN_STATUS2 = 1, - DGUSLCD_SCREEN_TEMPERATURE = 10, - DGUSLCD_SCREEN_PREHEAT = 18, - DGUSLCD_SCREEN_POWER_LOSS = 100, - DGUSLCD_SCREEN_MANUALMOVE = 192, - DGUSLCD_SCREEN_UTILITY = 120, - DGUSLCD_SCREEN_FILAMENT_HEATING = 146, - DGUSLCD_SCREEN_FILAMENT_LOADING = 148, - DGUSLCD_SCREEN_FILAMENT_UNLOADING = 158, - DGUSLCD_SCREEN_MANUALEXTRUDE = 160, - DGUSLCD_SCREEN_SDFILELIST = 71, - DGUSLCD_SCREEN_SDPRINTMANIPULATION = 73, - DGUSLCD_SCREEN_SDPRINTTUNE = 75, - DGUSLCD_SCREEN_FLC_PREHEAT = 94, - DGUSLCD_SCREEN_FLC_PRINTING = 96, - DGUSLCD_SCREEN_STEPPERMM = 212, - DGUSLCD_SCREEN_PID_E = 214, - DGUSLCD_SCREEN_PID_BED = 218, - DGUSLCD_SCREEN_Z_OFFSET = 222, - DGUSLCD_SCREEN_INFOS = 36, - DGUSLCD_SCREEN_CONFIRM = 240, - DGUSLCD_SCREEN_KILL = 250, ///< Kill Screen. Must always be 250 (to be able to display "Error wrong LCD Version") - DGUSLCD_SCREEN_WAITING = 251, - DGUSLCD_SCREEN_POPUP = 252, ///< special target, popup screen will also return this code to say "return to previous screen" - DGUSLDC_SCREEN_UNUSED = 255 -}; - -// Display Memory layout used (T5UID) -// Except system variables this is arbitrary, just to organize stuff.... - -// 0x0000 .. 0x0FFF -- System variables and reserved by the display -// 0x1000 .. 0x1FFF -- Variables to never change location, regardless of UI Version -// 0x2000 .. 0x2FFF -- Controls (VPs that will trigger some action) -// 0x3000 .. 0x4FFF -- Marlin Data to be displayed -// 0x5000 .. -- SPs (if we want to modify display elements, e.g change color or like) -- currently unused - -// As there is plenty of space (at least most displays have >8k RAM), we do not pack them too tight, -// so that we can keep variables nicely together in the address space. - -// UI Version always on 0x1000...0x1002 so that the firmware can check this and bail out. -constexpr uint16_t VP_UI_VERSION_MAJOR = 0x1000; // Major -- incremented when incompatible -constexpr uint16_t VP_UI_VERSION_MINOR = 0x1001; // Minor -- incremented on new features, but compatible -constexpr uint16_t VP_UI_VERSION_PATCH = 0x1002; // Patch -- fixed which do not change functionality. -constexpr uint16_t VP_UI_FLAVOUR = 0x1010; // lets reserve 16 bytes here to determine if UI is suitable for this Marlin. tbd. - -// Storage space for the Killscreen messages. 0x1100 - 0x1200 . Reused for the popup. -constexpr uint16_t VP_MSGSTR1 = 0x1100; -constexpr uint8_t VP_MSGSTR1_LEN = 0x20; // might be more place for it... -constexpr uint16_t VP_MSGSTR2 = 0x1140; -constexpr uint8_t VP_MSGSTR2_LEN = 0x20; -constexpr uint16_t VP_MSGSTR3 = 0x1180; -constexpr uint8_t VP_MSGSTR3_LEN = 0x20; -constexpr uint16_t VP_MSGSTR4 = 0x11C0; -constexpr uint8_t VP_MSGSTR4_LEN = 0x20; - -// Screenchange request for screens that only make sense when printer is idle. -// e.g movement is only allowed if printer is not printing. -// Marlin must confirm by setting the screen manually. -constexpr uint16_t VP_SCREENCHANGE_ASK = 0x2000; -constexpr uint16_t VP_SCREENCHANGE = 0x2001; // 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 = 0x2002; // Turn all heaters off. Value arbitrary ;)= -constexpr uint16_t VP_SCREENCHANGE_WHENSD = 0x2003; // "Print" Button touched -- go only there if there is an SD Card. - -constexpr uint16_t VP_CONFIRMED = 0x2010; // OK on confirm screen. - -// Buttons on the SD-Card File listing. -constexpr uint16_t VP_SD_ScrollEvent = 0x2020; // Data: 0 for "up a directory", numbers are the amount to scroll, e.g -1 one up, 1 one down -constexpr uint16_t VP_SD_FileSelected = 0x2022; // Number of file field selected. -constexpr uint16_t VP_SD_FileSelectConfirm = 0x2024; // (This is a virtual VP and emulated by the Confirm Screen when a file has been confirmed) - -constexpr uint16_t VP_SD_ResumePauseAbort = 0x2026; // Resume(Data=0), Pause(Data=1), Abort(Data=2) SD Card prints -constexpr uint16_t VP_SD_AbortPrintConfirmed = 0x2028; // Abort print confirmation (virtual, will be injected by the confirm dialog) -constexpr uint16_t VP_SD_Print_Setting = 0x2040; -constexpr uint16_t VP_SD_Print_LiveAdjustZ = 0x2050; // Data: 0 down, 1 up - -// Controls for movement (we can't use the incremental / decremental feature of the display at this feature works only with 16 bit values -// (which would limit us to 655.35mm, which is likely not a problem for common setups, but i don't want to rule out hangprinters support) -// A word about the coding: The VP will be per axis and the return code will be an signed 16 bit value in 0.01 mm resolution, telling us -// the relative travel amount t he user wants to do. So eg. if the display sends us VP=2100 with value 100, the user wants us to move X by +1 mm. -constexpr uint16_t VP_MOVE_X = 0x2100; -constexpr uint16_t VP_MOVE_Y = 0x2102; -constexpr uint16_t VP_MOVE_Z = 0x2104; -constexpr uint16_t VP_MOVE_E0 = 0x2110; -constexpr uint16_t VP_MOVE_E1 = 0x2112; -//constexpr uint16_t VP_MOVE_E2 = 0x2114; -//constexpr uint16_t VP_MOVE_E3 = 0x2116; -//constexpr uint16_t VP_MOVE_E4 = 0x2118; -//constexpr uint16_t VP_MOVE_E5 = 0x211A; -constexpr uint16_t VP_HOME_ALL = 0x2120; -constexpr uint16_t VP_MOTOR_LOCK_UNLOK = 0x2130; - -// Power loss recovery -constexpr uint16_t VP_POWER_LOSS_RECOVERY = 0x2180; - -// Fan Control Buttons , switch between "off" and "on" -constexpr uint16_t VP_FAN0_CONTROL = 0x2200; -constexpr uint16_t VP_FAN1_CONTROL = 0x2202; -constexpr uint16_t VP_FAN2_CONTROL = 0x2204; -constexpr uint16_t VP_FAN3_CONTROL = 0x2206; - -// Heater Control Buttons , triged between "cool down" and "heat PLA" state -constexpr uint16_t VP_E0_CONTROL = 0x2210; -constexpr uint16_t VP_E1_CONTROL = 0x2212; -//constexpr uint16_t VP_E2_CONTROL = 0x2214; -//constexpr uint16_t VP_E3_CONTROL = 0x2216; -//constexpr uint16_t VP_E4_CONTROL = 0x2218; -//constexpr uint16_t VP_E5_CONTROL = 0x221A; -constexpr uint16_t VP_BED_CONTROL = 0x221C; - -// Preheat -constexpr uint16_t VP_E0_BED_PREHEAT = 0x2220; -constexpr uint16_t VP_E1_BED_PREHEAT = 0x2222; -//constexpr uint16_t VP_E2_BED_PREHEAT = 0x2224; -//constexpr uint16_t VP_E3_BED_PREHEAT = 0x2226; -//constexpr uint16_t VP_E4_BED_PREHEAT = 0x2228; -//constexpr uint16_t VP_E5_BED_PREHEAT = 0x222A; - -// Filament load and unload -constexpr uint16_t VP_E0_FILAMENT_LOAD_UNLOAD = 0x2300; -constexpr uint16_t VP_E1_FILAMENT_LOAD_UNLOAD = 0x2302; - -// Settings store , reset -constexpr uint16_t VP_SETTINGS = 0x2400; - -// PID autotune -constexpr uint16_t VP_PID_AUTOTUNE_E0 = 0x2410; -constexpr uint16_t VP_PID_AUTOTUNE_E1 = 0x2412; -//constexpr uint16_t VP_PID_AUTOTUNE_E2 = 0x2414; -//constexpr uint16_t VP_PID_AUTOTUNE_E3 = 0x2416; -//constexpr uint16_t VP_PID_AUTOTUNE_E4 = 0x2418; -//constexpr uint16_t VP_PID_AUTOTUNE_E5 = 0x241A; -constexpr uint16_t VP_PID_AUTOTUNE_BED = 0x2420; - -// Calibrate Z -constexpr uint16_t VP_Z_CALIBRATE = 0x2430; - -// First layer cal -constexpr uint16_t VP_Z_FIRST_LAYER_CAL = 0x2500; // Data: 0 - Cancel first layer cal progress, >0 filament type have loaded - -// Firmware version on the boot screen. -constexpr uint16_t VP_MARLIN_VERSION = 0x3000; -constexpr uint8_t VP_MARLIN_VERSION_LEN = 16; // there is more space on the display, if needed. - -// Place for status messages. -constexpr uint16_t VP_M117 = 0x3020; -constexpr uint8_t VP_M117_LEN = 0x20; - -// Temperatures. -constexpr uint16_t VP_T_E0_Is = 0x3060; // 4 Byte Integer -constexpr uint16_t VP_T_E0_Set = 0x3062; // 2 Byte Integer -constexpr uint16_t VP_T_E1_Is = 0x3064; // 4 Byte Integer - -// reserved to support up to 6 Extruders: -constexpr uint16_t VP_T_E1_Set = 0x3066; // 2 Byte Integer -//constexpr uint16_t VP_T_E2_Is = 0x3068; // 4 Byte Integer -//constexpr uint16_t VP_T_E2_Set = 0x306A; // 2 Byte Integer -//constexpr uint16_t VP_T_E3_Is = 0x306C; // 4 Byte Integer -//constexpr uint16_t VP_T_E3_Set = 0x306E; // 2 Byte Integer -//constexpr uint16_t VP_T_E4_Is = 0x3070; // 4 Byte Integer -//constexpr uint16_t VP_T_E4_Set = 0x3072; // 2 Byte Integer -//constexpr uint16_t VP_T_E4_Is = 0x3074; // 4 Byte Integer -//constexpr uint16_t VP_T_E4_Set = 0x3076; // 2 Byte Integer -//constexpr uint16_t VP_T_E5_Is = 0x3078; // 4 Byte Integer -//constexpr uint16_t VP_T_E5_Set = 0x307A; // 2 Byte Integer - -constexpr uint16_t VP_T_Bed_Is = 0x3080; // 4 Byte Integer -constexpr uint16_t VP_T_Bed_Set = 0x3082; // 2 Byte Integer - -constexpr uint16_t VP_Flowrate_E0 = 0x3090; // 2 Byte Integer -constexpr uint16_t VP_Flowrate_E1 = 0x3092; // 2 Byte Integer - -// reserved for up to 6 Extruders: -//constexpr uint16_t VP_Flowrate_E2 = 0x3094; -//constexpr uint16_t VP_Flowrate_E3 = 0x3096; -//constexpr uint16_t VP_Flowrate_E4 = 0x3098; -//constexpr uint16_t VP_Flowrate_E5 = 0x309A; - -constexpr uint16_t VP_Fan0_Percentage = 0x3100; // 2 Byte Integer (0..100) -constexpr uint16_t VP_Fan1_Percentage = 0x3102; // 2 Byte Integer (0..100) -constexpr uint16_t VP_Fan2_Percentage = 0x3104; // 2 Byte Integer (0..100) -constexpr uint16_t VP_Fan3_Percentage = 0x3106; // 2 Byte Integer (0..100) -constexpr uint16_t VP_Feedrate_Percentage = 0x3108; // 2 Byte Integer (0..100) - -// Actual Position -constexpr uint16_t VP_XPos = 0x3110; // 4 Byte Fixed point number; format xxx.yy -constexpr uint16_t VP_YPos = 0x3112; // 4 Byte Fixed point number; format xxx.yy -constexpr uint16_t VP_ZPos = 0x3114; // 4 Byte Fixed point number; format xxx.yy - -constexpr uint16_t VP_EPos = 0x3120; // 4 Byte Fixed point number; format xxx.yy - -constexpr uint16_t VP_PrintProgress_Percentage = 0x3130; // 2 Byte Integer (0..100) - -constexpr uint16_t VP_PrintTime = 0x3140; -constexpr uint16_t VP_PrintTime_LEN = 32; - -constexpr uint16_t VP_PrintAccTime = 0x3160; -constexpr uint16_t VP_PrintAccTime_LEN = 32; - -constexpr uint16_t VP_PrintsTotal = 0x3180; -constexpr uint16_t VP_PrintsTotal_LEN = 16; - -// SDCard File Listing -constexpr uint16_t VP_SD_FileName_LEN = 32; // LEN is shared for all entries. -constexpr uint16_t DGUS_SD_FILESPERSCREEN = 5; // FIXME move that info to the display and read it from there. -constexpr uint16_t VP_SD_FileName0 = 0x3200; -constexpr uint16_t VP_SD_FileName1 = 0x3220; -constexpr uint16_t VP_SD_FileName2 = 0x3240; -constexpr uint16_t VP_SD_FileName3 = 0x3260; -constexpr uint16_t VP_SD_FileName4 = 0x3280; - -constexpr uint16_t VP_SD_Print_ProbeOffsetZ = 0x32A0; // -constexpr uint16_t VP_SD_Print_Filename = 0x32C0; - -// Fan status -constexpr uint16_t VP_FAN0_STATUS = 0x3300; -constexpr uint16_t VP_FAN1_STATUS = 0x3302; -constexpr uint16_t VP_FAN2_STATUS = 0x3304; -constexpr uint16_t VP_FAN3_STATUS = 0x3306; - -// Heater status -constexpr uint16_t VP_E0_STATUS = 0x3310; -constexpr uint16_t VP_E1_STATUS = 0x3312; -//constexpr uint16_t VP_E2_STATUS = 0x3314; -//constexpr uint16_t VP_E3_STATUS = 0x3316; -//constexpr uint16_t VP_E4_STATUS = 0x3318; -//constexpr uint16_t VP_E5_STATUS = 0x331A; -constexpr uint16_t VP_BED_STATUS = 0x331C; - -constexpr uint16_t VP_MOVE_OPTION = 0x3400; - -// Step per mm -constexpr uint16_t VP_X_STEP_PER_MM = 0x3600; // at the moment , 2 byte unsigned int , 0~1638.4 -//constexpr uint16_t VP_X2_STEP_PER_MM = 0x3602; -constexpr uint16_t VP_Y_STEP_PER_MM = 0x3604; -//constexpr uint16_t VP_Y2_STEP_PER_MM = 0x3606; -constexpr uint16_t VP_Z_STEP_PER_MM = 0x3608; -//constexpr uint16_t VP_Z2_STEP_PER_MM = 0x360A; -constexpr uint16_t VP_E0_STEP_PER_MM = 0x3610; -constexpr uint16_t VP_E1_STEP_PER_MM = 0x3612; -//constexpr uint16_t VP_E2_STEP_PER_MM = 0x3614; -//constexpr uint16_t VP_E3_STEP_PER_MM = 0x3616; -//constexpr uint16_t VP_E4_STEP_PER_MM = 0x3618; -//constexpr uint16_t VP_E5_STEP_PER_MM = 0x361A; - -// PIDs -constexpr uint16_t VP_E0_PID_P = 0x3700; // at the moment , 2 byte unsigned int , 0~1638.4 -constexpr uint16_t VP_E0_PID_I = 0x3702; -constexpr uint16_t VP_E0_PID_D = 0x3704; -constexpr uint16_t VP_E1_PID_P = 0x3706; // at the moment , 2 byte unsigned int , 0~1638.4 -constexpr uint16_t VP_E1_PID_I = 0x3708; -constexpr uint16_t VP_E1_PID_D = 0x370A; -constexpr uint16_t VP_BED_PID_P = 0x3710; -constexpr uint16_t VP_BED_PID_I = 0x3712; -constexpr uint16_t VP_BED_PID_D = 0x3714; - -// Wating screen status -constexpr uint16_t VP_WAITING_STATUS = 0x3800; - -// SPs for certain variables... -// located at 0x5000 and up -// Not used yet! -// This can be used e.g to make controls / data display invisible -constexpr uint16_t SP_T_E0_Is = 0x5000; -constexpr uint16_t SP_T_E0_Set = 0x5010; -constexpr uint16_t SP_T_E1_Is = 0x5020; -constexpr uint16_t SP_T_Bed_Is = 0x5030; -constexpr uint16_t SP_T_Bed_Set = 0x5040; diff --git a/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.cpp deleted file mode 100644 index 82c06d7a4afb..000000000000 --- a/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.cpp +++ /dev/null @@ -1,485 +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 . - * - */ - -/* DGUS VPs changed by George Fu in 2019 for Marlin */ - -#include "../../../../../inc/MarlinConfigPre.h" - -#if ENABLED(DGUS_LCD_UI_HIPRECY) - -#include "../DGUSDisplayDef.h" -#include "../DGUSDisplay.h" -#include "../DGUSScreenHandler.h" - -#include "../../../../../module/temperature.h" -#include "../../../../../module/motion.h" -#include "../../../../../module/planner.h" - -#include "../../../ui_api.h" -#include "../../../../ultralcd.h" - -#if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - uint16_t distanceToMove = 10; -#endif - -const uint16_t VPList_Boot[] PROGMEM = { - VP_MARLIN_VERSION, - 0x0000 -}; - -const uint16_t VPList_Main[] PROGMEM = { - /* VP_M117, for completeness, but it cannot be auto-uploaded. */ - #if HOTENDS >= 1 - VP_T_E0_Is, VP_T_E0_Set, VP_E0_STATUS, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, - #endif - #if HAS_HEATED_BED - VP_T_Bed_Is, VP_T_Bed_Set, VP_BED_STATUS, - #endif - #if HAS_FAN - VP_Fan0_Percentage, VP_FAN0_STATUS, - #endif - VP_XPos, VP_YPos, VP_ZPos, - VP_Fan0_Percentage, - VP_Feedrate_Percentage, - #if ENABLED(LCD_SET_PROGRESS_MANUALLY) - VP_PrintProgress_Percentage, - #endif - 0x0000 -}; - -const uint16_t VPList_Temp[] PROGMEM = { - #if HOTENDS >= 1 - VP_T_E0_Is, VP_T_E0_Set, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, - #endif - #if HAS_HEATED_BED - VP_T_Bed_Is, VP_T_Bed_Set, - #endif - 0x0000 -}; - -const uint16_t VPList_Status[] PROGMEM = { - /* VP_M117, for completeness, but it cannot be auto-uploaded */ - #if HOTENDS >= 1 - VP_T_E0_Is, VP_T_E0_Set, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, - #endif - #if HAS_HEATED_BED - VP_T_Bed_Is, VP_T_Bed_Set, - #endif - #if HAS_FAN - VP_Fan0_Percentage, - #endif - VP_XPos, VP_YPos, VP_ZPos, - VP_Fan0_Percentage, - VP_Feedrate_Percentage, - VP_PrintProgress_Percentage, - 0x0000 -}; - -const uint16_t VPList_Status2[] PROGMEM = { - /* VP_M117, for completeness, but it cannot be auto-uploaded */ - #if HOTENDS >= 1 - VP_Flowrate_E0, - #endif - #if HOTENDS >= 2 - VP_Flowrate_E1, - #endif - VP_PrintProgress_Percentage, - VP_PrintTime, - 0x0000 -}; - -const uint16_t VPList_Preheat[] PROGMEM = { - #if HOTENDS >= 1 - VP_T_E0_Is, VP_T_E0_Set, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, - #endif - #if HAS_HEATED_BED - VP_T_Bed_Is, VP_T_Bed_Set, - #endif - 0x0000 -}; - -const uint16_t VPList_ManualMove[] PROGMEM = { - VP_XPos, VP_YPos, VP_ZPos, - 0x0000 -}; - -const uint16_t VPList_ManualExtrude[] PROGMEM = { - #if HOTENDS >= 1 - VP_T_E0_Is, VP_T_E0_Set, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, - #endif - VP_EPos, - 0x0000 -}; - -const uint16_t VPList_FanAndFeedrate[] PROGMEM = { - VP_Feedrate_Percentage, VP_Fan0_Percentage, - 0x0000 -}; - -const uint16_t VPList_SD_FlowRates[] PROGMEM = { - VP_Flowrate_E0, VP_Flowrate_E1, - 0x0000 -}; - -const uint16_t VPList_Filament_heating[] PROGMEM = { - #if HOTENDS >= 1 - VP_T_E0_Is, VP_T_E0_Set, - VP_E0_FILAMENT_LOAD_UNLOAD, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, - #endif - 0x0000 -}; - -const uint16_t VPList_Filament_load_unload[] PROGMEM = { - #if HOTENDS >= 1 - VP_E0_FILAMENT_LOAD_UNLOAD, - #endif - #if HOTENDS >= 2 - VP_E1_FILAMENT_LOAD_UNLOAD, - #endif - 0x0000 -}; - -const uint16_t VPList_SDFileList[] PROGMEM = { - VP_SD_FileName0, VP_SD_FileName1, VP_SD_FileName2, VP_SD_FileName3, VP_SD_FileName4, - 0x0000 -}; - -const uint16_t VPList_SD_PrintManipulation[] PROGMEM = { - VP_PrintProgress_Percentage, VP_PrintTime, - #if HOTENDS >= 1 - VP_T_E0_Is, VP_T_E0_Set, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, - #endif - #if HAS_HEATED_BED - VP_T_Bed_Is, VP_T_Bed_Set, - #endif - #if HAS_FAN - VP_Fan0_Percentage, - #if FAN_COUNT > 1 - VP_Fan1_Percentage, - #endif - #endif - VP_Flowrate_E0, - 0x0000 -}; - -const uint16_t VPList_SDPrintTune[] PROGMEM = { - #if HOTENDS >= 1 - VP_T_E0_Is, VP_T_E0_Set, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, - #endif - #if HAS_HEATED_BED - VP_T_Bed_Is, VP_T_Bed_Set, - #endif - VP_Feedrate_Percentage, - #if HAS_FAN - VP_Fan0_Percentage, - #endif - VP_Flowrate_E0, - VP_SD_Print_ProbeOffsetZ, - 0x0000 -}; - -const uint16_t VPList_StepPerMM[] PROGMEM = { - VP_X_STEP_PER_MM, - VP_Y_STEP_PER_MM, - VP_Z_STEP_PER_MM, - #if HOTENDS >= 1 - VP_E0_STEP_PER_MM, - #endif - #if HOTENDS >= 2 - VP_E1_STEP_PER_MM, - #endif - 0x0000 -}; - -const uint16_t VPList_PIDE0[] PROGMEM = { - #if ENABLED(PIDTEMP) - VP_E0_PID_P, - VP_E0_PID_I, - VP_E0_PID_D, - #endif - 0x0000 -}; - -const uint16_t VPList_PIDBED[] PROGMEM = { - #if ENABLED(PIDTEMP) - VP_BED_PID_P, - VP_BED_PID_I, - VP_BED_PID_D, - #endif - 0x0000 -}; - -const uint16_t VPList_Infos[] PROGMEM = { - VP_MARLIN_VERSION, - VP_PrintTime, - #if ENABLED(PRINTCOUNTER) - VP_PrintAccTime, - VP_PrintsTotal, - #endif - 0x0000 -}; - -const uint16_t VPList_PIDTuningWaiting[] PROGMEM = { - VP_WAITING_STATUS, - 0x0000 -}; - -const uint16_t VPList_FLCPreheat[] PROGMEM = { - #if HOTENDS >= 1 - VP_T_E0_Is, VP_T_E0_Set, - #endif - #if HAS_HEATED_BED - VP_T_Bed_Is, VP_T_Bed_Set, - #endif - 0x0000 -}; - -const uint16_t VPList_FLCPrinting[] PROGMEM = { - #if HOTENDS >= 1 - VP_SD_Print_ProbeOffsetZ, - #endif - 0x0000 -}; - -const uint16_t VPList_Z_Offset[] PROGMEM = { - #if HOTENDS >= 1 - VP_SD_Print_ProbeOffsetZ, - #endif - 0x0000 -}; - -const struct VPMapping VPMap[] PROGMEM = { - { DGUSLCD_SCREEN_BOOT, VPList_Boot }, - { DGUSLCD_SCREEN_MAIN, VPList_Main }, - { DGUSLCD_SCREEN_TEMPERATURE, VPList_Temp }, - { DGUSLCD_SCREEN_STATUS, VPList_Status }, - { DGUSLCD_SCREEN_STATUS2, VPList_Status2 }, - { DGUSLCD_SCREEN_PREHEAT, VPList_Preheat }, - { DGUSLCD_SCREEN_MANUALMOVE, VPList_ManualMove }, - { DGUSLCD_SCREEN_Z_OFFSET, VPList_Z_Offset }, - { DGUSLCD_SCREEN_MANUALEXTRUDE, VPList_ManualExtrude }, - { DGUSLCD_SCREEN_FILAMENT_HEATING, VPList_Filament_heating }, - { DGUSLCD_SCREEN_FILAMENT_LOADING, VPList_Filament_load_unload }, - { DGUSLCD_SCREEN_FILAMENT_UNLOADING, VPList_Filament_load_unload }, - { DGUSLCD_SCREEN_SDPRINTMANIPULATION, VPList_SD_PrintManipulation }, - { DGUSLCD_SCREEN_SDFILELIST, VPList_SDFileList }, - { DGUSLCD_SCREEN_SDPRINTTUNE, VPList_SDPrintTune }, - { DGUSLCD_SCREEN_WAITING, VPList_PIDTuningWaiting }, - { DGUSLCD_SCREEN_FLC_PREHEAT, VPList_FLCPreheat }, - { DGUSLCD_SCREEN_FLC_PRINTING, VPList_FLCPrinting }, - { DGUSLCD_SCREEN_STEPPERMM, VPList_StepPerMM }, - { DGUSLCD_SCREEN_PID_E, VPList_PIDE0 }, - { DGUSLCD_SCREEN_PID_BED, VPList_PIDBED }, - { DGUSLCD_SCREEN_INFOS, VPList_Infos }, - { 0 , nullptr } // List is terminated with an nullptr as table entry. -}; - -const char MarlinVersion[] PROGMEM = SHORT_BUILD_VERSION; - -// Helper to define a DGUS_VP_Variable for common use cases. -#define VPHELPER(VPADR, VPADRVAR, RXFPTR, TXFPTR ) { .VP=VPADR, .memadr=VPADRVAR, .size=sizeof(VPADRVAR), \ - .set_by_display_handler = RXFPTR, .send_to_display_handler = TXFPTR } - -// Helper to define a DGUS_VP_Variable when the sizeo of the var cannot be determined automaticalyl (eg. a string) -#define VPHELPER_STR(VPADR, VPADRVAR, STRLEN, RXFPTR, TXFPTR ) { .VP=VPADR, .memadr=VPADRVAR, .size=STRLEN, \ - .set_by_display_handler = RXFPTR, .send_to_display_handler = TXFPTR } - -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) - VPHELPER(VP_SCREENCHANGE_WHENSD, nullptr, ScreenHandler.ScreenChangeHookIfSD, nullptr), - #endif - VPHELPER(VP_CONFIRMED, nullptr, ScreenHandler.ScreenConfirmedOK, nullptr), - - VPHELPER(VP_TEMP_ALL_OFF, nullptr, &ScreenHandler.HandleAllHeatersOff, nullptr), - - #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - VPHELPER(VP_MOVE_OPTION, &distanceToMove, &ScreenHandler.HandleManualMoveOption, nullptr), - #endif - #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - VPHELPER(VP_MOVE_X, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Y, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Z, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_HOME_ALL, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), - #else - VPHELPER(VP_MOVE_X, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Y, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Z, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_HOME_ALL, nullptr, &ScreenHandler.HandleManualMove, nullptr), - #endif - VPHELPER(VP_MOTOR_LOCK_UNLOK, nullptr, &ScreenHandler.HandleMotorLockUnlock, nullptr), - #if ENABLED(POWER_LOSS_RECOVERY) - VPHELPER(VP_POWER_LOSS_RECOVERY, nullptr, &ScreenHandler.HandlePowerLossRecovery, nullptr), - #endif - VPHELPER(VP_SETTINGS, nullptr, &ScreenHandler.HandleSettings, nullptr), - #if ENABLED(SINGLE_Z_CALIBRATION) - VPHELPER(VP_Z_CALIBRATE, nullptr, &ScreenHandler.HandleZCalibration, nullptr), - #endif - #if ENABLED(FIRST_LAYER_CAL) - VPHELPER(VP_Z_FIRST_LAYER_CAL, nullptr, &ScreenHandler.HandleFirstLayerCal, nullptr), - #endif - - { .VP = VP_MARLIN_VERSION, .memadr = (void*)MarlinVersion, .size = VP_MARLIN_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler =&ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - // M117 LCD String (We don't need the string in memory but "just" push it to the display on demand, hence the nullptr - { .VP = VP_M117, .memadr = nullptr, .size = VP_M117_LEN, .set_by_display_handler = nullptr, .send_to_display_handler =&ScreenHandler.DGUSLCD_SendStringToDisplay }, - - // Temperature Data - #if HOTENDS >= 1 - VPHELPER(VP_T_E0_Is, &thermalManager.temp_hotend[0].celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), - VPHELPER(VP_T_E0_Set, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleTemperatureChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Flowrate_E0, &planner.flow_percentage[ExtUI::extruder_t::E0], ScreenHandler.HandleFlowRateChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_EPos, &destination.e, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), - VPHELPER(VP_MOVE_E0, nullptr, &ScreenHandler.HandleManualExtrude, nullptr), - VPHELPER(VP_E0_CONTROL, &thermalManager.temp_hotend[0].target, &ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_E0_STATUS, &thermalManager.temp_hotend[0].target, nullptr, &ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), - #if ENABLED(DGUS_PREHEAT_UI) - VPHELPER(VP_E0_BED_PREHEAT, nullptr, &ScreenHandler.HandlePreheat, nullptr), - #endif - #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) - VPHELPER(VP_E0_FILAMENT_LOAD_UNLOAD, nullptr, &ScreenHandler.HandleFilamentOption, &ScreenHandler.HandleFilamentLoadUnload), - #endif - #if ENABLED(PIDTEMP) - VPHELPER(VP_E0_PID_P, &thermalManager.temp_hotend[0].pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_E0_PID_I, &thermalManager.temp_hotend[0].pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_E0_PID_D, &thermalManager.temp_hotend[0].pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_PID_AUTOTUNE_E0, nullptr, &ScreenHandler.HandlePIDAutotune, nullptr), - #endif - #endif - #if HOTENDS >= 2 - VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, DGUSLCD_SendFloatAsLongValueToDisplay<0>), - VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleTemperatureChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Flowrate_E1, nullptr, ScreenHandler.HandleFlowRateChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_MOVE_E1, nullptr, &ScreenHandler.HandleManualExtrude, nullptr), - VPHELPER(VP_E1_CONTROL, &thermalManager.temp_hotend[1].target, &ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_E1_STATUS, &thermalManager.temp_hotend[1].target, nullptr, &ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), - #endif - #if HAS_HEATED_BED - VPHELPER(VP_T_Bed_Is, &thermalManager.temp_bed.celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), - VPHELPER(VP_T_Bed_Set, &thermalManager.temp_bed.target, ScreenHandler.HandleTemperatureChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_BED_CONTROL, &thermalManager.temp_bed.target, &ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_BED_STATUS, &thermalManager.temp_bed.target, nullptr, &ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), - #if ENABLED(PIDTEMP) - VPHELPER(VP_BED_PID_P, &thermalManager.temp_bed.pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_BED_PID_I, &thermalManager.temp_bed.pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_BED_PID_D, &thermalManager.temp_bed.pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_PID_AUTOTUNE_BED, nullptr, &ScreenHandler.HandlePIDAutotune, nullptr), - #endif - #endif - - // Fan Data - #if HAS_FAN - #define FAN_VPHELPER(N) \ - VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], ScreenHandler.DGUSLCD_PercentageToUint8, &ScreenHandler.DGUSLCD_SendPercentageToDisplay), \ - VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], &ScreenHandler.HandleFanControl, nullptr), \ - VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, &ScreenHandler.DGUSLCD_SendFanStatusToDisplay), - REPEAT(FAN_COUNT, FAN_VPHELPER) - #endif - - // Feedrate - VPHELPER(VP_Feedrate_Percentage, &feedrate_percentage, ScreenHandler.DGUSLCD_SetValueDirectly, &ScreenHandler.DGUSLCD_SendWordValueToDisplay ), - - // Position Data - VPHELPER(VP_XPos, ¤t_position.x, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), - VPHELPER(VP_YPos, ¤t_position.y, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), - VPHELPER(VP_ZPos, ¤t_position.z, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), - - // Print Progress - VPHELPER(VP_PrintProgress_Percentage, nullptr, nullptr, ScreenHandler.DGUSLCD_SendPrintProgressToDisplay ), - - // Print Time - VPHELPER_STR(VP_PrintTime, nullptr, VP_PrintTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintTimeToDisplay ), - #if ENABLED(PRINTCOUNTER) - VPHELPER_STR(VP_PrintAccTime, nullptr, VP_PrintAccTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintAccTimeToDisplay ), - VPHELPER_STR(VP_PrintsTotal, nullptr, VP_PrintsTotal_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintsTotalToDisplay ), - #endif - - VPHELPER(VP_X_STEP_PER_MM, &planner.settings.axis_steps_per_mm[X_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), - VPHELPER(VP_Y_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Y_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), - VPHELPER(VP_Z_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Z_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), - #if HOTENDS >= 1 - VPHELPER(VP_E0_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(0)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), - #endif - #if HOTENDS >= 2 - VPHELPER(VP_E1_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(1)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), - #endif - - // SDCard File listing. - #if ENABLED(SDSUPPORT) - VPHELPER(VP_SD_ScrollEvent, nullptr, ScreenHandler.DGUSLCD_SD_ScrollFilelist, nullptr), - VPHELPER(VP_SD_FileSelected, nullptr, ScreenHandler.DGUSLCD_SD_FileSelected, nullptr), - VPHELPER(VP_SD_FileSelectConfirm, nullptr, ScreenHandler.DGUSLCD_SD_StartPrint, nullptr), - VPHELPER_STR(VP_SD_FileName0, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename ), - VPHELPER_STR(VP_SD_FileName1, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename ), - VPHELPER_STR(VP_SD_FileName2, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename ), - VPHELPER_STR(VP_SD_FileName3, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename ), - VPHELPER_STR(VP_SD_FileName4, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename ), - VPHELPER(VP_SD_ResumePauseAbort, nullptr, ScreenHandler.DGUSLCD_SD_ResumePauseAbort, nullptr), - VPHELPER(VP_SD_AbortPrintConfirmed, nullptr, ScreenHandler.DGUSLCD_SD_ReallyAbort, nullptr), - VPHELPER(VP_SD_Print_Setting, nullptr, ScreenHandler.DGUSLCD_SD_PrintTune, nullptr), - #if HAS_BED_PROBE - VPHELPER(VP_SD_Print_ProbeOffsetZ, &probe.offset.z, ScreenHandler.HandleProbeOffsetZChanged, &ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<2>), - #if ENABLED(BABYSTEPPING) - VPHELPER(VP_SD_Print_LiveAdjustZ, nullptr, ScreenHandler.HandleLiveAdjustZ, nullptr), - #endif - #endif - #endif - - #if ENABLED(DGUS_UI_WAITING) - VPHELPER(VP_WAITING_STATUS, nullptr, nullptr, ScreenHandler.DGUSLCD_SendWaitingStatusToDisplay), - #endif - - // Messages for the User, shared by the popup and the kill screen. They cant be autouploaded as we do not buffer content. - { .VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - - VPHELPER(0, 0, 0, 0) // must be last entry. -}; - -#endif // DGUS_LCD_UI_HIPRECY diff --git a/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.h b/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.h deleted file mode 100644 index 3ff5e06dc18c..000000000000 --- a/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.h +++ /dev/null @@ -1,290 +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 - -enum DGUSLCD_Screens : uint8_t { - DGUSLCD_SCREEN_BOOT = 160, - DGUSLCD_SCREEN_MAIN = 1, - DGUSLCD_SCREEN_STATUS = 1, - DGUSLCD_SCREEN_STATUS2 = 1, - DGUSLCD_SCREEN_POWER_LOSS = 17, - DGUSLCD_SCREEN_TEMPERATURE = 40, - DGUSLCD_SCREEN_MANUALMOVE = 86, - DGUSLCD_SCREEN_PREHEAT = 48, - DGUSLCD_SCREEN_UTILITY = 70, - DGUSLCD_SCREEN_FILAMENT_HEATING = 80, - DGUSLCD_SCREEN_FILAMENT_LOADING = 76, - DGUSLCD_SCREEN_FILAMENT_UNLOADING = 82, - DGUSLCD_SCREEN_MANUALEXTRUDE = 84, - DGUSLCD_SCREEN_Z_OFFSET = 88, - DGUSLCD_SCREEN_SDFILELIST = 3, - DGUSLCD_SCREEN_SDPRINTMANIPULATION = 7, - DGUSLCD_SCREEN_SDPRINTTUNE = 9, - DGUSLCD_SCREEN_FLC_PREHEAT = 94, - DGUSLCD_SCREEN_FLC_PRINTING = 96, - DGUSLCD_SCREEN_STEPPERMM = 122, - DGUSLCD_SCREEN_PID_E = 126, - DGUSLCD_SCREEN_PID_BED = 128, - DGUSLCD_SCREEN_INFOS = 131, - DGUSLCD_SCREEN_CONFIRM = 240, - DGUSLCD_SCREEN_KILL = 250, ///< Kill Screen. Must always be 250 (to be able to display "Error wrong LCD Version") - DGUSLCD_SCREEN_WAITING = 251, - DGUSLCD_SCREEN_POPUP = 252, ///< special target, popup screen will also return this code to say "return to previous screen" - DGUSLDC_SCREEN_UNUSED = 255 -}; - -// Display Memory layout used (T5UID) -// Except system variables this is arbitrary, just to organize stuff.... - -// 0x0000 .. 0x0FFF -- System variables and reserved by the display -// 0x1000 .. 0x1FFF -- Variables to never change location, regardless of UI Version -// 0x2000 .. 0x2FFF -- Controls (VPs that will trigger some action) -// 0x3000 .. 0x4FFF -- Marlin Data to be displayed -// 0x5000 .. -- SPs (if we want to modify display elements, e.g change color or like) -- currently unused - -// As there is plenty of space (at least most displays have >8k RAM), we do not pack them too tight, -// so that we can keep variables nicely together in the address space. - -// UI Version always on 0x1000...0x1002 so that the firmware can check this and bail out. -constexpr uint16_t VP_UI_VERSION_MAJOR = 0x1000; // Major -- incremented when incompatible -constexpr uint16_t VP_UI_VERSION_MINOR = 0x1001; // Minor -- incremented on new features, but compatible -constexpr uint16_t VP_UI_VERSION_PATCH = 0x1002; // Patch -- fixed which do not change functionality. -constexpr uint16_t VP_UI_FLAVOUR = 0x1010; // lets reserve 16 bytes here to determine if UI is suitable for this Marlin. tbd. - -// Storage space for the Killscreen messages. 0x1100 - 0x1200 . Reused for the popup. -constexpr uint16_t VP_MSGSTR1 = 0x1100; -constexpr uint8_t VP_MSGSTR1_LEN = 0x20; // might be more place for it... -constexpr uint16_t VP_MSGSTR2 = 0x1140; -constexpr uint8_t VP_MSGSTR2_LEN = 0x20; -constexpr uint16_t VP_MSGSTR3 = 0x1180; -constexpr uint8_t VP_MSGSTR3_LEN = 0x20; -constexpr uint16_t VP_MSGSTR4 = 0x11C0; -constexpr uint8_t VP_MSGSTR4_LEN = 0x20; - -// Screenchange request for screens that only make sense when printer is idle. -// e.g movement is only allowed if printer is not printing. -// Marlin must confirm by setting the screen manually. -constexpr uint16_t VP_SCREENCHANGE_ASK = 0x2000; -constexpr uint16_t VP_SCREENCHANGE = 0x2001; // 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 = 0x2002; // Turn all heaters off. Value arbitrary ;)= -constexpr uint16_t VP_SCREENCHANGE_WHENSD = 0x2003; // "Print" Button touched -- go only there if there is an SD Card. - -constexpr uint16_t VP_CONFIRMED = 0x2010; // OK on confirm screen. - -// Buttons on the SD-Card File listing. -constexpr uint16_t VP_SD_ScrollEvent = 0x2020; // Data: 0 for "up a directory", numbers are the amount to scroll, e.g -1 one up, 1 one down -constexpr uint16_t VP_SD_FileSelected = 0x2022; // Number of file field selected. -constexpr uint16_t VP_SD_FileSelectConfirm = 0x2024; // (This is a virtual VP and emulated by the Confirm Screen when a file has been confirmed) - -constexpr uint16_t VP_SD_ResumePauseAbort = 0x2026; // Resume(Data=0), Pause(Data=1), Abort(Data=2) SD Card prints -constexpr uint16_t VP_SD_AbortPrintConfirmed = 0x2028; // Abort print confirmation (virtual, will be injected by the confirm dialog) -constexpr uint16_t VP_SD_Print_Setting = 0x2040; -constexpr uint16_t VP_SD_Print_LiveAdjustZ = 0x2050; // Data: 0 down, 1 up - -// Controls for movement (we can't use the incremental / decremental feature of the display at this feature works only with 16 bit values -// (which would limit us to 655.35mm, which is likely not a problem for common setups, but i don't want to rule out hangprinters support) -// A word about the coding: The VP will be per axis and the return code will be an signed 16 bit value in 0.01 mm resolution, telling us -// the relative travel amount t he user wants to do. So eg. if the display sends us VP=2100 with value 100, the user wants us to move X by +1 mm. -constexpr uint16_t VP_MOVE_X = 0x2100; -constexpr uint16_t VP_MOVE_Y = 0x2102; -constexpr uint16_t VP_MOVE_Z = 0x2104; -constexpr uint16_t VP_MOVE_E0 = 0x2110; -constexpr uint16_t VP_MOVE_E1 = 0x2112; -//constexpr uint16_t VP_MOVE_E2 = 0x2114; -//constexpr uint16_t VP_MOVE_E3 = 0x2116; -//constexpr uint16_t VP_MOVE_E4 = 0x2118; -//constexpr uint16_t VP_MOVE_E5 = 0x211A; -constexpr uint16_t VP_HOME_ALL = 0x2120; -constexpr uint16_t VP_MOTOR_LOCK_UNLOK = 0x2130; - -// Power loss recovery -constexpr uint16_t VP_POWER_LOSS_RECOVERY = 0x2180; - -// Fan Control Buttons , switch between "off" and "on" -constexpr uint16_t VP_FAN0_CONTROL = 0x2200; -constexpr uint16_t VP_FAN1_CONTROL = 0x2202; -//constexpr uint16_t VP_FAN2_CONTROL = 0x2204; -//constexpr uint16_t VP_FAN3_CONTROL = 0x2206; - -// Heater Control Buttons , triged between "cool down" and "heat PLA" state -constexpr uint16_t VP_E0_CONTROL = 0x2210; -constexpr uint16_t VP_E1_CONTROL = 0x2212; -//constexpr uint16_t VP_E2_CONTROL = 0x2214; -//constexpr uint16_t VP_E3_CONTROL = 0x2216; -//constexpr uint16_t VP_E4_CONTROL = 0x2218; -//constexpr uint16_t VP_E5_CONTROL = 0x221A; -constexpr uint16_t VP_BED_CONTROL = 0x221C; - -// Preheat -constexpr uint16_t VP_E0_BED_PREHEAT = 0x2220; -//constexpr uint16_t VP_E1_BED_PREHEAT = 0x2222; -//constexpr uint16_t VP_E2_BED_PREHEAT = 0x2224; -//constexpr uint16_t VP_E3_BED_PREHEAT = 0x2226; -//constexpr uint16_t VP_E4_BED_PREHEAT = 0x2228; -//constexpr uint16_t VP_E5_BED_PREHEAT = 0x222A; - -// Filament load and unload -constexpr uint16_t VP_E0_FILAMENT_LOAD_UNLOAD = 0x2300; - -// Settings store , reset -constexpr uint16_t VP_SETTINGS = 0x2400; - -// PID autotune -constexpr uint16_t VP_PID_AUTOTUNE_E0 = 0x2410; -//constexpr uint16_t VP_PID_AUTOTUNE_E1 = 0x2412; -//constexpr uint16_t VP_PID_AUTOTUNE_E2 = 0x2414; -//constexpr uint16_t VP_PID_AUTOTUNE_E3 = 0x2416; -//constexpr uint16_t VP_PID_AUTOTUNE_E4 = 0x2418; -//constexpr uint16_t VP_PID_AUTOTUNE_E5 = 0x241A; -constexpr uint16_t VP_PID_AUTOTUNE_BED = 0x2420; - -// Calibrate Z -constexpr uint16_t VP_Z_CALIBRATE = 0x2430; - -// First layer cal -constexpr uint16_t VP_Z_FIRST_LAYER_CAL = 0x2500; // Data: 0 - Cancel first layer cal progress, >0 filament type have loaded - -// Firmware version on the boot screen. -constexpr uint16_t VP_MARLIN_VERSION = 0x3000; -constexpr uint8_t VP_MARLIN_VERSION_LEN = 16; // there is more space on the display, if needed. - -// Place for status messages. -constexpr uint16_t VP_M117 = 0x3020; -constexpr uint8_t VP_M117_LEN = 0x20; - -// Temperatures. -constexpr uint16_t VP_T_E0_Is = 0x3060; // 4 Byte Integer -constexpr uint16_t VP_T_E0_Set = 0x3062; // 2 Byte Integer -constexpr uint16_t VP_T_E1_Is = 0x3064; // 4 Byte Integer - -// reserved to support up to 6 Extruders: -//constexpr uint16_t VP_T_E1_Set = 0x3066; // 2 Byte Integer -//constexpr uint16_t VP_T_E2_Is = 0x3068; // 4 Byte Integer -//constexpr uint16_t VP_T_E2_Set = 0x306A; // 2 Byte Integer -//constexpr uint16_t VP_T_E3_Is = 0x306C; // 4 Byte Integer -//constexpr uint16_t VP_T_E3_Set = 0x306E; // 2 Byte Integer -//constexpr uint16_t VP_T_E4_Is = 0x3070; // 4 Byte Integer -//constexpr uint16_t VP_T_E4_Set = 0x3072; // 2 Byte Integer -//constexpr uint16_t VP_T_E4_Is = 0x3074; // 4 Byte Integer -//constexpr uint16_t VP_T_E4_Set = 0x3076; // 2 Byte Integer -//constexpr uint16_t VP_T_E5_Is = 0x3078; // 4 Byte Integer -//constexpr uint16_t VP_T_E5_Set = 0x307A; // 2 Byte Integer - -constexpr uint16_t VP_T_Bed_Is = 0x3080; // 4 Byte Integer -constexpr uint16_t VP_T_Bed_Set = 0x3082; // 2 Byte Integer - -constexpr uint16_t VP_Flowrate_E0 = 0x3090; // 2 Byte Integer -constexpr uint16_t VP_Flowrate_E1 = 0x3092; // 2 Byte Integer - -// reserved for up to 6 Extruders: -//constexpr uint16_t VP_Flowrate_E2 = 0x3094; -//constexpr uint16_t VP_Flowrate_E3 = 0x3096; -//constexpr uint16_t VP_Flowrate_E4 = 0x3098; -//constexpr uint16_t VP_Flowrate_E5 = 0x309A; - -constexpr uint16_t VP_Fan0_Percentage = 0x3100; // 2 Byte Integer (0..100) -constexpr uint16_t VP_Fan1_Percentage = 0x3102; // 2 Byte Integer (0..100) -constexpr uint16_t VP_Fan2_Percentage = 0x3104; // 2 Byte Integer (0..100) -constexpr uint16_t VP_Fan3_Percentage = 0x3106; // 2 Byte Integer (0..100) -constexpr uint16_t VP_Feedrate_Percentage = 0x3108; // 2 Byte Integer (0..100) - -// Actual Position -constexpr uint16_t VP_XPos = 0x3110; // 4 Byte Fixed point number; format xxx.yy -constexpr uint16_t VP_YPos = 0x3112; // 4 Byte Fixed point number; format xxx.yy -constexpr uint16_t VP_ZPos = 0x3114; // 4 Byte Fixed point number; format xxx.yy - -constexpr uint16_t VP_EPos = 0x3120; // 4 Byte Fixed point number; format xxx.yy - -constexpr uint16_t VP_PrintProgress_Percentage = 0x3130; // 2 Byte Integer (0..100) - -constexpr uint16_t VP_PrintTime = 0x3140; -constexpr uint16_t VP_PrintTime_LEN = 32; - -constexpr uint16_t VP_PrintAccTime = 0x3160; -constexpr uint16_t VP_PrintAccTime_LEN = 32; - -constexpr uint16_t VP_PrintsTotal = 0x3180; -constexpr uint16_t VP_PrintsTotal_LEN = 16; - -// SDCard File Listing -constexpr uint16_t VP_SD_FileName_LEN = 32; // LEN is shared for all entries. -constexpr uint16_t DGUS_SD_FILESPERSCREEN = 5; // FIXME move that info to the display and read it from there. -constexpr uint16_t VP_SD_FileName0 = 0x3200; -constexpr uint16_t VP_SD_FileName1 = 0x3220; -constexpr uint16_t VP_SD_FileName2 = 0x3240; -constexpr uint16_t VP_SD_FileName3 = 0x3260; -constexpr uint16_t VP_SD_FileName4 = 0x3280; - -constexpr uint16_t VP_SD_Print_ProbeOffsetZ = 0x32A0; // - -constexpr uint16_t VP_SD_Print_Filename = 0x32C0; // -// Fan status -constexpr uint16_t VP_FAN0_STATUS = 0x3300; -constexpr uint16_t VP_FAN1_STATUS = 0x3302; -//constexpr uint16_t VP_FAN2_STATUS = 0x3304; -//constexpr uint16_t VP_FAN3_STATUS = 0x3306; - -// Heater status -constexpr uint16_t VP_E0_STATUS = 0x3310; -//constexpr uint16_t VP_E1_STATUS = 0x3312; -//constexpr uint16_t VP_E2_STATUS = 0x3314; -//constexpr uint16_t VP_E3_STATUS = 0x3316; -//constexpr uint16_t VP_E4_STATUS = 0x3318; -//constexpr uint16_t VP_E5_STATUS = 0x331A; -constexpr uint16_t VP_BED_STATUS = 0x331C; - -constexpr uint16_t VP_MOVE_OPTION = 0x3400; - -// Step per mm -constexpr uint16_t VP_X_STEP_PER_MM = 0x3600; // at the moment , 2 byte unsigned int , 0~1638.4 -//constexpr uint16_t VP_X2_STEP_PER_MM = 0x3602; -constexpr uint16_t VP_Y_STEP_PER_MM = 0x3604; -//constexpr uint16_t VP_Y2_STEP_PER_MM = 0x3606; -constexpr uint16_t VP_Z_STEP_PER_MM = 0x3608; -//constexpr uint16_t VP_Z2_STEP_PER_MM = 0x360A; -constexpr uint16_t VP_E0_STEP_PER_MM = 0x3610; -//constexpr uint16_t VP_E1_STEP_PER_MM = 0x3612; -//constexpr uint16_t VP_E2_STEP_PER_MM = 0x3614; -//constexpr uint16_t VP_E3_STEP_PER_MM = 0x3616; -//constexpr uint16_t VP_E4_STEP_PER_MM = 0x3618; -//constexpr uint16_t VP_E5_STEP_PER_MM = 0x361A; - -// PIDs -constexpr uint16_t VP_E0_PID_P = 0x3700; // at the moment , 2 byte unsigned int , 0~1638.4 -constexpr uint16_t VP_E0_PID_I = 0x3702; -constexpr uint16_t VP_E0_PID_D = 0x3704; -constexpr uint16_t VP_BED_PID_P = 0x3710; -constexpr uint16_t VP_BED_PID_I = 0x3712; -constexpr uint16_t VP_BED_PID_D = 0x3714; - -// Wating screen status -constexpr uint16_t VP_WAITING_STATUS = 0x3800; - -// SPs for certain variables... -// located at 0x5000 and up -// Not used yet! -// This can be used e.g to make controls / data display invisible -constexpr uint16_t SP_T_E0_Is = 0x5000; -constexpr uint16_t SP_T_E0_Set = 0x5010; -constexpr uint16_t SP_T_E1_Is = 0x5020; -constexpr uint16_t SP_T_Bed_Is = 0x5030; -constexpr uint16_t SP_T_Bed_Set = 0x5040; diff --git a/Marlin/src/lcd/extui/lib/dgus/origin/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/lib/dgus/origin/DGUSDisplayDef.cpp deleted file mode 100644 index f9d4351e02d9..000000000000 --- a/Marlin/src/lcd/extui/lib/dgus/origin/DGUSDisplayDef.cpp +++ /dev/null @@ -1,310 +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 . - * - */ - -/* DGUS implementation written by coldtobi in 2019 for Marlin */ - -#include "../../../../../inc/MarlinConfigPre.h" - -#if ENABLED(DGUS_LCD_UI_ORIGIN) - -#include "../DGUSDisplayDef.h" -#include "../DGUSDisplay.h" -#include "../DGUSScreenHandler.h" - -#include "../../../../../module/temperature.h" -#include "../../../../../module/motion.h" -#include "../../../../../module/planner.h" - -#include "../../../../ultralcd.h" -#include "../../../ui_api.h" - -#if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - uint16_t distanceToMove = 10; -#endif -using namespace ExtUI; - -const uint16_t VPList_Boot[] PROGMEM = { - VP_MARLIN_VERSION, - 0x0000 -}; - -const uint16_t VPList_Main[] PROGMEM = { - /* VP_M117, for completeness, but it cannot be auto-uploaded. */ - 0x0000 -}; - -const uint16_t VPList_Temp[] PROGMEM = { - #if HOTENDS >= 1 - VP_T_E0_Is, VP_T_E0_Set, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, - #endif - #if HAS_HEATED_BED - VP_T_Bed_Is, VP_T_Bed_Set, - #endif - 0x0000 -}; - -const uint16_t VPList_Status[] PROGMEM = { - /* VP_M117, for completeness, but it cannot be auto-uploaded */ - #if HOTENDS >= 1 - VP_T_E0_Is, VP_T_E0_Set, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, - #endif - #if HAS_HEATED_BED - VP_T_Bed_Is, VP_T_Bed_Set, - #endif - #if HAS_FAN - VP_Fan0_Percentage, - #endif - VP_XPos, VP_YPos, VP_ZPos, - VP_Fan0_Percentage, - VP_Feedrate_Percentage, - VP_PrintProgress_Percentage, - 0x0000 -}; - -const uint16_t VPList_Status2[] PROGMEM = { - /* VP_M117, for completeness, but it cannot be auto-uploaded */ - #if HOTENDS >= 1 - VP_Flowrate_E0, - #endif - #if HOTENDS >= 2 - VP_Flowrate_E1, - #endif - VP_PrintProgress_Percentage, - VP_PrintTime, - 0x0000 -}; - -const uint16_t VPList_ManualMove[] PROGMEM = { - VP_XPos, VP_YPos, VP_ZPos, - 0x0000 -}; - -const uint16_t VPList_ManualExtrude[] PROGMEM = { - VP_EPos, - 0x0000 -}; - -const uint16_t VPList_FanAndFeedrate[] PROGMEM = { - VP_Feedrate_Percentage, VP_Fan0_Percentage, - 0x0000 -}; - -const uint16_t VPList_SD_FlowRates[] PROGMEM = { - VP_Flowrate_E0, VP_Flowrate_E1, - 0x0000 -}; - -const uint16_t VPList_SDFileList[] PROGMEM = { - VP_SD_FileName0, VP_SD_FileName1, VP_SD_FileName2, VP_SD_FileName3, VP_SD_FileName4, - 0x0000 -}; - -const uint16_t VPList_SD_PrintManipulation[] PROGMEM = { - VP_PrintProgress_Percentage, VP_PrintTime, - 0x0000 -}; - -const struct VPMapping VPMap[] PROGMEM = { - { DGUSLCD_SCREEN_BOOT, VPList_Boot }, - { DGUSLCD_SCREEN_MAIN, VPList_Main }, - { DGUSLCD_SCREEN_TEMPERATURE, VPList_Temp }, - { DGUSLCD_SCREEN_STATUS, VPList_Status }, - { DGUSLCD_SCREEN_STATUS2, VPList_Status2 }, - { DGUSLCD_SCREEN_MANUALMOVE, VPList_ManualMove }, - { DGUSLCD_SCREEN_MANUALEXTRUDE, VPList_ManualExtrude }, - { DGUSLCD_SCREEN_FANANDFEEDRATE, VPList_FanAndFeedrate }, - { DGUSLCD_SCREEN_FLOWRATES, VPList_SD_FlowRates }, - { DGUSLCD_SCREEN_SDPRINTMANIPULATION, VPList_SD_PrintManipulation }, - { DGUSLCD_SCREEN_SDFILELIST, VPList_SDFileList }, - { 0 , nullptr } // List is terminated with an nullptr as table entry. -}; - -const char MarlinVersion[] PROGMEM = SHORT_BUILD_VERSION; - -// Helper to define a DGUS_VP_Variable for common use cases. -#define VPHELPER(VPADR, VPADRVAR, RXFPTR, TXFPTR ) { .VP=VPADR, .memadr=VPADRVAR, .size=sizeof(VPADRVAR), \ - .set_by_display_handler = RXFPTR, .send_to_display_handler = TXFPTR } - -// Helper to define a DGUS_VP_Variable when the sizeo of the var cannot be determined automaticalyl (eg. a string) -#define VPHELPER_STR(VPADR, VPADRVAR, STRLEN, RXFPTR, TXFPTR ) { .VP=VPADR, .memadr=VPADRVAR, .size=STRLEN, \ - .set_by_display_handler = RXFPTR, .send_to_display_handler = TXFPTR } - -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) - VPHELPER(VP_SCREENCHANGE_WHENSD, nullptr, ScreenHandler.ScreenChangeHookIfSD, nullptr), - #endif - VPHELPER(VP_CONFIRMED, nullptr, ScreenHandler.ScreenConfirmedOK, nullptr), - - VPHELPER(VP_TEMP_ALL_OFF, nullptr, &ScreenHandler.HandleAllHeatersOff, nullptr), - - #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - VPHELPER(VP_MOVE_OPTION, &distanceToMove, &ScreenHandler.HandleManualMoveOption, nullptr), - #endif - #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - VPHELPER(VP_MOVE_X, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Y, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Z, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_HOME_ALL, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), - #else - VPHELPER(VP_MOVE_X, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Y, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Z, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_HOME_ALL, nullptr, &ScreenHandler.HandleManualMove, nullptr), - #endif - - VPHELPER(VP_MOTOR_LOCK_UNLOK, nullptr, &ScreenHandler.HandleMotorLockUnlock, nullptr), - #if ENABLED(POWER_LOSS_RECOVERY) - VPHELPER(VP_POWER_LOSS_RECOVERY, nullptr, &ScreenHandler.HandlePowerLossRecovery, nullptr), - #endif - VPHELPER(VP_SETTINGS, nullptr, &ScreenHandler.HandleSettings, nullptr), - - { .VP = VP_MARLIN_VERSION, .memadr = (void*)MarlinVersion, .size = VP_MARLIN_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler =&ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - // M117 LCD String (We don't need the string in memory but "just" push it to the display on demand, hence the nullptr - { .VP = VP_M117, .memadr = nullptr, .size = VP_M117_LEN, .set_by_display_handler = nullptr, .send_to_display_handler =&ScreenHandler.DGUSLCD_SendStringToDisplay }, - - // Temperature Data - #if HOTENDS >= 1 - VPHELPER(VP_T_E0_Is, nullptr, nullptr, SET_VARIABLE(getActualTemp_celsius, E0, long)), - VPHELPER(VP_T_E0_Set, nullptr, GET_VARIABLE(setTargetTemp_celsius, E0), - SET_VARIABLE(getTargetTemp_celsius, E0)), - VPHELPER(VP_Flowrate_E0, nullptr, ScreenHandler.HandleFlowRateChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_EPos, &destination.e, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), - VPHELPER(VP_MOVE_E0, nullptr, &ScreenHandler.HandleManualExtrude, nullptr), - VPHELPER(VP_E0_CONTROL, &thermalManager.temp_hotend[0].target, &ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_E0_STATUS, &thermalManager.temp_hotend[0].target, nullptr, &ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), - #if ENABLED(DGUS_PREHEAT_UI) - VPHELPER(VP_E0_BED_PREHEAT, nullptr, &ScreenHandler.HandlePreheat, nullptr), - #endif - #if ENABLED(PIDTEMP) - VPHELPER(VP_E0_PID_P, &thermalManager.temp_hotend[0].pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_E0_PID_I, &thermalManager.temp_hotend[0].pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_E0_PID_D, &thermalManager.temp_hotend[0].pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_PID_AUTOTUNE_E0, nullptr, &ScreenHandler.HandlePIDAutotune, nullptr), - #endif - #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) - VPHELPER(VP_E0_FILAMENT_LOAD_UNLOAD, nullptr, &ScreenHandler.HandleFilamentOption, &ScreenHandler.HandleFilamentLoadUnload), - #endif - #endif - #if HOTENDS >= 2 - VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, DGUSLCD_SendFloatAsLongValueToDisplay<0>), - VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleTemperatureChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Flowrate_E1, nullptr, ScreenHandler.HandleFlowRateChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_MOVE_E1, nullptr, &ScreenHandler.HandleManualExtrude, nullptr), - VPHELPER(VP_E1_CONTROL, &thermalManager.temp_hotend[1].target, &ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_E1_STATUS, &thermalManager.temp_hotend[1].target, nullptr, &ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), - #if ENABLED(PIDTEMP) - VPHELPER(VP_PID_AUTOTUNE_E1, nullptr, &ScreenHandler.HandlePIDAutotune, nullptr), - #endif - #endif - #if HAS_HEATED_BED - VPHELPER(VP_T_Bed_Is, &thermalManager.temp_bed.celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), - VPHELPER(VP_T_Bed_Set, &thermalManager.temp_bed.target, ScreenHandler.HandleTemperatureChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_BED_CONTROL, &thermalManager.temp_bed.target, &ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_BED_STATUS, &thermalManager.temp_bed.target, nullptr, &ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), - #if ENABLED(PIDTEMPBED) - VPHELPER(VP_BED_PID_P, &thermalManager.temp_bed.pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_BED_PID_I, &thermalManager.temp_bed.pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_BED_PID_D, &thermalManager.temp_bed.pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - #endif - #endif - - // Fan Data - #if HAS_FAN - #define FAN_VPHELPER(N) \ - VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], ScreenHandler.DGUSLCD_PercentageToUint8, &ScreenHandler.DGUSLCD_SendPercentageToDisplay), \ - VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], &ScreenHandler.HandleFanControl, nullptr), \ - VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, &ScreenHandler.DGUSLCD_SendFanStatusToDisplay), - REPEAT(FAN_COUNT, FAN_VPHELPER) - #endif - - // Feedrate - VPHELPER(VP_Feedrate_Percentage, &feedrate_percentage, ScreenHandler.DGUSLCD_SetValueDirectly, &ScreenHandler.DGUSLCD_SendWordValueToDisplay ), - - // Position Data - VPHELPER(VP_XPos, ¤t_position.x, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), - VPHELPER(VP_YPos, ¤t_position.y, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), - VPHELPER(VP_ZPos, ¤t_position.z, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), - - // Print Progress - VPHELPER(VP_PrintProgress_Percentage, nullptr, nullptr, ScreenHandler.DGUSLCD_SendPrintProgressToDisplay ), - - // Print Time - VPHELPER_STR(VP_PrintTime, nullptr, VP_PrintTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintTimeToDisplay ), - #if ENABLED(PRINTCOUNTER) - VPHELPER_STR(VP_PrintAccTime, nullptr, VP_PrintAccTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintAccTimeToDisplay ), - VPHELPER_STR(VP_PrintsTotal, nullptr, VP_PrintsTotal_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintsTotalToDisplay ), - #endif - - VPHELPER(VP_X_STEP_PER_MM, &planner.settings.axis_steps_per_mm[X_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), - VPHELPER(VP_Y_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Y_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), - VPHELPER(VP_Z_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Z_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), - #if HOTENDS >= 1 - VPHELPER(VP_E0_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(0)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), - #endif - #if HOTENDS >= 2 - VPHELPER(VP_E1_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(1)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), - #endif - - // SDCard File listing. - #if ENABLED(SDSUPPORT) - VPHELPER(VP_SD_ScrollEvent, nullptr, ScreenHandler.DGUSLCD_SD_ScrollFilelist, nullptr), - VPHELPER(VP_SD_FileSelected, nullptr, ScreenHandler.DGUSLCD_SD_FileSelected, nullptr), - VPHELPER(VP_SD_FileSelectConfirm, nullptr, ScreenHandler.DGUSLCD_SD_StartPrint, nullptr), - VPHELPER_STR(VP_SD_FileName0, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename ), - VPHELPER_STR(VP_SD_FileName1, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename ), - VPHELPER_STR(VP_SD_FileName2, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename ), - VPHELPER_STR(VP_SD_FileName3, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename ), - VPHELPER_STR(VP_SD_FileName4, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename ), - VPHELPER(VP_SD_ResumePauseAbort, nullptr, ScreenHandler.DGUSLCD_SD_ResumePauseAbort, nullptr), - VPHELPER(VP_SD_AbortPrintConfirmed, nullptr, ScreenHandler.DGUSLCD_SD_ReallyAbort, nullptr), - VPHELPER(VP_SD_Print_Setting, nullptr, ScreenHandler.DGUSLCD_SD_PrintTune, nullptr), - #if HAS_BED_PROBE - VPHELPER(VP_SD_Print_ProbeOffsetZ, &probe.offset.z, ScreenHandler.HandleProbeOffsetZChanged, &ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<2>), - #if ENABLED(BABYSTEPPING) - VPHELPER(VP_SD_Print_LiveAdjustZ, nullptr, ScreenHandler.HandleLiveAdjustZ, nullptr), - #endif - #endif - #endif - - #if ENABLED(DGUS_UI_WAITING) - VPHELPER(VP_WAITING_STATUS, nullptr, nullptr, ScreenHandler.DGUSLCD_SendWaitingStatusToDisplay), - #endif - - // Messages for the User, shared by the popup and the kill screen. They cant be autouploaded as we do not buffer content. - { .VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - - VPHELPER(0, 0, 0, 0) // must be last entry. -}; - -#endif // DGUS_LCD_UI_ORIGIN diff --git a/Marlin/src/lcd/extui/lib/dgus/origin/DGUSDisplayDef.h b/Marlin/src/lcd/extui/lib/dgus/origin/DGUSDisplayDef.h deleted file mode 100644 index 451c11adba16..000000000000 --- a/Marlin/src/lcd/extui/lib/dgus/origin/DGUSDisplayDef.h +++ /dev/null @@ -1,280 +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 - -enum DGUSLCD_Screens : uint8_t { - DGUSLCD_SCREEN_BOOT = 0, - DGUSLCD_SCREEN_MAIN = 10, - DGUSLCD_SCREEN_TEMPERATURE = 20, - DGUSLCD_SCREEN_STATUS = 30, - DGUSLCD_SCREEN_STATUS2 = 32, - DGUSLCD_SCREEN_MANUALMOVE = 40, - DGUSLCD_SCREEN_MANUALEXTRUDE=42, - DGUSLCD_SCREEN_FANANDFEEDRATE = 44, - DGUSLCD_SCREEN_FLOWRATES = 46, - DGUSLCD_SCREEN_SDFILELIST = 50, - DGUSLCD_SCREEN_SDPRINTMANIPULATION = 52, - DGUSLCD_SCREEN_POWER_LOSS = 100, - DGUSLCD_SCREEN_PREHEAT=120, - DGUSLCD_SCREEN_UTILITY=110, - DGUSLCD_SCREEN_FILAMENT_HEATING=146, - DGUSLCD_SCREEN_FILAMENT_LOADING=148, - DGUSLCD_SCREEN_FILAMENT_UNLOADING=158, - DGUSLCD_SCREEN_SDPRINTTUNE = 170, - DGUSLCD_SCREEN_CONFIRM = 240, - DGUSLCD_SCREEN_KILL = 250, ///< Kill Screen. Must always be 250 (to be able to display "Error wrong LCD Version") - DGUSLCD_SCREEN_WAITING = 251, - DGUSLCD_SCREEN_POPUP = 252, ///< special target, popup screen will also return this code to say "return to previous screen" - DGUSLDC_SCREEN_UNUSED = 255 -}; - -// Display Memory layout used (T5UID) -// Except system variables this is arbitrary, just to organize stuff.... - -// 0x0000 .. 0x0FFF -- System variables and reserved by the display -// 0x1000 .. 0x1FFF -- Variables to never change location, regardless of UI Version -// 0x2000 .. 0x2FFF -- Controls (VPs that will trigger some action) -// 0x3000 .. 0x4FFF -- Marlin Data to be displayed -// 0x5000 .. -- SPs (if we want to modify display elements, e.g change color or like) -- currently unused - -// As there is plenty of space (at least most displays have >8k RAM), we do not pack them too tight, -// so that we can keep variables nicely together in the address space. - -// UI Version always on 0x1000...0x1002 so that the firmware can check this and bail out. -constexpr uint16_t VP_UI_VERSION_MAJOR = 0x1000; // Major -- incremented when incompatible -constexpr uint16_t VP_UI_VERSION_MINOR = 0x1001; // Minor -- incremented on new features, but compatible -constexpr uint16_t VP_UI_VERSION_PATCH = 0x1002; // Patch -- fixed which do not change functionality. -constexpr uint16_t VP_UI_FLAVOUR = 0x1010; // lets reserve 16 bytes here to determine if UI is suitable for this Marlin. tbd. - -// Storage space for the Killscreen messages. 0x1100 - 0x1200 . Reused for the popup. -constexpr uint16_t VP_MSGSTR1 = 0x1100; -constexpr uint8_t VP_MSGSTR1_LEN = 0x20; // might be more place for it... -constexpr uint16_t VP_MSGSTR2 = 0x1140; -constexpr uint8_t VP_MSGSTR2_LEN = 0x20; -constexpr uint16_t VP_MSGSTR3 = 0x1180; -constexpr uint8_t VP_MSGSTR3_LEN = 0x20; -constexpr uint16_t VP_MSGSTR4 = 0x11C0; -constexpr uint8_t VP_MSGSTR4_LEN = 0x20; - -// Screenchange request for screens that only make sense when printer is idle. -// e.g movement is only allowed if printer is not printing. -// Marlin must confirm by setting the screen manually. -constexpr uint16_t VP_SCREENCHANGE_ASK = 0x2000; -constexpr uint16_t VP_SCREENCHANGE = 0x2001; // 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 = 0x2002; // Turn all heaters off. Value arbitrary ;)= -constexpr uint16_t VP_SCREENCHANGE_WHENSD = 0x2003; // "Print" Button touched -- go only there if there is an SD Card. - -constexpr uint16_t VP_CONFIRMED = 0x2010; // OK on confirm screen. - -// Buttons on the SD-Card File listing. -constexpr uint16_t VP_SD_ScrollEvent = 0x2020; // Data: 0 for "up a directory", numbers are the amount to scroll, e.g -1 one up, 1 one down -constexpr uint16_t VP_SD_FileSelected = 0x2022; // Number of file field selected. -constexpr uint16_t VP_SD_FileSelectConfirm = 0x2024; // (This is a virtual VP and emulated by the Confirm Screen when a file has been confirmed) - -constexpr uint16_t VP_SD_ResumePauseAbort = 0x2026; // Resume(Data=0), Pause(Data=1), Abort(Data=2) SD Card prints -constexpr uint16_t VP_SD_AbortPrintConfirmed = 0x2028; // Abort print confirmation (virtual, will be injected by the confirm dialog) -constexpr uint16_t VP_SD_Print_Setting = 0x2040; -constexpr uint16_t VP_SD_Print_LiveAdjustZ = 0x2050; // Data: 0 down, 1 up - -// Controls for movement (we can't use the incremental / decremental feature of the display at this feature works only with 16 bit values -// (which would limit us to 655.35mm, which is likely not a problem for common setups, but i don't want to rule out hangprinters support) -// A word about the coding: The VP will be per axis and the return code will be an signed 16 bit value in 0.01 mm resolution, telling us -// the relative travel amount t he user wants to do. So eg. if the display sends us VP=2100 with value 100, the user wants us to move X by +1 mm. -constexpr uint16_t VP_MOVE_X = 0x2100; -constexpr uint16_t VP_MOVE_Y = 0x2102; -constexpr uint16_t VP_MOVE_Z = 0x2104; -constexpr uint16_t VP_MOVE_E0 = 0x2110; -constexpr uint16_t VP_MOVE_E1 = 0x2112; -//constexpr uint16_t VP_MOVE_E2 = 0x2114; -//constexpr uint16_t VP_MOVE_E3 = 0x2116; -//constexpr uint16_t VP_MOVE_E4 = 0x2118; -//constexpr uint16_t VP_MOVE_E5 = 0x211A; -constexpr uint16_t VP_HOME_ALL = 0x2120; -constexpr uint16_t VP_MOTOR_LOCK_UNLOK = 0x2130; - -// Power loss recovery -constexpr uint16_t VP_POWER_LOSS_RECOVERY = 0x2180; - -// Fan Control Buttons , switch between "off" and "on" -constexpr uint16_t VP_FAN0_CONTROL = 0x2200; -constexpr uint16_t VP_FAN1_CONTROL = 0x2202; -//constexpr uint16_t VP_FAN2_CONTROL = 0x2204; -//constexpr uint16_t VP_FAN3_CONTROL = 0x2206; - -// Heater Control Buttons , triged between "cool down" and "heat PLA" state -constexpr uint16_t VP_E0_CONTROL = 0x2210; -constexpr uint16_t VP_E1_CONTROL = 0x2212; -//constexpr uint16_t VP_E2_CONTROL = 0x2214; -//constexpr uint16_t VP_E3_CONTROL = 0x2216; -//constexpr uint16_t VP_E4_CONTROL = 0x2218; -//constexpr uint16_t VP_E5_CONTROL = 0x221A; -constexpr uint16_t VP_BED_CONTROL = 0x221C; - -// Preheat -constexpr uint16_t VP_E0_BED_PREHEAT = 0x2220; -constexpr uint16_t VP_E1_BED_CONTROL = 0x2222; -//constexpr uint16_t VP_E2_BED_CONTROL = 0x2224; -//constexpr uint16_t VP_E3_BED_CONTROL = 0x2226; -//constexpr uint16_t VP_E4_BED_CONTROL = 0x2228; -//constexpr uint16_t VP_E5_BED_CONTROL = 0x222A; - -// Filament load and unload -constexpr uint16_t VP_E0_FILAMENT_LOAD_UNLOAD = 0x2300; -constexpr uint16_t VP_E1_FILAMENT_LOAD_UNLOAD = 0x2302; - -// Settings store , reset -constexpr uint16_t VP_SETTINGS = 0x2400; - -// PID autotune -constexpr uint16_t VP_PID_AUTOTUNE_E0 = 0x2410; -//constexpr uint16_t VP_PID_AUTOTUNE_E1 = 0x2412; -//constexpr uint16_t VP_PID_AUTOTUNE_E2 = 0x2414; -//constexpr uint16_t VP_PID_AUTOTUNE_E3 = 0x2416; -//constexpr uint16_t VP_PID_AUTOTUNE_E4 = 0x2418; -//constexpr uint16_t VP_PID_AUTOTUNE_E5 = 0x241A; -constexpr uint16_t VP_PID_AUTOTUNE_BED = 0x2420; - -// Firmware version on the boot screen. -constexpr uint16_t VP_MARLIN_VERSION = 0x3000; -constexpr uint8_t VP_MARLIN_VERSION_LEN = 16; // there is more space on the display, if needed. - -// Place for status messages. -constexpr uint16_t VP_M117 = 0x3020; -constexpr uint8_t VP_M117_LEN = 0x20; - -// Temperatures. -constexpr uint16_t VP_T_E0_Is = 0x3060; // 4 Byte Integer -constexpr uint16_t VP_T_E0_Set = 0x3062; // 2 Byte Integer -constexpr uint16_t VP_T_E1_Is = 0x3064; // 4 Byte Integer - -// reserved to support up to 6 Extruders: -//constexpr uint16_t VP_T_E1_Set = 0x3066; // 2 Byte Integer -//constexpr uint16_t VP_T_E2_Is = 0x3068; // 4 Byte Integer -//constexpr uint16_t VP_T_E2_Set = 0x306A; // 2 Byte Integer -//constexpr uint16_t VP_T_E3_Is = 0x306C; // 4 Byte Integer -//constexpr uint16_t VP_T_E3_Set = 0x306E; // 2 Byte Integer -//constexpr uint16_t VP_T_E4_Is = 0x3070; // 4 Byte Integer -//constexpr uint16_t VP_T_E4_Set = 0x3072; // 2 Byte Integer -//constexpr uint16_t VP_T_E4_Is = 0x3074; // 4 Byte Integer -//constexpr uint16_t VP_T_E4_Set = 0x3076; // 2 Byte Integer -//constexpr uint16_t VP_T_E5_Is = 0x3078; // 4 Byte Integer -//constexpr uint16_t VP_T_E5_Set = 0x307A; // 2 Byte Integer - -constexpr uint16_t VP_T_Bed_Is = 0x3080; // 4 Byte Integer -constexpr uint16_t VP_T_Bed_Set = 0x3082; // 2 Byte Integer - -constexpr uint16_t VP_Flowrate_E0 = 0x3090; // 2 Byte Integer -constexpr uint16_t VP_Flowrate_E1 = 0x3092; // 2 Byte Integer - -// reserved for up to 6 Extruders: -//constexpr uint16_t VP_Flowrate_E2 = 0x3094; -//constexpr uint16_t VP_Flowrate_E3 = 0x3096; -//constexpr uint16_t VP_Flowrate_E4 = 0x3098; -//constexpr uint16_t VP_Flowrate_E5 = 0x309A; - -constexpr uint16_t VP_Fan0_Percentage = 0x3100; // 2 Byte Integer (0..100) -constexpr uint16_t VP_Fan1_Percentage = 0x33A2; // 2 Byte Integer (0..100) -//constexpr uint16_t VP_Fan2_Percentage = 0x33A4; // 2 Byte Integer (0..100) -//constexpr uint16_t VP_Fan3_Percentage = 0x33A6; // 2 Byte Integer (0..100) - -constexpr uint16_t VP_Feedrate_Percentage = 0x3102; // 2 Byte Integer (0..100) -constexpr uint16_t VP_PrintProgress_Percentage = 0x3104; // 2 Byte Integer (0..100) - -constexpr uint16_t VP_PrintTime = 0x3106; -constexpr uint16_t VP_PrintTime_LEN = 10; - -constexpr uint16_t VP_PrintAccTime = 0x3160; -constexpr uint16_t VP_PrintAccTime_LEN = 32; - -constexpr uint16_t VP_PrintsTotal = 0x3180; -constexpr uint16_t VP_PrintsTotal_LEN = 16; - -// Actual Position -constexpr uint16_t VP_XPos = 0x3110; // 4 Byte Fixed point number; format xxx.yy -constexpr uint16_t VP_YPos = 0x3112; // 4 Byte Fixed point number; format xxx.yy -constexpr uint16_t VP_ZPos = 0x3114; // 4 Byte Fixed point number; format xxx.yy - -constexpr uint16_t VP_EPos = 0x3120; // 4 Byte Fixed point number; format xxx.yy - -// SDCard File Listing -constexpr uint16_t VP_SD_FileName_LEN = 32; // LEN is shared for all entries. -constexpr uint16_t DGUS_SD_FILESPERSCREEN = 5; // FIXME move that info to the display and read it from there. -constexpr uint16_t VP_SD_FileName0 = 0x3200; -constexpr uint16_t VP_SD_FileName1 = 0x3220; -constexpr uint16_t VP_SD_FileName2 = 0x3240; -constexpr uint16_t VP_SD_FileName3 = 0x3260; -constexpr uint16_t VP_SD_FileName4 = 0x3280; - -constexpr uint16_t VP_SD_Print_ProbeOffsetZ = 0x32A0; // -constexpr uint16_t VP_SD_Print_Filename = 0x32C0; // - -// Fan status -constexpr uint16_t VP_FAN0_STATUS = 0x3300; -constexpr uint16_t VP_FAN1_STATUS = 0x3302; -//constexpr uint16_t VP_FAN2_STATUS = 0x3304; -//constexpr uint16_t VP_FAN3_STATUS = 0x3306; - -// Heater status -constexpr uint16_t VP_E0_STATUS = 0x3310; -//constexpr uint16_t VP_E1_STATUS = 0x3312; -//constexpr uint16_t VP_E2_STATUS = 0x3314; -//constexpr uint16_t VP_E3_STATUS = 0x3316; -//constexpr uint16_t VP_E4_STATUS = 0x3318; -//constexpr uint16_t VP_E5_STATUS = 0x331A; -constexpr uint16_t VP_BED_STATUS = 0x331C; - -constexpr uint16_t VP_MOVE_OPTION = 0x3400; - -// Step per mm -constexpr uint16_t VP_X_STEP_PER_MM = 0x3600; // at the moment , 2 byte unsigned int , 0~1638.4 -//constexpr uint16_t VP_X2_STEP_PER_MM = 0x3602; -constexpr uint16_t VP_Y_STEP_PER_MM = 0x3604; -//constexpr uint16_t VP_Y2_STEP_PER_MM = 0x3606; -constexpr uint16_t VP_Z_STEP_PER_MM = 0x3608; -//constexpr uint16_t VP_Z2_STEP_PER_MM = 0x360A; -constexpr uint16_t VP_E0_STEP_PER_MM = 0x3610; -//constexpr uint16_t VP_E1_STEP_PER_MM = 0x3612; -//constexpr uint16_t VP_E2_STEP_PER_MM = 0x3614; -//constexpr uint16_t VP_E3_STEP_PER_MM = 0x3616; -//constexpr uint16_t VP_E4_STEP_PER_MM = 0x3618; -//constexpr uint16_t VP_E5_STEP_PER_MM = 0x361A; - -// PIDs -constexpr uint16_t VP_E0_PID_P = 0x3700; // at the moment , 2 byte unsigned int , 0~1638.4 -constexpr uint16_t VP_E0_PID_I = 0x3702; -constexpr uint16_t VP_E0_PID_D = 0x3704; -constexpr uint16_t VP_BED_PID_P = 0x3710; -constexpr uint16_t VP_BED_PID_I = 0x3712; -constexpr uint16_t VP_BED_PID_D = 0x3714; - -// Wating screen status -constexpr uint16_t VP_WAITING_STATUS = 0x3800; - -// SPs for certain variables... -// located at 0x5000 and up -// Not used yet! -// This can be used e.g to make controls / data display invisible -constexpr uint16_t SP_T_E0_Is = 0x5000; -constexpr uint16_t SP_T_E0_Set = 0x5010; -constexpr uint16_t SP_T_E1_Is = 0x5020; -constexpr uint16_t SP_T_Bed_Is = 0x5030; -constexpr uint16_t SP_T_Bed_Set = 0x5040; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/compat.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/compat.h deleted file mode 100644 index 11ad0798b56f..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/compat.h +++ /dev/null @@ -1,52 +0,0 @@ -/************ - * compat.h * - ************/ - -/**************************************************************************** - * 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 - -/** - * This following provides compatibility whether compiling - * as a part of Marlin or outside it - */ - -#ifdef __has_include - #if __has_include("../../ui_api.h") - #include "../../ui_api.h" - #endif -#else - #include "../../ui_api.h" -#endif - -#ifdef __MARLIN_FIRMWARE__ - // __MARLIN_FIRMWARE__ exists when compiled within Marlin. - #include "pin_mappings.h" - #undef max - #define max(a,b) ((a)>(b)?(a):(b)) - #undef min - #define min(a,b) ((a)<(b)?(a):(b)) -#else - namespace UI { - static inline uint32_t safe_millis() {return millis();}; - static inline void yield() {}; - }; -#endif - -class __FlashStringHelper; -typedef const __FlashStringHelper *progmem_str; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/boards.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/boards.h deleted file mode 100644 index c09d10f1488c..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/boards.h +++ /dev/null @@ -1,184 +0,0 @@ -/************ - * boards.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 HAS_RESOLUTION (defined(TOUCH_UI_320x240) || defined(TOUCH_UI_480x272) || defined(TOUCH_UI_800x480)) - -#define IS_FT800 \ - constexpr uint16_t ftdi_chip = 800; \ - using namespace FTDI_FT800; \ - namespace DL { \ - using namespace FTDI_FT800_DL; \ - } \ - typedef ft800_memory_map ftdi_memory_map; \ - typedef ft800_registers ftdi_registers; - -#define IS_FT810 \ - constexpr uint16_t ftdi_chip = 810; \ - using namespace FTDI_FT810; \ - namespace DL { \ - using namespace FTDI_FT800_DL; \ - using namespace FTDI_FT810_DL; \ - } \ - typedef ft810_memory_map ftdi_memory_map; \ - typedef ft810_registers ftdi_registers; - -#ifdef LCD_FTDI_VM800B35A - #if !HAS_RESOLUTION - #define TOUCH_UI_320x240 - #endif - #ifndef FTDI_API_LEVEL - #define FTDI_API_LEVEL 800 - #endif - namespace FTDI { - IS_FT800 - constexpr bool Use_Crystal = true; // 0 = use internal oscillator, 1 = module has a crystal populated - constexpr bool GPIO_0_Audio_Enable = false; /* 1 = does use GPIO00 for amplifier control, 0 = not in use for Audio */ - constexpr bool GPIO_1_Audio_Shutdown = true; /* 1 = does use GPIO01 for amplifier control, 0 = not in use for Audio */ - constexpr uint8_t Swizzle = 2; - constexpr uint8_t CSpread = 1; - - constexpr uint16_t touch_threshold = 1200; /* touch-sensitivity */ - } - -/** - * Settings for the Haoyu Electronics, 4.3" Graphical LCD Touchscreen, 480x272, SPI, FT800 (FT800CB-HY43B) - * and 5" Graphical LCD Touchscreen, 480x272, SPI, FT800 (FT800CB-HY50B) - * http://www.hotmcu.com/43-graphical-lcd-touchscreen-480x272-spi-ft800-p-111.html?cPath=6_16 - * http://www.hotmcu.com/5-graphical-lcd-touchscreen-480x272-spi-ft800-p-124.html?cPath=6_16 - * Datasheet: - * https://www.hantronix.com/files/data/1278363262430-3.pdf - * https://www.haoyuelectronics.com/Attachment/HY43-LCD/LCD%20DataSheet.pdf - * https://www.haoyuelectronics.com/Attachment/HY5-LCD-HD/KD50G21-40NT-A1.pdf - */ -#elif defined(LCD_HAOYU_FT800CB) - #if !HAS_RESOLUTION - #define TOUCH_UI_480x272 - #endif - #ifndef FTDI_API_LEVEL - #define FTDI_API_LEVEL 800 - #endif - namespace FTDI { - IS_FT800 - constexpr bool Use_Crystal = true; // 0 = use internal oscillator, 1 = module has a crystal populated - constexpr bool GPIO_0_Audio_Enable = false; - constexpr bool GPIO_1_Audio_Shutdown = false; - constexpr uint8_t Swizzle = 0; - constexpr uint8_t CSpread = 1; - constexpr uint16_t touch_threshold = 2000; /* touch-sensitivity */ - } - -/** - * Settings for the Haoyu Electronics, 5" Graphical LCD Touchscreen, 800x480, SPI, FT810 - * http://www.hotmcu.com/5-graphical-lcd-touchscreen-800x480-spi-ft810-p-286.html - * Datasheet: - * https://www.haoyuelectronics.com/Attachment/HY5-LCD-HD/KD50G21-40NT-A1.pdf - */ -#elif defined(LCD_HAOYU_FT810CB) - #if !HAS_RESOLUTION - #define TOUCH_UI_800x480 - #endif - #ifndef FTDI_API_LEVEL - #define FTDI_API_LEVEL 810 - #endif - namespace FTDI { - IS_FT810 - constexpr bool Use_Crystal = true; // 0 = use internal oscillator, 1 = module has a crystal populated - constexpr bool GPIO_0_Audio_Enable = false; - constexpr bool GPIO_1_Audio_Shutdown = false; - constexpr uint8_t Swizzle = 0; - constexpr uint8_t CSpread = 1; - constexpr uint16_t touch_threshold = 2000; /* touch-sensitivity */ - } - -/** - * Settings for the 4D Systems, 4.3" Embedded SPI Display 480x272, SPI, FT800 (4DLCD-FT843) - * https://4dsystems.com.au/4dlcd-ft843 - * Datasheet: - * https://4dsystems.com.au/mwdownloads/download/link/id/52/ - */ -#elif defined(LCD_4DSYSTEMS_4DLCD_FT843) - #if !HAS_RESOLUTION - #define TOUCH_UI_480x272 - #endif - #ifndef FTDI_API_LEVEL - #define FTDI_API_LEVEL 800 - #endif - namespace FTDI { - IS_FT800 - constexpr bool Use_Crystal = true; // 0 = use internal oscillator, 1 = module has a crystal populated - constexpr bool GPIO_0_Audio_Enable = false; - constexpr bool GPIO_1_Audio_Shutdown = true; - constexpr uint8_t Swizzle = 0; - constexpr uint8_t CSpread = 1; - constexpr uint16_t touch_threshold = 1200; /* touch-sensitivity */ - } - -/** - * Settings for the Aleph Objects Color LCD User Interface - * Datasheet https://www.hantronix.com/files/data/s1501799605s500-gh7.pdf - */ -#elif defined(LCD_ALEPHOBJECTS_CLCD_UI) - #if !HAS_RESOLUTION - #define TOUCH_UI_800x480 - #endif - #ifndef FTDI_API_LEVEL - #define FTDI_API_LEVEL 810 - #endif - namespace FTDI { - IS_FT810 - constexpr bool Use_Crystal = false; // 0 = use internal oscillator, 1 = module has a crystal populated - constexpr bool GPIO_0_Audio_Enable = true; // The AO CLCD uses GPIO0 to enable audio - constexpr bool GPIO_1_Audio_Shutdown = false; - constexpr uint8_t Swizzle = 0; - constexpr uint8_t CSpread = 0; - constexpr uint16_t touch_threshold = 2000; /* touch-sensitivity */ - } - -/** - * FYSETC Color LCD - * https://www.aliexpress.com/item/4000627651757.html - * Product information: - * https://github.com/FYSETC/TFT81050 - */ -#elif defined(LCD_FYSETC_TFT81050) - #if !HAS_RESOLUTION - #define TOUCH_UI_800x480 - #endif - #ifndef FTDI_API_LEVEL - #define FTDI_API_LEVEL 810 - #endif - namespace FTDI { - IS_FT810 - constexpr bool Use_Crystal = false; // 0 = use internal oscillator, 1 = module has a crystal populated - constexpr bool GPIO_0_Audio_Enable = true; // The AO CLCD uses GPIO0 to enable audio - constexpr bool GPIO_1_Audio_Shutdown = false; - constexpr uint8_t Swizzle = 0; - constexpr uint8_t CSpread = 0; - constexpr uint16_t touch_threshold = 2000; /* touch-sensitivity */ - } -#else - - #error "Unknown or no TOUCH_UI_FTDI_EVE board specified. To add a new board, modify this file." - -#endif diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/resolutions.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/resolutions.h deleted file mode 100644 index 8d455907e91a..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/resolutions.h +++ /dev/null @@ -1,127 +0,0 @@ -/***************** - * resolutions.h * - *****************/ - -/**************************************************************************** - * Written By Mark Pelletier 2019 - Aleph Objects, Inc. * - * Written By Marcio Teixeira 2019 - 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 - -/*** - * The FT8xx has odd registers that don't correspond to timing values in - * display datasheets. This macro computes the register values using the - * formulas given in the document: - * - * Bridgetek Application Note - * AN_336 FT8xx - * Selecting an LCD Display - * Version 2.1 - * Issue Date: 2017-11-14 - */ -#define COMPUTE_REGS_FROM_DATASHEET \ - constexpr uint16_t Hoffset = thfp + thb - 1; \ - constexpr uint16_t Hcycle = th; \ - constexpr uint16_t Hsync0 = thfp - 1 ; \ - constexpr uint16_t Hsync1 = thfp + thpw - 1; \ - constexpr uint16_t Voffset = tvfp + tvb - 1; \ - constexpr uint16_t Vcycle = tv; \ - constexpr uint16_t Vsync0 = tvfp - 1; \ - constexpr uint16_t Vsync1 = tvfp + tvpw - 1; \ - static_assert(thfp + thb + Hsize == th, "Mismatch in display th"); \ - static_assert(tvfp + tvb + Vsize == tv, "Mismatch in display tv"); - -#ifdef TOUCH_UI_320x240 - namespace FTDI { - constexpr uint8_t Pclk = 8; - constexpr uint8_t Pclkpol = 0; - constexpr uint16_t Hsize = 320; - constexpr uint16_t Vsize = 240; - constexpr uint16_t Vsync0 = 0; - constexpr uint16_t Vsync1 = 2; - constexpr uint16_t Voffset = 13; - constexpr uint16_t Vcycle = 263; - constexpr uint16_t Hsync0 = 0; - constexpr uint16_t Hsync1 = 10; - constexpr uint16_t Hoffset = 70; - constexpr uint16_t Hcycle = 408; - - constexpr uint32_t default_transform_a = 0x000054AD; - constexpr uint32_t default_transform_b = 0xFFFFFF52; - constexpr uint32_t default_transform_c = 0xFFF7F6E4; - constexpr uint32_t default_transform_d = 0x00000065; - constexpr uint32_t default_transform_e = 0xFFFFBE3B; - constexpr uint32_t default_transform_f = 0x00F68E75; - } - -#elif defined(TOUCH_UI_480x272) - namespace FTDI { - constexpr uint8_t Pclk = 7; - constexpr uint8_t Pclkpol = 1; - constexpr uint16_t Hsize = 480; - constexpr uint16_t Vsize = 272; - - constexpr uint16_t th = 525; // One horizontal line - constexpr uint16_t thfp = 43; // HS Front porch - constexpr uint16_t thb = 2; // HS Back porch (blanking) - constexpr uint16_t thpw = 41; // HS pulse width - - constexpr uint16_t tv = 286; // Vertical period time - constexpr uint16_t tvfp = 12; // VS Front porch - constexpr uint16_t tvb = 2; // VS Back porch (blanking) - constexpr uint16_t tvpw = 10; // VS pulse width - - COMPUTE_REGS_FROM_DATASHEET - - constexpr uint32_t default_transform_a = 0x00008100; - constexpr uint32_t default_transform_b = 0x00000000; - constexpr uint32_t default_transform_c = 0xFFF18000; - constexpr uint32_t default_transform_d = 0x00000000; - constexpr uint32_t default_transform_e = 0xFFFFB100; - constexpr uint32_t default_transform_f = 0x0120D000; - } - -#elif defined(TOUCH_UI_800x480) - namespace FTDI { - constexpr uint8_t Pclk = 3; - constexpr uint8_t Pclkpol = 1; - constexpr uint16_t Hsize = 800; - constexpr uint16_t Vsize = 480; - - constexpr uint16_t th = 1056; // One horizontal line - constexpr uint16_t thfp = 210; // HS Front porch - constexpr uint16_t thb = 46; // HS Back porch (blanking) - constexpr uint16_t thpw = 23; // HS pulse width - - constexpr uint16_t tv = 525; // Vertical period time - constexpr uint16_t tvfp = 22; // VS Front porch - constexpr uint16_t tvb = 23; // VS Back porch (blanking) - constexpr uint16_t tvpw = 10; // VS pulse width - - COMPUTE_REGS_FROM_DATASHEET - - constexpr uint32_t default_transform_a = 0x0000D8B9; - constexpr uint32_t default_transform_b = 0x00000124; - constexpr uint32_t default_transform_c = 0xFFE23926; - constexpr uint32_t default_transform_d = 0xFFFFFF51; - constexpr uint32_t default_transform_e = 0xFFFF7E4F; - constexpr uint32_t default_transform_f = 0x01F0AF70; - } - -#else - #error "Unknown or no TOUCH_UI_FTDI_EVE display resolution specified. To add a display resolution, modify 'ftdi_eve_resolutions.h'." -#endif diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h deleted file mode 100644 index 436c67edf2eb..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h +++ /dev/null @@ -1,271 +0,0 @@ -/**************************************************************************** - * 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 - -#include "../config.h" - -#ifdef __MARLIN_FIRMWARE__ - - // Marlin will define the I/O functions for us - #if ENABLED(TOUCH_UI_FTDI_EVE) - #define FTDI_BASIC - #define FTDI_EXTENDED - #endif - -#else // !__MARLIN_FIRMWARE__ - - #include - - #ifndef CLCD_USE_SOFT_SPI - #include - #endif - - namespace fast_io { - - template - struct port_pin { - typedef port_t port; - static inline void set_high() {port::port() = (port::port() | bits);} - static inline void set_low() {port::port() = (port::port() & (~bits));} - static inline void set_input() {port::ddr() = (port::ddr() & (~bits));} - static inline void set_input_pullup() {set_input(); set_high();} - static inline void set_output() {port::ddr() = (port::ddr() | bits);} - static inline uint8_t read() {return port::pin() & bits;} - static inline void write(bool v) {if (v) set_high(); else set_low();} - }; - - #define MAKE_AVR_PORT_PINS(ID) \ - struct port_##ID { \ - static volatile uint8_t &pin() {return PIN##ID;}; \ - static volatile uint8_t &port() {return PORT##ID;}; \ - static volatile uint8_t &ddr() {return DDR##ID;}; \ - }; \ - typedef port_pin AVR_##ID##0; \ - typedef port_pin AVR_##ID##1; \ - typedef port_pin AVR_##ID##2; \ - typedef port_pin AVR_##ID##3; \ - typedef port_pin AVR_##ID##4; \ - typedef port_pin AVR_##ID##5; \ - typedef port_pin AVR_##ID##6; \ - typedef port_pin AVR_##ID##7; - - #ifdef PORTA - MAKE_AVR_PORT_PINS(A); - #endif - #ifdef PORTB - MAKE_AVR_PORT_PINS(B); - #endif - #ifdef PORTC - MAKE_AVR_PORT_PINS(C); - #endif - #ifdef PORTD - MAKE_AVR_PORT_PINS(D); - #endif - #ifdef PORTE - MAKE_AVR_PORT_PINS(E); - #endif - #ifdef PORTF - MAKE_AVR_PORT_PINS(F); - #endif - #ifdef PORTG - MAKE_AVR_PORT_PINS(G); - #endif - #ifdef PORTH - MAKE_AVR_PORT_PINS(H); - #endif - #ifdef PORTJ - MAKE_AVR_PORT_PINS(J); - #endif - #ifdef PORTK - MAKE_AVR_PORT_PINS(K); - #endif - #ifdef PORTL - MAKE_AVR_PORT_PINS(L); - #endif - #ifdef PORTQ - MAKE_AVR_PORT_PINS(Q); - #endif - #ifdef PORTR - MAKE_AVR_PORT_PINS(R); - #endif - - #undef MAKE_AVR_PORT_PINS - - template - struct arduino_digital_pin { - static constexpr uint8_t pin = p; - static inline void set_high() {digitalWrite(p, HIGH);} - static inline void set_low() {digitalWrite(p, LOW);} - static inline void set_input() {pinMode(p, INPUT);} - static inline void set_input_pullup() {pinMode(p, INPUT_PULLUP);} - static inline void set_output() {pinMode(p, OUTPUT);} - static inline uint8_t read() {return digitalRead(p);} - static inline void write(bool v) {digitalWrite(p, v ? HIGH : LOW);} - }; - - #define MAKE_ARDUINO_PINS(ID) typedef arduino_digital_pin ARDUINO_DIGITAL_##ID; - MAKE_ARDUINO_PINS( 0); - MAKE_ARDUINO_PINS( 1); - MAKE_ARDUINO_PINS( 2); - MAKE_ARDUINO_PINS( 3); - MAKE_ARDUINO_PINS( 4); - MAKE_ARDUINO_PINS( 5); - MAKE_ARDUINO_PINS( 6); - MAKE_ARDUINO_PINS( 7); - MAKE_ARDUINO_PINS( 8); - MAKE_ARDUINO_PINS( 9); - MAKE_ARDUINO_PINS(10); - MAKE_ARDUINO_PINS(11); - MAKE_ARDUINO_PINS(12); - MAKE_ARDUINO_PINS(13); - MAKE_ARDUINO_PINS(14); - MAKE_ARDUINO_PINS(15); - MAKE_ARDUINO_PINS(16); - MAKE_ARDUINO_PINS(17); - MAKE_ARDUINO_PINS(18); - MAKE_ARDUINO_PINS(19); - MAKE_ARDUINO_PINS(10); - MAKE_ARDUINO_PINS(21); - MAKE_ARDUINO_PINS(22); - MAKE_ARDUINO_PINS(23); - MAKE_ARDUINO_PINS(24); - MAKE_ARDUINO_PINS(25); - MAKE_ARDUINO_PINS(26); - MAKE_ARDUINO_PINS(27); - MAKE_ARDUINO_PINS(28); - MAKE_ARDUINO_PINS(29); - MAKE_ARDUINO_PINS(30); - MAKE_ARDUINO_PINS(31); - MAKE_ARDUINO_PINS(32); - MAKE_ARDUINO_PINS(33); - MAKE_ARDUINO_PINS(34); - MAKE_ARDUINO_PINS(35); - MAKE_ARDUINO_PINS(36); - MAKE_ARDUINO_PINS(37); - MAKE_ARDUINO_PINS(38); - MAKE_ARDUINO_PINS(39); - MAKE_ARDUINO_PINS(40); - MAKE_ARDUINO_PINS(41); - MAKE_ARDUINO_PINS(42); - MAKE_ARDUINO_PINS(43); - MAKE_ARDUINO_PINS(44); - MAKE_ARDUINO_PINS(45); - MAKE_ARDUINO_PINS(46); - MAKE_ARDUINO_PINS(47); - MAKE_ARDUINO_PINS(48); - MAKE_ARDUINO_PINS(49); - MAKE_ARDUINO_PINS(50); - MAKE_ARDUINO_PINS(51); - MAKE_ARDUINO_PINS(52); - MAKE_ARDUINO_PINS(53); - #undef MAKE_ARDUINO_PINS - } // namespace fast_io - - #define SET_INPUT(pin) fast_io::pin::set_input() - #define SET_INPUT_PULLUP(pin) do{ fast_io::pin::set_input(); fast_io::pin::set_high(); }while(0) - #define SET_INPUT_PULLDOWN SET_INPUT - #define SET_OUTPUT(pin) fast_io::pin::set_output() - #define READ(pin) fast_io::pin::read() - #define WRITE(pin, value) fast_io::pin::write(value) - - #ifndef pgm_read_word_far - #define pgm_read_word_far pgm_read_word - #endif - - #ifndef pgm_read_dword_far - #define pgm_read_dword_far pgm_read_dword - #endif - - #ifndef pgm_read_ptr_far - #define pgm_read_ptr_far pgm_read_ptr - #endif - - #define SERIAL_ECHO_START() - #define SERIAL_ECHOLNPGM(str) Serial.println(F(str)) - #define SERIAL_ECHOPGM(str) Serial.print(F(str)) - #define SERIAL_ECHO_MSG(str) Serial.println(str) - #define SERIAL_ECHOLNPAIR(str, val) do{ Serial.print(F(str)); Serial.println(val); }while(0) - #define SERIAL_ECHOPAIR(str, val) do{ Serial.print(F(str)); Serial.print(val); }while(0) - - #define safe_delay delay - - // Define macros for compatibility - - #define _CAT(a,V...) a##V - #define CAT(a,V...) _CAT(a,V) - - #define FIRST(a,...) a - #define SECOND(a,b,...) b - #define THIRD(a,b,c,...) c - - #define IS_PROBE(V...) SECOND(V, 0) // Get the second item passed, or 0 - #define PROBE() ~, 1 // Second item will be 1 if this is passed - #define _NOT_0 PROBE() - #define NOT(x) IS_PROBE(_CAT(_NOT_, x)) // NOT('0') gets '1'. Anything else gets '0'. - #define _BOOL(x) NOT(NOT(x)) // NOT('0') gets '0'. Anything else gets '1'. - - #define _DO_1(W,C,A) (_##W##_1(A)) - #define _DO_2(W,C,A,B) (_##W##_1(A) C _##W##_1(B)) - #define _DO_3(W,C,A,V...) (_##W##_1(A) C _DO_2(W,C,V)) - #define _DO_4(W,C,A,V...) (_##W##_1(A) C _DO_3(W,C,V)) - #define _DO_5(W,C,A,V...) (_##W##_1(A) C _DO_4(W,C,V)) - #define _DO_6(W,C,A,V...) (_##W##_1(A) C _DO_5(W,C,V)) - #define _DO_7(W,C,A,V...) (_##W##_1(A) C _DO_6(W,C,V)) - #define _DO_8(W,C,A,V...) (_##W##_1(A) C _DO_7(W,C,V)) - #define _DO_9(W,C,A,V...) (_##W##_1(A) C _DO_8(W,C,V)) - #define _DO_10(W,C,A,V...) (_##W##_1(A) C _DO_9(W,C,V)) - #define _DO_11(W,C,A,V...) (_##W##_1(A) C _DO_10(W,C,V)) - #define _DO_12(W,C,A,V...) (_##W##_1(A) C _DO_11(W,C,V)) - #define __DO_N(W,C,N,V...) _DO_##N(W,C,V) - #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) - - #define _ISENA_ ~,1 - #define _ISENA_1 ~,1 - #define _ISENA_0x1 ~,1 - #define _ISENA_true ~,1 - #define _ISENA(V...) IS_PROBE(V) - #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 TERN(O,A,B) _TERN(_ENA_1(O),B,A) // OPTION converted to '0' or '1' - #define TERN0(O,A) _TERN(_ENA_1(O),0,A) // OPTION converted to A or '0' - #define TERN1(O,A) _TERN(_ENA_1(O),1,A) // OPTION converted to A or '1' - #define TERN_(O,A) _TERN(_ENA_1(O),,A) // OPTION converted to A or '' - #define _TERN(E,V...) __TERN(_CAT(T_,E),V) // Prepend 'T_' to get 'T_0' or 'T_1' - #define __TERN(T,V...) ___TERN(_CAT(_NO,T),V) // Prepend '_NO' to get '_NOT_0' or '_NOT_1' - #define ___TERN(P,V...) THIRD(P,V) // If first argument has a comma, A. Else B. - - #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) - - // Remove compiler warning on an unused variable - #ifndef UNUSED - #if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) - #define UNUSED(X) (void)X - #else - #define UNUSED(x) ((void)(x)) - #endif - #endif - -#endif // !__MARLIN_FIRMWARE__ diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp deleted file mode 100644 index 3616f15ab620..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp +++ /dev/null @@ -1,129 +0,0 @@ -/**************** - * text_box.cpp * - ****************/ - -/**************************************************************************** - * Written By Marcio Teixeira 2019 - 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 "ftdi_extended.h" - -#ifdef FTDI_EXTENDED - -namespace FTDI { - /** - * Given a str, end will be set to the position at which a line needs to - * be broken so that the display width is less than w. The line will also - * be broken after a '\n'. Returns the display width of the line. - */ - static uint16_t find_line_break(const FontMetrics &fm, uint16_t w, const char *str, const char *&end) { - w -= fm.get_char_width(' '); - const char *p = str; - end = str; - uint16_t lw = 0, result = 0; - for (;;) { - utf8_char_t c = get_utf8_char_and_inc(p); - if (c == ' ' || c == '\n' || c == '\0') { - if (lw < w || end == str) { - end = (c == '\0') ? p-1 : p; - result = lw; - } - if (c == '\0' || c == '\n') break; - } - lw += fm.get_char_width(c); - } - if (end == str) { - end = p-1; - result = lw; - } - return result; - } - - /** - * This function returns a measurements of the word-wrapped text box. - */ - static void measure_text_box(const FontMetrics &fm, const char *str, uint16_t &width, uint16_t &height) { - const char *line_start = (const char*)str; - const char *line_end; - const uint16_t wrap_width = width; - width = height = 0; - for (;;) { - uint16_t line_width = find_line_break(fm, wrap_width, line_start, line_end); - if (line_end == line_start) break; - width = max(width, line_width); - height += fm.get_height(); - line_start = line_end; - } - } - - /** - * This function draws text inside a bounding box, doing word wrapping and using the largest font that will fit. - */ - void draw_text_box(CommandProcessor& cmd, int x, int y, int w, int h, const char *str, uint16_t options, uint8_t font) { - uint16_t box_width, box_height; - - FontMetrics fm(font); - - // Shrink the font until we find a font that fits - for (;;) { - box_width = w; - measure_text_box(fm, str, box_width, box_height); - if (box_width <= (uint16_t)w && box_height <= (uint16_t)h) break; - fm.load(--font); - if (font == 26) break; - } - - const uint16_t dx = (options & OPT_RIGHTX) ? w : (options & OPT_CENTERX) ? w/2 : 0; - const uint16_t dy = (options & OPT_CENTERY) ? (h - box_height)/2 : 0; - - const char *line_start = str; - const char *line_end; - for (;;) { - find_line_break(fm, w, line_start, line_end); - if (line_end == line_start) break; - - const size_t line_len = line_end - line_start; - if (line_len) { - char line[line_len + 1]; - strncpy(line, line_start, line_len); - line[line_len] = 0; - if (line[line_len - 1] == '\n' || line[line_len - 1] == ' ') - line[line_len - 1] = 0; - - #ifdef TOUCH_UI_USE_UTF8 - if (has_utf8_chars(line)) { - draw_utf8_text(cmd, x + dx, y + dy, line, fm.fs, options & ~OPT_CENTERY); - } else - #endif - { - cmd.CLCD::CommandFifo::text(x + dx, y + dy, font, options & ~OPT_CENTERY); - cmd.CLCD::CommandFifo::str(line); - } - } - y += fm.get_height(); - - line_start = line_end; - } - } - - void draw_text_box(CommandProcessor& cmd, int x, int y, int w, int h, progmem_str pstr, uint16_t options, uint8_t font) { - char str[strlen_P((const char*)pstr) + 1]; - strcpy_P(str, (const char*)pstr); - draw_text_box(cmd, x, y, w, h, (const char*) str, options, font); - } -} // namespace FTDI - -#endif // FTDI_EXTENDED diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/bitmap2cpp.py b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/bitmap2cpp.py deleted file mode 100644 index a7de06d68bb3..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/bitmap2cpp.py +++ /dev/null @@ -1,108 +0,0 @@ -#!/usr/bin/python - -# Written By Marcio Teixeira 2019 - 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: . - -from __future__ import print_function -from PIL import Image -import argparse -import textwrap - -def pack_rle(data): - """Use run-length encoding to pack the bytes""" - rle = [] - value = data[0] - count = 0 - for i in data: - if i != value or count == 255: - rle.append(count) - rle.append(value) - value = i - count = 1 - else: - count += 1 - rle.append(count) - rle.append(value) - return rle - -class WriteSource: - def __init__(self, lines_in_blocks): - self.blocks = [] - self.values = [] - self.block_size = lines_in_blocks - self.rows = 0 - - def add_pixel(self, value): - self.values.append(value) - - def convert_to_4bpp(self, data, chunk_size = 0): - # Invert the image - data = map(lambda i: 255 - i, data) - # Quanitize 8-bit values into 4-bits - data = map(lambda i: i >> 4, data) - # Make sure there is an even number of elements - if (len(data) & 1) == 1: - result.append(0) - # Combine each two adjacent values into one - i = iter(data) - data = map(lambda a, b: a << 4 | b, i ,i) - # Pack the data - data = pack_rle(data) - # Convert values into hex strings - return map(lambda a: "0x" + format(a, '02x'), data) - - def end_row(self, y): - # Pad each row into even number of values - if len(self.values) & 1: - self.values.append(0) - - self.rows += 1 - if self.block_size and (self.rows % self.block_size) == 0: - self.blocks.append(self.values) - self.values = [] - - def write(self): - if len(self.values): - self.blocks.append(self.values) - - block_strs = []; - for b in self.blocks: - data = self.convert_to_4bpp(b) - data = ', '.join(data) - data = textwrap.fill(data, 75, initial_indent = ' ', subsequent_indent = ' ') - block_strs.append(data) - - print("const unsigned char font[] PROGMEM = {") - for i, b in enumerate(block_strs): - if i: - print(',') - print('\n /* {} */'.format(i)) - print(b, end='') - print("\n};") - -if __name__ == "__main__": - parser = argparse.ArgumentParser(description='Converts a grayscale bitmap into a 16-level RLE packed C array for use as font data') - parser.add_argument("input") - parser.add_argument('--char_height', help='Adds a separator every so many lines', type=int) - args = parser.parse_args() - - writer = WriteSource(args.char_height) - - img = Image.open(args.input).convert('L') - for y in range(img.height): - for x in range(img.width): - writer.add_pixel(img.getpixel((x,y))) - writer.end_row(y) - writer.write() diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/circular_progress.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/circular_progress.h deleted file mode 100644 index 5357de3ef36c..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/circular_progress.h +++ /dev/null @@ -1,105 +0,0 @@ -/*********************** - * circular_progress.h * - ***********************/ - -/**************************************************************************** - * Written By Marcio Teixeira 2019 - 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 - -/* This function draws a circular progress "ring" */ - -void draw_circular_progress(CommandProcessor& cmd, int x, int y, int w, int h, float percent, char *text, uint32_t bgcolor, uint32_t fgcolor) { - using namespace FTDI; - - 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 int ro = min(w,h) * 8; - const int rr = ro * rim; - const int cx = x * 16 + w * 8; - const int cy = y * 16 + h * 8; - - // Load a rim shape into stencil buffer - cmd.cmd(SAVE_CONTEXT()); - cmd.cmd(TAG_MASK(0)); - cmd.cmd(CLEAR(0,1,0)); - cmd.cmd(COLOR_MASK(0,0,0,0)); - cmd.cmd(STENCIL_OP(STENCIL_OP_KEEP, STENCIL_OP_INVERT)); - cmd.cmd(STENCIL_FUNC(STENCIL_FUNC_ALWAYS, 255, 255)); - cmd.cmd(BEGIN(POINTS)); - cmd.cmd(POINT_SIZE(ro)); - cmd.cmd(VERTEX2F(cx, cy)); - cmd.cmd(POINT_SIZE(ro - rr)); - cmd.cmd(VERTEX2F(cx, cy)); - cmd.cmd(RESTORE_CONTEXT()); - - // Mask further drawing by stencil buffer - cmd.cmd(SAVE_CONTEXT()); - cmd.cmd(STENCIL_FUNC(STENCIL_FUNC_NOTEQUAL, 0, 255)); - - // Fill the background - cmd.cmd(COLOR_RGB(bgcolor)); - cmd.cmd(BEGIN(POINTS)); - cmd.cmd(POINT_SIZE(ro)); - cmd.cmd(VERTEX2F(cx, cy)); - cmd.cmd(COLOR_RGB(fgcolor)); - - // Paint upper-right quadrant - cmd.cmd(BEGIN(EDGE_STRIP_A)); - cmd.cmd(VERTEX2F(cx, cy)); - cmd.cmd(VERTEX2F(cx + ro*sin(a1) + 16,cy - ro*cos(a1) + 8)); - - // Paint lower-right quadrant - if (a > 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) { - 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) { - cmd.cmd(BEGIN(EDGE_STRIP_L)); - cmd.cmd(VERTEX2F(cx, cy)); - cmd.cmd(VERTEX2F(cx - ro*cos(a4),cy - ro*sin(a4))); - } - cmd.cmd(RESTORE_CONTEXT()); - - // Draw the text - - cmd.cmd(SAVE_CONTEXT()); - cmd.cmd(COLOR_RGB(fgcolor)); - cmd.text(x,y,w,h,text, OPT_CENTERX | OPT_CENTERY); - cmd.cmd(RESTORE_CONTEXT()); -} - -void draw_circular_progress(CommandProcessor& cmd, int x, int y, int w, int h, float percent, uint32_t bgcolor, uint32_t fgcolor) { - char str[5]; - sprintf(str,"%d\%%",int(percent)); - draw_circular_progress(cmd, x, y, w, h, percent, str, bgcolor, fgcolor); -} diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp deleted file mode 100644 index fe68faefee44..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp +++ /dev/null @@ -1,175 +0,0 @@ -/********************* - * marlin_events.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 "compat.h" - -#if ENABLED(TOUCH_UI_FTDI_EVE) - -#include "screens/screens.h" - -namespace ExtUI { - using namespace Theme; - using namespace FTDI; - - void onStartup() { - EventLoop::setup(); - } - - void onIdle() { - EventLoop::loop(); - } - - void onPrinterKilled(PGM_P const error, PGM_P const component) { - char str[strlen_P(error) + strlen_P(component) + 3]; - sprintf_P(str, PSTR(S_FMT ": " S_FMT), error, component); - KillScreen::show(str); - } - - void onMediaInserted() { - if (AT_SCREEN(StatusScreen)) - StatusScreen::setStatusMessage(GET_TEXT_F(MSG_MEDIA_INSERTED)); - sound.play(media_inserted, PLAY_ASYNCHRONOUS); - } - - void onMediaRemoved() { - if (isPrintingFromMedia()) { - stopPrint(); - InterfaceSoundsScreen::playEventSound(InterfaceSoundsScreen::PRINTING_FAILED); - } - else - sound.play(media_removed, PLAY_ASYNCHRONOUS); - - if (AT_SCREEN(StatusScreen) || isPrintingFromMedia()) - StatusScreen::setStatusMessage(GET_TEXT_F(MSG_MEDIA_REMOVED)); - - #if ENABLED(SDSUPPORT) - if (AT_SCREEN(FilesScreen)) GOTO_SCREEN(StatusScreen); - #endif - } - - void onMediaError() { - sound.play(sad_trombone, PLAY_ASYNCHRONOUS); - AlertDialogBox::showError(F("Unable to read media.")); - } - - void onStatusChanged(const char* lcd_msg) { - StatusScreen::setStatusMessage(lcd_msg); - } - - void onStatusChanged(progmem_str lcd_msg) { - StatusScreen::setStatusMessage(lcd_msg); - } - - void onPrintTimerStarted() { - InterfaceSoundsScreen::playEventSound(InterfaceSoundsScreen::PRINTING_STARTED); - } - - void onPrintTimerStopped() { - InterfaceSoundsScreen::playEventSound(InterfaceSoundsScreen::PRINTING_FINISHED); - } - - void onPrintTimerPaused() { - } - - void onFilamentRunout(const extruder_t extruder) { - char lcd_msg[30]; - sprintf_P(lcd_msg, PSTR("Extruder %d Filament Error"), extruder + 1); - StatusScreen::setStatusMessage(lcd_msg); - InterfaceSoundsScreen::playEventSound(InterfaceSoundsScreen::PRINTING_FAILED, FTDI::PLAY_SYNCHRONOUS); - } - - void onFactoryReset() { - InterfaceSettingsScreen::defaultSettings(); - } - - void onStoreSettings(char *buff) { - InterfaceSettingsScreen::saveSettings(buff); - } - - void onLoadSettings(const char *buff) { - InterfaceSettingsScreen::loadSettings(buff); - } - - void onConfigurationStoreWritten(bool success) { - #ifdef ARCHIM2_SPI_FLASH_EEPROM_BACKUP_SIZE - if (success && InterfaceSettingsScreen::backupEEPROM()) { - SERIAL_ECHOLNPGM("Made backup of EEPROM to SPI Flash"); - } - #else - UNUSED(success); - #endif - } - - void onConfigurationStoreRead(bool) { - } - - void onPlayTone(const uint16_t frequency, const uint16_t duration) { - sound.play_tone(frequency, duration); - } - - void onUserConfirmRequired(const char * const msg) { - if (msg) - ConfirmUserRequestAlertBox::show(msg); - else - ConfirmUserRequestAlertBox::hide(); - } - - #if HAS_LEVELING && HAS_MESH - void onMeshUpdate(const int8_t x, const int8_t y, const float val) { - BedMeshScreen::onMeshUpdate(x, y, val); - } - - void onMeshUpdate(const int8_t x, const int8_t y, const ExtUI::probe_state_t state) { - BedMeshScreen::onMeshUpdate(x, y, state); - } - #endif - - #if ENABLED(POWER_LOSS_RECOVERY) - void onPowerLossResume() { - // Called on resume from power-loss - } - #endif - - #if HAS_PID_HEATING - void onPidTuning(const result_t rst) { - // Called for temperature PID tuning result - //SERIAL_ECHOLNPAIR("OnPidTuning:", rst); - switch (rst) { - case PID_BAD_EXTRUDER_NUM: - StatusScreen::setStatusMessage(GET_TEXT_F(MSG_PID_BAD_EXTRUDER_NUM)); - break; - case PID_TEMP_TOO_HIGH: - StatusScreen::setStatusMessage(GET_TEXT_F(MSG_PID_TEMP_TOO_HIGH)); - break; - case PID_TUNING_TIMEOUT: - StatusScreen::setStatusMessage(GET_TEXT_F(MSG_PID_TIMEOUT)); - break; - case PID_DONE: - StatusScreen::setStatusMessage(GET_TEXT_F(MSG_PID_AUTOTUNE_DONE)); - break; - } - GOTO_SCREEN(StatusScreen); - } - #endif // HAS_PID_HEATING -} - -#endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp deleted file mode 100644 index cfb268f0b44f..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp +++ /dev/null @@ -1,155 +0,0 @@ -/***************************** - * advance_settings_menu.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" - -#if ENABLED(TOUCH_UI_FTDI_EVE) && !defined(TOUCH_UI_LULZBOT_BIO) - -#include "screens.h" - -using namespace FTDI; -using namespace ExtUI; -using namespace Theme; - -void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { - if (what & BACKGROUND) { - CommandProcessor cmd; - cmd.cmd(CLEAR_COLOR_RGB(Theme::bg_color)) - .cmd(CLEAR(true,true,true)); - } - - #ifdef TOUCH_UI_PORTRAIT - #if EITHER(HAS_MULTI_HOTEND, SENSORLESS_HOMING) - #define GRID_ROWS 9 - #else - #define GRID_ROWS 8 - #endif - #define GRID_COLS 2 - #define RESTORE_DEFAULTS_POS BTN_POS(1,1), BTN_SIZE(2,1) - #define DISPLAY_POS BTN_POS(1,2), BTN_SIZE(1,1) - #define INTERFACE_POS BTN_POS(2,2), BTN_SIZE(1,1) - #define ZPROBE_ZOFFSET_POS BTN_POS(1,3), BTN_SIZE(1,1) - #define STEPS_PER_MM_POS BTN_POS(2,3), BTN_SIZE(1,1) - #define FILAMENT_POS BTN_POS(1,4), BTN_SIZE(1,1) - #define VELOCITY_POS BTN_POS(2,4), BTN_SIZE(1,1) - #define TMC_CURRENT_POS BTN_POS(1,5), BTN_SIZE(1,1) - #define ACCELERATION_POS BTN_POS(2,5), BTN_SIZE(1,1) - #define ENDSTOPS_POS BTN_POS(1,6), BTN_SIZE(1,1) - #define JERK_POS BTN_POS(2,6), BTN_SIZE(1,1) - #define CASE_LIGHT_POS BTN_POS(1,7), BTN_SIZE(1,1) - #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) - #define BACK_POS BTN_POS(1,9), BTN_SIZE(2,1) - #else - #define BACK_POS BTN_POS(1,8), BTN_SIZE(2,1) - #endif - #else - #define GRID_ROWS 6 - #define GRID_COLS 3 - #define ZPROBE_ZOFFSET_POS BTN_POS(1,1), BTN_SIZE(1,1) - #define CASE_LIGHT_POS BTN_POS(1,4), BTN_SIZE(1,1) - #define STEPS_PER_MM_POS BTN_POS(2,1), BTN_SIZE(1,1) - #define TMC_CURRENT_POS BTN_POS(3,1), BTN_SIZE(1,1) - #define TMC_HOMING_THRS_POS BTN_POS(3,2), BTN_SIZE(1,1) - #define BACKLASH_POS BTN_POS(3,3), BTN_SIZE(1,1) - #define FILAMENT_POS BTN_POS(1,3), BTN_SIZE(1,1) - #define ENDSTOPS_POS BTN_POS(3,4), BTN_SIZE(1,1) - #define DISPLAY_POS BTN_POS(3,5), BTN_SIZE(1,1) - #define INTERFACE_POS BTN_POS(1,5), BTN_SIZE(2,1) - #define RESTORE_DEFAULTS_POS BTN_POS(1,6), BTN_SIZE(2,1) - #define VELOCITY_POS BTN_POS(2,2), BTN_SIZE(1,1) - #define ACCELERATION_POS BTN_POS(2,3), BTN_SIZE(1,1) - #define JERK_POS BTN_POS(2,4), BTN_SIZE(1,1) - #define OFFSETS_POS BTN_POS(1,2), BTN_SIZE(1,1) - #define BACK_POS BTN_POS(3,6), BTN_SIZE(1,1) - #endif - - if (what & FOREGROUND) { - CommandProcessor cmd; - cmd.colors(normal_btn) - .font(Theme::font_medium) - .enabled(ENABLED(HAS_BED_PROBE)) - .tag(2) .button( ZPROBE_ZOFFSET_POS, GET_TEXT_F(MSG_ZPROBE_ZOFFSET)) - .enabled(ENABLED(CASE_LIGHT_ENABLE)) - .tag(16).button( CASE_LIGHT_POS, GET_TEXT_F(MSG_CASE_LIGHT)) - .tag(3) .button( STEPS_PER_MM_POS, GET_TEXT_F(MSG_STEPS_PER_MM)) - .enabled(ENABLED(HAS_TRINAMIC_CONFIG)) - .tag(13).button( TMC_CURRENT_POS, GET_TEXT_F(MSG_TMC_CURRENT)) - .enabled(ENABLED(SENSORLESS_HOMING)) - .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)) - .tag(11).button( FILAMENT_POS, GET_TEXT_F(MSG_FILAMENT)) - .tag(12).button( ENDSTOPS_POS, GET_TEXT_F(MSG_LCD_ENDSTOPS)) - .tag(15).button( DISPLAY_POS, GET_TEXT_F(MSG_DISPLAY_MENU)) - .tag(9) .button( INTERFACE_POS, GET_TEXT_F(MSG_INTERFACE)) - .tag(10).button( RESTORE_DEFAULTS_POS, GET_TEXT_F(MSG_RESTORE_DEFAULTS)) - .tag(5) .button( VELOCITY_POS, GET_TEXT_F(MSG_VELOCITY)) - .tag(6) .button( ACCELERATION_POS, GET_TEXT_F(MSG_ACCELERATION)) - .tag(7) .button( JERK_POS, GET_TEXT_F(TERN(HAS_JUNCTION_DEVIATION, MSG_JUNCTION_DEVIATION, MSG_JERK))) - .enabled(ENABLED(BACKLASH_GCODE)) - .tag(8).button( BACKLASH_POS, GET_TEXT_F(MSG_BACKLASH)) - .colors(action_btn) - .tag(1).button( BACK_POS, GET_TEXT_F(MSG_BACK)); - } -} - -bool AdvancedSettingsMenu::onTouchEnd(uint8_t tag) { - switch (tag) { - case 1: SaveSettingsDialogBox::promptToSaveSettings(); break; - #if HAS_BED_PROBE - case 2: GOTO_SCREEN(ZOffsetScreen); break; - #endif - case 3: GOTO_SCREEN(StepsScreen); break; - #if ENABLED(HAS_MULTI_HOTEND) - case 4: GOTO_SCREEN(NozzleOffsetScreen); break; - #endif - case 5: GOTO_SCREEN(MaxVelocityScreen); break; - case 6: GOTO_SCREEN(DefaultAccelerationScreen); break; - case 7: GOTO_SCREEN(TERN(HAS_JUNCTION_DEVIATION, JunctionDeviationScreen, JerkScreen)); break; - #if ENABLED(BACKLASH_GCODE) - case 8: GOTO_SCREEN(BacklashCompensationScreen); break; - #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) - case 11: GOTO_SCREEN(FilamentMenu); break; - #endif - case 12: GOTO_SCREEN(EndstopStatesScreen); break; - #if HAS_TRINAMIC_CONFIG - case 13: GOTO_SCREEN(StepperCurrentScreen); break; - #endif - #if ENABLED(SENSORLESS_HOMING) - case 14: GOTO_SCREEN(StepperBumpSensitivityScreen); break; - #endif - case 15: GOTO_SCREEN(DisplayTuningScreen); break; - #if ENABLED(CASE_LIGHT_ENABLE) - case 16: GOTO_SCREEN(CaseLightScreen); break; - #endif - default: return false; - } - return true; -} -#endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_screen.cpp deleted file mode 100644 index a11609dd97d2..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_screen.cpp +++ /dev/null @@ -1,353 +0,0 @@ -/*********************** - * bed_mesh_screen.cpp * - ***********************/ - -/**************************************************************************** - * Written By Marcio Teixeira 2020 * - * * - * This program is free software: you can redistribute it and/or modify * - * it under the terms of the GNU General Public License as published by * - * the Free Software Foundation, either version 3 of the License, or * - * (at your option) any later version. * - * * - * This program is distributed in the hope that it will be useful, * - * but WITHOUT ANY WARRANTY; without even the implied warranty of * - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * - * GNU General Public License for more details. * - * * - * To view a copy of the GNU General Public License, go to the following * - * location: . * - ****************************************************************************/ - -#include "../config.h" - -#if BOTH(TOUCH_UI_FTDI_EVE, HAS_MESH) - -#include "screens.h" -#include "screen_data.h" - -using namespace FTDI; -using namespace Theme; -using namespace ExtUI; - -#ifdef TOUCH_UI_PORTRAIT - #define GRID_COLS 2 - #define GRID_ROWS 10 - - #define MESH_POS BTN_POS(1, 2), BTN_SIZE(2,5) - #define MESSAGE_POS BTN_POS(1, 7), BTN_SIZE(2,1) - #define Z_LABEL_POS BTN_POS(1, 8), BTN_SIZE(1,1) - #define Z_VALUE_POS BTN_POS(2, 8), BTN_SIZE(1,1) - #define OKAY_POS BTN_POS(1,10), BTN_SIZE(2,1) -#else - #define GRID_COLS 5 - #define GRID_ROWS 5 - - #define MESH_POS BTN_POS(1,1), BTN_SIZE(3,5) - #define MESSAGE_POS BTN_POS(4,1), BTN_SIZE(2,1) - #define Z_LABEL_POS BTN_POS(4,2), BTN_SIZE(2,1) - #define Z_VALUE_POS BTN_POS(4,3), BTN_SIZE(2,1) - #define OKAY_POS BTN_POS(4,5), BTN_SIZE(2,1) -#endif - -void BedMeshScreen::drawMesh(int16_t x, int16_t y, int16_t w, int16_t h, ExtUI::bed_mesh_t data, uint8_t opts, float autoscale_max) { - constexpr uint8_t rows = GRID_MAX_POINTS_Y; - constexpr uint8_t cols = GRID_MAX_POINTS_X; - - #define VALUE(X,Y) (data ? data[X][Y] : 0) - #define ISVAL(X,Y) (data ? !isnan(VALUE(X,Y)) : true) - #define HEIGHT(X,Y) (ISVAL(X,Y) ? (VALUE(X,Y) - val_min) * scale_z : 0) - - // Compute the mean, min and max for the points - - float val_mean = 0; - float val_max = -INFINITY; - float val_min = INFINITY; - uint8_t val_cnt = 0; - - if (data && (opts & USE_AUTOSCALE)) { - for (uint8_t y = 0; y < rows; y++) { - for (uint8_t x = 0; x < cols; x++) { - if (ISVAL(x,y)) { - const float val = VALUE(x,y); - val_mean += val; - val_max = max(val_max, val); - val_min = min(val_min, val); - val_cnt++; - } - } - } - } - if (val_cnt) { - val_mean /= val_cnt; - } else { - val_mean = 0; - val_min = 0; - val_max = 0; - } - - const float scale_z = ((val_max == val_min) ? 1 : 1/(val_max - val_min)) * autoscale_max; - - /** - * The 3D points go through a 3D graphics pipeline to determine the final 2D point on the screen. - * This is written out as a stack of macros that each apply an affine transformation to the point. - * At compile time, the compiler should be able to reduce these expressions. - * - * The last transformation in the chain (TRANSFORM_5) is initially set to a no-op so we can measure - * the dimensions of the grid, but is later replaced with a scaling transform that scales the grid - * to fit. - */ - - #define TRANSFORM_5(X,Y,Z) (X), (Y) // No transform - #define TRANSFORM_4(X,Y,Z) TRANSFORM_5((X)/(Z),(Y)/-(Z), 0) // Perspective - #define TRANSFORM_3(X,Y,Z) TRANSFORM_4((X), (Z), (Y)) // Swap Z and Y - #define TRANSFORM_2(X,Y,Z) TRANSFORM_3((X), (Y) + 2.5, (Z) - 1) // Translate - #define TRANSFORM(X,Y,Z) TRANSFORM_2(float(X)/(cols-1) - 0.5, float(Y)/(rows-1) - 0.5, (Z)) // Normalize - - // Compute the bounding box for the grid prior to scaling. Do this at compile-time by - // transforming the four corner points via the transformation equations and finding - // the min and max for each axis. - - constexpr float bounds[][3] = {{TRANSFORM(0 , 0 , 0)}, - {TRANSFORM(cols-1, 0 , 0)}, - {TRANSFORM(0 , rows-1, 0)}, - {TRANSFORM(cols-1, rows-1, 0)}}; - #define APPLY(FUNC, AXIS) FUNC(FUNC(bounds[0][AXIS], bounds[1][AXIS]), FUNC(bounds[2][AXIS], bounds[3][AXIS])) - constexpr float grid_x = APPLY(min,0); - constexpr float grid_y = APPLY(min,1); - constexpr float grid_w = APPLY(max,0) - grid_x; - constexpr float grid_h = APPLY(max,1) - grid_y; - constexpr float grid_cx = grid_x + grid_w/2; - constexpr float grid_cy = grid_y + grid_h/2; - - // Figure out scale and offset such that the grid fits within the rectangle given by (x,y,w,h) - - const float scale_x = float(w)/grid_w; - const float scale_y = float(h)/grid_h; - const float center_x = x + w/2; - const float center_y = y + h/2; - - // Now replace the last transformation in the chain with a scaling operation. - - #undef TRANSFORM_5 - #define TRANSFORM_6(X,Y,Z) (X)*16, (Y)*16 // Scale to 1/16 pixel units - #define TRANSFORM_5(X,Y,Z) TRANSFORM_6( center_x + ((X) - grid_cx) * scale_x, \ - center_y + ((Y) - grid_cy) * scale_y, 0) // Scale to bounds - - // Draw the grid - - const uint16_t basePointSize = min(w,h) / max(cols,rows); - - CommandProcessor cmd; - cmd.cmd(SAVE_CONTEXT()) - .cmd(TAG_MASK(false)) - .cmd(SAVE_CONTEXT()); - - for (uint8_t y = 0; y < rows; y++) { - for (uint8_t x = 0; x < cols; x++) { - if (ISVAL(x,y)) { - const bool hasLeftSegment = x < cols - 1 && ISVAL(x+1,y); - const bool hasRightSegment = y < rows - 1 && ISVAL(x,y+1); - if (hasLeftSegment || hasRightSegment) { - cmd.cmd(BEGIN(LINE_STRIP)); - if (hasLeftSegment) cmd.cmd(VERTEX2F(TRANSFORM(x + 1, y , HEIGHT(x + 1, y )))); - cmd.cmd( VERTEX2F(TRANSFORM(x , y , HEIGHT(x , y )))); - if (hasRightSegment) cmd.cmd(VERTEX2F(TRANSFORM(x , y + 1, HEIGHT(x , y + 1)))); - } - } - } - - if (opts & USE_POINTS) { - const float sq_min = sq(val_min - val_mean); - const float sq_max = sq(val_max - val_mean); - cmd.cmd(POINT_SIZE(basePointSize * 2)); - cmd.cmd(BEGIN(POINTS)); - for (uint8_t x = 0; x < cols; x++) { - if (ISVAL(x,y)) { - if (opts & USE_COLORS) { - const float val_dev = VALUE(x, y) - val_mean; - const uint8_t neg_byte = sq(val_dev) / (val_dev < 0 ? sq_min : sq_max) * 0xFF; - const uint8_t pos_byte = 255 - neg_byte; - cmd.cmd(COLOR_RGB(pos_byte, pos_byte, 0xFF)); - } - cmd.cmd(VERTEX2F(TRANSFORM(x, y, HEIGHT(x, y)))); - } - } - if (opts & USE_COLORS) { - cmd.cmd(RESTORE_CONTEXT()) - .cmd(SAVE_CONTEXT()); - } - } - } - cmd.cmd(RESTORE_CONTEXT()) - .cmd(TAG_MASK(true)); - - if (opts & USE_TAGS) { - cmd.cmd(COLOR_MASK(false, false, false, false)) - .cmd(POINT_SIZE(basePointSize * 10)) - .cmd(BEGIN(POINTS)); - for (uint8_t y = 0; y < rows; y++) { - for (uint8_t x = 0; x < cols; x++) { - const uint8_t tag = pointToTag(x, y); - cmd.tag(tag).cmd(VERTEX2F(TRANSFORM(x, y, HEIGHT(x, y)))); - } - } - cmd.cmd(COLOR_MASK(true, true, true, true)); - } - - if (opts & USE_HIGHLIGHT) { - const uint8_t tag = screen_data.BedMeshScreen.highlightedTag; - uint8_t x, y; - if (tagToPoint(tag, x, y)) { - cmd.cmd(COLOR_A(128)) - .cmd(POINT_SIZE(basePointSize * 6)) - .cmd(BEGIN(POINTS)) - .tag(tag).cmd(VERTEX2F(TRANSFORM(x, y, HEIGHT(x, y)))); - } - } - cmd.cmd(END()); - cmd.cmd(RESTORE_CONTEXT()); -} - -uint8_t BedMeshScreen::pointToTag(uint8_t x, uint8_t y) { - return y * (GRID_MAX_POINTS_X) + x + 10; -} - -bool BedMeshScreen::tagToPoint(uint8_t tag, uint8_t &x, uint8_t &y) { - if (tag < 10) return false; - x = (tag - 10) % (GRID_MAX_POINTS_X); - y = (tag - 10) / (GRID_MAX_POINTS_X); - return true; -} - -void BedMeshScreen::onEntry() { - screen_data.BedMeshScreen.highlightedTag = 0; - screen_data.BedMeshScreen.count = GRID_MAX_POINTS; - screen_data.BedMeshScreen.message = screen_data.BedMeshScreen.MSG_NONE; - BaseScreen::onEntry(); -} - -float BedMeshScreen::getHightlightedValue() { - if (screen_data.BedMeshScreen.highlightedTag) { - xy_uint8_t pt; - tagToPoint(screen_data.BedMeshScreen.highlightedTag, pt.x, pt.y); - return ExtUI::getMeshPoint(pt); - } - return NAN; -} - -void BedMeshScreen::drawHighlightedPointValue() { - char str[16]; - const float val = getHightlightedValue(); - const bool isGood = !isnan(val); - if (isGood) - dtostrf(val, 5, 3, str); - else - strcpy_P(str, PSTR("-")); - - CommandProcessor cmd; - cmd.font(Theme::font_medium) - .text(Z_LABEL_POS, GET_TEXT_F(MSG_MESH_EDIT_Z)) - .text(Z_VALUE_POS, str) - .colors(action_btn) - .tag(1).button( OKAY_POS, GET_TEXT_F(MSG_BUTTON_OKAY)) - .tag(0); - - switch (screen_data.BedMeshScreen.message) { - case screen_data.BedMeshScreen.MSG_MESH_COMPLETE: cmd.text(MESSAGE_POS, GET_TEXT_F(MSG_BED_MAPPING_DONE)); break; - case screen_data.BedMeshScreen.MSG_MESH_INCOMPLETE: cmd.text(MESSAGE_POS, GET_TEXT_F(MSG_BED_MAPPING_INCOMPLETE)); break; - default: break; - } -} - -void BedMeshScreen::onRedraw(draw_mode_t what) { - #define _INSET_POS(x,y,w,h) x + min(w,h)/10, y + min(w,h)/10, w - min(w,h)/5, h - min(w,h)/5 - #define INSET_POS(pos) _INSET_POS(pos) - - if (what & BACKGROUND) { - CommandProcessor cmd; - cmd.cmd(CLEAR_COLOR_RGB(bg_color)) - .cmd(CLEAR(true,true,true)); - - // Draw the shadow and tags - cmd.cmd(COLOR_RGB(0x444444)); - BedMeshScreen::drawMesh(INSET_POS(MESH_POS), nullptr, USE_POINTS | USE_TAGS); - cmd.cmd(COLOR_RGB(bg_text_enabled)); - } - - if (what & FOREGROUND) { - constexpr float autoscale_max_amplitude = 0.03; - const bool gotAllPoints = screen_data.BedMeshScreen.count >= GRID_MAX_POINTS; - if (gotAllPoints) { - drawHighlightedPointValue(); - } - const float levelingProgress = sq(float(screen_data.BedMeshScreen.count) / GRID_MAX_POINTS); - BedMeshScreen::drawMesh(INSET_POS(MESH_POS), ExtUI::getMeshArray(), - USE_POINTS | USE_HIGHLIGHT | USE_AUTOSCALE | (gotAllPoints ? USE_COLORS : 0), - autoscale_max_amplitude * levelingProgress - ); - } -} - -bool BedMeshScreen::onTouchStart(uint8_t tag) { - screen_data.BedMeshScreen.highlightedTag = tag; - return true; -} - -bool BedMeshScreen::onTouchEnd(uint8_t tag) { - switch (tag) { - case 1: - GOTO_PREVIOUS(); - return true; - default: - return false; - } -} - -void BedMeshScreen::onMeshUpdate(const int8_t, const int8_t, const float) { - if (AT_SCREEN(BedMeshScreen)) - onRefresh(); -} - -bool BedMeshScreen::isMeshComplete(ExtUI::bed_mesh_t data) { - for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) { - for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) { - if (isnan(data[x][y])) { - return false; - } - } - } - return true; -} - -void BedMeshScreen::onMeshUpdate(const int8_t x, const int8_t y, const ExtUI::probe_state_t state) { - switch (state) { - case ExtUI::MESH_START: - screen_data.BedMeshScreen.count = 0; - screen_data.BedMeshScreen.message = screen_data.BedMeshScreen.MSG_NONE; - break; - case ExtUI::MESH_FINISH: - if (screen_data.BedMeshScreen.count == GRID_MAX_POINTS && isMeshComplete(ExtUI::getMeshArray())) { - screen_data.BedMeshScreen.message = screen_data.BedMeshScreen.MSG_MESH_COMPLETE; - } else { - screen_data.BedMeshScreen.message = screen_data.BedMeshScreen.MSG_MESH_INCOMPLETE; - } - screen_data.BedMeshScreen.count = GRID_MAX_POINTS; - break; - case ExtUI::PROBE_START: - screen_data.BedMeshScreen.highlightedTag = pointToTag(x, y); - break; - case ExtUI::PROBE_FINISH: - screen_data.BedMeshScreen.count++; - break; - } - BedMeshScreen::onMeshUpdate(x, y, 0); -} - -void BedMeshScreen::startMeshProbe() { - GOTO_SCREEN(BedMeshScreen); - screen_data.BedMeshScreen.count = 0; - injectCommands_P(PSTR(BED_LEVELING_COMMANDS)); -} - -#endif // TOUCH_UI_FTDI_EVE && HAS_MESH diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp deleted file mode 100644 index 76ebdca587e4..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp +++ /dev/null @@ -1,137 +0,0 @@ -/***************************** - * bio_advanced_settings.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" - -#if ENABLED(TOUCH_UI_FTDI_EVE) && defined(TOUCH_UI_LULZBOT_BIO) - -#include "screens.h" - -using namespace FTDI; -using namespace Theme; - -void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { - if (what & BACKGROUND) { - CommandProcessor cmd; - cmd.cmd(CLEAR_COLOR_RGB(Theme::bg_color)) - .cmd(CLEAR(true,true,true)); - } - - if (what & FOREGROUND) { - CommandProcessor cmd; - cmd.colors(normal_btn) - .font(Theme::font_medium) - #define GRID_ROWS 9 - #define GRID_COLS 2 - - .tag(2) .button( BTN_POS(1,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_DISPLAY_MENU)) - .enabled( - #if HAS_TRINAMIC_CONFIG - 1 - #endif - ) - .tag(3) .button( BTN_POS(1,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_TMC_CURRENT)) - .enabled( - #if HAS_TRINAMIC_CONFIG - 1 - #endif - ) - .tag(4) .button( BTN_POS(1,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_TMC_HOMING_THRS)) - .tag(5) .button( BTN_POS(1,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_LCD_ENDSTOPS)) - .enabled( - #if HAS_MULTI_HOTEND - 1 - #endif - ) - .tag(6) .button( BTN_POS(1,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_OFFSETS_MENU)) - - - .tag(7) .button( BTN_POS(2,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_STEPS_PER_MM)) - .tag(8) .button( BTN_POS(2,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_VELOCITY)) - .tag(9) .button( BTN_POS(2,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_ACCELERATION)) - #if HAS_JUNCTION_DEVIATION - .tag(10) .button( BTN_POS(2,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_JUNCTION_DEVIATION)) - #else - .tag(10) .button( BTN_POS(2,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_JERK)) - #endif - .enabled( - #if ENABLED(BACKLASH_GCODE) - 1 - #endif - ) - .tag(11) .button( BTN_POS(2,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_BACKLASH)) - .enabled( - #if ENABLED(LIN_ADVANCE) - 1 - #endif - ) - .tag(12) .button( BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_LINEAR_ADVANCE)) - .tag(13) .button( BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_INTERFACE)) - .tag(14) .button( BTN_POS(1,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_RESTORE_DEFAULTS)) - .colors(action_btn) - .tag(1). button( BTN_POS(1,9), BTN_SIZE(2,1), GET_TEXT_F(MSG_BACK)); - #undef GRID_COLS - #undef GRID_ROWS - } -} - -bool AdvancedSettingsMenu::onTouchEnd(uint8_t tag) { - using namespace ExtUI; - - switch (tag) { - case 1: SaveSettingsDialogBox::promptToSaveSettings(); break; - case 2: GOTO_SCREEN(DisplayTuningScreen); break; - #if HAS_TRINAMIC_CONFIG - case 3: GOTO_SCREEN(StepperCurrentScreen); break; - case 4: GOTO_SCREEN(StepperBumpSensitivityScreen); break; - #endif - case 5: GOTO_SCREEN(EndstopStatesScreen); break; - #if HAS_MULTI_HOTEND - case 6: GOTO_SCREEN(NozzleOffsetScreen); break; - #endif - - case 7: GOTO_SCREEN(StepsScreen); break; - case 8: GOTO_SCREEN(MaxVelocityScreen); break; - case 9: GOTO_SCREEN(DefaultAccelerationScreen); break; - case 10: - #if HAS_JUNCTION_DEVIATION - GOTO_SCREEN(JunctionDeviationScreen); - #else - GOTO_SCREEN(JerkScreen); - #endif - break; - #if ENABLED(BACKLASH_GCODE) - case 11: GOTO_SCREEN(BacklashCompensationScreen); break; - #endif - #if ENABLED(LIN_ADVANCE) - case 12: GOTO_SCREEN(LinearAdvanceScreen); break; - #endif - case 13: GOTO_SCREEN(InterfaceSettingsScreen); break; - case 14: GOTO_SCREEN(RestoreFailsafeDialogBox); break; - - default: - return false; - } - return true; -} - -#endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_e.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_e.cpp deleted file mode 100644 index da772971ce01..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_e.cpp +++ /dev/null @@ -1,56 +0,0 @@ -/**************************** - * bio_confirm_home_xyz.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" - -#if ENABLED(TOUCH_UI_FTDI_EVE) && defined(TOUCH_UI_LULZBOT_BIO) - -#include "screens.h" - -using namespace FTDI; - -void BioConfirmHomeE::onRedraw(draw_mode_t) { - drawMessage(GET_TEXT_F(MSG_HOME_E_WARNING)); - drawYesNoButtons(1); -} - -bool BioConfirmHomeE::onTouchEnd(uint8_t tag) { - switch (tag) { - case 1: - #if defined(AXIS_LEVELING_COMMANDS) && defined(PARK_AND_RELEASE_COMMANDS) - SpinnerDialogBox::enqueueAndWait_P(F( - "G28 E\n" - AXIS_LEVELING_COMMANDS "\n" - PARK_AND_RELEASE_COMMANDS - )); - #endif - current_screen.forget(); - break; - case 2: - GOTO_SCREEN(StatusScreen); - break; - default: - return DialogBoxBaseClass::onTouchEnd(tag); - } - return true; -} -#endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.cpp deleted file mode 100644 index 48ce320482b2..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.cpp +++ /dev/null @@ -1,55 +0,0 @@ -/**************************** - * bio_confirm_home_xyz.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" - -#if ENABLED(TOUCH_UI_FTDI_EVE) && defined(TOUCH_UI_LULZBOT_BIO) - -#include "screens.h" - -using namespace FTDI; - -void BioConfirmHomeXYZ::onRedraw(draw_mode_t) { - drawMessage(GET_TEXT_F(MSG_HOME_XYZ_WARNING)); - drawYesNoButtons(1); -} - -bool BioConfirmHomeXYZ::onTouchEnd(uint8_t tag) { - switch (tag) { - case 1: - #ifdef PARK_AND_RELEASE_COMMANDS - SpinnerDialogBox::enqueueAndWait_P(F( - "G28\n" - PARK_AND_RELEASE_COMMANDS - )); - #endif - current_screen.forget(); - break; - case 2: - GOTO_SCREEN(StatusScreen); - break; - default: - return DialogBoxBaseClass::onTouchEnd(tag); - } - return true; -} -#endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_main_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_main_menu.cpp deleted file mode 100644 index e2bb8a241402..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_main_menu.cpp +++ /dev/null @@ -1,88 +0,0 @@ -/********************* - * bio_main_menu.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" - -#if ENABLED(TOUCH_UI_FTDI_EVE) && defined(TOUCH_UI_LULZBOT_BIO) - -#include "screens.h" - -using namespace FTDI; -using namespace Theme; - -void MainMenu::onRedraw(draw_mode_t what) { - #define GRID_ROWS 10 - #define GRID_COLS 2 - - if (what & BACKGROUND) { - CommandProcessor cmd; - cmd.cmd(CLEAR_COLOR_RGB(Theme::bg_color)) - .cmd(CLEAR(true,true,true)) - .tag(0); - } - - 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)) - .colors(normal_btn) - .font(font_medium) - .tag(2).button( BTN_POS(1,2), BTN_SIZE(2,1), GET_TEXT_F(MSG_MOVE_TO_HOME)) - .tag(3).button( BTN_POS(1,3), BTN_SIZE(2,1), GET_TEXT_F(MSG_RAISE_PLUNGER)) - .tag(4).button( BTN_POS(1,4), BTN_SIZE(2,1), GET_TEXT_F(MSG_RELEASE_XY_AXIS)) - .tag(5).button( BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_AUTOLEVEL_X_AXIS)) - .tag(6).button( BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_BED_TEMPERATURE)) - .tag(7).button( BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_INTERFACE)) - .tag(8).button( BTN_POS(1,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_ADVANCED_SETTINGS)) - .tag(9).button( BTN_POS(1,9), BTN_SIZE(2,1), GET_TEXT_F(MSG_INFO_MENU)) - .colors(action_btn) - .tag(1).button( BTN_POS(1,10), BTN_SIZE(2,1), GET_TEXT_F(MSG_BACK)); - } - - #undef GRID_COLS - #undef GRID_ROWS -} - -bool MainMenu::onTouchEnd(uint8_t tag) { - using namespace ExtUI; - - const bool e_homed = isAxisPositionKnown(E0); - - switch (tag) { - case 1: SaveSettingsDialogBox::promptToSaveSettings(); break; - case 2: GOTO_SCREEN(BioConfirmHomeXYZ); break; - case 3: SpinnerDialogBox::enqueueAndWait_P(e_homed ? F("G0 E0 F120") : F("G112")); break; - case 4: StatusScreen::unlockMotors(); break; - #ifdef AXIS_LEVELING_COMMANDS - case 5: SpinnerDialogBox::enqueueAndWait_P(F(AXIS_LEVELING_COMMANDS)); break; - #endif - case 6: GOTO_SCREEN(TemperatureScreen); break; - case 7: GOTO_SCREEN(InterfaceSettingsScreen); break; - case 8: GOTO_SCREEN(AdvancedSettingsMenu); break; - case 9: GOTO_SCREEN(AboutScreen); break; - default: - return false; - } - return true; -} - -#endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_printer_ui_landscape.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_printer_ui_landscape.h deleted file mode 100644 index 9279fd7df0d6..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_printer_ui_landscape.h +++ /dev/null @@ -1,59 +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.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 z_neg[] = {0x7950, 0x51EA, 0x824E, 0x51EA, 0x824E, 0x71E2, 0x86CD, 0x71E2, 0x7DCF, 0x81DF, 0x74D1, 0x71E2, 0x7950, 0x71E2, 0x7950, 0x51EA}; -const PROGMEM uint16_t z_pos[] = {0x7950, 0x41EE, 0x824E, 0x41EE, 0x824E, 0x21F5, 0x86CD, 0x21F5, 0x7DCF, 0x11F9, 0x74D0, 0x21F5, 0x7950, 0x21F5, 0x7950, 0x41EE}; -const PROGMEM uint16_t y_neg[] = {0x3479, 0x56CF, 0x3EC6, 0x56CF, 0x3747, 0x7281, 0x3C6D, 0x7281, 0x2E61, 0x8059, 0x27D4, 0x7281, 0x2CFA, 0x7281, 0x3479, 0x56CF}; -const PROGMEM uint16_t y_pos[] = {0x3BF9, 0x3B1D, 0x4645, 0x3B1D, 0x4DC4, 0x1F6B, 0x52EB, 0x1F6B, 0x4C5E, 0x1192, 0x3E52, 0x1F6B, 0x4378, 0x1F6B, 0x3BF9, 0x3B1D}; -const PROGMEM uint16_t x_neg[] = {0x350E, 0x4209, 0x314E, 0x4FE2, 0x1CB5, 0x4FE2, 0x1AD6, 0x56CF, 0x1449, 0x48F6, 0x2255, 0x3B1D, 0x2075, 0x4209, 0x350E, 0x4209}; -const PROGMEM uint16_t x_pos[] = {0x498C, 0x4209, 0x45CC, 0x4FE2, 0x5A65, 0x4FE2, 0x5885, 0x56CF, 0x6691, 0x48F6, 0x6004, 0x3B1D, 0x5E25, 0x4209, 0x498C, 0x4209}; -const PROGMEM uint16_t syringe_fluid[] = {0xB4E9, 0x78BE, 0xBB12, 0x7C44, 0xBDE3, 0x7C44, 0xC426, 0x78BE, 0xC426, 0x250D, 0xB4E9, 0x250D, 0xB4E9, 0x78BE}; -const PROGMEM uint16_t syringe[] = {0xB8AD, 0x6BB1, 0xB8AD, 0x6E0C, 0xBE02, 0x6E0C, 0xBE02, 0x6BB1, 0xFFFF, 0xB8AD, 0x6248, 0xB8AD, 0x64A2, 0xBE02, 0x64A2, 0xBE02, 0x6248, 0xFFFF, 0xB8AD, 0x58DF, 0xB8AD, 0x5B39, 0xBE02, 0x5B39, 0xBE02, 0x58DF, 0xFFFF, 0xB8AD, 0x4F75, 0xB8AD, 0x51D0, 0xBE02, 0x51D0, 0xBE02, 0x4F75, 0xFFFF, 0xB8AD, 0x460C, 0xB8AD, 0x4866, 0xBE02, 0x4866, 0xBE02, 0x460C, 0xFFFF, 0xB8AD, 0x3CA3, 0xB8AD, 0x3EFD, 0xBE02, 0x3EFD, 0xBE02, 0x3CA3, 0xFFFF, 0xB8AD, 0x3339, 0xB8AD, 0x3594, 0xBE02, 0x3594, 0xBE02, 0x3339, 0xFFFF, 0xB396, 0x110A, 0xB396, 0x1818, 0xB995, 0x1818, 0xB995, 0x22AD, 0xB396, 0x22AD, 0xB396, 0x7ADA, 0xB995, 0x7E61, 0xB995, 0x88F5, 0xBB95, 0x88F5, 0xBB95, 0xA8B4, 0xBD94, 0xAC3B, 0xBD94, 0x88F5, 0xBF94, 0x88F5, 0xBF94, 0x7E61, 0xC593, 0x7ADA, 0xC593, 0x22AD, 0xBF94, 0x22AD, 0xBF94, 0x1818, 0xC593, 0x1818, 0xC593, 0x110A, 0xFFFF, 0xBB95, 0x1818, 0xBD94, 0x1818, 0xBD94, 0x22AD, 0xBB95, 0x22AD, 0xBB95, 0x1818, 0xFFFF, 0xB596, 0x2634, 0xC393, 0x2634, 0xC393, 0x7753, 0xBD94, 0x7ADA, 0xBB95, 0x7ADA, 0xB596, 0x7753, 0xB596, 0x2634}; -const PROGMEM uint16_t syringe_outline[] = {0xB396, 0x110A, 0xB396, 0x1818, 0xB995, 0x1818, 0xB995, 0x22AD, 0xB396, 0x22AD, 0xB396, 0x7ADA, 0xB995, 0x7E61, 0xB995, 0x88F5, 0xBB95, 0x88F5, 0xBB95, 0xA8B4, 0xBD94, 0xAC3B, 0xBD94, 0x88F5, 0xBF94, 0x88F5, 0xBF94, 0x7E61, 0xC593, 0x7ADA, 0xC593, 0x22AD, 0xBF94, 0x22AD, 0xBF94, 0x1818, 0xC593, 0x1818, 0xC593, 0x110A, 0xB396, 0x110A}; -const PROGMEM uint16_t padlock[] = {0x3FE3, 0x2A04, 0x3D34, 0x2AF9, 0x3AFF, 0x2D93, 0x397D, 0x316D, 0x38E8, 0x3626, 0x38E8, 0x3A14, 0x39B3, 0x3C8F, 0x3B50, 0x3C8F, 0x3C1C, 0x3A14, 0x3C1C, 0x363C, 0x3C6B, 0x33A9, 0x3D3A, 0x3193, 0x3E6C, 0x302D, 0x3FE3, 0x2FAA, 0x415A, 0x302D, 0x428C, 0x3192, 0x435B, 0x33A8, 0x43AB, 0x363C, 0x43AB, 0x4492, 0x38C3, 0x4492, 0x3741, 0x45AC, 0x36A1, 0x4856, 0x36A1, 0x5C41, 0x3741, 0x5EEC, 0x38C3, 0x6005, 0x4703, 0x6005, 0x4886, 0x5EEC, 0x4925, 0x5C41, 0x4925, 0x4856, 0x4886, 0x45AC, 0x4703, 0x4492, 0x46DE, 0x362B, 0x4649, 0x316D, 0x44C7, 0x2D92, 0x4292, 0x2AF9}; -const PROGMEM uint16_t home_z[] = {0x80BB, 0x2B43, 0x712C, 0x46B9, 0x750F, 0x46B9, 0x750F, 0x622F, 0x7CD7, 0x622F, 0x7CD7, 0x5474, 0x849F, 0x5474, 0x849F, 0x622F, 0x8C67, 0x622F, 0x8C67, 0x46B9, 0x904B, 0x46B9, 0x8A48, 0x3C1D, 0x8A48, 0x2ECD, 0x8664, 0x2ECD, 0x8664, 0x3540}; -const PROGMEM uint16_t usb_btn[] = {0x0558, 0xC0D6, 0x3BDB, 0xC0D6, 0x3BDB, 0xF431, 0x0558, 0xF431, 0x0558, 0xC0D6}; -const PROGMEM uint16_t menu_btn[] = {0x416B, 0xC0D6, 0x77EE, 0xC0D6, 0x77EE, 0xF431, 0x416B, 0xF431, 0x416B, 0xC0D6}; -const PROGMEM uint16_t e_pos[] = {0xE04E, 0x5E7B, 0xE94C, 0x5E7B, 0xE94C, 0x7E74, 0xEDCB, 0x7E74, 0xE4CD, 0x8E70, 0xDBCF, 0x7E74, 0xE04E, 0x7E74, 0xE04E, 0x5E7B}; -const PROGMEM uint16_t e_neg[] = {0xE04E, 0x4E7F, 0xE94C, 0x4E7F, 0xE94C, 0x2E87, 0xEDCB, 0x2E87, 0xE4CD, 0x1E8A, 0xDBCF, 0x2E87, 0xE04E, 0x2E87, 0xE04E, 0x4E7F}; -const PROGMEM uint16_t home_e[] = {0xD705, 0x3885, 0xC775, 0x53FB, 0xCB59, 0x53FB, 0xCB59, 0x6F71, 0xD321, 0x6F71, 0xD321, 0x61B6, 0xDAE9, 0x61B6, 0xDAE9, 0x6F71, 0xE2B1, 0x6F71, 0xE2B1, 0x53FB, 0xE695, 0x53FB, 0xE092, 0x495F, 0xE092, 0x3C0E, 0xDCAE, 0x3C0E, 0xDCAE, 0x4281}; -const PROGMEM uint16_t fine_label[] = {0x0D92, 0x9444, 0x5211, 0x9444, 0x5211, 0xA9EA, 0x0D92, 0xA9EA}; -const PROGMEM uint16_t fine_toggle[] = {0x56E7, 0x9444, 0x8007, 0x9444, 0x8007, 0xA9EA, 0x56E7, 0xA9EA}; -const PROGMEM uint16_t h1_temp[] = {0x9C2B, 0xDD3B, 0xBBDE, 0xDD3B, 0xBBDE, 0xFA57, 0x9C2B, 0xFA57}; -const PROGMEM uint16_t h1_label[] = {0x9C2B, 0xBE8F, 0xBBDC, 0xBE8F, 0xBBDC, 0xDBAA, 0x9C2B, 0xDBAA}; -const PROGMEM uint16_t h0_temp[] = {0x7BD0, 0xDD3B, 0x9B83, 0xDD3B, 0x9B83, 0xFA57, 0x7BD0, 0xFA57}; -const PROGMEM uint16_t h0_label[] = {0x7BD0, 0xBE8F, 0x9B83, 0xBE8F, 0x9B83, 0xDBAA, 0x7BD0, 0xDBAA}; -const PROGMEM uint16_t h2_temp[] = {0xBC86, 0xDD3B, 0xDC39, 0xDD3B, 0xDC39, 0xFA57, 0xBC86, 0xFA57}; -const PROGMEM uint16_t h2_label[] = {0xBC86, 0xBE8F, 0xDC37, 0xBE8F, 0xDC37, 0xDBAA, 0xBC86, 0xDBAA}; -const PROGMEM uint16_t h3_temp[] = {0xDCE2, 0xDD0D, 0xFC95, 0xDD0D, 0xFC95, 0xFA28, 0xDCE2, 0xFA28}; -const PROGMEM uint16_t h3_label[] = {0xDCE2, 0xBE60, 0xFC92, 0xBE60, 0xFC92, 0xDB7C, 0xDCE2, 0xDB7C}; -const PROGMEM uint16_t actual_temp[] = {0xCDF6, 0xD037, 0xF7CA, 0xD037, 0xF7CA, 0xF424, 0xCDF6, 0xF424}; -const PROGMEM uint16_t bed_icon[] = {0xCDF6, 0xA5CC, 0xF7CA, 0xA5CC, 0xF7CA, 0xC9B9, 0xCDF6, 0xC9B9}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_printer_ui_portrait.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_printer_ui_portrait.h deleted file mode 100644 index f03e3413f833..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_printer_ui_portrait.h +++ /dev/null @@ -1,52 +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.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 = 272.000000; -constexpr float y_min = 0.000000; -constexpr float y_max = 480.000000; - -const PROGMEM uint16_t z_neg[] = {0xC9B1, 0x96B3, 0xD990, 0x96B3, 0xD990, 0xA8D0, 0xE17F, 0xA8D0, 0xD1A0, 0xB1DF, 0xC1C2, 0xA8D0, 0xC9B1, 0xA8D0, 0xC9B1, 0x96B3}; -const PROGMEM uint16_t z_pos[] = {0xC9B1, 0x8DA4, 0xD990, 0x8DA4, 0xD990, 0x7B86, 0xE17F, 0x7B86, 0xD1A0, 0x7277, 0xC1C2, 0x7B86, 0xC9B1, 0x7B86, 0xC9B1, 0x8DA4}; -const PROGMEM uint16_t y_neg[] = {0x5037, 0x9979, 0x6264, 0x9979, 0x5529, 0xA92A, 0x5E3F, 0xA92A, 0x4575, 0xB103, 0x39E6, 0xA92A, 0x42FC, 0xA92A, 0x5037, 0x9979}; -const PROGMEM uint16_t y_pos[] = {0x5D72, 0x89C7, 0x6F9F, 0x89C7, 0x7CDA, 0x7A15, 0x85F0, 0x7A15, 0x7A61, 0x723D, 0x6197, 0x7A15, 0x6AAD, 0x7A15, 0x5D72, 0x89C7}; -const PROGMEM uint16_t x_neg[] = {0x513D, 0x8DB3, 0x4AA0, 0x958C, 0x2647, 0x958C, 0x22F8, 0x9979, 0x1769, 0x91A0, 0x3033, 0x89C7, 0x2CE4, 0x8DB3, 0x513D, 0x8DB3}; -const PROGMEM uint16_t x_pos[] = {0x7566, 0x8DB3, 0x6EC9, 0x958C, 0x9322, 0x958C, 0x8FD4, 0x9979, 0xA89E, 0x91A0, 0x9D0E, 0x89C7, 0x99C0, 0x8DB3, 0x7566, 0x8DB3}; -const PROGMEM uint16_t syringe_fluid[] = {0x7D1D, 0x4A0F, 0x87FC, 0x4C0E, 0x8CF4, 0x4C0E, 0x9801, 0x4A0F, 0x9801, 0x1AA2, 0x7D1D, 0x1AA2, 0x7D1D, 0x4A0F}; -const PROGMEM uint16_t syringe[] = {0x83C2, 0x42AA, 0x83C2, 0x43FF, 0x8D2C, 0x43FF, 0x8D2C, 0x42AA, 0xFFFF, 0x83C2, 0x3D54, 0x83C2, 0x3EAA, 0x8D2C, 0x3EAA, 0x8D2C, 0x3D54, 0xFFFF, 0x83C2, 0x37FF, 0x83C2, 0x3954, 0x8D2C, 0x3954, 0x8D2C, 0x37FF, 0xFFFF, 0x83C2, 0x32AA, 0x83C2, 0x33FF, 0x8D2C, 0x33FF, 0x8D2C, 0x32AA, 0xFFFF, 0x83C2, 0x2D54, 0x83C2, 0x2EAA, 0x8D2C, 0x2EAA, 0x8D2C, 0x2D54, 0xFFFF, 0x83C2, 0x27FF, 0x83C2, 0x2955, 0x8D2C, 0x2955, 0x8D2C, 0x27FF, 0xFFFF, 0x83C2, 0x22AA, 0x83C2, 0x23FF, 0x8D2C, 0x23FF, 0x8D2C, 0x22AA, 0xFFFF, 0x7AC7, 0x0F4B, 0x7AC7, 0x134A, 0x855B, 0x134A, 0x855B, 0x1949, 0x7AC7, 0x1949, 0x7AC7, 0x4B40, 0x855B, 0x4D40, 0x855B, 0x533F, 0x88E2, 0x533F, 0x88E2, 0x653C, 0x8C69, 0x673C, 0x8C69, 0x533F, 0x8FF0, 0x533F, 0x8FF0, 0x4D40, 0x9A85, 0x4B40, 0x9A85, 0x1949, 0x8FF0, 0x1949, 0x8FF0, 0x134A, 0x9A85, 0x134A, 0x9A85, 0x0F4B, 0xFFFF, 0x88E2, 0x134A, 0x8C69, 0x134A, 0x8C69, 0x1949, 0x88E2, 0x1949, 0x88E2, 0x134A, 0xFFFF, 0x7E4D, 0x1B49, 0x96FE, 0x1B49, 0x96FE, 0x4941, 0x8C69, 0x4B40, 0x88E2, 0x4B40, 0x7E4D, 0x4941, 0x7E4D, 0x1B49}; -const PROGMEM uint16_t syringe_outline[] = {0x7AC7, 0x0F4B, 0x7AC7, 0x134A, 0x855B, 0x134A, 0x855B, 0x1949, 0x7AC7, 0x1949, 0x7AC7, 0x4B40, 0x855B, 0x4D40, 0x855B, 0x533F, 0x88E2, 0x533F, 0x88E2, 0x653C, 0x8C69, 0x673C, 0x8C69, 0x533F, 0x8FF0, 0x533F, 0x8FF0, 0x4D40, 0x9A85, 0x4B40, 0x9A85, 0x1949, 0x8FF0, 0x1949, 0x8FF0, 0x134A, 0x9A85, 0x134A, 0x9A85, 0x0F4B, 0x7AC7, 0x0F4B}; -const PROGMEM uint16_t padlock[] = {0x645A, 0x8017, 0x5F9E, 0x80A1, 0x5BBA, 0x821B, 0x5911, 0x844A, 0x580A, 0x86F7, 0x580A, 0x8931, 0x5970, 0x8A98, 0x5C49, 0x8A98, 0x5DB0, 0x8931, 0x5DB0, 0x8703, 0x5E3C, 0x858E, 0x5FAA, 0x845F, 0x61C5, 0x8394, 0x645A, 0x834A, 0x66F0, 0x8394, 0x690C, 0x845F, 0x6A7A, 0x858D, 0x6B07, 0x8703, 0x6B07, 0x8F23, 0x57C8, 0x8F23, 0x551E, 0x8FC3, 0x5404, 0x9145, 0x5404, 0x9C8F, 0x551E, 0x9E11, 0x57C8, 0x9EB1, 0x70EE, 0x9EB1, 0x7398, 0x9E11, 0x74B2, 0x9C8F, 0x74B2, 0x9145, 0x7398, 0x8FC3, 0x70EE, 0x8F23, 0x70AC, 0x86FA, 0x6FA5, 0x844A, 0x6CFD, 0x821B, 0x6917, 0x80A1}; -const PROGMEM uint16_t home_z[] = {0xD6C9, 0x80CC, 0xBB53, 0x905B, 0xC231, 0x905B, 0xC231, 0x9FEB, 0xCFEC, 0x9FEB, 0xCFEC, 0x9823, 0xDDA7, 0x9823, 0xDDA7, 0x9FEB, 0xEB62, 0x9FEB, 0xEB62, 0x905B, 0xF240, 0x905B, 0xE7A3, 0x8A58, 0xE7A3, 0x82CD, 0xE0C6, 0x82CD, 0xE0C6, 0x8674}; -const PROGMEM uint16_t home_e[] = {0xB94F, 0x25AA, 0x9DD8, 0x353A, 0xA4B6, 0x353A, 0xA4B6, 0x44C9, 0xB271, 0x44C9, 0xB271, 0x3D02, 0xC02C, 0x3D02, 0xC02C, 0x44C9, 0xCDE7, 0x44C9, 0xCDE7, 0x353A, 0xD4C5, 0x353A, 0xCA28, 0x2F36, 0xCA28, 0x27AB, 0xC34B, 0x27AB, 0xC34B, 0x2B53}; -const PROGMEM uint16_t bed_icon[] = {0x1764, 0x2C4C, 0x6135, 0x2C4C, 0x6135, 0x40A8, 0x1764, 0x40A8}; -const PROGMEM uint16_t actual_temp[] = {0x1764, 0x466F, 0x6135, 0x466F, 0x6135, 0x5ACB, 0x1764, 0x5ACB}; -const PROGMEM uint16_t target_temp[] = {0x1764, 0x1228, 0x6135, 0x1228, 0x6135, 0x2684, 0x1764, 0x2684}; -const PROGMEM uint16_t fine_label[] = {0x1AA7, 0xC6D2, 0x9387, 0xC6D2, 0x9387, 0xD316, 0x1AA7, 0xD316}; -const PROGMEM uint16_t fine_toggle[] = {0x9C10, 0xC6D2, 0xE4A3, 0xC6D2, 0xE4A3, 0xD316, 0x9C10, 0xD316}; -const PROGMEM uint16_t usb_btn[] = {0x0B68, 0xE880, 0x7B1A, 0xE880, 0x7B1A, 0xF94B, 0x0B68, 0xF94B, 0x0B68, 0xE880}; -const PROGMEM uint16_t menu_btn[] = {0x84E3, 0xE880, 0xF495, 0xE880, 0xF495, 0xF94B, 0x84E3, 0xF94B, 0x84E3, 0xE880}; -const PROGMEM uint16_t e_pos[] = {0xC9B1, 0x3B2D, 0xD990, 0x3B2D, 0xD990, 0x4D4B, 0xE17F, 0x4D4B, 0xD1A0, 0x565A, 0xC1C2, 0x4D4B, 0xC9B1, 0x4D4B, 0xC9B1, 0x3B2D}; -const PROGMEM uint16_t e_neg[] = {0xC9B1, 0x321E, 0xD990, 0x321E, 0xD990, 0x2000, 0xE17F, 0x2000, 0xD1A0, 0x16F1, 0xC1C2, 0x2000, 0xC9B1, 0x2000, 0xC9B1, 0x321E}; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_printing_dialog_box.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_printing_dialog_box.cpp deleted file mode 100644 index c5e26da98a32..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_printing_dialog_box.cpp +++ /dev/null @@ -1,155 +0,0 @@ -/******************************* - * bio_printing_dialog_box.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" - -#if ENABLED(TOUCH_UI_FTDI_EVE) && defined(TOUCH_UI_LULZBOT_BIO) - -#include "screens.h" - -#include "../ftdi_eve_lib/extras/circular_progress.h" - -using namespace FTDI; -using namespace ExtUI; -using namespace Theme; - -#define GRID_COLS 2 -#define GRID_ROWS 9 - -void BioPrintingDialogBox::draw_status_message(draw_mode_t what, const char* message) { - if (what & BACKGROUND) { - CommandProcessor cmd; - cmd.cmd(COLOR_RGB(bg_text_enabled)) - .tag(0); - draw_text_box(cmd, BTN_POS(1,2), BTN_SIZE(2,2), message, OPT_CENTER, font_large); - } -} - -void BioPrintingDialogBox::draw_progress(draw_mode_t what) { - if (what & FOREGROUND) { - CommandProcessor cmd; - cmd.font(font_large) - .text(BTN_POS(1,1), BTN_SIZE(2,2), isPrinting() ? F("Printing...") : F("Finished.")) - .tag(1) - .font(font_xlarge); - - draw_circular_progress(cmd, BTN_POS(1,4), BTN_SIZE(2,3), getProgress_percent(), theme_dark, theme_darkest); - } -} - -void BioPrintingDialogBox::draw_time_remaining(draw_mode_t what) { - if (what & FOREGROUND) { - const uint32_t elapsed = getProgress_seconds_elapsed(); - const uint8_t hrs = elapsed/3600; - const uint8_t min = (elapsed/60)%60; - - char time_str[10]; - sprintf_P(time_str, PSTR("%02dh %02dm"), hrs, min); - - CommandProcessor cmd; - cmd.font(font_large) - .text(BTN_POS(1,7), BTN_SIZE(2,2), time_str); - } -} - -void BioPrintingDialogBox::draw_interaction_buttons(draw_mode_t what) { - if (what & FOREGROUND) { - CommandProcessor cmd; - cmd.colors(normal_btn) - .font(font_medium) - .colors(isPrinting() ? action_btn : normal_btn) - .tag(2).button(BTN_POS(1,9), BTN_SIZE(1,1), F("Menu")) - #if ENABLED(SDSUPPORT) - .enabled(isPrinting() ? isPrintingFromMedia() : 1) - #else - .enabled(isPrinting() ? 0 : 1) - #endif - .tag(3) - .colors(isPrinting() ? normal_btn : action_btn) - .button( BTN_POS(2,9), BTN_SIZE(1,1), isPrinting() ? F("Cancel") : F("Back")); - } -} - -void BioPrintingDialogBox::onRedraw(draw_mode_t what) { - if (what & FOREGROUND) { - draw_progress(FOREGROUND); - draw_time_remaining(FOREGROUND); - draw_interaction_buttons(FOREGROUND); - } -} - -bool BioPrintingDialogBox::onTouchEnd(uint8_t tag) { - switch (tag) { - case 1: GOTO_SCREEN(FeedratePercentScreen); break; - case 2: GOTO_SCREEN(TuneMenu); break; - case 3: - if (isPrinting()) - GOTO_SCREEN(ConfirmAbortPrintDialogBox); - else - GOTO_SCREEN(StatusScreen); - break; - default: return false; - } - return true; -} - -void BioPrintingDialogBox::setStatusMessage(progmem_str message) { - char buff[strlen_P((const char*)message)+1]; - strcpy_P(buff, (const char*) message); - setStatusMessage(buff); -} - -void BioPrintingDialogBox::setStatusMessage(const char* message) { - CommandProcessor cmd; - cmd.cmd(CMD_DLSTART) - .cmd(CLEAR_COLOR_RGB(bg_color)) - .cmd(CLEAR(true,true,true)); - - draw_status_message(BACKGROUND, message); - draw_progress(BACKGROUND); - draw_time_remaining(BACKGROUND); - draw_interaction_buttons(BACKGROUND); - storeBackground(); - - #if ENABLED(TOUCH_UI_DEBUG) - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR("New status message: ", message); - #endif - - if (AT_SCREEN(BioPrintingDialogBox)) - current_screen.onRefresh(); -} - -void BioPrintingDialogBox::onIdle() { - reset_menu_timeout(); - if (refresh_timer.elapsed(STATUS_UPDATE_INTERVAL)) { - onRefresh(); - refresh_timer.start(); - } - BaseScreen::onIdle(); -} - -void BioPrintingDialogBox::show() { - GOTO_SCREEN(BioPrintingDialogBox); -} - -#endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_status_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_status_screen.cpp deleted file mode 100644 index e881995f2e69..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_status_screen.cpp +++ /dev/null @@ -1,462 +0,0 @@ -/************************* - * bio_status_screen.cpp * - *************************/ - -/**************************************************************************** - * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * - * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * - * Written By Marcio Teixeira 2019 - Cocoa Press * - * * - * This program is free software: you can redistribute it and/or modify * - * it under the terms of the GNU General Public License as published by * - * the Free Software Foundation, either version 3 of the License, or * - * (at your option) any later version. * - * * - * This program is distributed in the hope that it will be useful, * - * but WITHOUT ANY WARRANTY; without even the implied warranty of * - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * - * GNU General Public License for more details. * - * * - * To view a copy of the GNU General Public License, go to the following * - * location: . * - ****************************************************************************/ - -#include "../config.h" - -#if ENABLED(TOUCH_UI_FTDI_EVE) && ANY(TOUCH_UI_LULZBOT_BIO, TOUCH_UI_COCOA_PRESS) - -#include "screens.h" - -#include "../ftdi_eve_lib/extras/poly_ui.h" - -#if ENABLED(TOUCH_UI_COCOA_PRESS) - #include "cocoa_press_ui.h" -#elif ENABLED(TOUCH_UI_PORTRAIT) - #include "bio_printer_ui_portrait.h" -#else - #include "bio_printer_ui_landscape.h" -#endif - -#define GRID_COLS 2 -#define GRID_ROWS 9 - -#define POLY(A) PolyUI::poly_reader_t(A, sizeof(A)/sizeof(A[0])) - -const uint8_t shadow_depth = 5; -const float max_speed = 1.00; -const float min_speed = 0.02; -const float emax_speed = 2.00; -const float emin_speed = 0.70; - -using namespace FTDI; -using namespace Theme; -using namespace ExtUI; - -float StatusScreen::increment; -bool StatusScreen::jog_xy; -bool StatusScreen::fine_motion; - -void StatusScreen::unlockMotors() { - injectCommands_P(PSTR("M84 XY")); - jog_xy = false; -} - -void StatusScreen::draw_temperature(draw_mode_t what) { - CommandProcessor cmd; - PolyUI ui(cmd, what); - - int16_t x, y, h, v; - - cmd.tag(15); - - if (what & BACKGROUND) { - cmd.cmd(COLOR_RGB(bg_color)); - - #if ENABLED(TOUCH_UI_LULZBOT_BIO) - // The LulzBot Bio shows the temperature for - // the bed. - - #ifdef TOUCH_UI_PORTRAIT - // Draw touch surfaces - ui.bounds(POLY(target_temp), x, y, h, v); - cmd.rectangle(x, y, h, v); - ui.bounds(POLY(actual_temp), x, y, h, v); - cmd.rectangle(x, y, h, v); - #else - ui.bounds(POLY(bed_temp), x, y, h, v); - cmd.rectangle(x, y, h, v); - #endif - ui.bounds(POLY(bed_icon), x, y, h, v); - cmd.rectangle(x, y, h, v); - - // Draw bed icon - cmd.cmd(BITMAP_SOURCE(Bed_Heat_Icon_Info)) - .cmd(BITMAP_LAYOUT(Bed_Heat_Icon_Info)) - .cmd(BITMAP_SIZE (Bed_Heat_Icon_Info)) - .cmd(COLOR_RGB(shadow_rgb)) - .icon (x + 2, y + 2, h, v, Bed_Heat_Icon_Info, icon_scale * 2) - .cmd(COLOR_RGB(bg_text_enabled)) - .icon (x, y, h, v, Bed_Heat_Icon_Info, icon_scale * 2); - #elif ENABLED(TOUCH_UI_COCOA_PRESS) && DISABLED(TOUCH_UI_PORTRAIT) - // The CocoaPress shows the temperature for two - // heating zones, but has no bed temperature - - cmd.cmd(COLOR_RGB(bg_text_enabled)); - cmd.font(font_xsmall); - - ui.bounds(POLY(h0_label), x, y, h, v); - cmd.text(x, y, h, v, GET_TEXT_F(MSG_ZONE_1)); - - ui.bounds(POLY(h1_label), x, y, h, v); - cmd.text(x, y, h, v, GET_TEXT_F(MSG_ZONE_2)); - - ui.bounds(POLY(h2_label), x, y, h, v); - cmd.text(x, y, h, v, GET_TEXT_F(MSG_ZONE_3)); - - ui.bounds(POLY(h3_label), x, y, h, v); - cmd.text(x, y, h, v, GET_TEXT_F(MSG_CHAMBER)); - #else - UNUSED(x); - UNUSED(y); - UNUSED(h); - UNUSED(v); - #endif - - #ifdef TOUCH_UI_USE_UTF8 - load_utf8_bitmaps(cmd); // Restore font bitmap handles - #endif - } - - if (what & FOREGROUND) { - char str[15]; - cmd.cmd(COLOR_RGB(bg_text_enabled)); - #if ENABLED(TOUCH_UI_LULZBOT_BIO) - cmd.font(font_medium); - - #ifdef TOUCH_UI_PORTRAIT - if (!isHeaterIdle(BED) && getTargetTemp_celsius(BED) > 0) - format_temp(str, getTargetTemp_celsius(BED)); - else - strcpy_P(str, GET_TEXT(MSG_BED)); - - ui.bounds(POLY(target_temp), x, y, h, v); - cmd.text(x, y, h, v, str); - - format_temp(str, getActualTemp_celsius(BED)); - ui.bounds(POLY(actual_temp), x, y, h, v); - cmd.text(x, y, h, v, str); - #else - if (!isHeaterIdle(BED) && getTargetTemp_celsius(BED) > 0) - format_temp_and_temp(str, getActualTemp_celsius(BED), getTargetTemp_celsius(BED)); - else - format_temp_and_idle(str, getActualTemp_celsius(BED)); - - ui.bounds(POLY(bed_temp), x, y, h, v); - cmd.text(x, y, h, v, str); - #endif - - #elif ENABLED(TOUCH_UI_COCOA_PRESS) && DISABLED(TOUCH_UI_PORTRAIT) - // The CocoaPress shows the temperature for two - // heating zones, but has no bed temperature - - cmd.font(font_large); - - if (!isHeaterIdle(E0) && getTargetTemp_celsius(E0) > 0) - format_temp_and_temp(str, getActualTemp_celsius(E0), getTargetTemp_celsius(E0)); - else - format_temp_and_idle(str, getActualTemp_celsius(E0)); - - ui.bounds(POLY(h0_temp), x, y, h, v); - cmd.text(x, y, h, v, str); - - if (!isHeaterIdle(E1) && getTargetTemp_celsius(E1) > 0) - format_temp_and_temp(str, getActualTemp_celsius(E1), getTargetTemp_celsius(E1)); - else - format_temp_and_idle(str, getActualTemp_celsius(E1)); - - ui.bounds(POLY(h1_temp), x, y, h, v); - cmd.text(x, y, h, v, str); - - if (!isHeaterIdle(E2) && getTargetTemp_celsius(E2) > 0) - format_temp_and_temp(str, getActualTemp_celsius(E2), getTargetTemp_celsius(E2)); - else - format_temp_and_idle(str, getActualTemp_celsius(E2)); - - ui.bounds(POLY(h2_temp), x, y, h, v); - cmd.text(x, y, h, v, str); - - if (!isHeaterIdle(CHAMBER) && getTargetTemp_celsius(CHAMBER) > 0) - format_temp_and_temp(str, getActualTemp_celsius(CHAMBER), getTargetTemp_celsius(CHAMBER)); - else - format_temp_and_idle(str, getActualTemp_celsius(CHAMBER)); - - ui.bounds(POLY(h3_temp), x, y, h, v); - cmd.text(x, y, h, v, str); - #else - UNUSED(str); - #endif - } -} - -void StatusScreen::draw_syringe(draw_mode_t what) { - int16_t x, y, h, v; - const float fill_level = ( - #ifdef E_MAX_POS - 1.0 - min(1.0, max(0.0, getAxisPosition_mm(E0) / E_MAX_POS)) - #else - 0.75 - #endif - ); - const bool e_homed = TERN0(TOUCH_UI_LULZBOT_BIO, isAxisPositionKnown(E0)); - - CommandProcessor cmd; - PolyUI ui(cmd, what); - - if (what & BACKGROUND) { - // Paint the shadow for the syringe - ui.color(shadow_rgb); - ui.shadow(POLY(syringe_outline), shadow_depth); - } - - if (what & FOREGROUND && e_homed) { - // Paint the syringe icon - ui.color(syringe_rgb); - ui.fill(POLY(syringe_outline)); - - ui.color(fluid_rgb); - ui.bounds(POLY(syringe_fluid), x, y, h, v); - cmd.cmd(SAVE_CONTEXT()); - cmd.cmd(SCISSOR_XY(x,y + v * (1.0 - fill_level))); - cmd.cmd(SCISSOR_SIZE(h, v * fill_level)); - ui.fill(POLY(syringe_fluid), false); - cmd.cmd(RESTORE_CONTEXT()); - - ui.color(stroke_rgb); - ui.fill(POLY(syringe)); - } -} - -void StatusScreen::draw_arrows(draw_mode_t what) { - const bool e_homed = TERN1(TOUCH_UI_LULZBOT_BIO, isAxisPositionKnown(E0)), - z_homed = isAxisPositionKnown(Z); - - CommandProcessor cmd; - PolyUI ui(cmd, what); - - ui.button_fill (fill_rgb); - ui.button_stroke(stroke_rgb, 28); - ui.button_shadow(shadow_rgb, shadow_depth); - - constexpr uint8_t style = TERN(TOUCH_UI_COCOA_PRESS, PolyUI::FILL | PolyUI::SHADOW, PolyUI::REGULAR); - - if ((what & BACKGROUND) || jog_xy) { - ui.button(1, POLY(x_neg), style); - ui.button(2, POLY(x_pos), style); - ui.button(3, POLY(y_neg), style); - ui.button(4, POLY(y_pos), style); - } - - if ((what & BACKGROUND) || z_homed) { - ui.button(5, POLY(z_neg), style); - ui.button(6, POLY(z_pos), style); - } - - if ((what & BACKGROUND) || e_homed) { - #if DISABLED(TOUCH_UI_COCOA_PRESS) - ui.button(7, POLY(e_neg), style); - #endif - ui.button(8, POLY(e_pos), style); - } -} - -void StatusScreen::draw_fine_motion(draw_mode_t what) { - int16_t x, y, h, v; - CommandProcessor cmd; - PolyUI ui(cmd, what); - - cmd.font( - #ifdef TOUCH_UI_PORTRAIT - font_medium - #else - font_small - #endif - ) - .tag(16); - - if (what & BACKGROUND) { - ui.bounds(POLY(fine_label), x, y, h, v); - cmd.cmd(COLOR_RGB(bg_text_enabled)) - .text(x, y, h, v, GET_TEXT_F(MSG_FINE_MOTION)); - } - - if (what & FOREGROUND) { - ui.bounds(POLY(fine_toggle), x, y, h, v); - cmd.colors(ui_toggle) - .toggle2(x, y, h, v, GET_TEXT_F(MSG_NO), GET_TEXT_F(MSG_YES), fine_motion); - } -} - -void StatusScreen::draw_overlay_icons(draw_mode_t what) { - const bool e_homed = TERN1(TOUCH_UI_LULZBOT_BIO, isAxisPositionKnown(E0)), - z_homed = isAxisPositionKnown(Z); - - CommandProcessor cmd; - PolyUI ui(cmd, what); - - if (what & FOREGROUND) { - ui.button_fill (TERN(TOUCH_UI_COCOA_PRESS, stroke_rgb, fill_rgb)); - ui.button_stroke(stroke_rgb, 28); - ui.button_shadow(shadow_rgb, shadow_depth); - - constexpr uint8_t style = TERN(TOUCH_UI_COCOA_PRESS, PolyUI::FILL | PolyUI::SHADOW, PolyUI::REGULAR); - if (!jog_xy) ui.button(12, POLY(padlock), style); - if (!e_homed) ui.button(13, POLY(home_e), style); - if (!z_homed) ui.button(14, POLY(home_z), style); - } -} - -void StatusScreen::draw_buttons(draw_mode_t what) { - int16_t x, y, h, v; - - const bool has_media = isMediaInserted() && !isPrintingFromMedia(); - - CommandProcessor cmd; - PolyUI ui(cmd, what); - - ui.bounds(POLY(usb_btn), x, y, h, v); - cmd.font(font_medium) - .colors(normal_btn) - .enabled(has_media) - .colors(has_media ? action_btn : normal_btn) - .tag(9).button(x, y, h, v, - isPrintingFromMedia() ? - GET_TEXT_F(MSG_PRINTING) : - GET_TEXT_F(MSG_BUTTON_MEDIA) - ); - - ui.bounds(POLY(menu_btn), x, y, h, v); - cmd.colors(!has_media ? action_btn : normal_btn).tag(10).button(x, y, h, v, GET_TEXT_F(MSG_BUTTON_MENU)); -} - -void StatusScreen::loadBitmaps() { - // Load the bitmaps for the status screen - constexpr uint32_t base = ftdi_memory_map::RAM_G; - CLCD::mem_write_pgm(base + Bed_Heat_Icon_Info.RAMG_offset, Bed_Heat_Icon, sizeof(Bed_Heat_Icon)); - - // Load fonts for internationalization - #ifdef TOUCH_UI_USE_UTF8 - load_utf8_data(base + UTF8_FONT_OFFSET); - #endif -} - -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); - } - - draw_syringe(what); - draw_temperature(what); - draw_arrows(what); - draw_overlay_icons(what); - draw_buttons(what); - draw_fine_motion(what); -} - -bool StatusScreen::onTouchStart(uint8_t) { - increment = 0; - return true; -} - -bool StatusScreen::onTouchEnd(uint8_t tag) { - switch (tag) { - case 1: - case 2: - case 3: - case 4: - case 12: - if (!jog_xy) { - jog_xy = true; - injectCommands_P(PSTR("M17")); - } - jog({ 0, 0, 0 }); - break; - case 5: - case 6: - jog({ 0, 0, 0 }); - break; - case 9: GOTO_SCREEN(FilesScreen); break; - case 10: GOTO_SCREEN(MainMenu); break; - #if ENABLED(TOUCH_UI_LULZBOT_BIO) - case 13: GOTO_SCREEN(BioConfirmHomeE); break; - #endif - case 14: SpinnerDialogBox::enqueueAndWait_P(F("G28 Z")); break; - case 15: GOTO_SCREEN(TemperatureScreen); break; - case 16: fine_motion = !fine_motion; break; - default: return false; - } - // If a passcode is enabled, the LockScreen will prevent the - // user from proceeding. - LockScreen::check_passcode(); - return true; -} - -bool StatusScreen::onTouchHeld(uint8_t tag) { - if (tag >= 1 && tag <= 4 && !jog_xy) return false; - const float s = min_speed + (fine_motion ? 0 : (max_speed - min_speed) * sq(increment)); - switch (tag) { - case 1: jog({-s, 0, 0}); break; - case 2: jog({ s, 0, 0}); break; - case 4: jog({ 0, -s, 0}); break; // NOTE: Y directions inverted because bed rather than needle moves - case 3: jog({ 0, s, 0}); break; - case 5: jog({ 0, 0, -s}); break; - case 6: jog({ 0, 0, s}); break; - case 7: case 8: - { - if (ExtUI::isMoving()) return false; - const feedRate_t feedrate = emin_speed + (fine_motion ? 0 : (emax_speed - emin_speed) * sq(increment)); - const float increment = 0.25 * feedrate * (tag == 7 ? -1 : 1); - MoveAxisScreen::setManualFeedrate(E0, feedrate); - UI_INCREMENT(AxisPosition_mm, E0); - current_screen.onRefresh(); - break; - } - default: - return false; - } - increment = min(1.0f, increment + 0.1f); - return false; -} - -void StatusScreen::setStatusMessage(progmem_str pstr) { - #ifdef TOUCH_UI_LULZBOT_BIO - BioPrintingDialogBox::setStatusMessage(pstr); - #else - UNUSED(pstr); - #endif -} - -void StatusScreen::setStatusMessage(const char * const str) { - #ifdef TOUCH_UI_LULZBOT_BIO - BioPrintingDialogBox::setStatusMessage(str); - #else - UNUSED(str); - #endif -} - -void StatusScreen::onIdle() { - reset_menu_timeout(); - if (refresh_timer.elapsed(STATUS_UPDATE_INTERVAL)) { - if (!EventLoop::is_touch_held()) - onRefresh(); - #ifdef TOUCH_UI_LULZBOT_BIO - if (isPrintingFromMedia()) - BioPrintingDialogBox::show(); - #endif - refresh_timer.start(); - } -} - -#endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_tune_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_tune_menu.cpp deleted file mode 100644 index 0d8d71b45ce1..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_tune_menu.cpp +++ /dev/null @@ -1,79 +0,0 @@ -/********************* - * bio_tune_menu.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" - -#if ENABLED(TOUCH_UI_FTDI_EVE) && defined(TOUCH_UI_LULZBOT_BIO) - -#include "screens.h" - -using namespace FTDI; -using namespace Theme; -using namespace ExtUI; - -void TuneMenu::onRedraw(draw_mode_t what) { - #define GRID_ROWS 8 - #define GRID_COLS 2 - - if (what & BACKGROUND) { - CommandProcessor cmd; - cmd.cmd(CLEAR_COLOR_RGB(bg_color)) - .cmd(CLEAR(true,true,true)) - .cmd(COLOR_RGB(bg_text_enabled)) - .tag(0) - .font(font_large) - .text( BTN_POS(1,1), BTN_SIZE(2,1), GET_TEXT_F(MSG_PRINT_MENU)); - } - - if (what & FOREGROUND) { - CommandProcessor cmd; - cmd.colors(normal_btn) - .font(font_medium) - .enabled( isPrinting()).tag(2).button( BTN_POS(1,2), BTN_SIZE(2,1), GET_TEXT_F(MSG_PRINT_SPEED)) - .tag(3).button( BTN_POS(1,3), BTN_SIZE(2,1), GET_TEXT_F(MSG_BED_TEMPERATURE)) - .enabled(TERN_(BABYSTEPPING, true)) - .tag(4).button( BTN_POS(1,4), BTN_SIZE(2,1), GET_TEXT_F(MSG_NUDGE_NOZZLE)) - .enabled(!isPrinting()).tag(5).button( BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_MOVE_TO_HOME)) - .enabled(!isPrinting()).tag(6).button( BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_RAISE_PLUNGER)) - .enabled(!isPrinting()).tag(7).button( BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_RELEASE_XY_AXIS)) - .colors(action_btn) .tag(1).button( BTN_POS(1,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_BACK)); - } - #undef GRID_COLS - #undef GRID_ROWS -} - -bool TuneMenu::onTouchEnd(uint8_t tag) { - switch (tag) { - case 1: GOTO_PREVIOUS(); break; - case 2: GOTO_SCREEN(FeedratePercentScreen); break; - case 3: GOTO_SCREEN(TemperatureScreen); break; - case 4: GOTO_SCREEN(NudgeNozzleScreen); break; - case 5: GOTO_SCREEN(BioConfirmHomeXYZ); break; - case 6: SpinnerDialogBox::enqueueAndWait_P(F("G0 E0 F120")); break; - case 7: StatusScreen::unlockMotors(); break; - default: - return false; - } - return true; -} - -#endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/change_filament_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/change_filament_screen.cpp deleted file mode 100644 index 589da9b21055..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/change_filament_screen.cpp +++ /dev/null @@ -1,354 +0,0 @@ -/****************************** - * change_filament_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" - -#if ENABLED(TOUCH_UI_FTDI_EVE) - -#include "screens.h" -#include "screen_data.h" - -using namespace ExtUI; -using namespace FTDI; -using namespace Theme; - -#define COOL_TEMP 40 -#define LOW_TEMP 180 -#define MED_TEMP 200 -#define HIGH_TEMP 220 - -/****************** COLOR SCALE ***********************/ - -uint32_t getWarmColor(uint16_t temp, uint16_t cool, uint16_t low, uint16_t med, uint16_t high) { - rgb_t R0, R1, mix; - - float t; - if (temp < cool) { - R0 = cool_rgb; - R1 = low_rgb; - t = 0; - } - else if (temp < low) { - R0 = cool_rgb; - R1 = low_rgb; - t = (float(temp)-cool)/(low-cool); - } - else if (temp < med) { - R0 = low_rgb; - R1 = med_rgb; - t = (float(temp)-low)/(med-low); - } - else if (temp < high) { - R0 = med_rgb; - R1 = high_rgb; - t = (float(temp)-med)/(high-med); - } - else if (temp >= high) { - R0 = med_rgb; - R1 = high_rgb; - t = 1; - } - rgb_t::lerp(t, R0, R1, mix); - return mix; -} - -void ChangeFilamentScreen::drawTempGradient(uint16_t x, uint16_t y, uint16_t w, uint16_t h) { - CommandProcessor cmd; - cmd.cmd(SCISSOR_XY (x, y)) - .cmd(SCISSOR_SIZE (w, h/2)) - .gradient (x, y, high_rgb, x, y+h/2, med_rgb) - .cmd(SCISSOR_XY (x, y+h/2)) - .cmd(SCISSOR_SIZE (w, h/2)) - .gradient (x, y+h/2, med_rgb, x, y+h, low_rgb) - .cmd(SCISSOR_XY ()) - .cmd(SCISSOR_SIZE ()); -} - -void ChangeFilamentScreen::onEntry() { - screen_data.ChangeFilamentScreen.e_tag = ExtUI::getActiveTool() + 10; - screen_data.ChangeFilamentScreen.t_tag = 0; - screen_data.ChangeFilamentScreen.repeat_tag = 0; - screen_data.ChangeFilamentScreen.saved_extruder = getActiveTool(); - #if FILAMENT_UNLOAD_PURGE_LENGTH > 0 - screen_data.ChangeFilamentScreen.need_purge = true; - #endif -} - -void ChangeFilamentScreen::onExit() { - setActiveTool(screen_data.ChangeFilamentScreen.saved_extruder, true); -} - -void ChangeFilamentScreen::onRedraw(draw_mode_t what) { - CommandProcessor cmd; - - #ifdef TOUCH_UI_PORTRAIT - #define GRID_COLS 2 - #define GRID_ROWS 11 - #else - #define GRID_COLS 4 - #define GRID_ROWS 6 - #endif - - if (what & BACKGROUND) { - cmd.cmd(CLEAR_COLOR_RGB(bg_color)) - .cmd(CLEAR(true,true,true)) - .cmd(COLOR_RGB(bg_text_enabled)) - .tag(0) - #ifdef TOUCH_UI_PORTRAIT - .font(font_large) - #else - .font(font_medium) - #endif - .text(BTN_POS(1,1), BTN_SIZE(2,1), GET_TEXT_F(MSG_EXTRUDER_SELECTION)) - #ifdef TOUCH_UI_PORTRAIT - .text(BTN_POS(1,7), BTN_SIZE(1,1), GET_TEXT_F(MSG_CURRENT_TEMPERATURE)) - #else - .text(BTN_POS(3,1), BTN_SIZE(2,1), GET_TEXT_F(MSG_CURRENT_TEMPERATURE)) - .font(font_small) - #endif - .text(BTN_POS(1,3), BTN_SIZE(2,1), GET_TEXT_F(MSG_REMOVAL_TEMPERATURE)); - drawTempGradient(BTN_POS(1,4), BTN_SIZE(1,3)); - } - - if (what & FOREGROUND) { - const extruder_t e = getExtruder(); - - char e_str[15]; - if (isHeaterIdle(e)) - format_temp_and_idle(e_str, getActualTemp_celsius(e)); - else - format_temp_and_temp(e_str, getActualTemp_celsius(e), getTargetTemp_celsius(e)); - - const rgb_t tcol = getWarmColor(getActualTemp_celsius(e), COOL_TEMP, LOW_TEMP, MED_TEMP, HIGH_TEMP); - cmd.cmd(COLOR_RGB(tcol)) - .tag(15) - #ifdef TOUCH_UI_PORTRAIT - .rectangle(BTN_POS(2,7), BTN_SIZE(1,1)) - #else - .rectangle(BTN_POS(3,2), BTN_SIZE(2,1)) - #endif - .cmd(COLOR_RGB(tcol.luminance() > 128 ? 0x000000 : 0xFFFFFF)) - .font(font_medium) - #ifdef TOUCH_UI_PORTRAIT - .text(BTN_POS(2,7), BTN_SIZE(1,1), e_str) - #else - .text(BTN_POS(3,2), BTN_SIZE(2,1), e_str) - #endif - .colors(normal_btn); - - const bool t_ok = getActualTemp_celsius(e) > getSoftenTemp() - 10; - - if (screen_data.ChangeFilamentScreen.t_tag && !t_ok) { - cmd.text(BTN_POS(1,6), BTN_SIZE(1,1), GET_TEXT_F(MSG_HEATING)); - } else if (getActualTemp_celsius(e) > 100) { - cmd.cmd(COLOR_RGB(0xFF0000)) - .text(BTN_POS(1,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_CAUTION)) - .colors(normal_btn) - .text(BTN_POS(1,6), BTN_SIZE(1,1), GET_TEXT_F(MSG_HOT)); - } - - #define TOG_STYLE(A) colors(A ? action_btn : normal_btn) - - const bool tog2 = screen_data.ChangeFilamentScreen.t_tag == 2; - const bool tog3 = screen_data.ChangeFilamentScreen.t_tag == 3; - const bool tog4 = screen_data.ChangeFilamentScreen.t_tag == 4; - const bool tog10 = screen_data.ChangeFilamentScreen.e_tag == 10; - #if HAS_MULTI_HOTEND - const bool tog11 = screen_data.ChangeFilamentScreen.e_tag == 11; - #endif - - #ifdef TOUCH_UI_PORTRAIT - cmd.font(font_large) - #else - cmd.font(font_medium) - #endif - .TOG_STYLE(tog10) - .tag(10) .button (BTN_POS(1,2), BTN_SIZE(1,1), F("1")) - #if HOTENDS < 2 - .enabled(false) - #else - .TOG_STYLE(tog11) - #endif - .tag(11) .button (BTN_POS(2,2), BTN_SIZE(1,1), F("2")); - - if (!t_ok) reset_menu_timeout(); - - const bool tog7 = screen_data.ChangeFilamentScreen.repeat_tag == 7; - const bool tog8 = screen_data.ChangeFilamentScreen.repeat_tag == 8; - - - cmd.font( - #ifdef TOUCH_UI_PORTRAIT - font_large - #else - font_small - #endif - ); - - { - char str[30]; - - format_temp(str, LOW_TEMP); - cmd.tag(2) .TOG_STYLE(tog2) .button (BTN_POS(2,6), BTN_SIZE(1,1), str); - - format_temp(str, MED_TEMP); - cmd.tag(3) .TOG_STYLE(tog3) .button (BTN_POS(2,5), BTN_SIZE(1,1), str); - - format_temp(str, HIGH_TEMP); - cmd.tag(4) .TOG_STYLE(tog4) .button (BTN_POS(2,4), BTN_SIZE(1,1), str); - } - cmd.colors(normal_btn) - - // Add tags to color gradient - .cmd(COLOR_MASK(0,0,0,0)) - .tag(2) .rectangle(BTN_POS(1,6), BTN_SIZE(1,1)) - .tag(3) .rectangle(BTN_POS(1,5), BTN_SIZE(1,1)) - .tag(4) .rectangle(BTN_POS(1,4), BTN_SIZE(1,1)) - .cmd(COLOR_MASK(1,1,1,1)) - - .cmd(COLOR_RGB(t_ok ? bg_text_enabled : bg_text_disabled)) - #ifdef TOUCH_UI_PORTRAIT - .font(font_large) - .tag(0) .text (BTN_POS(1,8), BTN_SIZE(1,1), GET_TEXT_F(MSG_UNLOAD_FILAMENT)) - .text (BTN_POS(2,8), BTN_SIZE(1,1), GET_TEXT_F(MSG_LOAD_FILAMENT)) - .tag(5) .enabled(t_ok).button (BTN_POS(1,9), BTN_SIZE(1,1), GET_TEXT_F(MSG_MOMENTARY)) - .tag(6) .enabled(t_ok).button (BTN_POS(2,9), BTN_SIZE(1,1), GET_TEXT_F(MSG_MOMENTARY)) - .tag(7).TOG_STYLE(tog7).enabled(t_ok).button (BTN_POS(1,10), BTN_SIZE(1,1), GET_TEXT_F(MSG_CONTINUOUS)) - .tag(8).TOG_STYLE(tog8).enabled(t_ok).button (BTN_POS(2,10), BTN_SIZE(1,1), GET_TEXT_F(MSG_CONTINUOUS)) - .tag(1).colors(action_btn) .button (BTN_POS(1,11), BTN_SIZE(2,1), GET_TEXT_F(MSG_BACK)); - #else - .font(font_small) - .tag(0) .text (BTN_POS(3,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_UNLOAD_FILAMENT)) - .text (BTN_POS(4,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_LOAD_FILAMENT)) - .tag(5) .enabled(t_ok).button (BTN_POS(3,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_MOMENTARY)) - .tag(6) .enabled(t_ok).button (BTN_POS(4,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_MOMENTARY)) - .tag(7).TOG_STYLE(tog7).enabled(t_ok).button (BTN_POS(3,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_CONTINUOUS)) - .tag(8).TOG_STYLE(tog8).enabled(t_ok).button (BTN_POS(4,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_CONTINUOUS)) - .font(font_medium) - .tag(1).colors(action_btn) .button (BTN_POS(3,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_BACK)); - #endif - } - #undef GRID_COLS - #undef GRID_ROWS -} - -uint8_t ChangeFilamentScreen::getSoftenTemp() { - switch (screen_data.ChangeFilamentScreen.t_tag) { - case 2: return LOW_TEMP; - case 3: return MED_TEMP; - case 4: return HIGH_TEMP; - default: return EXTRUDE_MINTEMP; - } -} - -ExtUI::extruder_t ChangeFilamentScreen::getExtruder() { - switch (screen_data.ChangeFilamentScreen.e_tag) { - case 13: return ExtUI::E3; - case 12: return ExtUI::E2; - case 11: return ExtUI::E1; - default: return ExtUI::E0; - } -} - -void ChangeFilamentScreen::doPurge() { - #if FILAMENT_UNLOAD_PURGE_LENGTH > 0 - constexpr float purge_distance_mm = FILAMENT_UNLOAD_PURGE_LENGTH; - if (screen_data.ChangeFilamentScreen.need_purge) { - screen_data.ChangeFilamentScreen.need_purge = false; - MoveAxisScreen::setManualFeedrate(getExtruder(), purge_distance_mm); - ExtUI::setAxisPosition_mm(ExtUI::getAxisPosition_mm(getExtruder()) + purge_distance_mm, getExtruder()); - } - #endif -} - -bool ChangeFilamentScreen::onTouchStart(uint8_t tag) { - // Make the Momentary and Continuous buttons slightly more responsive - switch (tag) { - case 5: case 6: case 7: case 8: - #if FILAMENT_UNLOAD_PURGE_LENGTH > 0 - if (tag == 5 || tag == 7) doPurge(); - #endif - return ChangeFilamentScreen::onTouchHeld(tag); - default: - return false; - } -} - -bool ChangeFilamentScreen::onTouchEnd(uint8_t tag) { - using namespace ExtUI; - switch (tag) { - case 1: GOTO_PREVIOUS(); break; - case 2: - case 3: - case 4: - // Change temperature - screen_data.ChangeFilamentScreen.t_tag = tag; - setTargetTemp_celsius(getSoftenTemp(), getExtruder()); - break; - case 7: - screen_data.ChangeFilamentScreen.repeat_tag = (screen_data.ChangeFilamentScreen.repeat_tag == 7) ? 0 : 7; - break; - case 8: - screen_data.ChangeFilamentScreen.repeat_tag = (screen_data.ChangeFilamentScreen.repeat_tag == 8) ? 0 : 8; - break; - case 10: - case 11: - // Change extruder - screen_data.ChangeFilamentScreen.e_tag = tag; - screen_data.ChangeFilamentScreen.t_tag = 0; - screen_data.ChangeFilamentScreen.repeat_tag = 0; - #if FILAMENT_UNLOAD_PURGE_LENGTH > 0 - screen_data.ChangeFilamentScreen.need_purge = true; - #endif - setActiveTool(getExtruder(), true); - break; - case 15: GOTO_SCREEN(TemperatureScreen); break; - } - return true; -} - -bool ChangeFilamentScreen::onTouchHeld(uint8_t tag) { - if (ExtUI::isMoving()) return false; // Don't allow moves to accumulate - constexpr float increment = 1; - #define UI_INCREMENT_AXIS(axis) UI_INCREMENT(AxisPosition_mm, axis); - #define UI_DECREMENT_AXIS(axis) UI_DECREMENT(AxisPosition_mm, axis); - switch (tag) { - case 5: case 7: UI_DECREMENT_AXIS(getExtruder()); break; - case 6: case 8: UI_INCREMENT_AXIS(getExtruder()); break; - default: return false; - } - #undef UI_DECREMENT_AXIS - #undef UI_INCREMENT_AXIS - return false; -} - -void ChangeFilamentScreen::onIdle() { - reset_menu_timeout(); - if (screen_data.ChangeFilamentScreen.repeat_tag) onTouchHeld(screen_data.ChangeFilamentScreen.repeat_tag); - if (refresh_timer.elapsed(STATUS_UPDATE_INTERVAL)) { - onRefresh(); - refresh_timer.start(); - } - BaseScreen::onIdle(); -} - -#endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/developer_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/developer_menu.cpp deleted file mode 100644 index 8e56c4197bbd..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/developer_menu.cpp +++ /dev/null @@ -1,150 +0,0 @@ -/********************** - * developer_menu.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" - -#if BOTH(TOUCH_UI_FTDI_EVE, TOUCH_UI_DEVELOPER_MENU) - -#include "screens.h" - -#include "../archim2-flash/flash_storage.h" - -using namespace FTDI; -using namespace Theme; - -void DeveloperMenu::onRedraw(draw_mode_t what) { - if (what & BACKGROUND) { - CommandProcessor cmd; - cmd.cmd(CLEAR_COLOR_RGB(bg_color)) - .cmd(CLEAR(true,true,true)) - .font(font_medium) - .tag(0); - - #ifdef SPI_FLASH_SS - constexpr bool has_flash = true; - #else - constexpr bool has_flash = false; - #endif - - #if ENABLED(SDSUPPORT) - constexpr bool has_media = true; - #else - constexpr bool has_media = false; - #endif - - cmd.cmd(COLOR_RGB(bg_text_enabled)); - #ifdef TOUCH_UI_PORTRAIT - #define GRID_ROWS 10 - #define GRID_COLS 1 - cmd.font(font_large) .text ( BTN_POS(1,1), BTN_SIZE(1,1), F("Developer Menu")) - .colors(normal_btn) - .tag(2).font(font_medium) .button( BTN_POS(1,2), BTN_SIZE(1,1), F("Show All Widgets")) - .tag(3) .button( BTN_POS(1,3), BTN_SIZE(1,1), F("Stress Test")) - .tag(4) .button( BTN_POS(1,4), BTN_SIZE(1,1), F("Show Touch Registers")) - .tag(5) .button( BTN_POS(1,5), BTN_SIZE(1,1), F("Play Song")) - .tag(6).enabled(has_media).button( BTN_POS(1,6), BTN_SIZE(1,1), F("Play Video from Media")) - .tag(7).enabled(has_flash).button( BTN_POS(1,7), BTN_SIZE(1,1), F("Play Video from SPI Flash")) - .tag(8).enabled(has_flash).button( BTN_POS(1,8), BTN_SIZE(1,1), F("Load Video to SPI Flash")) - .tag(9).enabled(has_flash).button( BTN_POS(1,9), BTN_SIZE(1,1), F("Erase SPI Flash")) - - .tag(1).colors(action_btn) - .button( BTN_POS(1,10), BTN_SIZE(1,1), F("Back")); - #else - #define GRID_ROWS 6 - #define GRID_COLS 2 - cmd.font(font_medium) .text ( BTN_POS(1,1), BTN_SIZE(2,1), F("Developer Menu")) - .colors(normal_btn) - .tag(2).font(font_small) .button( BTN_POS(1,2), BTN_SIZE(1,1), F("Show All Widgets")) - .tag(3) .button( BTN_POS(1,3), BTN_SIZE(1,1), F("Show Touch Registers")) - .tag(9) .button( BTN_POS(1,4), BTN_SIZE(1,1), F("Show Pin States")) - .tag(4) .button( BTN_POS(1,5), BTN_SIZE(1,1), F("Play Song")) - .tag(5).enabled(has_media).button( BTN_POS(2,2), BTN_SIZE(1,1), F("Play Video from Media")) - .tag(6).enabled(has_flash).button( BTN_POS(2,3), BTN_SIZE(1,1), F("Play Video from SPI Flash")) - .tag(7).enabled(has_flash).button( BTN_POS(2,4), BTN_SIZE(1,1), F("Load Video to SPI Flash")) - .tag(8).enabled(has_flash).button( BTN_POS(2,5), BTN_SIZE(1,1), F("Erase SPI Flash")) - .tag(1).colors(action_btn) - .button( BTN_POS(1,6), BTN_SIZE(2,1), F("Back")); - #endif - } -} - -bool DeveloperMenu::onTouchEnd(uint8_t tag) { - using namespace Theme; - switch (tag) { - case 1: GOTO_PREVIOUS(); break; - case 2: GOTO_SCREEN(WidgetsScreen); break; - case 3: - PUSH_SCREEN(StressTestScreen); - AlertDialogBox::show(F("Please do not run this test unattended as it may cause your printer to malfunction.")); - current_screen.forget(); - break; - case 4: GOTO_SCREEN(TouchRegistersScreen); break; - case 5: sound.play(js_bach_joy, PLAY_ASYNCHRONOUS); break; - #if ENABLED(SDSUPPORT) - case 6: - if (!MediaPlayerScreen::playCardMedia()) - AlertDialogBox::showError(F("Cannot open STARTUP.AVI")); - break; - #endif - #ifdef SPI_FLASH_SS - case 7: - if (!MediaPlayerScreen::playBootMedia()) - AlertDialogBox::showError(F("No boot media available")); - break; - case 8: - { - SpinnerDialogBox::show(F("Saving...")); - UIFlashStorage::error_t res = UIFlashStorage::write_media_file(F("STARTUP.AVI")); - SpinnerDialogBox::hide(); - reset_menu_timeout(); - switch (res) { - case UIFlashStorage::SUCCESS: - AlertDialogBox::show(F("File copied!")); - break; - - case UIFlashStorage::READ_ERROR: - AlertDialogBox::showError(F("Failed to read file")); - break; - - case UIFlashStorage::VERIFY_ERROR: - AlertDialogBox::showError(F("Failed to verify file")); - break; - - case UIFlashStorage::FILE_NOT_FOUND: - AlertDialogBox::showError(F("Cannot open STARTUP.AVI")); - break; - - case UIFlashStorage::WOULD_OVERWRITE: - AlertDialogBox::showError(F("Cannot overwrite existing media.")); - break; - } - break; - } - case 9: GOTO_SCREEN(ConfirmEraseFlashDialogBox); break; - #endif - case 10: GOTO_SCREEN(EndstopStatesScreen); break; - default: return false; - } - return true; -} - -#endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/files_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/files_screen.cpp deleted file mode 100644 index f4c224dbe8cf..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/files_screen.cpp +++ /dev/null @@ -1,264 +0,0 @@ -/******************** - * files_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" - -#if BOTH(TOUCH_UI_FTDI_EVE, SDSUPPORT) - -#include "screens.h" -#include "screen_data.h" - -using namespace FTDI; -using namespace ExtUI; -using namespace Theme; - -void FilesScreen::onEntry() { - screen_data.FilesScreen.cur_page = 0; - screen_data.FilesScreen.selected_tag = 0xFF; - #if ENABLED(SCROLL_LONG_FILENAMES) && (FTDI_API_LEVEL >= 810) - CLCD::mem_write_32(CLCD::REG::MACRO_0,DL::NOP); - #endif - gotoPage(0); - BaseScreen::onEntry(); -} - -const char *FilesScreen::getSelectedFilename(bool longName) { - FileList files; - files.seek(getSelectedFileIndex(), true); - return longName ? files.longFilename() : files.shortFilename(); -} - -void FilesScreen::drawSelectedFile() { - FileList files; - files.seek(getSelectedFileIndex(), true); - screen_data.FilesScreen.flags.is_dir = files.isDir(); - drawFileButton( - files.filename(), - screen_data.FilesScreen.selected_tag, - screen_data.FilesScreen.flags.is_dir, - true - ); -} - -uint16_t FilesScreen::getSelectedFileIndex() { - return getFileForTag(screen_data.FilesScreen.selected_tag); -} - -uint16_t FilesScreen::getFileForTag(uint8_t tag) { - return screen_data.FilesScreen.cur_page * files_per_page + tag - 2; -} - -#ifdef TOUCH_UI_PORTRAIT - #define GRID_COLS 6 - #define GRID_ROWS (files_per_page + header_h + footer_h) -#else - #define GRID_COLS 6 - #define GRID_ROWS (files_per_page + header_h + footer_h) -#endif - -void FilesScreen::drawFileButton(const char* filename, uint8_t tag, bool is_dir, bool is_highlighted) { - const uint8_t line = getLineForTag(tag)+1; - CommandProcessor cmd; - cmd.tag(tag); - cmd.cmd(COLOR_RGB(is_highlighted ? fg_action : bg_color)); - cmd.font(font_medium) - .rectangle( 0, BTN_Y(header_h+line), display_width, BTN_H(1)); - cmd.cmd(COLOR_RGB(is_highlighted ? normal_btn.rgb : bg_text_enabled)); - constexpr uint16_t dim[2] = {BTN_SIZE(6,1)}; - #define POS_AND_SHORTEN(SHORTEN) BTN_POS(1,header_h+line), dim[0] - (SHORTEN), dim[1] - #define POS_AND_SIZE POS_AND_SHORTEN(0) - #if ENABLED(SCROLL_LONG_FILENAMES) - if (is_highlighted) { - cmd.cmd(SAVE_CONTEXT()); - cmd.cmd(MACRO(0)); - cmd.text(POS_AND_SIZE, filename, OPT_CENTERY | OPT_NOFIT); - } else - #endif - draw_text_with_ellipsis(cmd, POS_AND_SHORTEN(is_dir ? 20 : 0), filename, OPT_CENTERY, font_medium); - if (is_dir && !is_highlighted) { - cmd.text(POS_AND_SIZE, F("> "), OPT_CENTERY | OPT_RIGHTX); - } - #if ENABLED(SCROLL_LONG_FILENAMES) - if (is_highlighted) { - cmd.cmd(RESTORE_CONTEXT()); - } - #endif -} - -void FilesScreen::drawFileList() { - FileList files; - screen_data.FilesScreen.num_page = max(1,ceil(float(files.count()) / files_per_page)); - screen_data.FilesScreen.cur_page = min(screen_data.FilesScreen.cur_page, screen_data.FilesScreen.num_page-1); - screen_data.FilesScreen.flags.is_root = files.isAtRootDir(); - - #undef MARGIN_T - #undef MARGIN_B - #define MARGIN_T 0 - #define MARGIN_B 0 - uint16_t fileIndex = screen_data.FilesScreen.cur_page * files_per_page; - for (uint8_t i = 0; i < files_per_page; i++, fileIndex++) { - if (files.seek(fileIndex)) { - drawFileButton(files.filename(), getTagForLine(i), files.isDir(), false); - } - else { - break; - } - } -} - -void FilesScreen::drawHeader() { - const bool prev_enabled = screen_data.FilesScreen.cur_page > 0; - const bool next_enabled = screen_data.FilesScreen.cur_page < (screen_data.FilesScreen.num_page - 1); - - #undef MARGIN_T - #undef MARGIN_B - #define MARGIN_T 0 - #define MARGIN_B 2 - - char str[16]; - sprintf_P(str, PSTR("Page %d of %d"), - screen_data.FilesScreen.cur_page + 1, screen_data.FilesScreen.num_page); - - CommandProcessor cmd; - cmd.colors(normal_btn) - .font(font_small) - .tag(0).button( BTN_POS(2,1), BTN_SIZE(4,header_h), str, OPT_CENTER | OPT_FLAT) - .font(font_medium) - .colors(action_btn) - .tag(241).enabled(prev_enabled).button( BTN_POS(1,1), BTN_SIZE(1,header_h), F("<")) - .tag(242).enabled(next_enabled).button( BTN_POS(6,1), BTN_SIZE(1,header_h), F(">")); -} - -void FilesScreen::drawFooter() { - #undef MARGIN_T - #undef MARGIN_B - #ifdef TOUCH_UI_PORTRAIT - #define MARGIN_T 15 - #define MARGIN_B 5 - #else - #define MARGIN_T 5 - #define MARGIN_B 5 - #endif - const bool has_selection = screen_data.FilesScreen.selected_tag != 0xFF; - const uint8_t back_tag = screen_data.FilesScreen.flags.is_root ? 240 : 245; - const uint8_t y = GRID_ROWS - footer_h + 1; - const uint8_t h = footer_h; - - CommandProcessor cmd; - cmd.colors(normal_btn) - .font(font_medium) - .colors(has_selection ? normal_btn : action_btn) - .tag(back_tag).button( BTN_POS(4,y), BTN_SIZE(3,h), GET_TEXT_F(MSG_BACK)) - .enabled(has_selection) - .colors(has_selection ? action_btn : normal_btn); - if (screen_data.FilesScreen.flags.is_dir) { - cmd.tag(244).button( BTN_POS(1, y), BTN_SIZE(3,h), GET_TEXT_F(MSG_BUTTON_OPEN)); - } else { - cmd.tag(243).button( BTN_POS(1, y), BTN_SIZE(3,h), GET_TEXT_F(MSG_BUTTON_PRINT)); - } -} - -void FilesScreen::onRedraw(draw_mode_t what) { - if (what & FOREGROUND) { - drawHeader(); - drawSelectedFile(); - drawFooter(); - } -} - -void FilesScreen::gotoPage(uint8_t page) { - screen_data.FilesScreen.selected_tag = 0xFF; - screen_data.FilesScreen.cur_page = page; - CommandProcessor cmd; - cmd.cmd(CMD_DLSTART) - .cmd(CLEAR_COLOR_RGB(bg_color)) - .cmd(CLEAR(true,true,true)) - .colors(normal_btn); - drawFileList(); - storeBackground(); -} - -bool FilesScreen::onTouchEnd(uint8_t tag) { - switch (tag) { - case 240: GOTO_PREVIOUS(); return true; - case 241: - if (screen_data.FilesScreen.cur_page > 0) { - gotoPage(screen_data.FilesScreen.cur_page-1); - } - break; - case 242: - if (screen_data.FilesScreen.cur_page < (screen_data.FilesScreen.num_page-1)) { - gotoPage(screen_data.FilesScreen.cur_page+1); - } - break; - case 243: - ConfirmStartPrintDialogBox::show(getSelectedFileIndex()); - return true; - case 244: - { - FileList files; - files.changeDir(getSelectedShortFilename()); - gotoPage(0); - } - break; - case 245: - { - FileList files; - files.upDir(); - gotoPage(0); - } - break; - default: - if (tag < 240) { - screen_data.FilesScreen.selected_tag = tag; - #if ENABLED(SCROLL_LONG_FILENAMES) && (FTDI_API_LEVEL >= 810) - if (FTDI::ftdi_chip >= 810) { - const char *longFilename = getSelectedLongFilename(); - if (longFilename[0]) { - CommandProcessor cmd; - uint16_t text_width = cmd.font(font_medium).text_width(longFilename); - screen_data.FilesScreen.scroll_pos = 0; - if (text_width > display_width) - screen_data.FilesScreen.scroll_max = text_width - display_width + MARGIN_L + MARGIN_R; - else - screen_data.FilesScreen.scroll_max = 0; - } - } - #endif - } - break; - } - return true; -} - -void FilesScreen::onIdle() { - #if ENABLED(SCROLL_LONG_FILENAMES) && (FTDI_API_LEVEL >= 810) - if (FTDI::ftdi_chip >= 810) { - CLCD::mem_write_32(CLCD::REG::MACRO_0, - VERTEX_TRANSLATE_X(-int32_t(screen_data.FilesScreen.scroll_pos))); - if (screen_data.FilesScreen.scroll_pos < screen_data.FilesScreen.scroll_max * 16) - screen_data.FilesScreen.scroll_pos++; - } - #endif -} - -#endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_sounds_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_sounds_screen.cpp deleted file mode 100644 index 25a44c1adbb5..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_sounds_screen.cpp +++ /dev/null @@ -1,160 +0,0 @@ -/******************************* - * interface_sounds_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" - -#if ENABLED(TOUCH_UI_FTDI_EVE) - -#include "screens.h" -#include "screen_data.h" - -using namespace FTDI; -using namespace Theme; -using namespace ExtUI; - -uint8_t InterfaceSoundsScreen::event_sounds[]; - -const char* InterfaceSoundsScreen::getSoundSelection(event_t event) { - return SoundList::name(event_sounds[event]); -} - -void InterfaceSoundsScreen::toggleSoundSelection(event_t event) { - event_sounds[event] = (event_sounds[event]+1) % SoundList::n; - playEventSound(event); -} - -void InterfaceSoundsScreen::setSoundSelection(event_t event, const SoundPlayer::sound_t* sound) { - for (uint8_t i = 0; i < SoundList::n; i++) - if (SoundList::data(i) == sound) - event_sounds[event] = i; -} - -void InterfaceSoundsScreen::playEventSound(event_t event, play_mode_t mode) { - sound.play(SoundList::data(event_sounds[event]), mode); -} - -void InterfaceSoundsScreen::defaultSettings() { - setSoundSelection(PRINTING_STARTED, twinkle); - setSoundSelection(PRINTING_FINISHED, fanfare); - setSoundSelection(PRINTING_FAILED, sad_trombone); -} - -void InterfaceSoundsScreen::onRedraw(draw_mode_t what) { - CommandProcessor cmd; - - if (what & BACKGROUND) { - cmd.cmd(CLEAR_COLOR_RGB(bg_color)) - .cmd(CLEAR(true,true,true)) - .cmd(COLOR_RGB(bg_text_enabled)) - .tag(0) - - #define GRID_COLS 4 - #define GRID_ROWS 9 - - .font(font_medium) - .text(BTN_POS(1,1), BTN_SIZE(4,1), GET_TEXT_F(MSG_SOUNDS)) - #undef EDGE_R - #define EDGE_R 30 - .font(font_small) - .tag(0).text (BTN_POS(1,2), BTN_SIZE(2,1), GET_TEXT_F(MSG_SOUND_VOLUME), OPT_RIGHTX | OPT_CENTERY) - .text (BTN_POS(1,3), BTN_SIZE(2,1), GET_TEXT_F(MSG_CLICK_SOUNDS), OPT_RIGHTX | OPT_CENTERY) - .text (BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_PRINT_STARTING), OPT_RIGHTX | OPT_CENTERY) - .text (BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_PRINT_FINISHED), OPT_RIGHTX | OPT_CENTERY) - .text (BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_PRINT_ERROR), OPT_RIGHTX | OPT_CENTERY); - #undef EDGE_R - } - - if (what & FOREGROUND) { - #ifdef TOUCH_UI_PORTRAIT - constexpr uint8_t w = 2; - #else - constexpr uint8_t w = 1; - #endif - - cmd.font(font_medium) - .colors(ui_slider) - #define EDGE_R 30 - .tag(2).slider (BTN_POS(3,2), BTN_SIZE(2,1), screen_data.InterfaceSettingsScreen.volume, 0xFF) - .colors(ui_toggle) - .tag(3).toggle2 (BTN_POS(3,3), BTN_SIZE(w,1), GET_TEXT_F(MSG_NO), GET_TEXT_F(MSG_YES), UIData::touch_sounds_enabled()) - #undef EDGE_R - .colors(normal_btn) - #define EDGE_R 0 - .tag(4).button (BTN_POS(3,5), BTN_SIZE(2,1), getSoundSelection(PRINTING_STARTED)) - .tag(5).button (BTN_POS(3,6), BTN_SIZE(2,1), getSoundSelection(PRINTING_FINISHED)) - .tag(6).button (BTN_POS(3,7), BTN_SIZE(2,1), getSoundSelection(PRINTING_FAILED)) - .colors(action_btn) - .tag(1).button (BTN_POS(1,9), BTN_SIZE(4,1), GET_TEXT_F(MSG_BACK)); - } -} - -void InterfaceSoundsScreen::onEntry() { - screen_data.InterfaceSettingsScreen.volume = SoundPlayer::get_volume(); - BaseScreen::onEntry(); -} - -bool InterfaceSoundsScreen::onTouchEnd(uint8_t tag) { - switch (tag) { - case 1: GOTO_PREVIOUS(); return true; - case 3: UIData::enable_touch_sounds(!UIData::touch_sounds_enabled()); break; - case 4: toggleSoundSelection(PRINTING_STARTED); break; - case 5: toggleSoundSelection(PRINTING_FINISHED); break; - case 6: toggleSoundSelection(PRINTING_FAILED); break; - default: - return false; - } - SaveSettingsDialogBox::settingsChanged(); - return true; -} - -bool InterfaceSoundsScreen::onTouchStart(uint8_t tag) { - CommandProcessor cmd; - #undef EDGE_R - #define EDGE_R 30 - switch (tag) { - case 2: cmd.track_linear(BTN_POS(3,2), BTN_SIZE(2,1), 2).execute(); break; - default: break; - } - return true; -} - -void InterfaceSoundsScreen::onIdle() { - if (refresh_timer.elapsed(TOUCH_UPDATE_INTERVAL)) { - refresh_timer.start(); - - uint16_t value; - CommandProcessor cmd; - switch (cmd.track_tag(value)) { - case 2: - screen_data.InterfaceSettingsScreen.volume = value >> 8; - SoundPlayer::set_volume(screen_data.InterfaceSettingsScreen.volume); - SaveSettingsDialogBox::settingsChanged(); - break; - default: - return; - } - onRefresh(); - } - BaseScreen::onIdle(); -} - -#endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/leveling_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/leveling_menu.cpp deleted file mode 100644 index 763403d28722..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/leveling_menu.cpp +++ /dev/null @@ -1,125 +0,0 @@ -/********************* - * leveling_menu.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" - -#if BOTH(TOUCH_UI_FTDI_EVE,HAS_LEVELING) - -#include "screens.h" - -#if BOTH(HAS_BED_PROBE,BLTOUCH) - #include "../../../../../feature/bltouch.h" -#endif - -using namespace FTDI; -using namespace ExtUI; -using namespace Theme; - -#ifdef TOUCH_UI_PORTRAIT - #define GRID_ROWS 10 - #define GRID_COLS 2 - #define TITLE_POS BTN_POS(1,1), BTN_SIZE(2,1) - #define LEVEL_BED_POS BTN_POS(1,2), BTN_SIZE(2,1) - #define LEVEL_AXIS_POS BTN_POS(1,3), BTN_SIZE(2,1) - #define Z_AUTO_ALIGN_POS BTN_POS(1,4), BTN_SIZE(2,1) - #define SHOW_MESH_POS BTN_POS(1,5), BTN_SIZE(2,1) - #define BLTOUCH_TITLE_POS BTN_POS(1,7), BTN_SIZE(2,1) - #define BLTOUCH_RESET_POS BTN_POS(1,8), BTN_SIZE(1,1) - #define BLTOUCH_TEST_POS BTN_POS(2,8), BTN_SIZE(1,1) - #define BACK_POS BTN_POS(1,10), BTN_SIZE(2,1) -#else - #define GRID_ROWS 8 - #define GRID_COLS 2 - #define TITLE_POS BTN_POS(1,1), BTN_SIZE(2,1) - #define LEVEL_BED_POS BTN_POS(1,2), BTN_SIZE(2,1) - #define LEVEL_AXIS_POS BTN_POS(1,3), BTN_SIZE(2,1) - #define Z_AUTO_ALIGN_POS BTN_POS(1,4), BTN_SIZE(2,1) - #define SHOW_MESH_POS BTN_POS(1,5), BTN_SIZE(2,1) - #define BLTOUCH_TITLE_POS BTN_POS(1,6), BTN_SIZE(2,1) - #define BLTOUCH_RESET_POS BTN_POS(1,7), BTN_SIZE(1,1) - #define BLTOUCH_TEST_POS BTN_POS(2,7), BTN_SIZE(1,1) - #define BACK_POS BTN_POS(1,8), BTN_SIZE(2,1) -#endif - -void LevelingMenu::onRedraw(draw_mode_t what) { - if (what & BACKGROUND) { - CommandProcessor cmd; - cmd.cmd(CLEAR_COLOR_RGB(Theme::bg_color)) - .cmd(CLEAR(true,true,true)) - .tag(0); - } - - if (what & FOREGROUND) { - CommandProcessor cmd; - cmd.font(font_large) - .text(TITLE_POS, GET_TEXT_F(MSG_LEVELING)) - .font(font_medium).colors(normal_btn) - .tag(2).button(LEVEL_BED_POS, GET_TEXT_F(MSG_LEVEL_BED)) - .enabled( - #ifdef AXIS_LEVELING_COMMANDS - 1 - #endif - ) - .tag(3).button(LEVEL_AXIS_POS, GET_TEXT_F(MSG_AUTOLEVEL_X_AXIS)) - .enabled(ENABLED(Z_STEPPER_AUTO_ALIGN)) - .tag(4).button(Z_AUTO_ALIGN_POS, GET_TEXT_F(MSG_AUTO_Z_ALIGN)) - .enabled(ENABLED(HAS_MESH)) - .tag(5).button(SHOW_MESH_POS, GET_TEXT_F(MSG_SHOW_MESH)); - #if ENABLED(BLTOUCH) - cmd.text(BLTOUCH_TITLE_POS, GET_TEXT_F(MSG_BLTOUCH)) - .tag(6).button(BLTOUCH_RESET_POS, GET_TEXT_F(MSG_BLTOUCH_RESET)) - .tag(7).button(BLTOUCH_TEST_POS, GET_TEXT_F(MSG_BLTOUCH_SELFTEST)); - #endif - cmd.colors(action_btn) - .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BACK)); - } -} - -bool LevelingMenu::onTouchEnd(uint8_t tag) { - switch (tag) { - case 1: GOTO_PREVIOUS(); break; - case 2: - #if HAS_MESH - BedMeshScreen::startMeshProbe(); - #else - SpinnerDialogBox::enqueueAndWait_P(F(BED_LEVELING_COMMANDS)); - #endif - break; - #ifdef AXIS_LEVELING_COMMANDS - case 3: SpinnerDialogBox::enqueueAndWait_P(F(AXIS_LEVELING_COMMANDS)); break; - #endif - #if ENABLED(Z_STEPPER_AUTO_ALIGN) - case 4: SpinnerDialogBox::enqueueAndWait_P(F("G34")); break; - #endif - #if HAS_MESH - case 5: GOTO_SCREEN(BedMeshScreen); break; - #endif - #if ENABLED(BLTOUCH) - case 6: injectCommands_P(PSTR("M280 P0 S60")); break; - case 7: SpinnerDialogBox::enqueueAndWait_P(F("M280 P0 S90\nG4 P100\nM280 P0 S120")); break; - #endif - default: return false; - } - return true; -} - -#endif // BOTH(TOUCH_UI_FTDI_EVE,HAS_LEVELING) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp deleted file mode 100644 index 53e3ab00c736..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp +++ /dev/null @@ -1,143 +0,0 @@ -/***************** - * main_menu.cpp * - *****************/ - -/**************************************************************************** - * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * - * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * - * Written By Marcio Teixeira 2019 - Cocoa Press * - * * - * This program is free software: you can redistribute it and/or modify * - * it under the terms of the GNU General Public License as published by * - * the Free Software Foundation, either version 3 of the License, or * - * (at your option) any later version. * - * * - * This program is distributed in the hope that it will be useful, * - * but WITHOUT ANY WARRANTY; without even the implied warranty of * - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * - * GNU General Public License for more details. * - * * - * To view a copy of the GNU General Public License, go to the following * - * location: . * - ****************************************************************************/ - -#include "../config.h" - -#if ENABLED(TOUCH_UI_FTDI_EVE) && !defined(TOUCH_UI_LULZBOT_BIO) - -#include "screens.h" - -using namespace FTDI; -using namespace Theme; - -void MainMenu::onRedraw(draw_mode_t what) { - if (what & BACKGROUND) { - CommandProcessor cmd; - cmd.cmd(CLEAR_COLOR_RGB(Theme::bg_color)) - .cmd(CLEAR(true,true,true)); - } - - #ifdef TOUCH_UI_PORTRAIT - #define GRID_ROWS 8 - #define GRID_COLS 2 - #define ABOUT_PRINTER_POS BTN_POS(1,1), BTN_SIZE(2,1) - #define ADVANCED_SETTINGS_POS BTN_POS(1,2), BTN_SIZE(2,1) - #define FILAMENTCHANGE_POS BTN_POS(1,3), BTN_SIZE(2,1) - #define TEMPERATURE_POS BTN_POS(1,4), BTN_SIZE(2,1) - #define DISABLE_STEPPERS_POS BTN_POS(1,5), BTN_SIZE(2,1) - #define MOVE_AXIS_POS BTN_POS(1,6), BTN_SIZE(1,1) - #define LEVELING_POS BTN_POS(2,6), BTN_SIZE(1,1) - #define AUTO_HOME_POS BTN_POS(1,7), BTN_SIZE(1,1) - #define CLEAN_NOZZLE_POS BTN_POS(2,7), BTN_SIZE(1,1) - #define BACK_POS BTN_POS(1,8), BTN_SIZE(2,1) - #else - #define GRID_ROWS 5 - #define GRID_COLS 2 - #define ADVANCED_SETTINGS_POS BTN_POS(1,1), BTN_SIZE(1,1) - #define ABOUT_PRINTER_POS BTN_POS(2,1), BTN_SIZE(1,1) - #define AUTO_HOME_POS BTN_POS(1,2), BTN_SIZE(1,1) - #define CLEAN_NOZZLE_POS BTN_POS(2,2), BTN_SIZE(1,1) - #define MOVE_AXIS_POS BTN_POS(1,3), BTN_SIZE(1,1) - #define DISABLE_STEPPERS_POS BTN_POS(2,3), BTN_SIZE(1,1) - #define TEMPERATURE_POS BTN_POS(1,4), BTN_SIZE(1,1) - #define FILAMENTCHANGE_POS BTN_POS(2,4), BTN_SIZE(1,1) - #define LEVELING_POS BTN_POS(1,5), BTN_SIZE(1,1) - #define BACK_POS BTN_POS(2,5), BTN_SIZE(1,1) - #endif - - if (what & FOREGROUND) { - CommandProcessor cmd; - cmd.colors(normal_btn) - .font(Theme::font_medium) - .tag(2).button( AUTO_HOME_POS, GET_TEXT_F(MSG_AUTO_HOME)) - .enabled( - #if ANY(NOZZLE_CLEAN_FEATURE, TOUCH_UI_COCOA_PRESS) - 1 - #endif - ) - .tag(3).button( CLEAN_NOZZLE_POS, GET_TEXT_F( - #if ENABLED(TOUCH_UI_COCOA_PRESS) - MSG_PREHEAT_1 - #else - MSG_CLEAN_NOZZLE - #endif - )) - .tag(4).button( MOVE_AXIS_POS, GET_TEXT_F(MSG_MOVE_AXIS)) - .tag(5).button( DISABLE_STEPPERS_POS, GET_TEXT_F(MSG_DISABLE_STEPPERS)) - .tag(6).button( TEMPERATURE_POS, GET_TEXT_F(MSG_TEMPERATURE)) - .enabled( - #if DISABLED(TOUCH_UI_LULZBOT_BIO) - 1 - #endif - ) - .tag(7).button( FILAMENTCHANGE_POS, GET_TEXT_F( - #if ENABLED(TOUCH_UI_COCOA_PRESS) - MSG_CASE_LIGHT - #else - MSG_FILAMENTCHANGE - #endif - )) - .tag(8).button( ADVANCED_SETTINGS_POS, GET_TEXT_F(MSG_ADVANCED_SETTINGS)) - .enabled( - #ifdef HAS_LEVELING - 1 - #endif - ) - .tag(9).button( LEVELING_POS, GET_TEXT_F(MSG_LEVELING)) - .tag(10).button( ABOUT_PRINTER_POS, GET_TEXT_F(MSG_INFO_MENU)) - .colors(action_btn) - .tag(1).button( BACK_POS, GET_TEXT_F(MSG_BACK)); - } -} - -bool MainMenu::onTouchEnd(uint8_t tag) { - using namespace ExtUI; - - switch (tag) { - case 1: SaveSettingsDialogBox::promptToSaveSettings(); break; - case 2: SpinnerDialogBox::enqueueAndWait_P(F("G28")); break; - #if ENABLED(TOUCH_UI_COCOA_PRESS) - case 3: GOTO_SCREEN(PreheatMenu); break; - #elif ENABLED(NOZZLE_CLEAN_FEATURE) - case 3: injectCommands_P(PSTR("G12")); GOTO_SCREEN(StatusScreen); break; - #endif - case 4: GOTO_SCREEN(MoveAxisScreen); break; - case 5: injectCommands_P(PSTR("M84")); break; - case 6: GOTO_SCREEN(TemperatureScreen); break; - #if BOTH(TOUCH_UI_COCOA_PRESS, CASE_LIGHT_ENABLE) - case 7: GOTO_SCREEN(CaseLightScreen); break; - #else - case 7: GOTO_SCREEN(ChangeFilamentScreen); break; - #endif - case 8: GOTO_SCREEN(AdvancedSettingsMenu); break; - #ifdef HAS_LEVELING - case 9: GOTO_SCREEN(LevelingMenu); break; - #endif - case 10: GOTO_SCREEN(AboutScreen); break; - default: - return false; - } - return true; -} - -#endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/move_axis_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/move_axis_screen.cpp deleted file mode 100644 index 5dd3174821e2..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/move_axis_screen.cpp +++ /dev/null @@ -1,133 +0,0 @@ -/************************ - * move_axis_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" - -#if ENABLED(TOUCH_UI_FTDI_EVE) - -#include "screens.h" -#include "screen_data.h" - -using namespace FTDI; -using namespace ExtUI; - -void MoveAxisScreen::onEntry() { - // Since Marlin keeps only one absolute position for all the extruders, - // we have to keep track of the relative motion of individual extruders - // ourselves. The relative distances are reset to zero whenever this - // screen is entered. - - LOOP_L_N(i, ExtUI::extruderCount) { - screen_data.MoveAxisScreen.e_rel[i] = 0; - } - BaseNumericAdjustmentScreen::onEntry(); -} - -void MoveAxisScreen::onRedraw(draw_mode_t what) { - widgets_t w(what); - w.precision(1); - w.units(GET_TEXT_F(MSG_UNITS_MM)); - w.heading( GET_TEXT_F(MSG_MOVE_AXIS)); - w.home_buttons(20); - w.color(Theme::x_axis).adjuster( 2, GET_TEXT_F(MSG_AXIS_X), getAxisPosition_mm(X), canMove(X)); - w.color(Theme::y_axis).adjuster( 4, GET_TEXT_F(MSG_AXIS_Y), getAxisPosition_mm(Y), canMove(Y)); - w.color(Theme::z_axis).adjuster( 6, GET_TEXT_F(MSG_AXIS_Z), getAxisPosition_mm(Z), canMove(Z)); - - w.color(Theme::e_axis); - #if EXTRUDERS == 1 - w.adjuster( 8, GET_TEXT_F(MSG_AXIS_E), screen_data.MoveAxisScreen.e_rel[0], canMove(E0)); - #elif HAS_MULTI_EXTRUDER - w.adjuster( 8, GET_TEXT_F(MSG_AXIS_E1), screen_data.MoveAxisScreen.e_rel[0], canMove(E0)); - w.adjuster( 10, GET_TEXT_F(MSG_AXIS_E2), screen_data.MoveAxisScreen.e_rel[1], canMove(E1)); - #if EXTRUDERS > 2 - w.adjuster( 12, GET_TEXT_F(MSG_AXIS_E3), screen_data.MoveAxisScreen.e_rel[2], canMove(E2)); - #endif - #if EXTRUDERS > 3 - w.adjuster( 14, GET_TEXT_F(MSG_AXIS_E4), screen_data.MoveAxisScreen.e_rel[3], canMove(E3)); - #endif - #endif - w.increments(); -} - -bool MoveAxisScreen::onTouchHeld(uint8_t tag) { - #define UI_INCREMENT_AXIS(axis) UI_INCREMENT(AxisPosition_mm, axis); - #define UI_DECREMENT_AXIS(axis) 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; - case 4: UI_DECREMENT_AXIS(Y); break; - case 5: UI_INCREMENT_AXIS(Y); break; - case 6: UI_DECREMENT_AXIS(Z); break; - case 7: UI_INCREMENT_AXIS(Z); break; - // For extruders, also update relative distances. - case 8: UI_DECREMENT_AXIS(E0); screen_data.MoveAxisScreen.e_rel[0] -= increment; break; - case 9: UI_INCREMENT_AXIS(E0); screen_data.MoveAxisScreen.e_rel[0] += increment; break; - #if HAS_MULTI_EXTRUDER - case 10: UI_DECREMENT_AXIS(E1); screen_data.MoveAxisScreen.e_rel[1] -= increment; break; - case 11: UI_INCREMENT_AXIS(E1); screen_data.MoveAxisScreen.e_rel[1] += increment; break; - #endif - #if EXTRUDERS > 2 - case 12: UI_DECREMENT_AXIS(E2); screen_data.MoveAxisScreen.e_rel[2] -= increment; break; - case 13: UI_INCREMENT_AXIS(E2); screen_data.MoveAxisScreen.e_rel[2] += increment; break; - #endif - #if EXTRUDERS > 3 - case 14: UI_DECREMENT_AXIS(E3); screen_data.MoveAxisScreen.e_rel[3] -= increment; break; - case 15: UI_INCREMENT_AXIS(E3); screen_data.MoveAxisScreen.e_rel[3] += increment; break; - #endif - case 20: SpinnerDialogBox::enqueueAndWait_P(F("G28 X")); break; - case 21: SpinnerDialogBox::enqueueAndWait_P(F("G28 Y")); break; - case 22: SpinnerDialogBox::enqueueAndWait_P(F("G28 Z")); break; - case 23: SpinnerDialogBox::enqueueAndWait_P(F("G28")); break; - default: - return false; - } - #undef UI_DECREMENT_AXIS - #undef UI_INCREMENT_AXIS - return true; -} - -float MoveAxisScreen::getManualFeedrate(uint8_t axis, float 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)); -} - -void MoveAxisScreen::setManualFeedrate(ExtUI::axis_t axis, float increment_mm) { - ExtUI::setFeedrate_mm_s(getManualFeedrate(X_AXIS + (axis - ExtUI::X), increment_mm)); -} - -void MoveAxisScreen::setManualFeedrate(ExtUI::extruder_t, float increment_mm) { - ExtUI::setFeedrate_mm_s(getManualFeedrate(E_AXIS, increment_mm)); -} - -void MoveAxisScreen::onIdle() { - if (refresh_timer.elapsed(STATUS_UPDATE_INTERVAL)) { - onRefresh(); - refresh_timer.start(); - } - BaseScreen::onIdle(); -} - -#endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/nudge_nozzle_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/nudge_nozzle_screen.cpp deleted file mode 100644 index ed3c8d999b4b..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/nudge_nozzle_screen.cpp +++ /dev/null @@ -1,123 +0,0 @@ -/******************** - * nudge_nozzle.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" - -#if BOTH(TOUCH_UI_FTDI_EVE, BABYSTEPPING) - -#include "screens.h" -#include "screen_data.h" - -using namespace FTDI; -using namespace Theme; -using namespace ExtUI; - -void NudgeNozzleScreen::onEntry() { - screen_data.NudgeNozzleScreen.show_offsets = false; - #if HAS_MULTI_EXTRUDER - screen_data.NudgeNozzleScreen.link_nozzles = true; - #endif - screen_data.NudgeNozzleScreen.rel.reset(); - - BaseNumericAdjustmentScreen::onEntry(); -} - -void NudgeNozzleScreen::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_NUDGE_NOZZLE)); - #if ENABLED(BABYSTEP_XY) - w.color(x_axis).adjuster(2, GET_TEXT_F(MSG_AXIS_X), screen_data.NudgeNozzleScreen.rel.x / getAxisSteps_per_mm(X)); - w.color(y_axis).adjuster(4, GET_TEXT_F(MSG_AXIS_Y), screen_data.NudgeNozzleScreen.rel.y / getAxisSteps_per_mm(Y)); - #endif - w.color(z_axis).adjuster(6, GET_TEXT_F(MSG_AXIS_Z), screen_data.NudgeNozzleScreen.rel.z / getAxisSteps_per_mm(Z)); - w.increments(); - #if HAS_MULTI_EXTRUDER - w.toggle(8, GET_TEXT_F(MSG_ADJUST_BOTH_NOZZLES), screen_data.NudgeNozzleScreen.link_nozzles); - #endif - - #if HAS_MULTI_EXTRUDER || HAS_BED_PROBE - w.toggle(9, GET_TEXT_F(MSG_SHOW_OFFSETS), screen_data.NudgeNozzleScreen.show_offsets); - - if (screen_data.NudgeNozzleScreen.show_offsets) { - char str[19]; - - w.draw_mode(BOTH); - w.color(other); - - #if HAS_BED_PROBE - dtostrf(getZOffset_mm(), 4, 2, str); - strcat(str, " "); - strcat_P(str, GET_TEXT(MSG_UNITS_MM)); - w.text_field(0, GET_TEXT_F(MSG_ZPROBE_ZOFFSET), str); - #endif - - #if HAS_MULTI_HOTEND - format_position(str, getNozzleOffset_mm(X, E1), getNozzleOffset_mm(Y, E1), getNozzleOffset_mm(Z, E1)); - w.text_field(0, GET_TEXT_F(MSG_OFFSETS_MENU), str); - #endif - } - #endif -} - -bool NudgeNozzleScreen::onTouchHeld(uint8_t tag) { - const float inc = getIncrement(); - #if HAS_MULTI_EXTRUDER - const bool link = screen_data.NudgeNozzleScreen.link_nozzles; - #else - constexpr bool link = true; - #endif - int16_t steps; - switch (tag) { - case 2: steps = mmToWholeSteps(inc, X); smartAdjustAxis_steps(-steps, X, link); screen_data.NudgeNozzleScreen.rel.x -= steps; break; - case 3: steps = mmToWholeSteps(inc, X); smartAdjustAxis_steps( steps, X, link); screen_data.NudgeNozzleScreen.rel.x += steps; break; - case 4: steps = mmToWholeSteps(inc, Y); smartAdjustAxis_steps(-steps, Y, link); screen_data.NudgeNozzleScreen.rel.y -= steps; break; - case 5: steps = mmToWholeSteps(inc, Y); smartAdjustAxis_steps( steps, Y, link); screen_data.NudgeNozzleScreen.rel.y += steps; break; - case 6: steps = mmToWholeSteps(inc, Z); smartAdjustAxis_steps(-steps, Z, link); screen_data.NudgeNozzleScreen.rel.z -= steps; break; - case 7: steps = mmToWholeSteps(inc, Z); smartAdjustAxis_steps( steps, Z, link); screen_data.NudgeNozzleScreen.rel.z += steps; break; - #if HAS_MULTI_EXTRUDER - case 8: screen_data.NudgeNozzleScreen.link_nozzles = !link; break; - #endif - case 9: screen_data.NudgeNozzleScreen.show_offsets = !screen_data.NudgeNozzleScreen.show_offsets; break; - default: return false; - } - #if HAS_MULTI_EXTRUDER || HAS_BED_PROBE - SaveSettingsDialogBox::settingsChanged(); - #endif - return true; -} - -bool NudgeNozzleScreen::onTouchEnd(uint8_t tag) { - if (tag == 1) { - SaveSettingsDialogBox::promptToSaveSettings(); - return true; - } - else - return BaseNumericAdjustmentScreen::onTouchEnd(tag); -} - -void NudgeNozzleScreen::onIdle() { - reset_menu_timeout(); -} - -#endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_menu.cpp deleted file mode 100644 index a8891162ea0d..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_menu.cpp +++ /dev/null @@ -1,83 +0,0 @@ -/******************** - * preheat_menu.cpp * - ********************/ - -/**************************************************************************** - * Written By Marcio Teixeira 2020 - Cocoa Press * - * * - * This program is free software: you can redistribute it and/or modify * - * it under the terms of the GNU General Public License as published by * - * the Free Software Foundation, either version 3 of the License, or * - * (at your option) any later version. * - * * - * This program is distributed in the hope that it will be useful, * - * but WITHOUT ANY WARRANTY; without even the implied warranty of * - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * - * GNU General Public License for more details. * - * * - * To view a copy of the GNU General Public License, go to the following * - * location: . * - ****************************************************************************/ - -#include "../config.h" - -#if ENABLED(TOUCH_UI_FTDI_EVE) && defined(TOUCH_UI_COCOA_PRESS) - -#include "screens.h" - -using namespace FTDI; -using namespace ExtUI; -using namespace Theme; - -void PreheatMenu::onRedraw(draw_mode_t what) { - if (what & BACKGROUND) { - CommandProcessor cmd; - cmd.cmd(CLEAR_COLOR_RGB(Theme::bg_color)) - .cmd(CLEAR(true,true,true)) - .tag(0); - } - - #define GRID_ROWS 3 - #define GRID_COLS 2 - - if (what & FOREGROUND) { - CommandProcessor cmd; - cmd.cmd(COLOR_RGB(bg_text_enabled)) - .font(Theme::font_medium) - .text ( BTN_POS(1,1), BTN_SIZE(2,1), GET_TEXT_F(MSG_PREHEAT_1)) - .colors(normal_btn) - .tag(2).button( BTN_POS(1,2), BTN_SIZE(1,1), F("Dark Chocolate")) - .tag(3).button( BTN_POS(2,2), BTN_SIZE(1,1), F("Milk Chocolate")) - .tag(4).button( BTN_POS(1,3), BTN_SIZE(1,1), F("White Chocolate")) - .colors(action_btn) - .tag(1) .button( BTN_POS(2,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_BACK)); - } -} - -bool PreheatMenu::onTouchEnd(uint8_t tag) { - switch (tag) { - case 1: GOTO_PREVIOUS(); break; - case 2: - #ifdef COCOA_PRESS_PREHEAT_DARK_CHOCOLATE_SCRIPT - injectCommands_P(PSTR(COCOA_PRESS_PREHEAT_DARK_CHOCOLATE_SCRIPT)); - #endif - GOTO_SCREEN(PreheatTimerScreen); - break; - case 3: - #ifdef COCOA_PRESS_PREHEAT_MILK_CHOCOLATE_SCRIPT - injectCommands_P(PSTR(COCOA_PRESS_PREHEAT_MILK_CHOCOLATE_SCRIPT)); - #endif - GOTO_SCREEN(PreheatTimerScreen); - break; - case 4: - #ifdef COCOA_PRESS_PREHEAT_WHITE_CHOCOLATE_SCRIPT - injectCommands_P(PSTR(COCOA_PRESS_PREHEAT_WHITE_CHOCOLATE_SCRIPT)); - #endif - GOTO_SCREEN(PreheatTimerScreen); - break; - default: return false; - } - return true; -} - -#endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_timer_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_timer_screen.cpp deleted file mode 100644 index 69eecaf54b36..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_timer_screen.cpp +++ /dev/null @@ -1,112 +0,0 @@ -/**************************** - * preheat_timer_screen.cpp * - ****************************/ - -/**************************************************************************** - * Written By Marcio Teixeira 2019 - Cocoa Press * - * * - * This program is free software: you can redistribute it and/or modify * - * it under the terms of the GNU General Public License as published by * - * the Free Software Foundation, either version 3 of the License, or * - * (at your option) any later version. * - * * - * This program is distributed in the hope that it will be useful, * - * but WITHOUT ANY WARRANTY; without even the implied warranty of * - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * - * GNU General Public License for more details. * - * * - * To view a copy of the GNU General Public License, go to the following * - * location: . * - ****************************************************************************/ - -#include "../config.h" - -#if ENABLED(TOUCH_UI_FTDI_EVE) && defined(TOUCH_UI_COCOA_PRESS) - -#include "screens.h" -#include "screen_data.h" - -#include "../ftdi_eve_lib/extras/circular_progress.h" - -using namespace FTDI; -using namespace ExtUI; -using namespace Theme; - -#define GRID_COLS 2 -#define GRID_ROWS 5 - -void PreheatTimerScreen::draw_message(draw_mode_t what) { - if (what & BACKGROUND) { - CommandProcessor cmd; - cmd.cmd(CLEAR_COLOR_RGB(bg_color)) - .cmd(CLEAR(true,true,true)) - .cmd(COLOR_RGB(bg_text_enabled)) - .tag(0); - draw_text_box(cmd, BTN_POS(2,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_HEATING), OPT_CENTER, font_large); - } -} - -uint16_t PreheatTimerScreen::secondsRemaining() { - const uint32_t elapsed_sec = (millis() - screen_data.PreheatTimerScreen.start_ms) / 1000; - return (COCOA_PRESS_PREHEAT_SECONDS > elapsed_sec) ? COCOA_PRESS_PREHEAT_SECONDS - elapsed_sec : 0; -} - -void PreheatTimerScreen::draw_time_remaining(draw_mode_t what) { - if (what & FOREGROUND) { - const uint16_t elapsed_sec = secondsRemaining(); - const uint8_t min = elapsed_sec / 60, - sec = elapsed_sec % 60; - - char str[10]; - sprintf_P(str, PSTR("%02d:%02d"), min, sec); - - CommandProcessor cmd; - cmd.font(font_xlarge); - draw_circular_progress(cmd, BTN_POS(1,1), BTN_SIZE(1,5), float(secondsRemaining()) * 100 / COCOA_PRESS_PREHEAT_SECONDS, str, theme_dark, theme_darkest); - } -} - -void PreheatTimerScreen::draw_interaction_buttons(draw_mode_t what) { - if (what & FOREGROUND) { - CommandProcessor cmd; - cmd.colors(normal_btn) - .font(font_medium) - .tag(1).button( BTN_POS(2,5), BTN_SIZE(1,1), F("Cancel")); - } -} - -void PreheatTimerScreen::onEntry() { - screen_data.PreheatTimerScreen.start_ms = millis(); -} - -void PreheatTimerScreen::onRedraw(draw_mode_t what) { - draw_message(what); - draw_time_remaining(what); - draw_interaction_buttons(what); -} - -bool PreheatTimerScreen::onTouchEnd(uint8_t tag) { - switch (tag) { - case 1: GOTO_PREVIOUS(); return true; - default: break; - } - return false; -} - -void PreheatTimerScreen::onIdle() { - if (secondsRemaining() == 0) { - AlertDialogBox::show(GET_TEXT_F(MSG_PREHEAT_FINISHED)); - // Remove SaveSettingsDialogBox from the stack - // so the alert box doesn't return to me. - current_screen.forget(); - } - - reset_menu_timeout(); - if (refresh_timer.elapsed(STATUS_UPDATE_INTERVAL)) { - onRefresh(); - refresh_timer.start(); - } - BaseScreen::onIdle(); -} - -#endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screen_data.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screen_data.h deleted file mode 100644 index dc38890a0efc..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screen_data.h +++ /dev/null @@ -1,97 +0,0 @@ -/***************** - * screen_data.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 - -#include "../ftdi_eve_lib/ftdi_eve_lib.h" - -// To save RAM, store state information related to a particular screen -// in a union. The values should be initialized in the onEntry method. - -struct base_numeric_adjustment_t {uint8_t increment;}; - -union screen_data_t { - struct base_numeric_adjustment_t BaseNumericAdjustmentScreen; - struct {uint8_t volume; uint8_t brightness;} InterfaceSettingsScreen; - struct {char passcode[5];} LockScreen; - struct {bool isError;} AlertDialogBox; - struct {bool auto_hide;} SpinnerDialogBox; - struct {uint8_t file_index;} ConfirmStartPrintDialogBox; - struct { - uint8_t e_tag, t_tag, repeat_tag; - ExtUI::extruder_t saved_extruder; - #if FILAMENT_UNLOAD_PURGE_LENGTH > 0 - bool need_purge; - #endif - } ChangeFilamentScreen; - struct { - struct { - uint8_t is_dir : 1; - uint8_t is_root : 1; - } flags; - uint8_t selected_tag; - uint8_t num_page; - uint8_t cur_page; - #if ENABLED(SCROLL_LONG_FILENAMES) && (FTDI_API_LEVEL >= 810) - uint16_t scroll_pos; - uint16_t scroll_max; - #endif - } FilesScreen; - struct { - struct base_numeric_adjustment_t placeholder; - float e_rel[ExtUI::extruderCount]; - } MoveAxisScreen; - #if HAS_MESH - struct { - enum : uint8_t { - MSG_NONE, - MSG_MESH_COMPLETE, - MSG_MESH_INCOMPLETE - } message; - uint8_t count; - uint8_t highlightedTag; - } BedMeshScreen; - #endif - #if ENABLED(TOUCH_UI_DEVELOPER_MENU) - struct { - uint32_t next_watchdog_trigger; - const char* message; - } StressTestScreen; - #endif - #if ENABLED(TOUCH_UI_COCOA_PRESS) - struct { - uint32_t start_ms; - } PreheatTimerScreen; - #endif - #if ENABLED(BABYSTEPPING) - struct { - struct base_numeric_adjustment_t placeholder; - xyz_int_t rel; - #if HAS_MULTI_EXTRUDER - bool link_nozzles; - #endif - bool show_offsets; - } NudgeNozzleScreen; - #endif -}; - -extern screen_data_t screen_data; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp deleted file mode 100644 index 16aa68216842..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp +++ /dev/null @@ -1,132 +0,0 @@ -/*************** - * screens.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" - -#if ENABLED(TOUCH_UI_FTDI_EVE) -#include "screens.h" -#include "screen_data.h" - -tiny_timer_t refresh_timer; -screen_data_t screen_data; - -SCREEN_TABLE { - DECL_SCREEN(BootScreen), - #if NUM_LANGUAGES > 1 - DECL_SCREEN(LanguageMenu), - #endif - DECL_SCREEN(TouchCalibrationScreen), - DECL_SCREEN(StatusScreen), - DECL_SCREEN(MainMenu), - DECL_SCREEN(TuneMenu), - DECL_SCREEN(AdvancedSettingsMenu), - DECL_SCREEN(AlertDialogBox), - DECL_SCREEN(ConfirmUserRequestAlertBox), - DECL_SCREEN(RestoreFailsafeDialogBox), - DECL_SCREEN(SaveSettingsDialogBox), - DECL_SCREEN(ConfirmStartPrintDialogBox), - DECL_SCREEN(ConfirmAbortPrintDialogBox), -#if ENABLED(CALIBRATION_GCODE) - DECL_SCREEN(ConfirmAutoCalibrationDialogBox), -#endif - DECL_SCREEN(SpinnerDialogBox), - DECL_SCREEN(AboutScreen), -#if ENABLED(PRINTCOUNTER) - DECL_SCREEN(StatisticsScreen), -#endif -#if ENABLED(BABYSTEPPING) - DECL_SCREEN(NudgeNozzleScreen), -#endif - DECL_SCREEN(MoveAxisScreen), - DECL_SCREEN(StepsScreen), -#if HAS_TRINAMIC_CONFIG - DECL_SCREEN(StepperCurrentScreen), - DECL_SCREEN(StepperBumpSensitivityScreen), -#endif -#if HAS_LEVELING - DECL_SCREEN(LevelingMenu), - #if HAS_BED_PROBE - DECL_SCREEN(ZOffsetScreen), - #endif - #if HAS_MESH - DECL_SCREEN(BedMeshScreen), - #endif -#endif -#if HAS_MULTI_HOTEND - DECL_SCREEN(NozzleOffsetScreen), -#endif -#if ENABLED(BACKLASH_GCODE) - DECL_SCREEN(BacklashCompensationScreen), -#endif - DECL_SCREEN(FeedratePercentScreen), - DECL_SCREEN(MaxVelocityScreen), - DECL_SCREEN(MaxAccelerationScreen), - DECL_SCREEN(DefaultAccelerationScreen), -#if HAS_JUNCTION_DEVIATION - DECL_SCREEN(JunctionDeviationScreen), -#else - DECL_SCREEN(JerkScreen), -#endif -#if ENABLED(CASE_LIGHT_ENABLE) - DECL_SCREEN(CaseLightScreen), -#endif -#if EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) - DECL_SCREEN(FilamentMenu), -#endif -#if ENABLED(FILAMENT_RUNOUT_SENSOR) - DECL_SCREEN(FilamentRunoutScreen), -#endif -#if ENABLED(LIN_ADVANCE) - DECL_SCREEN(LinearAdvanceScreen), -#endif - DECL_SCREEN(TemperatureScreen), - DECL_SCREEN(ChangeFilamentScreen), - DECL_SCREEN(InterfaceSettingsScreen), - DECL_SCREEN(InterfaceSoundsScreen), - DECL_SCREEN(LockScreen), -#if ENABLED(SDSUPPORT) - DECL_SCREEN(FilesScreen), -#endif - DECL_SCREEN(EndstopStatesScreen), -#if ENABLED(TOUCH_UI_LULZBOT_BIO) - DECL_SCREEN(BioPrintingDialogBox), - DECL_SCREEN(BioConfirmHomeXYZ), - DECL_SCREEN(BioConfirmHomeE), -#endif -#if ENABLED(TOUCH_UI_COCOA_PRESS) - DECL_SCREEN(PreheatMenu), - DECL_SCREEN(PreheatTimerScreen), -#endif -#if ENABLED(TOUCH_UI_DEVELOPER_MENU) - DECL_SCREEN(DeveloperMenu), - DECL_SCREEN(ConfirmEraseFlashDialogBox), - DECL_SCREEN(WidgetsScreen), - DECL_SCREEN(TouchRegistersScreen), - DECL_SCREEN(StressTestScreen), -#endif - DECL_SCREEN(MediaPlayerScreen), - DECL_SCREEN(DisplayTuningScreen) -}; - -SCREEN_TABLE_POST - -#endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h deleted file mode 100644 index 2108cff8df2a..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h +++ /dev/null @@ -1,851 +0,0 @@ -/************* - * screens.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 - -#include "../ftdi_eve_lib/ftdi_eve_lib.h" -#include "../language/language.h" -#include "../theme/theme.h" -#include "string_format.h" - -#ifndef BED_LEVELING_COMMANDS - #define BED_LEVELING_COMMANDS "G29" -#endif - -extern tiny_timer_t refresh_timer; - -/********************************* DL CACHE SLOTS ******************************/ - -// In order to reduce SPI traffic, we cache display lists (DL) in RAMG. This -// is done using the CLCD::DLCache class, which takes a unique ID for each -// cache location. These IDs are defined here: - -enum { - STATUS_SCREEN_CACHE, - MENU_SCREEN_CACHE, - TUNE_SCREEN_CACHE, - ALERT_BOX_CACHE, - SPINNER_CACHE, - ADVANCED_SETTINGS_SCREEN_CACHE, - MOVE_AXIS_SCREEN_CACHE, - TEMPERATURE_SCREEN_CACHE, - STEPS_SCREEN_CACHE, - MAX_FEEDRATE_SCREEN_CACHE, - MAX_VELOCITY_SCREEN_CACHE, - MAX_ACCELERATION_SCREEN_CACHE, - DEFAULT_ACCELERATION_SCREEN_CACHE, -#if HAS_LEVELING - LEVELING_SCREEN_CACHE, - #if HAS_BED_PROBE - ZOFFSET_SCREEN_CACHE, - #endif - #if HAS_MESH - BED_MESH_SCREEN_CACHE, - #endif -#endif -#if ENABLED(BABYSTEPPING) - ADJUST_OFFSETS_SCREEN_CACHE, -#endif -#if HAS_TRINAMIC_CONFIG - STEPPER_CURRENT_SCREEN_CACHE, - STEPPER_BUMP_SENSITIVITY_SCREEN_CACHE, -#endif -#if HAS_MULTI_HOTEND - NOZZLE_OFFSET_SCREEN_CACHE, -#endif -#if ENABLED(BACKLASH_GCODE) - BACKLASH_COMPENSATION_SCREEN_CACHE, -#endif -#if HAS_JUNCTION_DEVIATION - JUNC_DEV_SCREEN_CACHE, -#else - JERK_SCREEN_CACHE, -#endif -#if ENABLED(CASE_LIGHT_ENABLE) - CASE_LIGHT_SCREEN_CACHE, -#endif -#if EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) - FILAMENT_MENU_CACHE, -#endif -#if ENABLED(LIN_ADVANCE) - LINEAR_ADVANCE_SCREEN_CACHE, -#endif -#if ENABLED(FILAMENT_RUNOUT_SENSOR) - FILAMENT_RUNOUT_SCREEN_CACHE, -#endif -#if ENABLED(TOUCH_UI_LULZBOT_BIO) - PRINTING_SCREEN_CACHE, -#endif -#if ENABLED(TOUCH_UI_COCOA_PRESS) - PREHEAT_MENU_CACHE, - PREHEAT_TIMER_SCREEN_CACHE, -#endif -#if ENABLED(SDSUPPORT) - FILES_SCREEN_CACHE, -#endif - CHANGE_FILAMENT_SCREEN_CACHE, - INTERFACE_SETTINGS_SCREEN_CACHE, - INTERFACE_SOUNDS_SCREEN_CACHE, - LOCK_SCREEN_CACHE, - DISPLAY_TIMINGS_SCREEN_CACHE -}; - -// To save MCU RAM, the status message is "baked" in to the status screen -// cache, so we reserve a large chunk of memory for the DL cache - -#define STATUS_SCREEN_DL_SIZE 2048 -#define ALERT_BOX_DL_SIZE 3072 -#define SPINNER_DL_SIZE 3072 -#define FILE_SCREEN_DL_SIZE 4160 -#define PRINTING_SCREEN_DL_SIZE 2048 - -/************************* MENU SCREEN DECLARATIONS *************************/ - -class BaseScreen : public UIScreen { - protected: - #if LCD_TIMEOUT_TO_STATUS > 0 - static uint32_t last_interaction; - #endif - - static bool buttonIsPressed(uint8_t tag); - - public: - static bool buttonStyleCallback(CommandProcessor &, uint8_t, uint8_t &, uint16_t &, bool); - - static void reset_menu_timeout(); - - static void onEntry(); - static void onIdle(); -}; - -class BootScreen : public BaseScreen, public UncachedScreen { - private: - static void showSplashScreen(); - public: - static void onRedraw(draw_mode_t); - static void onIdle(); -}; - -class AboutScreen : public BaseScreen, public UncachedScreen { - public: - static void onEntry(); - static void onRedraw(draw_mode_t); - static bool onTouchEnd(uint8_t tag); -}; - -#if ENABLED(PRINTCOUNTER) - class StatisticsScreen : public BaseScreen, public UncachedScreen { - public: - static void onRedraw(draw_mode_t); - static bool onTouchEnd(uint8_t tag); - }; -#endif - -class KillScreen { - // The KillScreen is behaves differently than the - // others, so we do not bother extending UIScreen. - public: - static void show(const char*); -}; - -class DialogBoxBaseClass : public BaseScreen { - protected: - template static void drawMessage(const T, int16_t font = 0); - static void drawYesNoButtons(uint8_t default_btn = 0); - static void drawOkayButton(); - static void drawSpinner(); - static void drawButton(const progmem_str); - - static void onRedraw(draw_mode_t) {}; - public: - static bool onTouchEnd(uint8_t tag); - static void onIdle(); -}; - -class AlertDialogBox : public DialogBoxBaseClass, public CachedScreen { - public: - static void onEntry(); - static void onRedraw(draw_mode_t); - template static void show(T); - template static void showError(T); - static void hide(); -}; - -class RestoreFailsafeDialogBox : public DialogBoxBaseClass, public UncachedScreen { - public: - static void onRedraw(draw_mode_t); - static bool onTouchEnd(uint8_t tag); -}; - -class SaveSettingsDialogBox : public DialogBoxBaseClass, public UncachedScreen { - private: - static bool needs_save; - - public: - static void onRedraw(draw_mode_t); - static bool onTouchEnd(uint8_t tag); - - static void promptToSaveSettings(); - static void settingsChanged() {needs_save = true;} -}; - -class ConfirmStartPrintDialogBox : public DialogBoxBaseClass, public UncachedScreen { - private: - inline static const char *getShortFilename() {return getFilename(false);} - inline static const char *getLongFilename() {return getFilename(true);} - - static const char *getFilename(bool longName); - public: - static void onRedraw(draw_mode_t); - static bool onTouchEnd(uint8_t); - - static void show(uint8_t file_index); -}; - -class ConfirmAbortPrintDialogBox : public DialogBoxBaseClass, public UncachedScreen { - public: - static void onRedraw(draw_mode_t); - static bool onTouchEnd(uint8_t tag); -}; - -#if ENABLED(CALIBRATION_GCODE) -class ConfirmAutoCalibrationDialogBox : public DialogBoxBaseClass, public UncachedScreen { - public: - static void onRedraw(draw_mode_t); - static bool onTouchEnd(uint8_t tag); -}; -#endif - -class ConfirmUserRequestAlertBox : public AlertDialogBox { - public: - static void onRedraw(draw_mode_t); - static bool onTouchEnd(uint8_t); - static void hide(); - static void show(const char*); -}; - -class SpinnerDialogBox : public DialogBoxBaseClass, public CachedScreen { - public: - static void onRedraw(draw_mode_t); - static void onIdle(); - - static void show(const progmem_str); - static void hide(); - static void enqueueAndWait_P(const progmem_str commands); - static void enqueueAndWait_P(const progmem_str message, const progmem_str commands); -}; - -#if NONE(TOUCH_UI_LULZBOT_BIO, TOUCH_UI_COCOA_PRESS) -class StatusScreen : public BaseScreen, public CachedScreen { - private: - static void draw_axis_position(draw_mode_t); - static void draw_temperature(draw_mode_t); - static void draw_progress(draw_mode_t); - static void draw_interaction_buttons(draw_mode_t); - static void draw_status_message(draw_mode_t, const char * const); - - public: - static void loadBitmaps(); - static void setStatusMessage(const char *); - static void setStatusMessage(progmem_str); - static void onRedraw(draw_mode_t); - static void onStartup(); - static void onEntry(); - static void onIdle(); - static bool onTouchEnd(uint8_t tag); -}; -#else - class StatusScreen : public BaseScreen, public CachedScreen { - private: - static float increment; - static bool jog_xy; - static bool fine_motion; - - static void draw_temperature(draw_mode_t what); - static void draw_syringe(draw_mode_t what); - static void draw_arrows(draw_mode_t what); - static void draw_overlay_icons(draw_mode_t what); - static void draw_fine_motion(draw_mode_t what); - static void draw_buttons(draw_mode_t what); - public: - static void loadBitmaps(); - static void unlockMotors(); - - static void setStatusMessage(const char *); - static void setStatusMessage(progmem_str); - - static void onRedraw(draw_mode_t); - - static bool onTouchStart(uint8_t tag); - static bool onTouchHeld(uint8_t tag); - static bool onTouchEnd(uint8_t tag); - static void onIdle(); - - }; -#endif - -#if ENABLED(TOUCH_UI_LULZBOT_BIO) - class BioPrintingDialogBox : public BaseScreen, public CachedScreen { - private: - static void draw_status_message(draw_mode_t, const char * const); - static void draw_progress(draw_mode_t); - static void draw_time_remaining(draw_mode_t); - static void draw_interaction_buttons(draw_mode_t); - public: - static void onRedraw(draw_mode_t); - - static void show(); - - static void setStatusMessage(const char *); - static void setStatusMessage(progmem_str); - - static void onIdle(); - static bool onTouchEnd(uint8_t tag); - }; - - class BioConfirmHomeXYZ : public DialogBoxBaseClass, public UncachedScreen { - public: - static void onRedraw(draw_mode_t); - static bool onTouchEnd(uint8_t tag); - }; - - class BioConfirmHomeE : public DialogBoxBaseClass, public UncachedScreen { - public: - static void onRedraw(draw_mode_t); - static bool onTouchEnd(uint8_t tag); - }; -#endif - -#if ENABLED(TOUCH_UI_COCOA_PRESS) - class PreheatMenu : public BaseScreen, public CachedScreen { - public: - static void onRedraw(draw_mode_t); - static bool onTouchEnd(uint8_t tag); - }; - - class PreheatTimerScreen : public BaseScreen, public CachedScreen { - private: - static uint16_t secondsRemaining(); - - static void draw_message(draw_mode_t); - static void draw_time_remaining(draw_mode_t); - static void draw_interaction_buttons(draw_mode_t); - public: - static void onRedraw(draw_mode_t); - - static void onEntry(); - static void onIdle(); - static bool onTouchEnd(uint8_t tag); - }; -#endif - -class MainMenu : public BaseScreen, public CachedScreen { - public: - static void onRedraw(draw_mode_t); - static bool onTouchEnd(uint8_t tag); -}; - -class TuneMenu : public BaseScreen, public CachedScreen { - public: - static void onRedraw(draw_mode_t); - static bool onTouchEnd(uint8_t tag); -}; - -class TouchCalibrationScreen : public BaseScreen, public UncachedScreen { - public: - static void onRefresh(); - static void onEntry(); - static void onRedraw(draw_mode_t); - static void onIdle(); -}; - -class TouchRegistersScreen : public BaseScreen, public UncachedScreen { - public: - static void onRedraw(draw_mode_t); - static bool onTouchEnd(uint8_t tag); -}; - -class AdvancedSettingsMenu : public BaseScreen, public CachedScreen { - public: - static void onRedraw(draw_mode_t); - static bool onTouchEnd(uint8_t tag); -}; - -class ChangeFilamentScreen : public BaseScreen, public CachedScreen { - private: - static uint8_t getSoftenTemp(); - static ExtUI::extruder_t getExtruder(); - static void drawTempGradient(uint16_t x, uint16_t y, uint16_t w, uint16_t h); - static uint32_t getTempColor(uint32_t temp); - static void doPurge(); - public: - static void onEntry(); - static void onExit(); - static void onRedraw(draw_mode_t); - static bool onTouchStart(uint8_t tag); - static bool onTouchEnd(uint8_t tag); - static bool onTouchHeld(uint8_t tag); - static void onIdle(); -}; - -class BaseNumericAdjustmentScreen : public BaseScreen { - public: - enum precision_default_t { - DEFAULT_LOWEST, - DEFAULT_MIDRANGE, - DEFAULT_HIGHEST - }; - - protected: - class widgets_t { - private: - draw_mode_t _what; - uint8_t _line; - uint32_t _color; - uint8_t _decimals; - progmem_str _units; - enum style_t { - BTN_NORMAL, - BTN_ACTION, - BTN_TOGGLE, - BTN_DISABLED, - TEXT_AREA, - TEXT_LABEL - } _style; - - protected: - void _draw_increment_btn(CommandProcessor &, uint8_t line, const uint8_t tag); - void _button(CommandProcessor &, uint8_t tag, int16_t x, int16_t y, int16_t w, int16_t h, progmem_str, bool enabled = true, bool highlight = false); - void _button_style(CommandProcessor &cmd, style_t style); - public: - widgets_t(draw_mode_t); - - widgets_t &color(uint32_t color) {_color = color; return *this;} - widgets_t &units(progmem_str units) {_units = units; return *this;} - widgets_t &draw_mode(draw_mode_t what) {_what = what; return *this;} - widgets_t &precision(uint8_t decimals, precision_default_t = DEFAULT_HIGHEST); - - void heading (progmem_str label); - void adjuster_sram_val (uint8_t tag, progmem_str label, const char *value, bool is_enabled = true); - void adjuster (uint8_t tag, progmem_str label, const char *value, bool is_enabled = true); - void adjuster (uint8_t tag, progmem_str label, float value=0, bool is_enabled = true); - void button (uint8_t tag, progmem_str label, bool is_enabled = true); - void text_field (uint8_t tag, progmem_str label, const char *value, bool is_enabled = true); - void two_buttons (uint8_t tag1, progmem_str label1, - uint8_t tag2, progmem_str label2, bool is_enabled = true); - void toggle (uint8_t tag, progmem_str label, bool value, bool is_enabled = true); - void home_buttons (uint8_t tag); - void increments (); - }; - - static float getIncrement(); - - public: - static void onEntry(); - static bool onTouchEnd(uint8_t tag); -}; - -class MoveAxisScreen : public BaseNumericAdjustmentScreen, public CachedScreen { - private: - static float getManualFeedrate(uint8_t axis, float increment_mm); - public: - static void setManualFeedrate(ExtUI::axis_t, float increment_mm); - static void setManualFeedrate(ExtUI::extruder_t, float increment_mm); - - static void onEntry(); - static void onRedraw(draw_mode_t); - static bool onTouchHeld(uint8_t tag); - static void onIdle(); -}; - -class StepsScreen : public BaseNumericAdjustmentScreen, public CachedScreen { - public: - static void onRedraw(draw_mode_t); - static bool onTouchHeld(uint8_t tag); -}; - -#if HAS_TRINAMIC_CONFIG - class StepperCurrentScreen : public BaseNumericAdjustmentScreen, public CachedScreen { - public: - static void onRedraw(draw_mode_t); - static bool onTouchHeld(uint8_t tag); - }; - - class StepperBumpSensitivityScreen : public BaseNumericAdjustmentScreen, public CachedScreen { - public: - static void onRedraw(draw_mode_t); - static bool onTouchHeld(uint8_t tag); - }; -#endif - -#if HAS_MULTI_HOTEND - class NozzleOffsetScreen : public BaseNumericAdjustmentScreen, public CachedScreen { - public: - static void onEntry(); - static void onRedraw(draw_mode_t); - static bool onTouchHeld(uint8_t tag); - }; -#endif - -#if HAS_LEVELING - class LevelingMenu : public BaseScreen, public CachedScreen { - public: - static void onRedraw(draw_mode_t); - static bool onTouchEnd(uint8_t tag); - }; - - #if HAS_BED_PROBE - class ZOffsetScreen : public BaseNumericAdjustmentScreen, public CachedScreen { - public: - static void onRedraw(draw_mode_t); - static bool onTouchHeld(uint8_t tag); - }; - #endif - - #if HAS_MESH - class BedMeshScreen : public BaseScreen, public CachedScreen { - private: - enum MeshOpts { - USE_POINTS = 0x01, - USE_COLORS = 0x02, - USE_TAGS = 0x04, - USE_HIGHLIGHT = 0x08, - USE_AUTOSCALE = 0x10 - }; - - static uint8_t pointToTag(uint8_t x, uint8_t y); - static bool tagToPoint(uint8_t tag, uint8_t &x, uint8_t &y); - static float getHightlightedValue(); - static void drawHighlightedPointValue(); - static void drawMesh(int16_t x, int16_t y, int16_t w, int16_t h, ExtUI::bed_mesh_t data, uint8_t opts, float autoscale_max = 0.1); - static bool isMeshComplete(ExtUI::bed_mesh_t data); - - public: - static void onMeshUpdate(const int8_t x, const int8_t y, const float val); - static void onMeshUpdate(const int8_t x, const int8_t y, const ExtUI::probe_state_t); - static void onEntry(); - static void onRedraw(draw_mode_t); - static bool onTouchStart(uint8_t tag); - static bool onTouchEnd(uint8_t tag); - - static void startMeshProbe(); - }; - #endif -#endif - -#if ENABLED(BABYSTEPPING) - class NudgeNozzleScreen : public BaseNumericAdjustmentScreen, public CachedScreen { - public: - static void onEntry(); - static void onRedraw(draw_mode_t); - static bool onTouchEnd(uint8_t tag); - static bool onTouchHeld(uint8_t tag); - static void onIdle(); - }; -#endif - -#if ENABLED(BACKLASH_GCODE) - class BacklashCompensationScreen : public BaseNumericAdjustmentScreen, public CachedScreen { - public: - static void onRedraw(draw_mode_t); - static bool onTouchHeld(uint8_t tag); - }; -#endif - -class FeedratePercentScreen : public BaseNumericAdjustmentScreen, public CachedScreen { - public: - static void onRedraw(draw_mode_t); - static bool onTouchHeld(uint8_t tag); -}; - -class MaxVelocityScreen : public BaseNumericAdjustmentScreen, public CachedScreen { - public: - static void onRedraw(draw_mode_t); - static bool onTouchHeld(uint8_t tag); -}; - -class MaxAccelerationScreen : public BaseNumericAdjustmentScreen, public CachedScreen { - public: - static void onRedraw(draw_mode_t); - static bool onTouchHeld(uint8_t tag); -}; - -class DefaultAccelerationScreen : public BaseNumericAdjustmentScreen, public CachedScreen { - public: - static void onRedraw(draw_mode_t); - static bool onTouchHeld(uint8_t tag); -}; - -#if HAS_JUNCTION_DEVIATION - class JunctionDeviationScreen : public BaseNumericAdjustmentScreen, public CachedScreen { - public: - static void onRedraw(draw_mode_t); - static bool onTouchHeld(uint8_t tag); - }; -#else - class JerkScreen : public BaseNumericAdjustmentScreen, public CachedScreen { - public: - static void onRedraw(draw_mode_t); - static bool onTouchHeld(uint8_t tag); - }; -#endif - -#if ENABLED(CASE_LIGHT_ENABLE) - class CaseLightScreen : public BaseNumericAdjustmentScreen, public CachedScreen { - public: - static void onRedraw(draw_mode_t); - static bool onTouchHeld(uint8_t tag); - }; -#endif - -#if EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) - class FilamentMenu : public BaseNumericAdjustmentScreen, public CachedScreen { - public: - static void onRedraw(draw_mode_t); - static bool onTouchEnd(uint8_t tag); - }; -#endif - -#if ENABLED(FILAMENT_RUNOUT_SENSOR) - class FilamentRunoutScreen : public BaseNumericAdjustmentScreen, public CachedScreen { - public: - static void onRedraw(draw_mode_t); - static bool onTouchHeld(uint8_t tag); - }; -#endif - -#if ENABLED(LIN_ADVANCE) - class LinearAdvanceScreen : public BaseNumericAdjustmentScreen, public CachedScreen { - public: - static void onRedraw(draw_mode_t); - static bool onTouchHeld(uint8_t tag); - }; -#endif - -class TemperatureScreen : public BaseNumericAdjustmentScreen, public CachedScreen { - public: - static void onRedraw(draw_mode_t); - static bool onTouchHeld(uint8_t tag); -}; - -class InterfaceSoundsScreen : public BaseScreen, public CachedScreen { - public: - enum event_t { - PRINTING_STARTED = 0, - PRINTING_FINISHED = 1, - PRINTING_FAILED = 2, - - NUM_EVENTS - }; - - private: - friend class InterfaceSettingsScreen; - - static uint8_t event_sounds[NUM_EVENTS]; - - static const char* getSoundSelection(event_t); - static void toggleSoundSelection(event_t); - static void setSoundSelection(event_t, const FTDI::SoundPlayer::sound_t*); - - public: - static void playEventSound(event_t, FTDI::play_mode_t = FTDI::PLAY_ASYNCHRONOUS); - - static void defaultSettings(); - - static void onEntry(); - static void onRedraw(draw_mode_t); - static bool onTouchStart(uint8_t tag); - static bool onTouchEnd(uint8_t tag); - static void onIdle(); -}; - -class InterfaceSettingsScreen : public BaseScreen, public CachedScreen { - private: - struct persistent_data_t { - uint32_t touch_transform_a; - uint32_t touch_transform_b; - uint32_t touch_transform_c; - uint32_t touch_transform_d; - uint32_t touch_transform_e; - uint32_t touch_transform_f; - uint16_t passcode; - uint8_t display_brightness; - int8_t display_h_offset_adj; - int8_t display_v_offset_adj; - uint8_t sound_volume; - uint8_t bit_flags; - uint8_t event_sounds[InterfaceSoundsScreen::NUM_EVENTS]; - }; - - public: - #ifdef ARCHIM2_SPI_FLASH_EEPROM_BACKUP_SIZE - static bool backupEEPROM(); - #endif - - static void saveSettings(char *); - static void loadSettings(const char *); - static void defaultSettings(); - static void failSafeSettings(); - - static void onStartup(); - static void onEntry(); - static void onRedraw(draw_mode_t); - static bool onTouchStart(uint8_t tag); - static bool onTouchEnd(uint8_t tag); - static void onIdle(); -}; - -class LockScreen : public BaseScreen, public CachedScreen { - private: - friend InterfaceSettingsScreen; - - static uint16_t passcode; - - static char & message_style(); - static uint16_t compute_checksum(); - static void onPasscodeEntered(); - public: - static bool is_enabled(); - static void check_passcode(); - static void enable(); - static void disable(); - - static void set_hash(uint16_t pass) {passcode = pass;}; - static uint16_t get_hash() {return passcode;}; - - static void onEntry(); - static void onRedraw(draw_mode_t); - static bool onTouchEnd(uint8_t tag); -}; - -#if ENABLED(SDSUPPORT) - class FilesScreen : public BaseScreen, public CachedScreen { - private: - #ifdef TOUCH_UI_PORTRAIT - static constexpr uint8_t header_h = 2; - static constexpr uint8_t footer_h = 2; - static constexpr uint8_t files_per_page = 11; - #else - static constexpr uint8_t header_h = 1; - static constexpr uint8_t footer_h = 1; - static constexpr uint8_t files_per_page = 6; - #endif - - static uint8_t getTagForLine(uint8_t line) {return line + 2;} - static uint8_t getLineForTag(uint8_t tag) {return tag - 2;} - static uint16_t getFileForTag(uint8_t tag); - static uint16_t getSelectedFileIndex(); - - inline static const char *getSelectedShortFilename() {return getSelectedFilename(false);} - inline static const char *getSelectedLongFilename() {return getSelectedFilename(true);} - static const char *getSelectedFilename(bool longName); - - static void drawFileButton(const char* filename, uint8_t tag, bool is_dir, bool is_highlighted); - static void drawFileList(); - static void drawHeader(); - static void drawFooter(); - static void drawSelectedFile(); - - static void gotoPage(uint8_t); - public: - static void onEntry(); - static void onRedraw(draw_mode_t); - static bool onTouchEnd(uint8_t tag); - static void onIdle(); - }; -#endif - -class EndstopStatesScreen : public BaseScreen, public UncachedScreen { - public: - static void onEntry(); - static void onExit(); - static void onRedraw(draw_mode_t); - static bool onTouchEnd(uint8_t tag); - static void onIdle(); -}; - -class DisplayTuningScreen : public BaseNumericAdjustmentScreen, public CachedScreen { - public: - static void onRedraw(draw_mode_t); - static bool onTouchHeld(uint8_t tag); -}; - -#if ENABLED(TOUCH_UI_DEVELOPER_MENU) - class DeveloperMenu : public BaseScreen, public UncachedScreen { - public: - static void onRedraw(draw_mode_t); - static bool onTouchEnd(uint8_t tag); - }; - - class ConfirmEraseFlashDialogBox : public DialogBoxBaseClass, public UncachedScreen { - public: - static void onRedraw(draw_mode_t); - static bool onTouchEnd(uint8_t tag); - }; - - class WidgetsScreen : public BaseScreen, public UncachedScreen { - public: - static void onEntry(); - static void onRedraw(draw_mode_t); - static bool onTouchStart(uint8_t tag); - static void onIdle(); - }; - - class StressTestScreen : public BaseScreen, public UncachedScreen { - private: - static void drawDots(uint16_t x, uint16_t y, uint16_t h, uint16_t v); - static bool watchDogTestNow(); - static void recursiveLockup(); - static void iterativeLockup(); - static void runTestOnBootup(bool enable); - - public: - static void startupCheck(); - - static void onEntry(); - static void onRedraw(draw_mode_t); - static bool onTouchEnd(uint8_t tag); - static void onIdle(); - }; -#endif - -class MediaPlayerScreen : public BaseScreen, public UncachedScreen { - private: - typedef int16_t media_streamer_func_t(void *obj, void *buff, size_t bytes); - - public: - static bool playCardMedia(); - static bool playBootMedia(); - - static void onEntry(); - static void onRedraw(draw_mode_t); - - static void playStream(void *obj, media_streamer_func_t*); -}; - -#if NUM_LANGUAGES > 1 - class LanguageMenu : public BaseScreen, public UncachedScreen { - public: - static void onRedraw(draw_mode_t); - static bool onTouchEnd(uint8_t tag); - }; -#endif diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/spinner_dialog_box.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/spinner_dialog_box.cpp deleted file mode 100644 index de7eb92a8897..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/spinner_dialog_box.cpp +++ /dev/null @@ -1,68 +0,0 @@ -/************************** - * spinner_dialog_box.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" - -#if ENABLED(TOUCH_UI_FTDI_EVE) - -#include "screens.h" -#include "screen_data.h" - -using namespace FTDI; -using namespace ExtUI; - -void SpinnerDialogBox::onRedraw(draw_mode_t) { -} - -void SpinnerDialogBox::show(const progmem_str message) { - drawMessage(message); - drawSpinner(); - storeBackground(); - screen_data.SpinnerDialogBox.auto_hide = false; -} - -void SpinnerDialogBox::hide() { - CommandProcessor cmd; - cmd.stop().execute(); -} - -void SpinnerDialogBox::enqueueAndWait_P(const progmem_str commands) { - enqueueAndWait_P(GET_TEXT_F(MSG_PLEASE_WAIT), commands); -} - -void SpinnerDialogBox::enqueueAndWait_P(const progmem_str message, const progmem_str commands) { - show(message); - GOTO_SCREEN(SpinnerDialogBox); - ExtUI::injectCommands_P((const char*)commands); - screen_data.SpinnerDialogBox.auto_hide = true; -} - -void SpinnerDialogBox::onIdle() { - reset_menu_timeout(); - if (screen_data.SpinnerDialogBox.auto_hide && !commandsInQueue()) { - screen_data.SpinnerDialogBox.auto_hide = false; - hide(); - GOTO_PREVIOUS(); - } -} - -#endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/status_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/status_screen.cpp deleted file mode 100644 index fc7453fca70f..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/status_screen.cpp +++ /dev/null @@ -1,408 +0,0 @@ -/********************* - * status_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" - -#if ENABLED(TOUCH_UI_FTDI_EVE) && NONE(TOUCH_UI_LULZBOT_BIO, TOUCH_UI_COCOA_PRESS) - -#include "screens.h" -#include "screen_data.h" - -#include "../archim2-flash/flash_storage.h" - -using namespace FTDI; -using namespace Theme; - -#ifdef TOUCH_UI_PORTRAIT - #define GRID_ROWS 8 -#else - #define GRID_ROWS 8 -#endif - -void StatusScreen::draw_axis_position(draw_mode_t what) { - CommandProcessor cmd; - - #define GRID_COLS 3 - - #ifdef TOUCH_UI_PORTRAIT - #define X_LBL_POS BTN_POS(1,5), BTN_SIZE(1,1) - #define Y_LBL_POS BTN_POS(1,6), BTN_SIZE(1,1) - #define Z_LBL_POS BTN_POS(1,7), BTN_SIZE(1,1) - #define X_VAL_POS BTN_POS(2,5), BTN_SIZE(2,1) - #define Y_VAL_POS BTN_POS(2,6), BTN_SIZE(2,1) - #define Z_VAL_POS BTN_POS(2,7), BTN_SIZE(2,1) - #else - #define X_LBL_POS BTN_POS(1,5), BTN_SIZE(1,1) - #define Y_LBL_POS BTN_POS(2,5), BTN_SIZE(1,1) - #define Z_LBL_POS BTN_POS(3,5), BTN_SIZE(1,1) - #define X_VAL_POS BTN_POS(1,6), BTN_SIZE(1,1) - #define Y_VAL_POS BTN_POS(2,6), BTN_SIZE(1,1) - #define Z_VAL_POS BTN_POS(3,6), BTN_SIZE(1,1) - #endif - - #define _UNION_POS(x1,y1,w1,h1,x2,y2,w2,h2) x1,y1,max(x1+w1,x2+w2)-x1,max(y1+h1,y2+h2)-y1 - #define UNION_POS(p1, p2) _UNION_POS(p1, p2) - - if (what & BACKGROUND) { - cmd.tag(6) - .fgcolor(Theme::axis_label) - .font(Theme::font_large) - .button( UNION_POS(X_LBL_POS, X_VAL_POS), F(""), OPT_FLAT) - .button( UNION_POS(Y_LBL_POS, Y_VAL_POS), F(""), OPT_FLAT) - .button( UNION_POS(Z_LBL_POS, Z_VAL_POS), F(""), OPT_FLAT) - .font(Theme::font_medium) - .fgcolor(Theme::x_axis) .button( X_VAL_POS, F(""), OPT_FLAT) - .fgcolor(Theme::y_axis) .button( Y_VAL_POS, F(""), OPT_FLAT) - .fgcolor(Theme::z_axis) .button( Z_VAL_POS, F(""), OPT_FLAT) - .font(Theme::font_small) - .text ( X_LBL_POS, GET_TEXT_F(MSG_AXIS_X)) - .text ( Y_LBL_POS, GET_TEXT_F(MSG_AXIS_Y)) - .text ( Z_LBL_POS, GET_TEXT_F(MSG_AXIS_Z)) - .colors(normal_btn); - } - - if (what & FOREGROUND) { - using namespace ExtUI; - char x_str[15]; - char y_str[15]; - char z_str[15]; - - if (isAxisPositionKnown(X)) - format_position(x_str, getAxisPosition_mm(X)); - else - strcpy_P(x_str, PSTR("?")); - - if (isAxisPositionKnown(Y)) - format_position(y_str, getAxisPosition_mm(Y)); - else - strcpy_P(y_str, PSTR("?")); - - if (isAxisPositionKnown(Z)) - format_position(z_str, getAxisPosition_mm(Z), 2); - else - strcpy_P(z_str, PSTR("?")); - - cmd.tag(6) - .font(Theme::font_medium) - .text ( X_VAL_POS, x_str) - .text ( Y_VAL_POS, y_str) - .text ( Z_VAL_POS, z_str); - } - - #undef GRID_COLS -} - -#ifdef TOUCH_UI_PORTRAIT - #define GRID_COLS 8 -#else - #define GRID_COLS 12 -#endif - -void StatusScreen::draw_temperature(draw_mode_t what) { - using namespace Theme; - - #define TEMP_RECT_1 BTN_POS(1,1), BTN_SIZE(4,2) - #define TEMP_RECT_2 BTN_POS(1,1), BTN_SIZE(8,1) - #define NOZ_1_POS BTN_POS(1,1), BTN_SIZE(4,1) - #define NOZ_2_POS BTN_POS(5,1), BTN_SIZE(4,1) - #define BED_POS BTN_POS(1,2), BTN_SIZE(4,1) - #define FAN_POS BTN_POS(5,2), BTN_SIZE(4,1) - - #define _ICON_POS(x,y,w,h) x, y, w/4, h - #define _TEXT_POS(x,y,w,h) x + w/4, y, w - w/4, h - #define ICON_POS(pos) _ICON_POS(pos) - #define TEXT_POS(pos) _TEXT_POS(pos) - - CommandProcessor cmd; - - if (what & BACKGROUND) { - cmd.font(Theme::font_small) - .tag(5) - .fgcolor(temp) .button( TEMP_RECT_1, F(""), OPT_FLAT) - .button( TEMP_RECT_2, F(""), OPT_FLAT) - .fgcolor(fan_speed).button( FAN_POS, F(""), OPT_FLAT) - .tag(0); - - // Draw Extruder Bitmap on Extruder Temperature Button - - cmd.tag(5) - .cmd (BITMAP_SOURCE(Extruder_Icon_Info)) - .cmd (BITMAP_LAYOUT(Extruder_Icon_Info)) - .cmd (BITMAP_SIZE (Extruder_Icon_Info)) - .icon(ICON_POS(NOZ_1_POS), Extruder_Icon_Info, icon_scale) - .icon(ICON_POS(NOZ_2_POS), Extruder_Icon_Info, icon_scale); - - // Draw Bed Heat Bitmap on Bed Heat Button - cmd.cmd (BITMAP_SOURCE(Bed_Heat_Icon_Info)) - .cmd (BITMAP_LAYOUT(Bed_Heat_Icon_Info)) - .cmd (BITMAP_SIZE (Bed_Heat_Icon_Info)) - .icon(ICON_POS(BED_POS), Bed_Heat_Icon_Info, icon_scale); - - // Draw Fan Percent Bitmap on Bed Heat Button - - cmd.cmd (BITMAP_SOURCE(Fan_Icon_Info)) - .cmd (BITMAP_LAYOUT(Fan_Icon_Info)) - .cmd (BITMAP_SIZE (Fan_Icon_Info)) - .icon(ICON_POS(FAN_POS), Fan_Icon_Info, icon_scale); - - #ifdef TOUCH_UI_USE_UTF8 - load_utf8_bitmaps(cmd); // Restore font bitmap handles - #endif - } - - if (what & FOREGROUND) { - using namespace ExtUI; - char e0_str[20]; - char e1_str[20]; - char bed_str[20]; - char fan_str[20]; - - sprintf_P(fan_str, PSTR("%-3d %%"), int8_t(getActualFan_percent(FAN0))); - - if (isHeaterIdle(BED)) - format_temp_and_idle(bed_str, getActualTemp_celsius(BED)); - else - format_temp_and_temp(bed_str, getActualTemp_celsius(BED), getTargetTemp_celsius(BED)); - - if (isHeaterIdle(H0)) - format_temp_and_idle(e0_str, getActualTemp_celsius(H0)); - else - format_temp_and_temp(e0_str, getActualTemp_celsius(H0), getTargetTemp_celsius(H0)); - - - #if HAS_MULTI_EXTRUDER - if (isHeaterIdle(H1)) - format_temp_and_idle(e1_str, getActualTemp_celsius(H1)); - else - format_temp_and_temp(e1_str, getActualTemp_celsius(H1), getTargetTemp_celsius(H1)); - #else - strcpy_P(e1_str, PSTR("-")); - #endif - - cmd.tag(5) - .font(font_medium) - .text(TEXT_POS(NOZ_1_POS), e0_str) - .text(TEXT_POS(NOZ_2_POS), e1_str) - .text(TEXT_POS(BED_POS), bed_str) - .text(TEXT_POS(FAN_POS), fan_str); - } -} - -void StatusScreen::draw_progress(draw_mode_t what) { - using namespace ExtUI; - using namespace Theme; - - CommandProcessor cmd; - - #if ENABLED(TOUCH_UI_PORTRAIT) - #define TIME_POS BTN_POS(1,3), BTN_SIZE(4,1) - #define PROGRESS_POS BTN_POS(5,3), BTN_SIZE(4,1) - #else - #define TIME_POS BTN_POS(9,1), BTN_SIZE(4,1) - #define PROGRESS_POS BTN_POS(9,2), BTN_SIZE(4,1) - #endif - - if (what & BACKGROUND) { - cmd.tag(0).font(font_medium) - .fgcolor(progress).button(TIME_POS, F(""), OPT_FLAT) - .button(PROGRESS_POS, F(""), OPT_FLAT); - } - - if (what & FOREGROUND) { - const uint32_t elapsed = getProgress_seconds_elapsed(); - const uint8_t hrs = elapsed/3600; - const uint8_t min = (elapsed/60)%60; - - char time_str[10]; - char progress_str[10]; - - sprintf_P(time_str, PSTR(" %02d : %02d"), hrs, min); - sprintf_P(progress_str, PSTR("%-3d %%"), getProgress_percent() ); - - cmd.font(font_medium) - .tag(7).text(TIME_POS, time_str) - .text(PROGRESS_POS, progress_str); - } -} - -#undef GRID_COLS - - -void StatusScreen::draw_interaction_buttons(draw_mode_t what) { - #define GRID_COLS 4 - if (what & FOREGROUND) { - using namespace ExtUI; - - #if ENABLED(TOUCH_UI_PORTRAIT) - #define MEDIA_BTN_POS BTN_POS(1,8), BTN_SIZE(2,1) - #define MENU_BTN_POS BTN_POS(3,8), BTN_SIZE(2,1) - #else - #define MEDIA_BTN_POS BTN_POS(1,7), BTN_SIZE(2,2) - #define MENU_BTN_POS BTN_POS(3,7), BTN_SIZE(2,2) - #endif - - const bool has_media = isMediaInserted() && !isPrintingFromMedia(); - - CommandProcessor cmd; - cmd.colors(normal_btn) - .font(Theme::font_medium) - .colors(has_media ? action_btn : normal_btn) - .enabled(has_media) - .tag(3).button(MEDIA_BTN_POS, isPrintingFromMedia() ? GET_TEXT_F(MSG_PRINTING) : GET_TEXT_F(MSG_BUTTON_MEDIA)) - .colors(!has_media ? action_btn : normal_btn) - .tag(4).button( MENU_BTN_POS, GET_TEXT_F(MSG_BUTTON_MENU)); - } - #undef GRID_COLS -} - -void StatusScreen::draw_status_message(draw_mode_t what, const char* message) { - #define GRID_COLS 1 - - #if ENABLED(TOUCH_UI_PORTRAIT) - #define STATUS_POS BTN_POS(1,4), BTN_SIZE(1,1) - #else - #define STATUS_POS BTN_POS(1,3), BTN_SIZE(1,2) - #endif - - if (what & BACKGROUND) { - CommandProcessor cmd; - cmd.fgcolor(Theme::status_msg) - .tag(0) - .button( STATUS_POS, F(""), OPT_FLAT); - - draw_text_box(cmd, STATUS_POS, message, OPT_CENTER, font_large); - } - #undef GRID_COLS -} - -void StatusScreen::setStatusMessage(progmem_str 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* message) { - CommandProcessor cmd; - cmd.cmd(CMD_DLSTART) - .cmd(CLEAR_COLOR_RGB(Theme::bg_color)) - .cmd(CLEAR(true,true,true)); - - draw_temperature(BACKGROUND); - draw_status_message(BACKGROUND, message); - draw_interaction_buttons(BACKGROUND); - draw_progress(BACKGROUND); - draw_axis_position(BACKGROUND); - - storeBackground(); - - #if ENABLED(TOUCH_UI_DEBUG) - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR("New status message: ", message); - #endif - - if (AT_SCREEN(StatusScreen)) { - current_screen.onRefresh(); - } -} - -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)); - - // Load fonts for internationalization - #ifdef TOUCH_UI_USE_UTF8 - load_utf8_data(base + UTF8_FONT_OFFSET); - #endif -} - -void StatusScreen::onStartup() { - UIFlashStorage::initialize(); -} - -void StatusScreen::onRedraw(draw_mode_t what) { - if (what & FOREGROUND) { - draw_temperature(FOREGROUND); - draw_progress(FOREGROUND); - draw_axis_position(FOREGROUND); - draw_interaction_buttons(FOREGROUND); - } -} - -void StatusScreen::onEntry() { - BaseScreen::onEntry(); - onRefresh(); -} - -void StatusScreen::onIdle() { - if (refresh_timer.elapsed(STATUS_UPDATE_INTERVAL)) { - onRefresh(); - refresh_timer.start(); - } - BaseScreen::onIdle(); -} - -bool StatusScreen::onTouchEnd(uint8_t tag) { - using namespace ExtUI; - - switch (tag) { - #if ENABLED(SDSUPPORT) - case 3: GOTO_SCREEN(FilesScreen); break; - #endif - case 4: - if (isPrinting()) { - GOTO_SCREEN(TuneMenu); - } - else { - GOTO_SCREEN(MainMenu); - } - break; - case 5: GOTO_SCREEN(TemperatureScreen); break; - case 6: - if (isPrinting()) { - #if ENABLED(BABYSTEPPING) - GOTO_SCREEN(NudgeNozzleScreen); - #elif HAS_BED_PROBE - GOTO_SCREEN(ZOffsetScreen); - #else - return false; - #endif - } - else { - GOTO_SCREEN(MoveAxisScreen); - } - break; - case 7: GOTO_SCREEN(FeedratePercentScreen); break; - default: - return true; - } - // If a passcode is enabled, the LockScreen will prevent the - // user from proceeding. - LockScreen::check_passcode(); - return true; -} - -#endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/string_format.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/string_format.cpp deleted file mode 100644 index b7ce76ecd2b3..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/string_format.cpp +++ /dev/null @@ -1,83 +0,0 @@ -/********************* - * string_format.cpp * - *********************/ - -/**************************************************************************** - * 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" - -#if ENABLED(TOUCH_UI_FTDI_EVE) - -#include "screens.h" - -#define ROUND(val) uint16_t((val)+0.5) - -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wno-format" - -/** - * Formats a temperature string (e.g. "100°C") - */ -void format_temp(char *str, float t1) { - sprintf_P(str, PSTR("%3d" S_FMT), ROUND(t1), GET_TEXT(MSG_UNITS_C)); -} - -/** - * Formats a temperature string for an idle heater (e.g. "100 °C / idle") - */ -void format_temp_and_idle(char *str, float t1) { - sprintf_P(str, PSTR("%3d" S_FMT " / " S_FMT), ROUND(t1), GET_TEXT(MSG_UNITS_C), GET_TEXT(MSG_IDLE)); -} - -/** - * Formats a temperature string for an active heater (e.g. "100 / 200°C") - */ -void format_temp_and_temp(char *str, float t1, float t2) { - sprintf_P(str, PSTR("%3d / %3d" S_FMT), ROUND(t1), ROUND(t2), GET_TEXT(MSG_UNITS_C)); -} - -/** - * Formats a temperature string for a material (e.g. "100°C (PLA)") - */ -void format_temp_and_material(char *str, float t1, const char *material) { - sprintf_P(str, PSTR("%3d" S_FMT " (" S_FMT ")"), ROUND(t1), GET_TEXT(MSG_UNITS_C), material); -} - -/** - * Formats a position value (e.g. "10 mm") - */ -void format_position(char *str, float p, uint8_t decimals) { - dtostrf(p, 4 + decimals, decimals, str); - strcat_P(str, PSTR(" ")); - strcat_P(str, GET_TEXT(MSG_UNITS_MM)); -} - -/** - * Formats a position vector (e.g. "10; 20; 30 mm") - */ -void format_position(char *str, float x, float y, float z) { - char num1[7], num2[7], num3[7]; - dtostrf(x, 4, 2, num1); - dtostrf(y, 4, 2, num2); - dtostrf(z, 4, 2, num3); - sprintf_P(str, PSTR("%s; %s; %s " S_FMT), num1, num2, num3, GET_TEXT(MSG_UNITS_MM)); -} - -#pragma GCC diagnostic pop - -#endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/touch_registers_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/touch_registers_screen.cpp deleted file mode 100644 index 8c3bc856b3c7..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/touch_registers_screen.cpp +++ /dev/null @@ -1,86 +0,0 @@ -/****************************** - * touch_registers_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" - -#if BOTH(TOUCH_UI_FTDI_EVE, TOUCH_UI_DEVELOPER_MENU) - -#include "screens.h" - -using namespace FTDI; -using namespace Theme; - -void TouchRegistersScreen::onRedraw(draw_mode_t) { - const uint32_t T_Transform_A = CLCD::mem_read_32(CLCD::REG::TOUCH_TRANSFORM_A); - const uint32_t T_Transform_B = CLCD::mem_read_32(CLCD::REG::TOUCH_TRANSFORM_B); - const uint32_t T_Transform_C = CLCD::mem_read_32(CLCD::REG::TOUCH_TRANSFORM_C); - const uint32_t T_Transform_D = CLCD::mem_read_32(CLCD::REG::TOUCH_TRANSFORM_D); - const uint32_t T_Transform_E = CLCD::mem_read_32(CLCD::REG::TOUCH_TRANSFORM_E); - const uint32_t T_Transform_F = CLCD::mem_read_32(CLCD::REG::TOUCH_TRANSFORM_F); - char b[20]; - - CommandProcessor cmd; - cmd.cmd(CLEAR_COLOR_RGB(bg_color)) - .cmd(CLEAR(true,true,true)) - .tag(0); - - #define GRID_ROWS 7 - #define GRID_COLS 2 - cmd.tag(0) - .font(font_xsmall) - .fgcolor(transformA) .button( BTN_POS(1,1), BTN_SIZE(1,1), F("TOUCH_XFORM_A")) - .fgcolor(transformB) .button( BTN_POS(1,2), BTN_SIZE(1,1), F("TOUCH_XFORM_B")) - .fgcolor(transformC) .button( BTN_POS(1,3), BTN_SIZE(1,1), F("TOUCH_XFORM_C")) - .fgcolor(transformD) .button( BTN_POS(1,4), BTN_SIZE(1,1), F("TOUCH_XFORM_D")) - .fgcolor(transformE) .button( BTN_POS(1,5), BTN_SIZE(1,1), F("TOUCH_XFORM_E")) - .fgcolor(transformF) .button( BTN_POS(1,6), BTN_SIZE(1,1), F("TOUCH_XFORM_F")) - - .fgcolor(transformVal).button( BTN_POS(2,1), BTN_SIZE(1,1), F(""), OPT_FLAT) - .fgcolor(transformVal).button( BTN_POS(2,2), BTN_SIZE(1,1), F(""), OPT_FLAT) - .fgcolor(transformVal).button( BTN_POS(2,3), BTN_SIZE(1,1), F(""), OPT_FLAT) - .fgcolor(transformVal).button( BTN_POS(2,4), BTN_SIZE(1,1), F(""), OPT_FLAT) - .fgcolor(transformVal).button( BTN_POS(2,5), BTN_SIZE(1,1), F(""), OPT_FLAT) - .fgcolor(transformVal).button( BTN_POS(2,6), BTN_SIZE(1,1), F(""), OPT_FLAT); - - sprintf_P(b, PSTR("0x%08lX"), T_Transform_A); cmd.text( BTN_POS(2,1), BTN_SIZE(1,1), b); - sprintf_P(b, PSTR("0x%08lX"), T_Transform_B); cmd.text( BTN_POS(2,2), BTN_SIZE(1,1), b); - sprintf_P(b, PSTR("0x%08lX"), T_Transform_C); cmd.text( BTN_POS(2,3), BTN_SIZE(1,1), b); - sprintf_P(b, PSTR("0x%08lX"), T_Transform_D); cmd.text( BTN_POS(2,4), BTN_SIZE(1,1), b); - sprintf_P(b, PSTR("0x%08lX"), T_Transform_E); cmd.text( BTN_POS(2,5), BTN_SIZE(1,1), b); - sprintf_P(b, PSTR("0x%08lX"), T_Transform_F); cmd.text( BTN_POS(2,6), BTN_SIZE(1,1), b); - - cmd.colors(action_btn).font(font_medium) - .tag(1).button( BTN_POS(2,7), BTN_SIZE(1,1), F("Back")); - #undef GRID_COLS - #undef GRID_ROWS - } - - bool TouchRegistersScreen::onTouchEnd(uint8_t tag) { - switch (tag) { - case 1: GOTO_PREVIOUS(); break; - default: - return false; - } - return true; - } - -#endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/tune_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/tune_menu.cpp deleted file mode 100644 index 9fe2f1e9cbcb..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/tune_menu.cpp +++ /dev/null @@ -1,127 +0,0 @@ -/******************* - * tune_menu.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" - -#if ENABLED(TOUCH_UI_FTDI_EVE) && !defined(TOUCH_UI_LULZBOT_BIO) - -#include "screens.h" - -using namespace FTDI; -using namespace Theme; - -void TuneMenu::onRedraw(draw_mode_t what) { - if (what & BACKGROUND) { - CommandProcessor cmd; - cmd.cmd(CLEAR_COLOR_RGB(bg_color)) - .cmd(CLEAR(true,true,true)); - } - - #ifdef TOUCH_UI_PORTRAIT - #define GRID_ROWS 9 - #define GRID_COLS 2 - #define TEMPERATURE_POS BTN_POS(1,1), BTN_SIZE(2,1) - #define FIL_CHANGE_POS BTN_POS(1,2), BTN_SIZE(2,1) - #define FILAMENT_POS BTN_POS(1,3), BTN_SIZE(2,1) - #define NUDGE_NOZ_POS BTN_POS(1,4), BTN_SIZE(2,1) - #define SPEED_POS BTN_POS(1,5), BTN_SIZE(2,1) - #define PAUSE_POS BTN_POS(1,6), BTN_SIZE(2,1) - #define STOP_POS BTN_POS(1,7), BTN_SIZE(2,1) - #define CASE_LIGHT_POS BTN_POS(1,8), BTN_SIZE(2,1) - #define BACK_POS BTN_POS(1,9), BTN_SIZE(2,1) - #else - #define GRID_ROWS 5 - #define GRID_COLS 2 - #define TEMPERATURE_POS BTN_POS(1,1), BTN_SIZE(1,1) - #define NUDGE_NOZ_POS BTN_POS(2,1), BTN_SIZE(1,1) - #define FIL_CHANGE_POS BTN_POS(1,2), BTN_SIZE(1,1) - #define SPEED_POS BTN_POS(2,2), BTN_SIZE(1,1) - #define PAUSE_POS BTN_POS(1,3), BTN_SIZE(1,1) - #define STOP_POS BTN_POS(2,3), BTN_SIZE(1,1) - #define FILAMENT_POS BTN_POS(1,4), BTN_SIZE(1,1) - #define CASE_LIGHT_POS BTN_POS(2,4), BTN_SIZE(1,1) - #define BACK_POS BTN_POS(1,5), BTN_SIZE(2,1) - #endif - - if (what & FOREGROUND) { - using namespace ExtUI; - - CommandProcessor cmd; - cmd.colors(normal_btn) - .font(font_medium) - .tag(2).button( TEMPERATURE_POS, GET_TEXT_F(MSG_TEMPERATURE)) - .enabled(!isPrinting() || isPrintingFromMediaPaused()) - .tag(3).button( FIL_CHANGE_POS, GET_TEXT_F(MSG_FILAMENTCHANGE)) - .enabled(EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR)) - .tag(9).button( FILAMENT_POS, GET_TEXT_F(MSG_FILAMENT)) - .enabled(EITHER(HAS_BED_PROBE, BABYSTEPPING)) - .tag(4).button( NUDGE_NOZ_POS, GET_TEXT_F(TERN(BABYSTEPPING, MSG_NUDGE_NOZZLE, MSG_ZPROBE_ZOFFSET))) - .tag(5).button( SPEED_POS, GET_TEXT_F(MSG_PRINT_SPEED)) - .tag(isPrintingFromMediaPaused() ? 7 : 6) - .enabled(TERN0(SDSUPPORT, isPrintingFromMedia())) - .button( PAUSE_POS, isPrintingFromMediaPaused() ? GET_TEXT_F(MSG_RESUME_PRINT) : GET_TEXT_F(MSG_PAUSE_PRINT)) - .enabled(TERN0(SDSUPPORT, isPrintingFromMedia())) - .tag(8).button( STOP_POS, GET_TEXT_F(MSG_STOP_PRINT)) - .enabled(ENABLED(CASE_LIGHT_ENABLE)) - .tag(10).button( CASE_LIGHT_POS, GET_TEXT_F(MSG_CASE_LIGHT)) - .tag(1).colors(action_btn) - .button( BACK_POS, GET_TEXT_F(MSG_BACK)); - } - #undef GRID_COLS - #undef GRID_ROWS -} - -bool TuneMenu::onTouchEnd(uint8_t tag) { - using namespace Theme; - using namespace ExtUI; - switch (tag) { - case 1: GOTO_PREVIOUS(); break; - case 2: GOTO_SCREEN(TemperatureScreen); break; - case 3: GOTO_SCREEN(ChangeFilamentScreen); break; - case 4: - #if ENABLED(BABYSTEPPING) - GOTO_SCREEN(NudgeNozzleScreen); - #elif HAS_BED_PROBE - GOTO_SCREEN(ZOffsetScreen); - #endif - break; - case 5: GOTO_SCREEN(FeedratePercentScreen); break; - case 6: sound.play(twinkle, PLAY_ASYNCHRONOUS); ExtUI::pausePrint(); GOTO_SCREEN(StatusScreen); break; - case 7: sound.play(twinkle, PLAY_ASYNCHRONOUS); ExtUI::resumePrint(); GOTO_SCREEN(StatusScreen); break; - case 8: - GOTO_SCREEN(ConfirmAbortPrintDialogBox); - current_screen.forget(); - PUSH_SCREEN(StatusScreen); - break; - #if EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) - case 9: GOTO_SCREEN(FilamentMenu); break; - #endif - #if ENABLED(CASE_LIGHT_ENABLE) - case 10: GOTO_SCREEN(CaseLightScreen); break; - #endif - default: - return false; - } - return true; -} - -#endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/z_offset_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/z_offset_screen.cpp deleted file mode 100644 index f5cd03697c08..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/z_offset_screen.cpp +++ /dev/null @@ -1,54 +0,0 @@ -/*********************** - * 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" - -#if BOTH(TOUCH_UI_FTDI_EVE, HAS_BED_PROBE) - -#include "screens.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(); -} - -bool ZOffsetScreen::onTouchHeld(uint8_t tag) { - const float increment = getIncrement(); - switch (tag) { - case 4: UI_DECREMENT(ZOffset_mm); break; - case 5: UI_INCREMENT(ZOffset_mm); break; - default: - return false; - } - SaveSettingsDialogBox::settingsChanged(); - return true; -} - -#endif // TOUCH_UI_FTDI_EVE && HAS_BED_PROBE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/bitmaps.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/bitmaps.h deleted file mode 100644 index 2cb039c84df9..000000000000 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/bitmaps.h +++ /dev/null @@ -1,183 +0,0 @@ -/************* - * bitmaps.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 - -namespace Theme { - using namespace FTDI; - - constexpr PROGMEM bitmap_info_t Extruder_Icon_Info = { - .format = L1, - .linestride = 3, - .filter = BILINEAR, - .wrapx = BORDER, - .wrapy = BORDER, - .RAMG_offset = 8000, - .width = 24, - .height = 23, - }; - - constexpr PROGMEM unsigned char Extruder_Icon[] = { - 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, - 0x00, 0xC3, 0x00, - 0x00, 0x66, 0x00, - 0x00, 0x3C, 0x00, - 0x00, 0x3C, 0x00 - }; - - constexpr PROGMEM bitmap_info_t Bed_Heat_Icon_Info = { - .format = L1, - .linestride = 4, - .filter = BILINEAR, - .wrapx = BORDER, - .wrapy = BORDER, - .RAMG_offset = 8100, - .width = 32, - .height = 23, - }; - - constexpr PROGMEM unsigned char Bed_Heat_Icon[] = { - 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, - 0x00, 0x00, 0x00, 0x00, - 0xFF, 0xFF, 0xFF, 0xFF, - 0xFF, 0xFF, 0xFF, 0xFF, - 0xC0, 0x00, 0x00, 0x03, - 0xFF, 0xFF, 0xFF, 0xFF - }; - - constexpr PROGMEM bitmap_info_t Fan_Icon_Info = { - .format = L1, - .linestride = 4, - .filter = BILINEAR, - .wrapx = BORDER, - .wrapy = BORDER, - .RAMG_offset = 8300, - .width = 32, - .height = 32, - }; - - constexpr PROGMEM unsigned char Fan_Icon[] = { - 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, - 0xFF, 0xFF, 0xFF, 0xFF, - 0xFF, 0xFF, 0xFF, 0xFF - }; - - constexpr PROGMEM bitmap_info_t TD_Icon_Info = { - .format = L1, - .linestride = 7, - .filter = BILINEAR, - .wrapx = BORDER, - .wrapy = BORDER, - .RAMG_offset = 9000, - .width = 50, - .height = 20, - }; - - constexpr PROGMEM unsigned char TD_Icon[] = { - 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 - }; - - constexpr PROGMEM uint32_t UTF8_FONT_OFFSET = 10000; -}; // namespace Theme diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_about.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_about.cpp deleted file mode 100644 index 34b7427860ed..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_about.cpp +++ /dev/null @@ -1,125 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "lv_conf.h" -#include "draw_ui.h" -//#include "../lvgl/src/lv_objx/lv_imgbtn.h" -//#include "../lvgl/src/lv_objx/lv_img.h" -//#include "../lvgl/src/lv_core/lv_disp.h" -//#include "../lvgl/src/lv_core/lv_refr.h" - -#include "../../../../MarlinCore.h" -#include "../../../../module/temperature.h" - -extern lv_group_t * g; -static lv_obj_t * scr; -static lv_obj_t * fw_type, *board; //*fw_version; - -#define ID_A_RETURN 1 - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_A_RETURN: - if (event == LV_EVENT_CLICKED) { - // do nothing - } - else if (event == LV_EVENT_RELEASED) { - clear_cur_ui(); - draw_return_ui(); - } - break; - } -} - -void lv_draw_about(void) { - lv_obj_t *buttonBack, *label_Back; - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != ABOUT_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = ABOUT_UI; - } - disp_state = ABOUT_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, creat_title_text()); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - // Create an Image button - buttonBack = lv_imgbtn_create(scr, NULL); - - #if 1 - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_A_RETURN, NULL, 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_return.bin"); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_return.bin"); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonBack); - #endif - #endif - - lv_obj_set_pos(buttonBack, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - - // Create a label on the image button - label_Back = lv_label_create(buttonBack, NULL); - - if (gCfgItems.multiple_language != 0) { - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - - //fw_version = lv_label_create(scr, NULL); - //lv_obj_set_style(fw_version, &tft_style_label_rel); - //lv_label_set_text(fw_version, SHORT_BUILD_VERSION); - //lv_obj_align(fw_version, NULL, LV_ALIGN_CENTER, 0, -60); - - fw_type = lv_label_create(scr, NULL); - lv_obj_set_style(fw_type, &tft_style_label_rel); - lv_label_set_text(fw_type, "Firmware: Marlin " SHORT_BUILD_VERSION); - lv_obj_align(fw_type, NULL, LV_ALIGN_CENTER, 0, -20); - - board = lv_label_create(scr, NULL); - lv_obj_set_style(board, &tft_style_label_rel); - lv_label_set_text(board, "Board: " BOARD_INFO_NAME); - lv_obj_align(board, NULL, LV_ALIGN_CENTER, 0, -60); -} - -void lv_clear_about() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_acceleration_settings.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_acceleration_settings.cpp deleted file mode 100644 index a30c99dba07d..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_acceleration_settings.cpp +++ /dev/null @@ -1,449 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "lv_conf.h" -#include "draw_ui.h" - -#include "../../../../MarlinCore.h" -#include "../../../../module/planner.h" - -extern lv_group_t * g; -static lv_obj_t * scr; - -#define ID_ACCE_RETURN 1 -#define ID_ACCE_PRINT 2 -#define ID_ACCE_RETRA 3 -#define ID_ACCE_TRAVEL 4 -#define ID_ACCE_X 5 -#define ID_ACCE_Y 6 -#define ID_ACCE_Z 7 -#define ID_ACCE_E0 8 -#define ID_ACCE_E1 9 -#define ID_ACCE_UP 10 -#define ID_ACCE_DOWN 11 - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_ACCE_RETURN: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - uiCfg.para_ui_page = 0; - lv_clear_acceleration_settings(); - draw_return_ui(); - } - break; - case ID_ACCE_PRINT: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = PrintAcceleration; - lv_clear_acceleration_settings(); - lv_draw_number_key(); - } - break; - case ID_ACCE_RETRA: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = RetractAcceleration; - lv_clear_acceleration_settings(); - lv_draw_number_key(); - } - break; - case ID_ACCE_TRAVEL: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = TravelAcceleration; - lv_clear_acceleration_settings(); - lv_draw_number_key(); - } - break; - case ID_ACCE_X: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = XAcceleration; - lv_clear_acceleration_settings(); - lv_draw_number_key(); - } - break; - case ID_ACCE_Y: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = YAcceleration; - lv_clear_acceleration_settings(); - lv_draw_number_key(); - } - break; - case ID_ACCE_Z: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = ZAcceleration; - lv_clear_acceleration_settings(); - lv_draw_number_key(); - } - break; - case ID_ACCE_E0: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = E0Acceleration; - lv_clear_acceleration_settings(); - lv_draw_number_key(); - } - break; - case ID_ACCE_E1: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = E1Acceleration; - lv_clear_acceleration_settings(); - lv_draw_number_key(); - } - break; - case ID_ACCE_UP: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - uiCfg.para_ui_page = 0; - lv_clear_acceleration_settings(); - lv_draw_acceleration_settings(); - } - break; - case ID_ACCE_DOWN: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - uiCfg.para_ui_page = 1; - lv_clear_acceleration_settings(); - lv_draw_acceleration_settings(); - } - break; - } -} - -void lv_draw_acceleration_settings(void) { - lv_obj_t *buttonBack = NULL, *label_Back = NULL, *buttonTurnPage = NULL, *labelTurnPage = NULL; - lv_obj_t *labelPrintText = NULL, *buttonPrintValue = NULL, *labelPrintValue = NULL; - lv_obj_t *labelRetraText = NULL, *buttonRetraValue = NULL, *labelRetraValue = NULL; - lv_obj_t *labelTravelText = NULL, *buttonTravelValue = NULL, *labelTravelValue = NULL; - lv_obj_t *labelXText = NULL, *buttonXValue = NULL, *labelXValue = NULL; - lv_obj_t *labelYText = NULL, *buttonYValue = NULL, *labelYValue = NULL; - lv_obj_t *labelZText = NULL, *buttonZValue = NULL, *labelZValue = NULL; - lv_obj_t *labelE0Text = NULL, *buttonE0Value = NULL, *labelE0Value = NULL; - lv_obj_t *labelE1Text = NULL, *buttonE1Value = NULL, *labelE1Value = NULL; - lv_obj_t * line1 = NULL, * line2 = NULL, * line3 = NULL, * line4 = NULL; - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != ACCELERATION_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = ACCELERATION_UI; - } - disp_state = ACCELERATION_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, machine_menu.AccelerationConfTitle); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - if (uiCfg.para_ui_page != 1) { - - labelPrintText = lv_label_create(scr, NULL); - lv_obj_set_style(labelPrintText, &tft_style_label_rel); - lv_obj_set_pos(labelPrintText, PARA_UI_POS_X, PARA_UI_POS_Y + 10); - lv_label_set_text(labelPrintText, machine_menu.PrintAcceleration); - - buttonPrintValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonPrintValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y + PARA_UI_VALUE_V); - lv_obj_set_size(buttonPrintValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonPrintValue, event_handler, ID_ACCE_PRINT, NULL, 0); - lv_btn_set_style(buttonPrintValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonPrintValue, LV_BTN_STYLE_PR, &style_para_value); - labelPrintValue = lv_label_create(buttonPrintValue, NULL); - - line1 = lv_line_create(scr, NULL); - lv_ex_line(line1, line_points[0]); - - labelRetraText = lv_label_create(scr, NULL); - lv_obj_set_style(labelRetraText, &tft_style_label_rel); - lv_obj_set_pos(labelRetraText, PARA_UI_POS_X, PARA_UI_POS_Y * 2 + 10); - lv_label_set_text(labelRetraText, machine_menu.RetractAcceleration); - - buttonRetraValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonRetraValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 2 + PARA_UI_VALUE_V); - lv_obj_set_size(buttonRetraValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonRetraValue, event_handler, ID_ACCE_RETRA, NULL, 0); - lv_btn_set_style(buttonRetraValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonRetraValue, LV_BTN_STYLE_PR, &style_para_value); - labelRetraValue = lv_label_create(buttonRetraValue, NULL); - - line2 = lv_line_create(scr, NULL); - lv_ex_line(line2, line_points[1]); - - labelTravelText = lv_label_create(scr, NULL); - lv_obj_set_style(labelTravelText, &tft_style_label_rel); - lv_obj_set_pos(labelTravelText, PARA_UI_POS_X, PARA_UI_POS_Y * 3 + 10); - lv_label_set_text(labelTravelText, machine_menu.TravelAcceleration); - - buttonTravelValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonTravelValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 3 + PARA_UI_VALUE_V); - lv_obj_set_size(buttonTravelValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonTravelValue, event_handler, ID_ACCE_TRAVEL, NULL, 0); - lv_btn_set_style(buttonTravelValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonTravelValue, LV_BTN_STYLE_PR, &style_para_value); - labelTravelValue = lv_label_create(buttonTravelValue, NULL); - - line3 = lv_line_create(scr, NULL); - lv_ex_line(line3, line_points[2]); - - labelXText = lv_label_create(scr, NULL); - lv_obj_set_style(labelXText, &tft_style_label_rel); - lv_obj_set_pos(labelXText, PARA_UI_POS_X, PARA_UI_POS_Y * 4 + 10); - lv_label_set_text(labelXText, machine_menu.X_Acceleration); - - buttonXValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonXValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 4 + PARA_UI_VALUE_V); - lv_obj_set_size(buttonXValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonXValue, event_handler, ID_ACCE_X, NULL, 0); - lv_btn_set_style(buttonXValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonXValue, LV_BTN_STYLE_PR, &style_para_value); - labelXValue = lv_label_create(buttonXValue, NULL); - - line4 = lv_line_create(scr, NULL); - lv_ex_line(line4, line_points[3]); - - buttonTurnPage = lv_btn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_ACCE_DOWN, NULL, 0); - lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_REL, &style_para_back); - lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_PR, &style_para_back); - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonPrintValue); - lv_group_add_obj(g, buttonRetraValue); - lv_group_add_obj(g, buttonTravelValue); - lv_group_add_obj(g, buttonXValue); - lv_group_add_obj(g, buttonTurnPage); - } - #endif - } - else { - labelYText = lv_label_create(scr, NULL); - lv_obj_set_style(labelYText, &tft_style_label_rel); - lv_obj_set_pos(labelYText, PARA_UI_POS_X, PARA_UI_POS_Y + 10); - lv_label_set_text(labelYText, machine_menu.Y_Acceleration); - - buttonYValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonYValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y + PARA_UI_VALUE_V); - lv_obj_set_size(buttonYValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonYValue, event_handler, ID_ACCE_Y, NULL, 0); - lv_btn_set_style(buttonYValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonYValue, LV_BTN_STYLE_PR, &style_para_value); - labelYValue = lv_label_create(buttonYValue, NULL); - - line1 = lv_line_create(scr, NULL); - lv_ex_line(line1, line_points[0]); - - labelZText = lv_label_create(scr, NULL); - lv_obj_set_style(labelZText, &tft_style_label_rel); - lv_obj_set_pos(labelZText, PARA_UI_POS_X, PARA_UI_POS_Y * 2 + 10); - lv_label_set_text(labelZText, machine_menu.Z_Acceleration); - - buttonZValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonZValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 2 + PARA_UI_VALUE_V); - lv_obj_set_size(buttonZValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); lv_obj_set_event_cb_mks(buttonYValue, event_handler, ID_ACCE_Y, NULL, 0); - lv_obj_set_event_cb_mks(buttonZValue, event_handler, ID_ACCE_Z, NULL, 0); - lv_btn_set_style(buttonZValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonZValue, LV_BTN_STYLE_PR, &style_para_value); - labelZValue = lv_label_create(buttonZValue, NULL); - - - line2 = lv_line_create(scr, NULL); - lv_ex_line(line2, line_points[1]); - - labelE0Text = lv_label_create(scr, NULL); - lv_obj_set_style(labelE0Text, &tft_style_label_rel); - lv_obj_set_pos(labelE0Text, PARA_UI_POS_X, PARA_UI_POS_Y * 3 + 10); - lv_label_set_text(labelE0Text, machine_menu.E0_Acceleration); - - buttonE0Value = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonE0Value, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 3 + PARA_UI_VALUE_V); - lv_obj_set_size(buttonE0Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); lv_obj_set_event_cb_mks(buttonYValue, event_handler, ID_ACCE_Y, NULL, 0); - lv_obj_set_event_cb_mks(buttonE0Value, event_handler, ID_ACCE_E0, NULL, 0); - lv_btn_set_style(buttonE0Value, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonE0Value, LV_BTN_STYLE_PR, &style_para_value); - labelE0Value = lv_label_create(buttonE0Value, NULL); - - - line3 = lv_line_create(scr, NULL); - lv_ex_line(line3, line_points[2]); - - labelE1Text = lv_label_create(scr, NULL); - lv_obj_set_style(labelE1Text, &tft_style_label_rel); - lv_obj_set_pos(labelE1Text, PARA_UI_POS_X, PARA_UI_POS_Y * 4 + 10); - lv_label_set_text(labelE1Text, machine_menu.E1_Acceleration); - - buttonE1Value = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonE1Value, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 4 + PARA_UI_VALUE_V); - lv_obj_set_size(buttonE1Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); lv_obj_set_event_cb_mks(buttonYValue, event_handler, ID_ACCE_Y, NULL, 0); - lv_obj_set_event_cb_mks(buttonE1Value, event_handler, ID_ACCE_E1, NULL, 0); - lv_btn_set_style(buttonE1Value, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonE1Value, LV_BTN_STYLE_PR, &style_para_value); - labelE1Value = lv_label_create(buttonE1Value, NULL); - - - line4 = lv_line_create(scr, NULL); - lv_ex_line(line4, line_points[3]); - - buttonTurnPage = lv_btn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_ACCE_UP, NULL, 0); - //lv_imgbtn_set_src(buttonTurnPage, LV_BTN_STATE_REL, "F:/bmp_back70x40.bin"); - //lv_imgbtn_set_src(buttonTurnPage, LV_BTN_STATE_PR, "F:/bmp_back70x40.bin"); - //lv_imgbtn_set_style(buttonTurnPage, LV_BTN_STATE_PR, &tft_style_label_pre); - //lv_imgbtn_set_style(buttonTurnPage, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_REL, &style_para_back); - lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_PR, &style_para_back); - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonYValue); - lv_group_add_obj(g, buttonZValue); - lv_group_add_obj(g, buttonE0Value); - lv_group_add_obj(g, buttonE1Value); - lv_group_add_obj(g, buttonTurnPage); - } - #endif - } - - //lv_obj_set_pos(buttonTurnPage, PARA_UI_TURN_PAGE_POS_X, PARA_UI_TURN_PAGE_POS_Y); - //lv_btn_set_layout(buttonTurnPage, LV_LAYOUT_OFF); - //labelTurnPage = lv_label_create(buttonTurnPage, NULL); - lv_obj_set_pos(buttonTurnPage, PARA_UI_TURN_PAGE_POS_X, PARA_UI_TURN_PAGE_POS_Y); - lv_obj_set_size(buttonTurnPage, PARA_UI_BACK_BTN_X_SIZE, PARA_UI_BACK_BTN_Y_SIZE); - labelTurnPage = lv_label_create(buttonTurnPage, NULL); - - buttonBack = lv_btn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_ACCE_RETURN, NULL, 0); - //lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_back70x40.bin"); - //lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_back70x40.bin"); - //lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); - //lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_btn_set_style(buttonBack, LV_BTN_STYLE_REL, &style_para_back); - lv_btn_set_style(buttonBack, LV_BTN_STYLE_PR, &style_para_back); - lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); - lv_obj_set_size(buttonBack, PARA_UI_BACK_BTN_X_SIZE, PARA_UI_BACK_BTN_Y_SIZE); - label_Back = lv_label_create(buttonBack, NULL); - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonBack); - #endif - - //lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); - //lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - - if (gCfgItems.multiple_language != 0) { - if (uiCfg.para_ui_page != 1) { - - lv_label_set_text(labelTurnPage, machine_menu.next); - lv_obj_align(labelTurnPage, buttonTurnPage, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%.1f"), planner.settings.acceleration); - lv_label_set_text(labelPrintValue, public_buf_l); - lv_obj_align(labelPrintValue, buttonPrintValue, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%.1f"), planner.settings.retract_acceleration); - lv_label_set_text(labelRetraValue, public_buf_l); - lv_obj_align(labelRetraValue, buttonRetraValue, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%.1f"), planner.settings.travel_acceleration); - lv_label_set_text(labelTravelValue, public_buf_l); - lv_obj_align(labelTravelValue, buttonTravelValue, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%d"), (int)planner.settings.max_acceleration_mm_per_s2[X_AXIS]); - lv_label_set_text(labelXValue, public_buf_l); - lv_obj_align(labelXValue, buttonXValue, LV_ALIGN_CENTER, 0, 0); - } - else { - - lv_label_set_text(labelTurnPage, machine_menu.previous); - lv_obj_align(labelTurnPage, buttonTurnPage, LV_ALIGN_CENTER, 0, 0); - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%d"), (int)planner.settings.max_acceleration_mm_per_s2[Y_AXIS]); - lv_label_set_text(labelYValue, public_buf_l); - lv_obj_align(labelYValue, buttonYValue, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%d"), (int)planner.settings.max_acceleration_mm_per_s2[Z_AXIS]); - lv_label_set_text(labelZValue, public_buf_l); - lv_obj_align(labelZValue, buttonZValue, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%d"), (int)planner.settings.max_acceleration_mm_per_s2[E_AXIS]); - lv_label_set_text(labelE0Value, public_buf_l); - lv_obj_align(labelE0Value, buttonE0Value, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%d"), (int)planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(1)]); - lv_label_set_text(labelE1Value, public_buf_l); - lv_obj_align(labelE1Value, buttonE1Value, LV_ALIGN_CENTER, 0, 0); - } - - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_CENTER, 0, 0); - } -} - -void lv_clear_acceleration_settings() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_advance_settings.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_advance_settings.cpp deleted file mode 100644 index 5b1b24171697..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_advance_settings.cpp +++ /dev/null @@ -1,334 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "lv_conf.h" -#include "draw_ui.h" - -#include "../../../../MarlinCore.h" - -extern lv_group_t * g; -static lv_obj_t * scr; - -#define ID_ADVANCE_RETURN 1 -#define ID_PAUSE_POS 2 -#define ID_PAUSE_POS_ARROW 3 -#define ID_WIFI_PARA 4 -#define ID_WIFI_PARA_ARROW 5 -#define ID_FILAMENT_SETTINGS 6 -#define ID_FILAMENT_SETTINGS_ARROW 7 -#define ID_ENCODER_SETTINGS 8 -#define ID_ENCODER_SETTINGS_ARROW 9 - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_ADVANCE_RETURN: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_advance_settings(); - draw_return_ui(); - } - break; - case ID_PAUSE_POS: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_advance_settings(); - lv_draw_pause_position(); - } - break; - case ID_PAUSE_POS_ARROW: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_advance_settings(); - lv_draw_pause_position(); - } - break; - case ID_FILAMENT_SETTINGS: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_advance_settings(); - lv_draw_filament_settings(); - } - break; - case ID_FILAMENT_SETTINGS_ARROW: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_advance_settings(); - lv_draw_filament_settings(); - } - break; - #if ENABLED(USE_WIFI_FUNCTION) - case ID_WIFI_PARA: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_advance_settings(); - lv_draw_wifi_settings(); - } - break; - case ID_WIFI_PARA_ARROW: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_advance_settings(); - lv_draw_wifi_settings(); - } - break; - #endif - #if HAS_ROTARY_ENCODER - case ID_ENCODER_SETTINGS: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_advance_settings(); - lv_draw_encoder_settings(); - } - break; - case ID_ENCODER_SETTINGS_ARROW: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_advance_settings(); - lv_draw_encoder_settings(); - } - break; - #endif - } -} - -void lv_draw_advance_settings(void) { - lv_obj_t *buttonBack, *label_Back; - lv_obj_t *buttonPausePos, *labelPausePos, *buttonPausePosNarrow; - lv_obj_t *buttonFilamentSettings, *labelFilamentSettings, *buttonFilamentSettingsNarrow; - lv_obj_t * line1,* line2; - #if ENABLED(USE_WIFI_FUNCTION) - lv_obj_t *buttonWifiSet,*labelWifiSet,*buttonWifiSetNarrow; - #endif - #if HAS_ROTARY_ENCODER - lv_obj_t *buttonEcoder,*labelEcoder,*buttonEcoderNarrow; - #endif - - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != ADVANCED_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = ADVANCED_UI; - } - disp_state = ADVANCED_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, machine_menu.AdvancedConfTitle); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - buttonPausePos = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonPausePos, PARA_UI_POS_X, PARA_UI_POS_Y); - lv_obj_set_size(buttonPausePos, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); - //lv_obj_set_event_cb(buttonMachine, event_handler); - lv_obj_set_event_cb_mks(buttonPausePos, event_handler, ID_PAUSE_POS, NULL, 0); - lv_btn_set_style(buttonPausePos, LV_BTN_STYLE_REL, &tft_style_label_rel); - lv_btn_set_style(buttonPausePos, LV_BTN_STYLE_PR, &tft_style_label_pre); - lv_btn_set_layout(buttonPausePos, LV_LAYOUT_OFF); - labelPausePos = lv_label_create(buttonPausePos, NULL); - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonPausePos); - #endif - - buttonPausePosNarrow = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonPausePosNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y + PARA_UI_ARROW_V); - lv_obj_set_event_cb_mks(buttonPausePosNarrow, event_handler, ID_PAUSE_POS_ARROW, NULL, 0); - lv_imgbtn_set_src(buttonPausePosNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); - lv_imgbtn_set_src(buttonPausePosNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); - lv_imgbtn_set_style(buttonPausePosNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonPausePosNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_btn_set_layout(buttonPausePosNarrow, LV_LAYOUT_OFF); - - line1 = lv_line_create(lv_scr_act(), NULL); - lv_ex_line(line1, line_points[0]); - - buttonFilamentSettings = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonFilamentSettings, PARA_UI_POS_X, PARA_UI_POS_Y*2); - lv_obj_set_size(buttonFilamentSettings, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); - lv_obj_set_event_cb_mks(buttonFilamentSettings, event_handler, ID_FILAMENT_SETTINGS, NULL, 0); - lv_btn_set_style(buttonFilamentSettings, LV_BTN_STYLE_REL, &tft_style_label_rel); - lv_btn_set_style(buttonFilamentSettings, LV_BTN_STYLE_PR, &tft_style_label_pre); - lv_btn_set_layout(buttonFilamentSettings, LV_LAYOUT_OFF); - labelFilamentSettings = lv_label_create(buttonFilamentSettings, NULL); - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonFilamentSettings); - #endif - - buttonFilamentSettingsNarrow = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonFilamentSettingsNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y*2 + PARA_UI_ARROW_V); - lv_obj_set_event_cb_mks(buttonFilamentSettingsNarrow, event_handler, ID_FILAMENT_SETTINGS_ARROW, NULL, 0); - lv_imgbtn_set_src(buttonFilamentSettingsNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); - lv_imgbtn_set_src(buttonFilamentSettingsNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); - lv_imgbtn_set_style(buttonFilamentSettingsNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonFilamentSettingsNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_btn_set_layout(buttonFilamentSettingsNarrow, LV_LAYOUT_OFF); - - line2 = lv_line_create(lv_scr_act(), NULL); - lv_ex_line(line2, line_points[1]); - - #if ENABLED(USE_WIFI_FUNCTION) - - buttonWifiSet = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonWifiSet, PARA_UI_POS_X,PARA_UI_POS_Y*3); - lv_obj_set_size(buttonWifiSet, PARA_UI_SIZE_X,PARA_UI_SIZE_Y); - lv_obj_set_event_cb_mks(buttonWifiSet, event_handler,ID_WIFI_PARA,NULL,0); - lv_btn_set_style(buttonWifiSet, LV_BTN_STYLE_REL, &tft_style_label_rel); - lv_btn_set_style(buttonWifiSet, LV_BTN_STYLE_PR, &tft_style_label_pre); - lv_btn_set_layout(buttonWifiSet, LV_LAYOUT_OFF); - labelWifiSet = lv_label_create(buttonWifiSet, NULL); - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonWifiSet); - #endif - - buttonWifiSetNarrow = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonWifiSetNarrow,PARA_UI_POS_X+PARA_UI_SIZE_X,PARA_UI_POS_Y*3+PARA_UI_ARROW_V); - lv_obj_set_event_cb_mks(buttonWifiSetNarrow, event_handler,ID_WIFI_PARA_ARROW, NULL,0); - lv_imgbtn_set_src(buttonWifiSetNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); - lv_imgbtn_set_src(buttonWifiSetNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); - lv_imgbtn_set_style(buttonWifiSetNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonWifiSetNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_btn_set_layout(buttonWifiSetNarrow, LV_LAYOUT_OFF); - - lv_obj_t * line3 = lv_line_create(scr, NULL); - lv_ex_line(line3,line_points[2]); - - #if HAS_ROTARY_ENCODER - buttonEcoder = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonEcoder, PARA_UI_POS_X,PARA_UI_POS_Y*4); - lv_obj_set_size(buttonEcoder, PARA_UI_SIZE_X,PARA_UI_SIZE_Y); - lv_obj_set_event_cb_mks(buttonEcoder, event_handler,ID_ENCODER_SETTINGS,NULL,0); - lv_btn_set_style(buttonEcoder, LV_BTN_STYLE_REL, &tft_style_label_rel); - lv_btn_set_style(buttonEcoder, LV_BTN_STYLE_PR, &tft_style_label_pre); - lv_btn_set_layout(buttonEcoder, LV_LAYOUT_OFF); - labelEcoder = lv_label_create(buttonEcoder, NULL); - - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonEcoder); - - buttonEcoderNarrow = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonEcoderNarrow,PARA_UI_POS_X+PARA_UI_SIZE_X,PARA_UI_POS_Y*4+PARA_UI_ARROW_V); - lv_obj_set_event_cb_mks(buttonEcoderNarrow, event_handler,ID_ENCODER_SETTINGS_ARROW, NULL,0); - lv_imgbtn_set_src(buttonEcoderNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); - lv_imgbtn_set_src(buttonEcoderNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); - lv_imgbtn_set_style(buttonEcoderNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonEcoderNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_btn_set_layout(buttonEcoderNarrow, LV_LAYOUT_OFF); - - lv_obj_t * line4 = lv_line_create(scr, NULL); - lv_ex_line(line4,line_points[3]); - #endif - - #elif HAS_ROTARY_ENCODER - buttonEcoder = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonEcoder, PARA_UI_POS_X,PARA_UI_POS_Y*3); - lv_obj_set_size(buttonEcoder, PARA_UI_SIZE_X,PARA_UI_SIZE_Y); - lv_obj_set_event_cb_mks(buttonEcoder, event_handler,ID_ENCODER_SETTINGS,NULL,0); - lv_btn_set_style(buttonEcoder, LV_BTN_STYLE_REL, &tft_style_label_rel); - lv_btn_set_style(buttonEcoder, LV_BTN_STYLE_PR, &tft_style_label_pre); - lv_btn_set_layout(buttonEcoder, LV_LAYOUT_OFF); - labelEcoder = lv_label_create(buttonEcoder, NULL); - - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonEcoder); - - buttonEcoderNarrow = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonEcoderNarrow,PARA_UI_POS_X+PARA_UI_SIZE_X,PARA_UI_POS_Y*3+PARA_UI_ARROW_V); - lv_obj_set_event_cb_mks(buttonEcoderNarrow, event_handler,ID_ENCODER_SETTINGS_ARROW, NULL,0); - lv_imgbtn_set_src(buttonEcoderNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); - lv_imgbtn_set_src(buttonEcoderNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); - lv_imgbtn_set_style(buttonEcoderNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonEcoderNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_btn_set_layout(buttonEcoderNarrow, LV_LAYOUT_OFF); - - lv_obj_t * line3 = lv_line_create(scr, NULL); - lv_ex_line(line3,line_points[2]); - #endif - - buttonBack = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_ADVANCE_RETURN, NULL, 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_back70x40.bin"); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_back70x40.bin"); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonBack); - #endif - - lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); - lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - label_Back = lv_label_create(buttonBack, NULL); - - if (gCfgItems.multiple_language != 0) { - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_CENTER, 0, 0); - - lv_label_set_text(labelPausePos, machine_menu.PausePosition); - lv_obj_align(labelPausePos, buttonPausePos, LV_ALIGN_IN_LEFT_MID, 0, 0); - - lv_label_set_text(labelFilamentSettings, machine_menu.FilamentConf); - lv_obj_align(labelFilamentSettings, buttonFilamentSettings, LV_ALIGN_IN_LEFT_MID, 0, 0); - - #if ENABLED(USE_WIFI_FUNCTION) - lv_label_set_text(labelWifiSet, machine_menu.WifiSettings); - lv_obj_align(labelWifiSet, buttonWifiSet, LV_ALIGN_IN_LEFT_MID,0, 0); - #endif - #if HAS_ROTARY_ENCODER - lv_label_set_text(labelEcoder, machine_menu.EncoderSettings); - lv_obj_align(labelEcoder, buttonEcoder, LV_ALIGN_IN_LEFT_MID,0, 0); - #endif - } - -} - -void lv_clear_advance_settings() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_auto_level_offset_settings.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_auto_level_offset_settings.cpp deleted file mode 100644 index bb6b45aebe48..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_auto_level_offset_settings.cpp +++ /dev/null @@ -1,203 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if BOTH(HAS_TFT_LVGL_UI, HAS_BED_PROBE) - -#include "lv_conf.h" -#include "draw_ui.h" - -#include "../../../../MarlinCore.h" -#include "../../../../module/planner.h" -#include "../../../../module/probe.h" - -extern lv_group_t * g; -static lv_obj_t * scr; - -#define ID_OFFSET_RETURN 1 -#define ID_OFFSET_X 2 -#define ID_OFFSET_Y 3 -#define ID_OFFSET_Z 4 - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_OFFSET_RETURN: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_auto_level_offset_settings(); - draw_return_ui(); - } - break; - case ID_OFFSET_X: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = x_offset; - lv_clear_auto_level_offset_settings(); - lv_draw_number_key(); - } - break; - case ID_OFFSET_Y: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = y_offset; - lv_clear_auto_level_offset_settings(); - lv_draw_number_key(); - } - break; - case ID_OFFSET_Z: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = z_offset; - lv_clear_auto_level_offset_settings(); - lv_draw_number_key(); - } - break; - } -} - -void lv_draw_auto_level_offset_settings(void) { - lv_obj_t *buttonBack = NULL, *label_Back = NULL; - lv_obj_t *labelXText = NULL, *buttonXValue = NULL, *labelXValue = NULL; - lv_obj_t *labelYText = NULL, *buttonYValue = NULL, *labelYValue = NULL; - lv_obj_t *labelZText = NULL, *buttonZValue = NULL, *labelZValue = NULL; - lv_obj_t * line1 = NULL, * line2 = NULL, * line3 = NULL; - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != NOZZLE_PROBE_OFFSET_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = NOZZLE_PROBE_OFFSET_UI; - } - disp_state = NOZZLE_PROBE_OFFSET_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, machine_menu.OffsetConfTitle); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - labelXText = lv_label_create(scr, NULL); - lv_obj_set_style(labelXText, &tft_style_label_rel); - lv_obj_set_pos(labelXText, PARA_UI_POS_X, PARA_UI_POS_Y + 10); - lv_label_set_text(labelXText, machine_menu.Xoffset); - - buttonXValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonXValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y + PARA_UI_VALUE_V_2); - lv_obj_set_size(buttonXValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonXValue, event_handler, ID_OFFSET_X, NULL, 0); - lv_btn_set_style(buttonXValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonXValue, LV_BTN_STYLE_PR, &style_para_value); - labelXValue = lv_label_create(buttonXValue, NULL); - - line1 = lv_line_create(scr, NULL); - lv_ex_line(line1, line_points[0]); - - labelYText = lv_label_create(scr, NULL); - lv_obj_set_style(labelYText, &tft_style_label_rel); - lv_obj_set_pos(labelYText, PARA_UI_POS_X, PARA_UI_POS_Y * 2 + 10); - lv_label_set_text(labelYText, machine_menu.Yoffset); - - buttonYValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonYValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 2 + PARA_UI_VALUE_V_2); - lv_obj_set_size(buttonYValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonYValue, event_handler, ID_OFFSET_Y, NULL, 0); - lv_btn_set_style(buttonYValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonYValue, LV_BTN_STYLE_PR, &style_para_value); - labelYValue = lv_label_create(buttonYValue, NULL); - - line2 = lv_line_create(scr, NULL); - lv_ex_line(line2, line_points[1]); - - labelZText = lv_label_create(scr, NULL); - lv_obj_set_style(labelZText, &tft_style_label_rel); - lv_obj_set_pos(labelZText, PARA_UI_POS_X, PARA_UI_POS_Y * 3 + 10); - lv_label_set_text(labelZText, machine_menu.Zoffset); - - buttonZValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonZValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 3 + PARA_UI_VALUE_V_2); - lv_obj_set_size(buttonZValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonZValue, event_handler, ID_OFFSET_Z, NULL, 0); - lv_btn_set_style(buttonZValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonZValue, LV_BTN_STYLE_PR, &style_para_value); - labelZValue = lv_label_create(buttonZValue, NULL); - - line3 = lv_line_create(scr, NULL); - lv_ex_line(line3, line_points[2]); - - buttonBack = lv_btn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_OFFSET_RETURN, NULL, 0); - lv_btn_set_style(buttonBack, LV_BTN_STYLE_REL, &style_para_back); - lv_btn_set_style(buttonBack, LV_BTN_STYLE_PR, &style_para_back); - lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); - lv_obj_set_size(buttonBack, PARA_UI_BACK_BTN_X_SIZE, PARA_UI_BACK_BTN_Y_SIZE); - label_Back = lv_label_create(buttonBack, NULL); - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonXValue); - lv_group_add_obj(g, buttonYValue); - lv_group_add_obj(g, buttonZValue); - lv_group_add_obj(g, buttonBack); - } - #endif - - if (gCfgItems.multiple_language != 0) { - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%.1f"), TERN(HAS_PROBE_XY_OFFSET, probe.offset.x, 0)); - lv_label_set_text(labelXValue, public_buf_l); - lv_obj_align(labelXValue, buttonXValue, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%.1f"), TERN(HAS_PROBE_XY_OFFSET, probe.offset.y, 0)); - lv_label_set_text(labelYValue, public_buf_l); - lv_obj_align(labelYValue, buttonYValue, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%.1f"), probe.offset.z); - lv_label_set_text(labelZValue, public_buf_l); - lv_obj_align(labelZValue, buttonZValue, LV_ALIGN_CENTER, 0, 0); - - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_CENTER, 0, 0); - } -} - -void lv_clear_auto_level_offset_settings() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI && HAS_BED_PROBE diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_baby_stepping.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_baby_stepping.cpp deleted file mode 100644 index 70564c036c64..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_baby_stepping.cpp +++ /dev/null @@ -1,352 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "lv_conf.h" -#include "draw_ui.h" - -#include "../../../../MarlinCore.h" -#include "../../../../gcode/queue.h" -#include "../../../../gcode/gcode.h" - -#if HAS_BED_PROBE - #include "../../../../module/probe.h" -#endif - -extern lv_group_t * g; -static lv_obj_t * scr; - -static lv_obj_t *labelV, *buttonV, * zOffsetText; - -#define ID_BABY_STEP_X_P 1 -#define ID_BABY_STEP_X_N 2 -#define ID_BABY_STEP_Y_P 3 -#define ID_BABY_STEP_Y_N 4 -#define ID_BABY_STEP_Z_P 5 -#define ID_BABY_STEP_Z_N 6 -#define ID_BABY_STEP_DIST 7 -#define ID_BABY_STEP_RETURN 8 - -static float babystep_dist=0.01; -static uint8_t has_adjust_z = 0; - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - char baby_buf[30]={0}; - switch (obj->mks_obj_id) { - case ID_BABY_STEP_X_P: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - ZERO(baby_buf); - sprintf_P(baby_buf, PSTR("M290 X%.3f"),babystep_dist); - gcode.process_subcommands_now_P(PSTR(baby_buf)); - has_adjust_z = 1; - } - break; - case ID_BABY_STEP_X_N: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - ZERO(baby_buf); - sprintf_P(baby_buf, PSTR("M290 X%.3f"),((float)0 - babystep_dist)); - gcode.process_subcommands_now_P(PSTR(baby_buf)); - has_adjust_z = 1; - } - break; - case ID_BABY_STEP_Y_P: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - ZERO(baby_buf); - sprintf_P(baby_buf, PSTR("M290 Y%.3f"), babystep_dist); - gcode.process_subcommands_now_P(PSTR(baby_buf)); - has_adjust_z = 1; - } - break; - case ID_BABY_STEP_Y_N: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - ZERO(baby_buf); - sprintf_P(baby_buf, PSTR("M290 Y%.3f"),((float)0 - babystep_dist)); - gcode.process_subcommands_now_P(PSTR(baby_buf)); - has_adjust_z = 1; - } - break; - case ID_BABY_STEP_Z_P: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - ZERO(baby_buf); - sprintf_P(baby_buf, PSTR("M290 Z%.3f"), babystep_dist); - gcode.process_subcommands_now_P(PSTR(baby_buf)); - has_adjust_z = 1; - } - break; - case ID_BABY_STEP_Z_N: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - ZERO(baby_buf); - sprintf_P(baby_buf, PSTR("M290 Z%.3f"),((float)0 - babystep_dist)); - gcode.process_subcommands_now_P(PSTR(baby_buf)); - has_adjust_z = 1; - } - break; - case ID_BABY_STEP_DIST: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - if (abs((int)(100 * babystep_dist)) == 1) - babystep_dist = 0.05; - else if (abs((int)(100 * babystep_dist)) == 5) - babystep_dist = 0.1; - else - babystep_dist = 0.01; - disp_baby_step_dist(); - } - - break; - case ID_BABY_STEP_RETURN: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - if (has_adjust_z == 1) { - gcode.process_subcommands_now_P(PSTR("M500")); - has_adjust_z = 0; - } - clear_cur_ui(); - draw_return_ui(); - } - break; - } -} - -void lv_draw_baby_stepping(void) { - lv_obj_t *buttonXI, *buttonXD, *buttonYI, *buttonYD, *buttonZI, *buttonZD, *buttonBack; - - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != BABY_STEP_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = BABY_STEP_UI; - } - disp_state = BABY_STEP_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, creat_title_text()); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - // Create an Image button - buttonXI = lv_imgbtn_create(scr, NULL); - buttonXD = lv_imgbtn_create(scr, NULL); - buttonYI = lv_imgbtn_create(scr, NULL); - buttonYD = lv_imgbtn_create(scr, NULL); - buttonZI = lv_imgbtn_create(scr, NULL); - buttonZD = lv_imgbtn_create(scr, NULL); - buttonV = lv_imgbtn_create(scr, NULL); - buttonBack = lv_imgbtn_create(scr, NULL); - - lv_obj_set_event_cb_mks(buttonXI, event_handler, ID_BABY_STEP_X_P, NULL, 0); - lv_imgbtn_set_src(buttonXI, LV_BTN_STATE_REL, "F:/bmp_xAdd.bin"); - lv_imgbtn_set_src(buttonXI, LV_BTN_STATE_PR, "F:/bmp_xAdd.bin"); - lv_imgbtn_set_style(buttonXI, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonXI, LV_BTN_STATE_REL, &tft_style_label_rel); - - #if 1 - lv_obj_set_event_cb_mks(buttonXD, event_handler, ID_BABY_STEP_X_N, NULL, 0); - lv_imgbtn_set_src(buttonXD, LV_BTN_STATE_REL, "F:/bmp_xDec.bin"); - lv_imgbtn_set_src(buttonXD, LV_BTN_STATE_PR, "F:/bmp_xDec.bin"); - lv_imgbtn_set_style(buttonXD, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonXD, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonYI, event_handler, ID_BABY_STEP_Y_P, NULL, 0); - lv_imgbtn_set_src(buttonYI, LV_BTN_STATE_REL, "F:/bmp_yAdd.bin"); - lv_imgbtn_set_src(buttonYI, LV_BTN_STATE_PR, "F:/bmp_yAdd.bin"); - lv_imgbtn_set_style(buttonYI, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonYI, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonYD, event_handler, ID_BABY_STEP_Y_N, NULL, 0); - lv_imgbtn_set_src(buttonYD, LV_BTN_STATE_REL, "F:/bmp_yDec.bin"); - lv_imgbtn_set_src(buttonYD, LV_BTN_STATE_PR, "F:/bmp_yDec.bin"); - lv_imgbtn_set_style(buttonYD, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonYD, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonZI, event_handler, ID_BABY_STEP_Z_P, NULL, 0); - lv_imgbtn_set_src(buttonZI, LV_BTN_STATE_REL, "F:/bmp_zAdd.bin"); - lv_imgbtn_set_src(buttonZI, LV_BTN_STATE_PR, "F:/bmp_zAdd.bin"); - lv_imgbtn_set_style(buttonZI, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonZI, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonZD, event_handler, ID_BABY_STEP_Z_N, NULL, 0); - lv_imgbtn_set_src(buttonZD, LV_BTN_STATE_REL, "F:/bmp_zDec.bin"); - lv_imgbtn_set_src(buttonZD, LV_BTN_STATE_PR, "F:/bmp_zDec.bin"); - lv_imgbtn_set_style(buttonZD, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonZD, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonV, event_handler, ID_BABY_STEP_DIST, NULL, 0); - lv_imgbtn_set_style(buttonV, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonV, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_BABY_STEP_RETURN, NULL, 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_return.bin"); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_return.bin"); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); - - #endif // if 1 - lv_obj_set_pos(buttonXI, INTERVAL_V, titleHeight); - lv_obj_set_pos(buttonYI, BTN_X_PIXEL + INTERVAL_V * 2, titleHeight); - lv_obj_set_pos(buttonZI, BTN_X_PIXEL * 2 + INTERVAL_V * 3, titleHeight); - lv_obj_set_pos(buttonV, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight); - lv_obj_set_pos(buttonXD, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - lv_obj_set_pos(buttonYD, BTN_X_PIXEL + INTERVAL_V * 2, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - lv_obj_set_pos(buttonZD, BTN_X_PIXEL * 2 + INTERVAL_V * 3, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - lv_obj_set_pos(buttonBack, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - - // Create labels on the image buttons - lv_btn_set_layout(buttonXI, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonXD, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonYI, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonYD, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonZI, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonZD, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonV, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - - lv_obj_t *labelXI = lv_label_create(buttonXI, NULL); - lv_obj_t *labelXD = lv_label_create(buttonXD, NULL); - lv_obj_t *labelYI = lv_label_create(buttonYI, NULL); - lv_obj_t *labelYD = lv_label_create(buttonYD, NULL); - lv_obj_t *labelZI = lv_label_create(buttonZI, NULL); - lv_obj_t *labelZD = lv_label_create(buttonZD, NULL); - labelV = lv_label_create(buttonV, NULL); - lv_obj_t *label_Back = lv_label_create(buttonBack, NULL); - - if (gCfgItems.multiple_language != 0) { - lv_label_set_text(labelXI, move_menu.x_add); - lv_obj_align(labelXI, buttonXI, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(labelXD, move_menu.x_dec); - lv_obj_align(labelXD, buttonXD, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(labelYI, move_menu.y_add); - lv_obj_align(labelYI, buttonYI, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(labelYD, move_menu.y_dec); - lv_obj_align(labelYD, buttonYD, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(labelZI, move_menu.z_add); - lv_obj_align(labelZI, buttonZI, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(labelZD, move_menu.z_dec); - lv_obj_align(labelZD, buttonZD, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonXI); - lv_group_add_obj(g, buttonXD); - lv_group_add_obj(g, buttonYI); - lv_group_add_obj(g, buttonYD); - lv_group_add_obj(g, buttonZI); - lv_group_add_obj(g, buttonZD); - lv_group_add_obj(g, buttonV); - lv_group_add_obj(g, buttonBack); - } - #endif - - disp_baby_step_dist(); - - zOffsetText = lv_label_create(scr, NULL); - lv_obj_set_style(zOffsetText, &tft_style_label_rel); - lv_obj_set_pos(zOffsetText, 290, TITLE_YPOS); - disp_z_offset_value(); -} - -void disp_baby_step_dist() { - // char buf[30] = {0}; - - if ((int)(100 * babystep_dist) == 1) { - lv_imgbtn_set_src(buttonV, LV_BTN_STATE_REL, "F:/bmp_baby_move0_01.bin"); - lv_imgbtn_set_src(buttonV, LV_BTN_STATE_PR, "F:/bmp_baby_move0_01.bin"); - } - else if ((int)(100 * babystep_dist) == 5) { - lv_imgbtn_set_src(buttonV, LV_BTN_STATE_REL, "F:/bmp_baby_move0_05.bin"); - lv_imgbtn_set_src(buttonV, LV_BTN_STATE_PR, "F:/bmp_baby_move0_05.bin"); - } - else if ((int)(100 * babystep_dist) == 10) { - lv_imgbtn_set_src(buttonV, LV_BTN_STATE_REL, "F:/bmp_baby_move0_1.bin"); - lv_imgbtn_set_src(buttonV, LV_BTN_STATE_PR, "F:/bmp_baby_move0_1.bin"); - } - if (gCfgItems.multiple_language != 0) { - if ((int)(100 * babystep_dist) == 1) { - lv_label_set_text(labelV, move_menu.step_001mm); - lv_obj_align(labelV, buttonV, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - else if ((int)(100 * babystep_dist) == 5) { - lv_label_set_text(labelV, move_menu.step_005mm); - lv_obj_align(labelV, buttonV, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - else if ((int)(100 * babystep_dist) == 10) { - lv_label_set_text(labelV, move_menu.step_01mm); - lv_obj_align(labelV, buttonV, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - } -} - -void disp_z_offset_value() { - char buf[20]; - - ZERO(buf); - sprintf_P(buf, PSTR("offset Z: %.3f"), (double)TERN(HAS_BED_PROBE, probe.offset.z, 0)); - lv_label_set_text(zOffsetText, buf); -} - -void lv_clear_baby_stepping() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_change_speed.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_change_speed.cpp deleted file mode 100644 index c60000afaee3..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_change_speed.cpp +++ /dev/null @@ -1,356 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "lv_conf.h" -#include "draw_ui.h" -//#include "../lvgl/src/lv_objx/lv_imgbtn.h" -//#include "../lvgl/src/lv_objx/lv_img.h" -//#include "../lvgl/src/lv_core/lv_disp.h" -//#include "../lvgl/src/lv_core/lv_refr.h" - -#include "../../../../MarlinCore.h" -#include "../../../../module/temperature.h" -#include "../../../../module/planner.h" - -extern lv_group_t * g; -static lv_obj_t * scr; -static lv_obj_t *labelStep, *buttonStep, *buttonMov, *buttonExt; -static lv_obj_t *labelMov, *labelExt; -static lv_obj_t * printSpeedText; - -#define ID_C_ADD 1 -#define ID_C_DEC 2 -#define ID_C_MOVE 3 -#define ID_C_EXT 4 -#define ID_C_STEP 5 -#define ID_C_RETURN 6 - -static uint8_t speedType; - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_C_ADD: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - if (speedType == 0) { - if (feedrate_percentage < MAX_EXT_SPEED_PERCENT - uiCfg.stepPrintSpeed) - feedrate_percentage += uiCfg.stepPrintSpeed; - else - feedrate_percentage = MAX_EXT_SPEED_PERCENT; - } - else if (speedType == 1) { - if (planner.flow_percentage[0] < MAX_EXT_SPEED_PERCENT - uiCfg.stepPrintSpeed) - planner.flow_percentage[0] += uiCfg.stepPrintSpeed; - else - planner.flow_percentage[0] = MAX_EXT_SPEED_PERCENT; - //planner.e_factor[0]= planner.flow_percentage[0]*0.01; - //planner.flow_percentage[1] = planner.flow_percentage[0]; - //planner.e_factor[1]= planner.flow_percentage[1]*0.01; - planner.refresh_e_factor(0); - #if HAS_MULTI_EXTRUDER - planner.flow_percentage[1] = planner.flow_percentage[0]; - planner.refresh_e_factor(1); - #endif - } - disp_print_speed(); - } - break; - case ID_C_DEC: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - if (speedType == 0) { - if (feedrate_percentage > MIN_EXT_SPEED_PERCENT + uiCfg.stepPrintSpeed) - feedrate_percentage -= uiCfg.stepPrintSpeed; - else - feedrate_percentage = MIN_EXT_SPEED_PERCENT; - } - else if (speedType == 1) { - if (planner.flow_percentage[0] > MIN_EXT_SPEED_PERCENT + uiCfg.stepPrintSpeed) - planner.flow_percentage[0] -= uiCfg.stepPrintSpeed; - else - planner.flow_percentage[0] = MIN_EXT_SPEED_PERCENT; - //planner.e_factor[0]= planner.flow_percentage[0] * 0.01; - //planner.flow_percentage[1] = planner.flow_percentage[0]; - //planner.e_factor[1]= planner.flow_percentage[1] * 0.01; - planner.refresh_e_factor(0); - #if HAS_MULTI_EXTRUDER - planner.flow_percentage[1] = planner.flow_percentage[0]; - planner.refresh_e_factor(1); - #endif - } - disp_print_speed(); - } - break; - case ID_C_MOVE: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - speedType = 0; - disp_speed_type(); - disp_print_speed(); - } - break; - case ID_C_EXT: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - speedType = 1; - disp_speed_type(); - disp_print_speed(); - } - break; - case ID_C_STEP: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - if (uiCfg.stepPrintSpeed == 1) - uiCfg.stepPrintSpeed = 5; - else if (uiCfg.stepPrintSpeed == 5) - uiCfg.stepPrintSpeed = 10; - else - uiCfg.stepPrintSpeed = 1; - disp_speed_step(); - } - break; - case ID_C_RETURN: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - clear_cur_ui(); - draw_return_ui(); - } - break; - } -} - -void lv_draw_change_speed(void) { - lv_obj_t *buttonAdd, *buttonDec; - lv_obj_t *buttonBack; - - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != CHANGE_SPEED_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = CHANGE_SPEED_UI; - } - disp_state = CHANGE_SPEED_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, creat_title_text()); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - - // Create an Image button - buttonAdd = lv_imgbtn_create(scr, NULL); - buttonDec = lv_imgbtn_create(scr, NULL); - buttonMov = lv_imgbtn_create(scr, NULL); - buttonExt = lv_imgbtn_create(scr, NULL); - buttonStep = lv_imgbtn_create(scr, NULL); - buttonBack = lv_imgbtn_create(scr, NULL); - - lv_obj_set_event_cb_mks(buttonAdd, event_handler, ID_C_ADD, NULL, 0); - lv_imgbtn_set_src(buttonAdd, LV_BTN_STATE_REL, "F:/bmp_Add.bin"); - lv_imgbtn_set_src(buttonAdd, LV_BTN_STATE_PR, "F:/bmp_Add.bin"); - lv_imgbtn_set_style(buttonAdd, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonAdd, LV_BTN_STATE_REL, &tft_style_label_rel); - - #if 1 - lv_obj_set_event_cb_mks(buttonDec, event_handler, ID_C_DEC, NULL, 0); - lv_imgbtn_set_src(buttonDec, LV_BTN_STATE_REL, "F:/bmp_Dec.bin"); - lv_imgbtn_set_src(buttonDec, LV_BTN_STATE_PR, "F:/bmp_Dec.bin"); - lv_imgbtn_set_style(buttonDec, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonDec, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonMov, event_handler, ID_C_MOVE, NULL, 0); - lv_imgbtn_set_style(buttonMov, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonMov, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonExt, event_handler, ID_C_EXT, NULL, 0); - lv_imgbtn_set_style(buttonExt, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonExt, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonStep, event_handler, ID_C_STEP, NULL, 0); - lv_imgbtn_set_style(buttonStep, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonStep, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_C_RETURN, NULL, 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_return.bin"); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_return.bin"); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); - #endif - - lv_obj_set_pos(buttonAdd, INTERVAL_V, titleHeight); - lv_obj_set_pos(buttonDec, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight); - lv_obj_set_pos(buttonMov, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - lv_obj_set_pos(buttonExt, BTN_X_PIXEL + INTERVAL_V * 2, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - lv_obj_set_pos(buttonStep, BTN_X_PIXEL * 2 + INTERVAL_V * 3, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - lv_obj_set_pos(buttonBack, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - - // Create labels on the image buttons - lv_btn_set_layout(buttonAdd, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonDec, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonMov, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonExt, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonStep, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - - lv_obj_t *labelAdd = lv_label_create(buttonAdd, NULL); - lv_obj_t *labelDec = lv_label_create(buttonDec, NULL); - labelMov = lv_label_create(buttonMov, NULL); - labelExt = lv_label_create(buttonExt, NULL); - labelStep = lv_label_create(buttonStep, NULL); - lv_obj_t *label_Back = lv_label_create(buttonBack, NULL); - - if (gCfgItems.multiple_language != 0) { - lv_label_set_text(labelAdd, speed_menu.add); - lv_obj_align(labelAdd, buttonAdd, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(labelDec, speed_menu.dec); - lv_obj_align(labelDec, buttonDec, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonAdd); - lv_group_add_obj(g, buttonDec); - lv_group_add_obj(g, buttonMov); - lv_group_add_obj(g, buttonExt); - lv_group_add_obj(g, buttonStep); - lv_group_add_obj(g, buttonBack); - } - #endif - - disp_speed_type(); - disp_speed_step(); - - printSpeedText = lv_label_create(scr, NULL); - lv_obj_set_style(printSpeedText, &tft_style_label_rel); - disp_print_speed(); -} - -void disp_speed_step() { - if (uiCfg.stepPrintSpeed == 1) { - lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_REL, "F:/bmp_step1_percent.bin"); - lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_PR, "F:/bmp_step1_percent.bin"); - } - else if (uiCfg.stepPrintSpeed == 5) { - lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_REL, "F:/bmp_step5_percent.bin"); - lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_PR, "F:/bmp_step5_percent.bin"); - } - else if (uiCfg.stepPrintSpeed == 10) { - lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_REL, "F:/bmp_step10_percent.bin"); - lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_PR, "F:/bmp_step10_percent.bin"); - } - if (gCfgItems.multiple_language != 0) { - if (uiCfg.stepPrintSpeed == 1) { - lv_label_set_text(labelStep, speed_menu.step_1percent); - lv_obj_align(labelStep, buttonStep, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - else if (uiCfg.stepPrintSpeed == 5) { - lv_label_set_text(labelStep, speed_menu.step_5percent); - lv_obj_align(labelStep, buttonStep, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - else if (uiCfg.stepPrintSpeed == 10) { - lv_label_set_text(labelStep, speed_menu.step_10percent); - lv_obj_align(labelStep, buttonStep, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - } -} - -void disp_print_speed() { - char buf[30] = { 0 }; - - public_buf_l[0] = '\0'; - - if (speedType == 0) { // move - strcat(public_buf_l, speed_menu.move_speed); - strcat_P(public_buf_l, PSTR(": ")); - sprintf_P(buf, PSTR("%d%%"), feedrate_percentage); - strcat(public_buf_l, buf); - } - else if (speedType == 1) { // e1 - strcat(public_buf_l, speed_menu.extrude_speed); - strcat_P(public_buf_l, PSTR(": ")); - sprintf_P(buf, PSTR("%d%%"), planner.flow_percentage[0]); - strcat(public_buf_l, buf); - } - lv_label_set_text(printSpeedText, public_buf_l); - lv_obj_align(printSpeedText, NULL, LV_ALIGN_CENTER, 0, -65); -} - -void disp_speed_type() { - switch (speedType) { - case 1: - lv_imgbtn_set_src(buttonMov, LV_BTN_STATE_REL, "F:/bmp_mov_changeSpeed.bin"); - lv_imgbtn_set_src(buttonMov, LV_BTN_STATE_PR, "F:/bmp_mov_changeSpeed.bin"); - lv_imgbtn_set_src(buttonExt, LV_BTN_STATE_REL, "F:/bmp_extruct_sel.bin"); - lv_imgbtn_set_src(buttonExt, LV_BTN_STATE_PR, "F:/bmp_extruct_sel.bin"); - break; - - default: - lv_imgbtn_set_src(buttonMov, LV_BTN_STATE_REL, "F:/bmp_mov_sel.bin"); - lv_imgbtn_set_src(buttonMov, LV_BTN_STATE_PR, "F:/bmp_mov_sel.bin"); - lv_imgbtn_set_src(buttonExt, LV_BTN_STATE_REL, "F:/bmp_speed_extruct.bin"); - lv_imgbtn_set_src(buttonExt, LV_BTN_STATE_PR, "F:/bmp_speed_extruct.bin"); - break; - } - lv_obj_refresh_ext_draw_pad(buttonExt); - lv_obj_refresh_ext_draw_pad(buttonMov); - - if (gCfgItems.multiple_language != 0) { - lv_label_set_text(labelMov, speed_menu.move); - lv_obj_align(labelMov, buttonMov, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(labelExt, speed_menu.extrude); - lv_obj_align(labelExt, buttonExt, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } -} - -void lv_clear_change_speed() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_dialog.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_dialog.cpp deleted file mode 100644 index c8483230103c..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_dialog.cpp +++ /dev/null @@ -1,703 +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 . - * - */ - -/** - * draw_dialog.cpp - */ - -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "lv_conf.h" -#include "draw_ui.h" - -//#include "../lvgl/src/lv_objx/lv_imgbtn.h" -//#include "../lvgl/src/lv_objx/lv_img.h" -//#include "../lvgl/src/lv_core/lv_disp.h" -//#include "../lvgl/src/lv_core/lv_refr.h" - -#include "../../../../MarlinCore.h" -#include "../../../../sd/cardreader.h" -#include "../../../../gcode/queue.h" -#include "../../../../module/temperature.h" -#include "../../../../module/planner.h" -#include "../../../../gcode/gcode.h" - -#if ENABLED(POWER_LOSS_RECOVERY) - #include "../../../../feature/powerloss.h" -#endif - -#if ENABLED(PARK_HEAD_ON_PAUSE) - #include "../../../../feature/pause.h" -#endif -#include "../../../../gcode/gcode.h" - -extern lv_group_t * g; -static lv_obj_t * scr; -static lv_obj_t * tempText1; -static lv_obj_t * filament_bar; - -extern uint8_t sel_id; -extern uint8_t once_flag; -extern uint8_t gcode_preview_over; -extern int upload_result ; -extern uint32_t upload_time; -extern uint32_t upload_size; -extern uint8_t temperature_change_frequency; - -static void btn_ok_event_cb(lv_obj_t * btn, lv_event_t event) { - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - if (uiCfg.dialogType == DIALOG_TYPE_PRINT_FILE) { - #if HAS_GCODE_PREVIEW - preview_gcode_prehandle(list_file.file_name[sel_id]); - #endif - reset_print_time(); - start_print_time(); - - uiCfg.print_state = WORKING; - lv_clear_dialog(); - lv_draw_printing(); - - #if ENABLED(SDSUPPORT) - if (gcode_preview_over != 1) { - char *cur_name; - cur_name = strrchr(list_file.file_name[sel_id], '/'); - - SdFile file, *curDir; - card.endFilePrint(); - const char * const fname = card.diveToFile(true, 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()) { - feedrate_percentage = 100; - //saved_feedrate_percentage = feedrate_percentage; - planner.flow_percentage[0] = 100; - planner.e_factor[0] = planner.flow_percentage[0] * 0.01f; - #if HAS_MULTI_EXTRUDER - planner.flow_percentage[1] = 100; - planner.e_factor[1] = planner.flow_percentage[1] * 0.01f; - #endif - card.startFileprint(); - #if ENABLED(POWER_LOSS_RECOVERY) - recovery.prepare(); - #endif - once_flag = 0; - } - } - #endif - } - else if (uiCfg.dialogType == DIALOG_TYPE_STOP) { - wait_for_heatup = false; - stop_print_time(); - lv_clear_dialog(); - lv_draw_ready_print(); - - #if ENABLED(SDSUPPORT) - //card.endFilePrint(); - //wait_for_heatup = false; - uiCfg.print_state = IDLE; - card.flag.abort_sd_printing = true; - //queue.clear(); - //quickstop_stepper(); - //print_job_timer.stop(); - //thermalManager.disable_all_heaters(); - - //#if ENABLED(POWER_LOSS_RECOVERY) - // recovery.purge(); - //#endif - //queue.enqueue_now_P(PSTR("G91\nG1 Z10\nG90\nG28 X0 Y0")); - //queue.inject_P(PSTR("G91\nG1 Z10\nG90\nG28 X0 Y0\nM84\nM107")); - #endif - } - else if (uiCfg.dialogType == DIALOG_TYPE_FINISH_PRINT) { - clear_cur_ui(); - lv_draw_ready_print(); - } - #if ENABLED(ADVANCED_PAUSE_FEATURE) - else if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_WAITING - || uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_INSERT - || uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_HEAT - ) { - wait_for_user = false; - } - else if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_OPTION) { - pause_menu_response = PAUSE_RESPONSE_EXTRUDE_MORE; - } - else if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_RESUME) { - clear_cur_ui(); - draw_return_ui(); - } - #endif - else if (uiCfg.dialogType == DIALOG_STORE_EEPROM_TIPS) { - gcode.process_subcommands_now_P(PSTR("M500")); - clear_cur_ui(); - draw_return_ui(); - } - else if (uiCfg.dialogType == DIALOG_READ_EEPROM_TIPS) { - gcode.process_subcommands_now_P(PSTR("M501")); - clear_cur_ui(); - draw_return_ui(); - } - else if (uiCfg.dialogType == DIALOG_REVERT_EEPROM_TIPS) { - gcode.process_subcommands_now_P(PSTR("M502")); - clear_cur_ui(); - draw_return_ui(); - } - else if (uiCfg.dialogType == DIALOG_WIFI_CONFIG_TIPS) { - uiCfg.configWifi = 1; - clear_cur_ui(); - draw_return_ui(); - } - else if (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_HEAT_LOAD_COMPLETED) { - uiCfg.filament_heat_completed_load = 1; - } - else if (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_HEAT_UNLOAD_COMPLETED) { - uiCfg.filament_heat_completed_unload = 1; - } - else if (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_LOAD_COMPLETED - || uiCfg.dialogType == DIALOG_TYPE_FILAMENT_UNLOAD_COMPLETED - ) { - clear_cur_ui(); - draw_return_ui(); - } - } -} - -static void btn_cancel_event_cb(lv_obj_t * btn, lv_event_t event) { - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_OPTION) { - #if ENABLED(ADVANCED_PAUSE_FEATURE) - pause_menu_response = PAUSE_RESPONSE_RESUME_PRINT; - #endif - } - else if ((uiCfg.dialogType == DIALOG_TYPE_FILAMENT_LOAD_HEAT) - || (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_UNLOAD_HEAT) - || (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_HEAT_LOAD_COMPLETED) - || (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_HEAT_UNLOAD_COMPLETED) - ) { - thermalManager.temp_hotend[uiCfg.curSprayerChoose].target= uiCfg.desireSprayerTempBak; - clear_cur_ui(); - draw_return_ui(); - } - else if ((uiCfg.dialogType == DIALOG_TYPE_FILAMENT_LOADING) - || (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_UNLOADING) - ) { - queue.enqueue_one_P(PSTR("M410")); - uiCfg.filament_rate = 0; - uiCfg.filament_loading_completed = 0; - uiCfg.filament_unloading_completed = 0; - uiCfg.filament_loading_time_flg = 0; - uiCfg.filament_loading_time_cnt = 0; - uiCfg.filament_unloading_time_flg = 0; - uiCfg.filament_unloading_time_cnt = 0; - thermalManager.temp_hotend[uiCfg.curSprayerChoose].target = uiCfg.desireSprayerTempBak; - clear_cur_ui(); - draw_return_ui(); - } - else { - clear_cur_ui(); - draw_return_ui(); - } - } -} - -void lv_draw_dialog(uint8_t type) { - - lv_obj_t * btnOk = NULL; - lv_obj_t * btnCancel = NULL; - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != DIALOG_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = DIALOG_UI; - } - disp_state = DIALOG_UI; - - uiCfg.dialogType = type; - - scr = lv_obj_create(NULL, NULL); - - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, creat_title_text()); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - - static lv_style_t style_btn_rel; // A variable to store the released style - lv_style_copy(&style_btn_rel, &lv_style_plain); // Initialize from a built-in style - style_btn_rel.body.border.color = lv_color_hex3(0x269); - style_btn_rel.body.border.width = 1; - style_btn_rel.body.main_color = lv_color_hex3(0xADF); - style_btn_rel.body.grad_color = lv_color_hex3(0x46B); - style_btn_rel.body.shadow.width = 4; - style_btn_rel.body.shadow.type = LV_SHADOW_BOTTOM; - style_btn_rel.body.radius = LV_RADIUS_CIRCLE; - style_btn_rel.text.color = lv_color_hex3(0xDEF); - style_btn_rel.text.font = &TERN(HAS_SPI_FLASH_FONT, gb2312_puhui32, lv_font_roboto_22); - - static lv_style_t style_btn_pr; // A variable to store the pressed style - lv_style_copy(&style_btn_pr, &style_btn_rel); // Initialize from the released style - style_btn_pr.body.border.color = lv_color_hex3(0x46B); - style_btn_pr.body.main_color = lv_color_hex3(0x8BD); - style_btn_pr.body.grad_color = lv_color_hex3(0x24A); - style_btn_pr.body.shadow.width = 2; - style_btn_pr.text.color = lv_color_hex3(0xBCD); - style_btn_pr.text.font = &TERN(HAS_SPI_FLASH_FONT, gb2312_puhui32, lv_font_roboto_22); - - lv_obj_t *labelDialog = lv_label_create(scr, NULL); - lv_obj_set_style(labelDialog, &tft_style_label_rel); - - if (uiCfg.dialogType == DIALOG_TYPE_FINISH_PRINT || uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_RESUME) { - btnOk = lv_btn_create(scr, NULL); // Add a button the current screen - lv_obj_set_pos(btnOk, BTN_OK_X + 90, BTN_OK_Y); // Set its position - lv_obj_set_size(btnOk, 100, 50); // Set its size - lv_obj_set_event_cb(btnOk, btn_ok_event_cb); - lv_btn_set_style(btnOk, LV_BTN_STYLE_REL, &style_btn_rel); // Set the button's released style - lv_btn_set_style(btnOk, LV_BTN_STYLE_PR, &style_btn_pr); // Set the button's pressed style - lv_obj_t *labelOk = lv_label_create(btnOk, NULL); // Add a label to the button - lv_label_set_text(labelOk, print_file_dialog_menu.confirm); // Set the labels text - } - else if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_WAITING - || uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_INSERT - || uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_HEAT - ) { - btnOk = lv_btn_create(scr, NULL); // Add a button the current screen - lv_obj_set_pos(btnOk, BTN_OK_X + 90, BTN_OK_Y); // Set its position - lv_obj_set_size(btnOk, 100, 50); // Set its size - lv_obj_set_event_cb(btnOk, btn_ok_event_cb); - lv_btn_set_style(btnOk, LV_BTN_STYLE_REL, &style_btn_rel); // Set the button's released style - lv_btn_set_style(btnOk, LV_BTN_STYLE_PR, &style_btn_pr); // Set the button's pressed style - lv_obj_t *labelOk = lv_label_create(btnOk, NULL); // Add a label to the button - lv_label_set_text(labelOk, print_file_dialog_menu.confirm); // Set the labels text - } - else if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_PAUSING - || uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_CHANGING - || uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_UNLOAD - || uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_LOAD - || uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_PURGE - || uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_RESUME - || uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_HEATING - ) { - // nothing to do - } - else if (uiCfg.dialogType == WIFI_ENABLE_TIPS) { - btnCancel = lv_btn_create(scr, NULL); - lv_obj_set_pos(btnCancel, BTN_OK_X+90, BTN_OK_Y); - lv_obj_set_size(btnCancel, 100, 50); - lv_obj_set_event_cb(btnCancel, btn_cancel_event_cb); - lv_btn_set_style(btnCancel, LV_BTN_STYLE_REL, &style_btn_rel); - lv_btn_set_style(btnCancel, LV_BTN_STYLE_PR, &style_btn_pr); - lv_obj_t *labelCancel = lv_label_create(btnCancel, NULL); - lv_label_set_text(labelCancel, print_file_dialog_menu.cancle); - } - else if (uiCfg.dialogType == DIALOG_TRANSFER_NO_DEVICE) { - btnCancel = lv_btn_create(scr, NULL); - lv_obj_set_pos(btnCancel, BTN_OK_X+90, BTN_OK_Y); - lv_obj_set_size(btnCancel, 100, 50); - lv_obj_set_event_cb(btnCancel, btn_cancel_event_cb); - lv_btn_set_style(btnCancel, LV_BTN_STYLE_REL, &style_btn_rel); - lv_btn_set_style(btnCancel, LV_BTN_STYLE_PR, &style_btn_pr); - lv_obj_t *labelCancel = lv_label_create(btnCancel, NULL); - lv_label_set_text(labelCancel, print_file_dialog_menu.cancle); - } - #if ENABLED(USE_WIFI_FUNCTION) - else if (uiCfg.dialogType == DIALOG_TYPE_UPLOAD_FILE) { - if (upload_result == 2) { - btnCancel = lv_btn_create(scr, NULL); - lv_obj_set_pos(btnCancel, BTN_OK_X+90, BTN_OK_Y); - lv_obj_set_size(btnCancel, 100, 50); - lv_obj_set_event_cb(btnCancel, btn_cancel_event_cb); - lv_btn_set_style(btnCancel, LV_BTN_STYLE_REL, &style_btn_rel); - lv_btn_set_style(btnCancel, LV_BTN_STYLE_PR, &style_btn_pr); - lv_obj_t *labelCancel = lv_label_create(btnCancel, NULL); - lv_label_set_text(labelCancel, print_file_dialog_menu.cancle); - } - else if (upload_result == 3) { - btnOk = lv_btn_create(scr, NULL); - lv_obj_set_pos(btnOk, BTN_OK_X+90, BTN_OK_Y); - lv_obj_set_size(btnOk, 100, 50); - lv_obj_set_event_cb(btnOk, btn_ok_event_cb); - lv_btn_set_style(btnOk, LV_BTN_STYLE_REL, &style_btn_rel); - lv_btn_set_style(btnOk, LV_BTN_STYLE_PR, &style_btn_pr); - lv_obj_t *labelOk = lv_label_create(btnOk, NULL); - lv_label_set_text(labelOk, print_file_dialog_menu.confirm); - } - } - #endif //USE_WIFI_FUNCTION - else if (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_LOAD_HEAT - || uiCfg.dialogType == DIALOG_TYPE_FILAMENT_UNLOAD_HEAT - ) { - btnCancel = lv_btn_create(scr, NULL); - lv_obj_set_pos(btnCancel, BTN_OK_X+90, BTN_OK_Y); - lv_obj_set_size(btnCancel, 100, 50); - lv_obj_set_event_cb(btnCancel, btn_cancel_event_cb); - lv_btn_set_style(btnCancel, LV_BTN_STYLE_REL, &style_btn_rel); - lv_btn_set_style(btnCancel, LV_BTN_STYLE_PR, &style_btn_pr); - lv_obj_t *labelCancel = lv_label_create(btnCancel, NULL); - lv_label_set_text(labelCancel, print_file_dialog_menu.cancle); - - tempText1 = lv_label_create(scr, NULL); - lv_obj_set_style(tempText1, &tft_style_label_rel); - filament_sprayer_temp(); - } - else if (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_LOAD_COMPLETED - || uiCfg.dialogType == DIALOG_TYPE_FILAMENT_UNLOAD_COMPLETED - ) { - btnOk = lv_btn_create(scr, NULL); - lv_obj_set_pos(btnOk, BTN_OK_X+90, BTN_OK_Y); - lv_obj_set_size(btnOk, 100, 50); - lv_obj_set_event_cb(btnOk, btn_ok_event_cb); - lv_btn_set_style(btnOk, LV_BTN_STYLE_REL, &style_btn_rel); - lv_btn_set_style(btnOk, LV_BTN_STYLE_PR, &style_btn_pr); - lv_obj_t *labelOk = lv_label_create(btnOk, NULL); - lv_label_set_text(labelOk, print_file_dialog_menu.confirm); - } - else if (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_LOADING - || uiCfg.dialogType == DIALOG_TYPE_FILAMENT_UNLOADING - ) { - btnCancel = lv_btn_create(scr, NULL); - lv_obj_set_pos(btnCancel, BTN_OK_X+90, BTN_OK_Y); - lv_obj_set_size(btnCancel, 100, 50); - lv_obj_set_event_cb(btnCancel, btn_cancel_event_cb); - lv_btn_set_style(btnCancel, LV_BTN_STYLE_REL, &style_btn_rel); - lv_btn_set_style(btnCancel, LV_BTN_STYLE_PR, &style_btn_pr); - lv_obj_t *labelCancel = lv_label_create(btnCancel, NULL); - lv_label_set_text(labelCancel, print_file_dialog_menu.cancle); - - filament_bar = lv_bar_create(scr, NULL); - lv_obj_set_pos(filament_bar, (TFT_WIDTH-400)/2, ((TFT_HEIGHT - titleHeight)-40)/2); - lv_obj_set_size(filament_bar, 400, 25); - lv_bar_set_style(filament_bar, LV_BAR_STYLE_INDIC, &lv_bar_style_indic); - lv_bar_set_anim_time(filament_bar, 1000); - lv_bar_set_value(filament_bar, 0, LV_ANIM_ON); - } - else { - btnOk = lv_btn_create(scr, NULL); // Add a button the current screen - lv_obj_set_pos(btnOk, BTN_OK_X, BTN_OK_Y); // Set its position - lv_obj_set_size(btnOk, 100, 50); // Set its size - lv_obj_set_event_cb(btnOk, btn_ok_event_cb); - lv_btn_set_style(btnOk, LV_BTN_STYLE_REL, &style_btn_rel); // Set the button's released style - lv_btn_set_style(btnOk, LV_BTN_STYLE_PR, &style_btn_pr); // Set the button's pressed style - lv_obj_t *labelOk = lv_label_create(btnOk, NULL); // Add a label to the button - - btnCancel = lv_btn_create(scr, NULL); // Add a button the current screen - lv_obj_set_pos(btnCancel, BTN_CANCEL_X, BTN_CANCEL_Y); // Set its position - lv_obj_set_size(btnCancel, 100, 50); // Set its size - lv_obj_set_event_cb(btnCancel, btn_cancel_event_cb); - lv_btn_set_style(btnCancel, LV_BTN_STYLE_REL, &style_btn_rel); // Set the button's released style - lv_btn_set_style(btnCancel, LV_BTN_STYLE_PR, &style_btn_pr); // Set the button's pressed style - lv_obj_t *labelCancel = lv_label_create(btnCancel, NULL); // Add a label to the button - - if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_OPTION) { - lv_label_set_text(labelOk, pause_msg_menu.purgeMore); // Set the labels text - lv_label_set_text(labelCancel, pause_msg_menu.continuePrint); - } - else { - lv_label_set_text(labelOk, print_file_dialog_menu.confirm); // Set the labels text - lv_label_set_text(labelCancel, print_file_dialog_menu.cancle); - } - } - if (uiCfg.dialogType == DIALOG_TYPE_PRINT_FILE) { - lv_label_set_text(labelDialog, print_file_dialog_menu.print_file); - lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); - - lv_obj_t *labelFile = lv_label_create(scr, NULL); - lv_obj_set_style(labelFile, &tft_style_label_rel); - - lv_label_set_text(labelFile, list_file.long_name[sel_id]); - lv_obj_align(labelFile, NULL, LV_ALIGN_CENTER, 0, -60); - } - else if (uiCfg.dialogType == DIALOG_TYPE_STOP) { - lv_label_set_text(labelDialog, print_file_dialog_menu.cancle_print); - lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); - } - else if (uiCfg.dialogType == DIALOG_TYPE_FINISH_PRINT) { - lv_label_set_text(labelDialog, print_file_dialog_menu.print_finish); - lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); - } - else if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_PAUSING) { - lv_label_set_text(labelDialog, pause_msg_menu.pausing); - lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); - } - else if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_CHANGING) { - lv_label_set_text(labelDialog, pause_msg_menu.changing); - lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); - } - else if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_UNLOAD) { - lv_label_set_text(labelDialog, pause_msg_menu.unload); - lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); - } - else if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_WAITING) { - lv_label_set_text(labelDialog, pause_msg_menu.waiting); - lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); - } - else if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_INSERT) { - lv_label_set_text(labelDialog, pause_msg_menu.insert); - lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); - } - else if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_LOAD) { - lv_label_set_text(labelDialog, pause_msg_menu.load); - lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); - } - else if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_PURGE) { - lv_label_set_text(labelDialog, pause_msg_menu.purge); - lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); - } - else if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_RESUME) { - lv_label_set_text(labelDialog, pause_msg_menu.resume); - lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); - } - else if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_HEAT) { - lv_label_set_text(labelDialog, pause_msg_menu.heat); - lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); - } - else if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_HEATING) { - lv_label_set_text(labelDialog, pause_msg_menu.heating); - lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); - } - else if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_OPTION) { - lv_label_set_text(labelDialog, pause_msg_menu.option); - lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); - } - else if (uiCfg.dialogType == DIALOG_STORE_EEPROM_TIPS) { - lv_label_set_text(labelDialog, eeprom_menu.storeTips); - lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); - } - else if (uiCfg.dialogType == DIALOG_READ_EEPROM_TIPS) { - lv_label_set_text(labelDialog, eeprom_menu.readTips); - lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); - } - else if (uiCfg.dialogType == DIALOG_REVERT_EEPROM_TIPS) { - lv_label_set_text(labelDialog, eeprom_menu.revertTips); - lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); - } - else if (uiCfg.dialogType == DIALOG_WIFI_CONFIG_TIPS) { - lv_label_set_text(labelDialog, machine_menu.wifiConfigTips); - lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); - } - else if (uiCfg.dialogType == WIFI_ENABLE_TIPS) { - lv_label_set_text(labelDialog, print_file_dialog_menu.wifi_enable_tips); - lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); - } - else if (uiCfg.dialogType == DIALOG_TRANSFER_NO_DEVICE) { - lv_label_set_text(labelDialog, DIALOG_UPDATE_NO_DEVICE_EN); - lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); - } - #if ENABLED(USE_WIFI_FUNCTION) - else if (uiCfg.dialogType == DIALOG_TYPE_UPLOAD_FILE) { - if (upload_result == 1) { - lv_label_set_text(labelDialog, DIALOG_UPLOAD_ING_EN); - lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); - } - else if (upload_result == 2) { - lv_label_set_text(labelDialog, DIALOG_UPLOAD_ERROR_EN); - lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); - } - else if (upload_result == 3) { - char buf[200]; - int _index = 0; - - ZERO(buf); - - strcpy(buf, DIALOG_UPLOAD_FINISH_EN); - _index = strlen(buf); - buf[_index] = '\n'; - _index++; - strcat(buf, DIALOG_UPLOAD_SIZE_EN); - - _index = strlen(buf); - buf[_index] = ':'; - _index++; - sprintf(&buf[_index], " %d KBytes\n", (int)(upload_size / 1024)); - - strcat(buf, DIALOG_UPLOAD_TIME_EN); - _index = strlen(buf); - buf[_index] = ':'; - _index++; - sprintf(&buf[_index], " %d s\n", (int)upload_time); - - strcat(buf, DIALOG_UPLOAD_SPEED_EN); - _index = strlen(buf); - buf[_index] = ':'; - _index++; - sprintf(&buf[_index], " %d KBytes/s\n", (int)(upload_size / upload_time / 1024)); - - lv_label_set_text(labelDialog, buf); - lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); - - } - } - #endif //USE_WIFI_FUNCTION - else if (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_LOAD_HEAT) { - lv_label_set_text(labelDialog, filament_menu.filament_dialog_load_heat); - lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); - } - else if (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_HEAT_LOAD_COMPLETED) { - lv_label_set_text(labelDialog, filament_menu.filament_dialog_load_heat_confirm); - lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); - } - else if (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_UNLOAD_HEAT) { - lv_label_set_text(labelDialog, filament_menu.filament_dialog_unload_heat); - lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); - } - else if (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_HEAT_UNLOAD_COMPLETED) { - lv_label_set_text(labelDialog, filament_menu.filament_dialog_unload_heat_confirm); - lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); - } - else if (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_LOAD_COMPLETED) { - lv_label_set_text(labelDialog, filament_menu.filament_dialog_load_completed); - lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); - } - else if (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_UNLOAD_COMPLETED) { - lv_label_set_text(labelDialog, filament_menu.filament_dialog_unload_completed); - lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); - } - else if (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_LOADING) { - lv_label_set_text(labelDialog, filament_menu.filament_dialog_loading); - lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -70); - } - else if (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_UNLOADING) { - lv_label_set_text(labelDialog, filament_menu.filament_dialog_unloading); - lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -70); - } - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - if (btnOk) lv_group_add_obj(g, btnOk); - if (btnCancel) lv_group_add_obj(g, btnCancel); - } - #endif -} - -void filament_sprayer_temp() { - char buf[20] = {0}; - - public_buf_l[0] = '\0'; - - if (uiCfg.curSprayerChoose < 1) - strcat(public_buf_l, preheat_menu.ext1); - else - strcat(public_buf_l, preheat_menu.ext2); - sprintf(buf, preheat_menu.value_state, (int)thermalManager.temp_hotend[uiCfg.curSprayerChoose].celsius, (int)thermalManager.temp_hotend[uiCfg.curSprayerChoose].target); - - strcat_P(public_buf_l, PSTR(": ")); - strcat(public_buf_l, buf); - lv_label_set_text(tempText1, public_buf_l); - lv_obj_align(tempText1, NULL, LV_ALIGN_CENTER, 0, -50); -} - -void filament_dialog_handle() { - if ((temperature_change_frequency == 1) - && ((uiCfg.dialogType == DIALOG_TYPE_FILAMENT_LOAD_HEAT) - || (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_UNLOAD_HEAT)) - ) { - filament_sprayer_temp(); - temperature_change_frequency = 0; - } - if (uiCfg.filament_heat_completed_load == 1) { - uiCfg.filament_heat_completed_load = 0; - lv_clear_dialog(); - lv_draw_dialog(DIALOG_TYPE_FILAMENT_LOADING); - planner.synchronize(); - uiCfg.filament_loading_time_flg = 1; - uiCfg.filament_loading_time_cnt = 0; - ZERO(public_buf_m); - sprintf_P(public_buf_m,PSTR("T%d\nG91\nG1 E%d F%d\nG90"),uiCfg.curSprayerChoose,gCfgItems.filamentchange_load_length,gCfgItems.filamentchange_load_speed); - queue.inject_P(PSTR(public_buf_m)); - //gcode.process_subcommands_now_P(PSTR(public_buf_m)); - } - if (uiCfg.filament_heat_completed_unload == 1) { - uiCfg.filament_heat_completed_unload = 0; - lv_clear_dialog(); - lv_draw_dialog(DIALOG_TYPE_FILAMENT_UNLOADING); - planner.synchronize(); - uiCfg.filament_unloading_time_flg = 1; - uiCfg.filament_unloading_time_cnt = 0; - ZERO(public_buf_m); - sprintf_P(public_buf_m,PSTR("T%d\nG91\nG1 E-%d F%d\nG90"),uiCfg.curSprayerChoose,gCfgItems.filamentchange_unload_length,gCfgItems.filamentchange_unload_speed); - queue.inject_P(PSTR(public_buf_m)); - } - - if (((abs((int)((int)thermalManager.temp_hotend[uiCfg.curSprayerChoose].celsius - gCfgItems.filament_limit_temper)) <= 1) - || ((int)thermalManager.temp_hotend[uiCfg.curSprayerChoose].celsius > gCfgItems.filament_limit_temper)) - && (uiCfg.filament_load_heat_flg == 1) - ) { - uiCfg.filament_load_heat_flg = 0; - lv_clear_dialog(); - lv_draw_dialog(DIALOG_TYPE_FILAMENT_HEAT_LOAD_COMPLETED); - } - - if (uiCfg.filament_loading_completed == 1) { - uiCfg.filament_rate = 0; - uiCfg.filament_loading_completed = 0; - lv_clear_dialog(); - lv_draw_dialog(DIALOG_TYPE_FILAMENT_LOAD_COMPLETED); - } - if (((abs((int)((int)thermalManager.temp_hotend[uiCfg.curSprayerChoose].celsius - gCfgItems.filament_limit_temper)) <= 1) - || ((int)thermalManager.temp_hotend[uiCfg.curSprayerChoose].celsius > gCfgItems.filament_limit_temper)) - && (uiCfg.filament_unload_heat_flg == 1) - ) { - uiCfg.filament_unload_heat_flg = 0; - lv_clear_dialog(); - lv_draw_dialog(DIALOG_TYPE_FILAMENT_HEAT_UNLOAD_COMPLETED); - } - - if (uiCfg.filament_unloading_completed == 1) { - uiCfg.filament_rate = 0; - uiCfg.filament_unloading_completed = 0; - lv_clear_dialog(); - lv_draw_dialog(DIALOG_TYPE_FILAMENT_UNLOAD_COMPLETED); - } - - if ( uiCfg.dialogType == DIALOG_TYPE_FILAMENT_LOADING - || uiCfg.dialogType == DIALOG_TYPE_FILAMENT_UNLOADING - ) lv_filament_setbar(); -} - -void lv_filament_setbar() { - lv_bar_set_value(filament_bar, uiCfg.filament_rate, LV_ANIM_ON); -} - -void lv_clear_dialog() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_dialog.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_dialog.h deleted file mode 100644 index dc5adc5ad64c..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_dialog.h +++ /dev/null @@ -1,88 +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 - -#ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ -#endif - -#define DIALOG_TYPE_STOP 0 -#define DIALOG_TYPE_PRINT_FILE 1 -#define DIALOG_TYPE_REPRINT_NO_FILE 2 - -#define DIALOG_TYPE_M80_FAIL 3 //** -#define DIALOG_TYPE_MESSAGE_ERR1 4 //** - -#define DIALOG_TYPE_UPDATE_ESP_FIRMARE 5 -#define DIALOG_TYPE_UPDATE_ESP_DATA 6 -#define DIALOG_TYPE_UPLOAD_FILE 7 -#define DIALOG_TYPE_UNBIND 8 - -#define DIALOG_TYPE_FILAMENT_LOAD_HEAT 9 -#define DIALOG_TYPE_FILAMENT_HEAT_LOAD_COMPLETED 10 -#define DIALOG_TYPE_FILAMENT_LOADING 11 -#define DIALOG_TYPE_FILAMENT_LOAD_COMPLETED 12 -#define DIALOG_TYPE_FILAMENT_UNLOAD_HEAT 13 -#define DIALOG_TYPE_FILAMENT_HEAT_UNLOAD_COMPLETED 14 -#define DIALOG_TYPE_FILAMENT_UNLOADING 15 -#define DIALOG_TYPE_FILAMENT_UNLOAD_COMPLETED 16 - -#define DIALOG_TYPE_FILE_LOADING 17 //** - -#define DIALOG_TYPE_FILAMENT_NO_PRESS 18 -#define DIALOG_TYPE_FINISH_PRINT 19 - -#define WIFI_ENABLE_TIPS 20 - -#define DIALOG_PAUSE_MESSAGE_PAUSING 21 -#define DIALOG_PAUSE_MESSAGE_CHANGING 22 -#define DIALOG_PAUSE_MESSAGE_UNLOAD 23 -#define DIALOG_PAUSE_MESSAGE_WAITING 24 -#define DIALOG_PAUSE_MESSAGE_INSERT 25 -#define DIALOG_PAUSE_MESSAGE_LOAD 26 -#define DIALOG_PAUSE_MESSAGE_PURGE 27 -#define DIALOG_PAUSE_MESSAGE_RESUME 28 -#define DIALOG_PAUSE_MESSAGE_HEAT 29 -#define DIALOG_PAUSE_MESSAGE_HEATING 30 -#define DIALOG_PAUSE_MESSAGE_OPTION 31 - -#define DIALOG_STORE_EEPROM_TIPS 32 -#define DIALOG_READ_EEPROM_TIPS 33 -#define DIALOG_REVERT_EEPROM_TIPS 34 - -#define DIALOG_WIFI_CONFIG_TIPS 35 -#define DIALOG_TRANSFER_NO_DEVICE 36 -#define BTN_OK_X 100 -#define BTN_OK_Y 180 -#define BTN_CANCEL_X 280 -#define BTN_CANCEL_Y 180 - -extern void lv_draw_dialog(uint8_t type); -extern void lv_clear_dialog(); -extern void filament_sprayer_temp(); -extern void filament_dialog_handle(); -extern void lv_filament_setbar(); - -//extern void disp_temp_ready_print(); -#ifdef __cplusplus - } /* C-declarations for C++ */ -#endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_eeprom_settings.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_eeprom_settings.cpp deleted file mode 100644 index ca7d2d1e31b8..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_eeprom_settings.cpp +++ /dev/null @@ -1,224 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "lv_conf.h" -#include "draw_ui.h" - -#include "../../../../MarlinCore.h" - -extern lv_group_t * g; -static lv_obj_t * scr; - -#define ID_EEPROM_RETURN 1 -#define ID_EEPROM_STORE 2 -#define ID_EEPROM_STORE_ARROW 3 -#define ID_EEPROM_READ 4 -#define ID_EEPROM_READ_ARROW 5 -#define ID_EEPROM_REVERT 6 -#define ID_EEPROM_REVERT_ARROW 7 - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_EEPROM_RETURN: - if (event == LV_EVENT_CLICKED) { - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_eeprom_settings(); - draw_return_ui(); - } - break; - case ID_EEPROM_STORE: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_eeprom_settings(); - lv_draw_dialog(DIALOG_STORE_EEPROM_TIPS); - } - break; - case ID_EEPROM_STORE_ARROW: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_eeprom_settings(); - lv_draw_dialog(DIALOG_STORE_EEPROM_TIPS); - } - break; - #if 0 - case ID_EEPROM_READ: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_eeprom_settings(); - lv_draw_dialog(DIALOG_READ_EEPROM_TIPS); - } - break; - case ID_EEPROM_READ_ARROW: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_eeprom_settings(); - lv_draw_dialog(DIALOG_READ_EEPROM_TIPS); - } - break; - #endif - - case ID_EEPROM_REVERT: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_eeprom_settings(); - lv_draw_dialog(DIALOG_REVERT_EEPROM_TIPS); - } - break; - case ID_EEPROM_REVERT_ARROW: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_eeprom_settings(); - lv_draw_dialog(DIALOG_REVERT_EEPROM_TIPS); - } - break; - } -} - -void lv_draw_eeprom_settings(void) { - lv_obj_t *buttonBack, *label_Back; - lv_obj_t *buttonStore,*labelStore,*buttonStoreNarrow; - //lv_obj_t *buttonRead,*labelRead,*buttonReadNarrow; - lv_obj_t *buttonRevert, *labelRevert, *buttonRevertNarrow; - lv_obj_t * line1, * line2; //* line3; - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != EEPROM_SETTINGS_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = EEPROM_SETTINGS_UI; - } - disp_state = EEPROM_SETTINGS_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, creat_title_text()); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - buttonRevert = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonRevert, PARA_UI_POS_X, PARA_UI_POS_Y); /*Set its position*/ - lv_obj_set_size(buttonRevert, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - //lv_obj_set_event_cb(buttonMotor, event_handler); - lv_obj_set_event_cb_mks(buttonRevert, event_handler, ID_EEPROM_REVERT, NULL, 0); - lv_btn_set_style(buttonRevert, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonRevert, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonRevert, LV_LAYOUT_OFF); - labelRevert = lv_label_create(buttonRevert, NULL); /*Add a label to the button*/ - - buttonRevertNarrow = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonRevertNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y + PARA_UI_ARROW_V); - lv_obj_set_event_cb_mks(buttonRevertNarrow, event_handler, ID_EEPROM_REVERT_ARROW, NULL, 0); - lv_imgbtn_set_src(buttonRevertNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); - lv_imgbtn_set_src(buttonRevertNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); - lv_imgbtn_set_style(buttonRevertNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonRevertNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_btn_set_layout(buttonRevertNarrow, LV_LAYOUT_OFF); - - //line3 = lv_line_create(scr, NULL); - //lv_ex_line(line3,line_points[2]); - line1 = lv_line_create(scr, NULL); - lv_ex_line(line1, line_points[0]); - - buttonStore = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonStore, PARA_UI_POS_X, PARA_UI_POS_Y * 2); /*Set its position*/ - lv_obj_set_size(buttonStore, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - //lv_obj_set_event_cb(buttonMotor, event_handler); - lv_obj_set_event_cb_mks(buttonStore, event_handler, ID_EEPROM_STORE, NULL, 0); - lv_btn_set_style(buttonStore, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonStore, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonStore, LV_LAYOUT_OFF); - labelStore = lv_label_create(buttonStore, NULL); /*Add a label to the button*/ - - buttonStoreNarrow = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonStoreNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y * 2 + PARA_UI_ARROW_V); - lv_obj_set_event_cb_mks(buttonStoreNarrow, event_handler, ID_EEPROM_STORE_ARROW, NULL, 0); - lv_imgbtn_set_src(buttonStoreNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); - lv_imgbtn_set_src(buttonStoreNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); - lv_imgbtn_set_style(buttonStoreNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonStoreNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_btn_set_layout(buttonStoreNarrow, LV_LAYOUT_OFF); - - line2 = lv_line_create(scr, NULL); - lv_ex_line(line2, line_points[1]); - - buttonBack = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_EEPROM_RETURN, NULL, 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_back70x40.bin"); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_back70x40.bin"); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); - lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - label_Back = lv_label_create(buttonBack, NULL); - - if (gCfgItems.multiple_language != 0) { - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_CENTER, 0, 0); - - lv_label_set_text(labelStore, eeprom_menu.store); - lv_obj_align(labelStore, buttonStore, LV_ALIGN_IN_LEFT_MID,0, 0); - - //lv_label_set_text(labelRead, eeprom_menu.read); - //lv_obj_align(labelRead, buttonRead, LV_ALIGN_IN_LEFT_MID,0, 0); - - lv_label_set_text(labelRevert, eeprom_menu.revert); - lv_obj_align(labelRevert, buttonRevert, LV_ALIGN_IN_LEFT_MID, 0, 0); - } - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonRevert); - lv_group_add_obj(g, buttonStore); - lv_group_add_obj(g, buttonBack); - } - #endif - -} - -void lv_clear_eeprom_settings() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_encoder_settings.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_encoder_settings.cpp deleted file mode 100644 index 0ad2bb5f1ddb..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_encoder_settings.cpp +++ /dev/null @@ -1,172 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "lv_conf.h" -#include "draw_ui.h" - -#include "../../../../MarlinCore.h" -#include "../../../../module/planner.h" -#include "../../../../module/stepper/indirection.h" -#include "../../../../feature/tmc_util.h" -#include "../../../../gcode/gcode.h" -#include "../../../../module/planner.h" - -#if BUTTONS_EXIST(EN1, EN2) - -extern lv_group_t * g; -static lv_obj_t * scr; -static lv_obj_t * buttonEncoderState = NULL; -static lv_obj_t *labelEncoderState = NULL; - -#define ID_ENCODER_RETURN 1 -#define ID_ENCODER_STATE 2 - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_ENCODER_RETURN: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_encoder_settings(); - draw_return_ui(); - } - break; - case ID_ENCODER_STATE: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - if (gCfgItems.encoder_enable) { - gCfgItems.encoder_enable = false; - lv_imgbtn_set_src(buttonEncoderState, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); - lv_imgbtn_set_src(buttonEncoderState, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); - lv_label_set_text(labelEncoderState, machine_menu.disable); - update_spi_flash(); - } - else { - gCfgItems.encoder_enable = true; - lv_imgbtn_set_src(buttonEncoderState, LV_BTN_STATE_REL, "F:/bmp_enable.bin"); - lv_imgbtn_set_src(buttonEncoderState, LV_BTN_STATE_PR, "F:/bmp_enable.bin"); - lv_label_set_text(labelEncoderState, machine_menu.enable); - update_spi_flash(); - } - } - break; - } -} - -void lv_draw_encoder_settings(void) { - lv_obj_t *buttonBack = NULL, *label_Back = NULL; - lv_obj_t *labelEncoderTips = NULL; - - lv_obj_t * line1 = NULL; - - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != ENCODER_SETTINGS_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = ENCODER_SETTINGS_UI; - } - disp_state = ENCODER_SETTINGS_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, machine_menu.EncoderConfTitle); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - labelEncoderTips = lv_label_create(scr, NULL); - lv_obj_set_style(labelEncoderTips, &tft_style_label_rel); - lv_obj_set_pos(labelEncoderTips, PARA_UI_POS_X, PARA_UI_POS_Y + 10); - lv_label_set_text(labelEncoderTips, machine_menu.EncoderConfText); - - buttonEncoderState = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonEncoderState, PARA_UI_STATE_POS_X, PARA_UI_POS_Y + PARA_UI_STATE_V); - if (gCfgItems.encoder_enable) { - lv_imgbtn_set_src(buttonEncoderState, LV_BTN_STATE_REL, "F:/bmp_enable.bin"); - lv_imgbtn_set_src(buttonEncoderState, LV_BTN_STATE_PR, "F:/bmp_enable.bin"); - } - else { - lv_imgbtn_set_src(buttonEncoderState, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); - lv_imgbtn_set_src(buttonEncoderState, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); - } - - lv_obj_set_event_cb_mks(buttonEncoderState, event_handler, ID_ENCODER_STATE, NULL, 0); - - lv_imgbtn_set_style(buttonEncoderState, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonEncoderState, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_btn_set_layout(buttonEncoderState, LV_LAYOUT_OFF); - labelEncoderState = lv_label_create(buttonEncoderState, NULL); - - line1 = lv_line_create(scr, NULL); - lv_ex_line(line1, line_points[0]); - - buttonBack = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_ENCODER_RETURN, NULL, 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_back70x40.bin"); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_back70x40.bin"); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); - lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - label_Back = lv_label_create(buttonBack, NULL); - - if (gCfgItems.encoder_enable) { - lv_label_set_text(labelEncoderState, machine_menu.enable); - lv_obj_align(labelEncoderState, buttonEncoderState, LV_ALIGN_CENTER, 0, 0); - } - else { - lv_label_set_text(labelEncoderState, machine_menu.disable); - lv_obj_align(labelEncoderState, buttonEncoderState, LV_ALIGN_CENTER, 0, 0); - } - - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_CENTER, 0, 0); - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonEncoderState); - lv_group_add_obj(g, buttonBack); - } - #endif -} - -void lv_clear_encoder_settings() { - #if HAS_ROTARY_ENCODER - lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // BUTTONS_EXIST(EN1, EN2) - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_error_message.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_error_message.cpp deleted file mode 100644 index c21ee3612c3a..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_error_message.cpp +++ /dev/null @@ -1,86 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "SPI_TFT.h" - -#include "lv_conf.h" -#include "draw_ui.h" -#include "tft_lvgl_configuration.h" -#include "mks_hardware_test.h" -//#include "../lvgl/src/lv_objx/lv_imgbtn.h" -//#include "../lvgl/src/lv_objx/lv_img.h" -//#include "../lvgl/src/lv_core/lv_disp.h" -//#include "../lvgl/src/lv_core/lv_refr.h" - -#include "../../../../MarlinCore.h" - -static lv_obj_t * scr; - -void lv_draw_error_message(PGM_P const msg) { - #if 0 - static lv_obj_t * message = NULL, *kill_message = NULL, *reset_tips = NULL; - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != ERROR_MESSAGE_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = ERROR_MESSAGE_UI; - } - disp_state = ERROR_MESSAGE_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - if (msg) { - message = lv_label_create(scr, NULL); - lv_obj_set_style(message, &tft_style_label_rel); - lv_label_set_text(message, msg); - lv_obj_align(message, NULL, LV_ALIGN_CENTER, 0, -50); - } - - kill_message = lv_label_create(scr, NULL); - lv_obj_set_style(kill_message, &tft_style_label_rel); - lv_label_set_text(kill_message, "PRINTER HALTED"); - lv_obj_align(kill_message, NULL, LV_ALIGN_CENTER, 0, -10); - - reset_tips = lv_label_create(scr, NULL); - lv_obj_set_style(reset_tips, &tft_style_label_rel); - lv_label_set_text(reset_tips, "Please Reset"); - lv_obj_align(reset_tips, NULL, LV_ALIGN_CENTER, 0, 30); - - lv_task_handler(); - #endif - - SPI_TFT.LCD_clear(0x0000); - if (msg) disp_string((TFT_WIDTH - strlen(msg) * 16) / 2, 100, msg, 0xFFFF, 0x0000); - disp_string((TFT_WIDTH - strlen("PRINTER HALTED") * 16) / 2, 140, "PRINTER HALTED", 0xFFFF, 0x0000); - disp_string((TFT_WIDTH - strlen("Please Reset") * 16) / 2, 180, "Please Reset", 0xFFFF, 0x0000); -} - -void lv_clear_error_message() { lv_obj_del(scr); } - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_extrusion.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_extrusion.cpp deleted file mode 100644 index 543202067f59..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_extrusion.cpp +++ /dev/null @@ -1,403 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "lv_conf.h" -#include "draw_ui.h" -//#include "../lvgl/src/lv_objx/lv_imgbtn.h" -//#include "../lvgl/src/lv_objx/lv_img.h" -//#include "../lvgl/src/lv_core/lv_disp.h" -//#include "../lvgl/src/lv_core/lv_refr.h" - -#include "../../../../MarlinCore.h" -#include "../../../../module/temperature.h" -#include "../../../../gcode/queue.h" - -static lv_obj_t * scr; -extern lv_group_t* g; -static lv_obj_t * buttoType, *buttonStep, *buttonSpeed; -static lv_obj_t *labelType; -static lv_obj_t *labelStep; -static lv_obj_t *labelSpeed; -static lv_obj_t * tempText; -static lv_obj_t * ExtruText; - -#define ID_E_ADD 1 -#define ID_E_DEC 2 -#define ID_E_TYPE 3 -#define ID_E_STEP 4 -#define ID_E_SPEED 5 -#define ID_E_RETURN 6 - -static int32_t extructAmount; - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_E_ADD: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - if (thermalManager.temp_hotend[uiCfg.curSprayerChoose].celsius >= EXTRUDE_MINTEMP) { - queue.enqueue_now_P(PSTR("G91")); - ZERO(public_buf_l); - sprintf_P((char *)public_buf_l, PSTR("G1 E%d F%d"), uiCfg.extruStep, 60 * uiCfg.extruSpeed); - queue.enqueue_one_now(public_buf_l); - queue.enqueue_now_P(PSTR("G90")); - extructAmount += uiCfg.extruStep; - disp_extru_amount(); - } - } - break; - case ID_E_DEC: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - if (thermalManager.temp_hotend[uiCfg.curSprayerChoose].celsius >= EXTRUDE_MINTEMP) { - queue.enqueue_now_P(PSTR("G91")); - ZERO(public_buf_l); - sprintf_P((char *)public_buf_l, PSTR("G1 E%d F%d"), 0 - uiCfg.extruStep, 60 * uiCfg.extruSpeed); - queue.enqueue_one_now(public_buf_l); - queue.enqueue_now_P(PSTR("G90")); - extructAmount -= uiCfg.extruStep; - disp_extru_amount(); - } - } - break; - case ID_E_TYPE: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - if (ENABLED(HAS_MULTI_EXTRUDER)) { - if (uiCfg.curSprayerChoose == 0) { - uiCfg.curSprayerChoose = 1; - queue.inject_P(PSTR("T1")); - } - else { - uiCfg.curSprayerChoose = 0; - queue.inject_P(PSTR("T0")); - } - } - else - uiCfg.curSprayerChoose = 0; - - extructAmount = 0; - disp_hotend_temp(); - disp_ext_type(); - disp_extru_amount(); - } - break; - case ID_E_STEP: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - switch (abs(uiCfg.extruStep)) { - case 1: uiCfg.extruStep = 5; break; - case 5: uiCfg.extruStep = 10; break; - case 10: uiCfg.extruStep = 1; break; - default: break; - } - disp_ext_step(); - } - break; - case ID_E_SPEED: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - switch (uiCfg.extruSpeed) { - case 1: uiCfg.extruSpeed = 10; break; - case 10: uiCfg.extruSpeed = 20; break; - case 20: uiCfg.extruSpeed = 1; break; - default: break; - } - disp_ext_speed(); - } - break; - case ID_E_RETURN: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - clear_cur_ui(); - draw_return_ui(); - } - break; - } -} - -void lv_draw_extrusion(void) { - lv_obj_t *buttonAdd, *buttonDec, *buttonBack; - - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != EXTRUSION_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = EXTRUSION_UI; - } - disp_state = EXTRUSION_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, creat_title_text()); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - // Create image buttons - buttonAdd = lv_imgbtn_create(scr, NULL); - buttonDec = lv_imgbtn_create(scr, NULL); - buttoType = lv_imgbtn_create(scr, NULL); - buttonStep = lv_imgbtn_create(scr, NULL); - buttonSpeed = lv_imgbtn_create(scr, NULL); - buttonBack = lv_imgbtn_create(scr, NULL); - - lv_obj_set_event_cb_mks(buttonAdd, event_handler, ID_E_ADD, NULL, 0); - lv_imgbtn_set_src(buttonAdd, LV_BTN_STATE_REL, "F:/bmp_in.bin"); - lv_imgbtn_set_src(buttonAdd, LV_BTN_STATE_PR, "F:/bmp_in.bin"); - lv_imgbtn_set_style(buttonAdd, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonAdd, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_clear_protect(buttonAdd, LV_PROTECT_FOLLOW); - - #if 1 - lv_obj_set_event_cb_mks(buttonDec, event_handler, ID_E_DEC, NULL, 0); - lv_imgbtn_set_src(buttonDec, LV_BTN_STATE_REL, "F:/bmp_out.bin"); - lv_imgbtn_set_src(buttonDec, LV_BTN_STATE_PR, "F:/bmp_out.bin"); - lv_imgbtn_set_style(buttonDec, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonDec, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttoType, event_handler, ID_E_TYPE, NULL, 0); - lv_imgbtn_set_style(buttoType, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttoType, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonStep, event_handler, ID_E_STEP, NULL, 0); - lv_imgbtn_set_style(buttonStep, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonStep, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonSpeed, event_handler, ID_E_SPEED, NULL, 0); - lv_imgbtn_set_style(buttonSpeed, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonSpeed, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_E_RETURN, NULL, 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_return.bin"); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_return.bin"); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); - #endif - - lv_obj_set_pos(buttonAdd, INTERVAL_V, titleHeight); - lv_obj_set_pos(buttonDec, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight); - lv_obj_set_pos(buttoType, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - lv_obj_set_pos(buttonStep, BTN_X_PIXEL + INTERVAL_V * 2, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - lv_obj_set_pos(buttonSpeed, BTN_X_PIXEL * 2 + INTERVAL_V * 3, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - lv_obj_set_pos(buttonBack, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - - // Create labels on the image buttons - lv_btn_set_layout(buttonAdd, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonDec, LV_LAYOUT_OFF); - lv_btn_set_layout(buttoType, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonStep, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonSpeed, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - - lv_obj_t *labelAdd = lv_label_create(buttonAdd, NULL); - lv_obj_t *labelDec = lv_label_create(buttonDec, NULL); - labelType = lv_label_create(buttoType, NULL); - labelStep = lv_label_create(buttonStep, NULL); - labelSpeed = lv_label_create(buttonSpeed, NULL); - lv_obj_t *label_Back = lv_label_create(buttonBack, NULL); - - if (gCfgItems.multiple_language != 0) { - lv_label_set_text(labelAdd, extrude_menu.in); - lv_obj_align(labelAdd, buttonAdd, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(labelDec, extrude_menu.out); - lv_obj_align(labelDec, buttonDec, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonAdd); - lv_group_add_obj(g, buttonDec); - lv_group_add_obj(g, buttoType); - lv_group_add_obj(g, buttonStep); - lv_group_add_obj(g, buttonSpeed); - lv_group_add_obj(g, buttonBack); - } - #endif - - disp_ext_type(); - disp_ext_step(); - disp_ext_speed(); - - tempText = lv_label_create(scr, NULL); - lv_obj_set_style(tempText, &tft_style_label_rel); - disp_hotend_temp(); - - ExtruText = lv_label_create(scr, NULL); - lv_obj_set_style(ExtruText, &tft_style_label_rel); - disp_extru_amount(); -} - -void disp_ext_type() { - if (uiCfg.curSprayerChoose == 1) { - lv_imgbtn_set_src(buttoType, LV_BTN_STATE_REL, "F:/bmp_extru2.bin"); - lv_imgbtn_set_src(buttoType, LV_BTN_STATE_PR, "F:/bmp_extru2.bin"); - if (gCfgItems.multiple_language != 0) { - lv_label_set_text(labelType, extrude_menu.ext2); - lv_obj_align(labelType, buttoType, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - } - else { - lv_imgbtn_set_src(buttoType, LV_BTN_STATE_REL, "F:/bmp_extru1.bin"); - lv_imgbtn_set_src(buttoType, LV_BTN_STATE_PR, "F:/bmp_extru1.bin"); - if (gCfgItems.multiple_language != 0) { - lv_label_set_text(labelType, extrude_menu.ext1); - lv_obj_align(labelType, buttoType, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - } -} - -void disp_ext_speed() { - if (uiCfg.extruSpeed == 20) { - lv_imgbtn_set_src(buttonSpeed, LV_BTN_STATE_REL, "F:/bmp_speed_high.bin"); - lv_imgbtn_set_src(buttonSpeed, LV_BTN_STATE_PR, "F:/bmp_speed_high.bin"); - } - else if (uiCfg.extruSpeed == 1) { - lv_imgbtn_set_src(buttonSpeed, LV_BTN_STATE_REL, "F:/bmp_speed_slow.bin"); - lv_imgbtn_set_src(buttonSpeed, LV_BTN_STATE_PR, "F:/bmp_speed_slow.bin"); - } - else { - lv_imgbtn_set_src(buttonSpeed, LV_BTN_STATE_REL, "F:/bmp_speed_normal.bin"); - lv_imgbtn_set_src(buttonSpeed, LV_BTN_STATE_PR, "F:/bmp_speed_normal.bin"); - } - - if (gCfgItems.multiple_language != 0) { - if (uiCfg.extruSpeed == 20) { - lv_label_set_text(labelSpeed, extrude_menu.high); - lv_obj_align(labelSpeed, buttonSpeed, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - else if (uiCfg.extruSpeed == 1) { - lv_label_set_text(labelSpeed, extrude_menu.low); - lv_obj_align(labelSpeed, buttonSpeed, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - else { - lv_label_set_text(labelSpeed, extrude_menu.normal); - lv_obj_align(labelSpeed, buttonSpeed, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - } -} - -void disp_hotend_temp() { - char buf[20] = {0}; - public_buf_l[0] = '\0'; - strcat(public_buf_l, extrude_menu.temper_text); - sprintf(buf, extrude_menu.temp_value, (int)thermalManager.temp_hotend[uiCfg.curSprayerChoose].celsius, (int)thermalManager.temp_hotend[uiCfg.curSprayerChoose].target); - strcat(public_buf_l, buf); - lv_label_set_text(tempText, public_buf_l); - lv_obj_align(tempText, NULL, LV_ALIGN_CENTER, 0, -50); -} - -void disp_extru_amount() { - char buf1[10] = {0}; - - public_buf_l[0] = '\0'; - - if (extructAmount < 999 && extructAmount > -99) { - sprintf(buf1, extrude_menu.count_value_mm, extructAmount); - if (uiCfg.curSprayerChoose < 1) - strcat(public_buf_l, extrude_menu.ext1); - else - strcat(public_buf_l, extrude_menu.ext2); - strcat(public_buf_l, buf1); - } - else if (extructAmount < 9999 && extructAmount > -999) { - sprintf(buf1, extrude_menu.count_value_cm, extructAmount / 10); - if (uiCfg.curSprayerChoose < 1) - strcat(public_buf_l, extrude_menu.ext1); - else - strcat(public_buf_l, extrude_menu.ext2); - strcat(public_buf_l, buf1); - } - else { - sprintf(buf1, extrude_menu.count_value_m, extructAmount / 1000); - if (uiCfg.curSprayerChoose < 1) - strcat(public_buf_l, extrude_menu.ext1); - else - strcat(public_buf_l, extrude_menu.ext2); - strcat(public_buf_l, buf1); - } - - lv_label_set_text(ExtruText, public_buf_l); - lv_obj_align(ExtruText, NULL, LV_ALIGN_CENTER, 0, -75); -} - -void disp_ext_step() { - if (uiCfg.extruStep == 1) { - lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_REL, "F:/bmp_step1_mm.bin"); - lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_PR, "F:/bmp_step1_mm.bin"); - } - else if (uiCfg.extruStep == 5) { - lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_REL, "F:/bmp_step5_mm.bin"); - lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_PR, "F:/bmp_step5_mm.bin"); - } - else if (uiCfg.extruStep == 10) { - lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_REL, "F:/bmp_step10_mm.bin"); - lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_PR, "F:/bmp_step10_mm.bin"); - } - - if (gCfgItems.multiple_language != 0) { - if (uiCfg.extruStep == 1) { - lv_label_set_text(labelStep, extrude_menu.step_1mm); - lv_obj_align(labelStep, buttonStep, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - else if (uiCfg.extruStep == 5) { - lv_label_set_text(labelStep, extrude_menu.step_5mm); - lv_obj_align(labelStep, buttonStep, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - else if (uiCfg.extruStep == 10) { - lv_label_set_text(labelStep, extrude_menu.step_10mm); - lv_obj_align(labelStep, buttonStep, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - } -} - -void lv_clear_extrusion() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_fan.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_fan.cpp deleted file mode 100644 index 8cdc14964f4b..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_fan.cpp +++ /dev/null @@ -1,265 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "../../../../MarlinCore.h" -#include "lv_conf.h" -//#include "../lvgl/src/lv_objx/lv_imgbtn.h" -//#include "../lvgl/src/lv_objx/lv_img.h" -//#include "../lvgl/src/lv_core/lv_disp.h" -//#include "../lvgl/src/lv_core/lv_refr.h" -#include "../../../../../Configuration.h" -#include "draw_ui.h" -#include "../../../../module/temperature.h" -#include "../../../../gcode/queue.h" -#include "../../../../gcode/gcode.h" - -extern lv_group_t * g; -static lv_obj_t * scr; -static lv_obj_t * fanText; - -#define ID_F_ADD 1 -#define ID_F_DEC 2 -#define ID_F_HIGH 3 -#define ID_F_MID 4 -#define ID_F_OFF 5 -#define ID_F_RETURN 6 - -static uint8_t fanSpeed; - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_F_ADD: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - if (fanSpeed + 1 <= 255) { - fanSpeed++; - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("M106 S%d"), fanSpeed); - gcode.process_subcommands_now(public_buf_l); - } - } - break; - case ID_F_DEC: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - if (fanSpeed > 0) { - fanSpeed--; - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("M106 S%d"), fanSpeed); - gcode.process_subcommands_now(public_buf_l); - } - } - - break; - case ID_F_HIGH: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - gcode.process_subcommands_now_P(PSTR("M106 S255")); - } - break; - case ID_F_MID: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - gcode.process_subcommands_now_P(PSTR("M106 S127")); - } - break; - case ID_F_OFF: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - gcode.process_subcommands_now_P(PSTR("M107")); - } - break; - case ID_F_RETURN: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - clear_cur_ui(); - draw_return_ui(); - } - break; - } -} - -void lv_draw_fan(void) { - lv_obj_t *buttonAdd, *buttonDec, *buttonHigh, *buttonMid; - lv_obj_t *buttonOff, *buttonBack; - - #if HAS_FAN - fanSpeed = thermalManager.fan_speed[0]; - #endif - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != FAN_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = FAN_UI; - } - disp_state = FAN_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, creat_title_text()); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - // Create an Image button - buttonAdd = lv_imgbtn_create(scr, NULL); - buttonDec = lv_imgbtn_create(scr, NULL); - buttonHigh = lv_imgbtn_create(scr, NULL); - buttonMid = lv_imgbtn_create(scr, NULL); - buttonOff = lv_imgbtn_create(scr, NULL); - buttonBack = lv_imgbtn_create(scr, NULL); - - lv_obj_set_event_cb_mks(buttonAdd, event_handler, ID_F_ADD, NULL, 0); - lv_imgbtn_set_src(buttonAdd, LV_BTN_STATE_REL, "F:/bmp_Add.bin"); - lv_imgbtn_set_src(buttonAdd, LV_BTN_STATE_PR, "F:/bmp_Add.bin"); - lv_imgbtn_set_style(buttonAdd, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonAdd, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_clear_protect(buttonAdd, LV_PROTECT_FOLLOW); - - #if 1 - lv_obj_set_event_cb_mks(buttonDec, event_handler, ID_F_DEC, NULL, 0); - lv_imgbtn_set_src(buttonDec, LV_BTN_STATE_REL, "F:/bmp_Dec.bin"); - lv_imgbtn_set_src(buttonDec, LV_BTN_STATE_PR, "F:/bmp_Dec.bin"); - lv_imgbtn_set_style(buttonDec, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonDec, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonHigh, event_handler,ID_F_HIGH, NULL,0); - lv_imgbtn_set_src(buttonHigh, LV_BTN_STATE_REL, "F:/bmp_speed255.bin"); - lv_imgbtn_set_src(buttonHigh, LV_BTN_STATE_PR, "F:/bmp_speed255.bin"); - lv_imgbtn_set_style(buttonHigh, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonHigh, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonMid, event_handler,ID_F_MID, NULL,0); - lv_imgbtn_set_src(buttonMid, LV_BTN_STATE_REL, "F:/bmp_speed127.bin"); - lv_imgbtn_set_src(buttonMid, LV_BTN_STATE_PR, "F:/bmp_speed127.bin"); - lv_imgbtn_set_style(buttonMid, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonMid, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonOff, event_handler,ID_F_OFF, NULL,0); - lv_imgbtn_set_src(buttonOff, LV_BTN_STATE_REL, "F:/bmp_speed0.bin"); - lv_imgbtn_set_src(buttonOff, LV_BTN_STATE_PR, "F:/bmp_speed0.bin"); - lv_imgbtn_set_style(buttonOff, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonOff, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonBack, event_handler,ID_F_RETURN, NULL,0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_return.bin"); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_return.bin"); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); - - #endif - - lv_obj_set_pos(buttonAdd, INTERVAL_V, titleHeight); - lv_obj_set_pos(buttonDec, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight); - lv_obj_set_pos(buttonHigh, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - lv_obj_set_pos(buttonMid, BTN_X_PIXEL + INTERVAL_V * 2, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - lv_obj_set_pos(buttonOff, BTN_X_PIXEL * 2 + INTERVAL_V * 3, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - lv_obj_set_pos(buttonBack, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - - // Create labels on the image buttons - lv_btn_set_layout(buttonAdd, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonDec, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonHigh, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonMid, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonOff, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - - lv_obj_t *labelAdd = lv_label_create(buttonAdd, NULL); - lv_obj_t *labelDec = lv_label_create(buttonDec, NULL); - lv_obj_t *labelHigh = lv_label_create(buttonHigh, NULL); - lv_obj_t *labelMid = lv_label_create(buttonMid, NULL); - lv_obj_t *labelOff = lv_label_create(buttonOff, NULL); - lv_obj_t *label_Back = lv_label_create(buttonBack, NULL); - - if (gCfgItems.multiple_language != 0) { - lv_label_set_text(labelAdd, fan_menu.add); - lv_obj_align(labelAdd, buttonAdd, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(labelDec, fan_menu.dec); - lv_obj_align(labelDec, buttonDec, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(labelHigh, fan_menu.full); - lv_obj_align(labelHigh, buttonHigh, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(labelMid, fan_menu.half); - lv_obj_align(labelMid, buttonMid, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(labelOff, fan_menu.off); - lv_obj_align(labelOff, buttonOff, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonAdd); - lv_group_add_obj(g, buttonDec); - lv_group_add_obj(g, buttonHigh); - lv_group_add_obj(g, buttonMid); - lv_group_add_obj(g, buttonOff); - lv_group_add_obj(g, buttonBack); - } - #endif - - fanText = lv_label_create(scr, NULL); - lv_obj_set_style(fanText, &tft_style_label_rel); - disp_fan_value(); -} - -void disp_fan_value() { - char buf1[10] = {0}; - public_buf_l[0] = '\0'; - strcat(public_buf_l, fan_menu.state); - strcat_P(public_buf_l, PSTR(": ")); - sprintf_P(buf1, PSTR("%3d"), thermalManager.fan_speed[0]); - strcat(public_buf_l, buf1); - lv_label_set_text(fanText, public_buf_l); - lv_obj_align(fanText, NULL, LV_ALIGN_CENTER, 0, -65); -} - -void lv_clear_fan() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_filament_change.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_filament_change.cpp deleted file mode 100644 index 83f9e536774d..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_filament_change.cpp +++ /dev/null @@ -1,270 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "lv_conf.h" -#include "draw_ui.h" - -#include "../../../../MarlinCore.h" -#include "../../../../module/temperature.h" -#include "../../../../gcode/queue.h" -#include "../../../../gcode/gcode.h" -#include "../../../../module/motion.h" -#include "../../../../module/planner.h" - -extern lv_group_t * g; -static lv_obj_t * scr; -static lv_obj_t *buttoType; -static lv_obj_t *labelType; -static lv_obj_t * tempText1; - -#define ID_FILAMNT_IN 1 -#define ID_FILAMNT_OUT 2 -#define ID_FILAMNT_TYPE 3 -#define ID_FILAMNT_RETURN 4 - -extern feedRate_t feedrate_mm_s; - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_FILAMNT_IN: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - uiCfg.filament_load_heat_flg = 1; - if ((abs(thermalManager.temp_hotend[uiCfg.curSprayerChoose].target - thermalManager.temp_hotend[uiCfg.curSprayerChoose].celsius) <= 1) - || (gCfgItems.filament_limit_temper <= thermalManager.temp_hotend[uiCfg.curSprayerChoose].celsius)) { - lv_clear_filament_change(); - lv_draw_dialog(DIALOG_TYPE_FILAMENT_HEAT_LOAD_COMPLETED); - } - else { - lv_clear_filament_change(); - lv_draw_dialog(DIALOG_TYPE_FILAMENT_LOAD_HEAT); - if (thermalManager.temp_hotend[uiCfg.curSprayerChoose].target < gCfgItems.filament_limit_temper) { - thermalManager.temp_hotend[uiCfg.curSprayerChoose].target = gCfgItems.filament_limit_temper; - thermalManager.start_watching_hotend(uiCfg.curSprayerChoose); - } - } - } - break; - case ID_FILAMNT_OUT: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - uiCfg.filament_unload_heat_flg=1; - if ((thermalManager.temp_hotend[uiCfg.curSprayerChoose].target > 0) - && ((abs((int)((int)thermalManager.temp_hotend[uiCfg.curSprayerChoose].target - thermalManager.temp_hotend[uiCfg.curSprayerChoose].celsius)) <= 1) - || ((int)thermalManager.temp_hotend[uiCfg.curSprayerChoose].celsius >= gCfgItems.filament_limit_temper)) - ) { - lv_clear_filament_change(); - lv_draw_dialog(DIALOG_TYPE_FILAMENT_HEAT_UNLOAD_COMPLETED); - } - else { - lv_clear_filament_change(); - lv_draw_dialog(DIALOG_TYPE_FILAMENT_UNLOAD_HEAT); - if (thermalManager.temp_hotend[uiCfg.curSprayerChoose].target < gCfgItems.filament_limit_temper) { - thermalManager.temp_hotend[uiCfg.curSprayerChoose].target = gCfgItems.filament_limit_temper; - thermalManager.start_watching_hotend(uiCfg.curSprayerChoose); - } - filament_sprayer_temp(); - } - } - break; - case ID_FILAMNT_TYPE: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - #if HAS_MULTI_EXTRUDER - if (uiCfg.curSprayerChoose == 0) - uiCfg.curSprayerChoose = 1; - else if (uiCfg.curSprayerChoose == 1) - uiCfg.curSprayerChoose = 0; - #endif - disp_filament_type(); - } - break; - case ID_FILAMNT_RETURN: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - #if HAS_MULTI_EXTRUDER - if (uiCfg.print_state != IDLE && uiCfg.print_state != REPRINTED) - gcode.process_subcommands_now_P(uiCfg.curSprayerChoose_bak == 1 ? PSTR("T1") : PSTR("T0")); - #endif - feedrate_mm_s = (float)uiCfg.moveSpeed_bak; - if (uiCfg.print_state == PAUSED) - planner.set_e_position_mm((destination.e = current_position.e = uiCfg.current_e_position_bak)); - //current_position.e = destination.e = uiCfg.current_e_position_bak; - thermalManager.temp_hotend[uiCfg.curSprayerChoose].target = uiCfg.desireSprayerTempBak; - - clear_cur_ui(); - draw_return_ui(); - } - break; - } -} - -void lv_draw_filament_change(void) { - lv_obj_t *buttonIn, *buttonOut; - lv_obj_t *buttonBack; - - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != FILAMENTCHANGE_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = FILAMENTCHANGE_UI; - } - disp_state = FILAMENTCHANGE_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, creat_title_text()); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - // Create an Image button - buttonIn = lv_imgbtn_create(scr, NULL); - buttonOut = lv_imgbtn_create(scr, NULL); - buttoType = lv_imgbtn_create(scr, NULL); - buttonBack = lv_imgbtn_create(scr, NULL); - - lv_obj_set_event_cb_mks(buttonIn, event_handler, ID_FILAMNT_IN, NULL, 0); - lv_imgbtn_set_src(buttonIn, LV_BTN_STATE_REL, "F:/bmp_in.bin"); - lv_imgbtn_set_src(buttonIn, LV_BTN_STATE_PR, "F:/bmp_in.bin"); - lv_imgbtn_set_style(buttonIn, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonIn, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_clear_protect(buttonIn, LV_PROTECT_FOLLOW); - - lv_obj_set_event_cb_mks(buttonOut, event_handler, ID_FILAMNT_OUT, NULL, 0); - lv_imgbtn_set_src(buttonOut, LV_BTN_STATE_REL, "F:/bmp_out.bin"); - lv_imgbtn_set_src(buttonOut, LV_BTN_STATE_PR, "F:/bmp_out.bin"); - lv_imgbtn_set_style(buttonOut, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonOut, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttoType, event_handler, ID_FILAMNT_TYPE, NULL, 0); - lv_imgbtn_set_style(buttoType, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttoType, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_FILAMNT_RETURN, NULL, 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_return.bin"); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_return.bin"); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_pos(buttonIn, INTERVAL_V, titleHeight); - lv_obj_set_pos(buttonOut, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight); - lv_obj_set_pos(buttoType, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - lv_obj_set_pos(buttonBack, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - - // Create labels on the image buttons - lv_btn_set_layout(buttonIn, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonOut, LV_LAYOUT_OFF); - lv_btn_set_layout(buttoType, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - - lv_obj_t *labelIn = lv_label_create(buttonIn, NULL); - lv_obj_t *labelOut = lv_label_create(buttonOut, NULL); - labelType = lv_label_create(buttoType, NULL); - lv_obj_t *label_Back = lv_label_create(buttonBack, NULL); - - if (gCfgItems.multiple_language != 0) { - lv_label_set_text(labelIn, filament_menu.in); - lv_obj_align(labelIn, buttonIn, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(labelOut, filament_menu.out); - lv_obj_align(labelOut, buttonOut, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonIn); - lv_group_add_obj(g, buttonOut); - lv_group_add_obj(g, buttoType); - lv_group_add_obj(g, buttonBack); - } - #endif - - disp_filament_type(); - - tempText1 = lv_label_create(scr, NULL); - lv_obj_set_style(tempText1, &tft_style_label_rel); - disp_filament_temp(); -} - -void disp_filament_type() { - if (uiCfg.curSprayerChoose == 1) { - lv_imgbtn_set_src(buttoType, LV_BTN_STATE_REL, "F:/bmp_extru2.bin"); - lv_imgbtn_set_src(buttoType, LV_BTN_STATE_PR, "F:/bmp_extru2.bin"); - if (gCfgItems.multiple_language != 0) { - lv_label_set_text(labelType, preheat_menu.ext2); - lv_obj_align(labelType, buttoType, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - } - else { - lv_imgbtn_set_src(buttoType, LV_BTN_STATE_REL, "F:/bmp_extru1.bin"); - lv_imgbtn_set_src(buttoType, LV_BTN_STATE_PR, "F:/bmp_extru1.bin"); - if (gCfgItems.multiple_language != 0) { - lv_label_set_text(labelType, preheat_menu.ext1); - lv_obj_align(labelType, buttoType, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - } -} - -void disp_filament_temp() { - char buf[20] = {0}; - - public_buf_l[0] = '\0'; - - if (uiCfg.curSprayerChoose < 1) - strcat(public_buf_l, preheat_menu.ext1); - else - strcat(public_buf_l, preheat_menu.ext2); - sprintf(buf, preheat_menu.value_state, (int)thermalManager.temp_hotend[uiCfg.curSprayerChoose].celsius, (int)thermalManager.temp_hotend[uiCfg.curSprayerChoose].target); - - strcat_P(public_buf_l, PSTR(": ")); - strcat(public_buf_l, buf); - lv_label_set_text(tempText1, public_buf_l); - lv_obj_align(tempText1, NULL, LV_ALIGN_CENTER, 0, -50); -} - -void lv_clear_filament_change() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_filament_settings.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_filament_settings.cpp deleted file mode 100644 index 06ab35f3f0e5..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_filament_settings.cpp +++ /dev/null @@ -1,329 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "lv_conf.h" -#include "draw_ui.h" - -#include "../../../../MarlinCore.h" -#include "../../../../module/planner.h" - -extern lv_group_t * g; -static lv_obj_t * scr; - -#define ID_FILAMENT_SET_RETURN 1 -#define ID_FILAMENT_SET_IN_LENGTH 2 -#define ID_FILAMENT_SET_IN_SPEED 3 -#define ID_FILAMENT_SET_OUT_LENGTH 4 -#define ID_FILAMENT_SET_OUT_SPEED 5 -#define ID_FILAMENT_SET_TEMP 6 -#define ID_FILAMENT_SET_DOWN 12 -#define ID_FILAMENT_SET_UP 13 - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_FILAMENT_SET_RETURN: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - uiCfg.para_ui_page = 0; - lv_clear_filament_settings(); - draw_return_ui(); - } - break; - case ID_FILAMENT_SET_IN_LENGTH: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = load_length; - lv_clear_filament_settings(); - lv_draw_number_key(); - } - break; - case ID_FILAMENT_SET_IN_SPEED: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = load_speed; - lv_clear_filament_settings(); - lv_draw_number_key(); - } - break; - case ID_FILAMENT_SET_OUT_LENGTH: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = unload_length; - lv_clear_filament_settings(); - lv_draw_number_key(); - } - break; - case ID_FILAMENT_SET_OUT_SPEED: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = unload_speed; - lv_clear_filament_settings(); - lv_draw_number_key(); - } - break; - case ID_FILAMENT_SET_TEMP: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = filament_temp; - lv_clear_filament_settings(); - lv_draw_number_key(); - } - break; - case ID_FILAMENT_SET_UP: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - uiCfg.para_ui_page = 0; - lv_clear_filament_settings(); - lv_draw_filament_settings(); - } - break; - case ID_FILAMENT_SET_DOWN: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - uiCfg.para_ui_page = 1; - lv_clear_filament_settings(); - lv_draw_filament_settings(); - } - break; - } -} - -void lv_draw_filament_settings(void) { - lv_obj_t *buttonBack = NULL, *label_Back = NULL, *buttonTurnPage = NULL, *labelTurnPage = NULL; - lv_obj_t *labelInLengthText = NULL, *buttonInLengthValue = NULL, *labelInLengthValue = NULL; - lv_obj_t *labelInSpeedText = NULL, *buttonInSpeedValue = NULL, *labelInSpeedValue = NULL; - lv_obj_t *labelOutLengthText = NULL, *buttonOutLengthValue = NULL, *labelOutLengthValue = NULL; - lv_obj_t *labelOutSpeedText = NULL, *buttonOutSpeedValue = NULL, *labelOutSpeedValue = NULL; - lv_obj_t *labelTemperText = NULL, *buttonTemperValue = NULL, *labelTemperValue = NULL; - lv_obj_t * line1 = NULL, * line2 = NULL, * line3 = NULL, * line4 = NULL; - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != FILAMENT_SETTINGS_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = FILAMENT_SETTINGS_UI; - } - disp_state = FILAMENT_SETTINGS_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, machine_menu.FilamentConfTitle); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - if (uiCfg.para_ui_page != 1) { - labelInLengthText = lv_label_create(scr, NULL); - lv_obj_set_style(labelInLengthText, &tft_style_label_rel); - lv_obj_set_pos(labelInLengthText, PARA_UI_POS_X, PARA_UI_POS_Y + 10); - lv_label_set_text(labelInLengthText, machine_menu.InLength); - - buttonInLengthValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonInLengthValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y + PARA_UI_VALUE_V_2); - lv_obj_set_size(buttonInLengthValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonInLengthValue, event_handler, ID_FILAMENT_SET_IN_LENGTH, NULL, 0); - lv_btn_set_style(buttonInLengthValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonInLengthValue, LV_BTN_STYLE_PR, &style_para_value); - labelInLengthValue = lv_label_create(buttonInLengthValue, NULL); - - line1 = lv_line_create(scr, NULL); - lv_ex_line(line1, line_points[0]); - - labelInSpeedText = lv_label_create(scr, NULL); - lv_obj_set_style(labelInSpeedText, &tft_style_label_rel); - lv_obj_set_pos(labelInSpeedText, PARA_UI_POS_X, PARA_UI_POS_Y * 2 + 10); - lv_label_set_text(labelInSpeedText, machine_menu.InSpeed); - - buttonInSpeedValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonInSpeedValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 2 + PARA_UI_VALUE_V_2); - lv_obj_set_size(buttonInSpeedValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonInSpeedValue, event_handler, ID_FILAMENT_SET_IN_SPEED, NULL, 0); - lv_btn_set_style(buttonInSpeedValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonInSpeedValue, LV_BTN_STYLE_PR, &style_para_value); - labelInSpeedValue = lv_label_create(buttonInSpeedValue, NULL); - - line2 = lv_line_create(scr, NULL); - lv_ex_line(line2, line_points[1]); - - labelOutLengthText = lv_label_create(scr, NULL); - lv_obj_set_style(labelOutLengthText, &tft_style_label_rel); - lv_obj_set_pos(labelOutLengthText, PARA_UI_POS_X, PARA_UI_POS_Y * 3 + 6); - lv_label_set_text(labelOutLengthText, machine_menu.OutLength); - - buttonOutLengthValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonOutLengthValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 3 + PARA_UI_VALUE_V_2); - lv_obj_set_size(buttonOutLengthValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonOutLengthValue, event_handler, ID_FILAMENT_SET_OUT_LENGTH, NULL, 0); - lv_btn_set_style(buttonOutLengthValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonOutLengthValue, LV_BTN_STYLE_PR, &style_para_value); - labelOutLengthValue = lv_label_create(buttonOutLengthValue, NULL); - - line3 = lv_line_create(scr, NULL); - lv_ex_line(line3, line_points[2]); - - labelOutSpeedText = lv_label_create(scr, NULL); - lv_obj_set_style(labelOutSpeedText, &tft_style_label_rel); - lv_obj_set_pos(labelOutSpeedText, PARA_UI_POS_X, PARA_UI_POS_Y * 4 + 10); - lv_label_set_text(labelOutSpeedText, machine_menu.OutSpeed); - - buttonOutSpeedValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonOutSpeedValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 4 + PARA_UI_VALUE_V_2); - lv_obj_set_size(buttonOutSpeedValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonOutSpeedValue, event_handler, ID_FILAMENT_SET_OUT_SPEED, NULL, 0); - lv_btn_set_style(buttonOutSpeedValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonOutSpeedValue, LV_BTN_STYLE_PR, &style_para_value); - labelOutSpeedValue = lv_label_create(buttonOutSpeedValue, NULL); - - line4 = lv_line_create(scr, NULL); - lv_ex_line(line4, line_points[3]); - - buttonTurnPage = lv_btn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_FILAMENT_SET_DOWN, NULL, 0); - lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_REL, &style_para_back); - lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_PR, &style_para_back); - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonInLengthValue); - lv_group_add_obj(g, buttonInSpeedValue); - lv_group_add_obj(g, buttonOutLengthValue); - lv_group_add_obj(g, buttonOutSpeedValue); - lv_group_add_obj(g, buttonTurnPage); - } - #endif - } - else { - labelTemperText = lv_label_create(scr, NULL); - lv_obj_set_style(labelTemperText, &tft_style_label_rel); - lv_obj_set_pos(labelTemperText, PARA_UI_POS_X, PARA_UI_POS_Y + 10); - lv_label_set_text(labelTemperText, machine_menu.FilamentTemperature); - - buttonTemperValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonTemperValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y + PARA_UI_VALUE_V_2); - lv_obj_set_size(buttonTemperValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonTemperValue, event_handler, ID_FILAMENT_SET_TEMP, NULL, 0); - lv_btn_set_style(buttonTemperValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonTemperValue, LV_BTN_STYLE_PR, &style_para_value); - labelTemperValue = lv_label_create(buttonTemperValue, NULL); - - line1 = lv_line_create(scr, NULL); - lv_ex_line(line1, line_points[0]); - - buttonTurnPage = lv_btn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_FILAMENT_SET_UP, NULL, 0); - lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_REL, &style_para_back); - lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_PR, &style_para_back); - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonTemperValue); - lv_group_add_obj(g, buttonTurnPage); - } - #endif - } - - lv_obj_set_pos(buttonTurnPage, PARA_UI_TURN_PAGE_POS_X, PARA_UI_TURN_PAGE_POS_Y); - lv_obj_set_size(buttonTurnPage, PARA_UI_BACK_BTN_X_SIZE, PARA_UI_BACK_BTN_Y_SIZE); - labelTurnPage = lv_label_create(buttonTurnPage, NULL); - - buttonBack = lv_btn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_FILAMENT_SET_RETURN, NULL, 0); - lv_btn_set_style(buttonBack, LV_BTN_STYLE_REL, &style_para_back); - lv_btn_set_style(buttonBack, LV_BTN_STYLE_PR, &style_para_back); - lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); - lv_obj_set_size(buttonBack, PARA_UI_BACK_BTN_X_SIZE, PARA_UI_BACK_BTN_Y_SIZE); - label_Back = lv_label_create(buttonBack, NULL); - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonBack); - #endif - - if (gCfgItems.multiple_language != 0) { - if (uiCfg.para_ui_page != 1) { - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%d"), gCfgItems.filamentchange_load_length); - lv_label_set_text(labelInLengthValue, public_buf_l); - lv_obj_align(labelInLengthValue, buttonInLengthValue, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%d"), gCfgItems.filamentchange_load_speed); - lv_label_set_text(labelInSpeedValue, public_buf_l); - lv_obj_align(labelInSpeedValue, buttonInSpeedValue, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%d"), gCfgItems.filamentchange_unload_length); - lv_label_set_text(labelOutLengthValue, public_buf_l); - lv_obj_align(labelOutLengthValue, buttonOutLengthValue, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%d"), gCfgItems.filamentchange_unload_speed); - lv_label_set_text(labelOutSpeedValue, public_buf_l); - lv_obj_align(labelOutSpeedValue, buttonOutSpeedValue, LV_ALIGN_CENTER, 0, 0); - - lv_label_set_text(labelTurnPage, machine_menu.next); - lv_obj_align(labelTurnPage, buttonTurnPage, LV_ALIGN_CENTER, 0, 0); - } - else { - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%d"), gCfgItems.filament_limit_temper); - lv_label_set_text(labelTemperValue, public_buf_l); - lv_obj_align(labelTemperValue, buttonTemperValue, LV_ALIGN_CENTER, 0, 0); - - lv_label_set_text(labelTurnPage, machine_menu.previous); - lv_obj_align(labelTurnPage, buttonTurnPage, LV_ALIGN_CENTER, 0, 0); - } - - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_CENTER, 0, 0); - } -} - -void lv_clear_filament_settings() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_home.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_home.cpp deleted file mode 100644 index 22e05f0e00e5..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_home.cpp +++ /dev/null @@ -1,252 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "../../../../MarlinCore.h" -#include "draw_ready_print.h" -#include "draw_set.h" -#include "lv_conf.h" -//#include "../lvgl/src/lv_objx/lv_imgbtn.h" -//#include "../lvgl/src/lv_objx/lv_img.h" -//#include "../lvgl/src/lv_core/lv_disp.h" -//#include "../lvgl/src/lv_core/lv_refr.h" -#include "draw_ui.h" -#include "../../../../gcode/queue.h" - -extern lv_group_t * g; -static lv_obj_t * scr; - -#define ID_H_ALL 1 -#define ID_H_X 2 -#define ID_H_Y 3 -#define ID_H_Z 4 -#define ID_H_RETURN 5 -#define ID_H_OFF_ALL 6 -#define ID_H_OFF_XY 7 - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_H_ALL: - if (event == LV_EVENT_CLICKED) { - } - else if (event == LV_EVENT_RELEASED) { - queue.inject_P(PSTR("G28")); - } - break; - case ID_H_X: - if (event == LV_EVENT_CLICKED) { - } - else if (event == LV_EVENT_RELEASED) { - queue.inject_P(PSTR("G28 X0")); - } - break; - case ID_H_Y: - if (event == LV_EVENT_CLICKED) { - } - else if (event == LV_EVENT_RELEASED) { - queue.inject_P(PSTR("G28 Y0")); - } - break; - case ID_H_Z: - if (event == LV_EVENT_CLICKED) { - } - else if (event == LV_EVENT_RELEASED) { - queue.inject_P(PSTR("G28 Z0")); - } - break; - case ID_H_OFF_ALL: - if (event == LV_EVENT_CLICKED) { - } - else if (event == LV_EVENT_RELEASED) { - queue.inject_P(PSTR("M84")); - } - break; - case ID_H_OFF_XY: - if (event == LV_EVENT_CLICKED) { - } - else if (event == LV_EVENT_RELEASED) { - queue.inject_P(PSTR("M84 X Y")); - } - break; - case ID_H_RETURN: - if (event == LV_EVENT_CLICKED) { - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_home(); - lv_draw_tool(); - } - break; - } -} - -void lv_draw_home(void) { - lv_obj_t *buttonHomeAll, *buttonHomeX, *buttonHomeY, *buttonHomeZ; - lv_obj_t *buttonBack; - lv_obj_t *buttonOffAll, *buttonOffXY; - - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != ZERO_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = ZERO_UI; - } - disp_state = ZERO_UI; - - scr = lv_obj_create(NULL, NULL); - - //static lv_style_t tool_style; - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, creat_title_text()); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - // Create image buttons - //buttonWifi = lv_imgbtn_create(scr, NULL); - buttonHomeAll = lv_imgbtn_create(scr, NULL); - buttonHomeX = lv_imgbtn_create(scr, NULL); - //buttonContinue = lv_imgbtn_create(scr, NULL); - buttonHomeY = lv_imgbtn_create(scr, NULL); - buttonHomeZ = lv_imgbtn_create(scr, NULL); - buttonOffAll = lv_imgbtn_create(scr, NULL); - buttonOffXY = lv_imgbtn_create(scr, NULL); - buttonBack = lv_imgbtn_create(scr, NULL); - - #if 1 - lv_obj_set_event_cb_mks(buttonHomeAll, event_handler,ID_H_ALL, NULL,0); - lv_imgbtn_set_src(buttonHomeAll, LV_BTN_STATE_REL, "F:/bmp_zeroAll.bin"); - lv_imgbtn_set_src(buttonHomeAll, LV_BTN_STATE_PR, "F:/bmp_zeroAll.bin"); - lv_imgbtn_set_style(buttonHomeAll, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonHomeAll, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonHomeX, event_handler, ID_H_X, NULL, 0); - lv_imgbtn_set_src(buttonHomeX, LV_BTN_STATE_REL, "F:/bmp_zeroX.bin"); - lv_imgbtn_set_src(buttonHomeX, LV_BTN_STATE_PR, "F:/bmp_zeroX.bin"); - lv_imgbtn_set_style(buttonHomeX, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonHomeX, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonHomeY, event_handler, ID_H_Y, NULL, 0); - lv_imgbtn_set_src(buttonHomeY, LV_BTN_STATE_REL, "F:/bmp_zeroY.bin"); - lv_imgbtn_set_src(buttonHomeY, LV_BTN_STATE_PR, "F:/bmp_zeroY.bin"); - lv_imgbtn_set_style(buttonHomeY, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonHomeY, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonHomeZ, event_handler, ID_H_Z, NULL, 0); - lv_imgbtn_set_src(buttonHomeZ, LV_BTN_STATE_REL, "F:/bmp_zeroZ.bin"); - lv_imgbtn_set_src(buttonHomeZ, LV_BTN_STATE_PR, "F:/bmp_zeroZ.bin"); - lv_imgbtn_set_style(buttonHomeZ, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonHomeZ, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonOffAll, event_handler,ID_H_OFF_ALL, NULL,0); - lv_imgbtn_set_src(buttonOffAll, LV_BTN_STATE_REL, "F:/bmp_function1.bin"); - lv_imgbtn_set_src(buttonOffAll, LV_BTN_STATE_PR, "F:/bmp_function1.bin"); - lv_imgbtn_set_style(buttonOffAll, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonOffAll, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonOffXY, event_handler,ID_H_OFF_XY, NULL,0); - lv_imgbtn_set_src(buttonOffXY, LV_BTN_STATE_REL, "F:/bmp_function1.bin"); - lv_imgbtn_set_src(buttonOffXY, LV_BTN_STATE_PR, "F:/bmp_function1.bin"); - lv_imgbtn_set_style(buttonOffXY, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonOffXY, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonBack, event_handler,ID_H_RETURN, NULL,0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_return.bin"); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_return.bin"); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); - #endif - - lv_obj_set_pos(buttonHomeAll, INTERVAL_V, titleHeight); - lv_obj_set_pos(buttonHomeX, BTN_X_PIXEL + INTERVAL_V * 2, titleHeight); - lv_obj_set_pos(buttonHomeY, BTN_X_PIXEL * 2 + INTERVAL_V * 3, titleHeight); - lv_obj_set_pos(buttonHomeZ, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight); - lv_obj_set_pos(buttonOffAll, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - lv_obj_set_pos(buttonOffXY, BTN_X_PIXEL + INTERVAL_V * 2, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - lv_obj_set_pos(buttonBack, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - - // Create labels on the image buttons - lv_btn_set_layout(buttonHomeAll, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonHomeX, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonHomeY, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonHomeZ, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonOffAll, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonOffXY, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - - lv_obj_t *labelHomeAll = lv_label_create(buttonHomeAll, NULL); - lv_obj_t *labelHomeX = lv_label_create(buttonHomeX, NULL); - lv_obj_t *labelHomeY = lv_label_create(buttonHomeY, NULL); - lv_obj_t *labelHomeZ = lv_label_create(buttonHomeZ, NULL); - lv_obj_t *labelOffAll = lv_label_create(buttonOffAll, NULL); - lv_obj_t *labelOffXY = lv_label_create(buttonOffXY, NULL); - lv_obj_t *label_Back = lv_label_create(buttonBack, NULL); - - if (gCfgItems.multiple_language != 0) { - lv_label_set_text(labelHomeAll, home_menu.home_all); - lv_obj_align(labelHomeAll, buttonHomeAll, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(labelHomeX, home_menu.home_x); - lv_obj_align(labelHomeX, buttonHomeX, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(labelHomeY, home_menu.home_y); - lv_obj_align(labelHomeY, buttonHomeY, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(labelHomeZ, home_menu.home_z); - lv_obj_align(labelHomeZ, buttonHomeZ, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(labelOffAll, set_menu.motoroff); - lv_obj_align(labelOffAll, buttonOffAll, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(labelOffXY, set_menu.motoroffXY); - lv_obj_align(labelOffXY, buttonOffXY, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonHomeAll); - lv_group_add_obj(g, buttonHomeX); - lv_group_add_obj(g, buttonHomeY); - lv_group_add_obj(g, buttonHomeZ); - lv_group_add_obj(g, buttonOffAll); - lv_group_add_obj(g, buttonOffXY); - lv_group_add_obj(g, buttonBack); - } - #endif -} - -void lv_clear_home() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_homing_sensitivity_settings.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_homing_sensitivity_settings.cpp deleted file mode 100644 index d22eeb157e18..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_homing_sensitivity_settings.cpp +++ /dev/null @@ -1,262 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "lv_conf.h" -#include "draw_ui.h" - -#include "../../../../MarlinCore.h" -#include "../../../../module/planner.h" -#include "../../../../module/probe.h" - -#if USE_SENSORLESS -#include "../../../../module/stepper/indirection.h" -#include "../../../../feature/tmc_util.h" - -extern lv_group_t * g; -static lv_obj_t * scr; - -#define ID_SENSITIVITY_RETURN 1 -#define ID_SENSITIVITY_X 2 -#define ID_SENSITIVITY_Y 3 -#define ID_SENSITIVITY_Z 4 -#define ID_SENSITIVITY_Z2 5 - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_SENSITIVITY_RETURN: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_homing_sensitivity_settings(); - draw_return_ui(); - } - break; - case ID_SENSITIVITY_X: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = x_sensitivity; - lv_clear_homing_sensitivity_settings(); - lv_draw_number_key(); - } - break; - case ID_SENSITIVITY_Y: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = y_sensitivity; - lv_clear_homing_sensitivity_settings(); - lv_draw_number_key(); - } - break; - case ID_SENSITIVITY_Z: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = z_sensitivity; - lv_clear_homing_sensitivity_settings(); - lv_draw_number_key(); - } - break; - #if Z2_SENSORLESS - case ID_SENSITIVITY_Z2: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = z2_sensitivity; - lv_clear_homing_sensitivity_settings(); - lv_draw_number_key(); - } - break; - #endif - } -} - -void lv_draw_homing_sensitivity_settings(void) { - lv_obj_t *buttonBack = NULL, *label_Back = NULL; - lv_obj_t *labelXText = NULL, *buttonXValue = NULL, *labelXValue = NULL; - lv_obj_t *labelYText = NULL, *buttonYValue = NULL, *labelYValue = NULL; - lv_obj_t *labelZText = NULL, *buttonZValue = NULL, *labelZValue = NULL; - lv_obj_t * line1 = NULL, * line2 = NULL, * line3 = NULL; - #if Z2_SENSORLESS - lv_obj_t *labelZ2Text = NULL, *buttonZ2Value = NULL, *labelZ2Value = NULL; - lv_obj_t * line4 = NULL; - #endif - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != HOMING_SENSITIVITY_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = HOMING_SENSITIVITY_UI; - } - disp_state = HOMING_SENSITIVITY_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, machine_menu.HomingSensitivityConfTitle); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - labelXText = lv_label_create(scr, NULL); - lv_obj_set_style(labelXText, &tft_style_label_rel); - lv_obj_set_pos(labelXText, PARA_UI_POS_X, PARA_UI_POS_Y + 10); - lv_label_set_text(labelXText, machine_menu.X_Sensitivity); - - buttonXValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonXValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y + PARA_UI_VALUE_V_2); - lv_obj_set_size(buttonXValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonXValue, event_handler, ID_SENSITIVITY_X, NULL, 0); - lv_btn_set_style(buttonXValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonXValue, LV_BTN_STYLE_PR, &style_para_value); - labelXValue = lv_label_create(buttonXValue, NULL); - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonXValue); - #endif - - line1 = lv_line_create(scr, NULL); - lv_ex_line(line1, line_points[0]); - - labelYText = lv_label_create(scr, NULL); - lv_obj_set_style(labelYText, &tft_style_label_rel); - lv_obj_set_pos(labelYText, PARA_UI_POS_X, PARA_UI_POS_Y * 2 + 10); - lv_label_set_text(labelYText, machine_menu.Y_Sensitivity); - - buttonYValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonYValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 2 + PARA_UI_VALUE_V_2); - lv_obj_set_size(buttonYValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonYValue, event_handler, ID_SENSITIVITY_Y, NULL, 0); - lv_btn_set_style(buttonYValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonYValue, LV_BTN_STYLE_PR, &style_para_value); - labelYValue = lv_label_create(buttonYValue, NULL); - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonYValue); - #endif - - line2 = lv_line_create(scr, NULL); - lv_ex_line(line2, line_points[1]); - - labelZText = lv_label_create(scr, NULL); - lv_obj_set_style(labelZText, &tft_style_label_rel); - lv_obj_set_pos(labelZText, PARA_UI_POS_X, PARA_UI_POS_Y * 3 + 10); - lv_label_set_text(labelZText, machine_menu.Z_Sensitivity); - - buttonZValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonZValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 3 + PARA_UI_VALUE_V_2); - lv_obj_set_size(buttonZValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonZValue, event_handler, ID_SENSITIVITY_Z, NULL, 0); - lv_btn_set_style(buttonZValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonZValue, LV_BTN_STYLE_PR, &style_para_value); - labelZValue = lv_label_create(buttonZValue, NULL); - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable == true) lv_group_add_obj(g, buttonZValue); - #endif - - line3 = lv_line_create(scr, NULL); - lv_ex_line(line3, line_points[2]); - - #if Z2_SENSORLESS - labelZ2Text = lv_label_create(scr, NULL); - lv_obj_set_style(labelZ2Text, &tft_style_label_rel); - lv_obj_set_pos(labelZ2Text, PARA_UI_POS_X, PARA_UI_POS_Y * 4 + 10); - lv_label_set_text(labelZ2Text, machine_menu.Z2_Sensitivity); - - buttonZ2Value = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonZ2Value, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 4 + PARA_UI_VALUE_V_2); - lv_obj_set_size(buttonZ2Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonZ2Value, event_handler, ID_SENSITIVITY_Z2, NULL, 0); - lv_btn_set_style(buttonZ2Value, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonZ2Value, LV_BTN_STYLE_PR, &style_para_value); - labelZ2Value = lv_label_create(buttonZ2Value, NULL); - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonZ2Value); - #endif - - line4 = lv_line_create(scr, NULL); - lv_ex_line(line4, line_points[3]); - #endif - - buttonBack = lv_btn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_SENSITIVITY_RETURN, NULL, 0); - lv_btn_set_style(buttonBack, LV_BTN_STYLE_REL, &style_para_back); - lv_btn_set_style(buttonBack, LV_BTN_STYLE_PR, &style_para_back); - lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); - lv_obj_set_size(buttonBack, PARA_UI_BACK_BTN_X_SIZE, PARA_UI_BACK_BTN_Y_SIZE); - label_Back = lv_label_create(buttonBack, NULL); - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonBack); - #endif - - if (gCfgItems.multiple_language != 0) { - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%d"), TERN(X_SENSORLESS, stepperX.homing_threshold(), 0)); - lv_label_set_text(labelXValue, public_buf_l); - lv_obj_align(labelXValue, buttonXValue, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%d"), TERN(Y_SENSORLESS, stepperY.homing_threshold(), 0)); - lv_label_set_text(labelYValue, public_buf_l); - lv_obj_align(labelYValue, buttonYValue, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%d"), TERN(Z_SENSORLESS, stepperZ.homing_threshold(), 0)); - lv_label_set_text(labelZValue, public_buf_l); - lv_obj_align(labelZValue, buttonZValue, LV_ALIGN_CENTER, 0, 0); - - #if Z2_SENSORLESS - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%d"), TERN(Z2_SENSORLESS, stepperZ2.homing_threshold(), 0)); - lv_label_set_text(labelZ2Value, public_buf_l); - lv_obj_align(labelZ2Value, buttonZ2Value, LV_ALIGN_CENTER, 0, 0); - #endif - - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_CENTER, 0, 0); - } -} - -void lv_clear_homing_sensitivity_settings() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // USE_SENSORLESS - -#endif // HAS_TFT_LVGL_UI && USE_SENSORLESS diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_jerk_settings.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_jerk_settings.cpp deleted file mode 100644 index 8c359233e6ea..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_jerk_settings.cpp +++ /dev/null @@ -1,237 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if BOTH(HAS_TFT_LVGL_UI, HAS_CLASSIC_JERK) - -#include "lv_conf.h" -#include "draw_ui.h" - -#include "../../../../MarlinCore.h" -#include "../../../../module/planner.h" - -extern lv_group_t * g; -static lv_obj_t * scr; - -#define ID_JERK_RETURN 1 -#define ID_JERK_X 2 -#define ID_JERK_Y 3 -#define ID_JERK_Z 4 -#define ID_JERK_E 5 - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_JERK_RETURN: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_jerk_settings(); - draw_return_ui(); - } - break; - case ID_JERK_X: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = XJerk; - lv_clear_jerk_settings(); - lv_draw_number_key(); - } - break; - case ID_JERK_Y: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = YJerk; - lv_clear_jerk_settings(); - lv_draw_number_key(); - } - break; - case ID_JERK_Z: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = ZJerk; - lv_clear_jerk_settings(); - lv_draw_number_key(); - } - break; - case ID_JERK_E: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = EJerk; - lv_clear_jerk_settings(); - lv_draw_number_key(); - } - break; - } -} - -void lv_draw_jerk_settings(void) { - lv_obj_t *buttonBack = NULL, *label_Back = NULL; - lv_obj_t *labelXText = NULL, *buttonXValue = NULL, *labelXValue = NULL; - lv_obj_t *labelYText = NULL, *buttonYValue = NULL, *labelYValue = NULL; - lv_obj_t *labelZText = NULL, *buttonZValue = NULL, *labelZValue = NULL; - lv_obj_t *labelEText = NULL, *buttonEValue = NULL, *labelEValue = NULL; - lv_obj_t * line1 = NULL, * line2 = NULL, * line3 = NULL, * line4 = NULL; - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != JERK_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = JERK_UI; - } - disp_state = JERK_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, machine_menu.JerkConfTitle); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - labelXText = lv_label_create(scr, NULL); - lv_obj_set_style(labelXText, &tft_style_label_rel); - lv_obj_set_pos(labelXText, PARA_UI_POS_X, PARA_UI_POS_Y + 10); - lv_label_set_text(labelXText, machine_menu.X_Jerk); - - buttonXValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonXValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y + PARA_UI_VALUE_V); - lv_obj_set_size(buttonXValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonXValue, event_handler, ID_JERK_X, NULL, 0); - lv_btn_set_style(buttonXValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonXValue, LV_BTN_STYLE_PR, &style_para_value); - labelXValue = lv_label_create(buttonXValue, NULL); - - line1 = lv_line_create(scr, NULL); - lv_ex_line(line1, line_points[0]); - - labelYText = lv_label_create(scr, NULL); - lv_obj_set_style(labelYText, &tft_style_label_rel); - lv_obj_set_pos(labelYText, PARA_UI_POS_X, PARA_UI_POS_Y * 2 + 10); - lv_label_set_text(labelYText, machine_menu.Y_Jerk); - - buttonYValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonYValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 2 + PARA_UI_VALUE_V); - lv_obj_set_size(buttonYValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonYValue, event_handler, ID_JERK_Y, NULL, 0); - lv_btn_set_style(buttonYValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonYValue, LV_BTN_STYLE_PR, &style_para_value); - labelYValue = lv_label_create(buttonYValue, NULL); - - line2 = lv_line_create(scr, NULL); - lv_ex_line(line2, line_points[1]); - - labelZText = lv_label_create(scr, NULL); - lv_obj_set_style(labelZText, &tft_style_label_rel); - lv_obj_set_pos(labelZText, PARA_UI_POS_X, PARA_UI_POS_Y * 3 + 10); - lv_label_set_text(labelZText, machine_menu.Z_Jerk); - - buttonZValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonZValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 3 + PARA_UI_VALUE_V); - lv_obj_set_size(buttonZValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonZValue, event_handler, ID_JERK_Z, NULL, 0); - lv_btn_set_style(buttonZValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonZValue, LV_BTN_STYLE_PR, &style_para_value); - labelZValue = lv_label_create(buttonZValue, NULL); - - line3 = lv_line_create(scr, NULL); - lv_ex_line(line3, line_points[2]); - - labelEText = lv_label_create(scr, NULL); - lv_obj_set_style(labelEText, &tft_style_label_rel); - lv_obj_set_pos(labelEText, PARA_UI_POS_X, PARA_UI_POS_Y * 4 + 10); - lv_label_set_text(labelEText, machine_menu.E_Jerk); - - buttonEValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonEValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 4 + PARA_UI_VALUE_V); - lv_obj_set_size(buttonEValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonEValue, event_handler, ID_JERK_E, NULL, 0); - lv_btn_set_style(buttonEValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonEValue, LV_BTN_STYLE_PR, &style_para_value); - labelEValue = lv_label_create(buttonEValue, NULL); - - line4 = lv_line_create(scr, NULL); - lv_ex_line(line4, line_points[3]); - - buttonBack = lv_btn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_JERK_RETURN, NULL, 0); - lv_btn_set_style(buttonBack, LV_BTN_STYLE_REL, &style_para_back); - lv_btn_set_style(buttonBack, LV_BTN_STYLE_PR, &style_para_back); - - lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); - lv_obj_set_size(buttonBack, PARA_UI_BACK_BTN_X_SIZE, PARA_UI_BACK_BTN_Y_SIZE); - label_Back = lv_label_create(buttonBack, NULL); - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable == true) { - lv_group_add_obj(g, buttonXValue); - lv_group_add_obj(g, buttonYValue); - lv_group_add_obj(g, buttonZValue); - lv_group_add_obj(g, buttonEValue); - lv_group_add_obj(g, buttonBack); - } - #endif - - if (gCfgItems.multiple_language != 0) { - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%.1f"), planner.max_jerk[X_AXIS]); - lv_label_set_text(labelXValue, public_buf_l); - lv_obj_align(labelXValue, buttonXValue, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%.1f"), planner.max_jerk[Y_AXIS]); - lv_label_set_text(labelYValue, public_buf_l); - lv_obj_align(labelYValue, buttonYValue, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%.1f"), planner.max_jerk[Z_AXIS]); - lv_label_set_text(labelZValue, public_buf_l); - lv_obj_align(labelZValue, buttonZValue, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%.1f"), planner.max_jerk[E_AXIS]); - lv_label_set_text(labelEValue, public_buf_l); - lv_obj_align(labelEValue, buttonEValue, LV_ALIGN_CENTER, 0, 0); - - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_CENTER, 0, 0); - } -} - -void lv_clear_jerk_settings() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI && HAS_CLASSIC_JERK diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_language.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_language.cpp deleted file mode 100644 index 3e4ad06477cd..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_language.cpp +++ /dev/null @@ -1,401 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "lv_conf.h" -#include "draw_ui.h" -//#include "../lvgl/src/lv_objx/lv_imgbtn.h" -//#include "../lvgl/src/lv_objx/lv_img.h" -//#include "../lvgl/src/lv_core/lv_disp.h" -//#include "../lvgl/src/lv_core/lv_refr.h" - -#include "../../../../MarlinCore.h" -#include - -//static lv_obj_t *buttonMoveZ,*buttonTest,*buttonZ0,*buttonStop,*buttonReturn; - -#define ID_CN 1 -#define ID_T_CN 2 -#define ID_EN 3 -#define ID_RU 4 -#define ID_ES 5 -#define ID_FR 6 -#define ID_IT 7 -#define ID_L_RETURN 8 - -#define SELECTED 1 -#define UNSELECTED 0 - -static void disp_language(uint8_t language, uint8_t state); - -extern lv_group_t * g; -static lv_obj_t * scr; -static lv_obj_t *buttonCN, *buttonT_CN, *buttonEN, *buttonRU; -static lv_obj_t *buttonES, *buttonFR, *buttonIT, *buttonBack; - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_CN: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - disp_language(gCfgItems.language, UNSELECTED); - lv_imgbtn_set_src(buttonCN, LV_BTN_STATE_REL, "F:/bmp_simplified_cn_sel.bin"); - lv_imgbtn_set_src(buttonCN, LV_BTN_STATE_PR, "F:/bmp_simplified_cn_sel.bin"); - lv_obj_refresh_ext_draw_pad(buttonCN); - gCfgItems.language = LANG_SIMPLE_CHINESE; - update_spi_flash(); - disp_language_init(); - } - break; - case ID_T_CN: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - disp_language(gCfgItems.language, UNSELECTED); - lv_imgbtn_set_src(buttonT_CN, LV_BTN_STATE_REL, "F:/bmp_traditional_cn_sel.bin"); - lv_imgbtn_set_src(buttonT_CN, LV_BTN_STATE_PR, "F:/bmp_traditional_cn_sel.bin"); - lv_obj_refresh_ext_draw_pad(buttonT_CN); - gCfgItems.language = LANG_COMPLEX_CHINESE; - update_spi_flash(); - disp_language_init(); - } - break; - case ID_EN: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - disp_language(gCfgItems.language, UNSELECTED); - lv_imgbtn_set_src(buttonEN, LV_BTN_STATE_REL, "F:/bmp_english_sel.bin"); - lv_imgbtn_set_src(buttonEN, LV_BTN_STATE_PR, "F:/bmp_english_sel.bin"); - lv_obj_refresh_ext_draw_pad(buttonEN); - gCfgItems.language = LANG_ENGLISH; - update_spi_flash(); - disp_language_init(); - } - break; - case ID_RU: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - disp_language(gCfgItems.language, UNSELECTED); - lv_imgbtn_set_src(buttonRU, LV_BTN_STATE_REL, "F:/bmp_russian_sel.bin"); - lv_imgbtn_set_src(buttonRU, LV_BTN_STATE_PR, "F:/bmp_russian_sel.bin"); - lv_obj_refresh_ext_draw_pad(buttonRU); - gCfgItems.language = LANG_RUSSIAN; - update_spi_flash(); - disp_language_init(); - } - break; - case ID_ES: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - disp_language(gCfgItems.language, UNSELECTED); - lv_imgbtn_set_src(buttonES, LV_BTN_STATE_REL, "F:/bmp_spanish_sel.bin"); - lv_imgbtn_set_src(buttonES, LV_BTN_STATE_PR, "F:/bmp_spanish_sel.bin"); - lv_obj_refresh_ext_draw_pad(buttonES); - gCfgItems.language = LANG_SPANISH; - update_spi_flash(); - disp_language_init(); - } - break; - case ID_FR: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - disp_language(gCfgItems.language, UNSELECTED); - lv_imgbtn_set_src(buttonFR, LV_BTN_STATE_REL, "F:/bmp_french_sel.bin"); - lv_imgbtn_set_src(buttonFR, LV_BTN_STATE_PR, "F:/bmp_french_sel.bin"); - lv_obj_refresh_ext_draw_pad(buttonFR); - gCfgItems.language = LANG_FRENCH; - update_spi_flash(); - disp_language_init(); - } - break; - case ID_IT: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - disp_language(gCfgItems.language, UNSELECTED); - lv_imgbtn_set_src(buttonIT, LV_BTN_STATE_REL, "F:/bmp_italy_sel.bin"); - lv_imgbtn_set_src(buttonIT, LV_BTN_STATE_PR, "F:/bmp_italy_sel.bin"); - lv_obj_refresh_ext_draw_pad(buttonIT); - gCfgItems.language = LANG_ITALY; - update_spi_flash(); - disp_language_init(); - } - break; - case ID_L_RETURN: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - - buttonCN = NULL; - buttonT_CN = NULL; - buttonEN = NULL; - buttonRU = NULL; - buttonES = NULL; - buttonFR = NULL; - buttonFR = NULL; - buttonIT = NULL; - buttonBack = NULL; - lv_clear_language(); - lv_draw_set(); - } - break; - - } -} - -static void disp_language(uint8_t language, uint8_t state) { - uint16_t id; - lv_obj_t *obj; - - public_buf_l[0] = '\0'; - - switch (language) { - case LANG_SIMPLE_CHINESE: - id = ID_CN; - strcpy_P(public_buf_l, PSTR("F:/bmp_simplified_cn")); - obj = buttonCN; - break; - case LANG_COMPLEX_CHINESE: - id = ID_T_CN; - strcpy_P(public_buf_l, PSTR("F:/bmp_traditional_cn")); - obj = buttonT_CN; - break; - case LANG_ENGLISH: - id = ID_EN; - strcpy_P(public_buf_l, PSTR("F:/bmp_english")); - obj = buttonEN; - break; - case LANG_RUSSIAN: - id = ID_RU; - strcpy_P(public_buf_l, PSTR("F:/bmp_russian")); - obj = buttonRU; - break; - case LANG_SPANISH: - id = ID_ES; - strcpy_P(public_buf_l, PSTR("F:/bmp_spanish")); - obj = buttonES; - break; - case LANG_FRENCH: - id = ID_FR; - strcpy_P(public_buf_l, PSTR("F:/bmp_french")); - obj = buttonFR; - break; - case LANG_ITALY: - id = ID_IT; - strcpy_P(public_buf_l, PSTR("F:/bmp_italy")); - obj = buttonIT; - break; - default: - id = ID_CN; - strcpy_P(public_buf_l, PSTR("F:/bmp_simplified_cn")); - obj = buttonCN; - break; - } - - if (state == SELECTED) strcat_P(public_buf_l, PSTR("_sel")); - - strcat_P(public_buf_l, PSTR(".bin")); - - lv_obj_set_event_cb_mks(obj, event_handler, id, NULL, 0); - lv_imgbtn_set_src(obj, LV_BTN_STATE_REL, public_buf_l); - lv_imgbtn_set_src(obj, LV_BTN_STATE_PR, public_buf_l); - - if (state == UNSELECTED) lv_obj_refresh_ext_draw_pad(obj); -} - -void lv_draw_language(void) { - - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != LANGUAGE_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = LANGUAGE_UI; - } - disp_state = LANGUAGE_UI; - - scr = lv_obj_create(NULL, NULL); - - // static lv_style_t tool_style; - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, creat_title_text()); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - // Create image buttons - buttonCN = lv_imgbtn_create(scr, NULL); - buttonT_CN = lv_imgbtn_create(scr, NULL); - buttonEN = lv_imgbtn_create(scr, NULL); - buttonRU = lv_imgbtn_create(scr, NULL); - buttonES = lv_imgbtn_create(scr, NULL); - buttonFR = lv_imgbtn_create(scr, NULL); - buttonIT = lv_imgbtn_create(scr, NULL); - buttonBack = lv_imgbtn_create(scr, NULL); - - lv_obj_set_event_cb_mks(buttonCN, event_handler, ID_CN, NULL, 0); - lv_imgbtn_set_src(buttonCN, LV_BTN_STATE_REL, "F:/bmp_simplified_cn.bin"); - lv_imgbtn_set_src(buttonCN, LV_BTN_STATE_PR, "F:/bmp_simplified_cn.bin"); - lv_imgbtn_set_style(buttonCN, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonCN, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_clear_protect(buttonCN, LV_PROTECT_FOLLOW); - - #if 1 - lv_obj_set_event_cb_mks(buttonT_CN, event_handler, ID_T_CN, NULL, 0); - lv_imgbtn_set_src(buttonT_CN, LV_BTN_STATE_REL, "F:/bmp_traditional_cn.bin"); - lv_imgbtn_set_src(buttonT_CN, LV_BTN_STATE_PR, "F:/bmp_traditional_cn.bin"); - lv_imgbtn_set_style(buttonT_CN, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonT_CN, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonEN, event_handler, ID_EN, NULL, 0); - lv_imgbtn_set_src(buttonEN, LV_BTN_STATE_REL, "F:/bmp_english.bin"); - lv_imgbtn_set_src(buttonEN, LV_BTN_STATE_PR, "F:/bmp_english.bin"); - lv_imgbtn_set_style(buttonEN, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonEN, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonRU, event_handler, ID_RU, NULL, 0); - lv_imgbtn_set_src(buttonRU, LV_BTN_STATE_REL, "F:/bmp_russian.bin"); - lv_imgbtn_set_src(buttonRU, LV_BTN_STATE_PR, "F:/bmp_russian.bin"); - lv_imgbtn_set_style(buttonRU, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonRU, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonES, event_handler, ID_ES, NULL, 0); - lv_imgbtn_set_src(buttonES, LV_BTN_STATE_REL, "F:/bmp_spanish.bin"); - lv_imgbtn_set_src(buttonES, LV_BTN_STATE_PR, "F:/bmp_spanish.bin"); - lv_imgbtn_set_style(buttonES, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonES, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonFR, event_handler, ID_FR, NULL, 0); - lv_imgbtn_set_src(buttonFR, LV_BTN_STATE_REL, "F:/bmp_french.bin"); - lv_imgbtn_set_src(buttonFR, LV_BTN_STATE_PR, "F:/bmp_french.bin"); - lv_imgbtn_set_style(buttonFR, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonFR, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonIT, event_handler, ID_IT, NULL, 0); - lv_imgbtn_set_src(buttonIT, LV_BTN_STATE_REL, "F:/bmp_italy.bin"); - lv_imgbtn_set_src(buttonIT, LV_BTN_STATE_PR, "F:/bmp_italy.bin"); - lv_imgbtn_set_style(buttonIT, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonIT, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_L_RETURN, NULL, 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_return.bin"); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_return.bin"); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); - - #endif // if 1 - - lv_obj_set_pos(buttonCN, INTERVAL_V, titleHeight); - lv_obj_set_pos(buttonT_CN, BTN_X_PIXEL + INTERVAL_V * 2, titleHeight); - lv_obj_set_pos(buttonEN, BTN_X_PIXEL * 2 + INTERVAL_V * 3, titleHeight); - lv_obj_set_pos(buttonRU, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight); - lv_obj_set_pos(buttonES, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - lv_obj_set_pos(buttonFR, BTN_X_PIXEL + INTERVAL_V * 2, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - lv_obj_set_pos(buttonIT, BTN_X_PIXEL * 2 + INTERVAL_V * 3, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - lv_obj_set_pos(buttonBack, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - - // Create labels on the image buttons - lv_btn_set_layout(buttonCN, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonT_CN, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonEN, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonRU, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonES, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonFR, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonIT, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - - lv_obj_t *label_CN = lv_label_create(buttonCN, NULL); - lv_obj_t *label_T_CN = lv_label_create(buttonT_CN, NULL); - lv_obj_t *label_EN = lv_label_create(buttonEN, NULL); - lv_obj_t *label_RU = lv_label_create(buttonRU, NULL); - lv_obj_t *label_ES = lv_label_create(buttonES, NULL); - lv_obj_t *label_FR = lv_label_create(buttonFR, NULL); - lv_obj_t *label_IT = lv_label_create(buttonIT, NULL); - lv_obj_t *label_Back = lv_label_create(buttonBack, NULL); - - disp_language(gCfgItems.language, SELECTED); - - if (gCfgItems.multiple_language != 0) { - lv_label_set_text(label_CN, language_menu.chinese_s); - lv_obj_align(label_CN, buttonCN, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_T_CN, language_menu.chinese_t); - lv_obj_align(label_T_CN, buttonT_CN, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_EN, language_menu.english); - lv_obj_align(label_EN, buttonEN, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_RU, language_menu.russian); - lv_obj_align(label_RU, buttonRU, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_ES, language_menu.spanish); - lv_obj_align(label_ES, buttonES, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_FR, language_menu.french); - lv_obj_align(label_FR, buttonFR, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_IT, language_menu.italy); - lv_obj_align(label_IT, buttonIT, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonCN); - lv_group_add_obj(g, buttonT_CN); - lv_group_add_obj(g, buttonEN); - lv_group_add_obj(g, buttonRU); - lv_group_add_obj(g, buttonES); - lv_group_add_obj(g, buttonFR); - lv_group_add_obj(g, buttonIT); - lv_group_add_obj(g, buttonBack); - } - #endif -} - -void lv_clear_language() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_level_settings.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_level_settings.cpp deleted file mode 100644 index 0e0283d32a40..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_level_settings.cpp +++ /dev/null @@ -1,261 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "lv_conf.h" -#include "draw_ui.h" - -#include "../../../../MarlinCore.h" - -extern lv_group_t * g; -static lv_obj_t * scr; - -#define ID_LEVEL_RETURN 1 -#define ID_LEVEL_POSITION 2 -#define ID_LEVEL_POSITION_ARROW 3 -#define ID_LEVEL_COMMAND 4 -#define ID_LEVEL_COMMAND_ARROW 5 -#define ID_LEVEL_ZOFFSET 6 -#define ID_LEVEL_ZOFFSET_ARROW 7 - - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_LEVEL_RETURN: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_level_settings(); - draw_return_ui(); - } - break; - case ID_LEVEL_POSITION: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_level_settings(); - lv_draw_manual_level_pos_settings(); - } - break; - case ID_LEVEL_POSITION_ARROW: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_level_settings(); - lv_draw_manual_level_pos_settings(); - } - break; - case ID_LEVEL_COMMAND: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - keyboard_value = gcodeCommand; - lv_clear_level_settings(); - lv_draw_keyboard(); - } - break; - case ID_LEVEL_COMMAND_ARROW: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - keyboard_value = gcodeCommand; - lv_clear_level_settings(); - lv_draw_keyboard(); - } - break; - #if HAS_BED_PROBE - case ID_LEVEL_ZOFFSET: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_level_settings(); - lv_draw_auto_level_offset_settings(); - } - break; - case ID_LEVEL_ZOFFSET_ARROW: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_level_settings(); - lv_draw_auto_level_offset_settings(); - } - break; - #endif - } -} - -void lv_draw_level_settings(void) { - lv_obj_t *buttonBack, *label_Back; - lv_obj_t *buttonPosition, *labelPosition, *buttonPositionNarrow; - lv_obj_t *buttonCommand, *labelCommand, *buttonCommandNarrow; - #if HAS_BED_PROBE - lv_obj_t *buttonZoffset, *labelZoffset, *buttonZoffsetNarrow; - lv_obj_t * line3; - #endif - lv_obj_t * line1, * line2; - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != LEVELING_PARA_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = LEVELING_PARA_UI; - } - disp_state = LEVELING_PARA_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, machine_menu.LevelingParaConfTitle); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - - buttonPosition = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonPosition, PARA_UI_POS_X, PARA_UI_POS_Y); /*Set its position*/ - lv_obj_set_size(buttonPosition, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb_mks(buttonPosition, event_handler, ID_LEVEL_POSITION, NULL, 0); - lv_btn_set_style(buttonPosition, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonPosition, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonPosition, LV_LAYOUT_OFF); - labelPosition = lv_label_create(buttonPosition, NULL); /*Add a label to the button*/ - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonPosition); - #endif - - buttonPositionNarrow = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonPositionNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y + PARA_UI_ARROW_V); - lv_obj_set_event_cb_mks(buttonPositionNarrow, event_handler, ID_LEVEL_POSITION_ARROW, NULL, 0); - lv_imgbtn_set_src(buttonPositionNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); - lv_imgbtn_set_src(buttonPositionNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); - lv_imgbtn_set_style(buttonPositionNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonPositionNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_btn_set_layout(buttonPositionNarrow, LV_LAYOUT_OFF); - - line1 = lv_line_create(scr, NULL); - lv_ex_line(line1, line_points[0]); - - buttonCommand = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonCommand, PARA_UI_POS_X, PARA_UI_POS_Y * 2); - lv_obj_set_size(buttonCommand, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); - lv_obj_set_event_cb_mks(buttonCommand, event_handler, ID_LEVEL_COMMAND, NULL, 0); - lv_btn_set_style(buttonCommand, LV_BTN_STYLE_REL, &tft_style_label_rel); - lv_btn_set_style(buttonCommand, LV_BTN_STYLE_PR, &tft_style_label_pre); - lv_btn_set_layout(buttonCommand, LV_LAYOUT_OFF); - labelCommand = lv_label_create(buttonCommand, NULL); - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonCommand); - #endif - - buttonCommandNarrow = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonCommandNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y * 2 + PARA_UI_ARROW_V); - lv_obj_set_event_cb_mks(buttonCommandNarrow, event_handler, ID_LEVEL_COMMAND_ARROW, NULL, 0); - lv_imgbtn_set_src(buttonCommandNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); - lv_imgbtn_set_src(buttonCommandNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); - lv_imgbtn_set_style(buttonCommandNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonCommandNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_btn_set_layout(buttonCommandNarrow, LV_LAYOUT_OFF); - - line2 = lv_line_create(scr, NULL); - lv_ex_line(line2, line_points[1]); - - #if HAS_BED_PROBE - - buttonZoffset = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonZoffset, PARA_UI_POS_X, PARA_UI_POS_Y * 3); /*Set its position*/ - lv_obj_set_size(buttonZoffset, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb_mks(buttonZoffset, event_handler, ID_LEVEL_ZOFFSET, NULL, 0); - lv_btn_set_style(buttonZoffset, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonZoffset, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonZoffset, LV_LAYOUT_OFF); - labelZoffset = lv_label_create(buttonZoffset, NULL); /*Add a label to the button*/ - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonZoffset); - #endif - - buttonZoffsetNarrow = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonZoffsetNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y * 3 + PARA_UI_ARROW_V); - lv_obj_set_event_cb_mks(buttonZoffsetNarrow, event_handler, ID_LEVEL_ZOFFSET_ARROW, NULL, 0); - lv_imgbtn_set_src(buttonZoffsetNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); - lv_imgbtn_set_src(buttonZoffsetNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); - lv_imgbtn_set_style(buttonZoffsetNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonZoffsetNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_btn_set_layout(buttonZoffsetNarrow, LV_LAYOUT_OFF); - - line3 = lv_line_create(scr, NULL); - lv_ex_line(line3, line_points[2]); - - #endif // HAS_BED_PROBE - - buttonBack = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_LEVEL_RETURN, NULL, 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_back70x40.bin"); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_back70x40.bin"); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonBack); - #endif - - lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); - lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - label_Back = lv_label_create(buttonBack, NULL); - - if (gCfgItems.multiple_language != 0) { - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_CENTER, 0, 0); - - lv_label_set_text(labelPosition, machine_menu.LevelingManuPosConf); - lv_obj_align(labelPosition, buttonPosition, LV_ALIGN_IN_LEFT_MID, 0, 0); - - lv_label_set_text(labelCommand, machine_menu.LevelingAutoCommandConf); - lv_obj_align(labelCommand, buttonCommand, LV_ALIGN_IN_LEFT_MID, 0, 0); - #if HAS_BED_PROBE - lv_label_set_text(labelZoffset, machine_menu.LevelingAutoZoffsetConf); - lv_obj_align(labelZoffset, buttonZoffset, LV_ALIGN_IN_LEFT_MID, 0, 0); - #endif - } - -} - -void lv_clear_level_settings() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_machine_para.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_machine_para.cpp deleted file mode 100644 index 9f03793c24f7..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_machine_para.cpp +++ /dev/null @@ -1,290 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "lv_conf.h" -#include "draw_ui.h" - -#include "../../../../MarlinCore.h" - -extern lv_group_t * g; -static lv_obj_t * scr; - -#define ID_PARA_RETURN 1 -#define ID_PARA_MACHINE 2 -#define ID_PARA_MACHINE_ARROW 3 -#define ID_PARA_MOTOR 4 -#define ID_PARA_MOTOR_ARROW 5 -#define ID_PARA_LEVEL 6 -#define ID_PARA_LEVEL_ARROW 7 -#define ID_PARA_ADVANCE 8 -#define ID_PARA_ADVANCE_ARROW 9 - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_PARA_RETURN: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_machine_para(); - draw_return_ui(); - } - break; - case ID_PARA_MACHINE: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_machine_para(); - lv_draw_machine_settings(); - } - break; - case ID_PARA_MACHINE_ARROW: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_machine_para(); - lv_draw_machine_settings(); - } - break; - case ID_PARA_MOTOR: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_machine_para(); - lv_draw_motor_settings(); - } - break; - case ID_PARA_MOTOR_ARROW: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_machine_para(); - lv_draw_motor_settings(); - } - break; - case ID_PARA_LEVEL: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_machine_para(); - lv_draw_level_settings(); - } - break; - case ID_PARA_LEVEL_ARROW: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_machine_para(); - lv_draw_level_settings(); - } - break; - case ID_PARA_ADVANCE: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_machine_para(); - lv_draw_advance_settings(); - } - break; - case ID_PARA_ADVANCE_ARROW: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_machine_para(); - lv_draw_advance_settings(); - } - break; - } -} - -void lv_draw_machine_para(void) { - lv_obj_t *buttonBack, *label_Back; - lv_obj_t *buttonMachine, *labelMachine, *buttonMachineNarrow; - lv_obj_t *buttonMotor, *labelMotor, *buttonMotorNarrow; - lv_obj_t *buttonLevel, *labelLevel, *buttonLevelNarrow; - lv_obj_t *buttonAdvance, *labelAdvance, *buttonAdvanceNarrow; - lv_obj_t * line1, * line2, * line3, * line4; - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != MACHINE_PARA_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = MACHINE_PARA_UI; - } - disp_state = MACHINE_PARA_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, creat_title_text()); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - buttonMachine = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonMachine, PARA_UI_POS_X, PARA_UI_POS_Y); /*Set its position*/ - lv_obj_set_size(buttonMachine, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - //lv_obj_set_event_cb(buttonMachine, event_handler); - lv_obj_set_event_cb_mks(buttonMachine, event_handler, ID_PARA_MACHINE, NULL, 0); - lv_btn_set_style(buttonMachine, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonMachine, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonMachine, LV_LAYOUT_OFF); - labelMachine = lv_label_create(buttonMachine, NULL); /*Add a label to the button*/ - - buttonMachineNarrow = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonMachineNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y + PARA_UI_ARROW_V); - lv_obj_set_event_cb_mks(buttonMachineNarrow, event_handler, ID_PARA_MACHINE_ARROW, NULL, 0); - lv_imgbtn_set_src(buttonMachineNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); - lv_imgbtn_set_src(buttonMachineNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); - lv_imgbtn_set_style(buttonMachineNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonMachineNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_btn_set_layout(buttonMachineNarrow, LV_LAYOUT_OFF); - - line1 = lv_line_create(scr, NULL); - lv_ex_line(line1, line_points[0]); - - buttonMotor = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonMotor, PARA_UI_POS_X, PARA_UI_POS_Y * 2); /*Set its position*/ - lv_obj_set_size(buttonMotor, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - //lv_obj_set_event_cb(buttonMotor, event_handler); - lv_obj_set_event_cb_mks(buttonMotor, event_handler, ID_PARA_MOTOR, NULL, 0); - lv_btn_set_style(buttonMotor, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonMotor, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonMotor, LV_LAYOUT_OFF); - labelMotor = lv_label_create(buttonMotor, NULL); /*Add a label to the button*/ - - buttonMotorNarrow = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonMotorNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y * 2 + PARA_UI_ARROW_V); - lv_obj_set_event_cb_mks(buttonMotorNarrow, event_handler, ID_PARA_MOTOR_ARROW, NULL, 0); - lv_imgbtn_set_src(buttonMotorNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); - lv_imgbtn_set_src(buttonMotorNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); - lv_imgbtn_set_style(buttonMotorNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonMotorNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_btn_set_layout(buttonMotorNarrow, LV_LAYOUT_OFF); - - line2 = lv_line_create(scr, NULL); - lv_ex_line(line2, line_points[1]); - - buttonLevel = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonLevel, PARA_UI_POS_X, PARA_UI_POS_Y * 3); /*Set its position*/ - lv_obj_set_size(buttonLevel, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - //lv_obj_set_event_cb(buttonMotor, event_handler); - lv_obj_set_event_cb_mks(buttonLevel, event_handler, ID_PARA_LEVEL, NULL, 0); - lv_btn_set_style(buttonLevel, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonLevel, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonLevel, LV_LAYOUT_OFF); - labelLevel = lv_label_create(buttonLevel, NULL); /*Add a label to the button*/ - - buttonLevelNarrow = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonLevelNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y * 3 + PARA_UI_ARROW_V); - lv_obj_set_event_cb_mks(buttonLevelNarrow, event_handler, ID_PARA_LEVEL_ARROW, NULL, 0); - lv_imgbtn_set_src(buttonLevelNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); - lv_imgbtn_set_src(buttonLevelNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); - lv_imgbtn_set_style(buttonLevelNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonLevelNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_btn_set_layout(buttonLevelNarrow, LV_LAYOUT_OFF); - - line3 = lv_line_create(scr, NULL); - lv_ex_line(line3, line_points[2]); - - buttonAdvance = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonAdvance, PARA_UI_POS_X, PARA_UI_POS_Y * 4); /*Set its position*/ - lv_obj_set_size(buttonAdvance, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - //lv_obj_set_event_cb(buttonMotor, event_handler); - lv_obj_set_event_cb_mks(buttonAdvance, event_handler, ID_PARA_ADVANCE, NULL, 0); - lv_btn_set_style(buttonAdvance, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonAdvance, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonAdvance, LV_LAYOUT_OFF); - labelAdvance = lv_label_create(buttonAdvance, NULL); /*Add a label to the button*/ - - buttonAdvanceNarrow = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonAdvanceNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y * 4 + PARA_UI_ARROW_V); - lv_obj_set_event_cb_mks(buttonAdvanceNarrow, event_handler, ID_PARA_ADVANCE_ARROW, NULL, 0); - lv_imgbtn_set_src(buttonAdvanceNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); - lv_imgbtn_set_src(buttonAdvanceNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); - lv_imgbtn_set_style(buttonAdvanceNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonAdvanceNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_btn_set_layout(buttonAdvanceNarrow, LV_LAYOUT_OFF); - - line4 = lv_line_create(scr, NULL); - lv_ex_line(line4, line_points[3]); - - buttonBack = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_PARA_RETURN, NULL, 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_back70x40.bin"); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_back70x40.bin"); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X + 10, PARA_UI_BACL_POS_Y); - lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - label_Back = lv_label_create(buttonBack, NULL); - - if (gCfgItems.multiple_language != 0) { - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_CENTER, 0, -2); - - lv_label_set_text(labelMachine, MachinePara_menu.MachineSetting); - lv_obj_align(labelMachine, buttonMachine, LV_ALIGN_IN_LEFT_MID, 0, -3); - - lv_label_set_text(labelMotor, MachinePara_menu.MotorSetting); - lv_obj_align(labelMotor, buttonMotor, LV_ALIGN_IN_LEFT_MID, 0, -3); - - lv_label_set_text(labelLevel, MachinePara_menu.leveling); - lv_obj_align(labelLevel, buttonLevel, LV_ALIGN_IN_LEFT_MID, 0, -3); - - lv_label_set_text(labelAdvance, MachinePara_menu.AdvanceSetting); - lv_obj_align(labelAdvance, buttonAdvance, LV_ALIGN_IN_LEFT_MID, 0, -3); - } - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonMachine); - lv_group_add_obj(g, buttonMotor); - lv_group_add_obj(g, buttonLevel); - lv_group_add_obj(g, buttonAdvance); - lv_group_add_obj(g, buttonBack); - } - #endif - -} - -void lv_clear_machine_para() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_machine_settings.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_machine_settings.cpp deleted file mode 100644 index 0cf5bbaf7fba..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_machine_settings.cpp +++ /dev/null @@ -1,254 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "lv_conf.h" -#include "draw_ui.h" - -#include "../../../../MarlinCore.h" - -extern lv_group_t * g; -static lv_obj_t * scr; - -#define ID_MACHINE_RETURN 1 -#define ID_MACHINE_ACCELERATION 2 -#define ID_MACHINE_ACCELERATION_ARROW 3 -#define ID_MACHINE_FEEDRATE 4 -#define ID_MACHINE_FEEDRATE_ARROW 5 -#define ID_MACHINE_JERK 6 -#define ID_MACHINE_JERK_ARROW 7 - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_MACHINE_RETURN: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_machine_settings(); - draw_return_ui(); - } - break; - case ID_MACHINE_ACCELERATION: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_machine_settings(); - lv_draw_acceleration_settings(); - } - break; - case ID_MACHINE_ACCELERATION_ARROW: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_machine_settings(); - lv_draw_acceleration_settings(); - } - break; - case ID_MACHINE_FEEDRATE: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_machine_settings(); - lv_draw_max_feedrate_settings(); - } - break; - case ID_MACHINE_FEEDRATE_ARROW: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_machine_settings(); - lv_draw_max_feedrate_settings(); - } - break; - #if HAS_CLASSIC_JERK - case ID_MACHINE_JERK: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_machine_settings(); - lv_draw_jerk_settings(); - } - break; - case ID_MACHINE_JERK_ARROW: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_machine_settings(); - lv_draw_jerk_settings(); - } - break; - #endif - } -} - -void lv_draw_machine_settings(void) { - lv_obj_t *buttonBack, *label_Back; - lv_obj_t *buttonAcceleration, *labelAcceleration, *buttonAccelerationNarrow; - lv_obj_t *buttonMaxFeedrate, *labelMaxFeedrate, *buttonMaxFeedrateNarrow; - #if HAS_CLASSIC_JERK - lv_obj_t *buttonJerk, *labelJerk, *buttonJerkNarrow; - #endif - lv_obj_t * line1, * line2; - #if HAS_CLASSIC_JERK - lv_obj_t * line3; - #endif - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != MACHINE_SETTINGS_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = MACHINE_SETTINGS_UI; - } - disp_state = MACHINE_SETTINGS_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, machine_menu.MachineConfigTitle); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - buttonAcceleration = lv_btn_create(scr, NULL); // Add a button the current screen - lv_obj_set_pos(buttonAcceleration, PARA_UI_POS_X, PARA_UI_POS_Y); // Set its position - lv_obj_set_size(buttonAcceleration, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); // Set its size - //lv_obj_set_event_cb(buttonMachine, event_handler); - lv_obj_set_event_cb_mks(buttonAcceleration, event_handler, ID_MACHINE_ACCELERATION, NULL, 0); - lv_btn_set_style(buttonAcceleration, LV_BTN_STYLE_REL, &tft_style_label_rel); // Set the button's released style - lv_btn_set_style(buttonAcceleration, LV_BTN_STYLE_PR, &tft_style_label_pre); // Set the button's pressed style - lv_btn_set_layout(buttonAcceleration, LV_LAYOUT_OFF); - labelAcceleration = lv_label_create(buttonAcceleration, NULL); // Add a label to the button - - buttonAccelerationNarrow = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonAccelerationNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y + PARA_UI_ARROW_V); - lv_obj_set_event_cb_mks(buttonAccelerationNarrow, event_handler, ID_MACHINE_ACCELERATION_ARROW, NULL, 0); - lv_imgbtn_set_src(buttonAccelerationNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); - lv_imgbtn_set_src(buttonAccelerationNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); - lv_imgbtn_set_style(buttonAccelerationNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonAccelerationNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_btn_set_layout(buttonAccelerationNarrow, LV_LAYOUT_OFF); - - line1 = lv_line_create(lv_scr_act(), NULL); - lv_ex_line(line1, line_points[0]); - - buttonMaxFeedrate = lv_btn_create(scr, NULL); // Add a button the current screen - lv_obj_set_pos(buttonMaxFeedrate, PARA_UI_POS_X, PARA_UI_POS_Y * 2); // Set its position - lv_obj_set_size(buttonMaxFeedrate, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); // Set its size - //lv_obj_set_event_cb(buttonMachine, event_handler); - lv_obj_set_event_cb_mks(buttonMaxFeedrate, event_handler, ID_MACHINE_FEEDRATE, NULL, 0); - lv_btn_set_style(buttonMaxFeedrate, LV_BTN_STYLE_REL, &tft_style_label_rel); // Set the button's released style - lv_btn_set_style(buttonMaxFeedrate, LV_BTN_STYLE_PR, &tft_style_label_pre); // Set the button's pressed style - lv_btn_set_layout(buttonMaxFeedrate, LV_LAYOUT_OFF); - labelMaxFeedrate = lv_label_create(buttonMaxFeedrate, NULL); // Add a label to the button - - buttonMaxFeedrateNarrow = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonMaxFeedrateNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y * 2 + PARA_UI_ARROW_V); - lv_obj_set_event_cb_mks(buttonMaxFeedrateNarrow, event_handler, ID_MACHINE_FEEDRATE_ARROW, NULL, 0); - lv_imgbtn_set_src(buttonMaxFeedrateNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); - lv_imgbtn_set_src(buttonMaxFeedrateNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); - lv_imgbtn_set_style(buttonMaxFeedrateNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonMaxFeedrateNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_btn_set_layout(buttonMaxFeedrateNarrow, LV_LAYOUT_OFF); - - line2 = lv_line_create(lv_scr_act(), NULL); - lv_ex_line(line2, line_points[1]); - - #if HAS_CLASSIC_JERK - buttonJerk = lv_btn_create(scr, NULL); // Add a button the current screen - lv_obj_set_pos(buttonJerk, PARA_UI_POS_X, PARA_UI_POS_Y * 3); // Set its position - lv_obj_set_size(buttonJerk, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); // Set its size - //lv_obj_set_event_cb(buttonMotor, event_handler); - lv_obj_set_event_cb_mks(buttonJerk, event_handler, ID_MACHINE_JERK, NULL, 0); - lv_btn_set_style(buttonJerk, LV_BTN_STYLE_REL, &tft_style_label_rel); // Set the button's released style - lv_btn_set_style(buttonJerk, LV_BTN_STYLE_PR, &tft_style_label_pre); // Set the button's pressed style - lv_btn_set_layout(buttonJerk, LV_LAYOUT_OFF); - labelJerk = lv_label_create(buttonJerk, NULL); // Add a label to the button - - buttonJerkNarrow = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonJerkNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y * 3 + PARA_UI_ARROW_V); - lv_obj_set_event_cb_mks(buttonJerkNarrow, event_handler, ID_MACHINE_JERK_ARROW, NULL, 0); - lv_imgbtn_set_src(buttonJerkNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); - lv_imgbtn_set_src(buttonJerkNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); - lv_imgbtn_set_style(buttonJerkNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonJerkNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_btn_set_layout(buttonJerkNarrow, LV_LAYOUT_OFF); - - line3 = lv_line_create(lv_scr_act(), NULL); - lv_ex_line(line3, line_points[2]); - #endif - - buttonBack = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_MACHINE_RETURN, NULL, 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_back70x40.bin"); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_back70x40.bin"); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); - lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - label_Back = lv_label_create(buttonBack, NULL); - - if (gCfgItems.multiple_language != 0) { - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_CENTER, 0, 0); - - lv_label_set_text(labelAcceleration, machine_menu.AccelerationConf); - lv_obj_align(labelAcceleration, buttonAcceleration, LV_ALIGN_IN_LEFT_MID, 0, 0); - - lv_label_set_text(labelMaxFeedrate, machine_menu.MaxFeedRateConf); - lv_obj_align(labelMaxFeedrate, buttonMaxFeedrate, LV_ALIGN_IN_LEFT_MID, 0, 0); - #if HAS_CLASSIC_JERK - lv_label_set_text(labelJerk, machine_menu.JerkConf); - lv_obj_align(labelJerk, buttonJerk, LV_ALIGN_IN_LEFT_MID, 0, 0); - #endif - } - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonAcceleration); - lv_group_add_obj(g, buttonMaxFeedrate); - #if HAS_CLASSIC_JERK - lv_group_add_obj(g, buttonJerk); - #endif - lv_group_add_obj(g, buttonBack); - } - #endif -} - -void lv_clear_machine_settings() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_manuaLevel.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_manuaLevel.cpp deleted file mode 100644 index 3d68019b3527..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_manuaLevel.cpp +++ /dev/null @@ -1,294 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "../../../../MarlinCore.h" -#include "lv_conf.h" -//#include "../lvgl/src/lv_objx/lv_imgbtn.h" -//#include "../lvgl/src/lv_objx/lv_img.h" -//#include "../lvgl/src/lv_core/lv_disp.h" -//#include "../lvgl/src/lv_core/lv_refr.h" -#include "draw_ui.h" -#include "../../../../gcode/queue.h" - -extern lv_group_t * g; -static lv_obj_t * scr; - -#define ID_M_POINT1 1 -#define ID_M_POINT2 2 -#define ID_M_POINT3 3 -#define ID_M_POINT4 4 -#define ID_M_POINT5 5 -#define ID_MANUAL_RETURN 6 - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_M_POINT1: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - - if (queue.length == 0) { - if (uiCfg.leveling_first_time) { - queue.enqueue_now_P(PSTR("G28")); - uiCfg.leveling_first_time = 0; - } - - queue.enqueue_now_P(PSTR("G1 Z10")); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("G1 X%d Y%d"), (int)gCfgItems.levelingPos[0][0], (int)gCfgItems.levelingPos[0][1]); - queue.enqueue_one_now(public_buf_l); - queue.enqueue_now_P(PSTR("G1 Z0")); - } - } - break; - case ID_M_POINT2: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - if (queue.length == 0) { - if (uiCfg.leveling_first_time) { - queue.enqueue_now_P(PSTR("G28")); - uiCfg.leveling_first_time = 0; - } - - queue.enqueue_now_P(PSTR("G1 Z10")); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("G1 X%d Y%d"), (int)gCfgItems.levelingPos[1][0], (int)gCfgItems.levelingPos[1][1]); - queue.enqueue_one_now(public_buf_l); - queue.enqueue_now_P(PSTR("G1 Z0")); - } - } - break; - case ID_M_POINT3: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - if (queue.length == 0) { - if (uiCfg.leveling_first_time) { - queue.enqueue_now_P(PSTR("G28")); - uiCfg.leveling_first_time = 0; - } - - queue.enqueue_now_P(PSTR("G1 Z10")); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("G1 X%d Y%d"), (int)gCfgItems.levelingPos[2][0], (int)gCfgItems.levelingPos[2][1]); - queue.enqueue_one_now(public_buf_l); - queue.enqueue_now_P(PSTR("G1 Z0")); - } - } - - break; - case ID_M_POINT4: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - if (queue.length == 0) { - if (uiCfg.leveling_first_time) { - queue.enqueue_now_P(PSTR("G28")); - uiCfg.leveling_first_time = 0; - } - - queue.enqueue_now_P(PSTR("G1 Z10")); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("G1 X%d Y%d"), (int)gCfgItems.levelingPos[3][0], (int)gCfgItems.levelingPos[3][1]); - queue.enqueue_one_now(public_buf_l); - queue.enqueue_now_P(PSTR("G1 Z0")); - } - } - break; - case ID_M_POINT5: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - if (queue.length == 0) { - if (uiCfg.leveling_first_time) { - queue.enqueue_now_P(PSTR("G28")); - uiCfg.leveling_first_time = 0; - } - - queue.enqueue_now_P(PSTR("G1 Z10")); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("G1 X%d Y%d"), (int)gCfgItems.levelingPos[4][0], (int)gCfgItems.levelingPos[4][1]); - queue.enqueue_one_now(public_buf_l); - queue.enqueue_now_P(PSTR("G1 Z0")); - } - } - - break; - case ID_MANUAL_RETURN: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_manualLevel(); - lv_draw_tool(); - } - break; - } -} - -void lv_draw_manualLevel(void) { - lv_obj_t *buttonPoint1, *buttonPoint2, *buttonPoint3, *buttonPoint4, *buttonPoint5; - lv_obj_t *buttonBack; - - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != LEVELING_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = LEVELING_UI; - } - disp_state = LEVELING_UI; - - scr = lv_obj_create(NULL, NULL); - - // static lv_style_t tool_style; - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, creat_title_text()); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - // Create an Image button - buttonPoint1 = lv_imgbtn_create(scr, NULL); - buttonPoint2 = lv_imgbtn_create(scr, NULL); - buttonPoint3 = lv_imgbtn_create(scr, NULL); - buttonPoint4 = lv_imgbtn_create(scr, NULL); - buttonPoint5 = lv_imgbtn_create(scr, NULL); - buttonBack = lv_imgbtn_create(scr, NULL); - - lv_obj_set_event_cb_mks(buttonPoint1, event_handler, ID_M_POINT1, NULL, 0); - lv_imgbtn_set_src(buttonPoint1, LV_BTN_STATE_REL, "F:/bmp_leveling1.bin"); - lv_imgbtn_set_src(buttonPoint1, LV_BTN_STATE_PR, "F:/bmp_leveling1.bin"); - lv_imgbtn_set_style(buttonPoint1, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonPoint1, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_clear_protect(buttonPoint1, LV_PROTECT_FOLLOW); - - #if 1 - lv_obj_set_event_cb_mks(buttonPoint2, event_handler, ID_M_POINT2, NULL, 0); - lv_imgbtn_set_src(buttonPoint2, LV_BTN_STATE_REL, "F:/bmp_leveling2.bin"); - lv_imgbtn_set_src(buttonPoint2, LV_BTN_STATE_PR, "F:/bmp_leveling2.bin"); - lv_imgbtn_set_style(buttonPoint2, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonPoint2, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonPoint3, event_handler, ID_M_POINT3, NULL, 0); - lv_imgbtn_set_src(buttonPoint3, LV_BTN_STATE_REL, "F:/bmp_leveling3.bin"); - lv_imgbtn_set_src(buttonPoint3, LV_BTN_STATE_PR, "F:/bmp_leveling3.bin"); - lv_imgbtn_set_style(buttonPoint3, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonPoint3, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonPoint4, event_handler, ID_M_POINT4, NULL, 0); - lv_imgbtn_set_src(buttonPoint4, LV_BTN_STATE_REL, "F:/bmp_leveling4.bin"); - lv_imgbtn_set_src(buttonPoint4, LV_BTN_STATE_PR, "F:/bmp_leveling4.bin"); - lv_imgbtn_set_style(buttonPoint4, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonPoint4, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonPoint5, event_handler, ID_M_POINT5, NULL, 0); - lv_imgbtn_set_src(buttonPoint5, LV_BTN_STATE_REL, "F:/bmp_leveling5.bin"); - lv_imgbtn_set_src(buttonPoint5, LV_BTN_STATE_PR, "F:/bmp_leveling5.bin"); - lv_imgbtn_set_style(buttonPoint5, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonPoint5, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_MANUAL_RETURN, NULL, 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_return.bin"); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_return.bin"); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); - #endif - - lv_obj_set_pos(buttonPoint1, INTERVAL_V, titleHeight); - lv_obj_set_pos(buttonPoint2, BTN_X_PIXEL + INTERVAL_V * 2, titleHeight); - lv_obj_set_pos(buttonPoint3, BTN_X_PIXEL * 2 + INTERVAL_V * 3, titleHeight); - lv_obj_set_pos(buttonPoint4, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight); - lv_obj_set_pos(buttonPoint5, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - lv_obj_set_pos(buttonBack, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - - // Create labels on the image buttons - lv_btn_set_layout(buttonPoint1, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonPoint2, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonPoint3, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonPoint4, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonPoint5, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - - lv_obj_t *label_Point1 = lv_label_create(buttonPoint1, NULL); - lv_obj_t *label_Point2 = lv_label_create(buttonPoint2, NULL); - lv_obj_t *label_Point3 = lv_label_create(buttonPoint3, NULL); - lv_obj_t *label_Point4 = lv_label_create(buttonPoint4, NULL); - lv_obj_t *label_Point5 = lv_label_create(buttonPoint5, NULL); - lv_obj_t *label_Back = lv_label_create(buttonBack, NULL); - - if (gCfgItems.multiple_language != 0) { - lv_label_set_text(label_Point1, leveling_menu.position1); - lv_obj_align(label_Point1, buttonPoint1, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_Point2, leveling_menu.position2); - lv_obj_align(label_Point2, buttonPoint2, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_Point3, leveling_menu.position3); - lv_obj_align(label_Point3, buttonPoint3, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_Point4, leveling_menu.position4); - lv_obj_align(label_Point4, buttonPoint4, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_Point5, leveling_menu.position5); - lv_obj_align(label_Point5, buttonPoint5, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonPoint1); - lv_group_add_obj(g, buttonPoint2); - lv_group_add_obj(g, buttonPoint3); - lv_group_add_obj(g, buttonPoint4); - lv_group_add_obj(g, buttonPoint5); - lv_group_add_obj(g, buttonBack); - } - #endif -} - -void lv_clear_manualLevel() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_manual_level_pos_settings.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_manual_level_pos_settings.cpp deleted file mode 100644 index 9b7200b5a97d..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_manual_level_pos_settings.cpp +++ /dev/null @@ -1,459 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "lv_conf.h" -#include "draw_ui.h" - -#include "../../../../MarlinCore.h" -#include "../../../../module/planner.h" - -extern lv_group_t * g; -static lv_obj_t * scr; - -#define ID_MANUAL_POS_RETURN 1 -#define ID_MANUAL_POS_X1 2 -#define ID_MANUAL_POS_Y1 3 -#define ID_MANUAL_POS_X2 4 -#define ID_MANUAL_POS_Y2 5 -#define ID_MANUAL_POS_X3 6 -#define ID_MANUAL_POS_Y3 7 -#define ID_MANUAL_POS_X4 8 -#define ID_MANUAL_POS_Y4 9 -#define ID_MANUAL_POS_X5 10 -#define ID_MANUAL_POS_Y5 11 -#define ID_MANUAL_POS_DOWN 12 -#define ID_MANUAL_POS_UP 13 - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_MANUAL_POS_RETURN: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - uiCfg.para_ui_page = 0; - lv_clear_manual_level_pos_settings(); - draw_return_ui(); - } - break; - case ID_MANUAL_POS_X1: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = level_pos_x1; - lv_clear_manual_level_pos_settings(); - lv_draw_number_key(); - } - break; - case ID_MANUAL_POS_Y1: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = level_pos_y1; - lv_clear_manual_level_pos_settings(); - lv_draw_number_key(); - } - break; - case ID_MANUAL_POS_X2: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = level_pos_x2; - lv_clear_manual_level_pos_settings(); - lv_draw_number_key(); - } - break; - case ID_MANUAL_POS_Y2: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = level_pos_y2; - lv_clear_manual_level_pos_settings(); - lv_draw_number_key(); - } - break; - case ID_MANUAL_POS_X3: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = level_pos_x3; - lv_clear_manual_level_pos_settings(); - lv_draw_number_key(); - } - break; - case ID_MANUAL_POS_Y3: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = level_pos_y3; - lv_clear_manual_level_pos_settings(); - lv_draw_number_key(); - } - break; - case ID_MANUAL_POS_X4: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = level_pos_x4; - lv_clear_manual_level_pos_settings(); - lv_draw_number_key(); - } - break; - case ID_MANUAL_POS_Y4: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = level_pos_y4; - lv_clear_manual_level_pos_settings(); - lv_draw_number_key(); - } - break; - case ID_MANUAL_POS_X5: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = level_pos_y5; - lv_clear_manual_level_pos_settings(); - lv_draw_number_key(); - } - break; - case ID_MANUAL_POS_Y5: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = level_pos_y5; - lv_clear_manual_level_pos_settings(); - lv_draw_number_key(); - } - break; - case ID_MANUAL_POS_UP: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - uiCfg.para_ui_page = 0; - lv_clear_manual_level_pos_settings(); - lv_draw_manual_level_pos_settings(); - } - break; - case ID_MANUAL_POS_DOWN: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - uiCfg.para_ui_page = 1; - lv_clear_manual_level_pos_settings(); - lv_draw_manual_level_pos_settings(); - } - break; - } -} - -void lv_draw_manual_level_pos_settings(void) { - lv_obj_t *buttonBack = NULL, *label_Back = NULL, *buttonTurnPage = NULL, *labelTurnPage = NULL; - lv_obj_t *labelPoint1Text = NULL, *buttonX1Value = NULL, *labelX1Value = NULL; - lv_obj_t *buttonY1Value = NULL, *labelY1Value = NULL; - lv_obj_t *labelPoint2Text = NULL, *buttonX2Value = NULL, *labelX2Value = NULL; - lv_obj_t *buttonY2Value = NULL, *labelY2Value = NULL; - lv_obj_t *labelPoint3Text = NULL, *buttonX3Value = NULL, *labelX3Value = NULL; - lv_obj_t *buttonY3Value = NULL, *labelY3Value = NULL; - lv_obj_t *labelPoint4Text = NULL, *buttonX4Value = NULL, *labelX4Value = NULL; - lv_obj_t *buttonY4Value = NULL, *labelY4Value = NULL; - lv_obj_t *labelPoint5Text = NULL, *buttonX5Value = NULL, *labelX5Value = NULL; - lv_obj_t *buttonY5Value = NULL, *labelY5Value = NULL; - lv_obj_t * line1 = NULL, * line2 = NULL, * line3 = NULL, * line4 = NULL; - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != MANUAL_LEVELING_POSIGION_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = MANUAL_LEVELING_POSIGION_UI; - } - disp_state = MANUAL_LEVELING_POSIGION_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, machine_menu.LevelingParaConfTitle); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - if (uiCfg.para_ui_page != 1) { - labelPoint1Text = lv_label_create(scr, NULL); - lv_obj_set_style(labelPoint1Text, &tft_style_label_rel); - lv_obj_set_pos(labelPoint1Text, PARA_UI_POS_X, PARA_UI_POS_Y + 10); - lv_label_set_text(labelPoint1Text, leveling_menu.position1); - - buttonX1Value = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonX1Value, PARA_UI_VALUE_POS_X_2, PARA_UI_POS_Y + PARA_UI_VALUE_V_2); - lv_obj_set_size(buttonX1Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonX1Value, event_handler, ID_MANUAL_POS_X1, NULL, 0); - lv_btn_set_style(buttonX1Value, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonX1Value, LV_BTN_STYLE_PR, &style_para_value); - labelX1Value = lv_label_create(buttonX1Value, NULL); - - buttonY1Value = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonY1Value, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y + PARA_UI_VALUE_V_2); - lv_obj_set_size(buttonY1Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonY1Value, event_handler, ID_MANUAL_POS_Y1, NULL, 0); - lv_btn_set_style(buttonY1Value, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonY1Value, LV_BTN_STYLE_PR, &style_para_value); - labelY1Value = lv_label_create(buttonY1Value, NULL); - - line1 = lv_line_create(scr, NULL); - lv_ex_line(line1, line_points[0]); - - labelPoint2Text = lv_label_create(scr, NULL); - lv_obj_set_style(labelPoint2Text, &tft_style_label_rel); - lv_obj_set_pos(labelPoint2Text, PARA_UI_POS_X, PARA_UI_POS_Y * 2 + 10); - lv_label_set_text(labelPoint2Text, leveling_menu.position2); - - buttonX2Value = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonX2Value, PARA_UI_VALUE_POS_X_2, PARA_UI_POS_Y * 2 + PARA_UI_VALUE_V_2); - lv_obj_set_size(buttonX2Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonX2Value, event_handler, ID_MANUAL_POS_X2, NULL, 0); - lv_btn_set_style(buttonX2Value, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonX2Value, LV_BTN_STYLE_PR, &style_para_value); - labelX2Value = lv_label_create(buttonX2Value, NULL); - - buttonY2Value = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonY2Value, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 2 + PARA_UI_VALUE_V_2); - lv_obj_set_size(buttonY2Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonY2Value, event_handler, ID_MANUAL_POS_Y2, NULL, 0); - lv_btn_set_style(buttonY2Value, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonY2Value, LV_BTN_STYLE_PR, &style_para_value); - labelY2Value = lv_label_create(buttonY2Value, NULL); - - line2 = lv_line_create(scr, NULL); - lv_ex_line(line2, line_points[1]); - - labelPoint3Text = lv_label_create(scr, NULL); - lv_obj_set_style(labelPoint3Text, &tft_style_label_rel); - lv_obj_set_pos(labelPoint3Text, PARA_UI_POS_X, PARA_UI_POS_Y * 3 + 10); - lv_label_set_text(labelPoint3Text, leveling_menu.position3); - - buttonX3Value = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonX3Value, PARA_UI_VALUE_POS_X_2, PARA_UI_POS_Y * 3 + PARA_UI_VALUE_V_2); - lv_obj_set_size(buttonX3Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonX3Value, event_handler, ID_MANUAL_POS_X3, NULL, 0); - lv_btn_set_style(buttonX3Value, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonX3Value, LV_BTN_STYLE_PR, &style_para_value); - labelX3Value = lv_label_create(buttonX3Value, NULL); - - buttonY3Value = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonY3Value, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 3 + PARA_UI_VALUE_V_2); - lv_obj_set_size(buttonY3Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonY3Value, event_handler, ID_MANUAL_POS_Y3, NULL, 0); - lv_btn_set_style(buttonY3Value, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonY3Value, LV_BTN_STYLE_PR, &style_para_value); - labelY3Value = lv_label_create(buttonY3Value, NULL); - - line3 = lv_line_create(scr, NULL); - lv_ex_line(line3, line_points[2]); - - labelPoint4Text = lv_label_create(scr, NULL); - lv_obj_set_style(labelPoint4Text, &tft_style_label_rel); - lv_obj_set_pos(labelPoint4Text, PARA_UI_POS_X, PARA_UI_POS_Y * 4 + 10); - lv_label_set_text(labelPoint4Text, leveling_menu.position4); - - buttonX4Value = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonX4Value, PARA_UI_VALUE_POS_X_2, PARA_UI_POS_Y * 4 + PARA_UI_VALUE_V_2); - lv_obj_set_size(buttonX4Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonX4Value, event_handler, ID_MANUAL_POS_X4, NULL, 0); - lv_btn_set_style(buttonX4Value, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonX4Value, LV_BTN_STYLE_PR, &style_para_value); - labelX4Value = lv_label_create(buttonX4Value, NULL); - - buttonY4Value = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonY4Value, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 4 + PARA_UI_VALUE_V_2); - lv_obj_set_size(buttonY4Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonY4Value, event_handler, ID_MANUAL_POS_Y4, NULL, 0); - lv_btn_set_style(buttonY4Value, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonY4Value, LV_BTN_STYLE_PR, &style_para_value); - labelY4Value = lv_label_create(buttonY4Value, NULL); - - line4 = lv_line_create(scr, NULL); - lv_ex_line(line4, line_points[3]); - - buttonTurnPage = lv_btn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_MANUAL_POS_DOWN, NULL, 0); - lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_REL, &style_para_back); - lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_PR, &style_para_back); - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonX1Value); - lv_group_add_obj(g, buttonY1Value); - lv_group_add_obj(g, buttonX2Value); - lv_group_add_obj(g, buttonY2Value); - lv_group_add_obj(g, buttonX3Value); - lv_group_add_obj(g, buttonY3Value); - lv_group_add_obj(g, buttonX4Value); - lv_group_add_obj(g, buttonY4Value); - lv_group_add_obj(g, buttonTurnPage); - } - #endif - } - else { - labelPoint5Text = lv_label_create(scr, NULL); - lv_obj_set_style(labelPoint5Text, &tft_style_label_rel); - lv_obj_set_pos(labelPoint5Text, PARA_UI_POS_X, PARA_UI_POS_Y + 10); - lv_label_set_text(labelPoint5Text, leveling_menu.position5); - - buttonX5Value = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonX5Value, PARA_UI_VALUE_POS_X_2, PARA_UI_POS_Y + PARA_UI_VALUE_V_2); - lv_obj_set_size(buttonX5Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonX5Value, event_handler, ID_MANUAL_POS_X5, NULL, 0); - lv_btn_set_style(buttonX5Value, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonX5Value, LV_BTN_STYLE_PR, &style_para_value); - labelX5Value = lv_label_create(buttonX5Value, NULL); - - buttonY5Value = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonY5Value, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y + PARA_UI_VALUE_V_2); - lv_obj_set_size(buttonY5Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonY5Value, event_handler, ID_MANUAL_POS_Y5, NULL, 0); - lv_btn_set_style(buttonY5Value, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonY5Value, LV_BTN_STYLE_PR, &style_para_value); - labelY5Value = lv_label_create(buttonY5Value, NULL); - - line1 = lv_line_create(scr, NULL); - lv_ex_line(line1, line_points[0]); - - buttonTurnPage = lv_btn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_MANUAL_POS_UP, NULL, 0); - lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_REL, &style_para_back); - lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_PR, &style_para_back); - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonX5Value); - lv_group_add_obj(g, buttonY5Value); - lv_group_add_obj(g, buttonTurnPage); - } - #endif - } - - lv_obj_set_pos(buttonTurnPage, PARA_UI_TURN_PAGE_POS_X, PARA_UI_TURN_PAGE_POS_Y); - lv_obj_set_size(buttonTurnPage, PARA_UI_BACK_BTN_X_SIZE, PARA_UI_BACK_BTN_Y_SIZE); - labelTurnPage = lv_label_create(buttonTurnPage, NULL); - - buttonBack = lv_btn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_MANUAL_POS_RETURN, NULL, 0); - lv_btn_set_style(buttonBack, LV_BTN_STYLE_REL, &style_para_back); - lv_btn_set_style(buttonBack, LV_BTN_STYLE_PR, &style_para_back); - lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); - lv_obj_set_size(buttonBack, PARA_UI_BACK_BTN_X_SIZE, PARA_UI_BACK_BTN_Y_SIZE); - label_Back = lv_label_create(buttonBack, NULL); - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonBack); - #endif - - if (gCfgItems.multiple_language != 0) { - if (uiCfg.para_ui_page != 1) { - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%d"), gCfgItems.levelingPos[0][0]); - lv_label_set_text(labelX1Value, public_buf_l); - lv_obj_align(labelX1Value, buttonX1Value, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%d"), gCfgItems.levelingPos[0][1]); - lv_label_set_text(labelY1Value, public_buf_l); - lv_obj_align(labelY1Value, buttonY1Value, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%d"), gCfgItems.levelingPos[1][0]); - lv_label_set_text(labelX2Value, public_buf_l); - lv_obj_align(labelX2Value, buttonX2Value, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%d"), gCfgItems.levelingPos[1][1]); - lv_label_set_text(labelY2Value, public_buf_l); - lv_obj_align(labelY2Value, buttonY2Value, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%d"), gCfgItems.levelingPos[2][0]); - lv_label_set_text(labelX3Value, public_buf_l); - lv_obj_align(labelX3Value, buttonX3Value, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%d"), gCfgItems.levelingPos[2][1]); - lv_label_set_text(labelY3Value, public_buf_l); - lv_obj_align(labelY3Value, buttonY3Value, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%d"), gCfgItems.levelingPos[3][0]); - lv_label_set_text(labelX4Value, public_buf_l); - lv_obj_align(labelX4Value, buttonX4Value, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%d"), gCfgItems.levelingPos[3][1]); - lv_label_set_text(labelY4Value, public_buf_l); - lv_obj_align(labelY4Value, buttonY4Value, LV_ALIGN_CENTER, 0, 0); - - lv_label_set_text(labelTurnPage, machine_menu.next); - lv_obj_align(labelTurnPage, buttonTurnPage, LV_ALIGN_CENTER, 0, 0); - } - else { - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%d"), gCfgItems.levelingPos[4][0]); - lv_label_set_text(labelX5Value, public_buf_l); - lv_obj_align(labelX5Value, buttonX5Value, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%d"), gCfgItems.levelingPos[4][1]); - lv_label_set_text(labelY5Value, public_buf_l); - lv_obj_align(labelY5Value, buttonY5Value, LV_ALIGN_CENTER, 0, 0); - - lv_label_set_text(labelTurnPage, machine_menu.previous); - lv_obj_align(labelTurnPage, buttonTurnPage, LV_ALIGN_CENTER, 0, 0); - } - - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_CENTER, 0, 0); - } -} - -void lv_clear_manual_level_pos_settings() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_manual_level_pos_settings.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_manual_level_pos_settings.h deleted file mode 100644 index 8e89ecf559fc..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_manual_level_pos_settings.h +++ /dev/null @@ -1,33 +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 - -#ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ -#endif - -extern void lv_draw_manual_level_pos_settings(void); -extern void lv_clear_manual_level_pos_settings(); - -#ifdef __cplusplus - } /* C-declarations for C++ */ -#endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_max_feedrate_settings.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_max_feedrate_settings.cpp deleted file mode 100644 index e82124f7056c..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_max_feedrate_settings.cpp +++ /dev/null @@ -1,335 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "lv_conf.h" -#include "draw_ui.h" - -#include "../../../../MarlinCore.h" -#include "../../../../module/planner.h" - -extern lv_group_t * g; -static lv_obj_t * scr; - -#define ID_FEED_RETURN 1 -#define ID_FEED_X 2 -#define ID_FEED_Y 3 -#define ID_FEED_Z 4 -#define ID_FEED_E0 5 -#define ID_FEED_E1 6 -#define ID_FEED_DOWN 7 -#define ID_FEED_UP 8 - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_FEED_RETURN: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - uiCfg.para_ui_page = 0; - lv_clear_max_feedrate_settings(); - draw_return_ui(); - } - break; - case ID_FEED_X: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = XMaxFeedRate; - lv_clear_max_feedrate_settings(); - lv_draw_number_key(); - } - break; - case ID_FEED_Y: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = YMaxFeedRate; - lv_clear_max_feedrate_settings(); - lv_draw_number_key(); - } - break; - case ID_FEED_Z: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = ZMaxFeedRate; - lv_clear_max_feedrate_settings(); - lv_draw_number_key(); - } - break; - case ID_FEED_E0: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = E0MaxFeedRate; - lv_clear_max_feedrate_settings(); - lv_draw_number_key(); - } - break; - case ID_FEED_E1: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = E1MaxFeedRate; - lv_clear_max_feedrate_settings(); - lv_draw_number_key(); - } - break; - case ID_FEED_UP: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - uiCfg.para_ui_page = 0; - lv_clear_max_feedrate_settings(); - lv_draw_max_feedrate_settings(); - } - break; - case ID_FEED_DOWN: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - uiCfg.para_ui_page = 1; - lv_clear_max_feedrate_settings(); - lv_draw_max_feedrate_settings(); - } - break; - } -} - -void lv_draw_max_feedrate_settings(void) { - lv_obj_t *buttonBack = NULL, *label_Back = NULL, *buttonTurnPage = NULL, *labelTurnPage = NULL; - lv_obj_t *labelXText = NULL, *buttonXValue = NULL, *labelXValue = NULL; - lv_obj_t *labelYText = NULL, *buttonYValue = NULL, *labelYValue = NULL; - lv_obj_t *labelZText = NULL, *buttonZValue = NULL, *labelZValue = NULL; - lv_obj_t *labelE0Text = NULL, *buttonE0Value = NULL, *labelE0Value = NULL; - lv_obj_t *labelE1Text = NULL, *buttonE1Value = NULL, *labelE1Value = NULL; - lv_obj_t * line1 = NULL, * line2 = NULL, * line3 = NULL, * line4 = NULL; - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != MAXFEEDRATE_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = MAXFEEDRATE_UI; - } - disp_state = MAXFEEDRATE_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, machine_menu.MaxFeedRateConfTitle); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - if (uiCfg.para_ui_page != 1) { - labelXText = lv_label_create(scr, NULL); - lv_obj_set_style(labelXText, &tft_style_label_rel); - lv_obj_set_pos(labelXText, PARA_UI_POS_X, PARA_UI_POS_Y + 10); - lv_label_set_text(labelXText, machine_menu.XMaxFeedRate); - - buttonXValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonXValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y + PARA_UI_VALUE_V); - lv_obj_set_size(buttonXValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonXValue, event_handler, ID_FEED_X, NULL, 0); - lv_btn_set_style(buttonXValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonXValue, LV_BTN_STYLE_PR, &style_para_value); - lv_btn_set_layout(buttonXValue, LV_LAYOUT_OFF); - labelXValue = lv_label_create(buttonXValue, NULL); - - line1 = lv_line_create(scr, NULL); - lv_ex_line(line1, line_points[0]); - - labelYText = lv_label_create(scr, NULL); - lv_obj_set_style(labelYText, &tft_style_label_rel); - lv_obj_set_pos(labelYText, PARA_UI_POS_X, PARA_UI_POS_Y * 2 + 10); - lv_label_set_text(labelYText, machine_menu.YMaxFeedRate); - - buttonYValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonYValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 2 + PARA_UI_VALUE_V); - lv_obj_set_size(buttonYValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonYValue, event_handler, ID_FEED_Y, NULL, 0); - lv_btn_set_style(buttonYValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonYValue, LV_BTN_STYLE_PR, &style_para_value); - lv_btn_set_layout(buttonYValue, LV_LAYOUT_OFF); - labelYValue = lv_label_create(buttonYValue, NULL); - - line2 = lv_line_create(scr, NULL); - lv_ex_line(line2, line_points[1]); - - labelZText = lv_label_create(scr, NULL); - lv_obj_set_style(labelZText, &tft_style_label_rel); - lv_obj_set_pos(labelZText, PARA_UI_POS_X, PARA_UI_POS_Y * 3 + 10); - lv_label_set_text(labelZText, machine_menu.ZMaxFeedRate); - - buttonZValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonZValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 3 + PARA_UI_VALUE_V); - lv_obj_set_size(buttonZValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonZValue, event_handler, ID_FEED_Z, NULL, 0); - lv_btn_set_style(buttonZValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonZValue, LV_BTN_STYLE_PR, &style_para_value); - lv_btn_set_layout(buttonZValue, LV_LAYOUT_OFF); - labelZValue = lv_label_create(buttonZValue, NULL); - - line3 = lv_line_create(scr, NULL); - lv_ex_line(line3, line_points[2]); - - labelE0Text = lv_label_create(scr, NULL); - lv_obj_set_style(labelE0Text, &tft_style_label_rel); - lv_obj_set_pos(labelE0Text, PARA_UI_POS_X, PARA_UI_POS_Y * 4 + 10); - lv_label_set_text(labelE0Text, machine_menu.E0MaxFeedRate); - - buttonE0Value = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonE0Value, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 4 + PARA_UI_VALUE_V); - lv_obj_set_size(buttonE0Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonE0Value, event_handler, ID_FEED_E0, NULL, 0); - lv_btn_set_style(buttonE0Value, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonE0Value, LV_BTN_STYLE_PR, &style_para_value); - lv_btn_set_layout(buttonE0Value, LV_LAYOUT_OFF); - labelE0Value = lv_label_create(buttonE0Value, NULL); - - line4 = lv_line_create(scr, NULL); - lv_ex_line(line4, line_points[3]); - - buttonTurnPage = lv_btn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_FEED_DOWN, NULL, 0); - lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_REL, &style_para_back); - lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_PR, &style_para_back); - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonXValue); - lv_group_add_obj(g, buttonYValue); - lv_group_add_obj(g, buttonZValue); - lv_group_add_obj(g, buttonE0Value); - lv_group_add_obj(g, buttonTurnPage); - } - #endif - } - else { - labelE1Text = lv_label_create(scr, NULL); - lv_obj_set_style(labelE1Text, &tft_style_label_rel); - lv_obj_set_pos(labelE1Text, PARA_UI_POS_X, PARA_UI_POS_Y + 10); - lv_label_set_text(labelE1Text, machine_menu.E1MaxFeedRate); - - buttonE1Value = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonE1Value, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y + PARA_UI_VALUE_V); - lv_obj_set_size(buttonE1Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonE1Value, event_handler, ID_FEED_E1, NULL, 0); - lv_btn_set_style(buttonE1Value, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonE1Value, LV_BTN_STYLE_PR, &style_para_value); - lv_btn_set_layout(buttonE1Value, LV_LAYOUT_OFF); - labelE1Value = lv_label_create(buttonE1Value, NULL); - - - line1 = lv_line_create(scr, NULL); - lv_ex_line(line1, line_points[0]); - - buttonTurnPage = lv_btn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_FEED_UP, NULL, 0); - lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_REL, &style_para_back); - lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_PR, &style_para_back); - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonE1Value); - lv_group_add_obj(g, buttonTurnPage); - } - #endif - } - - lv_obj_set_pos(buttonTurnPage, PARA_UI_TURN_PAGE_POS_X, PARA_UI_TURN_PAGE_POS_Y); - lv_obj_set_size(buttonTurnPage, PARA_UI_BACK_BTN_X_SIZE, PARA_UI_BACK_BTN_Y_SIZE); - labelTurnPage = lv_label_create(buttonTurnPage, NULL); - - buttonBack = lv_btn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_FEED_RETURN, NULL, 0); - lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); - lv_obj_set_size(buttonBack, PARA_UI_BACK_BTN_X_SIZE, PARA_UI_BACK_BTN_Y_SIZE); - lv_btn_set_style(buttonBack, LV_BTN_STYLE_REL, &style_para_back); - lv_btn_set_style(buttonBack, LV_BTN_STYLE_PR, &style_para_back); - label_Back = lv_label_create(buttonBack, NULL); - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonBack); - #endif - - if (gCfgItems.multiple_language != 0) { - if (uiCfg.para_ui_page != 1) { - - lv_label_set_text(labelTurnPage, machine_menu.next); - lv_obj_align(labelTurnPage, buttonTurnPage, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%.1f"), planner.settings.max_feedrate_mm_s[X_AXIS]); - lv_label_set_text(labelXValue, public_buf_l); - lv_obj_align(labelXValue, buttonXValue, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%.1f"), planner.settings.max_feedrate_mm_s[Y_AXIS]); - lv_label_set_text(labelYValue, public_buf_l); - lv_obj_align(labelYValue, buttonYValue, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%.1f"), planner.settings.max_feedrate_mm_s[Z_AXIS]); - lv_label_set_text(labelZValue, public_buf_l); - lv_obj_align(labelZValue, buttonZValue, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%.1f"), planner.settings.max_feedrate_mm_s[E_AXIS]); - lv_label_set_text(labelE0Value, public_buf_l); - lv_obj_align(labelE0Value, buttonE0Value, LV_ALIGN_CENTER, 0, 0); - } - else { - lv_label_set_text(labelTurnPage, machine_menu.previous); - lv_obj_align(labelTurnPage, buttonTurnPage, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%.1f"), planner.settings.max_feedrate_mm_s[E_AXIS_N(1)]); - lv_label_set_text(labelE1Value, public_buf_l); - lv_obj_align(labelE1Value, buttonE1Value, LV_ALIGN_CENTER, 0, 0); - } - - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_CENTER, 0, 0); - } -} - -void lv_clear_max_feedrate_settings() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_motor_settings.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_motor_settings.cpp deleted file mode 100644 index f6568df14314..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_motor_settings.cpp +++ /dev/null @@ -1,343 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "lv_conf.h" -#include "draw_ui.h" - -#include "../../../../MarlinCore.h" - -extern lv_group_t * g; -static lv_obj_t * scr; - -#define ID_MOTOR_RETURN 1 -#define ID_MOTOR_STEPS 2 -#define ID_MOTOR_STEPS_ARROW 3 -#define ID_MOTOR_TMC_CURRENT 4 -#define ID_MOTOR_TMC_CURRENT_ARROW 5 -#define ID_MOTOR_STEP_MODE 6 -#define ID_MOTOR_STEP_MODE_ARROW 7 -#define ID_HOME_SENSE 8 -#define ID_HOME_SENSE_ARROW 9 - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_MOTOR_RETURN: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_motor_settings(); - draw_return_ui(); - } - break; - case ID_MOTOR_STEPS: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_motor_settings(); - lv_draw_step_settings(); - } - break; - case ID_MOTOR_STEPS_ARROW: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_motor_settings(); - lv_draw_step_settings(); - } - break; - #if USE_SENSORLESS - case ID_HOME_SENSE: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_motor_settings(); - lv_draw_homing_sensitivity_settings(); - } - break; - case ID_HOME_SENSE_ARROW: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_motor_settings(); - lv_draw_homing_sensitivity_settings(); - } - break; - #endif - #if HAS_TRINAMIC_CONFIG - case ID_MOTOR_TMC_CURRENT: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_motor_settings(); - lv_draw_tmc_current_settings(); - } - break; - case ID_MOTOR_TMC_CURRENT_ARROW: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_motor_settings(); - lv_draw_tmc_current_settings(); - } - break; - #if HAS_STEALTHCHOP - case ID_MOTOR_STEP_MODE: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_motor_settings(); - lv_draw_tmc_step_mode_settings(); - } - break; - case ID_MOTOR_STEP_MODE_ARROW: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_motor_settings(); - lv_draw_tmc_step_mode_settings(); - } - break; - #endif - #endif - } -} - -void lv_draw_motor_settings(void) { - lv_obj_t *buttonBack, *label_Back; - lv_obj_t *buttonSteps, *labelSteps, *buttonStepsNarrow; - lv_obj_t * line1; - #if USE_SENSORLESS - lv_obj_t *buttonSensitivity, *labelSensitivity, *buttonSensitivityNarrow; - lv_obj_t * line2; - #endif - #if HAS_TRINAMIC_CONFIG - #if USE_SENSORLESS - lv_obj_t * line3; - #else - lv_obj_t * line2; - #endif - lv_obj_t *buttonTMCcurrent, *labelTMCcurrent, *buttonTMCcurrentNarrow; - #if HAS_STEALTHCHOP - #if USE_SENSORLESS - lv_obj_t * line4; - #else - lv_obj_t * line3; - #endif - lv_obj_t *buttonStepMode, *labelStepMode, *buttonStepModeNarrow; - #endif - #endif - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != MOTOR_SETTINGS_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = MOTOR_SETTINGS_UI; - } - disp_state = MOTOR_SETTINGS_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, machine_menu.MotorConfTitle); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - buttonSteps = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonSteps, PARA_UI_POS_X, PARA_UI_POS_Y); /*Set its position*/ - lv_obj_set_size(buttonSteps, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - //lv_obj_set_event_cb(buttonMachine, event_handler); - lv_obj_set_event_cb_mks(buttonSteps, event_handler, ID_MOTOR_STEPS, NULL, 0); - lv_btn_set_style(buttonSteps, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonSteps, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonSteps, LV_LAYOUT_OFF); - labelSteps = lv_label_create(buttonSteps, NULL); /*Add a label to the button*/ - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonSteps); - #endif - - buttonStepsNarrow = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonStepsNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y + PARA_UI_ARROW_V); - lv_obj_set_event_cb_mks(buttonStepsNarrow, event_handler, ID_MOTOR_STEPS_ARROW, NULL, 0); - lv_imgbtn_set_src(buttonStepsNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); - lv_imgbtn_set_src(buttonStepsNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); - lv_imgbtn_set_style(buttonStepsNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonStepsNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_btn_set_layout(buttonStepsNarrow, LV_LAYOUT_OFF); - - line1 = lv_line_create(scr, NULL); - lv_ex_line(line1, line_points[0]); - - #if USE_SENSORLESS - buttonSensitivity = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonSensitivity, PARA_UI_POS_X, PARA_UI_POS_Y * 2); /*Set its position*/ - lv_obj_set_size(buttonSensitivity, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - //lv_obj_set_event_cb(buttonMachine, event_handler); - lv_obj_set_event_cb_mks(buttonSensitivity, event_handler, ID_HOME_SENSE, NULL, 0); - lv_btn_set_style(buttonSensitivity, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonSensitivity, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonSensitivity, LV_LAYOUT_OFF); - labelSensitivity = lv_label_create(buttonSensitivity, NULL); /*Add a label to the button*/ - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonSensitivity); - #endif - - buttonSensitivityNarrow = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonSensitivityNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y * 2 + PARA_UI_ARROW_V); - lv_obj_set_event_cb_mks(buttonSensitivityNarrow, event_handler, ID_HOME_SENSE_ARROW, NULL, 0); - lv_imgbtn_set_src(buttonSensitivityNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); - lv_imgbtn_set_src(buttonSensitivityNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); - lv_imgbtn_set_style(buttonSensitivityNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonSensitivityNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_btn_set_layout(buttonSensitivityNarrow, LV_LAYOUT_OFF); - - line2 = lv_line_create(scr, NULL); - lv_ex_line(line2, line_points[1]); - #endif - - - #if HAS_TRINAMIC_CONFIG - buttonTMCcurrent = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonTMCcurrent, PARA_UI_POS_X, TERN(USE_SENSORLESS, PARA_UI_POS_Y * 3, PARA_UI_POS_Y * 2)); - lv_obj_set_size(buttonTMCcurrent, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - //lv_obj_set_event_cb(buttonMachine, event_handler); - lv_obj_set_event_cb_mks(buttonTMCcurrent, event_handler, ID_MOTOR_TMC_CURRENT, NULL, 0); - lv_btn_set_style(buttonTMCcurrent, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonTMCcurrent, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonTMCcurrent, LV_LAYOUT_OFF); - labelTMCcurrent = lv_label_create(buttonTMCcurrent, NULL); /*Add a label to the button*/ - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonTMCcurrent); - #endif - - buttonTMCcurrentNarrow = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonTMCcurrentNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, TERN(USE_SENSORLESS, PARA_UI_POS_Y * 3, PARA_UI_POS_Y * 2) + PARA_UI_ARROW_V); - lv_obj_set_event_cb_mks(buttonTMCcurrentNarrow, event_handler, ID_MOTOR_TMC_CURRENT_ARROW, NULL, 0); - lv_imgbtn_set_src(buttonTMCcurrentNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); - lv_imgbtn_set_src(buttonTMCcurrentNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); - lv_imgbtn_set_style(buttonTMCcurrentNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonTMCcurrentNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_btn_set_layout(buttonTMCcurrentNarrow, LV_LAYOUT_OFF); - #if USE_SENSORLESS - line3 = lv_line_create(scr, NULL); - lv_ex_line(line3, line_points[2]); - #else - line2 = lv_line_create(scr, NULL); - lv_ex_line(line2, line_points[1]); - #endif - - #if HAS_STEALTHCHOP - buttonStepMode = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonStepMode, PARA_UI_POS_X, TERN(USE_SENSORLESS, PARA_UI_POS_Y * 4, PARA_UI_POS_Y * 3)); - lv_obj_set_size(buttonStepMode, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb_mks(buttonStepMode, event_handler, ID_MOTOR_STEP_MODE, NULL, 0); - lv_btn_set_style(buttonStepMode, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonStepMode, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonStepMode, LV_LAYOUT_OFF); - labelStepMode = lv_label_create(buttonStepMode, NULL); /*Add a label to the button*/ - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonStepMode); - #endif - - buttonStepModeNarrow = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonStepModeNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, TERN(USE_SENSORLESS, PARA_UI_POS_Y * 4, PARA_UI_POS_Y * 3) + PARA_UI_ARROW_V); - lv_obj_set_event_cb_mks(buttonStepModeNarrow, event_handler, ID_MOTOR_STEP_MODE_ARROW, NULL, 0); - lv_imgbtn_set_src(buttonStepModeNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); - lv_imgbtn_set_src(buttonStepModeNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); - lv_imgbtn_set_style(buttonStepModeNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonStepModeNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_btn_set_layout(buttonStepModeNarrow, LV_LAYOUT_OFF); - - #if USE_SENSORLESS - line4 = lv_line_create(scr, NULL); - lv_ex_line(line4, line_points[3]); - #else - line3 = lv_line_create(scr, NULL); - lv_ex_line(line3, line_points[2]); - #endif - - #endif // HAS_STEALTHCHOP - - #endif // HAS_TRINAMIC_CONFIG - - buttonBack = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_MOTOR_RETURN, NULL, 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_back70x40.bin"); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_back70x40.bin"); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); - lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - label_Back = lv_label_create(buttonBack, NULL); - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonBack); - #endif - - if (gCfgItems.multiple_language != 0) { - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_CENTER, 0, 0); - - lv_label_set_text(labelSteps, machine_menu.StepsConf); - lv_obj_align(labelSteps, buttonSteps, LV_ALIGN_IN_LEFT_MID, 0, 0); - - #if USE_SENSORLESS - lv_label_set_text(labelSensitivity, machine_menu.HomingSensitivityConf); - lv_obj_align(labelSensitivity, buttonSensitivity, LV_ALIGN_IN_LEFT_MID, 0, 0); - #endif - #if HAS_TRINAMIC_CONFIG - lv_label_set_text(labelTMCcurrent, machine_menu.TMCcurrentConf); - lv_obj_align(labelTMCcurrent, buttonTMCcurrent, LV_ALIGN_IN_LEFT_MID, 0, 0); - #if HAS_STEALTHCHOP - lv_label_set_text(labelStepMode, machine_menu.TMCStepModeConf); - lv_obj_align(labelStepMode, buttonStepMode, LV_ALIGN_IN_LEFT_MID, 0, 0); - #endif - #endif - } - -} - -void lv_clear_motor_settings() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_move_motor.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_move_motor.cpp deleted file mode 100644 index a6c0c0551aba..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_move_motor.cpp +++ /dev/null @@ -1,347 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "../../../../MarlinCore.h" -#include "lv_conf.h" -//#include "../lvgl/src/lv_objx/lv_imgbtn.h" -//#include "../lvgl/src/lv_objx/lv_img.h" -//#include "../lvgl/src/lv_core/lv_disp.h" -//#include "../lvgl/src/lv_core/lv_refr.h" -#include "draw_ui.h" -#include "../../../../gcode/queue.h" - -extern lv_group_t * g; -static lv_obj_t * scr; - -static lv_obj_t *labelV, *buttonV; - -#define ID_M_X_P 1 -#define ID_M_X_N 2 -#define ID_M_Y_P 3 -#define ID_M_Y_N 4 -#define ID_M_Z_P 5 -#define ID_M_Z_N 6 -#define ID_M_STEP 7 -#define ID_M_RETURN 8 - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_M_X_P: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - if (queue.length <= (BUFSIZE - 3)) { - ZERO(public_buf_l); - queue.enqueue_one_P(PSTR("G91")); - sprintf_P(public_buf_l, PSTR("G1 X%3.1f F%d"), uiCfg.move_dist, uiCfg.moveSpeed); - queue.enqueue_one_now(public_buf_l); - queue.enqueue_one_P(PSTR("G90")); - } - } - break; - case ID_M_X_N: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - if (queue.length <= (BUFSIZE - 3)) { - ZERO(public_buf_l); - queue.enqueue_now_P(PSTR("G91")); - sprintf_P(public_buf_l, PSTR("G1 X-%3.1f F%d"), uiCfg.move_dist, uiCfg.moveSpeed); - queue.enqueue_one_now(public_buf_l); - queue.enqueue_now_P(PSTR("G90")); - } - } - break; - case ID_M_Y_P: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - if (queue.length <= (BUFSIZE - 3)) { - ZERO(public_buf_l); - queue.enqueue_now_P(PSTR("G91")); - sprintf_P(public_buf_l, PSTR("G1 Y%3.1f F%d"), uiCfg.move_dist, uiCfg.moveSpeed); - queue.enqueue_one_now(public_buf_l); - queue.enqueue_now_P(PSTR("G90")); - } - } - break; - case ID_M_Y_N: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - if (queue.length <= (BUFSIZE - 3)) { - ZERO(public_buf_l); - queue.enqueue_now_P(PSTR("G91")); - sprintf_P(public_buf_l, PSTR("G1 Y-%3.1f F%d"), uiCfg.move_dist, uiCfg.moveSpeed); - queue.enqueue_one_now(public_buf_l); - queue.enqueue_now_P(PSTR("G90")); - } - } - break; - case ID_M_Z_P: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - if (queue.length <= (BUFSIZE - 3)) { - ZERO(public_buf_l); - queue.enqueue_now_P(PSTR("G91")); - sprintf_P(public_buf_l, PSTR("G1 Z%3.1f F%d"), uiCfg.move_dist, uiCfg.moveSpeed); - queue.enqueue_one_now(public_buf_l); - queue.enqueue_now_P(PSTR("G90")); - } - } - break; - case ID_M_Z_N: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - if (queue.length <= (BUFSIZE - 3)) { - ZERO(public_buf_l); - queue.enqueue_now_P(PSTR("G91")); - sprintf_P(public_buf_l, PSTR("G1 Z-%3.1f F%d"), uiCfg.move_dist, uiCfg.moveSpeed); - queue.enqueue_one_now(public_buf_l); - queue.enqueue_now_P(PSTR("G90")); - } - } - break; - case ID_M_STEP: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - if (abs(10 * (int)uiCfg.move_dist) == 100) - uiCfg.move_dist = 0.1; - else - uiCfg.move_dist *= (float)10; - - disp_move_dist(); - } - - break; - case ID_M_RETURN: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - clear_cur_ui(); - draw_return_ui(); - } - break; - } -} - -void lv_draw_move_motor(void) { - lv_obj_t *buttonXI, *buttonXD, *buttonYI, *buttonYD, *buttonZI, *buttonZD, *buttonBack; - - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != MOVE_MOTOR_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = MOVE_MOTOR_UI; - } - disp_state = MOVE_MOTOR_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, creat_title_text()); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - // Create an Image button - buttonXI = lv_imgbtn_create(scr, NULL); - buttonXD = lv_imgbtn_create(scr, NULL); - buttonYI = lv_imgbtn_create(scr, NULL); - buttonYD = lv_imgbtn_create(scr, NULL); - buttonZI = lv_imgbtn_create(scr, NULL); - buttonZD = lv_imgbtn_create(scr, NULL); - buttonV = lv_imgbtn_create(scr, NULL); - buttonBack = lv_imgbtn_create(scr, NULL); - - lv_obj_set_event_cb_mks(buttonXI, event_handler, ID_M_X_P, NULL, 0); - lv_imgbtn_set_src(buttonXI, LV_BTN_STATE_REL, "F:/bmp_xAdd.bin"); - lv_imgbtn_set_src(buttonXI, LV_BTN_STATE_PR, "F:/bmp_xAdd.bin"); - lv_imgbtn_set_style(buttonXI, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonXI, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_clear_protect(buttonXI, LV_PROTECT_FOLLOW); - - #if 1 - lv_obj_set_event_cb_mks(buttonXD, event_handler, ID_M_X_N, NULL, 0); - lv_imgbtn_set_src(buttonXD, LV_BTN_STATE_REL, "F:/bmp_xDec.bin"); - lv_imgbtn_set_src(buttonXD, LV_BTN_STATE_PR, "F:/bmp_xDec.bin"); - lv_imgbtn_set_style(buttonXD, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonXD, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonYI, event_handler, ID_M_Y_P, NULL, 0); - lv_imgbtn_set_src(buttonYI, LV_BTN_STATE_REL, "F:/bmp_yAdd.bin"); - lv_imgbtn_set_src(buttonYI, LV_BTN_STATE_PR, "F:/bmp_yAdd.bin"); - lv_imgbtn_set_style(buttonYI, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonYI, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonYD, event_handler, ID_M_Y_N, NULL, 0); - lv_imgbtn_set_src(buttonYD, LV_BTN_STATE_REL, "F:/bmp_yDec.bin"); - lv_imgbtn_set_src(buttonYD, LV_BTN_STATE_PR, "F:/bmp_yDec.bin"); - lv_imgbtn_set_style(buttonYD, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonYD, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonZI, event_handler, ID_M_Z_P, NULL, 0); - lv_imgbtn_set_src(buttonZI, LV_BTN_STATE_REL, "F:/bmp_zAdd.bin"); - lv_imgbtn_set_src(buttonZI, LV_BTN_STATE_PR, "F:/bmp_zAdd.bin"); - lv_imgbtn_set_style(buttonZI, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonZI, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonZD, event_handler, ID_M_Z_N, NULL, 0); - lv_imgbtn_set_src(buttonZD, LV_BTN_STATE_REL, "F:/bmp_zDec.bin"); - lv_imgbtn_set_src(buttonZD, LV_BTN_STATE_PR, "F:/bmp_zDec.bin"); - lv_imgbtn_set_style(buttonZD, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonZD, LV_BTN_STATE_REL, &tft_style_label_rel); - - //lv_obj_set_event_cb_mks(buttonV, event_handler,ID_T_MORE,"bmp_More.bin",0); - lv_obj_set_event_cb_mks(buttonV, event_handler, ID_M_STEP, NULL, 0); - lv_imgbtn_set_style(buttonV, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonV, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_M_RETURN, NULL, 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_return.bin"); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_return.bin"); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); - #endif // if 1 - - lv_obj_set_pos(buttonXI, INTERVAL_V, titleHeight); - lv_obj_set_pos(buttonYI, BTN_X_PIXEL + INTERVAL_V * 2, titleHeight); - lv_obj_set_pos(buttonZI, BTN_X_PIXEL * 2 + INTERVAL_V * 3, titleHeight); - lv_obj_set_pos(buttonV, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight); - lv_obj_set_pos(buttonXD, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - lv_obj_set_pos(buttonYD, BTN_X_PIXEL + INTERVAL_V * 2, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - lv_obj_set_pos(buttonZD, BTN_X_PIXEL * 2 + INTERVAL_V * 3, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - lv_obj_set_pos(buttonBack, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - - // Create labels on the image buttons - lv_btn_set_layout(buttonXI, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonXD, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonYI, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonYD, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonZI, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonZD, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonV, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - - lv_obj_t *labelXI = lv_label_create(buttonXI, NULL); - lv_obj_t *labelXD = lv_label_create(buttonXD, NULL); - lv_obj_t *labelYI = lv_label_create(buttonYI, NULL); - lv_obj_t *labelYD = lv_label_create(buttonYD, NULL); - lv_obj_t *labelZI = lv_label_create(buttonZI, NULL); - lv_obj_t *labelZD = lv_label_create(buttonZD, NULL); - labelV = lv_label_create(buttonV, NULL); - lv_obj_t *label_Back = lv_label_create(buttonBack, NULL); - - if (gCfgItems.multiple_language != 0) { - lv_label_set_text(labelXI, move_menu.x_add); - lv_obj_align(labelXI, buttonXI, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(labelXD, move_menu.x_dec); - lv_obj_align(labelXD, buttonXD, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(labelYI, move_menu.y_add); - lv_obj_align(labelYI, buttonYI, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(labelYD, move_menu.y_dec); - lv_obj_align(labelYD, buttonYD, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(labelZI, move_menu.z_add); - lv_obj_align(labelZI, buttonZI, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(labelZD, move_menu.z_dec); - lv_obj_align(labelZD, buttonZD, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonXI); - lv_group_add_obj(g, buttonXD); - lv_group_add_obj(g, buttonYI); - lv_group_add_obj(g, buttonYD); - lv_group_add_obj(g, buttonZI); - lv_group_add_obj(g, buttonZD); - lv_group_add_obj(g, buttonV); - lv_group_add_obj(g, buttonBack); - } - #endif - - disp_move_dist(); -} - -void disp_move_dist() { - // char buf[30] = {0}; - - if ((int)(10 * uiCfg.move_dist) == 1) { - lv_imgbtn_set_src(buttonV, LV_BTN_STATE_REL, "F:/bmp_step_move0_1.bin"); - lv_imgbtn_set_src(buttonV, LV_BTN_STATE_PR, "F:/bmp_step_move0_1.bin"); - } - else if ((int)(10 * uiCfg.move_dist) == 10) { - lv_imgbtn_set_src(buttonV, LV_BTN_STATE_REL, "F:/bmp_step_move1.bin"); - lv_imgbtn_set_src(buttonV, LV_BTN_STATE_PR, "F:/bmp_step_move1.bin"); - } - else if ((int)(10 * uiCfg.move_dist) == 100) { - lv_imgbtn_set_src(buttonV, LV_BTN_STATE_REL, "F:/bmp_step_move10.bin"); - lv_imgbtn_set_src(buttonV, LV_BTN_STATE_PR, "F:/bmp_step_move10.bin"); - } - if (gCfgItems.multiple_language != 0) { - if ((int)(10 * uiCfg.move_dist) == 1) { - lv_label_set_text(labelV, move_menu.step_01mm); - lv_obj_align(labelV, buttonV, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - else if ((int)(10 * uiCfg.move_dist) == 10) { - lv_label_set_text(labelV, move_menu.step_1mm); - lv_obj_align(labelV, buttonV, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - else if ((int)(10 * uiCfg.move_dist) == 100) { - lv_label_set_text(labelV, move_menu.step_10mm); - lv_obj_align(labelV, buttonV, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - } -} - -void lv_clear_move_motor() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_number_key.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_number_key.cpp deleted file mode 100644 index 4842776304d7..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_number_key.cpp +++ /dev/null @@ -1,981 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "lv_conf.h" -//#include "../../lvgl/src/lv_objx/lv_imgbtn.h" -//#include "../../lvgl/src/lv_objx/lv_img.h" -//#include "../../lvgl/src/lv_core/lv_disp.h" -//#include "../../lvgl/src/lv_core/lv_refr.h" -//#include "../../MarlinCore.h" -#include "draw_ui.h" - -#include "../../../../MarlinCore.h" -#include "../../../../module/temperature.h" -#include "../../../../gcode/queue.h" - -#if ENABLED(POWER_LOSS_RECOVERY) - #include "../../../../feature/powerloss.h" -#endif - -#include "../../../../gcode/gcode.h" -#include "../../../../module/planner.h" - -#if HAS_TRINAMIC_CONFIG - #include "../../../../module/stepper/indirection.h" - #include "../../../../feature/tmc_util.h" -#endif - -#if HAS_BED_PROBE - #include "../../../../module/probe.h" -#endif - -extern lv_group_t * g; -static lv_obj_t * scr; -static lv_obj_t *buttonValue = NULL; -static lv_obj_t *labelValue = NULL; - -static char key_value[11] = {0}; -static uint8_t cnt = 0; -static char point_flg = 1; - -#define ID_NUM_KEY1 1 -#define ID_NUM_KEY2 2 -#define ID_NUM_KEY3 3 -#define ID_NUM_KEY4 4 -#define ID_NUM_KEY5 5 -#define ID_NUM_KEY6 6 -#define ID_NUM_KEY7 7 -#define ID_NUM_KEY8 8 -#define ID_NUM_KEY9 9 -#define ID_NUM_KEY0 10 -#define ID_NUM_BACK 11 -#define ID_NUM_RESET 12 -#define ID_NUM_CONFIRM 13 -#define ID_NUM_POINT 14 -#define ID_NUM_NAGETIVE 15 - -static void disp_key_value() { - char *temp; - #if HAS_TRINAMIC_CONFIG - float milliamps; - #endif - - ZERO(public_buf_m); - - switch (value) { - case PrintAcceleration: - sprintf_P(public_buf_m, PSTR("%.1f"), planner.settings.acceleration); - break; - case RetractAcceleration: - sprintf_P(public_buf_m, PSTR("%.1f"), planner.settings.retract_acceleration); - break; - case TravelAcceleration: - sprintf_P(public_buf_m, PSTR("%.1f"), planner.settings.travel_acceleration); - break; - case XAcceleration: - sprintf_P(public_buf_m, PSTR("%d"), (int)planner.settings.max_acceleration_mm_per_s2[X_AXIS]); - break; - case YAcceleration: - sprintf_P(public_buf_m, PSTR("%d"), (int)planner.settings.max_acceleration_mm_per_s2[Y_AXIS]); - break; - case ZAcceleration: - sprintf_P(public_buf_m, PSTR("%d"), (int)planner.settings.max_acceleration_mm_per_s2[Z_AXIS]); - break; - case E0Acceleration: - sprintf_P(public_buf_m, PSTR("%d"), (int)planner.settings.max_acceleration_mm_per_s2[E_AXIS]); - break; - case E1Acceleration: - sprintf_P(public_buf_m, PSTR("%d"), (int)planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(1)]); - break; - case XMaxFeedRate: - sprintf_P(public_buf_m, PSTR("%.1f"), planner.settings.max_feedrate_mm_s[X_AXIS]); - break; - case YMaxFeedRate: - sprintf_P(public_buf_m, PSTR("%.1f"), planner.settings.max_feedrate_mm_s[Y_AXIS]); - break; - case ZMaxFeedRate: - sprintf_P(public_buf_m, PSTR("%.1f"), planner.settings.max_feedrate_mm_s[Z_AXIS]); - break; - case E0MaxFeedRate: - sprintf_P(public_buf_m, PSTR("%.1f"), planner.settings.max_feedrate_mm_s[E_AXIS]); - break; - case E1MaxFeedRate: - sprintf_P(public_buf_m, PSTR("%.1f"), planner.settings.max_feedrate_mm_s[E_AXIS_N(1)]); - break; - - case XJerk: - #if HAS_CLASSIC_JERK - sprintf_P(public_buf_m, PSTR("%.1f"), planner.max_jerk[X_AXIS]); - #endif - break; - case YJerk: - #if HAS_CLASSIC_JERK - sprintf_P(public_buf_m, PSTR("%.1f"), planner.max_jerk[Y_AXIS]); - #endif - break; - case ZJerk: - #if HAS_CLASSIC_JERK - sprintf_P(public_buf_m, PSTR("%.1f"), planner.max_jerk[Z_AXIS]); - #endif - break; - case EJerk: - #if HAS_CLASSIC_JERK - sprintf_P(public_buf_m, PSTR("%.1f"), planner.max_jerk[E_AXIS]); - #endif - break; - - case Xstep: - sprintf_P(public_buf_m, PSTR("%.1f"), planner.settings.axis_steps_per_mm[X_AXIS]); - - break; - case Ystep: - sprintf_P(public_buf_m, PSTR("%.1f"), planner.settings.axis_steps_per_mm[Y_AXIS]); - - break; - case Zstep: - sprintf_P(public_buf_m, PSTR("%.1f"), planner.settings.axis_steps_per_mm[Z_AXIS]); - - break; - case E0step: - sprintf_P(public_buf_m, PSTR("%.1f"), planner.settings.axis_steps_per_mm[E_AXIS]); - - break; - case E1step: - sprintf_P(public_buf_m, PSTR("%.1f"), planner.settings.axis_steps_per_mm[E_AXIS_N(1)]); - break; - - case Xcurrent: - #if AXIS_IS_TMC(X) - milliamps = stepperX.getMilliamps(); - sprintf_P(public_buf_m, PSTR("%.1f"), milliamps); - #endif - break; - - case Ycurrent: - #if AXIS_IS_TMC(Y) - milliamps = stepperY.getMilliamps(); - sprintf_P(public_buf_m, PSTR("%.1f"), milliamps); - #endif - break; - - case Zcurrent: - #if AXIS_IS_TMC(Z) - milliamps = stepperZ.getMilliamps(); - sprintf_P(public_buf_m, PSTR("%.1f"), milliamps); - #endif - break; - - case E0current: - #if AXIS_IS_TMC(E0) - milliamps = stepperE0.getMilliamps(); - sprintf_P(public_buf_m, PSTR("%.1f"), milliamps); - #endif - break; - - case E1current: - #if AXIS_IS_TMC(E1) - milliamps = stepperE1.getMilliamps(); - sprintf_P(public_buf_m, PSTR("%.1f"), milliamps); - #endif - break; - - case pause_pos_x: - sprintf_P(public_buf_m, PSTR("%.1f"), gCfgItems.pausePosX); - break; - case pause_pos_y: - sprintf_P(public_buf_m, PSTR("%.1f"), gCfgItems.pausePosY); - break; - case pause_pos_z: - sprintf_P(public_buf_m, PSTR("%.1f"), gCfgItems.pausePosZ); - break; - case level_pos_x1: - sprintf_P(public_buf_m, PSTR("%d"), (int)gCfgItems.levelingPos[0][0]); - break; - case level_pos_y1: - sprintf_P(public_buf_m, PSTR("%d"), (int)gCfgItems.levelingPos[0][1]); - break; - case level_pos_x2: - sprintf_P(public_buf_m, PSTR("%d"), (int)gCfgItems.levelingPos[1][0]); - break; - case level_pos_y2: - sprintf_P(public_buf_m, PSTR("%d"), (int)gCfgItems.levelingPos[1][1]); - break; - case level_pos_x3: - sprintf_P(public_buf_m, PSTR("%d"), (int)gCfgItems.levelingPos[2][0]); - break; - case level_pos_y3: - sprintf_P(public_buf_m, PSTR("%d"), (int)gCfgItems.levelingPos[2][1]); - break; - case level_pos_x4: - sprintf_P(public_buf_m, PSTR("%d"), (int)gCfgItems.levelingPos[3][0]); - break; - case level_pos_y4: - sprintf_P(public_buf_m, PSTR("%d"), (int)gCfgItems.levelingPos[3][1]); - break; - case level_pos_x5: - sprintf_P(public_buf_m, PSTR("%d"), (int)gCfgItems.levelingPos[4][0]); - break; - case level_pos_y5: - sprintf_P(public_buf_m, PSTR("%d"), (int)gCfgItems.levelingPos[4][1]); - break; - #if HAS_BED_PROBE - case x_offset: - #if HAS_PROBE_XY_OFFSET - sprintf_P(public_buf_m, PSTR("%.1f"), probe.offset.x); - #endif - break; - case y_offset: - #if HAS_PROBE_XY_OFFSET - sprintf_P(public_buf_m, PSTR("%.1f"), probe.offset.y); - #endif - break; - case z_offset: - sprintf_P(public_buf_m, PSTR("%.1f"), probe.offset.z); - break; - #endif - case load_length: - sprintf_P(public_buf_m, PSTR("%d"), gCfgItems.filamentchange_load_length); - break; - case load_speed: - sprintf_P(public_buf_m, PSTR("%d"), gCfgItems.filamentchange_load_speed); - break; - case unload_length: - sprintf_P(public_buf_m, PSTR("%d"), gCfgItems.filamentchange_unload_length); - break; - case unload_speed: - sprintf_P(public_buf_m, PSTR("%d"), gCfgItems.filamentchange_unload_speed); - break; - case filament_temp: - sprintf_P(public_buf_m, PSTR("%d"), gCfgItems.filament_limit_temper); - break; - case x_sensitivity: - #if X_SENSORLESS - sprintf_P(public_buf_m, PSTR("%d"), TERN(X_SENSORLESS, stepperX.homing_threshold(), 0)); - #endif - break; - case y_sensitivity: - #if Y_SENSORLESS - sprintf_P(public_buf_m, PSTR("%d"), TERN(Y_SENSORLESS, stepperY.homing_threshold(), 0)); - #endif - break; - case z_sensitivity: - #if Z_SENSORLESS - sprintf_P(public_buf_m, PSTR("%d"), TERN(Z_SENSORLESS, stepperZ.homing_threshold(), 0)); - #endif - break; - case z2_sensitivity: - #if Z2_SENSORLESS - sprintf_P(public_buf_m, PSTR("%d"), TERN(Z2_SENSORLESS, stepperZ2.homing_threshold(), 0)); - #endif - break; - } - ZERO(key_value); - strcpy(key_value, public_buf_m); - cnt = strlen(key_value); - temp = strchr(key_value, '.'); - if (temp) - point_flg = 0; - else - point_flg = 1; - lv_label_set_text(labelValue, key_value); - lv_obj_align(labelValue, buttonValue, LV_ALIGN_CENTER, 0, 0); - -} - -static void set_value_confirm() { - #if HAS_TRINAMIC_CONFIG - uint16_t current_mA; - #endif - switch (value) { - case PrintAcceleration: - planner.settings.acceleration = atof(key_value); - break; - case RetractAcceleration: - planner.settings.retract_acceleration = atof(key_value); - break; - case TravelAcceleration: - planner.settings.travel_acceleration = atof(key_value); - break; - case XAcceleration: - planner.settings.max_acceleration_mm_per_s2[X_AXIS] = atof(key_value); - break; - case YAcceleration: - planner.settings.max_acceleration_mm_per_s2[Y_AXIS] = atof(key_value); - break; - case ZAcceleration: - planner.settings.max_acceleration_mm_per_s2[Z_AXIS] = atof(key_value); - break; - case E0Acceleration: - planner.settings.max_acceleration_mm_per_s2[E_AXIS] = atof(key_value); - break; - case E1Acceleration: - planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(1)] = atof(key_value); - break; - case XMaxFeedRate: - planner.settings.max_feedrate_mm_s[X_AXIS] = atof(key_value); - break; - case YMaxFeedRate: - planner.settings.max_feedrate_mm_s[Y_AXIS] = atof(key_value); - break; - case ZMaxFeedRate: - planner.settings.max_feedrate_mm_s[Z_AXIS] = atof(key_value); - break; - case E0MaxFeedRate: - planner.settings.max_feedrate_mm_s[E_AXIS] = atof(key_value); - break; - case E1MaxFeedRate: - planner.settings.max_feedrate_mm_s[E_AXIS_N(1)] = atof(key_value); - break; - case XJerk: - #if HAS_CLASSIC_JERK - planner.max_jerk[X_AXIS] = atof(key_value); - #endif - break; - case YJerk: - #if HAS_CLASSIC_JERK - planner.max_jerk[Y_AXIS] = atof(key_value); - #endif - break; - case ZJerk: - #if HAS_CLASSIC_JERK - planner.max_jerk[Z_AXIS] = atof(key_value); - #endif - break; - case EJerk: - #if HAS_CLASSIC_JERK - planner.max_jerk[E_AXIS] = atof(key_value); - #endif - break; - case Xstep: - planner.settings.axis_steps_per_mm[X_AXIS] = atof(key_value); - planner.refresh_positioning(); - break; - case Ystep: - planner.settings.axis_steps_per_mm[Y_AXIS] = atof(key_value); - planner.refresh_positioning(); - break; - case Zstep: - planner.settings.axis_steps_per_mm[Z_AXIS] = atof(key_value); - planner.refresh_positioning(); - break; - case E0step: - planner.settings.axis_steps_per_mm[E_AXIS] = atof(key_value); - planner.refresh_positioning(); - break; - case E1step: - planner.settings.axis_steps_per_mm[E_AXIS_N(1)] = atof(key_value); - planner.refresh_positioning(); - break; - case Xcurrent: - #if AXIS_IS_TMC(X) - current_mA = atoi(key_value); - stepperX.rms_current(current_mA); - #endif - break; - case Ycurrent: - #if AXIS_IS_TMC(Y) - current_mA = atoi(key_value); - stepperY.rms_current(current_mA); - #endif - break; - case Zcurrent: - #if AXIS_IS_TMC(Z) - current_mA = atoi(key_value); - stepperZ.rms_current(current_mA); - #endif - break; - case E0current: - #if AXIS_IS_TMC(E0) - current_mA = atoi(key_value); - stepperE0.rms_current(current_mA); - #endif - break; - case E1current: - #if AXIS_IS_TMC(E1) - current_mA = atoi(key_value); - stepperE1.rms_current(current_mA); - #endif - break; - case pause_pos_x: - gCfgItems.pausePosX = atof(key_value); - update_spi_flash(); - break; - case pause_pos_y: - gCfgItems.pausePosY = atof(key_value); - update_spi_flash(); - break; - case pause_pos_z: - gCfgItems.pausePosZ = atof(key_value); - update_spi_flash(); - break; - case level_pos_x1: - gCfgItems.levelingPos[0][0] = atoi(key_value); - update_spi_flash(); - break; - case level_pos_y1: - gCfgItems.levelingPos[0][1] = atoi(key_value); - update_spi_flash(); - break; - case level_pos_x2: - gCfgItems.levelingPos[1][0] = atoi(key_value); - update_spi_flash(); - break; - case level_pos_y2: - gCfgItems.levelingPos[1][1] = atoi(key_value); - update_spi_flash(); - break; - case level_pos_x3: - gCfgItems.levelingPos[2][0] = atoi(key_value); - update_spi_flash(); - break; - case level_pos_y3: - gCfgItems.levelingPos[2][1] = atoi(key_value); - update_spi_flash(); - break; - case level_pos_x4: - gCfgItems.levelingPos[3][0] = atoi(key_value); - update_spi_flash(); - break; - case level_pos_y4: - gCfgItems.levelingPos[3][1] = atoi(key_value); - update_spi_flash(); - break; - case level_pos_x5: - gCfgItems.levelingPos[4][0] = atoi(key_value); - update_spi_flash(); - break; - case level_pos_y5: - gCfgItems.levelingPos[4][1] = atoi(key_value); - update_spi_flash(); - break; - #if HAS_BED_PROBE - case x_offset: - #if HAS_PROBE_XY_OFFSET - float x; - x = atof(key_value); - if (WITHIN(x, -(X_BED_SIZE), X_BED_SIZE)) - probe.offset.x = x; - #endif - break; - case y_offset: - #if HAS_PROBE_XY_OFFSET - float y; - y = atof(key_value); - if (WITHIN(y, -(Y_BED_SIZE), Y_BED_SIZE)) - probe.offset.y = y; - #endif - break; - case z_offset: - float z; - z = atof(key_value); - if (WITHIN(z, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX)) - probe.offset.z = z; - break; - #endif - case load_length: - gCfgItems.filamentchange_load_length = atoi(key_value); - uiCfg.filament_loading_time = (uint32_t)((gCfgItems.filamentchange_load_length*60.0/gCfgItems.filamentchange_load_speed)+0.5); - update_spi_flash(); - break; - case load_speed: - gCfgItems.filamentchange_load_speed = atoi(key_value); - uiCfg.filament_loading_time = (uint32_t)((gCfgItems.filamentchange_load_length*60.0/gCfgItems.filamentchange_load_speed)+0.5); - update_spi_flash(); - break; - case unload_length: - gCfgItems.filamentchange_unload_length = atoi(key_value); - uiCfg.filament_unloading_time = (uint32_t)((gCfgItems.filamentchange_unload_length*60.0/gCfgItems.filamentchange_unload_speed)+0.5); - update_spi_flash(); - break; - case unload_speed: - gCfgItems.filamentchange_unload_speed = atoi(key_value); - uiCfg.filament_unloading_time = (uint32_t)((gCfgItems.filamentchange_unload_length*60.0/gCfgItems.filamentchange_unload_speed)+0.5); - update_spi_flash(); - break; - case filament_temp: - gCfgItems.filament_limit_temper = atoi(key_value); - update_spi_flash(); - break; - case x_sensitivity: - #if X_SENSORLESS - stepperX.homing_threshold(atoi(key_value)); - #endif - break; - case y_sensitivity: - #if Y_SENSORLESS - stepperY.homing_threshold(atoi(key_value)); - #endif - break; - case z_sensitivity: - #if Z_SENSORLESS - stepperZ.homing_threshold(atoi(key_value)); - #endif - break; - case z2_sensitivity: - #if Z2_SENSORLESS - stepperZ2.homing_threshold(atoi(key_value)); - #endif - break; - } - gcode.process_subcommands_now_P(PSTR("M500")); -} - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_NUM_KEY1: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - if (cnt <= 10) { - key_value[cnt] = (char)'1'; - lv_label_set_text(labelValue, key_value); - lv_obj_align(labelValue, buttonValue, LV_ALIGN_CENTER, 0, 0); - cnt++; - } - } - break; - case ID_NUM_KEY2: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - if (cnt <= 10) { - key_value[cnt] = (char)'2'; - lv_label_set_text(labelValue, key_value); - lv_obj_align(labelValue, buttonValue, LV_ALIGN_CENTER, 0, 0); - cnt++; - } - } - break; - case ID_NUM_KEY3: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - if (cnt <= 10) { - key_value[cnt] = (char)'3'; - lv_label_set_text(labelValue, key_value); - lv_obj_align(labelValue, buttonValue, LV_ALIGN_CENTER, 0, 0); - cnt++; - } - } - break; - case ID_NUM_KEY4: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - if (cnt <= 10) { - key_value[cnt] = (char)'4'; - lv_label_set_text(labelValue, key_value); - lv_obj_align(labelValue, buttonValue, LV_ALIGN_CENTER, 0, 0); - cnt++; - } - } - break; - case ID_NUM_KEY5: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - if (cnt <= 10) { - key_value[cnt] = (char)'5'; - lv_label_set_text(labelValue, key_value); - lv_obj_align(labelValue, buttonValue, LV_ALIGN_CENTER, 0, 0); - cnt++; - } - } - break; - case ID_NUM_KEY6: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - if (cnt <= 10) { - key_value[cnt] = (char)'6'; - lv_label_set_text(labelValue, key_value); - lv_obj_align(labelValue, buttonValue, LV_ALIGN_CENTER, 0, 0); - cnt++; - } - } - break; - case ID_NUM_KEY7: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - if (cnt <= 10) { - key_value[cnt] = (char)'7'; - lv_label_set_text(labelValue, key_value); - lv_obj_align(labelValue, buttonValue, LV_ALIGN_CENTER, 0, 0); - cnt++; - } - } - break; - case ID_NUM_KEY8: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - if (cnt <= 10) { - key_value[cnt] = (char)'8'; - lv_label_set_text(labelValue, key_value); - lv_obj_align(labelValue, buttonValue, LV_ALIGN_CENTER, 0, 0); - cnt++; - } - } - break; - case ID_NUM_KEY9: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - if (cnt <= 10) { - key_value[cnt] = (char)'9'; - lv_label_set_text(labelValue, key_value); - lv_obj_align(labelValue, buttonValue, LV_ALIGN_CENTER, 0, 0); - cnt++; - } - } - break; - case ID_NUM_KEY0: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - if (cnt <= 10) { - key_value[cnt] = (char)'0'; - lv_label_set_text(labelValue, key_value); - lv_obj_align(labelValue, buttonValue, LV_ALIGN_CENTER, 0, 0); - cnt++; - } - } - break; - case ID_NUM_BACK: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - if (cnt > 0) - cnt--; - if (key_value[cnt] == (char)'.') point_flg = 1; - key_value[cnt] = (char)'\0'; - lv_label_set_text(labelValue, key_value); - lv_obj_align(labelValue, buttonValue, LV_ALIGN_CENTER, 0, 0); - } - break; - case ID_NUM_RESET: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - ZERO(key_value); - cnt = 0; - key_value[cnt] = (char)'0'; - point_flg = 1; - lv_label_set_text(labelValue, key_value); - lv_obj_align(labelValue, buttonValue, LV_ALIGN_CENTER, 0, 0); - } - break; - case ID_NUM_POINT: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - if ((cnt != 0) && (point_flg == 1)) { - point_flg = 0; - key_value[cnt] = (char)'.'; - lv_label_set_text(labelValue, key_value); - lv_obj_align(labelValue, buttonValue, LV_ALIGN_CENTER, 0, 0); - cnt++; - } - } - break; - case ID_NUM_NAGETIVE: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - if (cnt == 0) { - key_value[cnt] = (char)'-'; - lv_label_set_text(labelValue, key_value); - lv_obj_align(labelValue, buttonValue, LV_ALIGN_CENTER, 0, 0); - cnt++; - } - } - break; - case ID_NUM_CONFIRM: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - last_disp_state = NUMBER_KEY_UI; - if (strlen(key_value) != 0) - set_value_confirm(); - lv_clear_number_key(); - draw_return_ui(); - } - break; - } -} - -void lv_draw_number_key(void) { - lv_obj_t *NumberKey_1 = NULL, *NumberKey_2 = NULL, *NumberKey_3 = NULL, *NumberKey_4 = NULL, *NumberKey_5 = NULL; - lv_obj_t *NumberKey_6 = NULL, *NumberKey_7 = NULL, *NumberKey_8 = NULL, *NumberKey_9 = NULL, *NumberKey_0 = NULL; - lv_obj_t *KeyPoint = NULL, *KeyConfirm = NULL, *KeyReset = NULL, *KeyBack = NULL; - lv_obj_t *Minus = NULL; - lv_obj_t *labelKey_1 = NULL, *labelKey_2 = NULL, *labelKey_3 = NULL, *labelKey_4 = NULL, *labelKey_5 = NULL; - lv_obj_t *labelKey_6 = NULL, *labelKey_7 = NULL, *labelKey_8 = NULL, *labelKey_9 = NULL, *labelKey_0 = NULL; - lv_obj_t *labelKeyPoint = NULL, *labelKeyConfirm = NULL, *labelKeyReset = NULL, *labelKeyBack = NULL; - lv_obj_t *labelMinus = NULL; - - buttonValue = NULL; - labelValue = NULL; - - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != NUMBER_KEY_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = NUMBER_KEY_UI; - } - disp_state = NUMBER_KEY_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - //lv_obj_t * title = lv_label_create(scr, NULL); - //lv_obj_set_style(title, &tft_style_label_rel); - //lv_obj_set_pos(title,TITLE_XPOS,TITLE_YPOS); - //lv_label_set_text(title, creat_title_text()); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - buttonValue = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonValue, 92, 40); /*Set its position*/ - lv_obj_set_size(buttonValue, 296, 40); - lv_obj_set_event_cb_mks(buttonValue, event_handler, ID_NUM_KEY1, NULL, 0); - lv_btn_set_style(buttonValue, LV_BTN_STYLE_REL, &style_num_text); /*Set the button's released style*/ - lv_btn_set_style(buttonValue, LV_BTN_STYLE_PR, &style_num_text); /*Set the button's pressed style*/ - //lv_btn_set_layout(buttonValue, LV_LAYOUT_OFF); - labelValue = lv_label_create(buttonValue, NULL); /*Add a label to the button*/ - - NumberKey_1 = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(NumberKey_1, 92, 90); /*Set its position*/ - lv_obj_set_size(NumberKey_1, 68, 40); - lv_obj_set_event_cb_mks(NumberKey_1, event_handler, ID_NUM_KEY1, NULL, 0); - lv_btn_set_style(NumberKey_1, LV_BTN_STYLE_REL, &style_num_key_pre); /*Set the button's released style*/ - lv_btn_set_style(NumberKey_1, LV_BTN_STYLE_PR, &style_num_key_rel); /*Set the button's pressed style*/ - //lv_btn_set_layout(NumberKey_1, LV_LAYOUT_OFF); - labelKey_1 = lv_label_create(NumberKey_1, NULL); /*Add a label to the button*/ - lv_label_set_text(labelKey_1, machine_menu.key_1); - lv_obj_align(labelKey_1, NumberKey_1, LV_ALIGN_CENTER, 0, 0); - - NumberKey_2 = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(NumberKey_2, 168, 90); /*Set its position*/ - lv_obj_set_size(NumberKey_2, 68, 40); - lv_obj_set_event_cb_mks(NumberKey_2, event_handler, ID_NUM_KEY2, NULL, 0); - lv_btn_set_style(NumberKey_2, LV_BTN_STYLE_REL, &style_num_key_pre); /*Set the button's released style*/ - lv_btn_set_style(NumberKey_2, LV_BTN_STYLE_PR, &style_num_key_rel); /*Set the button's pressed style*/ - //lv_btn_set_layout(NumberKey_2, LV_LAYOUT_OFF); - labelKey_2 = lv_label_create(NumberKey_2, NULL); /*Add a label to the button*/ - lv_label_set_text(labelKey_2, machine_menu.key_2); - lv_obj_align(labelKey_2, NumberKey_2, LV_ALIGN_CENTER, 0, 0); - - NumberKey_3 = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(NumberKey_3, 244, 90); /*Set its position*/ - lv_obj_set_size(NumberKey_3, 68, 40); - lv_obj_set_event_cb_mks(NumberKey_3, event_handler, ID_NUM_KEY3, NULL, 0); - lv_btn_set_style(NumberKey_3, LV_BTN_STYLE_REL, &style_num_key_pre); /*Set the button's released style*/ - lv_btn_set_style(NumberKey_3, LV_BTN_STYLE_PR, &style_num_key_rel); /*Set the button's pressed style*/ - //lv_btn_set_layout(NumberKey_3, LV_LAYOUT_OFF); - labelKey_3 = lv_label_create(NumberKey_3, NULL); /*Add a label to the button*/ - lv_label_set_text(labelKey_3, machine_menu.key_3); - lv_obj_align(labelKey_3, NumberKey_3, LV_ALIGN_CENTER, 0, 0); - - NumberKey_4 = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(NumberKey_4, 92, 140); /*Set its position*/ - lv_obj_set_size(NumberKey_4, 68, 40); - lv_obj_set_event_cb_mks(NumberKey_4, event_handler, ID_NUM_KEY4, NULL, 0); - lv_btn_set_style(NumberKey_4, LV_BTN_STYLE_REL, &style_num_key_pre); /*Set the button's released style*/ - lv_btn_set_style(NumberKey_4, LV_BTN_STYLE_PR, &style_num_key_rel); /*Set the button's pressed style*/ - //lv_btn_set_layout(NumberKey_4, LV_LAYOUT_OFF); - labelKey_4 = lv_label_create(NumberKey_4, NULL); /*Add a label to the button*/ - lv_label_set_text(labelKey_4, machine_menu.key_4); - lv_obj_align(labelKey_4, NumberKey_4, LV_ALIGN_CENTER, 0, 0); - - NumberKey_5 = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(NumberKey_5, 168, 140); /*Set its position*/ - lv_obj_set_size(NumberKey_5, 68, 40); - lv_obj_set_event_cb_mks(NumberKey_5, event_handler, ID_NUM_KEY5, NULL, 0); - lv_btn_set_style(NumberKey_5, LV_BTN_STYLE_REL, &style_num_key_pre); /*Set the button's released style*/ - lv_btn_set_style(NumberKey_5, LV_BTN_STYLE_PR, &style_num_key_rel); /*Set the button's pressed style*/ - //lv_btn_set_layout(NumberKey_5, LV_LAYOUT_OFF); - labelKey_5 = lv_label_create(NumberKey_5, NULL); /*Add a label to the button*/ - lv_label_set_text(labelKey_5, machine_menu.key_5); - lv_obj_align(labelKey_5, NumberKey_5, LV_ALIGN_CENTER, 0, 0); - - NumberKey_6 = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(NumberKey_6, 244, 140); /*Set its position*/ - lv_obj_set_size(NumberKey_6, 68, 40); - lv_obj_set_event_cb_mks(NumberKey_6, event_handler, ID_NUM_KEY6, NULL, 0); - lv_btn_set_style(NumberKey_6, LV_BTN_STYLE_REL, &style_num_key_pre); /*Set the button's released style*/ - lv_btn_set_style(NumberKey_6, LV_BTN_STYLE_PR, &style_num_key_rel); /*Set the button's pressed style*/ - //lv_btn_set_layout(NumberKey_6, LV_LAYOUT_OFF); - labelKey_6 = lv_label_create(NumberKey_6, NULL); /*Add a label to the button*/ - lv_label_set_text(labelKey_6, machine_menu.key_6); - lv_obj_align(labelKey_6, NumberKey_6, LV_ALIGN_CENTER, 0, 0); - - NumberKey_7 = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(NumberKey_7, 92, 190); /*Set its position*/ - lv_obj_set_size(NumberKey_7, 68, 40); - lv_obj_set_event_cb_mks(NumberKey_7, event_handler, ID_NUM_KEY7, NULL, 0); - lv_btn_set_style(NumberKey_7, LV_BTN_STYLE_REL, &style_num_key_pre); /*Set the button's released style*/ - lv_btn_set_style(NumberKey_7, LV_BTN_STYLE_PR, &style_num_key_rel); /*Set the button's pressed style*/ - //lv_btn_set_layout(NumberKey_7, LV_LAYOUT_OFF); - labelKey_7 = lv_label_create(NumberKey_7, NULL); /*Add a label to the button*/ - lv_label_set_text(labelKey_7, machine_menu.key_7); - lv_obj_align(labelKey_7, NumberKey_7, LV_ALIGN_CENTER, 0, 0); - - NumberKey_8 = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(NumberKey_8, 168, 190); /*Set its position*/ - lv_obj_set_size(NumberKey_8, 68, 40); - lv_obj_set_event_cb_mks(NumberKey_8, event_handler, ID_NUM_KEY8, NULL, 0); - lv_btn_set_style(NumberKey_8, LV_BTN_STYLE_REL, &style_num_key_pre); /*Set the button's released style*/ - lv_btn_set_style(NumberKey_8, LV_BTN_STYLE_PR, &style_num_key_rel); /*Set the button's pressed style*/ - //lv_btn_set_layout(NumberKey_8, LV_LAYOUT_OFF); - labelKey_8 = lv_label_create(NumberKey_8, NULL); /*Add a label to the button*/ - lv_label_set_text(labelKey_8, machine_menu.key_8); - lv_obj_align(labelKey_8, NumberKey_8, LV_ALIGN_CENTER, 0, 0); - - NumberKey_9 = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(NumberKey_9, 244, 190); /*Set its position*/ - lv_obj_set_size(NumberKey_9, 68, 40); - lv_obj_set_event_cb_mks(NumberKey_9, event_handler, ID_NUM_KEY9, NULL, 0); - lv_btn_set_style(NumberKey_9, LV_BTN_STYLE_REL, &style_num_key_pre); /*Set the button's released style*/ - lv_btn_set_style(NumberKey_9, LV_BTN_STYLE_PR, &style_num_key_rel); /*Set the button's pressed style*/ - //lv_btn_set_layout(NumberKey_9, LV_LAYOUT_OFF); - labelKey_9 = lv_label_create(NumberKey_9, NULL); /*Add a label to the button*/ - lv_label_set_text(labelKey_9, machine_menu.key_9); - lv_obj_align(labelKey_9, NumberKey_9, LV_ALIGN_CENTER, 0, 0); - - NumberKey_0 = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(NumberKey_0, 92, 240); /*Set its position*/ - lv_obj_set_size(NumberKey_0, 68, 40); - lv_obj_set_event_cb_mks(NumberKey_0, event_handler, ID_NUM_KEY0, NULL, 0); - lv_btn_set_style(NumberKey_0, LV_BTN_STYLE_REL, &style_num_key_pre); /*Set the button's released style*/ - lv_btn_set_style(NumberKey_0, LV_BTN_STYLE_PR, &style_num_key_rel); /*Set the button's pressed style*/ - //lv_btn_set_layout(NumberKey_0, LV_LAYOUT_OFF); - labelKey_0 = lv_label_create(NumberKey_0, NULL); /*Add a label to the button*/ - lv_label_set_text(labelKey_0, machine_menu.key_0); - lv_obj_align(labelKey_0, NumberKey_0, LV_ALIGN_CENTER, 0, 0); - - KeyBack = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(KeyBack, 320, 90); /*Set its position*/ - lv_obj_set_size(KeyBack, 68, 40); - lv_obj_set_event_cb_mks(KeyBack, event_handler, ID_NUM_BACK, NULL, 0); - lv_btn_set_style(KeyBack, LV_BTN_STYLE_REL, &style_num_key_pre); /*Set the button's released style*/ - lv_btn_set_style(KeyBack, LV_BTN_STYLE_PR, &style_num_key_rel); /*Set the button's pressed style*/ - //lv_btn_set_layout(KeyBack, LV_LAYOUT_OFF); - labelKeyBack = lv_label_create(KeyBack, NULL); /*Add a label to the button*/ - lv_label_set_text(labelKeyBack, machine_menu.key_back); - lv_obj_align(labelKeyBack, KeyBack, LV_ALIGN_CENTER, 0, 0); - - KeyReset = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(KeyReset, 320, 140); /*Set its position*/ - lv_obj_set_size(KeyReset, 68, 40); - lv_obj_set_event_cb_mks(KeyReset, event_handler, ID_NUM_RESET, NULL, 0); - lv_btn_set_style(KeyReset, LV_BTN_STYLE_REL, &style_num_key_pre); /*Set the button's released style*/ - lv_btn_set_style(KeyReset, LV_BTN_STYLE_PR, &style_num_key_rel); /*Set the button's pressed style*/ - //lv_btn_set_layout(KeyReset, LV_LAYOUT_OFF); - labelKeyReset = lv_label_create(KeyReset, NULL); /*Add a label to the button*/ - lv_label_set_text(labelKeyReset, machine_menu.key_reset); - lv_obj_align(labelKeyReset, KeyReset, LV_ALIGN_CENTER, 0, 0); - - KeyConfirm = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(KeyConfirm, 320, 190); /*Set its position*/ - lv_obj_set_size(KeyConfirm, 68, 90); - lv_obj_set_event_cb_mks(KeyConfirm, event_handler, ID_NUM_CONFIRM, NULL, 0); - lv_btn_set_style(KeyConfirm, LV_BTN_STYLE_REL, &style_num_key_pre); /*Set the button's released style*/ - lv_btn_set_style(KeyConfirm, LV_BTN_STYLE_PR, &style_num_key_rel); /*Set the button's pressed style*/ - //lv_btn_set_layout(KeyConfirm, LV_LAYOUT_OFF); - labelKeyConfirm = lv_label_create(KeyConfirm, NULL); /*Add a label to the button*/ - lv_label_set_text(labelKeyConfirm, machine_menu.key_confirm); - lv_obj_align(labelKeyConfirm, KeyConfirm, LV_ALIGN_CENTER, 0, 0); - - KeyPoint = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(KeyPoint, 244, 240); /*Set its position*/ - lv_obj_set_size(KeyPoint, 68, 40); - lv_obj_set_event_cb_mks(KeyPoint, event_handler, ID_NUM_POINT, NULL, 0); - lv_btn_set_style(KeyPoint, LV_BTN_STYLE_REL, &style_num_key_pre); /*Set the button's released style*/ - lv_btn_set_style(KeyPoint, LV_BTN_STYLE_PR, &style_num_key_rel); /*Set the button's pressed style*/ - //lv_btn_set_layout(KeyPoint, LV_LAYOUT_OFF); - labelKeyPoint = lv_label_create(KeyPoint, NULL); /*Add a label to the button*/ - lv_label_set_text(labelKeyPoint, machine_menu.key_point); - lv_obj_align(labelKeyPoint, KeyPoint, LV_ALIGN_CENTER, 0, 0); - - Minus = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(Minus, 168, 240); /*Set its position*/ - lv_obj_set_size(Minus, 68, 40); - lv_obj_set_event_cb_mks(Minus, event_handler, ID_NUM_NAGETIVE, NULL, 0); - lv_btn_set_style(Minus, LV_BTN_STYLE_REL, &style_num_key_pre); /*Set the button's released style*/ - lv_btn_set_style(Minus, LV_BTN_STYLE_PR, &style_num_key_rel); /*Set the button's pressed style*/ - //lv_btn_set_layout(Minus, LV_LAYOUT_OFF); - labelMinus = lv_label_create(Minus, NULL); /*Add a label to the button*/ - lv_label_set_text(labelMinus, machine_menu.negative); - lv_obj_align(labelMinus, Minus, LV_ALIGN_CENTER, 0, 0); - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, NumberKey_1); - lv_group_add_obj(g, NumberKey_2); - lv_group_add_obj(g, NumberKey_3); - lv_group_add_obj(g, KeyBack); - lv_group_add_obj(g, NumberKey_4); - lv_group_add_obj(g, NumberKey_5); - lv_group_add_obj(g, NumberKey_6); - lv_group_add_obj(g, KeyReset); - lv_group_add_obj(g, NumberKey_7); - lv_group_add_obj(g, NumberKey_8); - lv_group_add_obj(g, NumberKey_9); - lv_group_add_obj(g, NumberKey_0); - lv_group_add_obj(g, Minus); - lv_group_add_obj(g, KeyPoint); - lv_group_add_obj(g, KeyConfirm); - } - #endif - - disp_key_value(); -} - -void lv_clear_number_key() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_operation.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_operation.cpp deleted file mode 100644 index 4a4a0ee1305b..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_operation.cpp +++ /dev/null @@ -1,413 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "lv_conf.h" -#include "draw_ui.h" -//#include "../lvgl/src/lv_objx/lv_imgbtn.h" -//#include "../lvgl/src/lv_objx/lv_img.h" -//#include "../lvgl/src/lv_core/lv_disp.h" -//#include "../lvgl/src/lv_core/lv_refr.h" - -#include "../../../../MarlinCore.h" -#include "../../../../module/temperature.h" -#include "../../../../module/motion.h" -#include "../../../../sd/cardreader.h" - -extern lv_group_t * g; -static lv_obj_t * scr; - -#define ID_O_PRE_HEAT 1 -#define ID_O_EXTRUCT 2 -#define ID_O_MOV 3 -#define ID_O_FILAMENT 4 -#define ID_O_SPEED 5 -#define ID_O_RETURN 6 -#define ID_O_FAN 7 -#define ID_O_POWER_OFF 8 -#define ID_O_BABY_STEP 9 - -static lv_obj_t *label_PowerOff; -static lv_obj_t *buttonPowerOff; - -extern feedRate_t feedrate_mm_s; - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_O_PRE_HEAT: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_operation(); - lv_draw_preHeat(); - } - break; - case ID_O_EXTRUCT: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_operation(); - lv_draw_extrusion(); - } - break; - case ID_O_MOV: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_operation(); - lv_draw_move_motor(); - } - break; - case ID_O_FILAMENT: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - #if HAS_MULTI_EXTRUDER - uiCfg.curSprayerChoose_bak = active_extruder; - #endif - if (uiCfg.print_state == WORKING) { - #if ENABLED(SDSUPPORT) - card.pauseSDPrint(); - stop_print_time(); - uiCfg.print_state = PAUSING; - #endif - } - uiCfg.moveSpeed_bak = (uint16_t)feedrate_mm_s; - uiCfg.desireSprayerTempBak = thermalManager.temp_hotend[active_extruder].target; - lv_clear_operation(); - lv_draw_filament_change(); - } - break; - case ID_O_FAN: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_operation(); - lv_draw_fan(); - } - break; - case ID_O_SPEED: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_operation(); - lv_draw_change_speed(); - } - break; - case ID_O_RETURN: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - clear_cur_ui(); - draw_return_ui(); - } - break; - case ID_O_POWER_OFF: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - if (gCfgItems.finish_power_off == 1) { - gCfgItems.finish_power_off = 0; - lv_imgbtn_set_src(buttonPowerOff, LV_BTN_STATE_REL, "F:/bmp_manual_off.bin"); - lv_imgbtn_set_src(buttonPowerOff, LV_BTN_STATE_PR, "F:/bmp_manual_off.bin"); - lv_label_set_text(label_PowerOff, printing_more_menu.manual); - lv_obj_align(label_PowerOff, buttonPowerOff, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - lv_obj_refresh_ext_draw_pad(label_PowerOff); - update_spi_flash(); - } - else { - gCfgItems.finish_power_off = 1; - lv_imgbtn_set_src(buttonPowerOff, LV_BTN_STATE_REL, "F:/bmp_auto_off.bin"); - lv_imgbtn_set_src(buttonPowerOff, LV_BTN_STATE_PR, "F:/bmp_auto_off.bin"); - lv_label_set_text(label_PowerOff, printing_more_menu.auto_close); - lv_obj_align(label_PowerOff, buttonPowerOff, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - lv_obj_refresh_ext_draw_pad(label_PowerOff); - update_spi_flash(); - } - } - break; - case ID_O_BABY_STEP: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_operation(); - lv_draw_baby_stepping(); - } - break; - } -} - -void lv_draw_operation(void) { - lv_obj_t *buttonPreHeat = NULL, *buttonExtrusion = NULL, *buttonSpeed = NULL; - lv_obj_t *buttonBack = NULL, *buttonFan = NULL; - lv_obj_t *labelPreHeat = NULL, *labelExtrusion = NULL; - lv_obj_t *label_Back = NULL, *label_Speed = NULL, *label_Fan = NULL; - lv_obj_t *buttonMove = NULL, *label_Move = NULL; - lv_obj_t *buttonBabyStep = NULL, *label_BabyStep = NULL; - lv_obj_t *buttonFilament = NULL, *label_Filament = NULL; - - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != OPERATE_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = OPERATE_UI; - } - disp_state = OPERATE_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, creat_title_text()); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - // Create image buttons - buttonPreHeat = lv_imgbtn_create(scr, NULL); - buttonFilament = lv_imgbtn_create(scr, NULL); - buttonFan = lv_imgbtn_create(scr, NULL); - buttonPowerOff = lv_imgbtn_create(scr, NULL); - if (uiCfg.print_state != WORKING) { - buttonExtrusion = lv_imgbtn_create(scr, NULL); - buttonMove = lv_imgbtn_create(scr, NULL); - } - else { - buttonSpeed = lv_imgbtn_create(scr, NULL); - buttonBabyStep = lv_imgbtn_create(scr, NULL); - } - buttonBack = lv_imgbtn_create(scr, NULL); - - lv_obj_set_event_cb_mks(buttonPreHeat, event_handler, ID_O_PRE_HEAT, NULL, 0); - lv_imgbtn_set_src(buttonPreHeat, LV_BTN_STATE_REL, "F:/bmp_temp.bin"); - lv_imgbtn_set_src(buttonPreHeat, LV_BTN_STATE_PR, "F:/bmp_temp.bin"); - lv_imgbtn_set_style(buttonPreHeat, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonPreHeat, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonFilament, event_handler, ID_O_FILAMENT, NULL, 0); - lv_imgbtn_set_src(buttonFilament, LV_BTN_STATE_REL, "F:/bmp_filamentchange.bin"); - lv_imgbtn_set_src(buttonFilament, LV_BTN_STATE_PR, "F:/bmp_filamentchange.bin"); - lv_imgbtn_set_style(buttonFilament, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonFilament, LV_BTN_STATE_REL, &tft_style_label_rel); - - #if 1 - lv_obj_set_event_cb_mks(buttonFan, event_handler, ID_O_FAN, NULL, 0); - lv_imgbtn_set_src(buttonFan, LV_BTN_STATE_REL, "F:/bmp_fan.bin"); - lv_imgbtn_set_src(buttonFan, LV_BTN_STATE_PR, "F:/bmp_fan.bin"); - lv_imgbtn_set_style(buttonFan, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonFan, LV_BTN_STATE_REL, &tft_style_label_rel); - - if (gCfgItems.finish_power_off == 1) { - lv_imgbtn_set_src(buttonPowerOff, LV_BTN_STATE_REL, "F:/bmp_auto_off.bin"); - lv_imgbtn_set_src(buttonPowerOff, LV_BTN_STATE_PR, "F:/bmp_auto_off.bin"); - } - else { - lv_imgbtn_set_src(buttonPowerOff, LV_BTN_STATE_REL, "F:/bmp_manual_off.bin"); - lv_imgbtn_set_src(buttonPowerOff, LV_BTN_STATE_PR, "F:/bmp_manual_off.bin"); - } - lv_obj_set_event_cb_mks(buttonPowerOff, event_handler, ID_O_POWER_OFF, NULL, 0); - lv_imgbtn_set_style(buttonPowerOff, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonPowerOff, LV_BTN_STATE_REL, &tft_style_label_rel); - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonPreHeat); - lv_group_add_obj(g, buttonFilament); - lv_group_add_obj(g, buttonFan); - lv_group_add_obj(g, buttonPowerOff); - } - #endif - - if (uiCfg.print_state != WORKING) { - lv_obj_set_event_cb_mks(buttonExtrusion, event_handler, ID_O_EXTRUCT, NULL, 0); - lv_imgbtn_set_src(buttonExtrusion, LV_BTN_STATE_REL, "F:/bmp_extrude_opr.bin"); - lv_imgbtn_set_src(buttonExtrusion, LV_BTN_STATE_PR, "F:/bmp_extrude_opr.bin"); - lv_imgbtn_set_style(buttonExtrusion, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonExtrusion, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonMove, event_handler, ID_O_MOV, NULL, 0); - lv_imgbtn_set_src(buttonMove, LV_BTN_STATE_REL, "F:/bmp_move_opr.bin"); - lv_imgbtn_set_src(buttonMove, LV_BTN_STATE_PR, "F:/bmp_move_opr.bin"); - lv_imgbtn_set_style(buttonMove, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonMove, LV_BTN_STATE_REL, &tft_style_label_rel); - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonExtrusion); - lv_group_add_obj(g, buttonMove); - } - #endif - } - else { - lv_obj_set_event_cb_mks(buttonSpeed, event_handler, ID_O_SPEED, NULL, 0); - lv_imgbtn_set_src(buttonSpeed, LV_BTN_STATE_REL, "F:/bmp_speed.bin"); - lv_imgbtn_set_src(buttonSpeed, LV_BTN_STATE_PR, "F:/bmp_speed.bin"); - lv_imgbtn_set_style(buttonSpeed, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonSpeed, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonBabyStep, event_handler, ID_O_BABY_STEP, NULL, 0); - lv_imgbtn_set_src(buttonBabyStep, LV_BTN_STATE_REL, "F:/bmp_mov.bin"); - lv_imgbtn_set_src(buttonBabyStep, LV_BTN_STATE_PR, "F:/bmp_mov.bin"); - lv_imgbtn_set_style(buttonBabyStep, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBabyStep, LV_BTN_STATE_REL, &tft_style_label_rel); - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonSpeed); - lv_group_add_obj(g, buttonBabyStep); - } - #endif - } - - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_O_RETURN, NULL, 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_return.bin"); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_return.bin"); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); - #endif // if 1 - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonBack); - #endif - - lv_obj_set_pos(buttonPreHeat, INTERVAL_V, titleHeight); - lv_obj_set_pos(buttonFilament, BTN_X_PIXEL + INTERVAL_V * 2, titleHeight); - lv_obj_set_pos(buttonFan, BTN_X_PIXEL * 2 + INTERVAL_V * 3, titleHeight); - lv_obj_set_pos(buttonPowerOff, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight); - - if (uiCfg.print_state != WORKING) { - /* - lv_obj_set_pos(buttonFilament,INTERVAL_V,BTN_Y_PIXEL+INTERVAL_H+titleHeight); - } else { - */ - lv_obj_set_pos(buttonExtrusion, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - lv_obj_set_pos(buttonMove, BTN_X_PIXEL + INTERVAL_V * 2, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - } - else { - lv_obj_set_pos(buttonSpeed, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - lv_obj_set_pos(buttonBabyStep, BTN_X_PIXEL + INTERVAL_V * 2, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - } - - lv_obj_set_pos(buttonBack, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - - // Create labels on the image buttons - lv_btn_set_layout(buttonPreHeat, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonFilament, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonFan, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonPowerOff, LV_LAYOUT_OFF); - - if (uiCfg.print_state != WORKING) { - /* - lv_btn_set_layout(buttonFilament, LV_LAYOUT_OFF); - } else { - */ - lv_btn_set_layout(buttonExtrusion, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonMove, LV_LAYOUT_OFF); - } - else { - lv_btn_set_layout(buttonSpeed, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonBabyStep, LV_LAYOUT_OFF); - } - - lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - - labelPreHeat = lv_label_create(buttonPreHeat, NULL); - label_Filament = lv_label_create(buttonFilament, NULL); - label_Fan = lv_label_create(buttonFan, NULL); - label_PowerOff = lv_label_create(buttonPowerOff, NULL); - - if (uiCfg.print_state != WORKING) { - /* - label_Filament = lv_label_create(buttonFilament, NULL); - } else { - */ - labelExtrusion = lv_label_create(buttonExtrusion, NULL); - label_Move = lv_label_create(buttonMove, NULL); - } - else { - label_Speed = lv_label_create(buttonSpeed, NULL); - label_BabyStep = lv_label_create(buttonBabyStep, NULL); - } - label_Back = lv_label_create(buttonBack, NULL); - - if (gCfgItems.multiple_language != 0) { - lv_label_set_text(labelPreHeat, operation_menu.temp); - lv_obj_align(labelPreHeat, buttonPreHeat, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_Filament, operation_menu.filament); - lv_obj_align(label_Filament, buttonFilament, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_Fan, operation_menu.fan); - lv_obj_align(label_Fan, buttonFan, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - if (gCfgItems.finish_power_off == 1) - lv_label_set_text(label_PowerOff, printing_more_menu.auto_close); - else - lv_label_set_text(label_PowerOff, printing_more_menu.manual); - lv_obj_align(label_PowerOff, buttonPowerOff, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - if (uiCfg.print_state != WORKING) { - /* - lv_label_set_text(label_Filament, operation_menu.filament); - lv_obj_align(label_Filament, buttonFilament, LV_ALIGN_IN_BOTTOM_MID,0, BUTTON_TEXT_Y_OFFSET); - } else { - */ - lv_label_set_text(labelExtrusion, operation_menu.extr); - lv_obj_align(labelExtrusion, buttonExtrusion, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_Move, operation_menu.move); - lv_obj_align(label_Move, buttonMove, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - else { - lv_label_set_text(label_Speed, operation_menu.speed); - lv_obj_align(label_Speed, buttonSpeed, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_BabyStep, operation_menu.babystep); - lv_obj_align(label_BabyStep, buttonBabyStep, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } -} - -void lv_clear_operation() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_pause_position.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_pause_position.cpp deleted file mode 100644 index 9b99971f4f96..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_pause_position.cpp +++ /dev/null @@ -1,202 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "lv_conf.h" -#include "draw_ui.h" - -#include "../../../../MarlinCore.h" -#include "../../../../module/planner.h" - -extern lv_group_t * g; -static lv_obj_t * scr; - -#define ID_PAUSE_RETURN 1 -#define ID_PAUSE_X 2 -#define ID_PAUSE_Y 3 -#define ID_PAUSE_Z 4 - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_PAUSE_RETURN: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_pause_position(); - draw_return_ui(); - } - break; - case ID_PAUSE_X: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = pause_pos_x; - lv_clear_pause_position(); - lv_draw_number_key(); - } - break; - case ID_PAUSE_Y: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = pause_pos_y; - lv_clear_pause_position(); - lv_draw_number_key(); - } - break; - case ID_PAUSE_Z: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = pause_pos_z; - lv_clear_pause_position(); - lv_draw_number_key(); - } - break; - } -} - -void lv_draw_pause_position(void) { - lv_obj_t *buttonBack = NULL, *label_Back = NULL; - lv_obj_t *labelXText = NULL, *buttonXValue = NULL, *labelXValue = NULL; - lv_obj_t *labelYText = NULL, *buttonYValue = NULL, *labelYValue = NULL; - lv_obj_t *labelZText = NULL, *buttonZValue = NULL, *labelZValue = NULL; - - lv_obj_t * line1 = NULL, * line2 = NULL, * line3 = NULL; - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != PAUSE_POS_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = PAUSE_POS_UI; - } - disp_state = PAUSE_POS_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, machine_menu.PausePosText); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - labelXText = lv_label_create(scr, NULL); - lv_obj_set_style(labelXText, &tft_style_label_rel); - lv_obj_set_pos(labelXText, PARA_UI_POS_X, PARA_UI_POS_Y + 10); - lv_label_set_text(labelXText, machine_menu.xPos); - - buttonXValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonXValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y + PARA_UI_VALUE_V); - lv_obj_set_size(buttonXValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_btn_set_style(buttonXValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonXValue, LV_BTN_STYLE_PR, &style_para_value); - lv_obj_set_event_cb_mks(buttonXValue, event_handler, ID_PAUSE_X, NULL, 0); - labelXValue = lv_label_create(buttonXValue, NULL); - - line1 = lv_line_create(scr, NULL); - lv_ex_line(line1, line_points[0]); - - labelYText = lv_label_create(scr, NULL); - lv_obj_set_style(labelYText, &tft_style_label_rel); - lv_obj_set_pos(labelYText, PARA_UI_POS_X, PARA_UI_POS_Y * 2 + 10); - lv_label_set_text(labelYText, machine_menu.yPos); - - buttonYValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonYValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 2 + PARA_UI_VALUE_V); - lv_obj_set_size(buttonYValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonYValue, event_handler, ID_PAUSE_Y, NULL, 0); - lv_btn_set_style(buttonYValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonYValue, LV_BTN_STYLE_PR, &style_para_value); - labelYValue = lv_label_create(buttonYValue, NULL); - - line2 = lv_line_create(scr, NULL); - lv_ex_line(line2, line_points[1]); - - labelZText = lv_label_create(scr, NULL); - lv_obj_set_style(labelZText, &tft_style_label_rel); - lv_obj_set_pos(labelZText, PARA_UI_POS_X, PARA_UI_POS_Y * 3 + 10); - lv_label_set_text(labelZText, machine_menu.zPos); - - buttonZValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonZValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 3 + PARA_UI_VALUE_V); - lv_obj_set_size(buttonZValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonZValue, event_handler, ID_PAUSE_Z, NULL, 0); - lv_btn_set_style(buttonZValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonZValue, LV_BTN_STYLE_PR, &style_para_value); - labelZValue = lv_label_create(buttonZValue, NULL); - - line3 = lv_line_create(scr, NULL); - lv_ex_line(line3, line_points[2]); - - buttonBack = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); - lv_obj_set_size(buttonBack, PARA_UI_BACK_BTN_X_SIZE, PARA_UI_BACK_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_PAUSE_RETURN, NULL, 0); - lv_btn_set_style(buttonBack, LV_BTN_STYLE_REL, &style_para_back); - lv_btn_set_style(buttonBack, LV_BTN_STYLE_PR, &style_para_back); - label_Back = lv_label_create(buttonBack, NULL); - - if (gCfgItems.multiple_language != 0) { - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%.1f"), gCfgItems.pausePosX); - lv_label_set_text(labelXValue, public_buf_l); - lv_obj_align(labelXValue, buttonXValue, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%.1f"), gCfgItems.pausePosY); - lv_label_set_text(labelYValue, public_buf_l); - lv_obj_align(labelYValue, buttonYValue, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%.1f"), gCfgItems.pausePosZ); - lv_label_set_text(labelZValue, public_buf_l); - lv_obj_align(labelZValue, buttonZValue, LV_ALIGN_CENTER, 0, 0); - - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_CENTER, 0, 0); - } - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonXValue); - lv_group_add_obj(g, buttonYValue); - lv_group_add_obj(g, buttonZValue); - lv_group_add_obj(g, buttonBack); - } - #endif -} - -void lv_clear_pause_position() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_preHeat.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_preHeat.cpp deleted file mode 100644 index f58a47b341b6..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_preHeat.cpp +++ /dev/null @@ -1,401 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "lv_conf.h" -#include "draw_ui.h" -//#include "../lvgl/src/lv_objx/lv_imgbtn.h" -//#include "../lvgl/src/lv_objx/lv_img.h" -//#include "../lvgl/src/lv_core/lv_disp.h" -//#include "../lvgl/src/lv_core/lv_refr.h" - -#include "../../../../MarlinCore.h" -#include "../../../../module/temperature.h" - -static lv_obj_t * scr; -extern lv_group_t* g; -static lv_obj_t *buttoType, *buttonStep; -static lv_obj_t *labelType; -static lv_obj_t *labelStep; -static lv_obj_t * tempText1; - -#define ID_P_ADD 1 -#define ID_P_DEC 2 -#define ID_P_TYPE 3 -#define ID_P_STEP 4 -#define ID_P_OFF 5 -#define ID_P_RETURN 6 - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_P_ADD: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - if (uiCfg.curTempType == 0) { - thermalManager.temp_hotend[uiCfg.curSprayerChoose].target += uiCfg.stepHeat; - if (uiCfg.curSprayerChoose == 0) { - if ((int)thermalManager.temp_hotend[uiCfg.curSprayerChoose].target > (HEATER_0_MAXTEMP - (WATCH_TEMP_INCREASE + TEMP_HYSTERESIS + 1))) { - thermalManager.temp_hotend[uiCfg.curSprayerChoose].target = (float)HEATER_0_MAXTEMP - (WATCH_TEMP_INCREASE + TEMP_HYSTERESIS + 1); - } - } - #if !defined(SINGLENOZZLE) && HAS_MULTI_EXTRUDER - else if ((int)thermalManager.temp_hotend[uiCfg.curSprayerChoose].target > (HEATER_1_MAXTEMP - (WATCH_TEMP_INCREASE + TEMP_HYSTERESIS + 1))) { - thermalManager.temp_hotend[uiCfg.curSprayerChoose].target = (float)HEATER_1_MAXTEMP - (WATCH_TEMP_INCREASE + TEMP_HYSTERESIS + 1); - } - #endif - thermalManager.start_watching_hotend(uiCfg.curSprayerChoose); - } - #if HAS_HEATED_BED - else { - thermalManager.temp_bed.target += uiCfg.stepHeat; - if ((int)thermalManager.temp_bed.target > BED_MAXTEMP - (WATCH_BED_TEMP_INCREASE + TEMP_BED_HYSTERESIS + 1)) { - thermalManager.temp_bed.target = (float)BED_MAXTEMP - (WATCH_BED_TEMP_INCREASE + TEMP_BED_HYSTERESIS + 1); - } - thermalManager.start_watching_bed(); - } - #endif - disp_desire_temp(); - } - break; - case ID_P_DEC: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - if (uiCfg.curTempType == 0) { - if ((int)thermalManager.temp_hotend[uiCfg.curSprayerChoose].target > uiCfg.stepHeat) { - thermalManager.temp_hotend[uiCfg.curSprayerChoose].target -= uiCfg.stepHeat; - } - else { - thermalManager.temp_hotend[uiCfg.curSprayerChoose].target = (float)0; - } - thermalManager.start_watching_hotend(uiCfg.curSprayerChoose); - } - #if HAS_HEATED_BED - else { - if ((int)thermalManager.temp_bed.target > uiCfg.stepHeat) { - thermalManager.temp_bed.target -= uiCfg.stepHeat; - } - else { - thermalManager.temp_bed.target = (float)0; - } - thermalManager.start_watching_bed(); - } - #endif - disp_desire_temp(); - } - - break; - case ID_P_TYPE: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - if (uiCfg.curTempType == 0) { - if (ENABLED(HAS_MULTI_EXTRUDER)) { - if (uiCfg.curSprayerChoose == 0) { - uiCfg.curSprayerChoose = 1; - } - else if (uiCfg.curSprayerChoose == 1) { - if (TEMP_SENSOR_BED != 0) { - uiCfg.curTempType = 1; - } - else { - uiCfg.curTempType = 0; - uiCfg.curSprayerChoose = 0; - } - } - } - else if (uiCfg.curSprayerChoose == 0) { - if (TEMP_SENSOR_BED != 0) - uiCfg.curTempType = 1; - else - uiCfg.curTempType = 0; - } - } - else if (uiCfg.curTempType == 1) { - uiCfg.curSprayerChoose = 0; - uiCfg.curTempType = 0; - } - disp_temp_type(); - } - break; - case ID_P_STEP: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - switch (uiCfg.stepHeat) { - case 1: uiCfg.stepHeat = 5; break; - case 5: uiCfg.stepHeat = 10; break; - case 10: uiCfg.stepHeat = 1; break; - default: break; - } - disp_step_heat(); - } - break; - case ID_P_OFF: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - if (uiCfg.curTempType == 0) { - thermalManager.temp_hotend[uiCfg.curSprayerChoose].target = (float)0; - thermalManager.start_watching_hotend(uiCfg.curSprayerChoose); - } - #if HAS_HEATED_BED - else { - thermalManager.temp_bed.target = (float)0; - thermalManager.start_watching_bed(); - } - #endif - disp_desire_temp(); - } - break; - case ID_P_RETURN: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - clear_cur_ui(); - draw_return_ui(); - } - break; - } -} - -void lv_draw_preHeat(void) { - lv_obj_t *buttonAdd, *buttonDec; - lv_obj_t *buttonOff, *buttonBack; - - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != PRE_HEAT_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = PRE_HEAT_UI; - } - disp_state = PRE_HEAT_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, creat_title_text()); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - // Create image buttons - buttonAdd = lv_imgbtn_create(scr, NULL); - buttonDec = lv_imgbtn_create(scr, NULL); - buttoType = lv_imgbtn_create(scr, NULL); - buttonStep = lv_imgbtn_create(scr, NULL); - buttonOff = lv_imgbtn_create(scr, NULL); - buttonBack = lv_imgbtn_create(scr, NULL); - - lv_obj_set_event_cb_mks(buttonAdd, event_handler, ID_P_ADD, NULL, 0); - lv_imgbtn_set_src(buttonAdd, LV_BTN_STATE_REL, "F:/bmp_Add.bin"); - lv_imgbtn_set_src(buttonAdd, LV_BTN_STATE_PR, "F:/bmp_Add.bin"); - lv_imgbtn_set_style(buttonAdd, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonAdd, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_clear_protect(buttonAdd, LV_PROTECT_FOLLOW); - - #if 1 - lv_obj_set_event_cb_mks(buttonDec, event_handler, ID_P_DEC, NULL, 0); - lv_imgbtn_set_src(buttonDec, LV_BTN_STATE_REL, "F:/bmp_Dec.bin"); - lv_imgbtn_set_src(buttonDec, LV_BTN_STATE_PR, "F:/bmp_Dec.bin"); - lv_imgbtn_set_style(buttonDec, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonDec, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttoType, event_handler, ID_P_TYPE, NULL, 0); - lv_imgbtn_set_style(buttoType, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttoType, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonStep, event_handler, ID_P_STEP, NULL, 0); - lv_imgbtn_set_style(buttonStep, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonStep, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonOff, event_handler, ID_P_OFF, NULL, 0); - lv_imgbtn_set_src(buttonOff, LV_BTN_STATE_REL, "F:/bmp_speed0.bin"); - lv_imgbtn_set_src(buttonOff, LV_BTN_STATE_PR, "F:/bmp_speed0.bin"); - lv_imgbtn_set_style(buttonOff, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonOff, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_P_RETURN, NULL, 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_return.bin"); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_return.bin"); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); - #endif - - lv_obj_set_pos(buttonAdd, INTERVAL_V, titleHeight); - lv_obj_set_pos(buttonDec, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight); - lv_obj_set_pos(buttoType, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - lv_obj_set_pos(buttonStep, BTN_X_PIXEL + INTERVAL_V * 2, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - lv_obj_set_pos(buttonOff, BTN_X_PIXEL * 2 + INTERVAL_V * 3, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - lv_obj_set_pos(buttonBack, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - - // Create labels on the image buttons - lv_btn_set_layout(buttonAdd, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonDec, LV_LAYOUT_OFF); - lv_btn_set_layout(buttoType, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonStep, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonOff, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - - lv_obj_t *labelAdd = lv_label_create(buttonAdd, NULL); - lv_obj_t *labelDec = lv_label_create(buttonDec, NULL); - labelType = lv_label_create(buttoType, NULL); - labelStep = lv_label_create(buttonStep, NULL); - lv_obj_t *labelOff = lv_label_create(buttonOff, NULL); - lv_obj_t *label_Back = lv_label_create(buttonBack, NULL); - - if (gCfgItems.multiple_language != 0) { - lv_label_set_text(labelAdd, preheat_menu.add); - lv_obj_align(labelAdd, buttonAdd, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(labelDec, preheat_menu.dec); - lv_obj_align(labelDec, buttonDec, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(labelOff, preheat_menu.off); - lv_obj_align(labelOff, buttonOff, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonAdd); - lv_group_add_obj(g, buttonDec); - lv_group_add_obj(g, buttoType); - lv_group_add_obj(g, buttonStep); - lv_group_add_obj(g, buttonOff); - lv_group_add_obj(g, buttonBack); - } - #endif - - disp_temp_type(); - disp_step_heat(); - - tempText1 = lv_label_create(scr, NULL); - lv_obj_set_style(tempText1, &tft_style_label_rel); - disp_desire_temp(); -} - -void disp_temp_type() { - if (uiCfg.curTempType == 0) { - if (uiCfg.curSprayerChoose == 1) { - lv_imgbtn_set_src(buttoType, LV_BTN_STATE_REL, "F:/bmp_extru2.bin"); - lv_imgbtn_set_src(buttoType, LV_BTN_STATE_PR, "F:/bmp_extru2.bin"); - if (gCfgItems.multiple_language != 0) { - lv_label_set_text(labelType, preheat_menu.ext2); - lv_obj_align(labelType, buttoType, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - } - else { - lv_imgbtn_set_src(buttoType, LV_BTN_STATE_REL, "F:/bmp_extru1.bin"); - lv_imgbtn_set_src(buttoType, LV_BTN_STATE_PR, "F:/bmp_extru1.bin"); - if (gCfgItems.multiple_language != 0) { - lv_label_set_text(labelType, preheat_menu.ext1); - lv_obj_align(labelType, buttoType, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - } - - } - else { - lv_imgbtn_set_src(buttoType, LV_BTN_STATE_REL, "F:/bmp_bed.bin"); - lv_imgbtn_set_src(buttoType, LV_BTN_STATE_PR, "F:/bmp_bed.bin"); - if (gCfgItems.multiple_language != 0) { - lv_label_set_text(labelType, preheat_menu.hotbed); - lv_obj_align(labelType, buttoType, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - } -} - -void disp_desire_temp() { - char buf[20] = {0}; - - public_buf_l[0] = '\0'; - - if (uiCfg.curTempType == 0) { - if (uiCfg.curSprayerChoose < 1) - strcat(public_buf_l, preheat_menu.ext1); - else - strcat(public_buf_l, preheat_menu.ext2); - sprintf(buf, preheat_menu.value_state, (int)thermalManager.temp_hotend[uiCfg.curSprayerChoose].celsius, (int)thermalManager.temp_hotend[uiCfg.curSprayerChoose].target); - } - #if HAS_HEATED_BED - else { - strcat(public_buf_l, preheat_menu.hotbed); - sprintf(buf, preheat_menu.value_state, (int)thermalManager.temp_bed.celsius, (int)thermalManager.temp_bed.target); - } - #endif - strcat_P(public_buf_l, PSTR(": ")); - strcat(public_buf_l, buf); - lv_label_set_text(tempText1, public_buf_l); - lv_obj_align(tempText1, NULL, LV_ALIGN_CENTER, 0, -50); -} - -void disp_step_heat() { - if (uiCfg.stepHeat == 1) { - lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_REL, "F:/bmp_step1_degree.bin"); - lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_PR, "F:/bmp_step1_degree.bin"); - } - else if (uiCfg.stepHeat == 5) { - lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_REL, "F:/bmp_step5_degree.bin"); - lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_PR, "F:/bmp_step5_degree.bin"); - } - else if (uiCfg.stepHeat == 10) { - lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_REL, "F:/bmp_step10_degree.bin"); - lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_PR, "F:/bmp_step10_degree.bin"); - } - - if (gCfgItems.multiple_language != 0) { - if (uiCfg.stepHeat == 1) { - lv_label_set_text(labelStep, preheat_menu.step_1c); - lv_obj_align(labelStep, buttonStep, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - else if (uiCfg.stepHeat == 5) { - lv_label_set_text(labelStep, preheat_menu.step_5c); - lv_obj_align(labelStep, buttonStep, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - else if (uiCfg.stepHeat == 10) { - lv_label_set_text(labelStep, preheat_menu.step_10c); - lv_obj_align(labelStep, buttonStep, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - } -} - -void lv_clear_preHeat() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_print_file.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_print_file.cpp deleted file mode 100644 index 6d7b68af42a7..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_print_file.cpp +++ /dev/null @@ -1,640 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "../../../../MarlinCore.h" -#include "lv_conf.h" -//#include "../lvgl/src/lv_objx/lv_imgbtn.h" -//#include "../lvgl/src/lv_objx/lv_img.h" -//#include "../lvgl/src/lv_core/lv_disp.h" -//#include "../lvgl/src/lv_core/lv_refr.h" -#include "draw_ui.h" -#include "../../../../sd/cardreader.h" - -static lv_obj_t * scr; -extern lv_group_t* g; - -static lv_obj_t *buttonPageUp, *buttonPageDown, *buttonBack, - *buttonGcode[FILE_BTN_CNT], *labelPageUp[FILE_BTN_CNT], *buttonText[FILE_BTN_CNT]; - -#define ID_P_UP 7 -#define ID_P_DOWN 8 -#define ID_P_RETURN 9 - -int8_t curDirLever = 0; -LIST_FILE list_file; -DIR_OFFSET dir_offset[10]; - -extern uint8_t public_buf[512]; -extern char public_buf_m[100]; - -uint8_t sel_id = 0; - -#if ENABLED(SDSUPPORT) - - static uint8_t search_file() { - int valid_name_cnt = 0; - //char tmp[SHORT_NEME_LEN*MAX_DIR_LEVEL+1]; - - list_file.Sd_file_cnt = 0; - //list_file.Sd_file_offset = dir_offset[curDirLever].cur_page_first_offset; - - //root2.rewind(); - //SERIAL_ECHOLN(list_file.curDirPath); - - if (curDirLever != 0) card.cd(list_file.curDirPath); - else card.cdroot(); // while(card.cdup()); - - const uint16_t fileCnt = card.get_num_Files(); - - for (uint16_t i = 0; i < fileCnt; i++) { - if (list_file.Sd_file_cnt == list_file.Sd_file_offset) { - const uint16_t nr = SD_ORDER(i, fileCnt); - card.getfilename_sorted(nr); - - if (card.flag.filenameIsDir) { - //SERIAL_ECHOLN(card.longest_filename); - list_file.IsFolder[valid_name_cnt] = 1; - } - else { - //SERIAL_ECHOLN(card.longFilename); - list_file.IsFolder[valid_name_cnt] = 0; - } - - #if 1 - // - memset(list_file.file_name[valid_name_cnt], 0, strlen(list_file.file_name[valid_name_cnt])); - strcpy(list_file.file_name[valid_name_cnt], list_file.curDirPath); - strcat_P(list_file.file_name[valid_name_cnt], PSTR("/")); - strcat(list_file.file_name[valid_name_cnt], card.filename); - // - memset(list_file.long_name[valid_name_cnt], 0, strlen(list_file.long_name[valid_name_cnt])); - if (card.longFilename[0] == 0) - strncpy(list_file.long_name[valid_name_cnt], card.filename, strlen(card.filename)); - else - strncpy(list_file.long_name[valid_name_cnt], card.longFilename, strlen(card.longFilename)); - - valid_name_cnt++; - if (valid_name_cnt == 1) - dir_offset[curDirLever].cur_page_first_offset = list_file.Sd_file_offset; - if (valid_name_cnt >= FILE_NUM) { - dir_offset[curDirLever].cur_page_last_offset = list_file.Sd_file_offset; - list_file.Sd_file_offset++; - break; - } - list_file.Sd_file_offset++; - #endif - } - list_file.Sd_file_cnt++; - } - //card.closefile(false); - return valid_name_cnt; - } - -#endif // SDSUPPORT - -uint8_t have_pre_pic(char *path) { - #if ENABLED(SDSUPPORT) - char *ps1, *ps2, *cur_name = strrchr(path, '/'); - - card.openFileRead(cur_name); - card.read(public_buf, 512); - ps1 = strstr((char *)public_buf, ";simage:"); - card.read(public_buf, 512); - ps2 = strstr((char *)public_buf, ";simage:"); - if (ps1 || ps2) { - card.closefile(); - return 1; - } - card.closefile(); - #endif - - return 0; -} - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - uint8_t i, file_count = 0; - //switch (obj->mks_obj_id) - //{ - if (obj->mks_obj_id == ID_P_UP) { - if (event == LV_EVENT_CLICKED) { - } - else if (event == LV_EVENT_RELEASED) { - if (dir_offset[curDirLever].curPage > 0) { - // 2015.05.19 - list_file.Sd_file_cnt = 0; - - 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 - if (file_count != 0) { - dir_offset[curDirLever].curPage--; - lv_clear_print_file(); - disp_gcode_icon(file_count); - } - } - } - } - else if (obj->mks_obj_id == ID_P_DOWN) { - if (event == LV_EVENT_CLICKED) { - } - else if (event == LV_EVENT_RELEASED) { - 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 - if (file_count != 0) { - dir_offset[curDirLever].curPage++; - lv_clear_print_file(); - disp_gcode_icon(file_count); - } - if (file_count < FILE_NUM) - dir_offset[curDirLever].cur_page_last_offset = 0; - } - } - } - else if (obj->mks_obj_id == ID_P_RETURN) { - if (event == LV_EVENT_CLICKED) { - } - else if (event == LV_EVENT_RELEASED) { - if (curDirLever > 0) { - int8_t *ch = (int8_t *)strrchr(list_file.curDirPath, '/'); - if (ch) { - *ch = 0; - #if ENABLED(SDSUPPORT) - card.cdup(); - #endif - 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 - lv_clear_print_file(); - disp_gcode_icon(file_count); - } - } - else { - lv_clear_print_file(); - lv_draw_ready_print(); - } - } - } - else { - for (i = 0; i < FILE_BTN_CNT; i++) { - if (obj->mks_obj_id == (i + 1)) { - if (event == LV_EVENT_CLICKED) { - } - else if (event == LV_EVENT_RELEASED) { - if (list_file.file_name[i][0] != 0) { - if (list_file.IsFolder[i] == 1) { - ZERO(list_file.curDirPath); - 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 - lv_clear_print_file(); - disp_gcode_icon(file_count); - } - else { - sel_id = i; - lv_clear_print_file(); - lv_draw_dialog(DIALOG_TYPE_PRINT_FILE); - } - break; - } - } - } - } - } -} - -void lv_draw_print_file(void) { - //uint8_t i; - uint8_t file_count; - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != PRINT_FILE_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = PRINT_FILE_UI; - } - disp_state = PRINT_FILE_UI; - - curDirLever = 0; - dir_offset[curDirLever].curPage = 0; - - list_file.Sd_file_offset = 0; - list_file.Sd_file_cnt = 0; - - ZERO(dir_offset); - ZERO(list_file.IsFolder); - ZERO(list_file.curDirPath); - - list_file.Sd_file_offset = dir_offset[curDirLever].cur_page_first_offset; - #if ENABLED(SDSUPPORT) - card.mount(); - file_count = search_file(); - #endif - disp_gcode_icon(file_count); - - //lv_obj_t *labelPageUp = lv_label_create(buttonPageUp, NULL); - //lv_obj_t *labelPageDown = lv_label_create(buttonPageDown, NULL); - //lv_obj_t *label_Back = lv_label_create(buttonBack, NULL); - - /* - if (gCfgItems.multiple_language != 0) { - lv_label_set_text(labelPageUp, tool_menu.preheat); - lv_obj_align(labelPageUp, buttonPageUp, LV_ALIGN_IN_BOTTOM_MID,0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(labelPageDown, tool_menu.extrude); - lv_obj_align(labelPageDown, buttonPageDown, LV_ALIGN_IN_BOTTOM_MID,0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID,0, BUTTON_TEXT_Y_OFFSET); - } - */ -} -static char test_public_buf_l[40]; -void disp_gcode_icon(uint8_t file_num) { - uint8_t i; - - scr = lv_obj_create(NULL, NULL); - - //static lv_style_t tool_style; - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, creat_title_text()); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - // Create image buttons - buttonPageUp = lv_imgbtn_create(scr, NULL); - buttonPageDown = lv_imgbtn_create(scr, NULL); - buttonBack = lv_imgbtn_create(scr, NULL); - - lv_obj_set_event_cb_mks(buttonPageUp, event_handler, ID_P_UP, NULL, 0); - lv_imgbtn_set_src(buttonPageUp, LV_BTN_STATE_REL, "F:/bmp_pageUp.bin"); - lv_imgbtn_set_src(buttonPageUp, LV_BTN_STATE_PR, "F:/bmp_pageUp.bin"); - lv_imgbtn_set_style(buttonPageUp, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonPageUp, LV_BTN_STATE_REL, &tft_style_label_rel); - - #if 1 - lv_obj_set_event_cb_mks(buttonPageDown, event_handler, ID_P_DOWN, NULL, 0); - lv_imgbtn_set_src(buttonPageDown, LV_BTN_STATE_REL, "F:/bmp_pageDown.bin"); - lv_imgbtn_set_src(buttonPageDown, LV_BTN_STATE_PR, "F:/bmp_pageDown.bin"); - lv_imgbtn_set_style(buttonPageDown, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonPageDown, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_P_RETURN, NULL, 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_back.bin"); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_back.bin"); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); - #endif - - lv_obj_set_pos(buttonPageUp, OTHER_BTN_XPIEL * 3 + INTERVAL_V * 4, titleHeight); - lv_obj_set_pos(buttonPageDown, OTHER_BTN_XPIEL * 3 + INTERVAL_V * 4, titleHeight + OTHER_BTN_YPIEL + INTERVAL_H); - lv_obj_set_pos(buttonBack, OTHER_BTN_XPIEL * 3 + INTERVAL_V * 4, titleHeight + OTHER_BTN_YPIEL * 2 + INTERVAL_H * 2); - - // Create labels on the image buttons - lv_btn_set_layout(buttonPageUp, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonPageDown, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - - for (i = 0; i < FILE_BTN_CNT; i++) { - /* - if (seq) { - j = (FILE_BTN_CNT-1) - i; - back_flg = 1; - } - else { - j = i; - back_flg = 0; - } - */ - if (i >= file_num) break; - - #ifdef TFT35 - buttonGcode[i] = lv_imgbtn_create(scr, NULL); - - lv_imgbtn_set_style(buttonGcode[i], LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonGcode[i], LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_clear_protect(buttonGcode[i], LV_PROTECT_FOLLOW); - lv_btn_set_layout(buttonGcode[i], LV_LAYOUT_OFF); - - ZERO(public_buf_m); - cutFileName((char *)list_file.long_name[i], 16, 8, (char *)public_buf_m); - - if (list_file.IsFolder[i] == 1) { - lv_obj_set_event_cb_mks(buttonGcode[i], event_handler, (i + 1), NULL, 0); - lv_imgbtn_set_src(buttonGcode[i], LV_BTN_STATE_REL, "F:/bmp_dir.bin"); - lv_imgbtn_set_src(buttonGcode[i], LV_BTN_STATE_PR, "F:/bmp_dir.bin"); - if (i < 3) - lv_obj_set_pos(buttonGcode[i], BTN_X_PIXEL * i + INTERVAL_V * (i + 1), titleHeight); - else - lv_obj_set_pos(buttonGcode[i], BTN_X_PIXEL * (i - 3) + INTERVAL_V * ((i - 3) + 1), BTN_Y_PIXEL + INTERVAL_H + titleHeight); - - labelPageUp[i] = lv_label_create(buttonGcode[i], NULL); - lv_obj_set_style(labelPageUp[i], &tft_style_label_rel); - lv_label_set_text(labelPageUp[i], public_buf_m); - lv_obj_align(labelPageUp[i], buttonGcode[i], LV_ALIGN_IN_BOTTOM_MID, 0, -5); - } - else { - if (have_pre_pic((char *)list_file.file_name[i])) { - - //lv_obj_set_event_cb_mks(buttonGcode[i], event_handler, (i + 1), list_file.file_name[i], 1); - - ZERO(test_public_buf_l); - strcat(test_public_buf_l,"S:"); - strcat(test_public_buf_l,list_file.file_name[i]); - char *temp = strstr(test_public_buf_l,".GCO"); - if (temp) { strcpy(temp,".bin"); } - lv_obj_set_event_cb_mks(buttonGcode[i], event_handler, (i + 1), NULL, 0); - lv_imgbtn_set_src(buttonGcode[i], LV_BTN_STATE_REL, test_public_buf_l); - lv_imgbtn_set_src(buttonGcode[i], LV_BTN_STATE_PR, test_public_buf_l); - if (i < 3) { - lv_obj_set_pos(buttonGcode[i], BTN_X_PIXEL * i + INTERVAL_V * (i + 1) + FILE_PRE_PIC_X_OFFSET, titleHeight + FILE_PRE_PIC_Y_OFFSET); - buttonText[i] = lv_btn_create(scr, NULL); - //lv_obj_set_event_cb(buttonText[i], event_handler); - - lv_btn_set_style(buttonText[i], LV_BTN_STATE_PR, &tft_style_label_pre); - lv_btn_set_style(buttonText[i], LV_BTN_STATE_REL, &tft_style_label_rel); - //lv_obj_set_style(buttonText[i], &tft_style_label_pre); - //lv_obj_set_style(buttonText[i], &tft_style_label_rel); - lv_obj_clear_protect(buttonText[i], LV_PROTECT_FOLLOW); - lv_btn_set_layout(buttonText[i], LV_LAYOUT_OFF); - //lv_obj_set_event_cb_mks(buttonText[i], event_handler,(i+10),NULL,0); - lv_obj_set_pos(buttonText[i], BTN_X_PIXEL * i + INTERVAL_V * (i + 1) + FILE_PRE_PIC_X_OFFSET, titleHeight + FILE_PRE_PIC_Y_OFFSET + 100); - lv_obj_set_size(buttonText[i], 100, 40); - } - else { - lv_obj_set_pos(buttonGcode[i], BTN_X_PIXEL * (i - 3) + INTERVAL_V * ((i - 3) + 1) + FILE_PRE_PIC_X_OFFSET, BTN_Y_PIXEL + INTERVAL_H + titleHeight + FILE_PRE_PIC_Y_OFFSET); - buttonText[i] = lv_btn_create(scr, NULL); - //lv_obj_set_event_cb(buttonText[i], event_handler); - - lv_btn_set_style(buttonText[i], LV_BTN_STATE_PR, &tft_style_label_pre); - lv_btn_set_style(buttonText[i], LV_BTN_STATE_REL, &tft_style_label_rel); - - //lv_imgbtn_set_style(buttonText[i], LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_clear_protect(buttonText[i], LV_PROTECT_FOLLOW); - lv_btn_set_layout(buttonText[i], LV_LAYOUT_OFF); - //lv_obj_set_event_cb_mks(buttonText[i], event_handler,(i+10),NULL,0); - lv_obj_set_pos(buttonText[i], BTN_X_PIXEL * (i - 3) + INTERVAL_V * ((i - 3) + 1) + FILE_PRE_PIC_X_OFFSET, BTN_Y_PIXEL + INTERVAL_H + titleHeight + FILE_PRE_PIC_Y_OFFSET + 100); - lv_obj_set_size(buttonText[i], 100, 40); - } - labelPageUp[i] = lv_label_create(buttonText[i], NULL); - lv_obj_set_style(labelPageUp[i], &tft_style_label_rel); - lv_label_set_text(labelPageUp[i], public_buf_m); - lv_obj_align(labelPageUp[i], buttonText[i], LV_ALIGN_IN_BOTTOM_MID, 0, 0); - } - else { - lv_obj_set_event_cb_mks(buttonGcode[i], event_handler, (i + 1), NULL, 0); - lv_imgbtn_set_src(buttonGcode[i], LV_BTN_STATE_REL, "F:/bmp_file.bin"); - lv_imgbtn_set_src(buttonGcode[i], LV_BTN_STATE_PR, "F:/bmp_file.bin"); - if (i < 3) - lv_obj_set_pos(buttonGcode[i], BTN_X_PIXEL * i + INTERVAL_V * (i + 1), titleHeight); - else - lv_obj_set_pos(buttonGcode[i], BTN_X_PIXEL * (i - 3) + INTERVAL_V * ((i - 3) + 1), BTN_Y_PIXEL + INTERVAL_H + titleHeight); - - labelPageUp[i] = lv_label_create(buttonGcode[i], NULL); - lv_obj_set_style(labelPageUp[i], &tft_style_label_rel); - lv_label_set_text(labelPageUp[i], public_buf_m); - lv_obj_align(labelPageUp[i], buttonGcode[i], LV_ALIGN_IN_BOTTOM_MID, 0, -5); - } - } - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonGcode[i]); - #endif - - #else // !TFT35 - #endif // !TFT35 - } - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonPageUp); - lv_group_add_obj(g, buttonPageDown); - lv_group_add_obj(g, buttonBack); - } - #endif -} - -uint32_t lv_open_gcode_file(char *path) { - #if ENABLED(SDSUPPORT) - uint32_t *ps4; - uint32_t pre_sread_cnt = 0; - char *cur_name; - - cur_name = strrchr(path, '/'); - - card.openFileRead(cur_name); - card.read(public_buf, 512); - ps4 = (uint32_t *)strstr((char *)public_buf, ";simage:"); - // Ignore the beginning message of gcode file - if (ps4) { - pre_sread_cnt = (uint32_t)ps4 - (uint32_t)((uint32_t *)(&public_buf[0])); - card.setIndex(pre_sread_cnt); - } - return pre_sread_cnt; - #endif // SDSUPPORT -} - -int ascii2dec_test(char *ascii) { - int result = 0; - if (ascii == 0) return 0; - - if (*(ascii) >= '0' && *(ascii) <= '9') - result = *(ascii) - '0'; - else if (*(ascii) >= 'a' && *(ascii) <= 'f') - result = *(ascii) - 'a' + 0x0A; - else if (*(ascii) >= 'A' && *(ascii) <= 'F') - result = *(ascii) - 'A' + 0x0A; - else - return 0; - - return result; -} - -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; - bool ignore_start = true; - char temp_test[200]; - volatile uint16_t *p_index; - - memset(public_buf, 0, 200); - - while (card.isFileOpen()) { - if (ignore_start) card.read(temp_test, 8); // line start -> ignore - card.read(temp_test, 200); // data - // \r;;gimage: we got the bit img, so stop here - if (temp_test[1] == ';') { - card.closefile(); - break; - } - for (i = 0; i < 200;) { - public_buf[row_1 * 200 + 100 * k + j] = (char)(ascii2dec_test(&temp_test[i]) << 4 | ascii2dec_test(&temp_test[i + 1])); - j++; - i += 2; - } - - uint16_t c = card.get(); - // check if we have more data or finished the line (CR) - if (c == '\r') break; - card.setIndex(card.getIndex()); - k++; - j = 0; - ignore_start = false; - } - #if ENABLED(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 - 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 // TFT_LVGL_UI_SPI - memcpy(data_buf, public_buf, 200); - #endif // SDSUPPORT -} - -void lv_close_gcode_file() {TERN_(SDSUPPORT, card.closefile());} - -void lv_gcode_file_seek(uint32_t pos) { - card.setIndex(pos); -} - -void cutFileName(char *path, int len, int bytePerLine, char *outStr) { - #if _LFN_UNICODE - TCHAR *tmpFile; - TCHAR *strIndex1 = 0, *strIndex2 = 0, *beginIndex; - TCHAR secSeg[10] = {0}; - TCHAR gFileTail[4] = {'~', '.', 'g', '\0'}; - #else - char *tmpFile; - char *strIndex1 = 0, *strIndex2 = 0, *beginIndex; - char secSeg[10] = {0}; - #endif - - if (path == 0 || len <= 3 || outStr == 0) return; - - tmpFile = path; - #if _LFN_UNICODE - strIndex1 = (WCHAR *)wcsstr((const WCHAR *)tmpFile, (const WCHAR *)'/'); - strIndex2 = (WCHAR *)wcsstr((const WCHAR *)tmpFile, (const WCHAR *)'.'); - #else - strIndex1 = (char *)strrchr(tmpFile, '/'); - strIndex2 = (char *)strrchr(tmpFile, '.'); - #endif - - beginIndex = (strIndex1 != 0 - //&& (strIndex2 != 0) && (strIndex1 < strIndex2) - ) ? strIndex1 + 1 : tmpFile; - - if (strIndex2 == 0 || (strIndex1 > strIndex2)) { // not gcode file - #if _LFN_UNICODE - if (wcslen(beginIndex) > len) - wcsncpy(outStr, beginIndex, len); - else - wcscpy(outStr, beginIndex); - #else - if ((int)strlen(beginIndex) > len) - strncpy(outStr, beginIndex, len); - else - strcpy(outStr, beginIndex); - #endif - } - else { // gcode file - if (strIndex2 - beginIndex > (len - 2)) { - #if _LFN_UNICODE - 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 { - #if _LFN_UNICODE - wcsncpy(outStr, (const WCHAR *)beginIndex, strIndex2 - beginIndex + 1); - wcscat(outStr, (const WCHAR *)&gFileTail[3]); - #else - strncpy(outStr, beginIndex, strIndex2 - beginIndex + 1); - strcat_P(outStr, PSTR("g")); - #endif - } - } - - #if _LFN_UNICODE - if (wcslen(outStr) > bytePerLine) { - wcscpy(secSeg, (const WCHAR *)&outStr[bytePerLine]); - outStr[bytePerLine] = '\n'; - outStr[bytePerLine + 1] = '\0'; - wcscat(outStr, (const WCHAR *)secSeg); - } - #else - if ((int)strlen(outStr) > bytePerLine) { - strcpy(secSeg, &outStr[bytePerLine]); - outStr[bytePerLine] = '\n'; - outStr[bytePerLine + 1] = '\0'; - strcat(outStr, secSeg); - } - else { - strcat_P(outStr, PSTR("\n")); - } - #endif -} - -void lv_clear_print_file() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_print_file.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_print_file.h deleted file mode 100644 index 083b3d9acf07..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_print_file.h +++ /dev/null @@ -1,66 +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 - -#ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ -#endif - -typedef struct { - int cur_page_first_offset; - int cur_page_last_offset; - int curPage; -} DIR_OFFSET; -extern DIR_OFFSET dir_offset[10]; - -#define FILE_NUM 6 -#define SHORT_NEME_LEN 13 -#define NAME_CUT_LEN 23 - -#define MAX_DIR_LEVEL 10 - -typedef struct { - //char longName[FILE_NUM][LONG_FILENAME_LENGTH]; - char file_name[FILE_NUM][SHORT_NEME_LEN * MAX_DIR_LEVEL + 1]; - char curDirPath[SHORT_NEME_LEN * MAX_DIR_LEVEL + 1]; - char long_name[FILE_NUM][SHORT_NEME_LEN * 2 + 1]; - char IsFolder[FILE_NUM]; - char Sd_file_cnt; - char sd_file_index; - char Sd_file_offset; -} LIST_FILE; -extern LIST_FILE list_file; - -extern void disp_gcode_icon(uint8_t file_num); -extern void lv_draw_print_file(void); -extern uint32_t lv_open_gcode_file(char *path); -extern void lv_gcode_file_read(uint8_t *data_buf); -extern void lv_close_gcode_file(); -extern void cutFileName(char *path, int len, int bytePerLine, char *outStr); -extern int ascii2dec_test(char *ascii); -extern void lv_clear_print_file(); -extern void lv_gcode_file_seek(uint32_t pos); - -//extern void disp_temp_ready_print(); -#ifdef __cplusplus - } /* C-declarations for C++ */ -#endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_printing.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_printing.cpp deleted file mode 100644 index c6369db41383..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_printing.cpp +++ /dev/null @@ -1,434 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "lv_conf.h" -#include "draw_ui.h" -//#include "../lvgl/src/lv_objx/lv_imgbtn.h" -//#include "../lvgl/src/lv_objx/lv_img.h" -//#include "../lvgl/src/lv_core/lv_disp.h" -//#include "../lvgl/src/lv_core/lv_refr.h" - -#include "../../../../MarlinCore.h" -#include "../../../../module/temperature.h" -#include "../../../../module/motion.h" -#include "../../../../sd/cardreader.h" -#include "../../../../gcode/queue.h" -#include "../../../../gcode/gcode.h" - -#if ENABLED(POWER_LOSS_RECOVERY) - #include "../../../../feature/powerloss.h" -#endif -#if BOTH(LCD_SET_PROGRESS_MANUALLY, USE_M73_REMAINING_TIME) - #include "../../../ultralcd.h" -#endif - -extern lv_group_t * g; -static lv_obj_t * scr; -static lv_obj_t *labelExt1, * labelFan, * labelZpos, * labelTime; -TERN_(HAS_MULTI_EXTRUDER, static lv_obj_t *labelExt2;) -static lv_obj_t *labelPause, * labelStop, * labelOperat; -static lv_obj_t * bar1, *bar1ValueText; -static lv_obj_t * buttonPause, *buttonOperat, *buttonStop; - -#if HAS_HEATED_BED - static lv_obj_t* labelBed; -#endif - -#define ID_PAUSE 1 -#define ID_STOP 2 -#define ID_OPTION 3 - -uint8_t once_flag = 0; -extern uint32_t To_pre_view; -extern uint8_t flash_preview_begin; -extern uint8_t default_preview_flg; -extern uint8_t gcode_preview_over; - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_PAUSE: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - if (gcode_preview_over != 1) { - if (uiCfg.print_state == WORKING) { - // #if ENABLED(PARK_HEAD_ON_PAUSE) - // queue.inject_P(PSTR("M25 P\nM24")); - #if ENABLED(SDSUPPORT) - // queue.inject_P(PSTR("M25\nG91\nG1 Z10\nG90")); - card.pauseSDPrint(); - stop_print_time(); - uiCfg.print_state = PAUSING; - #endif - lv_imgbtn_set_src(buttonPause, LV_BTN_STATE_REL, "F:/bmp_resume.bin"); - lv_imgbtn_set_src(buttonPause, LV_BTN_STATE_PR, "F:/bmp_resume.bin"); - lv_label_set_text(labelPause, printing_menu.resume); - lv_obj_align(labelPause, buttonPause, LV_ALIGN_CENTER, 30, 0); - } - else if (uiCfg.print_state == PAUSED) { - uiCfg.print_state = RESUMING; - lv_imgbtn_set_src(obj, LV_BTN_STATE_REL, "F:/bmp_pause.bin"); - lv_imgbtn_set_src(obj, LV_BTN_STATE_PR, "F:/bmp_pause.bin"); - lv_label_set_text(labelPause, printing_menu.pause); - lv_obj_align(labelPause, buttonPause, LV_ALIGN_CENTER, 30, 0); - } - #if ENABLED(POWER_LOSS_RECOVERY) - else if (uiCfg.print_state == REPRINTING) { - uiCfg.print_state = REPRINTED; - lv_imgbtn_set_src(obj, LV_BTN_STATE_REL, "F:/bmp_pause.bin"); - lv_imgbtn_set_src(obj, LV_BTN_STATE_PR, "F:/bmp_pause.bin"); - lv_label_set_text(labelPause, printing_menu.pause); - lv_obj_align(labelPause, buttonPause, LV_ALIGN_CENTER, 30, 0); - // recovery.resume(); - print_time.minutes = recovery.info.print_job_elapsed / 60; - print_time.seconds = recovery.info.print_job_elapsed % 60; - print_time.hours = print_time.minutes / 60; - } - #endif - } - } - break; - - case ID_STOP: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - if (gcode_preview_over != 1) { - lv_clear_printing(); - lv_draw_dialog(DIALOG_TYPE_STOP); - } - } - break; - case ID_OPTION: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - if (gcode_preview_over != 1) { - lv_clear_printing(); - lv_draw_operation(); - } - } - break; - } -} - -void lv_draw_printing(void) { - disp_state_stack._disp_index = 0; - ZERO(disp_state_stack._disp_state); - disp_state_stack._disp_state[disp_state_stack._disp_index] = PRINTING_UI; - - disp_state = PRINTING_UI; - - scr = lv_obj_create(NULL, NULL); - - // static lv_style_t tool_style; - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, creat_title_text()); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - // Create image buttons - lv_obj_t *buttonExt1 = lv_img_create(scr, NULL); - #if HAS_MULTI_EXTRUDER - lv_obj_t *buttonExt2 = lv_img_create(scr, NULL); - #endif - #if HAS_HEATED_BED - lv_obj_t *buttonBedstate = lv_img_create(scr, NULL); - #endif - lv_obj_t *buttonFanstate = lv_img_create(scr, NULL); - lv_obj_t *buttonTime = lv_img_create(scr, NULL); - lv_obj_t *buttonZpos = lv_img_create(scr, NULL); - buttonPause = lv_imgbtn_create(scr, NULL); - buttonStop = lv_imgbtn_create(scr, NULL); - buttonOperat = lv_imgbtn_create(scr, NULL); - - lv_img_set_src(buttonExt1, "F:/bmp_ext1_state.bin"); - #if 1 - #if HAS_MULTI_EXTRUDER - lv_img_set_src(buttonExt2, "F:/bmp_ext2_state.bin"); - #endif - #if HAS_HEATED_BED - lv_img_set_src(buttonBedstate, "F:/bmp_bed_state.bin"); - #endif - - lv_img_set_src(buttonFanstate, "F:/bmp_fan_state.bin"); - - lv_img_set_src(buttonTime, "F:/bmp_time_state.bin"); - - lv_img_set_src(buttonZpos, "F:/bmp_zpos_state.bin"); - - if (uiCfg.print_state == WORKING) { - lv_imgbtn_set_src(buttonPause, LV_BTN_STATE_REL, "F:/bmp_pause.bin"); - lv_imgbtn_set_src(buttonPause, LV_BTN_STATE_PR, "F:/bmp_pause.bin"); - } - else { - lv_imgbtn_set_src(buttonPause, LV_BTN_STATE_REL, "F:/bmp_resume.bin"); - lv_imgbtn_set_src(buttonPause, LV_BTN_STATE_PR, "F:/bmp_resume.bin"); - } - - lv_obj_set_event_cb_mks(buttonPause, event_handler, ID_PAUSE, NULL, 0); - lv_imgbtn_set_style(buttonPause, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonPause, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonStop, event_handler, ID_STOP, NULL, 0); - lv_imgbtn_set_src(buttonStop, LV_BTN_STATE_REL, "F:/bmp_stop.bin"); - lv_imgbtn_set_src(buttonStop, LV_BTN_STATE_PR, "F:/bmp_stop.bin"); - lv_imgbtn_set_style(buttonStop, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonStop, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonOperat, event_handler, ID_OPTION, NULL, 0); - lv_imgbtn_set_src(buttonOperat, LV_BTN_STATE_REL, "F:/bmp_operate.bin"); - lv_imgbtn_set_src(buttonOperat, LV_BTN_STATE_PR, "F:/bmp_operate.bin"); - lv_imgbtn_set_style(buttonOperat, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonOperat, LV_BTN_STATE_REL, &tft_style_label_rel); - - #endif // if 1 - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonPause); - lv_group_add_obj(g, buttonStop); - lv_group_add_obj(g, buttonOperat); - } - #endif - - lv_obj_set_pos(buttonExt1, 205, 136); - - #if HAS_MULTI_EXTRUDER - lv_obj_set_pos(buttonExt2, 350, 136); - #endif - - #if HAS_HEATED_BED - lv_obj_set_pos(buttonBedstate, 205, 186); - #endif - - lv_obj_set_pos(buttonFanstate, 350, 186); - lv_obj_set_pos(buttonTime, 205, 86); - lv_obj_set_pos(buttonZpos, 350, 86); - lv_obj_set_pos(buttonPause, 5, 240); - lv_obj_set_pos(buttonStop, 165, 240); - lv_obj_set_pos(buttonOperat, 325, 240); - - // Create labels on the image buttons - //lv_btn_set_layout(buttonExt1, LV_LAYOUT_OFF); - //#if HAS_MULTI_EXTRUDER - //lv_btn_set_layout(buttonExt2, LV_LAYOUT_OFF); - //#endif - - //#if HAS_HEATED_BED - //lv_btn_set_layout(buttonBedstate, LV_LAYOUT_OFF); - //#endif - - //lv_btn_set_layout(buttonFanstate, LV_LAYOUT_OFF); - //lv_btn_set_layout(buttonTime, LV_LAYOUT_OFF); - //lv_btn_set_layout(buttonZpos, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonPause, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonStop, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonOperat, LV_LAYOUT_OFF); - - labelExt1 = lv_label_create(scr, NULL); - lv_obj_set_style(labelExt1, &tft_style_label_rel); - lv_obj_set_pos(labelExt1, 250, 146); - - #if HAS_MULTI_EXTRUDER - labelExt2 = lv_label_create(scr, NULL); - lv_obj_set_style(labelExt2, &tft_style_label_rel); - lv_obj_set_pos(labelExt2, 395, 146); - #endif - - #if HAS_HEATED_BED - labelBed = lv_label_create(scr, NULL); - lv_obj_set_style(labelBed, &tft_style_label_rel); - lv_obj_set_pos(labelBed, 250, 196); - #endif - - labelFan = lv_label_create(scr, NULL); - lv_obj_set_style(labelFan, &tft_style_label_rel); - lv_obj_set_pos(labelFan, 395, 196); - - labelTime = lv_label_create(scr, NULL); - lv_obj_set_style(labelTime, &tft_style_label_rel); - lv_obj_set_pos(labelTime, 250, 96); - - labelZpos = lv_label_create(scr, NULL); - lv_obj_set_style(labelZpos, &tft_style_label_rel); - lv_obj_set_pos(labelZpos, 395, 96); - - labelPause = lv_label_create(buttonPause, NULL); - labelStop = lv_label_create(buttonStop, NULL); - labelOperat = lv_label_create(buttonOperat, NULL); - - if (gCfgItems.multiple_language != 0) { - lv_label_set_text(labelPause, uiCfg.print_state == WORKING ? printing_menu.pause : printing_menu.resume); - lv_obj_align(labelPause, buttonPause, LV_ALIGN_CENTER, 20, 0); - - lv_label_set_text(labelStop, printing_menu.stop); - lv_obj_align(labelStop, buttonStop, LV_ALIGN_CENTER, 20, 0); - - lv_label_set_text(labelOperat, printing_menu.option); - lv_obj_align(labelOperat, buttonOperat, LV_ALIGN_CENTER, 20, 0); - } - - bar1 = lv_bar_create(scr, NULL); - lv_obj_set_pos(bar1, 205, 36); - lv_obj_set_size(bar1, 270, 40); - lv_bar_set_style(bar1, LV_BAR_STYLE_INDIC, &lv_bar_style_indic); - lv_bar_set_anim_time(bar1, 1000); - lv_bar_set_value(bar1, 0, LV_ANIM_ON); - bar1ValueText = lv_label_create(bar1, NULL); - lv_label_set_text(bar1ValueText,"0%"); - lv_obj_align(bar1ValueText, bar1, LV_ALIGN_CENTER, 0, 0); - - disp_ext_temp(); - disp_bed_temp(); - disp_fan_speed(); - disp_print_time(); - disp_fan_Zpos(); -} - -void disp_ext_temp() { - ZERO(public_buf_l); - sprintf(public_buf_l, printing_menu.temp1, (int)thermalManager.temp_hotend[0].celsius, (int)thermalManager.temp_hotend[0].target); - lv_label_set_text(labelExt1, public_buf_l); - - #if HAS_MULTI_EXTRUDER - ZERO(public_buf_l); - sprintf(public_buf_l, printing_menu.temp1, (int)thermalManager.temp_hotend[1].celsius, (int)thermalManager.temp_hotend[1].target); - lv_label_set_text(labelExt2, public_buf_l); - #endif -} - -void disp_bed_temp() { - #if HAS_HEATED_BED - ZERO(public_buf_l); - sprintf(public_buf_l, printing_menu.bed_temp, (int)thermalManager.temp_bed.celsius, (int)thermalManager.temp_bed.target); - lv_label_set_text(labelBed, public_buf_l); - #endif -} - -void disp_fan_speed() { - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%3d"), thermalManager.fan_speed[0]); - lv_label_set_text(labelFan, public_buf_l); -} - -void disp_print_time() { - ZERO(public_buf_l); - #if BOTH(LCD_SET_PROGRESS_MANUALLY, USE_M73_REMAINING_TIME) - const uint32_t r = ui.get_remaining_time(); - sprintf_P(public_buf_l, PSTR("%02d:%02d R"), r / 3600, (r % 3600) / 60); - #else - sprintf_P(public_buf_l, PSTR("%d%d:%d%d:%d%d"), print_time.hours / 10, print_time.hours % 10, print_time.minutes / 10, print_time.minutes % 10, print_time.seconds / 10, print_time.seconds % 10); - #endif - lv_label_set_text(labelTime, public_buf_l); -} - -void disp_fan_Zpos() { - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%.3f"), current_position[Z_AXIS]); - lv_label_set_text(labelZpos, public_buf_l); -} - -void reset_print_time() { - // print_time.days = 0; - print_time.hours = 0; - print_time.minutes = 0; - print_time.seconds = 0; - print_time.ms_10 = 0; - // print_time.start = 1; -} - -void start_print_time() { print_time.start = 1; } - -void stop_print_time() { print_time.start = 0; } - -void setProBarRate() { - int rate; - volatile long long rate_tmp_r; - - if (gCfgItems.from_flash_pic != 1) { - #if ENABLED(SDSUPPORT) - rate_tmp_r = (long long)card.getIndex() * 100; - #endif - rate = rate_tmp_r / gCfgItems.curFilesize; - } - else { - #if ENABLED(SDSUPPORT) - 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)); - } - // gCurFileState.totalSend = rate; - - if (rate <= 0) return; - - if (disp_state == PRINTING_UI) { - lv_bar_set_value(bar1, rate, LV_ANIM_ON); - ZERO(public_buf_l); - sprintf_P(public_buf_l, "%d%%", rate); - lv_label_set_text(bar1ValueText,public_buf_l); - lv_obj_align(bar1ValueText, bar1, LV_ALIGN_CENTER, 0, 0); - - if (marlin_state == MF_SD_COMPLETE) { - if (once_flag == 0) { - stop_print_time(); - - flash_preview_begin = 0; - default_preview_flg = 0; - lv_clear_printing(); - lv_draw_dialog(DIALOG_TYPE_FINISH_PRINT); - - once_flag = 1; - - #if HAS_SUICIDE - if (gCfgItems.finish_power_off == 1) { - gcode.process_subcommands_now_P(PSTR("M1001")); - queue.inject_P(PSTR("M81")); - marlin_state = MF_RUNNING; - } - #endif - } - } - } -} - -void lv_clear_printing() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_printing.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_printing.h deleted file mode 100644 index b7d464e4f093..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_printing.h +++ /dev/null @@ -1,52 +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 - -#ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ -#endif - -#define IDLE 0 -#define WORKING 1 -#define PAUSING 2 -#define PAUSED 3 -#define REPRINTING 4 -#define REPRINTED 5 -#define RESUMING 6 -#define STOP 7 - -extern void lv_draw_printing(void); -extern void lv_clear_printing(); -extern void disp_ext_temp(); -extern void disp_bed_temp(); -extern void disp_fan_speed(); -extern void disp_print_time(); -extern void disp_fan_Zpos(); -extern void reset_print_time(); -extern void start_print_time(); -extern void stop_print_time(); -extern void setProBarRate(); - -//extern void disp_temp_ready_print(); -#ifdef __cplusplus - } /* C-declarations for C++ */ -#endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_ready_print.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_ready_print.cpp deleted file mode 100644 index 54ffdca64a44..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_ready_print.cpp +++ /dev/null @@ -1,310 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "draw_ready_print.h" -#include "draw_tool.h" -#include "lv_conf.h" -//#include "../lvgl/src/lv_objx/lv_imgbtn.h" -//#include "../lvgl/src/lv_objx/lv_img.h" -//#include "../lvgl/src/lv_core/lv_disp.h" -//#include "../lvgl/src/lv_core/lv_refr.h" -#include "tft_lvgl_configuration.h" -#include "mks_hardware_test.h" -#include "draw_ui.h" - -#include - -#include "../../../../MarlinCore.h" -#include "../../../../module/temperature.h" - -#include - -//static lv_obj_t *buttonPrint,*buttonTool,*buttonSet; -extern lv_group_t* g; -static lv_obj_t * scr; -#if ENABLED(MKS_TEST) - uint8_t curent_disp_ui = 0; -#endif - -#define ID_TOOL 1 -#define ID_SET 2 -#define ID_PRINT 3 - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_TOOL: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - - lv_clear_ready_print(); - lv_draw_tool(); - } - break; - case ID_SET: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_ready_print(); - lv_draw_set(); - } - break; - case ID_PRINT: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_ready_print(); - lv_draw_print_file(); - } - break; - } -} - -lv_obj_t *limit_info, *det_info; -lv_style_t limit_style, det_style; -void disp_Limit_ok() { - limit_style.text.color.full = 0xFFFF; - lv_obj_set_style(limit_info, &limit_style); - lv_label_set_text(limit_info, "Limit:ok"); -} -void disp_Limit_error() { - limit_style.text.color.full = 0xF800; - lv_obj_set_style(limit_info, &limit_style); - lv_label_set_text(limit_info, "Limit:error"); -} - -void disp_det_ok() { - det_style.text.color.full = 0xFFFF; - lv_obj_set_style(det_info, &det_style); - lv_label_set_text(det_info, "det:ok"); -} -void disp_det_error() { - det_style.text.color.full = 0xF800; - lv_obj_set_style(det_info, &det_style); - lv_label_set_text(det_info, "det:error"); -} - -lv_obj_t *e1, *e2, *e3, *bed; -void mks_disp_test() { - char buf[30] = {0}; - //lv_obj_t *label_tool2 = lv_label_create(scr, NULL); - //lv_obj_set_pos(label_tool,20,50); - ZERO(buf); - sprintf_P(buf, PSTR("e1:%d"), (int)thermalManager.temp_hotend[0].celsius); - lv_label_set_text(e1, buf); - #if HAS_MULTI_HOTEND - ZERO(buf); - sprintf_P(buf, PSTR("e2:%d"), (int)thermalManager.temp_hotend[1].celsius); - lv_label_set_text(e2, buf); - #endif - - //ZERO(buf); - //sprintf_P(buf, PSTR("e3:%d"), (int)thermalManager.temp_hotend[2].celsius); - //lv_label_set_text(e3, buf); - #if HAS_HEATED_BED - ZERO(buf); - sprintf_P(buf, PSTR("bed:%d"), (int)thermalManager.temp_bed.celsius); - lv_label_set_text(bed, buf); - #endif -} - -void lv_draw_ready_print(void) { - char buf[30] = {0}; - lv_obj_t *buttonPrint, *buttonTool, *buttonSet; - - disp_state_stack._disp_index = 0; - ZERO(disp_state_stack._disp_state); - disp_state_stack._disp_state[disp_state_stack._disp_index] = PRINT_READY_UI; - - disp_state = PRINT_READY_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - //lv_obj_set_hidden(scr,true); - lv_refr_now(lv_refr_get_disp_refreshing()); - - if (mks_test_flag == 0x1E) { - //lv_obj_t * title = lv_label_create(scr, NULL); - //lv_obj_set_style(title, &tft_style_label_rel); - //lv_obj_set_pos(title,TITLE_XPOS,TITLE_YPOS); - //lv_label_set_text(title, creat_title_text()); - - // Create image buttons - //buttonPrint = lv_imgbtn_create(scr, NULL); - buttonTool = lv_imgbtn_create(scr, NULL); - //buttonSet = lv_imgbtn_create(scr, NULL); - - #if 1 - lv_obj_set_event_cb_mks(buttonTool, event_handler, ID_TOOL, NULL, 0); - lv_imgbtn_set_src(buttonTool, LV_BTN_STATE_REL, "F:/bmp_tool.bin"); - lv_imgbtn_set_src(buttonTool, LV_BTN_STATE_PR, "F:/bmp_tool.bin"); - lv_imgbtn_set_style(buttonTool, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonTool, LV_BTN_STATE_REL, &tft_style_label_rel); - #endif - - lv_obj_set_pos(buttonTool, 360, 180); - //lv_obj_set_pos(buttonSet,180,90); - //lv_obj_set_pos(buttonPrint,340,90); - - //lv_obj_set_pos(buttonTool,SIMPLE_FIRST_PAGE_GRAP+1,(TFT_HEIGHT-BTN_Y_PIXEL)/2+2); - //lv_obj_set_pos(buttonSet,BTN_X_PIXEL+SIMPLE_FIRST_PAGE_GRAP*2+1,(TFT_HEIGHT-BTN_Y_PIXEL)/2+2); - //lv_obj_set_pos(buttonPrint,BTN_X_PIXEL*2+SIMPLE_FIRST_PAGE_GRAP*3+1,(TFT_HEIGHT-BTN_Y_PIXEL)/2+2); - - // Create labels on the image buttons - //lv_btn_set_layout(buttonPrint, LV_LAYOUT_OFF); - //lv_btn_set_layout(buttonSet, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonTool, LV_LAYOUT_OFF); - - //lv_obj_t *label_print = lv_label_create(buttonPrint, NULL); - //lv_obj_t *label_set = lv_label_create(buttonSet, NULL); - lv_obj_t *label_tool = lv_label_create(buttonTool, NULL); - if (gCfgItems.multiple_language != 0) { - //lv_label_set_text(label_print, main_menu.print); - //lv_obj_align(label_print, buttonPrint, LV_ALIGN_IN_BOTTOM_MID,0, BUTTON_TEXT_Y_OFFSET); - - //lv_label_set_text(label_set, main_menu.set); - //lv_obj_align(label_set, buttonSet, LV_ALIGN_IN_BOTTOM_MID,0, BUTTON_TEXT_Y_OFFSET); - - //lv_label_set_style(label_tool,LV_BTN_STATE_PR,&tft_style_label_pre); - //lv_label_set_style(label_tool,LV_BTN_STATE_REL,&tft_style_label_rel); - lv_label_set_text(label_tool, main_menu.tool); - lv_obj_align(label_tool, buttonTool, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - - #if 1 - e1 = lv_label_create(scr, NULL); - lv_obj_set_pos(e1, 20, 20); - sprintf_P(buf, PSTR("e1: %d"), (int)thermalManager.temp_hotend[0].celsius); - lv_label_set_text(e1, buf); - #if HAS_MULTI_HOTEND - e2 = lv_label_create(scr, NULL); - lv_obj_set_pos(e2, 20, 45); - sprintf_P(buf, PSTR("e1: %d"), (int)thermalManager.temp_hotend[1].celsius); - lv_label_set_text(e2, buf); - #endif - - //e3 = lv_label_create(scr, NULL); - //lv_obj_set_pos(e3,20,70); - //sprintf_P(buf, PSTR("e1: %d"), (int)thermalManager.temp_hotend[2].celsius); - //lv_label_set_text(e3, buf); - - #if HAS_HEATED_BED - bed = lv_label_create(scr, NULL); - lv_obj_set_pos(bed, 20, 95); - sprintf_P(buf, PSTR("bed: %d"), (int)thermalManager.temp_bed.celsius); - lv_label_set_text(bed, buf); - #endif - - limit_info = lv_label_create(scr, NULL); - - lv_style_copy(&limit_style, &lv_style_scr); - limit_style.body.main_color.full = 0X0000; - limit_style.body.grad_color.full = 0X0000; - limit_style.text.color.full = 0Xffff; - lv_obj_set_style(limit_info, &limit_style); - - lv_obj_set_pos(limit_info, 20, 120); - lv_label_set_text(limit_info, " "); - - det_info = lv_label_create(scr, NULL); - - lv_style_copy(&det_style, &lv_style_scr); - det_style.body.main_color.full = 0X0000; - det_style.body.grad_color.full = 0X0000; - det_style.text.color.full = 0Xffff; - lv_obj_set_style(det_info, &det_style); - - lv_obj_set_pos(det_info, 20, 145); - lv_label_set_text(det_info, " "); - #endif // if 1 - - } - else { - // Create an Image button - buttonTool = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonTool, 20, 90); - lv_obj_set_event_cb_mks(buttonTool, event_handler, ID_TOOL, NULL, 0); - lv_imgbtn_set_src(buttonTool, LV_BTN_STATE_REL, "F:/bmp_tool.bin"); - lv_imgbtn_set_src(buttonTool, LV_BTN_STATE_PR, "F:/bmp_tool.bin"); - lv_imgbtn_set_style(buttonTool, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonTool, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_t *label_tool = lv_label_create(buttonTool, NULL); - lv_btn_set_layout(buttonTool, LV_LAYOUT_OFF); - - buttonSet = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonSet, 180, 90); - lv_obj_set_event_cb_mks(buttonSet, event_handler, ID_SET, NULL, 0); - lv_imgbtn_set_src(buttonSet, LV_BTN_STATE_REL, "F:/bmp_set.bin"); - lv_imgbtn_set_src(buttonSet, LV_BTN_STATE_PR, "F:/bmp_set.bin"); - lv_imgbtn_set_style(buttonSet, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonSet, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_t *label_set = lv_label_create(buttonSet, NULL); - lv_btn_set_layout(buttonSet, LV_LAYOUT_OFF); - - buttonPrint = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonPrint, 340, 90); - lv_obj_set_event_cb_mks(buttonPrint, event_handler, ID_PRINT, NULL, 0); - lv_imgbtn_set_src(buttonPrint, LV_BTN_STATE_REL, "F:/bmp_printing.bin"); - lv_imgbtn_set_src(buttonPrint, LV_BTN_STATE_PR, "F:/bmp_printing.bin"); - lv_imgbtn_set_style(buttonPrint, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonPrint, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_t *label_print = lv_label_create(buttonPrint, NULL); - lv_btn_set_layout(buttonPrint, LV_LAYOUT_OFF); - - if (gCfgItems.multiple_language != 0) { - lv_label_set_text(label_print, main_menu.print); - lv_obj_align(label_print, buttonPrint, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_set, main_menu.set); - lv_obj_align(label_set, buttonSet, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_tool, main_menu.tool); - lv_obj_align(label_tool, buttonTool, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable == true) { - lv_group_add_obj(g, buttonTool); - lv_group_add_obj(g, buttonSet); - lv_group_add_obj(g, buttonPrint); - } - #endif - } -} - -void lv_clear_ready_print() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable == true) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_set.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_set.cpp deleted file mode 100644 index 6c10713d8a9c..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_set.cpp +++ /dev/null @@ -1,389 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "../../../../MarlinCore.h" -#include "draw_ready_print.h" -#include "draw_set.h" -#include "lv_conf.h" -//#include "../lvgl/src/lv_objx/lv_imgbtn.h" -//#include "../lvgl/src/lv_objx/lv_img.h" -//#include "../lvgl/src/lv_core/lv_disp.h" -//#include "../lvgl/src/lv_core/lv_refr.h" -#include "draw_ui.h" -#include "../../../../gcode/queue.h" -#include "pic_manager.h" - -static lv_obj_t * scr; -extern lv_group_t* g; - -#define ID_S_WIFI 1 -#define ID_S_FAN 2 -#define ID_S_ABOUT 3 -#define ID_S_CONTINUE 4 -#define ID_S_MOTOR_OFF 5 -#define ID_S_LANGUAGE 6 -#define ID_S_MACHINE_PARA 7 -#define ID_S_EEPROM_SET 8 -#define ID_S_RETURN 9 - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - #if ENABLED(USE_WIFI_FUNCTION) - char buf[6] = { 0 }; - #endif - switch (obj->mks_obj_id) { - - case ID_S_FAN: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_set(); - lv_draw_fan(); - } - break; - case ID_S_ABOUT: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_set(); - lv_draw_about(); - } - break; - case ID_S_CONTINUE: - - break; - case ID_S_MOTOR_OFF: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - #if HAS_SUICIDE - suicide(); - #else - queue.enqueue_now_P(PSTR("M84")); - #endif - } - break; - case ID_S_LANGUAGE: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_set(); - lv_draw_language(); - } - break; - case ID_S_MACHINE_PARA: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_set(); - lv_draw_machine_para(); - } - break; - case ID_S_EEPROM_SET: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_set(); - lv_draw_eeprom_settings(); - } - break; - case ID_S_RETURN: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_set(); - lv_draw_ready_print(); - } - break; - #if ENABLED(USE_WIFI_FUNCTION) - case ID_S_WIFI: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - if (gCfgItems.wifi_mode_sel == STA_MODEL) { - if (wifi_link_state == WIFI_CONNECTED) { - last_disp_state = SET_UI; - lv_clear_set(); - lv_draw_wifi(); - } - else { - if (uiCfg.command_send == 1) { - buf[0] = 0xA5; - buf[1] = 0x07; - buf[2] = 0x00; - buf[3] = 0x00; - buf[4] = 0xFC; - raw_send_to_wifi(buf, 5); - - last_disp_state = SET_UI; - lv_clear_set(); - lv_draw_wifi_list(); - } - else { - last_disp_state = SET_UI; - lv_clear_set(); - lv_draw_dialog(WIFI_ENABLE_TIPS); - } - } - } - else { - last_disp_state = SET_UI; - lv_clear_set(); - lv_draw_wifi(); - } - } - break; - #endif - } -} - -void lv_draw_set(void) { - lv_obj_t *buttonFan, *buttonAbout; - lv_obj_t *buMotorOff, *buttonBack; - #if HAS_LANG_SELECT_SCREEN - lv_obj_t *buttonLanguage; - #endif - lv_obj_t *buttonMachinePara; - lv_obj_t *buttonEepromSet; - #if ENABLED(USE_WIFI_FUNCTION) - lv_obj_t *buttonWifi; - #endif - - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != SET_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = SET_UI; - } - disp_state = SET_UI; - - scr = lv_obj_create(NULL, NULL); - - //static lv_style_t tool_style; - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, creat_title_text()); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - // Create image buttons - buttonEepromSet = lv_imgbtn_create(scr, NULL); - //buttonWifi = lv_imgbtn_create(scr, NULL); - buttonFan = lv_imgbtn_create(scr, NULL); - buttonAbout = lv_imgbtn_create(scr, NULL); - //buttonContinue = lv_imgbtn_create(scr, NULL); - buMotorOff = lv_imgbtn_create(scr, NULL); - buttonMachinePara = lv_imgbtn_create(scr, NULL); - #if HAS_LANG_SELECT_SCREEN - buttonLanguage = lv_imgbtn_create(scr, NULL); - #endif - #if ENABLED(USE_WIFI_FUNCTION) - buttonWifi = lv_imgbtn_create(scr, NULL); - #endif - buttonBack = lv_imgbtn_create(scr, NULL); - - lv_obj_set_event_cb_mks(buttonEepromSet, event_handler, ID_S_EEPROM_SET, NULL, 0); - lv_imgbtn_set_src(buttonEepromSet, LV_BTN_STATE_REL, "F:/bmp_eeprom_settings.bin"); - lv_imgbtn_set_src(buttonEepromSet, LV_BTN_STATE_PR, "F:/bmp_eeprom_settings.bin"); - lv_imgbtn_set_style(buttonEepromSet, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonEepromSet, LV_BTN_STATE_REL, &tft_style_label_rel); - - #if 1 - lv_obj_set_event_cb_mks(buttonFan, event_handler, ID_S_FAN, NULL, 0); - lv_imgbtn_set_src(buttonFan, LV_BTN_STATE_REL, "F:/bmp_fan.bin"); - lv_imgbtn_set_src(buttonFan, LV_BTN_STATE_PR, "F:/bmp_fan.bin"); - lv_imgbtn_set_style(buttonFan, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonFan, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonAbout, event_handler, ID_S_ABOUT, NULL, 0); - lv_imgbtn_set_src(buttonAbout, LV_BTN_STATE_REL, "F:/bmp_about.bin"); - lv_imgbtn_set_src(buttonAbout, LV_BTN_STATE_PR, "F:/bmp_about.bin"); - lv_imgbtn_set_style(buttonAbout, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonAbout, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buMotorOff, event_handler, ID_S_MOTOR_OFF, NULL, 0); - - #if HAS_SUICIDE - lv_imgbtn_set_src(buMotorOff, LV_BTN_STATE_REL, "F:/bmp_manual_off.bin"); - lv_imgbtn_set_src(buMotorOff, LV_BTN_STATE_PR, "F:/bmp_manual_off.bin"); - #else - lv_imgbtn_set_src(buMotorOff, LV_BTN_STATE_REL, "F:/bmp_function1.bin"); - lv_imgbtn_set_src(buMotorOff, LV_BTN_STATE_PR, "F:/bmp_function1.bin"); - #endif - lv_imgbtn_set_style(buMotorOff, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buMotorOff, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonMachinePara, event_handler, ID_S_MACHINE_PARA, NULL, 0); - lv_imgbtn_set_src(buttonMachinePara, LV_BTN_STATE_REL, "F:/bmp_machine_para.bin"); - lv_imgbtn_set_src(buttonMachinePara, LV_BTN_STATE_PR, "F:/bmp_machine_para.bin"); - lv_imgbtn_set_style(buttonMachinePara, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonMachinePara, LV_BTN_STATE_REL, &tft_style_label_rel); - - #if HAS_LANG_SELECT_SCREEN - lv_obj_set_event_cb_mks(buttonLanguage, event_handler, ID_S_LANGUAGE, NULL, 0); - lv_imgbtn_set_src(buttonLanguage, LV_BTN_STATE_REL, "F:/bmp_language.bin"); - lv_imgbtn_set_src(buttonLanguage, LV_BTN_STATE_PR, "F:/bmp_language.bin"); - lv_imgbtn_set_style(buttonLanguage, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonLanguage, LV_BTN_STATE_REL, &tft_style_label_rel); - #endif - - #if ENABLED(USE_WIFI_FUNCTION) - lv_obj_set_event_cb_mks(buttonWifi, event_handler,ID_S_WIFI,NULL,0); - lv_imgbtn_set_src(buttonWifi, LV_BTN_STATE_REL, "F:/bmp_wifi.bin"); - lv_imgbtn_set_src(buttonWifi, LV_BTN_STATE_PR, "F:/bmp_wifi.bin"); - lv_imgbtn_set_style(buttonWifi, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonWifi, LV_BTN_STATE_REL, &tft_style_label_rel); - #endif - - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_S_RETURN,NULL , 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_return.bin"); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_return.bin"); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); - - #endif // if 1 - - /*lv_obj_set_pos(buttonWifi,INTERVAL_V,titleHeight); - lv_obj_set_pos(buttonFan,BTN_X_PIXEL+INTERVAL_V*2,titleHeight); - lv_obj_set_pos(buttonAbout,BTN_X_PIXEL*2+INTERVAL_V*3,titleHeight); - lv_obj_set_pos(buttonContinue,BTN_X_PIXEL*3+INTERVAL_V*4,titleHeight); - lv_obj_set_pos(buMotorOff,INTERVAL_V, BTN_Y_PIXEL+INTERVAL_H+titleHeight); - lv_obj_set_pos(buttonLanguage,BTN_X_PIXEL+INTERVAL_V*2,BTN_Y_PIXEL+INTERVAL_H+titleHeight); - lv_obj_set_pos(buttonBack,BTN_X_PIXEL*3+INTERVAL_V*4, BTN_Y_PIXEL+INTERVAL_H+titleHeight);*/ - - //lv_obj_set_pos(buttonWifi,INTERVAL_V,titleHeight); - lv_obj_set_pos(buttonEepromSet, INTERVAL_V, titleHeight); - lv_obj_set_pos(buttonFan, BTN_X_PIXEL + INTERVAL_V * 2, titleHeight); - lv_obj_set_pos(buttonAbout, BTN_X_PIXEL * 2 + INTERVAL_V * 3, titleHeight); - //lv_obj_set_pos(buttonContinue,BTN_X_PIXEL*3+INTERVAL_V*4,titleHeight); - lv_obj_set_pos(buMotorOff, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight); - - lv_obj_set_pos(buttonMachinePara, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - #if HAS_LANG_SELECT_SCREEN - lv_obj_set_pos(buttonLanguage, BTN_X_PIXEL + INTERVAL_V * 2, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - #endif - #if ENABLED(USE_WIFI_FUNCTION) - lv_obj_set_pos(buttonWifi,BTN_X_PIXEL*2+INTERVAL_V*3,BTN_Y_PIXEL+INTERVAL_H+titleHeight); - #endif - lv_obj_set_pos(buttonBack, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - - /// Create labels on the buttons - //lv_btn_set_layout(buttonWifi, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonEepromSet, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonFan, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonAbout, LV_LAYOUT_OFF); - //lv_btn_set_layout(buttonContinue, LV_LAYOUT_OFF); - lv_btn_set_layout(buMotorOff, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonMachinePara, LV_LAYOUT_OFF); - #if HAS_LANG_SELECT_SCREEN - lv_btn_set_layout(buttonLanguage, LV_LAYOUT_OFF); - #endif - #if ENABLED(USE_WIFI_FUNCTION) - lv_btn_set_layout(buttonWifi, LV_LAYOUT_OFF); - #endif - lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - - //lv_obj_t *labelWifi= lv_label_create(buttonWifi, NULL); - lv_obj_t *label_EepromSet = lv_label_create(buttonEepromSet, NULL); - lv_obj_t *labelFan = lv_label_create(buttonFan, NULL); - lv_obj_t *label_About = lv_label_create(buttonAbout, NULL); - //lv_obj_t *label_Continue = lv_label_create(buttonContinue, NULL); - lv_obj_t *label_MotorOff = lv_label_create(buMotorOff, NULL); - lv_obj_t *label_MachinePara = lv_label_create(buttonMachinePara, NULL); - #if HAS_LANG_SELECT_SCREEN - lv_obj_t *label_Language = lv_label_create(buttonLanguage, NULL); - #endif - #if ENABLED(USE_WIFI_FUNCTION) - lv_obj_t *label_Wifi = lv_label_create(buttonWifi, NULL); - #endif - lv_obj_t *label_Back = lv_label_create(buttonBack, NULL); - - if (gCfgItems.multiple_language != 0) { - - lv_label_set_text(label_EepromSet, set_menu.eepromSet); - lv_obj_align(label_EepromSet, buttonEepromSet, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(labelFan, set_menu.fan); - lv_obj_align(labelFan, buttonFan, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_About, set_menu.about); - lv_obj_align(label_About, buttonAbout, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - //lv_label_set_text(label_Continue, set_menu.breakpoint); - //lv_obj_align(label_Continue, buttonContinue, LV_ALIGN_IN_BOTTOM_MID,0, BUTTON_TEXT_Y_OFFSET); - lv_label_set_text(label_MotorOff, set_menu.TERN(HAS_SUICIDE, shutdown, motoroff)); - lv_obj_align(label_MotorOff, buMotorOff, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_MachinePara, set_menu.machine_para); - lv_obj_align(label_MachinePara, buttonMachinePara, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - #if HAS_LANG_SELECT_SCREEN - lv_label_set_text(label_Language, set_menu.language); - lv_obj_align(label_Language, buttonLanguage, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - #endif - - #if ENABLED(USE_WIFI_FUNCTION) - lv_label_set_text(label_Wifi, set_menu.wifi); - lv_obj_align(label_Wifi, buttonWifi, LV_ALIGN_IN_BOTTOM_MID,0, BUTTON_TEXT_Y_OFFSET); - #endif - - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonEepromSet); - lv_group_add_obj(g, buttonFan); - lv_group_add_obj(g, buttonAbout); - lv_group_add_obj(g, buMotorOff); - lv_group_add_obj(g, buttonMachinePara); - lv_group_add_obj(g, buttonLanguage); - #if ENABLED(USE_WIFI_FUNCTION) - lv_group_add_obj(g, buttonWifi); - #endif - lv_group_add_obj(g, buttonBack); - } - #endif -} - -void lv_clear_set() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_step_settings.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_step_settings.cpp deleted file mode 100644 index baad23f9aed7..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_step_settings.cpp +++ /dev/null @@ -1,328 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "lv_conf.h" -#include "draw_ui.h" - -#include "../../../../MarlinCore.h" -#include "../../../../module/planner.h" - -extern lv_group_t * g; -static lv_obj_t * scr; - -#define ID_STEP_RETURN 1 -#define ID_STEP_X 2 -#define ID_STEP_Y 3 -#define ID_STEP_Z 4 -#define ID_STEP_E0 5 -#define ID_STEP_E1 6 -#define ID_STEP_DOWN 7 -#define ID_STEP_UP 8 - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_STEP_RETURN: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - uiCfg.para_ui_page = 0; - lv_clear_step_settings(); - draw_return_ui(); - } - break; - case ID_STEP_X: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = Xstep; - lv_clear_step_settings(); - lv_draw_number_key(); - } - break; - case ID_STEP_Y: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = Ystep; - lv_clear_step_settings(); - lv_draw_number_key(); - } - break; - case ID_STEP_Z: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = Zstep; - lv_clear_step_settings(); - lv_draw_number_key(); - } - break; - case ID_STEP_E0: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = E0step; - lv_clear_step_settings(); - lv_draw_number_key(); - } - break; - case ID_STEP_E1: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = E1step; - lv_clear_step_settings(); - lv_draw_number_key(); - } - break; - case ID_STEP_UP: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - uiCfg.para_ui_page = 0; - lv_clear_step_settings(); - lv_draw_step_settings(); - } - break; - case ID_STEP_DOWN: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - uiCfg.para_ui_page = 1; - lv_clear_step_settings(); - lv_draw_step_settings(); - } - break; - } -} - -void lv_draw_step_settings(void) { - lv_obj_t *buttonBack = NULL, *label_Back = NULL, *buttonTurnPage = NULL, *labelTurnPage = NULL; - lv_obj_t *labelXText = NULL, *buttonXValue = NULL, *labelXValue = NULL; - lv_obj_t *labelYText = NULL, *buttonYValue = NULL, *labelYValue = NULL; - lv_obj_t *labelZText = NULL, *buttonZValue = NULL, *labelZValue = NULL; - lv_obj_t *labelE0Text = NULL, *buttonE0Value = NULL, *labelE0Value = NULL; - lv_obj_t *labelE1Text = NULL, *buttonE1Value = NULL, *labelE1Value = NULL; - lv_obj_t * line1 = NULL, * line2 = NULL, * line3 = NULL, * line4 = NULL; - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != STEPS_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = STEPS_UI; - } - disp_state = STEPS_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, machine_menu.StepsConfTitle); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - if (uiCfg.para_ui_page != 1) { - labelXText = lv_label_create(scr, NULL); - lv_obj_set_style(labelXText, &tft_style_label_rel); - lv_obj_set_pos(labelXText, PARA_UI_POS_X, PARA_UI_POS_Y + 10); - lv_label_set_text(labelXText, machine_menu.X_Steps); - - buttonXValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonXValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y + PARA_UI_VALUE_V); - lv_obj_set_size(buttonXValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonXValue, event_handler, ID_STEP_X, NULL, 0); - lv_btn_set_style(buttonXValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonXValue, LV_BTN_STYLE_PR, &style_para_value); - labelXValue = lv_label_create(buttonXValue, NULL); - - line1 = lv_line_create(scr, NULL); - lv_ex_line(line1, line_points[0]); - - labelYText = lv_label_create(scr, NULL); - lv_obj_set_style(labelYText, &tft_style_label_rel); - lv_obj_set_pos(labelYText, PARA_UI_POS_X, PARA_UI_POS_Y * 2 + 10); - lv_label_set_text(labelYText, machine_menu.Y_Steps); - - buttonYValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonYValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 2 + PARA_UI_VALUE_V); - lv_obj_set_size(buttonYValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonYValue, event_handler, ID_STEP_Y, NULL, 0); - lv_btn_set_style(buttonYValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonYValue, LV_BTN_STYLE_PR, &style_para_value); - labelYValue = lv_label_create(buttonYValue, NULL); - - line2 = lv_line_create(scr, NULL); - lv_ex_line(line2, line_points[1]); - - labelZText = lv_label_create(scr, NULL); - lv_obj_set_style(labelZText, &tft_style_label_rel); - lv_obj_set_pos(labelZText, PARA_UI_POS_X, PARA_UI_POS_Y * 3 + 10); - lv_label_set_text(labelZText, machine_menu.Z_Steps); - - buttonZValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonZValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 3 + PARA_UI_VALUE_V); - lv_obj_set_size(buttonZValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonZValue, event_handler, ID_STEP_Z, NULL, 0); - lv_btn_set_style(buttonZValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonZValue, LV_BTN_STYLE_PR, &style_para_value); - labelZValue = lv_label_create(buttonZValue, NULL); - - line3 = lv_line_create(scr, NULL); - lv_ex_line(line3, line_points[2]); - - labelE0Text = lv_label_create(scr, NULL); - lv_obj_set_style(labelE0Text, &tft_style_label_rel); - lv_obj_set_pos(labelE0Text, PARA_UI_POS_X, PARA_UI_POS_Y * 4 + 10); - lv_label_set_text(labelE0Text, machine_menu.E0_Steps); - - buttonE0Value = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonE0Value, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 4 + PARA_UI_VALUE_V); - lv_obj_set_size(buttonE0Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonE0Value, event_handler, ID_STEP_E0, NULL, 0); - lv_btn_set_style(buttonE0Value, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonE0Value, LV_BTN_STYLE_PR, &style_para_value); - labelE0Value = lv_label_create(buttonE0Value, NULL); - - line4 = lv_line_create(scr, NULL); - lv_ex_line(line4, line_points[3]); - - buttonTurnPage = lv_btn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_STEP_DOWN, NULL, 0); - lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_REL, &style_para_back); - lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_PR, &style_para_back); - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonXValue); - lv_group_add_obj(g, buttonYValue); - lv_group_add_obj(g, buttonZValue); - lv_group_add_obj(g, buttonE0Value); - lv_group_add_obj(g, buttonTurnPage); - } - #endif - } - else { - labelE1Text = lv_label_create(scr, NULL); - lv_obj_set_style(labelE1Text, &tft_style_label_rel); - lv_obj_set_pos(labelE1Text, PARA_UI_POS_X, PARA_UI_POS_Y + 10); - lv_label_set_text(labelE1Text, machine_menu.E1_Steps); - - buttonE1Value = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonE1Value, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y + PARA_UI_VALUE_V); - lv_obj_set_size(buttonE1Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonE1Value, event_handler, ID_STEP_E1, NULL, 0); - lv_btn_set_style(buttonE1Value, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonE1Value, LV_BTN_STYLE_PR, &style_para_value); - labelE1Value = lv_label_create(buttonE1Value, NULL); - - line1 = lv_line_create(scr, NULL); - lv_ex_line(line1, line_points[0]); - - buttonTurnPage = lv_btn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_STEP_UP, NULL, 0); - lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_REL, &style_para_back); - lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_PR, &style_para_back); - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonE1Value); - lv_group_add_obj(g, buttonTurnPage); - } - #endif - } - - lv_obj_set_pos(buttonTurnPage, PARA_UI_TURN_PAGE_POS_X, PARA_UI_TURN_PAGE_POS_Y); - lv_obj_set_size(buttonTurnPage, PARA_UI_BACK_BTN_X_SIZE, PARA_UI_BACK_BTN_Y_SIZE); - labelTurnPage = lv_label_create(buttonTurnPage, NULL); - - buttonBack = lv_btn_create(scr, NULL); - lv_btn_set_style(buttonBack, LV_BTN_STYLE_REL, &style_para_back); - lv_btn_set_style(buttonBack, LV_BTN_STYLE_PR, &style_para_back); - lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); - lv_obj_set_size(buttonBack, PARA_UI_BACK_BTN_X_SIZE, PARA_UI_BACK_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_STEP_RETURN, NULL, 0); - label_Back = lv_label_create(buttonBack, NULL); - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonBack); - #endif - - if (gCfgItems.multiple_language != 0) { - if (uiCfg.para_ui_page != 1) { - lv_label_set_text(labelTurnPage, machine_menu.next); - lv_obj_align(labelTurnPage, buttonTurnPage, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%.1f"), planner.settings.axis_steps_per_mm[X_AXIS]); - lv_label_set_text(labelXValue, public_buf_l); - lv_obj_align(labelXValue, buttonXValue, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%.1f"), planner.settings.axis_steps_per_mm[Y_AXIS]); - lv_label_set_text(labelYValue, public_buf_l); - lv_obj_align(labelYValue, buttonYValue, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%.1f"), planner.settings.axis_steps_per_mm[Z_AXIS]); - lv_label_set_text(labelZValue, public_buf_l); - lv_obj_align(labelZValue, buttonZValue, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%.1f"), planner.settings.axis_steps_per_mm[E_AXIS]); - lv_label_set_text(labelE0Value, public_buf_l); - lv_obj_align(labelE0Value, buttonE0Value, LV_ALIGN_CENTER, 0, 0); - } - else { - lv_label_set_text(labelTurnPage, machine_menu.previous); - lv_obj_align(labelTurnPage, buttonTurnPage, LV_ALIGN_CENTER, 0, 0); - - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%.1f"), planner.settings.axis_steps_per_mm[E_AXIS_N(1)]); - lv_label_set_text(labelE1Value, public_buf_l); - lv_obj_align(labelE1Value, buttonE1Value, LV_ALIGN_CENTER, 0, 0); - } - - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_CENTER, 0, 0); - } -} - -void lv_clear_step_settings() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_current_settings.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_current_settings.cpp deleted file mode 100644 index 10aa7badff7e..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_current_settings.cpp +++ /dev/null @@ -1,387 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if BOTH(HAS_TFT_LVGL_UI, HAS_TRINAMIC_CONFIG) - -#include "lv_conf.h" -#include "draw_ui.h" - -#include "../../../../MarlinCore.h" -#include "../../../../module/planner.h" -#include "../../../../module/stepper/indirection.h" -#include "../../../../feature/tmc_util.h" - -extern lv_group_t * g; -static lv_obj_t * scr; - -#define ID_TMC_CURRENT_RETURN 1 -#define ID_TMC_CURRENT_X 2 -#define ID_TMC_CURRENT_Y 3 -#define ID_TMC_CURRENT_Z 4 -#define ID_TMC_CURRENT_E0 5 -#define ID_TMC_CURRENT_E1 6 -#define ID_TMC_CURRENT_DOWN 7 -#define ID_TMC_CURRENT_UP 8 - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_TMC_CURRENT_RETURN: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - uiCfg.para_ui_page = 0; - lv_clear_tmc_current_settings(); - draw_return_ui(); - } - break; - #if AXIS_IS_TMC(X) - case ID_TMC_CURRENT_X: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = Xcurrent; - lv_clear_tmc_current_settings(); - lv_draw_number_key(); - } - break; - #endif - - #if AXIS_IS_TMC(Y) - case ID_TMC_CURRENT_Y: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = Ycurrent; - lv_clear_tmc_current_settings(); - lv_draw_number_key(); - } - break; - #endif - - #if AXIS_IS_TMC(Z) - case ID_TMC_CURRENT_Z: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = Zcurrent; - lv_clear_tmc_current_settings(); - lv_draw_number_key(); - } - break; - #endif - - #if AXIS_IS_TMC(E0) - case ID_TMC_CURRENT_E0: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = E0current; - lv_clear_tmc_current_settings(); - lv_draw_number_key(); - } - break; - #endif - - #if AXIS_IS_TMC(E1) - case ID_TMC_CURRENT_E1: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = E1current; - lv_clear_tmc_current_settings(); - lv_draw_number_key(); - } - break; - #endif - case ID_TMC_CURRENT_UP: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - uiCfg.para_ui_page = 0; - lv_clear_tmc_current_settings(); - lv_draw_tmc_current_settings(); - } - break; - case ID_TMC_CURRENT_DOWN: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - uiCfg.para_ui_page = 1; - lv_clear_tmc_current_settings(); - lv_draw_tmc_current_settings(); - } - break; - } -} - -void lv_draw_tmc_current_settings(void) { - lv_obj_t *buttonBack = NULL, *label_Back = NULL; - lv_obj_t *labelXText = NULL, *buttonXValue = NULL, *labelXValue = NULL; - lv_obj_t *labelYText = NULL, *buttonYValue = NULL, *labelYValue = NULL; - lv_obj_t *labelZText = NULL, *buttonZValue = NULL, *labelZValue = NULL; - lv_obj_t *labelE0Text = NULL, *buttonE0Value = NULL, *labelE0Value = NULL; - - lv_obj_t * line1 = NULL, * line2 = NULL, * line3 = NULL, * line4 = NULL; - //#if AXIS_IS_TMC(E1) - lv_obj_t *buttonTurnPage = NULL, *labelTurnPage = NULL; - lv_obj_t *labelE1Text = NULL, *buttonE1Value = NULL, *labelE1Value = NULL; - //#endif - float milliamps; - - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != TMC_CURRENT_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = TMC_CURRENT_UI; - } - disp_state = TMC_CURRENT_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, machine_menu.TmcCurrentConfTitle); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - if (uiCfg.para_ui_page != 1) { - labelXText = lv_label_create(scr, NULL); - lv_obj_set_style(labelXText, &tft_style_label_rel); - lv_obj_set_pos(labelXText, PARA_UI_POS_X, PARA_UI_POS_Y + 10); - lv_label_set_text(labelXText, machine_menu.X_Current); - - buttonXValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonXValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y + PARA_UI_VALUE_V); - lv_obj_set_size(buttonXValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonXValue, event_handler, ID_TMC_CURRENT_X, NULL, 0); - lv_btn_set_style(buttonXValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonXValue, LV_BTN_STYLE_PR, &style_para_value); - labelXValue = lv_label_create(buttonXValue, NULL); - - line1 = lv_line_create(scr, NULL); - lv_ex_line(line1, line_points[0]); - - labelYText = lv_label_create(scr, NULL); - lv_obj_set_style(labelYText, &tft_style_label_rel); - lv_obj_set_pos(labelYText, PARA_UI_POS_X, PARA_UI_POS_Y * 2 + 10); - lv_label_set_text(labelYText, machine_menu.Y_Current); - - buttonYValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonYValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 2 + PARA_UI_VALUE_V); - lv_obj_set_size(buttonYValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonYValue, event_handler, ID_TMC_CURRENT_Y, NULL, 0); - lv_btn_set_style(buttonYValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonYValue, LV_BTN_STYLE_PR, &style_para_value); - labelYValue = lv_label_create(buttonYValue, NULL); - - line2 = lv_line_create(scr, NULL); - lv_ex_line(line2, line_points[1]); - - labelZText = lv_label_create(scr, NULL); - lv_obj_set_style(labelZText, &tft_style_label_rel); - lv_obj_set_pos(labelZText, PARA_UI_POS_X, PARA_UI_POS_Y * 3 + 10); - lv_label_set_text(labelZText, machine_menu.Z_Current); - - buttonZValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonZValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 3 + PARA_UI_VALUE_V); - lv_obj_set_size(buttonZValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonZValue, event_handler, ID_TMC_CURRENT_Z, NULL, 0); - lv_btn_set_style(buttonZValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonZValue, LV_BTN_STYLE_PR, &style_para_value); - labelZValue = lv_label_create(buttonZValue, NULL); - - line3 = lv_line_create(scr, NULL); - lv_ex_line(line3, line_points[2]); - - labelE0Text = lv_label_create(scr, NULL); - lv_obj_set_style(labelE0Text, &tft_style_label_rel); - lv_obj_set_pos(labelE0Text, PARA_UI_POS_X, PARA_UI_POS_Y * 4 + 10); - lv_label_set_text(labelE0Text, machine_menu.E0_Current); - - buttonE0Value = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonE0Value, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 4 + PARA_UI_VALUE_V); - lv_obj_set_size(buttonE0Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonE0Value, event_handler, ID_TMC_CURRENT_E0, NULL, 0); - lv_btn_set_style(buttonE0Value, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonE0Value, LV_BTN_STYLE_PR, &style_para_value); - labelE0Value = lv_label_create(buttonE0Value, NULL); - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonXValue); - lv_group_add_obj(g, buttonYValue); - lv_group_add_obj(g, buttonZValue); - lv_group_add_obj(g, buttonE0Value); - } - #endif - - line4 = lv_line_create(scr, NULL); - lv_ex_line(line4, line_points[3]); - - //#if AXIS_IS_TMC(E1) - buttonTurnPage = lv_btn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_TMC_CURRENT_DOWN, NULL, 0); - lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_REL, &style_para_back); - lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_PR, &style_para_back); - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonTurnPage); - #endif - //#endif - } - else { - //#if AXIS_IS_TMC(E1) - labelE1Text = lv_label_create(scr, NULL); - lv_obj_set_style(labelE1Text, &tft_style_label_rel); - lv_obj_set_pos(labelE1Text, PARA_UI_POS_X, PARA_UI_POS_Y + 10); - lv_label_set_text(labelE1Text, machine_menu.E1_Current); - - buttonE1Value = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonE1Value, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y + PARA_UI_VALUE_V); - lv_obj_set_size(buttonE1Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonE1Value, event_handler, ID_TMC_CURRENT_E1, NULL, 0); - lv_btn_set_style(buttonE1Value, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonE1Value, LV_BTN_STYLE_PR, &style_para_value); - labelE1Value = lv_label_create(buttonE1Value, NULL); - - line1 = lv_line_create(scr, NULL); - lv_ex_line(line1, line_points[0]); - - buttonTurnPage = lv_btn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_TMC_CURRENT_UP, NULL, 0); - lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_REL, &style_para_back); - lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_PR, &style_para_back); - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonE1Value); - lv_group_add_obj(g, buttonTurnPage); - } - #endif - //#endif - } - //#if AXIS_IS_TMC(E1) - lv_obj_set_pos(buttonTurnPage, PARA_UI_TURN_PAGE_POS_X, PARA_UI_TURN_PAGE_POS_Y); - lv_obj_set_size(buttonTurnPage, PARA_UI_BACK_BTN_X_SIZE, PARA_UI_BACK_BTN_Y_SIZE); - labelTurnPage = lv_label_create(buttonTurnPage, NULL); - //#endif - - buttonBack = lv_btn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_TMC_CURRENT_RETURN, NULL, 0); - lv_btn_set_style(buttonBack, LV_BTN_STYLE_REL, &style_para_back); - lv_btn_set_style(buttonBack, LV_BTN_STYLE_PR, &style_para_back); - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonBack); - #endif - - lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); - lv_obj_set_size(buttonBack, PARA_UI_BACK_BTN_X_SIZE, PARA_UI_BACK_BTN_Y_SIZE); - label_Back = lv_label_create(buttonBack, NULL); - - if (gCfgItems.multiple_language != 0) { - if (uiCfg.para_ui_page != 1) { - //#if AXIS_IS_TMC(E1) - lv_label_set_text(labelTurnPage, machine_menu.next); - lv_obj_align(labelTurnPage, buttonTurnPage, LV_ALIGN_CENTER, 0, 0); - //#endif - #if AXIS_IS_TMC(X) - milliamps = stepperX.getMilliamps(); - #else - milliamps = -1; - #endif - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%.1f"), milliamps); - lv_label_set_text(labelXValue, public_buf_l); - lv_obj_align(labelXValue, buttonXValue, LV_ALIGN_CENTER, 0, 0); - - #if AXIS_IS_TMC(Y) - milliamps = stepperY.getMilliamps(); - #else - milliamps = -1; - #endif - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%.1f"), milliamps); - lv_label_set_text(labelYValue, public_buf_l); - lv_obj_align(labelYValue, buttonYValue, LV_ALIGN_CENTER, 0, 0); - - #if AXIS_IS_TMC(Z) - milliamps = stepperZ.getMilliamps(); - #else - milliamps = -1; - #endif - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%.1f"), milliamps); - lv_label_set_text(labelZValue, public_buf_l); - lv_obj_align(labelZValue, buttonZValue, LV_ALIGN_CENTER, 0, 0); - - #if AXIS_IS_TMC(E0) - milliamps = stepperE0.getMilliamps(); - #else - milliamps = -1; - #endif - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%.1f"), milliamps); - lv_label_set_text(labelE0Value, public_buf_l); - lv_obj_align(labelE0Value, buttonE0Value, LV_ALIGN_CENTER, 0, 0); - } - else { - //#if AXIS_IS_TMC(E1) - lv_label_set_text(labelTurnPage, machine_menu.previous); - lv_obj_align(labelTurnPage, buttonTurnPage, LV_ALIGN_CENTER, 0, 0); - #if AXIS_IS_TMC(E1) - milliamps = stepperE1.getMilliamps(); - #else - milliamps = -1; - #endif - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%.1f"), milliamps); - lv_label_set_text(labelE1Value, public_buf_l); - lv_obj_align(labelE1Value, buttonE1Value, LV_ALIGN_CENTER, 0, 0); - //#endif - } - - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_CENTER, 0, 0); - } -} - -void lv_clear_tmc_current_settings() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI && HAS_TRINAMIC_CONFIG diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_step_mode_settings.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_step_mode_settings.cpp deleted file mode 100644 index 3e014a781cf0..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_step_mode_settings.cpp +++ /dev/null @@ -1,586 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if BOTH(HAS_TFT_LVGL_UI, HAS_STEALTHCHOP) - -#include "lv_conf.h" -#include "draw_ui.h" - -#include "../../../../MarlinCore.h" -#include "../../../../module/planner.h" -#include "../../../../module/stepper/indirection.h" -#include "../../../../feature/tmc_util.h" -#include "../../../../gcode/gcode.h" -#include "../../../../module/planner.h" - -extern lv_group_t * g; -static lv_obj_t * scr; - -#define ID_TMC_MODE_RETURN 1 -#define ID_TMC_MODE_X 2 -#define ID_TMC_MODE_Y 3 -#define ID_TMC_MODE_Z 4 -#define ID_TMC_MODE_E0 5 -#define ID_TMC_MODE_E1 6 -#define ID_TMC_MODE_DOWN 7 -#define ID_TMC_MODE_UP 8 - -static lv_obj_t *labelXState = NULL, *labelYState = NULL, *labelZState = NULL, *labelE0State = NULL; -static lv_obj_t *buttonXState = NULL, *buttonYState = NULL, *buttonZState = NULL, *buttonE0State = NULL; - -//#if AXIS_HAS_STEALTHCHOP(E1) - static lv_obj_t *labelE1State = NULL, *buttonE1State = NULL; -//#endif - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_TMC_MODE_RETURN: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - uiCfg.para_ui_page = 0; - lv_clear_tmc_step_mode_settings(); - draw_return_ui(); - } - break; - - #if AXIS_HAS_STEALTHCHOP(X) - case ID_TMC_MODE_X: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - if (stepperX.stored.stealthChop_enabled) { - stepperX.stored.stealthChop_enabled = false; - stepperX.refresh_stepping_mode(); - lv_imgbtn_set_src(buttonXState, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); - lv_imgbtn_set_src(buttonXState, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); - lv_label_set_text(labelXState, machine_menu.disable); - //lv_obj_align(labelXState, buttonE1State, LV_ALIGN_IN_LEFT_MID,0, 0); - // gcode.process_subcommands_now_P(PSTR("M500")); - } - else { - stepperX.stored.stealthChop_enabled = true; - stepperX.refresh_stepping_mode(); - lv_imgbtn_set_src(buttonXState, LV_BTN_STATE_REL, "F:/bmp_enable.bin"); - lv_imgbtn_set_src(buttonXState, LV_BTN_STATE_PR, "F:/bmp_enable.bin"); - lv_label_set_text(labelXState, machine_menu.enable); - // gcode.process_subcommands_now_P(PSTR("M500")); - } - gcode.process_subcommands_now_P(PSTR("M500")); - } - break; - #endif // if AXIS_HAS_STEALTHCHOP(X) - - #if AXIS_HAS_STEALTHCHOP(Y) - case ID_TMC_MODE_Y: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - if (stepperY.stored.stealthChop_enabled) { - stepperY.stored.stealthChop_enabled = false; - stepperY.refresh_stepping_mode(); - lv_imgbtn_set_src(buttonYState, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); - lv_imgbtn_set_src(buttonYState, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); - lv_label_set_text(labelYState, machine_menu.disable); - //lv_obj_align(labelXState, buttonE1State, LV_ALIGN_IN_LEFT_MID,0, 0); - } - else { - stepperY.stored.stealthChop_enabled = true; - stepperY.refresh_stepping_mode(); - lv_imgbtn_set_src(buttonYState, LV_BTN_STATE_REL, "F:/bmp_enable.bin"); - lv_imgbtn_set_src(buttonYState, LV_BTN_STATE_PR, "F:/bmp_enable.bin"); - lv_label_set_text(labelYState, machine_menu.enable); - } - gcode.process_subcommands_now_P(PSTR("M500")); - } - break; - #endif // if AXIS_HAS_STEALTHCHOP(Y) - - #if AXIS_HAS_STEALTHCHOP(Z) - case ID_TMC_MODE_Z: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - if (stepperZ.stored.stealthChop_enabled) { - stepperZ.stored.stealthChop_enabled = false; - stepperZ.refresh_stepping_mode(); - lv_imgbtn_set_src(buttonZState, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); - lv_imgbtn_set_src(buttonZState, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); - lv_label_set_text(labelZState, machine_menu.disable); - //lv_obj_align(labelXState, buttonE1State, LV_ALIGN_IN_LEFT_MID,0, 0); - } - else { - stepperZ.stored.stealthChop_enabled = true; - stepperZ.refresh_stepping_mode(); - lv_imgbtn_set_src(buttonZState, LV_BTN_STATE_REL, "F:/bmp_enable.bin"); - lv_imgbtn_set_src(buttonZState, LV_BTN_STATE_PR, "F:/bmp_enable.bin"); - lv_label_set_text(labelZState, machine_menu.enable); - } - gcode.process_subcommands_now_P(PSTR("M500")); - } - break; - #endif // if AXIS_HAS_STEALTHCHOP(Z) - - #if AXIS_HAS_STEALTHCHOP(E0) - case ID_TMC_MODE_E0: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - if (stepperE0.stored.stealthChop_enabled) { - stepperE0.stored.stealthChop_enabled = false; - stepperE0.refresh_stepping_mode(); - lv_imgbtn_set_src(buttonE0State, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); - lv_imgbtn_set_src(buttonE0State, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); - lv_label_set_text(labelE0State, machine_menu.disable); - //lv_obj_align(labelXState, buttonE1State, LV_ALIGN_IN_LEFT_MID,0, 0); - } - else { - stepperE0.stored.stealthChop_enabled = true; - stepperE0.refresh_stepping_mode(); - lv_imgbtn_set_src(buttonE0State, LV_BTN_STATE_REL, "F:/bmp_enable.bin"); - lv_imgbtn_set_src(buttonE0State, LV_BTN_STATE_PR, "F:/bmp_enable.bin"); - lv_label_set_text(labelE0State, machine_menu.enable); - } - gcode.process_subcommands_now_P(PSTR("M500")); - } - break; - #endif // if AXIS_HAS_STEALTHCHOP(E0) - - #if AXIS_HAS_STEALTHCHOP(E1) - case ID_TMC_MODE_E1: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - if (stepperE1.stored.stealthChop_enabled) { - stepperE1.stored.stealthChop_enabled = false; - stepperE1.refresh_stepping_mode(); - lv_imgbtn_set_src(buttonE1State, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); - lv_imgbtn_set_src(buttonE1State, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); - lv_label_set_text(labelE1State, machine_menu.disable); - //lv_obj_align(labelXState, buttonE1State, LV_ALIGN_IN_LEFT_MID,0, 0); - } - else { - stepperE1.stored.stealthChop_enabled = true; - stepperE1.refresh_stepping_mode(); - lv_imgbtn_set_src(buttonE1State, LV_BTN_STATE_REL, "F:/bmp_enable.bin"); - lv_imgbtn_set_src(buttonE1State, LV_BTN_STATE_PR, "F:/bmp_enable.bin"); - lv_label_set_text(labelE1State, machine_menu.enable); - } - gcode.process_subcommands_now_P(PSTR("M500")); - } - break; - #endif // if AXIS_HAS_STEALTHCHOP(E1) - case ID_TMC_MODE_UP: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - uiCfg.para_ui_page = 0; - lv_clear_tmc_step_mode_settings(); - lv_draw_tmc_step_mode_settings(); - } - break; - case ID_TMC_MODE_DOWN: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - uiCfg.para_ui_page = 1; - lv_clear_tmc_step_mode_settings(); - lv_draw_tmc_step_mode_settings(); - } - break; - } -} - -void lv_draw_tmc_step_mode_settings(void) { - lv_obj_t *buttonBack = NULL, *label_Back = NULL; - lv_obj_t *buttonXText = NULL, *labelXText = NULL; - lv_obj_t *buttonYText = NULL, *labelYText = NULL; - lv_obj_t *buttonZText = NULL, *labelZText = NULL; - lv_obj_t *buttonE0Text = NULL, *labelE0Text = NULL; - - lv_obj_t * line1 = NULL, * line2 = NULL, * line3 = NULL, * line4 = NULL; - //#if AXIS_HAS_STEALTHCHOP(E1) - lv_obj_t *buttonTurnPage = NULL, *labelTurnPage = NULL; - lv_obj_t *buttonE1Text = NULL, *labelE1Text = NULL; - //#endif - - - labelXState = NULL; - buttonXState = NULL; - labelYState = NULL; - buttonYState = NULL; - labelZState = NULL; - buttonZState = NULL; - labelE0State = NULL; - buttonE0State = NULL; - //#if AXIS_HAS_STEALTHCHOP(E1) - labelE1State = NULL; - buttonE1State = NULL; - //#endif - - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != TMC_MODE_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = TMC_MODE_UI; - } - disp_state = TMC_MODE_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, machine_menu.TmcStepModeConfTitle); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - if (uiCfg.para_ui_page != 1) { - buttonXText = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonXText, PARA_UI_POS_X, PARA_UI_POS_Y); /*Set its position*/ - lv_obj_set_size(buttonXText, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonXText, event_handler); - lv_btn_set_style(buttonXText, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonXText, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonXText, LV_LAYOUT_OFF); - labelXText = lv_label_create(buttonXText, NULL); /*Add a label to the button*/ - - buttonXState = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonXState, PARA_UI_STATE_POS_X, PARA_UI_POS_Y + PARA_UI_STATE_V); - #if AXIS_HAS_STEALTHCHOP(X) - if (stepperX.get_stealthChop_status()) { - lv_imgbtn_set_src(buttonXState, LV_BTN_STATE_REL, "F:/bmp_enable.bin"); - lv_imgbtn_set_src(buttonXState, LV_BTN_STATE_PR, "F:/bmp_enable.bin"); - } - else { - lv_imgbtn_set_src(buttonXState, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); - lv_imgbtn_set_src(buttonXState, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); - } - #else - lv_imgbtn_set_src(buttonXState, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); - lv_imgbtn_set_src(buttonXState, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); - #endif - lv_obj_set_event_cb_mks(buttonXState, event_handler, ID_TMC_MODE_X, NULL, 0); - - lv_imgbtn_set_style(buttonXState, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonXState, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_btn_set_layout(buttonXState, LV_LAYOUT_OFF); - labelXState = lv_label_create(buttonXState, NULL); - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonXState); - #endif - - line1 = lv_line_create(scr, NULL); - lv_ex_line(line1, line_points[0]); - - buttonYText = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonYText, PARA_UI_POS_X, PARA_UI_POS_Y * 2); /*Set its position*/ - lv_obj_set_size(buttonYText, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonYText, event_handler); - lv_btn_set_style(buttonYText, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonYText, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonYText, LV_LAYOUT_OFF); - labelYText = lv_label_create(buttonYText, NULL); /*Add a label to the button*/ - - buttonYState = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonYState, PARA_UI_STATE_POS_X, PARA_UI_POS_Y * 2 + PARA_UI_STATE_V); - #if AXIS_HAS_STEALTHCHOP(Y) - if (stepperY.get_stealthChop_status()) { - lv_imgbtn_set_src(buttonYState, LV_BTN_STATE_REL, "F:/bmp_enable.bin"); - lv_imgbtn_set_src(buttonYState, LV_BTN_STATE_PR, "F:/bmp_enable.bin"); - } - else { - lv_imgbtn_set_src(buttonYState, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); - lv_imgbtn_set_src(buttonYState, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); - } - #else - lv_imgbtn_set_src(buttonYState, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); - lv_imgbtn_set_src(buttonYState, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); - #endif - lv_obj_set_event_cb_mks(buttonYState, event_handler, ID_TMC_MODE_Y, NULL, 0); - - lv_imgbtn_set_style(buttonYState, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonYState, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_btn_set_layout(buttonYState, LV_LAYOUT_OFF); - labelYState = lv_label_create(buttonYState, NULL); - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonYState); - #endif - - line2 = lv_line_create(scr, NULL); - lv_ex_line(line2, line_points[1]); - - buttonZText = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonZText, PARA_UI_POS_X, PARA_UI_POS_Y * 3); /*Set its position*/ - lv_obj_set_size(buttonZText, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonZText, event_handler); - lv_btn_set_style(buttonZText, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonZText, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonZText, LV_LAYOUT_OFF); - labelZText = lv_label_create(buttonZText, NULL); /*Add a label to the button*/ - - buttonZState = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonZState, PARA_UI_STATE_POS_X, PARA_UI_POS_Y * 3 + PARA_UI_STATE_V); - #if AXIS_HAS_STEALTHCHOP(Z) - if (stepperZ.get_stealthChop_status()) { - lv_imgbtn_set_src(buttonZState, LV_BTN_STATE_REL, "F:/bmp_enable.bin"); - lv_imgbtn_set_src(buttonZState, LV_BTN_STATE_PR, "F:/bmp_enable.bin"); - } - else { - lv_imgbtn_set_src(buttonZState, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); - lv_imgbtn_set_src(buttonZState, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); - } - #else - lv_imgbtn_set_src(buttonZState, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); - lv_imgbtn_set_src(buttonZState, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); - #endif - lv_obj_set_event_cb_mks(buttonZState, event_handler, ID_TMC_MODE_Z, NULL, 0); - lv_imgbtn_set_style(buttonZState, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonZState, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_btn_set_layout(buttonZState, LV_LAYOUT_OFF); - labelZState = lv_label_create(buttonZState, NULL); - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonZState); - #endif - - line3 = lv_line_create(scr, NULL); - lv_ex_line(line3, line_points[2]); - - buttonE0Text = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonE0Text, PARA_UI_POS_X, PARA_UI_POS_Y * 4); /*Set its position*/ - lv_obj_set_size(buttonE0Text, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonE0Text, event_handler); - lv_btn_set_style(buttonE0Text, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonE0Text, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonE0Text, LV_LAYOUT_OFF); - labelE0Text = lv_label_create(buttonE0Text, NULL); /*Add a label to the button*/ - - buttonE0State = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonE0State, PARA_UI_STATE_POS_X, PARA_UI_POS_Y * 4 + PARA_UI_STATE_V); - #if AXIS_HAS_STEALTHCHOP(E0) - if (stepperE0.get_stealthChop_status()) { - lv_imgbtn_set_src(buttonE0State, LV_BTN_STATE_REL, "F:/bmp_enable.bin"); - lv_imgbtn_set_src(buttonE0State, LV_BTN_STATE_PR, "F:/bmp_enable.bin"); - } - else { - lv_imgbtn_set_src(buttonE0State, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); - lv_imgbtn_set_src(buttonE0State, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); - } - #else - lv_imgbtn_set_src(buttonE0State, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); - lv_imgbtn_set_src(buttonE0State, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); - #endif - - lv_obj_set_event_cb_mks(buttonE0State, event_handler, ID_TMC_MODE_E0, NULL, 0); - - lv_imgbtn_set_style(buttonE0State, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonE0State, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_btn_set_layout(buttonE0State, LV_LAYOUT_OFF); - labelE0State = lv_label_create(buttonE0State, NULL); - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonE0State); - #endif - - - line4 = lv_line_create(scr, NULL); - lv_ex_line(line4, line_points[3]); - - //#if AXIS_HAS_STEALTHCHOP(E1) - buttonTurnPage = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_TMC_MODE_DOWN, NULL, 0); - lv_imgbtn_set_src(buttonTurnPage, LV_BTN_STATE_REL, "F:/bmp_back70x40.bin"); - lv_imgbtn_set_src(buttonTurnPage, LV_BTN_STATE_PR, "F:/bmp_back70x40.bin"); - lv_imgbtn_set_style(buttonTurnPage, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonTurnPage, LV_BTN_STATE_REL, &tft_style_label_rel); - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonTurnPage); - #endif - //#endif - } - else { - //#if AXIS_HAS_STEALTHCHOP(E1) - buttonE1Text = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonE1Text, PARA_UI_POS_X, PARA_UI_POS_Y); /*Set its position*/ - lv_obj_set_size(buttonE1Text, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonE1Text, event_handler); - lv_btn_set_style(buttonE1Text, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonE1Text, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonE1Text, LV_LAYOUT_OFF); - labelE1Text = lv_label_create(buttonE1Text, NULL); /*Add a label to the button*/ - - buttonE1State = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonE1State, PARA_UI_STATE_POS_X, PARA_UI_POS_Y + PARA_UI_STATE_V); - #if AXIS_HAS_STEALTHCHOP(E1) - if (stepperE1.get_stealthChop_status()) { - lv_imgbtn_set_src(buttonE1State, LV_BTN_STATE_REL, "F:/bmp_enable.bin"); - lv_imgbtn_set_src(buttonE1State, LV_BTN_STATE_PR, "F:/bmp_enable.bin"); - } - else { - lv_imgbtn_set_src(buttonE1State, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); - lv_imgbtn_set_src(buttonE1State, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); - } - #else - lv_imgbtn_set_src(buttonE1State, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); - lv_imgbtn_set_src(buttonE1State, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); - #endif - lv_obj_set_event_cb_mks(buttonE1State, event_handler, ID_TMC_MODE_E1, NULL, 0); - lv_imgbtn_set_style(buttonE1State, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonE1State, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_btn_set_layout(buttonE1State, LV_LAYOUT_OFF); - labelE1State = lv_label_create(buttonE1State, NULL); - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonE1State); - #endif - - line1 = lv_line_create(scr, NULL); - lv_ex_line(line1, line_points[0]); - - buttonTurnPage = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_TMC_MODE_UP, NULL, 0); - lv_imgbtn_set_src(buttonTurnPage, LV_BTN_STATE_REL, "F:/bmp_back70x40.bin"); - lv_imgbtn_set_src(buttonTurnPage, LV_BTN_STATE_PR, "F:/bmp_back70x40.bin"); - lv_imgbtn_set_style(buttonTurnPage, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonTurnPage, LV_BTN_STATE_REL, &tft_style_label_rel); - //#endif - } - //#if AXIS_HAS_STEALTHCHOP(E1) - lv_obj_set_pos(buttonTurnPage, PARA_UI_TURN_PAGE_POS_X, PARA_UI_TURN_PAGE_POS_Y); - lv_btn_set_layout(buttonTurnPage, LV_LAYOUT_OFF); - labelTurnPage = lv_label_create(buttonTurnPage, NULL); - //#endif - - buttonBack = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_TMC_MODE_RETURN, NULL, 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_back70x40.bin"); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_back70x40.bin"); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonBack); - #endif - - lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); - lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - label_Back = lv_label_create(buttonBack, NULL); - - if (gCfgItems.multiple_language != 0) { - if (uiCfg.para_ui_page != 1) { - lv_label_set_text(labelXText, machine_menu.X_StepMode); - lv_obj_align(labelXText, buttonXText, LV_ALIGN_IN_LEFT_MID, 0, 0); - - lv_label_set_text(labelYText, machine_menu.Y_StepMode); - lv_obj_align(labelYText, buttonYText, LV_ALIGN_IN_LEFT_MID, 0, 0); - - lv_label_set_text(labelZText, machine_menu.Z_StepMode); - lv_obj_align(labelZText, buttonZText, LV_ALIGN_IN_LEFT_MID, 0, 0); - - lv_label_set_text(labelE0Text, machine_menu.E0_StepMode); - lv_obj_align(labelE0Text, buttonE0Text, LV_ALIGN_IN_LEFT_MID, 0, 0); - - #if AXIS_HAS_STEALTHCHOP(X) - if (stepperX.get_stealthChop_status()) - lv_label_set_text(labelXState, machine_menu.enable); - else - lv_label_set_text(labelXState, machine_menu.disable); - #else - lv_label_set_text(labelXState, machine_menu.disable); - #endif - lv_obj_align(labelXState, buttonXState, LV_ALIGN_CENTER, 0, 0); - - #if AXIS_HAS_STEALTHCHOP(Y) - if (stepperY.get_stealthChop_status()) - lv_label_set_text(labelYState, machine_menu.enable); - else - lv_label_set_text(labelYState, machine_menu.disable); - #else - lv_label_set_text(labelYState, machine_menu.disable); - #endif - lv_obj_align(labelYState, buttonYState, LV_ALIGN_CENTER, 0, 0); - - #if AXIS_HAS_STEALTHCHOP(Z) - if (stepperZ.get_stealthChop_status()) - lv_label_set_text(labelZState, machine_menu.enable); - else - lv_label_set_text(labelZState, machine_menu.disable); - #else - lv_label_set_text(labelZState, machine_menu.disable); - #endif - lv_obj_align(labelZState, buttonZState, LV_ALIGN_CENTER, 0, 0); - - #if AXIS_HAS_STEALTHCHOP(E0) - if (stepperE0.get_stealthChop_status()) - lv_label_set_text(labelE0State, machine_menu.enable); - else - lv_label_set_text(labelE0State, machine_menu.disable); - #else - lv_label_set_text(labelE0State, machine_menu.disable); - #endif - lv_obj_align(labelE0State, buttonE0State, LV_ALIGN_CENTER, 0, 0); - - //#if AXIS_HAS_STEALTHCHOP(E1) - lv_label_set_text(labelTurnPage, machine_menu.next); - lv_obj_align(labelTurnPage, buttonTurnPage, LV_ALIGN_CENTER, 0, 0); - //#endif - } - else { - //#if AXIS_HAS_STEALTHCHOP(E1) - lv_label_set_text(labelE1Text, machine_menu.E1_StepMode); - lv_obj_align(labelE1Text, buttonE1Text, LV_ALIGN_IN_LEFT_MID, 0, 0); - #if AXIS_HAS_STEALTHCHOP(E1) - if (stepperE1.get_stealthChop_status()) - lv_label_set_text(labelE1State, machine_menu.enable); - else - lv_label_set_text(labelE1State, machine_menu.disable); - #else - lv_label_set_text(labelE1State, machine_menu.disable); - #endif - lv_obj_align(labelE1State, buttonE1State, LV_ALIGN_CENTER, 0, 0); - - lv_label_set_text(labelTurnPage, machine_menu.previous); - lv_obj_align(labelTurnPage, buttonTurnPage, LV_ALIGN_CENTER, 0, 0); - //#endif - } - - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_CENTER, 0, 0); - } -} - -void lv_clear_tmc_step_mode_settings() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI && HAS_STEALTHCHOP diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_tool.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_tool.cpp deleted file mode 100644 index 3681b1b2d601..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_tool.cpp +++ /dev/null @@ -1,284 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "lv_conf.h" -#include "draw_ui.h" -//#include "../lvgl/src/lv_objx/lv_imgbtn.h" -//#include "../lvgl/src/lv_objx/lv_img.h" -//#include "../lvgl/src/lv_core/lv_disp.h" -//#include "../lvgl/src/lv_core/lv_refr.h" - -#include "../../../../MarlinCore.h" -#include "../../../../gcode/queue.h" -#include "../../../../module/temperature.h" - -extern lv_group_t * g; -static lv_obj_t * scr; - -#define ID_T_PRE_HEAT 1 -#define ID_T_EXTRUCT 2 -#define ID_T_MOV 3 -#define ID_T_HOME 4 -#define ID_T_LEVELING 5 -#define ID_T_FILAMENT 6 -#define ID_T_MORE 7 -#define ID_T_RETURN 8 - -#if ENABLED(MKS_TEST) - extern uint8_t curent_disp_ui; -#endif - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_T_PRE_HEAT: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_tool(); - lv_draw_preHeat(); - } - break; - case ID_T_EXTRUCT: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_tool(); - lv_draw_extrusion(); - } - break; - case ID_T_MOV: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_tool(); - lv_draw_move_motor(); - } - break; - case ID_T_HOME: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_tool(); - lv_draw_home(); - } - break; - case ID_T_LEVELING: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - #if ENABLED(AUTO_BED_LEVELING_BILINEAR) - //queue.enqueue_one_P(PSTR("G28")); - //queue.enqueue_one_P(PSTR("G29")); - get_gcode_command(AUTO_LEVELING_COMMAND_ADDR,(uint8_t *)public_buf_m); - public_buf_m[sizeof(public_buf_m)-1] = 0; - queue.inject_P(PSTR(public_buf_m)); - #else - uiCfg.leveling_first_time = 1; - lv_clear_tool(); - lv_draw_manualLevel(); - #endif - } - break; - case ID_T_FILAMENT: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - uiCfg.desireSprayerTempBak = thermalManager.temp_hotend[uiCfg.curSprayerChoose].target; - lv_clear_tool(); - lv_draw_filament_change(); - } - break; - case ID_T_MORE: break; - case ID_T_RETURN: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - TERN_(MKS_TEST, curent_disp_ui = 1); - lv_clear_tool(); - lv_draw_ready_print(); - } - break; - } -} - -void lv_draw_tool(void) { - lv_obj_t *buttonPreHeat, *buttonExtrusion, *buttonMove, *buttonHome, *buttonLevel; - lv_obj_t *buttonFilament; - lv_obj_t *buttonBack; - - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != TOOL_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = TOOL_UI; - } - disp_state = TOOL_UI; - - scr = lv_obj_create(NULL, NULL); - - //static lv_style_t tool_style; - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); - lv_label_set_text(title, creat_title_text()); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - // Create image buttons - buttonPreHeat = lv_imgbtn_create(scr, NULL); - buttonExtrusion = lv_imgbtn_create(scr, NULL); - buttonMove = lv_imgbtn_create(scr, NULL); - buttonHome = lv_imgbtn_create(scr, NULL); - buttonLevel = lv_imgbtn_create(scr, NULL); - buttonFilament = lv_imgbtn_create(scr, NULL); - //buttonMore = lv_imgbtn_create(scr, NULL); - buttonBack = lv_imgbtn_create(scr, NULL); - - lv_obj_set_event_cb_mks(buttonPreHeat, event_handler, ID_T_PRE_HEAT, NULL, 0); - lv_imgbtn_set_src(buttonPreHeat, LV_BTN_STATE_REL, "F:/bmp_preHeat.bin"); - lv_imgbtn_set_src(buttonPreHeat, LV_BTN_STATE_PR, "F:/bmp_preHeat.bin"); - lv_imgbtn_set_style(buttonPreHeat, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonPreHeat, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonExtrusion, event_handler, ID_T_EXTRUCT, NULL, 0); - lv_imgbtn_set_src(buttonExtrusion, LV_BTN_STATE_REL, "F:/bmp_extruct.bin"); - lv_imgbtn_set_src(buttonExtrusion, LV_BTN_STATE_PR, "F:/bmp_extruct.bin"); - lv_imgbtn_set_style(buttonExtrusion, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonExtrusion, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonMove, event_handler, ID_T_MOV, NULL, 0); - lv_imgbtn_set_src(buttonMove, LV_BTN_STATE_REL, "F:/bmp_mov.bin"); - lv_imgbtn_set_src(buttonMove, LV_BTN_STATE_PR, "F:/bmp_mov.bin"); - lv_imgbtn_set_style(buttonMove, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonMove, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonHome, event_handler, ID_T_HOME, NULL, 0); - lv_imgbtn_set_src(buttonHome, LV_BTN_STATE_REL, "F:/bmp_zero.bin"); - lv_imgbtn_set_src(buttonHome, LV_BTN_STATE_PR, "F:/bmp_zero.bin"); - lv_imgbtn_set_style(buttonHome, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonHome, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonLevel, event_handler, ID_T_LEVELING, NULL, 0); - lv_imgbtn_set_src(buttonLevel, LV_BTN_STATE_REL, "F:/bmp_leveling.bin"); - lv_imgbtn_set_src(buttonLevel, LV_BTN_STATE_PR, "F:/bmp_leveling.bin"); - lv_imgbtn_set_style(buttonLevel, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonLevel, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonFilament, event_handler,ID_T_FILAMENT,NULL,0); - lv_imgbtn_set_src(buttonFilament, LV_BTN_STATE_REL, "F:/bmp_filamentchange.bin"); - lv_imgbtn_set_src(buttonFilament, LV_BTN_STATE_PR, "F:/bmp_filamentchange.bin"); - lv_imgbtn_set_style(buttonFilament, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonFilament, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_T_RETURN, NULL, 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_return.bin"); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_return.bin"); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_pos(buttonPreHeat, INTERVAL_V, titleHeight); - lv_obj_set_pos(buttonExtrusion, BTN_X_PIXEL + INTERVAL_V * 2, titleHeight); - lv_obj_set_pos(buttonMove, BTN_X_PIXEL * 2 + INTERVAL_V * 3, titleHeight); - lv_obj_set_pos(buttonHome, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight); - lv_obj_set_pos(buttonLevel, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - lv_obj_set_pos(buttonFilament,BTN_X_PIXEL+INTERVAL_V*2,BTN_Y_PIXEL+INTERVAL_H+titleHeight); - //lv_obj_set_pos(buttonMore,BTN_X_PIXEL*2+INTERVAL_V*3, BTN_Y_PIXEL+INTERVAL_H+titleHeight); - lv_obj_set_pos(buttonBack, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - - // Create labels on the image buttons - lv_btn_set_layout(buttonPreHeat, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonExtrusion, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonMove, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonHome, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonLevel, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonFilament, LV_LAYOUT_OFF); - //lv_btn_set_layout(buttonMore, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - - lv_obj_t *labelPreHeat = lv_label_create(buttonPreHeat, NULL); - lv_obj_t *labelExtrusion = lv_label_create(buttonExtrusion, NULL); - lv_obj_t *label_Move = lv_label_create(buttonMove, NULL); - lv_obj_t *label_Home = lv_label_create(buttonHome, NULL); - lv_obj_t *label_Level = lv_label_create(buttonLevel, NULL); - lv_obj_t *label_Filament = lv_label_create(buttonFilament, NULL); - //lv_obj_t *label_More = lv_label_create(buttonMore, NULL); - lv_obj_t *label_Back = lv_label_create(buttonBack, NULL); - - if (gCfgItems.multiple_language != 0) { - lv_label_set_text(labelPreHeat, tool_menu.preheat); - lv_obj_align(labelPreHeat, buttonPreHeat, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(labelExtrusion, tool_menu.extrude); - lv_obj_align(labelExtrusion, buttonExtrusion, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_Move, tool_menu.move); - lv_obj_align(label_Move, buttonMove, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_Home, tool_menu.home); - lv_obj_align(label_Home, buttonHome, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_Level, tool_menu.TERN(AUTO_BED_LEVELING_BILINEAR, autoleveling, leveling)); - lv_obj_align(label_Level, buttonLevel, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_Filament, tool_menu.filament); - lv_obj_align(label_Filament, buttonFilament, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - //lv_label_set_text(label_More, tool_menu.more); - //lv_obj_align(label_More, buttonMore, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonPreHeat); - lv_group_add_obj(g, buttonExtrusion); - lv_group_add_obj(g, buttonMove); - lv_group_add_obj(g, buttonHome); - lv_group_add_obj(g, buttonLevel); - lv_group_add_obj(g, buttonFilament); - lv_group_add_obj(g, buttonBack); - } - #endif -} - -void lv_clear_tool() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_ui.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_ui.cpp deleted file mode 100644 index d600b09a5f16..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_ui.cpp +++ /dev/null @@ -1,1631 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "SPI_TFT.h" - -#include "tft_lvgl_configuration.h" - -#include "pic_manager.h" - -#include "draw_ui.h" -#include "mks_hardware_test.h" - -#include - -#include "../../../../MarlinCore.h" -#include "../../../../sd/cardreader.h" -#include "../../../../module/motion.h" -#include "../../../../module/planner.h" - -#if ENABLED(POWER_LOSS_RECOVERY) - #include "../../../../feature/powerloss.h" -#endif - -#if ENABLED(PARK_HEAD_ON_PAUSE) - #include "../../../../feature/pause.h" -#endif - -CFG_ITMES gCfgItems; -UI_CFG uiCfg; -DISP_STATE_STACK disp_state_stack; -DISP_STATE disp_state = MAIN_UI; -DISP_STATE last_disp_state; -PRINT_TIME print_time; -num_key_value_state value; -keyboard_value_state keyboard_value; - -uint32_t To_pre_view; -uint8_t gcode_preview_over; -uint8_t flash_preview_begin; -uint8_t default_preview_flg; -uint32_t size = 809; -uint16_t row; -uint8_t temperature_change_frequency; -uint8_t printing_rate_update_flag; - -extern uint8_t once_flag; -extern uint8_t sel_id; -extern uint8_t public_buf[512]; -extern uint8_t bmp_public_buf[17 * 1024]; - -extern void LCD_IO_WriteData(uint16_t RegValue); - -static const char custom_gcode_command[][100] = { - "G28\nG29\nM500", - "G28", - "G28", - "G28", - "G28" -}; - -lv_point_t line_points[4][2] = { - {{PARA_UI_POS_X, PARA_UI_POS_Y + PARA_UI_SIZE_Y}, {TFT_WIDTH, PARA_UI_POS_Y + PARA_UI_SIZE_Y}}, - {{PARA_UI_POS_X, PARA_UI_POS_Y*2 + PARA_UI_SIZE_Y}, {TFT_WIDTH, PARA_UI_POS_Y*2 + PARA_UI_SIZE_Y}}, - {{PARA_UI_POS_X, PARA_UI_POS_Y*3 + PARA_UI_SIZE_Y}, {TFT_WIDTH, PARA_UI_POS_Y*3 + PARA_UI_SIZE_Y}}, - {{PARA_UI_POS_X, PARA_UI_POS_Y*4 + PARA_UI_SIZE_Y}, {TFT_WIDTH, PARA_UI_POS_Y*4 + PARA_UI_SIZE_Y}} -}; -void gCfgItems_init() { - gCfgItems.multiple_language = MULTI_LANGUAGE_ENABLE; - #if 1 // LCD_LANGUAGE == en - gCfgItems.language = LANG_ENGLISH; - #elif LCD_LANGUAGE == zh_CN - gCfgItems.language = LANG_SIMPLE_CHINESE; - #elif LCD_LANGUAGE == zh_TW - gCfgItems.language = LANG_COMPLEX_CHINESE; - #elif LCD_LANGUAGE == jp_kana - gCfgItems.language = LANG_JAPAN; - #elif LCD_LANGUAGE == de - gCfgItems.language = LANG_GERMAN; - #elif LCD_LANGUAGE == fr - gCfgItems.language = LANG_FRENCH; - #elif LCD_LANGUAGE == ru - gCfgItems.language = LANG_RUSSIAN; - #elif LCD_LANGUAGE == ko_KR - gCfgItems.language = LANG_KOREAN; - #elif LCD_LANGUAGE == tr - gCfgItems.language = LANG_TURKISH; - #elif LCD_LANGUAGE == es - gCfgItems.language = LANG_SPANISH; - #elif LCD_LANGUAGE == el - gCfgItems.language = LANG_GREEK; - #elif LCD_LANGUAGE == it - gCfgItems.language = LANG_ITALY; - #elif LCD_LANGUAGE == pt - gCfgItems.language = LANG_PORTUGUESE; - #endif - gCfgItems.leveling_mode = 0; - gCfgItems.from_flash_pic = 0; - gCfgItems.curFilesize = 0; - gCfgItems.finish_power_off = 0; - gCfgItems.pause_reprint = 0; - gCfgItems.pausePosX = -1; - gCfgItems.pausePosY = -1; - gCfgItems.pausePosZ = 5; - gCfgItems.levelingPos[0][0] = X_MIN_POS + 30; - gCfgItems.levelingPos[0][1] = Y_MIN_POS + 30; - gCfgItems.levelingPos[1][0] = X_MAX_POS - 30; - gCfgItems.levelingPos[1][1] = Y_MIN_POS + 30; - gCfgItems.levelingPos[2][0] = X_MAX_POS - 30; - gCfgItems.levelingPos[2][1] = Y_MAX_POS - 30; - gCfgItems.levelingPos[3][0] = X_MIN_POS + 30; - gCfgItems.levelingPos[3][1] = Y_MAX_POS - 30; - gCfgItems.levelingPos[4][0] = X_BED_SIZE / 2; - gCfgItems.levelingPos[4][1] = Y_BED_SIZE / 2; - gCfgItems.cloud_enable = true; - #if ENABLED(USE_WIFI_FUNCTION) - gCfgItems.wifi_mode_sel = STA_MODEL; - gCfgItems.fileSysType = FILE_SYS_SD; - gCfgItems.wifi_type = ESP_WIFI; - #endif - gCfgItems.filamentchange_load_length = 200; - gCfgItems.filamentchange_load_speed = 1000; - gCfgItems.filamentchange_unload_length = 200; - gCfgItems.filamentchange_unload_speed = 1000; - gCfgItems.filament_limit_temper = 200; - - gCfgItems.encoder_enable = true; - - W25QXX.SPI_FLASH_BufferRead((uint8_t *)&gCfgItems.spi_flash_flag, VAR_INF_ADDR, sizeof(gCfgItems.spi_flash_flag)); - if (gCfgItems.spi_flash_flag == FLASH_INF_VALID_FLAG) { - W25QXX.SPI_FLASH_BufferRead((uint8_t *)&gCfgItems, VAR_INF_ADDR, sizeof(gCfgItems)); - } - else { - gCfgItems.spi_flash_flag = FLASH_INF_VALID_FLAG; - W25QXX.SPI_FLASH_SectorErase(VAR_INF_ADDR); - W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&gCfgItems, VAR_INF_ADDR, sizeof(gCfgItems)); - //init gcode command - W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&custom_gcode_command[0], AUTO_LEVELING_COMMAND_ADDR, 100); - W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&custom_gcode_command[1], OTHERS_COMMAND_ADDR_1, 100); - W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&custom_gcode_command[2], OTHERS_COMMAND_ADDR_2, 100); - W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&custom_gcode_command[3], OTHERS_COMMAND_ADDR_3, 100); - W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&custom_gcode_command[4], OTHERS_COMMAND_ADDR_4, 100); - } - - const byte rot = (TFT_ROTATION & TFT_ROTATE_180) ? 0xEE : 0x00; - if (gCfgItems.disp_rotation_180 != rot) { - gCfgItems.disp_rotation_180 = rot; - update_spi_flash(); - } - - uiCfg.F[0] = 'N'; - uiCfg.F[1] = 'A'; - uiCfg.F[2] = 'N'; - uiCfg.F[3] = 'O'; - W25QXX.SPI_FLASH_BlockErase(REFLSHE_FLGA_ADD + 32 - 64*1024); - W25QXX.SPI_FLASH_BufferWrite(uiCfg.F,REFLSHE_FLGA_ADD,4); -} - -void ui_cfg_init() { - uiCfg.curTempType = 0; - uiCfg.curSprayerChoose = 0; - uiCfg.stepHeat = 10; - uiCfg.leveling_first_time = 0; - uiCfg.para_ui_page = 0; - uiCfg.extruStep = 5; - uiCfg.extruSpeed = 10; - uiCfg.move_dist = 1; - uiCfg.moveSpeed = 3000; - uiCfg.stepPrintSpeed = 10; - uiCfg.command_send = 0; - uiCfg.dialogType = 0; - uiCfg.filament_heat_completed_load = 0; - uiCfg.filament_rate = 0; - uiCfg.filament_loading_completed = 0; - uiCfg.filament_unloading_completed = 0; - uiCfg.filament_loading_time_flg = 0; - uiCfg.filament_loading_time_cnt = 0; - uiCfg.filament_unloading_time_flg = 0; - uiCfg.filament_unloading_time_cnt = 0; - - #if ENABLED(USE_WIFI_FUNCTION) - memset(&wifiPara, 0, sizeof(wifiPara)); - memset(&ipPara, 0, sizeof(ipPara)); - strcpy(wifiPara.ap_name, WIFI_AP_NAME); - strcpy(wifiPara.keyCode, WIFI_KEY_CODE); - //client - strcpy(ipPara.ip_addr, IP_ADDR); - strcpy(ipPara.mask, IP_MASK); - strcpy(ipPara.gate, IP_GATE); - strcpy(ipPara.dns, IP_DNS); - - ipPara.dhcp_flag = IP_DHCP_FLAG; - - //AP - strcpy(ipPara.dhcpd_ip, AP_IP_ADDR); - strcpy(ipPara.dhcpd_mask, AP_IP_MASK); - strcpy(ipPara.dhcpd_gate, AP_IP_GATE); - strcpy(ipPara.dhcpd_dns, AP_IP_DNS); - strcpy(ipPara.start_ip_addr, IP_START_IP); - strcpy(ipPara.end_ip_addr, IP_END_IP); - - ipPara.dhcpd_flag = AP_IP_DHCP_FLAG; - - strcpy((char*)uiCfg.cloud_hostUrl, "baizhongyun.cn"); - uiCfg.cloud_port = 10086; - #endif - - uiCfg.filament_loading_time = (uint32_t)((gCfgItems.filamentchange_load_length * 60.0 / gCfgItems.filamentchange_load_speed) + 0.5); - uiCfg.filament_unloading_time = (uint32_t)((gCfgItems.filamentchange_unload_length * 60.0 / gCfgItems.filamentchange_unload_speed) + 0.5); -} - -void update_spi_flash() { - uint8_t command_buf[512]; - - W25QXX.init(SPI_QUARTER_SPEED); - //read back the gcode command befor erase spi flash - W25QXX.SPI_FLASH_BufferRead((uint8_t *)&command_buf, GCODE_COMMAND_ADDR, sizeof(command_buf)); - W25QXX.SPI_FLASH_SectorErase(VAR_INF_ADDR); - W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&gCfgItems, VAR_INF_ADDR, sizeof(gCfgItems)); - W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&command_buf, GCODE_COMMAND_ADDR, sizeof(command_buf)); -} - -void update_gcode_command(int addr,uint8_t *s) { - uint8_t command_buf[512]; - - W25QXX.init(SPI_QUARTER_SPEED); - //read back the gcode command befor erase spi flash - W25QXX.SPI_FLASH_BufferRead((uint8_t *)&command_buf, GCODE_COMMAND_ADDR, sizeof(command_buf)); - W25QXX.SPI_FLASH_SectorErase(VAR_INF_ADDR); - W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&gCfgItems, VAR_INF_ADDR, sizeof(gCfgItems)); - switch (addr) { - case AUTO_LEVELING_COMMAND_ADDR: memcpy(&command_buf[0*100], s, 100); break; - case OTHERS_COMMAND_ADDR_1: memcpy(&command_buf[1*100], s, 100); break; - case OTHERS_COMMAND_ADDR_2: memcpy(&command_buf[2*100], s, 100); break; - case OTHERS_COMMAND_ADDR_3: memcpy(&command_buf[3*100], s, 100); break; - case OTHERS_COMMAND_ADDR_4: memcpy(&command_buf[4*100], s, 100); break; - default: break; - } - W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&command_buf, GCODE_COMMAND_ADDR, sizeof(command_buf)); -} - -void get_gcode_command(int addr,uint8_t *d) { - W25QXX.init(SPI_QUARTER_SPEED); - W25QXX.SPI_FLASH_BufferRead((uint8_t *)d, addr, 100); -} - -lv_style_t tft_style_scr; -lv_style_t tft_style_label_pre; -lv_style_t tft_style_label_rel; -lv_style_t style_line; -lv_style_t style_para_value_pre; -lv_style_t style_para_value_rel; - -lv_style_t style_num_key_pre; -lv_style_t style_num_key_rel; - -lv_style_t style_num_text; -lv_style_t style_sel_text; - -lv_style_t style_para_value; -lv_style_t style_para_back; - -lv_style_t lv_bar_style_indic; - -void tft_style_init() { - lv_style_copy(&tft_style_scr, &lv_style_scr); - tft_style_scr.body.main_color = LV_COLOR_BACKGROUND; - tft_style_scr.body.grad_color = LV_COLOR_BACKGROUND; - tft_style_scr.text.color = LV_COLOR_TEXT; - tft_style_scr.text.sel_color = LV_COLOR_TEXT; - tft_style_scr.line.width = 0; - tft_style_scr.text.letter_space = 0; - tft_style_scr.text.line_space = 0; - - lv_style_copy(&tft_style_label_pre, &lv_style_scr); - lv_style_copy(&tft_style_label_rel, &lv_style_scr); - tft_style_label_pre.body.main_color = LV_COLOR_BACKGROUND; - tft_style_label_pre.body.grad_color = LV_COLOR_BACKGROUND; - tft_style_label_pre.text.color = LV_COLOR_TEXT; - tft_style_label_pre.text.sel_color = LV_COLOR_TEXT; - tft_style_label_rel.body.main_color = LV_COLOR_BACKGROUND; - tft_style_label_rel.body.grad_color = LV_COLOR_BACKGROUND; - tft_style_label_rel.text.color = LV_COLOR_TEXT; - tft_style_label_rel.text.sel_color = LV_COLOR_TEXT; - tft_style_label_pre.text.font = TERN(HAS_SPI_FLASH_FONT, &gb2312_puhui32, LV_FONT_DEFAULT); - tft_style_label_rel.text.font = TERN(HAS_SPI_FLASH_FONT, &gb2312_puhui32, LV_FONT_DEFAULT); - tft_style_label_pre.line.width = 0; - tft_style_label_rel.line.width = 0; - tft_style_label_pre.text.letter_space = 0; - tft_style_label_rel.text.letter_space = 0; - tft_style_label_pre.text.line_space = -5; - tft_style_label_rel.text.line_space = -5; - - lv_style_copy(&style_para_value_pre, &lv_style_scr); - lv_style_copy(&style_para_value_rel, &lv_style_scr); - style_para_value_pre.body.main_color = LV_COLOR_BACKGROUND; - style_para_value_pre.body.grad_color = LV_COLOR_BACKGROUND; - style_para_value_pre.text.color = LV_COLOR_TEXT; - style_para_value_pre.text.sel_color = LV_COLOR_TEXT; - style_para_value_rel.body.main_color = LV_COLOR_BACKGROUND; - style_para_value_rel.body.grad_color = LV_COLOR_BACKGROUND; - style_para_value_rel.text.color = LV_COLOR_BLACK; - style_para_value_rel.text.sel_color = LV_COLOR_BLACK; - style_para_value_pre.text.font = TERN(HAS_SPI_FLASH_FONT, &gb2312_puhui32, LV_FONT_DEFAULT); - style_para_value_rel.text.font = TERN(HAS_SPI_FLASH_FONT, &gb2312_puhui32, LV_FONT_DEFAULT); - style_para_value_pre.line.width = 0; - style_para_value_rel.line.width = 0; - style_para_value_pre.text.letter_space = 0; - style_para_value_rel.text.letter_space = 0; - style_para_value_pre.text.line_space = -5; - style_para_value_rel.text.line_space = -5; - - lv_style_copy(&style_num_key_pre, &lv_style_scr); - lv_style_copy(&style_num_key_rel, &lv_style_scr); - style_num_key_pre.body.main_color = LV_COLOR_KEY_BACKGROUND; - style_num_key_pre.body.grad_color = LV_COLOR_KEY_BACKGROUND; - style_num_key_pre.text.color = LV_COLOR_TEXT; - style_num_key_pre.text.sel_color = LV_COLOR_TEXT; - style_num_key_rel.body.main_color = LV_COLOR_KEY_BACKGROUND; - style_num_key_rel.body.grad_color = LV_COLOR_KEY_BACKGROUND; - style_num_key_rel.text.color = LV_COLOR_TEXT; - style_num_key_rel.text.sel_color = LV_COLOR_TEXT; - #if HAS_SPI_FLASH_FONT - style_num_key_pre.text.font = &gb2312_puhui32; - style_num_key_rel.text.font = &gb2312_puhui32; - #else - style_num_key_pre.text.font = LV_FONT_DEFAULT; - style_num_key_rel.text.font = LV_FONT_DEFAULT; - #endif - - style_num_key_pre.line.width = 0; - style_num_key_rel.line.width = 0; - style_num_key_pre.text.letter_space = 0; - style_num_key_rel.text.letter_space = 0; - style_num_key_pre.text.line_space = -5; - style_num_key_rel.text.line_space = -5; - lv_style_copy(&style_num_text, &lv_style_scr); - - style_num_text.body.main_color = LV_COLOR_WHITE; - style_num_text.body.grad_color = LV_COLOR_WHITE; - style_num_text.text.color = LV_COLOR_BLACK; - style_num_text.text.sel_color = LV_COLOR_BLACK; - style_num_text.text.font = TERN(HAS_SPI_FLASH_FONT, &gb2312_puhui32, LV_FONT_DEFAULT); - style_num_text.line.width = 0; - style_num_text.text.letter_space = 0; - style_num_text.text.line_space = -5; - - lv_style_copy(&style_sel_text, &lv_style_scr); - style_sel_text.body.main_color = LV_COLOR_BACKGROUND; - style_sel_text.body.grad_color = LV_COLOR_BACKGROUND; - style_sel_text.text.color = LV_COLOR_YELLOW; - style_sel_text.text.sel_color = LV_COLOR_YELLOW; - style_sel_text.text.font = &gb2312_puhui32; - style_sel_text.line.width = 0; - style_sel_text.text.letter_space = 0; - style_sel_text.text.line_space = -5; - lv_style_copy(&style_line, &lv_style_plain); - style_line.line.color = LV_COLOR_MAKE(0x49, 0x54, 0xFF); - style_line.line.width = 1; - style_line.line.rounded = 1; - - lv_style_copy(&style_para_value, &lv_style_plain); - style_para_value.body.border.color = LV_COLOR_BACKGROUND; - style_para_value.body.border.width = 1; - style_para_value.body.main_color = LV_COLOR_WHITE; - style_para_value.body.grad_color = LV_COLOR_WHITE; - style_para_value.body.shadow.width = 0; - style_para_value.body.radius = 3; - style_para_value.text.color = LV_COLOR_BLACK; - style_para_value.text.font = &TERN(HAS_SPI_FLASH_FONT, gb2312_puhui32, lv_font_roboto_22); - - lv_style_copy(&style_para_back, &lv_style_plain); - style_para_back.body.border.color = LV_COLOR_BACKGROUND; - style_para_back.body.border.width = 1; - style_para_back.body.main_color = TFT_LV_PARA_BACK_BODY_COLOR; - style_para_back.body.grad_color = TFT_LV_PARA_BACK_BODY_COLOR; - style_para_back.body.shadow.width = 0; - style_para_back.body.radius = 3; - style_para_back.text.color = LV_COLOR_WHITE; - style_para_back.text.font = &TERN(HAS_SPI_FLASH_FONT, gb2312_puhui32, lv_font_roboto_22); - - lv_style_copy(&lv_bar_style_indic, &lv_style_pretty_color); - lv_bar_style_indic.text.color = lv_color_hex3(0xADF); - lv_bar_style_indic.image.color = lv_color_hex3(0xADF); - lv_bar_style_indic.line.color = lv_color_hex3(0xADF); - lv_bar_style_indic.body.main_color = lv_color_hex3(0xADF); - lv_bar_style_indic.body.grad_color = lv_color_hex3(0xADF); - lv_bar_style_indic.body.border.color = lv_color_hex3(0xADF); - -} - -#define MAX_TITLE_LEN 28 - -char public_buf_m[100] = {0}; -char public_buf_l[30]; - -void titleText_cat(char *str, int strSize, char *addPart) { - if (str == 0 || addPart == 0) return; - if ((int)(strlen(str) + strlen(addPart)) >= strSize) return; - strcat(str, addPart); -} - -char *getDispText(int index) { - - ZERO(public_buf_l); - - switch (disp_state_stack._disp_state[index]) { - case PRINT_READY_UI: - strcpy(public_buf_l, main_menu.title); - break; - case PRINT_FILE_UI: - strcpy(public_buf_l, file_menu.title); - break; - case PRINTING_UI: - if (disp_state_stack._disp_state[disp_state_stack._disp_index] == PRINTING_UI - #ifndef TFT35 - || disp_state_stack._disp_state[disp_state_stack._disp_index] == OPERATE_UI - || disp_state_stack._disp_state[disp_state_stack._disp_index] == PAUSE_UI - #endif - ) strcpy(public_buf_l, common_menu.print_special_title); - else strcpy(public_buf_l, printing_menu.title); - break; - case MOVE_MOTOR_UI: - strcpy(public_buf_l, move_menu.title); - break; - case OPERATE_UI: - if (disp_state_stack._disp_state[disp_state_stack._disp_index] == PRINTING_UI - #ifndef TFT35 - || disp_state_stack._disp_state[disp_state_stack._disp_index] == OPERATE_UI - || disp_state_stack._disp_state[disp_state_stack._disp_index] == PAUSE_UI - #endif - ) strcpy(public_buf_l, common_menu.operate_special_title); - else strcpy(public_buf_l, operation_menu.title); - break; - - case PAUSE_UI: - if (disp_state_stack._disp_state[disp_state_stack._disp_index] == PRINTING_UI - || disp_state_stack._disp_state[disp_state_stack._disp_index] == OPERATE_UI - || disp_state_stack._disp_state[disp_state_stack._disp_index] == PAUSE_UI - ) strcpy(public_buf_l, common_menu.pause_special_title); - else strcpy(public_buf_l, pause_menu.title); - break; - - case EXTRUSION_UI: - strcpy(public_buf_l, extrude_menu.title); - break; - case CHANGE_SPEED_UI: - strcpy(public_buf_l, speed_menu.title); - break; - case FAN_UI: - strcpy(public_buf_l, fan_menu.title); - break; - case PRE_HEAT_UI: - if ((disp_state_stack._disp_state[disp_state_stack._disp_index - 1] == OPERATE_UI)) - strcpy(public_buf_l, preheat_menu.adjust_title); - else strcpy(public_buf_l, preheat_menu.title); - break; - case SET_UI: - strcpy(public_buf_l, set_menu.title); - break; - case ZERO_UI: - strcpy(public_buf_l, home_menu.title); - break; - case SPRAYER_UI: break; - case MACHINE_UI: break; - case LANGUAGE_UI: - strcpy(public_buf_l, language_menu.title); - break; - case ABOUT_UI: - strcpy(public_buf_l, about_menu.title); - break; - case LOG_UI: break; - case DISK_UI: - strcpy(public_buf_l, filesys_menu.title); - break; - case DIALOG_UI: - strcpy(public_buf_l, common_menu.dialog_confirm_title); - break; - case WIFI_UI: - strcpy(public_buf_l, wifi_menu.title); - break; - case MORE_UI: - case PRINT_MORE_UI: - strcpy(public_buf_l, more_menu.title); - break; - case FILAMENTCHANGE_UI: - strcpy(public_buf_l, filament_menu.title); - break; - case LEVELING_UI: - case MESHLEVELING_UI: - strcpy(public_buf_l, leveling_menu.title); - break; - case BIND_UI: - strcpy(public_buf_l, cloud_menu.title); - break; - case TOOL_UI: - strcpy(public_buf_l, tool_menu.title); - break; - case WIFI_LIST_UI: - #if ENABLED(USE_WIFI_FUNCTION) - strcpy(public_buf_l, list_menu.title); - break; - #endif - case MACHINE_PARA_UI: - strcpy(public_buf_l, MachinePara_menu.title); - break; - case BABY_STEP_UI: - strcpy(public_buf_l, operation_menu.babystep); - break; - case EEPROM_SETTINGS_UI: - strcpy(public_buf_l, eeprom_menu.title); - break; - default: break; - } - - return public_buf_l; -} - -char *creat_title_text() { - int index = 0; - char *tmpText = 0; - char tmpCurFileStr[20]; - - ZERO(tmpCurFileStr); - - #if _LFN_UNICODE - //cutFileName((TCHAR *)curFileName, 16, 16, (TCHAR *)tmpCurFileStr); - #else - cutFileName(list_file.long_name[sel_id], 16, 16, tmpCurFileStr); - #endif - - ZERO(public_buf_m); - - while (index <= disp_state_stack._disp_index) { - tmpText = getDispText(index); - if ((*tmpText == 0) || (tmpText == 0)) { - index++; - continue; - } - - titleText_cat(public_buf_m, sizeof(public_buf_m), tmpText); - if (index < disp_state_stack._disp_index) titleText_cat(public_buf_m, sizeof(public_buf_m), (char *)">"); - - index++; - } - - if (disp_state_stack._disp_state[disp_state_stack._disp_index] == PRINTING_UI - /*|| disp_state_stack._disp_state[disp_state_stack._disp_index] == OPERATE_UI - || disp_state_stack._disp_state[disp_state_stack._disp_index] == PAUSE_UI*/ - ) { - titleText_cat(public_buf_m, sizeof(public_buf_m), (char *)":"); - titleText_cat(public_buf_m, sizeof(public_buf_m), tmpCurFileStr); - } - - if (strlen(public_buf_m) > MAX_TITLE_LEN) { - ZERO(public_buf_m); - tmpText = getDispText(0); - if (*tmpText != 0) { - titleText_cat(public_buf_m, sizeof(public_buf_m), tmpText); - titleText_cat(public_buf_m, sizeof(public_buf_m), (char *)">...>"); - tmpText = getDispText(disp_state_stack._disp_index); - if (*tmpText != 0) titleText_cat(public_buf_m, sizeof(public_buf_m), tmpText); - } - } - - return public_buf_m; -} - -#if HAS_GCODE_PREVIEW - - uint32_t gPicturePreviewStart = 0; - - void preview_gcode_prehandle(char *path) { - #if ENABLED(SDSUPPORT) - //uint8_t re; - //uint32_t read; - uint32_t pre_read_cnt = 0; - uint32_t *p1; - char *cur_name; - - gPicturePreviewStart = 0; - cur_name = strrchr(path, '/'); - card.openFileRead(cur_name); - card.read(public_buf, 512); - p1 = (uint32_t *)strstr((char *)public_buf, ";simage:"); - - if (p1) { - pre_read_cnt = (uint32_t)p1 - (uint32_t)((uint32_t *)(&public_buf[0])); - - To_pre_view = pre_read_cnt; - gcode_preview_over = 1; - gCfgItems.from_flash_pic = 1; - update_spi_flash(); - } - else { - gcode_preview_over = 0; - default_preview_flg = 1; - gCfgItems.from_flash_pic = 0; - update_spi_flash(); - } - card.closefile(); - #endif - } - - #if 1 - - void gcode_preview(char *path, int xpos_pixel, int ypos_pixel) { - #if ENABLED(SDSUPPORT) - //uint8_t ress; - //uint32_t write; - volatile uint32_t i, j; - volatile uint16_t *p_index; - //int res; - char *cur_name; - - cur_name = strrchr(path, '/'); - card.openFileRead(cur_name); - - if (gPicturePreviewStart <= 0) { - while (1) { - uint32_t br = card.read(public_buf, 400); - uint32_t* p1 = (uint32_t *)strstr((char *)public_buf, ";gimage:"); - if (p1) { - gPicturePreviewStart += (uint32_t)p1 - (uint32_t)((uint32_t *)(&public_buf[0])); - break; - } - else { - gPicturePreviewStart += br; - } - if (br < 400) break; - } - } - - card.setIndex((gPicturePreviewStart + To_pre_view) + size * row + 8); - SPI_TFT.setWindow(xpos_pixel, ypos_pixel + row, 200, 1); - - j = i = 0; - - while (1) { - card.read(public_buf, 400); - for (i = 0; i < 400;) { - bmp_public_buf[j] = ascii2dec_test((char*)&public_buf[i]) << 4 | ascii2dec_test((char*)&public_buf[i + 1]); - i += 2; - j++; - } - if (j >= 400) break; - } - for (i = 0; i < 400; i += 2) { - p_index = (uint16_t *)(&bmp_public_buf[i]); - if (*p_index == 0x0000) *p_index = LV_COLOR_BACKGROUND.full; - } - SPI_TFT.tftio.WriteSequence((uint16_t*)bmp_public_buf, 200); - #if HAS_BAK_VIEW_IN_FLASH - W25QXX.init(SPI_QUARTER_SPEED); - if (row < 20) W25QXX.SPI_FLASH_SectorErase(BAK_VIEW_ADDR_TFT35 + row * 4096); - W25QXX.SPI_FLASH_BufferWrite(bmp_public_buf, BAK_VIEW_ADDR_TFT35 + row * 400, 400); - #endif - row++; - if (row >= 200) { - size = 809; - row = 0; - - gcode_preview_over = 0; - //flash_preview_begin = 1; - - card.closefile(); - - /* - if (gCurFileState.file_open_flag != 0xAA) { - reset_file_info(); - res = f_open(file, curFileName, FA_OPEN_EXISTING | FA_READ); - if (res == FR_OK) { - f_lseek(file,PREVIEW_SIZE+To_pre_view); - gCurFileState.file_open_flag = 0xAA; - //bakup_file_path((uint8_t *)curFileName, strlen(curFileName)); - srcfp = file; - mksReprint.mks_printer_state = MKS_WORKING; - once_flag = 0; - } - } - */ - char *cur_name; - - cur_name = strrchr(list_file.file_name[sel_id], '/'); - - SdFile file; - SdFile *curDir; - card.endFilePrint(); - const char * const fname = card.diveToFile(true, 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()) { - feedrate_percentage = 100; - //saved_feedrate_percentage = feedrate_percentage; - planner.flow_percentage[0] = 100; - planner.e_factor[0] = planner.flow_percentage[0] * 0.01; - #if HAS_MULTI_EXTRUDER - planner.flow_percentage[1] = 100; - planner.e_factor[1] = planner.flow_percentage[1] * 0.01; - #endif - card.startFileprint(); - TERN_(POWER_LOSS_RECOVERY, recovery.prepare()); - once_flag = 0; - } - return; - } - card.closefile(); - #endif // SDSUPPORT - } - - #else // if 1 - - void gcode_preview(char *path, int xpos_pixel, int ypos_pixel) { - #if ENABLED(SDSUPPORT) - //uint8_t ress; - //uint32_t write; - volatile uint32_t i, j; - volatile uint16_t *p_index; - //int res; - char *cur_name; - uint16_t Color; - - cur_name = strrchr(path, '/'); - card.openFileRead(cur_name); - - card.setIndex((PREVIEW_LITTLE_PIC_SIZE + To_pre_view) + size * row + 8); - #if ENABLED(TFT_LVGL_UI_SPI) - SPI_TFT.setWindow(xpos_pixel, ypos_pixel + row, 200, 1); - #else - LCD_setWindowArea(xpos_pixel, ypos_pixel + row, 200, 1); - LCD_WriteRAM_Prepare(); - #endif - - j = 0; - i = 0; - - while (1) { - card.read(public_buf, 400); - for (i = 0; i < 400;) { - bmp_public_buf[j] = ascii2dec_test((char*)&public_buf[i]) << 4 | ascii2dec_test((char*)&public_buf[i + 1]); - i += 2; - j++; - } - - //if (i > 800) break; - //#ifdef TFT70 - // if (j > 400) { - // f_read(file, buff_pic, 1, &read); - // break; - // } - //#elif defined(TFT35) - if (j >= 400) - //f_read(file, buff_pic, 1, &read); - break; - //#endif - - } - #if ENABLED(TFT_LVGL_UI_SPI) - for (i = 0; i < 400;) { - p_index = (uint16_t *)(&bmp_public_buf[i]); - - Color = (*p_index >> 8); - *p_index = Color | ((*p_index & 0xFF) << 8); - i += 2; - if (*p_index == 0x0000) *p_index = 0xC318; - } - TFT_CS_L; - TFT_DC_H; - SPI.dmaSend(bmp_public_buf, 400, true); - TFT_CS_H; - - #else - for (i = 0; i < 400;) { - p_index = (uint16_t *)(&bmp_public_buf[i]); - if (*p_index == 0x0000) *p_index = 0x18C3; - LCD_IO_WriteData(*p_index); - i = i + 2; - } - #endif - W25QXX.init(SPI_QUARTER_SPEED); - if (row < 20) - W25QXX.SPI_FLASH_SectorErase(BAK_VIEW_ADDR_TFT35 + row * 4096); - W25QXX.SPI_FLASH_BufferWrite(bmp_public_buf, BAK_VIEW_ADDR_TFT35 + row * 400, 400); - row++; - if (row >= 200) { - size = 809; - row = 0; - - gcode_preview_over = 0; - //flash_preview_begin = 1; - - card.closefile(); - - /* - if (gCurFileState.file_open_flag != 0xAA) { - reset_file_info(); - res = f_open(file, curFileName, FA_OPEN_EXISTING | FA_READ); - if (res == FR_OK) { - f_lseek(file,PREVIEW_SIZE+To_pre_view); - gCurFileState.file_open_flag = 0xAA; - //bakup_file_path((uint8_t *)curFileName, strlen(curFileName)); - srcfp = file; - mksReprint.mks_printer_state = MKS_WORKING; - once_flag = 0; - } - } - */ - char *cur_name; - - cur_name = strrchr(list_file.file_name[sel_id], '/'); - - SdFile file; - SdFile *curDir; - card.endFilePrint(); - const char * const fname = card.diveToFile(true, 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()) { - feedrate_percentage = 100; - //saved_feedrate_percentage = feedrate_percentage; - planner.flow_percentage[0] = 100; - planner.e_factor[0] = planner.flow_percentage[0] * 0.01; - #if HAS_MULTI_EXTRUDER - planner.flow_percentage[1] = 100; - planner.e_factor[1] = planner.flow_percentage[1] * 0.01; - #endif - card.startFileprint(); - TERN_(POWER_LOSS_RECOVERY, recovery.prepare()); - once_flag = 0; - } - return; - } - card.closefile(); - #endif // SDSUPPORT - } - - #endif // if 1 - - void Draw_default_preview(int xpos_pixel, int ypos_pixel, uint8_t sel) { - int index; - int y_off = 0; - W25QXX.init(SPI_QUARTER_SPEED); - for (index = 0; index < 10; index++) { // 200*200 - #if HAS_BAK_VIEW_IN_FLASH - if (sel == 1) { - flash_view_Read(bmp_public_buf, 8000); // 20k - } - else { - default_view_Read(bmp_public_buf, DEFAULT_VIEW_MAX_SIZE / 10); // 8k - } - #else - default_view_Read(bmp_public_buf, DEFAULT_VIEW_MAX_SIZE / 10); // 8k - #endif - - SPI_TFT.setWindow(xpos_pixel, y_off * 20 + ypos_pixel, 200, 20); // 200*200 - SPI_TFT.tftio.WriteSequence((uint16_t*)(bmp_public_buf), DEFAULT_VIEW_MAX_SIZE / 20); - - y_off++; - } - W25QXX.init(SPI_QUARTER_SPEED); - } - - void disp_pre_gcode(int xpos_pixel, int ypos_pixel) { - if (gcode_preview_over == 1) gcode_preview(list_file.file_name[sel_id], xpos_pixel, ypos_pixel); - #if HAS_BAK_VIEW_IN_FLASH - if (flash_preview_begin == 1) { - flash_preview_begin = 0; - Draw_default_preview(xpos_pixel, ypos_pixel, 1); - } - #endif - #if HAS_GCODE_DEFAULT_VIEW_IN_FLASH - if (default_preview_flg == 1) { - Draw_default_preview(xpos_pixel, ypos_pixel, 0); - default_preview_flg = 0; - } - #endif - } -#endif // HAS_GCODE_PREVIEW - -void print_time_run() { - static uint8_t lastSec = 0; - - if (print_time.seconds >= 60) { - print_time.seconds = 0; - print_time.minutes++; - if (print_time.minutes >= 60) { - print_time.minutes = 0; - print_time.hours++; - } - } - if (disp_state == PRINTING_UI) { - if (lastSec != print_time.seconds) disp_print_time(); - lastSec = print_time.seconds; - } -} - -void GUI_RefreshPage() { - if ((systick_uptime_millis % 1000) == 0) temperature_change_frequency = 1; - if ((systick_uptime_millis % 3000) == 0) printing_rate_update_flag = 1; - - switch (disp_state) { - case MAIN_UI: - //lv_draw_ready_print(); - break; - case EXTRUSION_UI: - if (temperature_change_frequency == 1) { - temperature_change_frequency = 0; - disp_hotend_temp(); - } - break; - case PRE_HEAT_UI: - if (temperature_change_frequency == 1) { - temperature_change_frequency = 0; - disp_desire_temp(); - } - break; - case PRINT_READY_UI: - /* - if (gCfgItems.display_style == 2) { - if (temperature_change_frequency) { - temperature_change_frequency = 0; - disp_restro_state(); - } - } - */ - break; - - case PRINT_FILE_UI: break; - - case PRINTING_UI: - if (temperature_change_frequency) { - temperature_change_frequency = 0; - disp_ext_temp(); - disp_bed_temp(); - disp_fan_speed(); - disp_print_time(); - disp_fan_Zpos(); - } - if (printing_rate_update_flag || marlin_state == MF_SD_COMPLETE) { - printing_rate_update_flag = 0; - if (gcode_preview_over == 0) setProBarRate(); - } - break; - - case OPERATE_UI: - /* - if (temperature_change_frequency == 1) { - temperature_change_frequency = 0; - disp_temp_operate(); - } - - setProBarRateOpera(); - */ - break; - - case PAUSE_UI: - /* - if (temperature_change_frequency == 1) { - temperature_change_frequency = 0; - disp_temp_pause(); - } - */ - break; - - case FAN_UI: - if (temperature_change_frequency == 1) { - temperature_change_frequency = 0; - disp_fan_value(); - } - break; - - case MOVE_MOTOR_UI: - /* - if (mksReprint.mks_printer_state == MKS_IDLE) { - if ((z_high_count==1)&&(temper_error_flg != 1)) { - z_high_count = 0; - { - memset((char *)gCfgItems.move_z_coordinate, ' ', sizeof(gCfgItems.move_z_coordinate)); - GUI_DispStringAt((const char *)gCfgItems.move_z_coordinate, 380, TITLE_YPOS); - sprintf_P((char *)gCfgItems.move_z_coordinate, PSTR("Z: %.3f"), current_position[Z_AXIS]); - GUI_DispStringAt((const char *)gCfgItems.move_z_coordinate, 380, TITLE_YPOS); - } - } - } - */ - break; - - #if ENABLED(USE_WIFI_FUNCTION) - case WIFI_UI: - if (temperature_change_frequency == 1) { - disp_wifi_state(); - temperature_change_frequency = 0; - } - break; - #endif - - case BIND_UI: - /*refresh_bind_ui();*/ - break; - - case FILAMENTCHANGE_UI: - if (temperature_change_frequency) { - temperature_change_frequency = 0; - disp_filament_temp(); - } - break; - case DIALOG_UI: - filament_dialog_handle(); - TERN_(USE_WIFI_FUNCTION, wifi_scan_handle()); - break; - case MESHLEVELING_UI: - /*disp_zpos();*/ - break; - case HARDWARE_TEST_UI: - break; - case WIFI_LIST_UI: - #if ENABLED(USE_WIFI_FUNCTION) - if (printing_rate_update_flag == 1) { - disp_wifi_list(); - printing_rate_update_flag = 0; - } - #endif - break; - case KEY_BOARD_UI: - /*update_password_disp(); - update_join_state_disp();*/ - break; - #if ENABLED(USE_WIFI_FUNCTION) - case WIFI_TIPS_UI: - switch (wifi_tips_type) { - case TIPS_TYPE_JOINING: - if (wifi_link_state == WIFI_CONNECTED && strcmp((const char *)wifi_list.wifiConnectedName,(const char *)wifi_list.wifiName[wifi_list.nameIndex]) == 0) { - tips_disp.timer = TIPS_TIMER_STOP; - tips_disp.timer_count = 0; - - lv_clear_wifi_tips(); - wifi_tips_type = TIPS_TYPE_WIFI_CONECTED; - lv_draw_wifi_tips(); - - } - if (tips_disp.timer_count >= 30 * 1000) { - tips_disp.timer = TIPS_TIMER_STOP; - tips_disp.timer_count = 0; - lv_clear_wifi_tips(); - wifi_tips_type = TIPS_TYPE_TAILED_JOIN; - lv_draw_wifi_tips(); - } - break; - case TIPS_TYPE_TAILED_JOIN: - if (tips_disp.timer_count >= 3 * 1000) { - tips_disp.timer = TIPS_TIMER_STOP; - tips_disp.timer_count = 0; - - last_disp_state = WIFI_TIPS_UI; - lv_clear_wifi_tips(); - lv_draw_wifi_list(); - } - break; - case TIPS_TYPE_WIFI_CONECTED: - if (tips_disp.timer_count >= 3 * 1000) { - tips_disp.timer = TIPS_TIMER_STOP; - tips_disp.timer_count = 0; - - last_disp_state = WIFI_TIPS_UI; - lv_clear_wifi_tips(); - lv_draw_wifi(); - } - break; - default: break; - } - break; - #endif - - case BABY_STEP_UI: - if (temperature_change_frequency == 1) { - temperature_change_frequency = 0; - disp_z_offset_value(); - } - break; - default: break; - } - - print_time_run(); -} - -void clear_cur_ui() { - last_disp_state = disp_state_stack._disp_state[disp_state_stack._disp_index]; - - switch (disp_state_stack._disp_state[disp_state_stack._disp_index]) { - case PRINT_READY_UI: - //Get_Temperature_Flg = 0; - lv_clear_ready_print(); - break; - case PRINT_FILE_UI: - lv_clear_print_file(); - break; - case PRINTING_UI: - lv_clear_printing(); - break; - case MOVE_MOTOR_UI: - lv_clear_move_motor(); - break; - case OPERATE_UI: - lv_clear_operation(); - break; - case PAUSE_UI: - //Clear_pause(); - break; - case EXTRUSION_UI: - lv_clear_extrusion(); - break; - case PRE_HEAT_UI: - lv_clear_preHeat(); - break; - case CHANGE_SPEED_UI: - lv_clear_change_speed(); - break; - case FAN_UI: - lv_clear_fan(); - break; - case SET_UI: - lv_clear_set(); - break; - case ZERO_UI: - lv_clear_home(); - break; - case SPRAYER_UI: - //Clear_Sprayer(); - break; - case MACHINE_UI: - //Clear_Machine(); - break; - case LANGUAGE_UI: - lv_clear_language(); - break; - case ABOUT_UI: - lv_clear_about(); - break; - case LOG_UI: - //Clear_Connect(); - break; - case DISK_UI: - //Clear_Disk(); - break; - #if ENABLED(USE_WIFI_FUNCTION) - case WIFI_UI: - lv_clear_wifi(); - break; - #endif - case MORE_UI: - //Clear_more(); - break; - case FILETRANSFER_UI: - //Clear_fileTransfer(); - break; - case DIALOG_UI: - lv_clear_dialog(); - break; - case FILETRANSFERSTATE_UI: - //Clear_WifiFileTransferdialog(); - break; - case PRINT_MORE_UI: - //Clear_Printmore(); - break; - case FILAMENTCHANGE_UI: - lv_clear_filament_change(); - break; - case LEVELING_UI: - lv_clear_manualLevel(); - break; - case BIND_UI: - //Clear_Bind(); - break; - #if HAS_BED_PROBE - case NOZZLE_PROBE_OFFSET_UI: - lv_clear_auto_level_offset_settings(); - break; - #endif - case TOOL_UI: - lv_clear_tool(); - break; - case MESHLEVELING_UI: - //Clear_MeshLeveling(); - break; - case HARDWARE_TEST_UI: - //Clear_Hardwaretest(); - break; - #if ENABLED(USE_WIFI_FUNCTION) - case WIFI_LIST_UI: - lv_clear_wifi_list(); - break; - #endif - case KEY_BOARD_UI: - lv_clear_keyboard(); - break; - #if ENABLED(USE_WIFI_FUNCTION) - case WIFI_TIPS_UI: - lv_clear_wifi_tips(); - break; - #endif - case MACHINE_PARA_UI: - lv_clear_machine_para(); - break; - case MACHINE_SETTINGS_UI: - lv_clear_machine_settings(); - break; - case TEMPERATURE_SETTINGS_UI: - //Clear_TemperatureSettings(); - break; - case MOTOR_SETTINGS_UI: - lv_clear_motor_settings(); - break; - case MACHINETYPE_UI: - //Clear_MachineType(); - break; - case STROKE_UI: - //Clear_Stroke(); - break; - case HOME_DIR_UI: - //Clear_HomeDir(); - break; - case ENDSTOP_TYPE_UI: - //Clear_EndstopType(); - break; - case FILAMENT_SETTINGS_UI: - lv_clear_filament_settings(); - break; - case LEVELING_SETTIGNS_UI: - //Clear_LevelingSettings(); - break; - case LEVELING_PARA_UI: - lv_clear_level_settings(); - break; - case DELTA_LEVELING_PARA_UI: - //Clear_DeltaLevelPara(); - break; - case MANUAL_LEVELING_POSIGION_UI: - lv_clear_manual_level_pos_settings(); - break; - case MAXFEEDRATE_UI: - lv_clear_max_feedrate_settings(); - break; - case STEPS_UI: - lv_clear_step_settings(); - break; - case ACCELERATION_UI: - lv_clear_acceleration_settings(); - break; - case JERK_UI: - #if HAS_CLASSIC_JERK - lv_clear_jerk_settings(); - #endif - break; - case MOTORDIR_UI: - //Clear_MotorDir(); - break; - case HOMESPEED_UI: - //Clear_HomeSpeed(); - break; - case NOZZLE_CONFIG_UI: - //Clear_NozzleConfig(); - break; - case HOTBED_CONFIG_UI: - //Clear_HotbedConfig(); - break; - case ADVANCED_UI: - lv_clear_advance_settings(); - break; - case DOUBLE_Z_UI: - //Clear_DoubleZ(); - break; - case ENABLE_INVERT_UI: - //Clear_EnableInvert(); - break; - case NUMBER_KEY_UI: - lv_clear_number_key(); - break; - case BABY_STEP_UI: - lv_clear_baby_stepping(); - break; - case PAUSE_POS_UI: - lv_clear_pause_position(); - break; - #if HAS_TRINAMIC_CONFIG - case TMC_CURRENT_UI: - lv_clear_tmc_current_settings(); - break; - #endif - case EEPROM_SETTINGS_UI: - lv_clear_eeprom_settings(); - break; - #if HAS_STEALTHCHOP - case TMC_MODE_UI: - lv_clear_tmc_step_mode_settings(); - break; - #endif - #if ENABLED(USE_WIFI_FUNCTION) - case WIFI_SETTINGS_UI: - lv_clear_wifi_settings(); - break; - #endif - #if USE_SENSORLESS - case HOMING_SENSITIVITY_UI: - lv_clear_homing_sensitivity_settings(); - break; - #endif - #if HAS_ROTARY_ENCODER - case ENCODER_SETTINGS_UI: - lv_clear_encoder_settings(); - break; - #endif - default: break; - } - //GUI_Clear(); -} - -void draw_return_ui() { - if (disp_state_stack._disp_index > 0) { - disp_state_stack._disp_index--; - - switch (disp_state_stack._disp_state[disp_state_stack._disp_index]) { - case PRINT_READY_UI: - lv_draw_ready_print(); - break; - case PRINT_FILE_UI: - lv_draw_print_file(); - break; - case PRINTING_UI: - if (gCfgItems.from_flash_pic == 1) flash_preview_begin = 1; - else default_preview_flg = 1; - lv_draw_printing(); - break; - case MOVE_MOTOR_UI: - lv_draw_move_motor(); - break; - case OPERATE_UI: - lv_draw_operation(); - break; - - #if 1 - case PAUSE_UI: - //draw_pause(); - break; - #endif - - case EXTRUSION_UI: - lv_draw_extrusion(); - break; - case PRE_HEAT_UI: - lv_draw_preHeat(); - break; - case CHANGE_SPEED_UI: - lv_draw_change_speed(); - break; - case FAN_UI: - lv_draw_fan(); - break; - case SET_UI: - lv_draw_set(); - break; - case ZERO_UI: - lv_draw_home(); - break; - case SPRAYER_UI: - //draw_Sprayer(); - break; - case MACHINE_UI: - //draw_Machine(); - break; - case LANGUAGE_UI: - lv_draw_language(); - break; - case ABOUT_UI: - lv_draw_about(); - break; - - case CALIBRATE_UI: - //draw_calibrate(); - break; - case DISK_UI: - //draw_Disk(); - break; - #if ENABLED(USE_WIFI_FUNCTION) - case WIFI_UI: - lv_draw_wifi(); - break; - #endif - case MORE_UI: - //draw_More(); - break; - case PRINT_MORE_UI: - //draw_printmore(); - break; - case FILAMENTCHANGE_UI: - lv_draw_filament_change(); - break; - case LEVELING_UI: - lv_draw_manualLevel(); - break; - case BIND_UI: - //draw_bind(); - break; - #if HAS_BED_PROBE - case NOZZLE_PROBE_OFFSET_UI: - lv_draw_auto_level_offset_settings(); - break; - #endif - case TOOL_UI: - lv_draw_tool(); - break; - case MESHLEVELING_UI: - //draw_meshleveling(); - break; - case HARDWARE_TEST_UI: - //draw_Hardwaretest(); - break; - case WIFI_LIST_UI: - #if ENABLED(USE_WIFI_FUNCTION) - lv_draw_wifi_list(); - #endif - break; - case KEY_BOARD_UI: - lv_draw_keyboard(); - break; - case WIFI_TIPS_UI: - #if ENABLED(USE_WIFI_FUNCTION) - lv_draw_wifi_tips(); - #endif - break; - case MACHINE_PARA_UI: - lv_draw_machine_para(); - break; - case MACHINE_SETTINGS_UI: - lv_draw_machine_settings(); - break; - case TEMPERATURE_SETTINGS_UI: - //draw_TemperatureSettings(); - break; - case MOTOR_SETTINGS_UI: - lv_draw_motor_settings(); - break; - case MACHINETYPE_UI: - //draw_MachineType(); - break; - case STROKE_UI: - //draw_Stroke(); - break; - case HOME_DIR_UI: - //draw_HomeDir(); - break; - case ENDSTOP_TYPE_UI: - //draw_EndstopType(); - break; - case FILAMENT_SETTINGS_UI: - lv_draw_filament_settings(); - break; - case LEVELING_SETTIGNS_UI: - //draw_LevelingSettings(); - break; - case LEVELING_PARA_UI: - lv_draw_level_settings(); - break; - case DELTA_LEVELING_PARA_UI: - //draw_DeltaLevelPara(); - break; - case MANUAL_LEVELING_POSIGION_UI: - lv_draw_manual_level_pos_settings(); - break; - case MAXFEEDRATE_UI: - lv_draw_max_feedrate_settings(); - break; - case STEPS_UI: - lv_draw_step_settings(); - break; - case ACCELERATION_UI: - lv_draw_acceleration_settings(); - break; - case JERK_UI: - #if HAS_CLASSIC_JERK - lv_draw_jerk_settings(); - #endif - break; - case MOTORDIR_UI: - //draw_MotorDir(); - break; - case HOMESPEED_UI: - //draw_HomeSpeed(); - break; - case NOZZLE_CONFIG_UI: - //draw_NozzleConfig(); - break; - case HOTBED_CONFIG_UI: - //draw_HotbedConfig(); - break; - case ADVANCED_UI: - lv_draw_advance_settings(); - break; - case DOUBLE_Z_UI: - //draw_DoubleZ(); - break; - case ENABLE_INVERT_UI: - //draw_EnableInvert(); - break; - case NUMBER_KEY_UI: - lv_draw_number_key(); - break; - case DIALOG_UI: - //draw_dialog(uiCfg.dialogType); - break; - case BABY_STEP_UI: - lv_draw_baby_stepping(); - break; - case PAUSE_POS_UI: - lv_draw_pause_position(); - break; - #if HAS_TRINAMIC_CONFIG - case TMC_CURRENT_UI: - lv_draw_tmc_current_settings(); - break; - #endif - case EEPROM_SETTINGS_UI: - lv_draw_eeprom_settings(); - break; - #if HAS_STEALTHCHOP - case TMC_MODE_UI: - lv_draw_tmc_step_mode_settings(); - break; - #endif - #if ENABLED(USE_WIFI_FUNCTION) - case WIFI_SETTINGS_UI: - lv_draw_wifi_settings(); - break; - #endif - #if USE_SENSORLESS - case HOMING_SENSITIVITY_UI: - lv_draw_homing_sensitivity_settings(); - break; - #endif - #if HAS_ROTARY_ENCODER - case ENCODER_SETTINGS_UI: - lv_draw_encoder_settings(); - break; - #endif - default: break; - } - } -} - -#if ENABLED(SDSUPPORT) - - void sd_detection() { - static bool last_sd_status; - const bool sd_status = IS_SD_INSERTED(); - if (sd_status != last_sd_status) { - last_sd_status = sd_status; - if (sd_status) card.mount(); else card.release(); - } - } - -#endif - -void lv_ex_line(lv_obj_t * line, lv_point_t *points) { - // Copy the previous line and apply the new style - lv_line_set_points(line, points, 2); // Set the points - lv_line_set_style(line, LV_LINE_STYLE_MAIN, &style_line); - lv_obj_align(line, NULL, LV_ALIGN_IN_TOP_MID, 0, 0); -} - -extern volatile uint32_t systick_uptime_millis; - -void print_time_count() { - if ((systick_uptime_millis % 1000) == 0) - if (print_time.start == 1) print_time.seconds++; -} - -void LV_TASK_HANDLER() { - //lv_tick_inc(1); - lv_task_handler(); - if (mks_test_flag == 0x1E) mks_hardware_test(); - - #if HAS_GCODE_PREVIEW - disp_pre_gcode(2, 36); - #endif - - GUI_RefreshPage(); - - #if ENABLED(USE_WIFI_FUNCTION) - get_wifi_commands(); - #endif - - //sd_detection(); - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_update_encoder(); - #endif -} - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_ui.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_ui.h deleted file mode 100644 index 51782688c0b1..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_ui.h +++ /dev/null @@ -1,454 +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 - -#include - -#include -#include - -// the colors of the last MKS Ui -#undef LV_COLOR_BACKGROUND -#define LV_COLOR_BACKGROUND LV_COLOR_MAKE(0x1A, 0x1A, 0x1A) // LV_COLOR_MAKE(0x00, 0x00, 0x00) - -#define TFT_LV_PARA_BACK_BODY_COLOR LV_COLOR_MAKE(0x4A, 0x52, 0xFF) - -#include "tft_lvgl_configuration.h" -#include "tft_multi_language.h" -#include "pic_manager.h" -#include "draw_ready_print.h" -#include "draw_language.h" -#include "draw_set.h" -#include "draw_tool.h" -#include "draw_print_file.h" -#include "draw_dialog.h" -#include "draw_printing.h" -#include "draw_operation.h" -#include "draw_preHeat.h" -#include "draw_extrusion.h" -#include "draw_home.h" -#include "draw_move_motor.h" -#include "draw_fan.h" -#include "draw_about.h" -#include "draw_change_speed.h" -#include "draw_manuaLevel.h" -#include "draw_error_message.h" -#include "printer_operation.h" -#include "draw_machine_para.h" -#include "draw_machine_settings.h" -#include "draw_motor_settings.h" -#include "draw_advance_settings.h" -#include "draw_acceleration_settings.h" -#include "draw_number_key.h" -#include "draw_jerk_settings.h" -#include "draw_pause_position.h" -#include "draw_step_settings.h" -#include "draw_tmc_current_settings.h" -#include "draw_eeprom_settings.h" -#include "draw_max_feedrate_settings.h" -#include "draw_tmc_step_mode_settings.h" -#include "draw_level_settings.h" -#include "draw_manual_level_pos_settings.h" -#include "draw_auto_level_offset_settings.h" -#include "draw_filament_change.h" -#include "draw_filament_settings.h" -#include "draw_homing_sensitivity_settings.h" -#include "draw_baby_stepping.h" -#include "draw_keyboard.h" -#include "draw_encoder_settings.h" - -#if ENABLED(USE_WIFI_FUNCTION) - #include "wifiSerial.h" - #include "wifi_module.h" - #include "wifi_upload.h" - #include "draw_wifi_settings.h" - #include "draw_wifi.h" - #include "draw_wifi_list.h" - #include "draw_wifi_tips.h" -#endif - -#include "../../inc/MarlinConfigPre.h" -#define FILE_SYS_USB 0 -#define FILE_SYS_SD 1 - -#define TICK_CYCLE 1 - -#define PARA_SEL_ICON_TEXT_COLOR LV_COLOR_MAKE(0x4A, 0x52, 0xFF); - -#define TFT35 - -#ifdef TFT35 - - #define TFT_WIDTH 480 - #define TFT_HEIGHT 320 - - #define titleHeight 36 // TFT_screen.title_high - #define INTERVAL_H 2 // TFT_screen.gap_h // 2 - #define INTERVAL_V 2 // TFT_screen.gap_v // 2 - #define BTN_X_PIXEL 117 // TFT_screen.btn_x_pixel - #define BTN_Y_PIXEL 140 // TFT_screen.btn_y_pixel - - #define SIMPLE_FIRST_PAGE_GRAP 30 - - #define BUTTON_TEXT_Y_OFFSET -20 - - #define TITLE_XPOS 3 // TFT_screen.title_xpos - #define TITLE_YPOS 5 // TFT_screen.title_ypos - - #define FILE_BTN_CNT 6 - - #define OTHER_BTN_XPIEL 117 - #define OTHER_BTN_YPIEL 92 - - #define FILE_PRE_PIC_X_OFFSET 8 - #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) - - // machine parameter ui - #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_ARROW_V 12 - - #define PARA_UI_BACL_POS_X 400 - #define PARA_UI_BACL_POS_Y 270 - - #define PARA_UI_TURN_PAGE_POS_X 320 - #define PARA_UI_TURN_PAGE_POS_Y 270 - - #define PARA_UI_VALUE_SIZE_X 370 - #define PARA_UI_VALUE_POS_X 400 - #define PARA_UI_VALUE_V 5 - - #define PARA_UI_STATE_POS_X 380 - #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_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 - -#else // ifdef TFT35 - - #define TFT_WIDTH 320 - #define TFT_HEIGHT 240 - -#endif // ifdef TFT35 - -#ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ -#endif - -extern char public_buf_m[100]; -extern char public_buf_l[30]; - -typedef struct { - uint32_t spi_flash_flag; - uint8_t disp_rotation_180; - uint8_t multiple_language; - uint8_t language; - uint8_t leveling_mode; - uint8_t from_flash_pic; - uint8_t finish_power_off; - uint8_t pause_reprint; - uint8_t wifi_mode_sel; - uint8_t fileSysType; - uint8_t wifi_type; - bool cloud_enable; - bool encoder_enable; - int levelingPos[5][2]; - int filamentchange_load_length; - int filamentchange_load_speed; - int filamentchange_unload_length; - int filamentchange_unload_speed; - int filament_limit_temper; - float pausePosX; - float pausePosY; - float pausePosZ; - uint32_t curFilesize; -} CFG_ITMES; - -typedef struct { - uint8_t curTempType : 1, - curSprayerChoose : 3, - stepHeat : 4; - uint8_t leveling_first_time : 1, - para_ui_page:1, - configWifi:1, - command_send:1, - filament_load_heat_flg:1, - filament_heat_completed_load:1, - filament_unload_heat_flg:1, - filament_heat_completed_unload:1; - uint8_t filament_loading_completed:1, - filament_unloading_completed:1, - filament_loading_time_flg:1, - filament_unloading_time_flg:1, - curSprayerChoose_bak:4; - uint8_t wifi_name[32]; - uint8_t wifi_key[64]; - uint8_t cloud_hostUrl[96]; - uint8_t extruStep; - uint8_t extruSpeed; - uint8_t print_state; - uint8_t stepPrintSpeed; - uint8_t waitEndMoves; - uint8_t dialogType; - uint8_t F[4]; - uint8_t filament_rate; - uint16_t moveSpeed; - uint16_t cloud_port; - uint16_t moveSpeed_bak; - uint32_t totalSend; - uint32_t filament_loading_time; - uint32_t filament_unloading_time; - uint32_t filament_loading_time_cnt; - uint32_t filament_unloading_time_cnt; - float move_dist; - float desireSprayerTempBak; - float current_x_position_bak; - float current_y_position_bak; - float current_e_position_bak; -} UI_CFG; - -typedef enum { - MAIN_UI, - PRINT_READY_UI, - PRINT_FILE_UI, - PRINTING_UI, - MOVE_MOTOR_UI, - OPERATE_UI, - PAUSE_UI, - EXTRUSION_UI, - FAN_UI, - PRE_HEAT_UI, - CHANGE_SPEED_UI, - TEMP_UI, - SET_UI, - ZERO_UI, - SPRAYER_UI, - MACHINE_UI, - LANGUAGE_UI, - ABOUT_UI, - LOG_UI, - DISK_UI, - CALIBRATE_UI, - DIALOG_UI, - WIFI_UI, - MORE_UI, - FILETRANSFER_UI, - FILETRANSFERSTATE_UI, - PRINT_MORE_UI, - FILAMENTCHANGE_UI, - LEVELING_UI, - MESHLEVELING_UI, - BIND_UI, - #if HAS_BED_PROBE - NOZZLE_PROBE_OFFSET_UI, - #endif - TOOL_UI, - HARDWARE_TEST_UI, - WIFI_LIST_UI, - KEY_BOARD_UI, - WIFI_TIPS_UI, - MACHINE_PARA_UI, - MACHINE_SETTINGS_UI, - TEMPERATURE_SETTINGS_UI, - MOTOR_SETTINGS_UI, - MACHINETYPE_UI, - STROKE_UI, - HOME_DIR_UI, - ENDSTOP_TYPE_UI, - FILAMENT_SETTINGS_UI, - LEVELING_SETTIGNS_UI, - LEVELING_PARA_UI, - DELTA_LEVELING_PARA_UI, - MANUAL_LEVELING_POSIGION_UI, - MAXFEEDRATE_UI, - STEPS_UI, - ACCELERATION_UI, - JERK_UI, - MOTORDIR_UI, - HOMESPEED_UI, - NOZZLE_CONFIG_UI, - HOTBED_CONFIG_UI, - ADVANCED_UI, - DOUBLE_Z_UI, - ENABLE_INVERT_UI, - NUMBER_KEY_UI, - BABY_STEP_UI, - ERROR_MESSAGE_UI, - PAUSE_POS_UI, - TMC_CURRENT_UI, - TMC_MODE_UI, - EEPROM_SETTINGS_UI, - WIFI_SETTINGS_UI, - HOMING_SENSITIVITY_UI, - ENCODER_SETTINGS_UI -} DISP_STATE; - -typedef struct { - DISP_STATE _disp_state[100]; - int _disp_index; -} DISP_STATE_STACK; - -typedef struct { - int16_t days; - uint16_t hours; - uint8_t minutes; - volatile int8_t seconds; - int8_t ms_10; - int8_t start; -} PRINT_TIME; -extern PRINT_TIME print_time; - -typedef enum { - PrintAcceleration, - RetractAcceleration, - TravelAcceleration, - XAcceleration, - YAcceleration, - ZAcceleration, - E0Acceleration, - E1Acceleration, - - XMaxFeedRate, - YMaxFeedRate, - ZMaxFeedRate, - E0MaxFeedRate, - E1MaxFeedRate, - - XJerk, - YJerk, - ZJerk, - EJerk, - - Xstep, - Ystep, - Zstep, - E0step, - E1step, - - Xcurrent, - Ycurrent, - Zcurrent, - E0current, - E1current, - - pause_pos_x, - pause_pos_y, - pause_pos_z, - - level_pos_x1, - level_pos_y1, - level_pos_x2, - level_pos_y2, - level_pos_x3, - level_pos_y3, - level_pos_x4, - level_pos_y4, - level_pos_x5, - level_pos_y5 - #if HAS_BED_PROBE - , - x_offset, - y_offset, - z_offset - #endif - , - load_length, - load_speed, - unload_length, - unload_speed, - filament_temp, - - x_sensitivity, - y_sensitivity, - z_sensitivity, - z2_sensitivity -} num_key_value_state; -extern num_key_value_state value; - -typedef enum { - wifiName, - wifiPassWord, - wifiConfig, - gcodeCommand -} keyboard_value_state; -extern keyboard_value_state keyboard_value; - -extern CFG_ITMES gCfgItems; -extern UI_CFG uiCfg; -extern DISP_STATE disp_state; -extern DISP_STATE last_disp_state; -extern DISP_STATE_STACK disp_state_stack; - -extern lv_style_t tft_style_scr; -extern lv_style_t tft_style_label_pre; -extern lv_style_t tft_style_label_rel; -extern lv_style_t style_line; -extern lv_style_t style_para_value_pre; -extern lv_style_t style_para_value_rel; -extern lv_style_t style_num_key_pre; -extern lv_style_t style_num_key_rel; -extern lv_style_t style_num_text; -extern lv_style_t style_sel_text; -extern lv_style_t style_para_value; -extern lv_style_t style_para_back; -extern lv_style_t lv_bar_style_indic; - -extern lv_point_t line_points[4][2]; - -extern void gCfgItems_init(); -extern void ui_cfg_init(); -extern void tft_style_init(); -extern char *creat_title_text(void); -extern void preview_gcode_prehandle(char *path); -extern void update_spi_flash(); -extern void update_gcode_command(int addr,uint8_t *s); -extern void get_gcode_command(int addr,uint8_t *d); -#if HAS_GCODE_PREVIEW - extern void disp_pre_gcode(int xpos_pixel, int ypos_pixel); -#endif -extern void GUI_RefreshPage(); -extern void clear_cur_ui(); -extern void draw_return_ui(); -extern void sd_detection(); -extern void gCfg_to_spiFlah(); -extern void print_time_count(); - -extern void LV_TASK_HANDLER(); -extern void lv_ex_line(lv_obj_t * line, lv_point_t *points); - -#ifdef __cplusplus - } /* C-declarations for C++ */ -#endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi.cpp deleted file mode 100644 index 9cf4555b25fe..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi.cpp +++ /dev/null @@ -1,222 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "lv_conf.h" -#include "draw_ui.h" - -#if ENABLED(USE_WIFI_FUNCTION) - -#include "../../../../../Configuration.h" -#include "../../../../module/temperature.h" - -extern lv_group_t * g; -static lv_obj_t *scr, *wifi_name_text, *wifi_key_text, *wifi_state_text, *wifi_ip_text; - -#define ID_W_RETURN 1 -#define ID_W_CLOUD 2 -#define ID_W_RECONNECT 3 - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_W_RETURN: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - clear_cur_ui(); - lv_draw_set(); - } - break; - case ID_W_CLOUD: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - //clear_cur_ui(); - //draw_return_ui(); - } - break; - case ID_W_RECONNECT: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - clear_cur_ui(); - lv_draw_wifi_list(); - } - break; - } -} - -void lv_draw_wifi(void) { - lv_obj_t *buttonBack=NULL,*label_Back=NULL; - lv_obj_t *buttonCloud=NULL,*label_Cloud=NULL; - lv_obj_t *buttonReconnect=NULL,*label_Reconnect=NULL; - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != WIFI_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = WIFI_UI; - } - disp_state = WIFI_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title,TITLE_XPOS,TITLE_YPOS); - lv_label_set_text(title, creat_title_text()); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - // Create an Image button - buttonBack = lv_imgbtn_create(scr, NULL); - if (gCfgItems.wifi_mode_sel == STA_MODEL) { - //buttonCloud = lv_imgbtn_create(scr, NULL); - buttonReconnect = lv_imgbtn_create(scr, NULL); - } - - lv_obj_set_event_cb_mks(buttonBack, event_handler,ID_W_RETURN, NULL,0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_return.bin"); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_return.bin"); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonBack); - #endif - - lv_obj_set_pos(buttonBack,BTN_X_PIXEL*3+INTERVAL_V*4, BTN_Y_PIXEL+INTERVAL_H+titleHeight); - lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - - if (gCfgItems.wifi_mode_sel == STA_MODEL) { - - lv_obj_set_event_cb_mks(buttonReconnect, event_handler,ID_W_RECONNECT, NULL,0); - lv_imgbtn_set_src(buttonReconnect, LV_BTN_STATE_REL, "F:/bmp_wifi.bin"); - lv_imgbtn_set_src(buttonReconnect, LV_BTN_STATE_PR, "F:/bmp_wifi.bin"); - lv_imgbtn_set_style(buttonReconnect, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonReconnect, LV_BTN_STATE_REL, &tft_style_label_rel); - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonReconnect); - #endif - - lv_obj_set_pos(buttonReconnect,BTN_X_PIXEL*2+INTERVAL_V*3, BTN_Y_PIXEL+INTERVAL_H+titleHeight); - lv_btn_set_layout(buttonReconnect, LV_LAYOUT_OFF); - } - - label_Back = lv_label_create(buttonBack, NULL); - - if (gCfgItems.wifi_mode_sel == STA_MODEL) { - //label_Cloud = lv_label_create(buttonCloud, NULL); - label_Reconnect = lv_label_create(buttonReconnect, NULL); - } - - if (gCfgItems.multiple_language !=0) { - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID,0, BUTTON_TEXT_Y_OFFSET); - - if (gCfgItems.wifi_mode_sel == STA_MODEL) { - //lv_label_set_text(label_Cloud, common_menu.text_back); - //lv_obj_align(label_Cloud, buttonCloud, LV_ALIGN_IN_BOTTOM_MID,0, BUTTON_TEXT_Y_OFFSET); - - lv_label_set_text(label_Reconnect, wifi_menu.reconnect); - lv_obj_align(label_Reconnect, buttonReconnect, LV_ALIGN_IN_BOTTOM_MID,0, BUTTON_TEXT_Y_OFFSET); - } - } - - wifi_ip_text = lv_label_create(scr, NULL); - lv_obj_set_style(wifi_ip_text, &tft_style_label_rel); - - wifi_name_text = lv_label_create(scr, NULL); - lv_obj_set_style(wifi_name_text, &tft_style_label_rel); - - wifi_key_text = lv_label_create(scr, NULL); - lv_obj_set_style(wifi_key_text, &tft_style_label_rel); - - wifi_state_text = lv_label_create(scr, NULL); - lv_obj_set_style(wifi_state_text, &tft_style_label_rel); - - disp_wifi_state(); -} - -void disp_wifi_state() { - memset(public_buf_m, 0, sizeof(public_buf_m)); - strcpy(public_buf_m,wifi_menu.ip); - strcat(public_buf_m,ipPara.ip_addr); - lv_label_set_text(wifi_ip_text, public_buf_m); - lv_obj_align(wifi_ip_text, NULL, LV_ALIGN_CENTER,0, -100); - - memset(public_buf_m, 0, sizeof(public_buf_m)); - strcpy(public_buf_m,wifi_menu.wifi); - strcat(public_buf_m,wifiPara.ap_name); - lv_label_set_text(wifi_name_text, public_buf_m); - lv_obj_align(wifi_name_text, NULL, LV_ALIGN_CENTER,0, -70); - - if (wifiPara.mode == AP_MODEL) { - memset(public_buf_m, 0, sizeof(public_buf_m)); - strcpy(public_buf_m,wifi_menu.key); - strcat(public_buf_m,wifiPara.keyCode); - lv_label_set_text(wifi_key_text, public_buf_m); - lv_obj_align(wifi_key_text, NULL, LV_ALIGN_CENTER,0, -40); - - memset(public_buf_m, 0, sizeof(public_buf_m)); - strcpy(public_buf_m,wifi_menu.state_ap); - if (wifi_link_state == WIFI_CONNECTED) - strcat(public_buf_m,wifi_menu.connected); - else if (wifi_link_state == WIFI_NOT_CONFIG) - strcat(public_buf_m,wifi_menu.disconnected); - else - strcat(public_buf_m,wifi_menu.exception); - lv_label_set_text(wifi_state_text, public_buf_m); - lv_obj_align(wifi_state_text, NULL, LV_ALIGN_CENTER,0, -10); - } - else { - ZERO(public_buf_m); - strcpy(public_buf_m, wifi_menu.state_sta); - if (wifi_link_state == WIFI_CONNECTED) - strcat(public_buf_m, wifi_menu.connected); - else if (wifi_link_state == WIFI_NOT_CONFIG) - strcat(public_buf_m, wifi_menu.disconnected); - else - strcat(public_buf_m, wifi_menu.exception); - lv_label_set_text(wifi_state_text, public_buf_m); - lv_obj_align(wifi_state_text, NULL, LV_ALIGN_CENTER,0, -40); - - lv_label_set_text(wifi_key_text, ""); - lv_obj_align(wifi_key_text, NULL, LV_ALIGN_CENTER,0, -10); - } -} - -void lv_clear_wifi() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // USE_WIFI_FUNCTION -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_list.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_list.cpp deleted file mode 100644 index 14fd63f85282..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_list.cpp +++ /dev/null @@ -1,235 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "lv_conf.h" -#include "draw_ui.h" - -#if ENABLED(USE_WIFI_FUNCTION) - -#include "../../../../../Configuration.h" -#include "../../../../module/temperature.h" - -#define NAME_BTN_X 330 -#define NAME_BTN_Y 48 - -#define MARK_BTN_X 0 -#define MARK_BTN_Y 68 - -WIFI_LIST wifi_list; -list_menu_def list_menu; - -extern lv_group_t * g; -static lv_obj_t * scr; -static lv_obj_t *buttonWifiN[NUMBER_OF_PAGE]; -static lv_obj_t *lableWifiText[NUMBER_OF_PAGE]; -static lv_obj_t *lablePageText; - -#define ID_WL_RETURN 11 -#define ID_WL_DOWN 12 - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - if (obj->mks_obj_id == ID_WL_RETURN) { - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - clear_cur_ui(); - lv_draw_set(); - } - } - else if (obj->mks_obj_id == ID_WL_DOWN) { - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - if (wifi_list.getNameNum > 0) { - if ((wifi_list.nameIndex + NUMBER_OF_PAGE) >= wifi_list.getNameNum) { - wifi_list.nameIndex = 0; - wifi_list.currentWifipage = 1; - } - else { - wifi_list.nameIndex += NUMBER_OF_PAGE; - wifi_list.currentWifipage++; - } - disp_wifi_list(); - } - } - } - else { - for (uint8_t i = 0; i < NUMBER_OF_PAGE; i++) { - if (obj->mks_obj_id == i + 1) { - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - if (wifi_list.getNameNum != 0) { - const bool do_wifi = wifi_link_state == WIFI_CONNECTED && strcmp((const char *)wifi_list.wifiConnectedName, (const char *)wifi_list.wifiName[wifi_list.nameIndex + i]) == 0; - wifi_list.nameIndex += i; - last_disp_state = WIFI_LIST_UI; - lv_clear_wifi_list(); - if (do_wifi) - lv_draw_wifi(); - else { - keyboard_value = wifiConfig; - lv_draw_keyboard(); - } - } - } - } - } - } -} - -void lv_draw_wifi_list(void) { - lv_obj_t *buttonBack = NULL, *buttonDown = NULL; - - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != WIFI_LIST_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = WIFI_LIST_UI; - } - disp_state = WIFI_LIST_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title,TITLE_XPOS,TITLE_YPOS); - lv_label_set_text(title, creat_title_text()); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - buttonDown = lv_imgbtn_create(scr, NULL); - buttonBack = lv_imgbtn_create(scr, NULL); - - lv_obj_set_event_cb_mks(buttonDown, event_handler,ID_WL_DOWN,NULL,0); - lv_imgbtn_set_src(buttonDown, LV_BTN_STATE_REL, "F:/bmp_pageDown.bin"); - lv_imgbtn_set_src(buttonDown, LV_BTN_STATE_PR, "F:/bmp_pageDown.bin"); - lv_imgbtn_set_style(buttonDown, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonDown, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonBack, event_handler,ID_WL_RETURN,NULL,0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_back.bin"); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_back.bin"); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_pos(buttonDown,OTHER_BTN_XPIEL*3+INTERVAL_V*4,titleHeight+OTHER_BTN_YPIEL+INTERVAL_H); - lv_obj_set_pos(buttonBack,OTHER_BTN_XPIEL*3+INTERVAL_V*4,titleHeight+OTHER_BTN_YPIEL*2+INTERVAL_H*2); - - lv_btn_set_layout(buttonDown, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - - for (uint8_t i = 0; i < NUMBER_OF_PAGE; i++) { - buttonWifiN[i] = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonWifiN[i], 0,NAME_BTN_Y*i+10+titleHeight); /*Set its position*/ - lv_obj_set_size(buttonWifiN[i], NAME_BTN_X,NAME_BTN_Y); /*Set its size*/ - lv_obj_set_event_cb_mks(buttonWifiN[i], event_handler,(i+1),NULL,0); - lv_btn_set_style(buttonWifiN[i], LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonWifiN[i], LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonWifiN[i], LV_LAYOUT_OFF); - lableWifiText[i] = lv_label_create(buttonWifiN[i], NULL); - #if HAS_ROTARY_ENCODER - uint8_t j = 0; - if (gCfgItems.encoder_enable) { - j = wifi_list.nameIndex + i; - if (j < wifi_list.getNameNum) lv_group_add_obj(g, buttonWifiN[i]); - } - #endif - } - - lablePageText = lv_label_create(scr, NULL); - lv_obj_set_style(lablePageText, &tft_style_label_rel); - - wifi_list.nameIndex = 0; - wifi_list.currentWifipage = 1; - - if (wifi_link_state == WIFI_CONNECTED && wifiPara.mode == STA_MODEL) { - memset(wifi_list.wifiConnectedName, 0, sizeof(&wifi_list.wifiConnectedName)); - memcpy(wifi_list.wifiConnectedName, wifiPara.ap_name, sizeof(wifi_list.wifiConnectedName)); - } - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonDown); - lv_group_add_obj(g, buttonBack); - } - #endif - - disp_wifi_list(); -} - -void disp_wifi_list(void) { - int8_t tmpStr[WIFI_NAME_BUFFER_SIZE] = { 0 }; - uint8_t i, j; - - sprintf((char *)tmpStr, list_menu.file_pages, wifi_list.currentWifipage, wifi_list.getPage); - lv_label_set_text(lablePageText, (const char *)tmpStr); - lv_obj_align(lablePageText, NULL, LV_ALIGN_CENTER, 50, -100); - - for (i = 0; i < NUMBER_OF_PAGE; i++) { - memset(tmpStr, 0, sizeof(tmpStr)); - - j = wifi_list.nameIndex + i; - if (j >= wifi_list.getNameNum) { - lv_label_set_text(lableWifiText[i], (const char *)tmpStr); - lv_obj_align(lableWifiText[i], buttonWifiN[i], LV_ALIGN_IN_LEFT_MID, 20, 0); - } - else { - lv_label_set_text(lableWifiText[i], (char const *)wifi_list.wifiName[j]); - lv_obj_align(lableWifiText[i], buttonWifiN[i], LV_ALIGN_IN_LEFT_MID, 20, 0); - - if (wifi_link_state == WIFI_CONNECTED && strcmp((const char *)wifi_list.wifiConnectedName, (const char *)wifi_list.wifiName[j]) == 0) { - lv_btn_set_style(buttonWifiN[i], LV_BTN_STYLE_REL, &style_sel_text); - } - else { - lv_btn_set_style(buttonWifiN[i], LV_BTN_STYLE_REL, &tft_style_label_rel); - } - } - } -} - -void wifi_scan_handle() { - if (uiCfg.dialogType != WIFI_ENABLE_TIPS || uiCfg.command_send != 1) return; - last_disp_state = DIALOG_UI; - lv_clear_dialog(); - if (wifi_link_state == WIFI_CONNECTED && wifiPara.mode != AP_MODEL) - lv_draw_wifi(); - else - lv_draw_wifi_list(); -} - -void lv_clear_wifi_list() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // USE_WIFI_FUNCTION - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_settings.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_settings.cpp deleted file mode 100644 index 86733470ddbb..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_settings.cpp +++ /dev/null @@ -1,299 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "lv_conf.h" -#include "draw_ui.h" - -#if ENABLED(USE_WIFI_FUNCTION) - -#include "../../../../../Configuration.h" -#include "../../../../module/planner.h" - -extern lv_group_t * g; -static lv_obj_t *scr, *labelModelValue = NULL, *buttonModelValue = NULL, *labelCloudValue = NULL; - -#define ID_WIFI_RETURN 1 -#define ID_WIFI_MODEL 2 -#define ID_WIFI_NAME 3 -#define ID_WIFI_PASSWORD 4 -#define ID_WIFI_CLOUD 5 -#define ID_WIFI_CONFIG 6 - -static void event_handler(lv_obj_t * obj, lv_event_t event) { - switch (obj->mks_obj_id) { - case ID_WIFI_RETURN: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_wifi_settings(); - draw_return_ui(); - } - break; - case ID_WIFI_MODEL: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - if (gCfgItems.wifi_mode_sel == AP_MODEL) { - gCfgItems.wifi_mode_sel = STA_MODEL; - lv_label_set_text(labelModelValue, WIFI_STA_TEXT); - lv_obj_align(labelModelValue, buttonModelValue, LV_ALIGN_CENTER,0, 0); - update_spi_flash(); - } - else{ - gCfgItems.wifi_mode_sel = AP_MODEL; - lv_label_set_text(labelModelValue, WIFI_AP_TEXT); - lv_obj_align(labelModelValue, buttonModelValue, LV_ALIGN_CENTER,0, 0); - update_spi_flash(); - } - } - break; - case ID_WIFI_NAME: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - keyboard_value=wifiName; - lv_clear_wifi_settings(); - lv_draw_keyboard(); - } - break; - case ID_WIFI_PASSWORD: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - keyboard_value=wifiPassWord; - lv_clear_wifi_settings(); - lv_draw_keyboard(); - } - break; - case ID_WIFI_CLOUD: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - if (gCfgItems.cloud_enable) { - gCfgItems.cloud_enable = false; - lv_obj_set_event_cb_mks(obj, event_handler,ID_WIFI_CLOUD,"bmp_disable.bin",0); - lv_label_set_text(labelCloudValue, machine_menu.disable); - update_spi_flash(); - } - else { - gCfgItems.cloud_enable = true; - lv_obj_set_event_cb_mks(obj, event_handler,ID_WIFI_CLOUD,"bmp_enable.bin",0); - lv_label_set_text(labelCloudValue, machine_menu.enable); - update_spi_flash(); - } - } - break; - case ID_WIFI_CONFIG: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_wifi_settings(); - lv_draw_dialog(DIALOG_WIFI_CONFIG_TIPS); - } - break; - } -} - -void lv_draw_wifi_settings(void) { - lv_obj_t *buttonBack = NULL, *label_Back = NULL, *buttonConfig = NULL, *labelConfig = NULL; - lv_obj_t *labelModelText = NULL; - lv_obj_t *labelNameText = NULL, *buttonNameValue = NULL, *labelNameValue = NULL; - lv_obj_t *labelPassWordText = NULL, *buttonPassWordValue = NULL, *labelPassWordValue = NULL; - lv_obj_t *labelCloudText = NULL, *buttonCloudValue = NULL; - lv_obj_t * line1 = NULL, *line2 = NULL, *line3 = NULL, *line4 = NULL; - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != WIFI_SETTINGS_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = WIFI_SETTINGS_UI; - } - disp_state = WIFI_SETTINGS_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_obj_t * title = lv_label_create(scr, NULL); - lv_obj_set_style(title, &tft_style_label_rel); - lv_obj_set_pos(title,TITLE_XPOS,TITLE_YPOS); - lv_label_set_text(title, machine_menu.WifiConfTitle); - - lv_refr_now(lv_refr_get_disp_refreshing()); - - labelModelText = lv_label_create(scr, NULL); - lv_obj_set_style(labelModelText, &tft_style_label_rel); - lv_obj_set_pos(labelModelText, PARA_UI_POS_X, PARA_UI_POS_Y + 10); - lv_label_set_text(labelModelText, machine_menu.wifiMode); - - buttonModelValue = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonModelValue,PARA_UI_VALUE_POS_X,PARA_UI_POS_Y+PARA_UI_VALUE_V); - lv_obj_set_event_cb_mks(buttonModelValue, event_handler,ID_WIFI_MODEL, NULL,0); - lv_imgbtn_set_src(buttonModelValue, LV_BTN_STATE_REL, "F:/bmp_blank_sel.bin"); - lv_imgbtn_set_src(buttonModelValue, LV_BTN_STATE_PR, "F:/bmp_blank_sel.bin"); - lv_imgbtn_set_style(buttonModelValue, LV_BTN_STATE_PR, &style_para_value_pre); - lv_imgbtn_set_style(buttonModelValue, LV_BTN_STATE_REL, &style_para_value_pre); - lv_btn_set_layout(buttonModelValue, LV_LAYOUT_OFF); - labelModelValue = lv_label_create(buttonModelValue, NULL); - - line1 = lv_line_create(scr, NULL); - lv_ex_line(line1,line_points[0]); - - labelNameText = lv_label_create(scr, NULL); - lv_obj_set_style(labelNameText, &tft_style_label_rel); - lv_obj_set_pos(labelNameText, PARA_UI_POS_X, PARA_UI_POS_Y * 2 + 10); - - buttonNameValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonNameValue,PARA_UI_VALUE_POS_X,PARA_UI_POS_Y*2+PARA_UI_VALUE_V); - lv_obj_set_size(buttonNameValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonNameValue, event_handler,ID_WIFI_NAME, NULL,0); - lv_btn_set_style(buttonNameValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonNameValue, LV_BTN_STYLE_PR, &style_para_value); - labelNameValue = lv_label_create(buttonNameValue, NULL); - - line2 = lv_line_create(scr, NULL); - lv_ex_line(line2,line_points[1]); - - labelPassWordText = lv_label_create(scr, NULL); - lv_obj_set_style(labelPassWordText, &tft_style_label_rel); - lv_obj_set_pos(labelPassWordText, PARA_UI_POS_X, PARA_UI_POS_Y * 3 + 10); - - buttonPassWordValue = lv_btn_create(scr, NULL); - lv_obj_set_pos(buttonPassWordValue,PARA_UI_VALUE_POS_X,PARA_UI_POS_Y*3+PARA_UI_VALUE_V); - lv_obj_set_size(buttonPassWordValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); - lv_obj_set_event_cb_mks(buttonPassWordValue, event_handler,ID_WIFI_PASSWORD, NULL,0); - lv_btn_set_style(buttonPassWordValue, LV_BTN_STYLE_REL, &style_para_value); - lv_btn_set_style(buttonPassWordValue, LV_BTN_STYLE_PR, &style_para_value); - labelPassWordValue = lv_label_create(buttonPassWordValue, NULL); - - line3 = lv_line_create(scr, NULL); - lv_ex_line(line3,line_points[2]); - - labelCloudText = lv_label_create(scr, NULL); - lv_obj_set_style(labelCloudText, &tft_style_label_rel); - lv_obj_set_pos(labelCloudText, PARA_UI_POS_X, PARA_UI_POS_Y * 4 + 10); - lv_label_set_text(labelCloudText, machine_menu.wifiCloud); - - buttonCloudValue = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonCloudValue,PARA_UI_STATE_POS_X,PARA_UI_POS_Y*4+PARA_UI_STATE_V); - if (gCfgItems.cloud_enable) { - lv_imgbtn_set_src(buttonCloudValue, LV_BTN_STATE_REL, "F:/bmp_enable.bin"); - lv_imgbtn_set_src(buttonCloudValue, LV_BTN_STATE_PR, "F:/bmp_enable.bin"); - } - else { - lv_imgbtn_set_src(buttonCloudValue, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); - lv_imgbtn_set_src(buttonCloudValue, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); - } - lv_obj_set_event_cb_mks(buttonCloudValue, event_handler,ID_WIFI_CLOUD, NULL,0); - lv_imgbtn_set_style(buttonCloudValue, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonCloudValue, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_btn_set_layout(buttonCloudValue, LV_LAYOUT_OFF); - labelCloudValue = lv_label_create(buttonCloudValue, NULL); - - line4 = lv_line_create(scr, NULL); - lv_ex_line(line4,line_points[3]); - - buttonConfig = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonConfig, event_handler,ID_WIFI_CONFIG, NULL,0); - lv_imgbtn_set_src(buttonConfig, LV_BTN_STATE_REL, "F:/bmp_back70x40.bin"); - lv_imgbtn_set_src(buttonConfig, LV_BTN_STATE_PR, "F:/bmp_back70x40.bin"); - lv_imgbtn_set_style(buttonConfig, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonConfig, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_pos(buttonConfig, PARA_UI_TURN_PAGE_POS_X, PARA_UI_TURN_PAGE_POS_Y); - lv_btn_set_layout(buttonConfig, LV_LAYOUT_OFF); - labelConfig = lv_label_create(buttonConfig, NULL); - - buttonBack = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_WIFI_RETURN, NULL, 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_back70x40.bin"); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_back70x40.bin"); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); - lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - label_Back = lv_label_create(buttonBack, NULL); - - if (gCfgItems.multiple_language !=0) { - if (gCfgItems.wifi_mode_sel == AP_MODEL) { - lv_label_set_text(labelModelValue, WIFI_AP_TEXT); - lv_obj_align(labelModelValue, buttonModelValue, LV_ALIGN_CENTER,0, 0); - } - else { - lv_label_set_text(labelModelValue, WIFI_STA_TEXT); - lv_obj_align(labelModelValue, buttonModelValue, LV_ALIGN_CENTER,0, 0); - } - memset(public_buf_m,0,sizeof(public_buf_m)); - strcat(public_buf_m,machine_menu.wifiName); - strcat(public_buf_m,(const char *)uiCfg.wifi_name); - lv_label_set_text(labelNameText,public_buf_m); - - lv_label_set_text(labelNameValue,machine_menu.wifiEdit); - lv_obj_align(labelNameValue, buttonNameValue, LV_ALIGN_CENTER,0, 0); - - memset(public_buf_m,0,sizeof(public_buf_m)); - strcat(public_buf_m,machine_menu.wifiPassWord); - strcat(public_buf_m,(const char *)uiCfg.wifi_key); - lv_label_set_text(labelPassWordText,public_buf_m); - - lv_label_set_text(labelPassWordValue,machine_menu.wifiEdit); - lv_obj_align(labelPassWordValue, buttonPassWordValue, LV_ALIGN_CENTER,0, 0); - - lv_label_set_text(labelCloudValue, gCfgItems.cloud_enable ? machine_menu.enable : machine_menu.disable); - lv_obj_align(labelCloudValue, buttonCloudValue, LV_ALIGN_CENTER,0, 0); - - lv_label_set_text(labelConfig,machine_menu.wifiConfig); - lv_obj_align(labelConfig, buttonConfig, LV_ALIGN_CENTER,0, 0); - - lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_CENTER,0, 0); - } - - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { - lv_group_add_obj(g, buttonModelValue); - lv_group_add_obj(g, buttonNameValue); - lv_group_add_obj(g, buttonPassWordValue); - lv_group_add_obj(g, buttonCloudValue); - lv_group_add_obj(g, buttonConfig); - lv_group_add_obj(g, buttonBack); - } - #endif -} - -void lv_clear_wifi_settings() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif - lv_obj_del(scr); -} - -#endif // USE_WIFI_FUNCTION - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_tips.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_tips.cpp deleted file mode 100644 index 50fa0aaf99c7..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_tips.cpp +++ /dev/null @@ -1,85 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "lv_conf.h" -#include "draw_ui.h" - -#if ENABLED(USE_WIFI_FUNCTION) - -#include "../../../../../Configuration.h" -#include "../../../../module/temperature.h" - -static lv_obj_t * scr; - -TIPS_TYPE wifi_tips_type; -TIPS_DISP tips_disp; -tips_menu_def tips_menu; - -void lv_draw_wifi_tips(void) { - static lv_obj_t * text_tips,*wifi_name; - - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != WIFI_TIPS_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = WIFI_TIPS_UI; - } - disp_state = WIFI_TIPS_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - lv_refr_now(lv_refr_get_disp_refreshing()); - - text_tips = lv_label_create(scr, NULL); - lv_obj_set_style(text_tips, &tft_style_label_rel); - - wifi_name = lv_label_create(scr, NULL); - lv_obj_set_style(wifi_name, &tft_style_label_rel); - - if (wifi_tips_type == TIPS_TYPE_JOINING) { - lv_label_set_text(text_tips, tips_menu.joining); - lv_obj_align(text_tips, NULL, LV_ALIGN_CENTER,0, -60); - } - else if (wifi_tips_type == TIPS_TYPE_TAILED_JOIN) { - lv_label_set_text(text_tips, tips_menu.failedJoin); - lv_obj_align(text_tips, NULL, LV_ALIGN_CENTER,0, -60); - } - else if (wifi_tips_type == TIPS_TYPE_WIFI_CONECTED) { - lv_label_set_text(text_tips, tips_menu.wifiConected); - lv_obj_align(text_tips, NULL, LV_ALIGN_CENTER,0, -60); - } - - lv_label_set_text(wifi_name, (const char *)wifi_list.wifiName[wifi_list.nameIndex]); - lv_obj_align(wifi_name, NULL, LV_ALIGN_CENTER,0, -20); - - tips_disp.timer = TIPS_TIMER_START; - tips_disp.timer_count = 0; -} - -void lv_clear_wifi_tips() { lv_obj_del(scr); } - -#endif // USE_WIFI_FUNCTION -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/irq_overrid.cpp b/Marlin/src/lcd/extui/lib/mks_ui/irq_overrid.cpp deleted file mode 100644 index cf64571292bf..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/irq_overrid.cpp +++ /dev/null @@ -1,69 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "draw_ui.h" - -#if ENABLED(USE_WIFI_FUNCTION) - -#include "wifiSerial.h" - -#include -#include -#include -#include -#include - -#include "../../../../inc/MarlinConfig.h" - -#ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ -#endif - -#define WIFI_IO1_SET() WRITE(WIFI_IO1_PIN, HIGH); -#define WIFI_IO1_RESET() WRITE(WIFI_IO1_PIN, LOW); - -void __irq_usart1(void) { - WIFISERIAL.wifi_usart_irq(USART1_BASE); - if (wifi_link_state == WIFI_TRANS_FILE) { - if (WIFISERIAL.available() == (400)) WIFI_IO1_SET(); - if (WIFISERIAL.wifi_rb_is_full()) { - if (esp_state == TRANSFER_IDLE) esp_state = TRANSFERING; - if (storeRcvData(UART_RX_BUFFER_SIZE)) { - if (wifiTransError.flag != 0x1) WIFI_IO1_RESET(); - } - else { - WIFI_IO1_SET(); - esp_state = TRANSFER_STORE; - } - } - } -} - -#ifdef __cplusplus - } /* C-declarations for C++ */ -#endif - -#endif // USE_WIFI_FUNCTION -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/mks_hardware_test.cpp b/Marlin/src/lcd/extui/lib/mks_ui/mks_hardware_test.cpp deleted file mode 100644 index bc329aa82b89..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/mks_hardware_test.cpp +++ /dev/null @@ -1,665 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "SPI_TFT.h" - -#include "tft_lvgl_configuration.h" -#include "draw_ready_print.h" -#include "mks_hardware_test.h" -#include "draw_ui.h" -#include "pic_manager.h" -#include - -#include "../../../../MarlinCore.h" -#include "../../../../module/temperature.h" -#include "../../../../sd/cardreader.h" - -uint8_t pw_det_sta, pw_off_sta, mt_det_sta, mt_det3_sta; -#if PIN_EXISTS(MT_DET_2) - uint8_t mt_det2_sta; -#endif -uint8_t endstopx1_sta, endstopx2_sta, endstopy1_sta, endstopy2_sta, endstopz1_sta, endstopz2_sta; -void test_gpio_readlevel_L() { - #if ENABLED(MKS_TEST) - volatile uint32_t itest; - WRITE(WIFI_IO0_PIN, HIGH); - itest = 10000; - while (itest--); - pw_det_sta = (READ(MKS_TEST_POWER_LOSS_PIN) == 0); - pw_off_sta = (READ(MKS_TEST_PS_ON_PIN) == 0); - mt_det_sta = (READ(MT_DET_1_PIN) == 0); - #if PIN_EXISTS(MT_DET_2) - mt_det2_sta = (READ(MT_DET_2_PIN) == 0); - #endif - //mt_det3_sta = (READ(FIL_RUNOUT_3_PIN) == 0); - endstopx1_sta = (READ(X_MIN_PIN) == 0); - //endstopx2_sta = (READ(X_MAX_PIN) == 0); - endstopy1_sta = (READ(Y_MIN_PIN) == 0); - //endstopy2_sta = (READ(Y_MAX_PIN) == 0); - endstopz1_sta = (READ(Z_MIN_PIN) == 0); - endstopz2_sta = (READ(Z_MAX_PIN) == 0); - #endif -} - -void test_gpio_readlevel_H() { - #if ENABLED(MKS_TEST) - volatile uint32_t itest; - WRITE(WIFI_IO0_PIN, LOW); - itest = 10000; - while (itest--); - pw_det_sta = (READ(MKS_TEST_POWER_LOSS_PIN) == 1); - pw_off_sta = (READ(MKS_TEST_PS_ON_PIN) == 1); - mt_det_sta = (READ(MT_DET_1_PIN) == 1); - #if PIN_EXISTS(MT_DET_2) - mt_det2_sta = (READ(MT_DET_2_PIN) == 1); - #endif - //mt_det3_sta = (READ(MT_DET_3_PIN) == 1); - endstopx1_sta = (READ(X_MIN_PIN) == 1); - //endstopx2_sta = (READ(X_MAX_PIN) == 1); - endstopy1_sta = (READ(Y_MIN_PIN) == 1); - //endstopy2_sta = (READ(Y_MAX_PIN) == 1); - endstopz1_sta = (READ(Z_MIN_PIN) == 1); - endstopz2_sta = (READ(Z_MAX_PIN) == 1); - #endif -} - -void init_test_gpio() { - #ifdef MKS_TEST - SET_INPUT_PULLUP(X_MIN_PIN); - //SET_INPUT_PULLUP(X_MAX_PIN); - SET_INPUT_PULLUP(Y_MIN_PIN); - //SET_INPUT_PULLUP(Y_MAX_PIN); - SET_INPUT_PULLUP(Z_MIN_PIN); - SET_INPUT_PULLUP(Z_MAX_PIN); - - SET_OUTPUT(WIFI_IO0_PIN); - - SET_INPUT_PULLUP(MT_DET_1_PIN); - #if PIN_EXISTS(MT_DET_2) - SET_INPUT_PULLUP(MT_DET_2_PIN); - #endif - //SET_INPUT_PULLUP(MT_DET_3_PIN); - - SET_INPUT_PULLUP(MKS_TEST_POWER_LOSS_PIN); - SET_INPUT_PULLUP(MKS_TEST_PS_ON_PIN); - - SET_INPUT_PULLUP(SERVO0_PIN); - - SET_OUTPUT(X_ENABLE_PIN); - SET_OUTPUT(Y_ENABLE_PIN); - SET_OUTPUT(Z_ENABLE_PIN); - SET_OUTPUT(E0_ENABLE_PIN); - #if !MB(MKS_ROBIN_E3P) - SET_OUTPUT(E1_ENABLE_PIN); - #endif - - WRITE(X_ENABLE_PIN, LOW); - WRITE(Y_ENABLE_PIN, LOW); - WRITE(Z_ENABLE_PIN, LOW); - WRITE(E0_ENABLE_PIN, LOW); - #if !MB(MKS_ROBIN_E3P) - WRITE(E1_ENABLE_PIN, LOW); - #endif - //WRITE(E2_ENABLE_PIN, LOW); - - #if MB(MKS_ROBIN_E3P) - SET_INPUT_PULLUP(PA1); - SET_INPUT_PULLUP(PA3); - SET_INPUT_PULLUP(PC2); - SET_INPUT_PULLUP(PD8); - SET_INPUT_PULLUP(PE5); - SET_INPUT_PULLUP(PE6); - SET_INPUT_PULLUP(PE7); - #endif - #endif -} - -void mks_test_beeper() { - #ifdef MKS_TEST - WRITE(BEEPER_PIN, HIGH); - delay(100); - WRITE(BEEPER_PIN, LOW); - delay(100); - #endif -} - -void mks_gpio_test() { - #if ENABLED(MKS_TEST) - init_test_gpio(); - - test_gpio_readlevel_L(); - test_gpio_readlevel_H(); - test_gpio_readlevel_L(); - if ((pw_det_sta == 1) - && (pw_off_sta == 1) - && (mt_det_sta == 1) - #if PIN_EXISTS(MT_DET_2) - && (mt_det2_sta == 1) - #endif - #if MB(MKS_ROBIN_E3P) - && (READ(PA1) == 0) - && (READ(PA3) == 0) - && (READ(PC2) == 0) - && (READ(PD8) == 0) - && (READ(PE5) == 0) - && (READ(PE6) == 0) - && (READ(PE7) == 0) - #endif - ) // &&(mt_det3_sta == 1)) - disp_det_ok(); - else - disp_det_error(); - - if ( (endstopx1_sta == 1) - //&& (endstopx2_sta == 1) - && (endstopy1_sta == 1) - //&& (endstopy2_sta == 1) - && (endstopz1_sta == 1) - && (endstopz2_sta == 1) - ) - disp_Limit_ok(); - else - disp_Limit_error(); - #endif -} - -void mks_hardware_test() { - #if ENABLED(MKS_TEST) - if (millis() % 2000 < 1000) { - WRITE(X_DIR_PIN, LOW); - WRITE(Y_DIR_PIN, LOW); - WRITE(Z_DIR_PIN, LOW); - WRITE(E0_DIR_PIN, LOW); - #if !MB(MKS_ROBIN_E3P) - WRITE(E1_DIR_PIN, LOW); - #endif - //WRITE(E2_DIR_PIN, LOW); - thermalManager.fan_speed[0] = 255; - //WRITE(HEATER_2_PIN, HIGH); // HE2 - #if !MB(MKS_ROBIN_E3P) - WRITE(HEATER_1_PIN, HIGH); // HE1 - #endif - WRITE(HEATER_0_PIN, HIGH); // HE0 - WRITE(HEATER_BED_PIN, HIGH); // HOT-BED - } - else { - WRITE(X_DIR_PIN, HIGH); - WRITE(Y_DIR_PIN, HIGH); - WRITE(Z_DIR_PIN, HIGH); - WRITE(E0_DIR_PIN, HIGH); - #if !MB(MKS_ROBIN_E3P) - WRITE(E1_DIR_PIN, HIGH); - #endif - //WRITE(E2_DIR_PIN, HIGH); - thermalManager.fan_speed[0] = 0; - //WRITE(HEATER_2_PIN, LOW); // HE2 - #if !MB(MKS_ROBIN_E3P) - WRITE(HEATER_1_PIN, LOW); // HE1 - #endif - WRITE(HEATER_0_PIN, LOW); // HE0 - WRITE(HEATER_BED_PIN, LOW); // HOT-BED - } - - if ( (endstopx1_sta == 1) && (endstopx2_sta == 1) - && (endstopy1_sta == 1) && (endstopy2_sta == 1) - && (endstopz1_sta == 1) && (endstopz2_sta == 1) - ) { - // nothing here - } - else { - //mks_test_beeper(); - } - - if (disp_state == PRINT_READY_UI) - mks_disp_test(); - - #endif -} - -static const uint16_t ASCII_Table_16x24[] PROGMEM = { - // Space ' ' - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // '!' - 0x0000, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, - 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0000, 0x0000, - 0x0180, 0x0180, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // '"' - 0x0000, 0x0000, 0x00CC, 0x00CC, 0x00CC, 0x00CC, 0x00CC, 0x00CC, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // '#' - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0C60, 0x0C60, - 0x0C60, 0x0630, 0x0630, 0x1FFE, 0x1FFE, 0x0630, 0x0738, 0x0318, - 0x1FFE, 0x1FFE, 0x0318, 0x0318, 0x018C, 0x018C, 0x018C, 0x0000, - // '$' - 0x0000, 0x0080, 0x03E0, 0x0FF8, 0x0E9C, 0x1C8C, 0x188C, 0x008C, - 0x0098, 0x01F8, 0x07E0, 0x0E80, 0x1C80, 0x188C, 0x188C, 0x189C, - 0x0CB8, 0x0FF0, 0x03E0, 0x0080, 0x0080, 0x0000, 0x0000, 0x0000, - // '%' - 0x0000, 0x0000, 0x0000, 0x180E, 0x0C1B, 0x0C11, 0x0611, 0x0611, - 0x0311, 0x0311, 0x019B, 0x018E, 0x38C0, 0x6CC0, 0x4460, 0x4460, - 0x4430, 0x4430, 0x4418, 0x6C18, 0x380C, 0x0000, 0x0000, 0x0000, - // '&' - 0x0000, 0x01E0, 0x03F0, 0x0738, 0x0618, 0x0618, 0x0330, 0x01F0, - 0x00F0, 0x00F8, 0x319C, 0x330E, 0x1E06, 0x1C06, 0x1C06, 0x3F06, - 0x73FC, 0x21F0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // "'" - 0x0000, 0x0000, 0x000C, 0x000C, 0x000C, 0x000C, 0x000C, 0x000C, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // '(' - 0x0000, 0x0200, 0x0300, 0x0180, 0x00C0, 0x00C0, 0x0060, 0x0060, - 0x0030, 0x0030, 0x0030, 0x0030, 0x0030, 0x0030, 0x0030, 0x0030, - 0x0060, 0x0060, 0x00C0, 0x00C0, 0x0180, 0x0300, 0x0200, 0x0000, - // ')' - 0x0000, 0x0020, 0x0060, 0x00C0, 0x0180, 0x0180, 0x0300, 0x0300, - 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, - 0x0300, 0x0300, 0x0180, 0x0180, 0x00C0, 0x0060, 0x0020, 0x0000, - // '*' - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x00C0, 0x00C0, - 0x06D8, 0x07F8, 0x01E0, 0x0330, 0x0738, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // '+' - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0180, 0x0180, - 0x0180, 0x0180, 0x0180, 0x3FFC, 0x3FFC, 0x0180, 0x0180, 0x0180, - 0x0180, 0x0180, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // ',' - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0180, 0x0180, 0x0100, 0x0100, 0x0080, 0x0000, 0x0000, - // '-' - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x07E0, 0x07E0, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // '.' - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x00C0, 0x00C0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // '/' - 0x0000, 0x0C00, 0x0C00, 0x0600, 0x0600, 0x0600, 0x0300, 0x0300, - 0x0300, 0x0380, 0x0180, 0x0180, 0x0180, 0x00C0, 0x00C0, 0x00C0, - 0x0060, 0x0060, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // '0' - 0x0000, 0x03E0, 0x07F0, 0x0E38, 0x0C18, 0x180C, 0x180C, 0x180C, - 0x180C, 0x180C, 0x180C, 0x180C, 0x180C, 0x180C, 0x0C18, 0x0E38, - 0x07F0, 0x03E0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // '1' - 0x0000, 0x0100, 0x0180, 0x01C0, 0x01F0, 0x0198, 0x0188, 0x0180, - 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, - 0x0180, 0x0180, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // '2' - 0x0000, 0x03E0, 0x0FF8, 0x0C18, 0x180C, 0x180C, 0x1800, 0x1800, - 0x0C00, 0x0600, 0x0300, 0x0180, 0x00C0, 0x0060, 0x0030, 0x0018, - 0x1FFC, 0x1FFC, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // '3' - 0x0000, 0x01E0, 0x07F8, 0x0E18, 0x0C0C, 0x0C0C, 0x0C00, 0x0600, - 0x03C0, 0x07C0, 0x0C00, 0x1800, 0x1800, 0x180C, 0x180C, 0x0C18, - 0x07F8, 0x03E0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // '4' - 0x0000, 0x0C00, 0x0E00, 0x0F00, 0x0F00, 0x0D80, 0x0CC0, 0x0C60, - 0x0C60, 0x0C30, 0x0C18, 0x0C0C, 0x3FFC, 0x3FFC, 0x0C00, 0x0C00, - 0x0C00, 0x0C00, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // '5' - 0x0000, 0x0FF8, 0x0FF8, 0x0018, 0x0018, 0x000C, 0x03EC, 0x07FC, - 0x0E1C, 0x1C00, 0x1800, 0x1800, 0x1800, 0x180C, 0x0C1C, 0x0E18, - 0x07F8, 0x03E0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // '6' - 0x0000, 0x07C0, 0x0FF0, 0x1C38, 0x1818, 0x0018, 0x000C, 0x03CC, - 0x0FEC, 0x0E3C, 0x1C1C, 0x180C, 0x180C, 0x180C, 0x1C18, 0x0E38, - 0x07F0, 0x03E0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // '7' - 0x0000, 0x1FFC, 0x1FFC, 0x0C00, 0x0600, 0x0600, 0x0300, 0x0380, - 0x0180, 0x01C0, 0x00C0, 0x00E0, 0x0060, 0x0060, 0x0070, 0x0030, - 0x0030, 0x0030, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // '8' - 0x0000, 0x03E0, 0x07F0, 0x0E38, 0x0C18, 0x0C18, 0x0C18, 0x0638, - 0x07F0, 0x07F0, 0x0C18, 0x180C, 0x180C, 0x180C, 0x180C, 0x0C38, - 0x0FF8, 0x03E0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // '9' - 0x0000, 0x03E0, 0x07F0, 0x0E38, 0x0C1C, 0x180C, 0x180C, 0x180C, - 0x1C1C, 0x1E38, 0x1BF8, 0x19E0, 0x1800, 0x0C00, 0x0C00, 0x0E1C, - 0x07F8, 0x01F0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // ':' - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0180, 0x0180, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0180, 0x0180, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // ';' - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0180, 0x0180, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0180, 0x0180, 0x0100, 0x0100, 0x0080, 0x0000, 0x0000, 0x0000, - // '<' - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x1000, 0x1C00, 0x0F80, 0x03E0, 0x00F8, 0x0018, 0x00F8, 0x03E0, - 0x0F80, 0x1C00, 0x1000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // '=' - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x1FF8, 0x0000, 0x0000, 0x0000, 0x1FF8, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // '>' - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0008, 0x0038, 0x01F0, 0x07C0, 0x1F00, 0x1800, 0x1F00, 0x07C0, - 0x01F0, 0x0038, 0x0008, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // '?' - 0x0000, 0x03E0, 0x0FF8, 0x0C18, 0x180C, 0x180C, 0x1800, 0x0C00, - 0x0600, 0x0300, 0x0180, 0x00C0, 0x00C0, 0x00C0, 0x0000, 0x0000, - 0x00C0, 0x00C0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // '@' - 0x0000, 0x0000, 0x07E0, 0x1818, 0x2004, 0x29C2, 0x4A22, 0x4411, - 0x4409, 0x4409, 0x4409, 0x2209, 0x1311, 0x0CE2, 0x4002, 0x2004, - 0x1818, 0x07E0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'A' - 0x0000, 0x0380, 0x0380, 0x06C0, 0x06C0, 0x06C0, 0x0C60, 0x0C60, - 0x1830, 0x1830, 0x1830, 0x3FF8, 0x3FF8, 0x701C, 0x600C, 0x600C, - 0xC006, 0xC006, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'B' - 0x0000, 0x03FC, 0x0FFC, 0x0C0C, 0x180C, 0x180C, 0x180C, 0x0C0C, - 0x07FC, 0x0FFC, 0x180C, 0x300C, 0x300C, 0x300C, 0x300C, 0x180C, - 0x1FFC, 0x07FC, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'C' - 0x0000, 0x07C0, 0x1FF0, 0x3838, 0x301C, 0x700C, 0x6006, 0x0006, - 0x0006, 0x0006, 0x0006, 0x0006, 0x0006, 0x6006, 0x700C, 0x301C, - 0x1FF0, 0x07E0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'D' - 0x0000, 0x03FE, 0x0FFE, 0x0E06, 0x1806, 0x1806, 0x3006, 0x3006, - 0x3006, 0x3006, 0x3006, 0x3006, 0x3006, 0x1806, 0x1806, 0x0E06, - 0x0FFE, 0x03FE, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'E' - 0x0000, 0x3FFC, 0x3FFC, 0x000C, 0x000C, 0x000C, 0x000C, 0x000C, - 0x1FFC, 0x1FFC, 0x000C, 0x000C, 0x000C, 0x000C, 0x000C, 0x000C, - 0x3FFC, 0x3FFC, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'F' - 0x0000, 0x3FF8, 0x3FF8, 0x0018, 0x0018, 0x0018, 0x0018, 0x0018, - 0x1FF8, 0x1FF8, 0x0018, 0x0018, 0x0018, 0x0018, 0x0018, 0x0018, - 0x0018, 0x0018, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'G' - 0x0000, 0x0FE0, 0x3FF8, 0x783C, 0x600E, 0xE006, 0xC007, 0x0003, - 0x0003, 0xFE03, 0xFE03, 0xC003, 0xC007, 0xC006, 0xC00E, 0xF03C, - 0x3FF8, 0x0FE0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'H' - 0x0000, 0x300C, 0x300C, 0x300C, 0x300C, 0x300C, 0x300C, 0x300C, - 0x3FFC, 0x3FFC, 0x300C, 0x300C, 0x300C, 0x300C, 0x300C, 0x300C, - 0x300C, 0x300C, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'I' - 0x0000, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, - 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, - 0x0180, 0x0180, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'J' - 0x0000, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, - 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0618, 0x0618, 0x0738, - 0x03F0, 0x01E0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'K' - 0x0000, 0x3006, 0x1806, 0x0C06, 0x0606, 0x0306, 0x0186, 0x00C6, - 0x0066, 0x0076, 0x00DE, 0x018E, 0x0306, 0x0606, 0x0C06, 0x1806, - 0x3006, 0x6006, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'L' - 0x0000, 0x0018, 0x0018, 0x0018, 0x0018, 0x0018, 0x0018, 0x0018, - 0x0018, 0x0018, 0x0018, 0x0018, 0x0018, 0x0018, 0x0018, 0x0018, - 0x1FF8, 0x1FF8, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'M' - 0x0000, 0xE00E, 0xF01E, 0xF01E, 0xF01E, 0xD836, 0xD836, 0xD836, - 0xD836, 0xCC66, 0xCC66, 0xCC66, 0xC6C6, 0xC6C6, 0xC6C6, 0xC6C6, - 0xC386, 0xC386, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'N' - 0x0000, 0x300C, 0x301C, 0x303C, 0x303C, 0x306C, 0x306C, 0x30CC, - 0x30CC, 0x318C, 0x330C, 0x330C, 0x360C, 0x360C, 0x3C0C, 0x3C0C, - 0x380C, 0x300C, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'O' - 0x0000, 0x07E0, 0x1FF8, 0x381C, 0x700E, 0x6006, 0xC003, 0xC003, - 0xC003, 0xC003, 0xC003, 0xC003, 0xC003, 0x6006, 0x700E, 0x381C, - 0x1FF8, 0x07E0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'P' - 0x0000, 0x0FFC, 0x1FFC, 0x380C, 0x300C, 0x300C, 0x300C, 0x300C, - 0x180C, 0x1FFC, 0x07FC, 0x000C, 0x000C, 0x000C, 0x000C, 0x000C, - 0x000C, 0x000C, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'Q' - 0x0000, 0x07E0, 0x1FF8, 0x381C, 0x700E, 0x6006, 0xE003, 0xC003, - 0xC003, 0xC003, 0xC003, 0xC003, 0xE007, 0x6306, 0x3F0E, 0x3C1C, - 0x3FF8, 0xF7E0, 0xC000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'R' - 0x0000, 0x0FFE, 0x1FFE, 0x3806, 0x3006, 0x3006, 0x3006, 0x3806, - 0x1FFE, 0x07FE, 0x0306, 0x0606, 0x0C06, 0x1806, 0x1806, 0x3006, - 0x3006, 0x6006, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'S' - 0x0000, 0x03E0, 0x0FF8, 0x0C1C, 0x180C, 0x180C, 0x000C, 0x001C, - 0x03F8, 0x0FE0, 0x1E00, 0x3800, 0x3006, 0x3006, 0x300E, 0x1C1C, - 0x0FF8, 0x07E0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'T' - 0x0000, 0x7FFE, 0x7FFE, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, - 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, - 0x0180, 0x0180, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'U' - 0x0000, 0x300C, 0x300C, 0x300C, 0x300C, 0x300C, 0x300C, 0x300C, - 0x300C, 0x300C, 0x300C, 0x300C, 0x300C, 0x300C, 0x300C, 0x1818, - 0x1FF8, 0x07E0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'V' - 0x0000, 0x6003, 0x3006, 0x3006, 0x3006, 0x180C, 0x180C, 0x180C, - 0x0C18, 0x0C18, 0x0E38, 0x0630, 0x0630, 0x0770, 0x0360, 0x0360, - 0x01C0, 0x01C0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'W' - 0x0000, 0x6003, 0x61C3, 0x61C3, 0x61C3, 0x3366, 0x3366, 0x3366, - 0x3366, 0x3366, 0x3366, 0x1B6C, 0x1B6C, 0x1B6C, 0x1A2C, 0x1E3C, - 0x0E38, 0x0E38, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'X' - 0x0000, 0xE00F, 0x700C, 0x3018, 0x1830, 0x0C70, 0x0E60, 0x07C0, - 0x0380, 0x0380, 0x03C0, 0x06E0, 0x0C70, 0x1C30, 0x1818, 0x300C, - 0x600E, 0xE007, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'Y' - 0x0000, 0xC003, 0x6006, 0x300C, 0x381C, 0x1838, 0x0C30, 0x0660, - 0x07E0, 0x03C0, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, - 0x0180, 0x0180, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'Z' - 0x0000, 0x7FFC, 0x7FFC, 0x6000, 0x3000, 0x1800, 0x0C00, 0x0600, - 0x0300, 0x0180, 0x00C0, 0x0060, 0x0030, 0x0018, 0x000C, 0x0006, - 0x7FFE, 0x7FFE, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // '[' - 0x0000, 0x03E0, 0x03E0, 0x0060, 0x0060, 0x0060, 0x0060, 0x0060, - 0x0060, 0x0060, 0x0060, 0x0060, 0x0060, 0x0060, 0x0060, 0x0060, - 0x0060, 0x0060, 0x0060, 0x0060, 0x0060, 0x03E0, 0x03E0, 0x0000, - // '\' - 0x0000, 0x0030, 0x0030, 0x0060, 0x0060, 0x0060, 0x00C0, 0x00C0, - 0x00C0, 0x01C0, 0x0180, 0x0180, 0x0180, 0x0300, 0x0300, 0x0300, - 0x0600, 0x0600, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // ']' - 0x0000, 0x03E0, 0x03E0, 0x0300, 0x0300, 0x0300, 0x0300, 0x0300, - 0x0300, 0x0300, 0x0300, 0x0300, 0x0300, 0x0300, 0x0300, 0x0300, - 0x0300, 0x0300, 0x0300, 0x0300, 0x0300, 0x03E0, 0x03E0, 0x0000, - // '^' - 0x0000, 0x0000, 0x01C0, 0x01C0, 0x0360, 0x0360, 0x0360, 0x0630, - 0x0630, 0x0C18, 0x0C18, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // '_' - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0xFFFF, 0xFFFF, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // ''' - 0x0000, 0x000C, 0x000C, 0x000C, 0x000C, 0x000C, 0x000C, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'a' - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x03F0, 0x07F8, - 0x0C1C, 0x0C0C, 0x0F00, 0x0FF0, 0x0CF8, 0x0C0C, 0x0C0C, 0x0F1C, - 0x0FF8, 0x18F0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'b' - 0x0000, 0x0018, 0x0018, 0x0018, 0x0018, 0x0018, 0x03D8, 0x0FF8, - 0x0C38, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, 0x0C38, - 0x0FF8, 0x03D8, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'c' - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x03C0, 0x07F0, - 0x0E30, 0x0C18, 0x0018, 0x0018, 0x0018, 0x0018, 0x0C18, 0x0E30, - 0x07F0, 0x03C0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'd' - 0x0000, 0x1800, 0x1800, 0x1800, 0x1800, 0x1800, 0x1BC0, 0x1FF0, - 0x1C30, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, 0x1C30, - 0x1FF0, 0x1BC0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'e' - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x03C0, 0x0FF0, - 0x0C30, 0x1818, 0x1FF8, 0x1FF8, 0x0018, 0x0018, 0x1838, 0x1C30, - 0x0FF0, 0x07C0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'f' - 0x0000, 0x0F80, 0x0FC0, 0x00C0, 0x00C0, 0x00C0, 0x07F0, 0x07F0, - 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, - 0x00C0, 0x00C0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'g' - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0DE0, 0x0FF8, - 0x0E18, 0x0C0C, 0x0C0C, 0x0C0C, 0x0C0C, 0x0C0C, 0x0C0C, 0x0E18, - 0x0FF8, 0x0DE0, 0x0C00, 0x0C0C, 0x061C, 0x07F8, 0x01F0, 0x0000, - // 'h' - 0x0000, 0x0018, 0x0018, 0x0018, 0x0018, 0x0018, 0x07D8, 0x0FF8, - 0x1C38, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, - 0x1818, 0x1818, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'i' - 0x0000, 0x00C0, 0x00C0, 0x0000, 0x0000, 0x0000, 0x00C0, 0x00C0, - 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, - 0x00C0, 0x00C0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'j' - 0x0000, 0x00C0, 0x00C0, 0x0000, 0x0000, 0x0000, 0x00C0, 0x00C0, - 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, - 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00F8, 0x0078, 0x0000, - // 'k' - 0x0000, 0x000C, 0x000C, 0x000C, 0x000C, 0x000C, 0x0C0C, 0x060C, - 0x030C, 0x018C, 0x00CC, 0x006C, 0x00FC, 0x019C, 0x038C, 0x030C, - 0x060C, 0x0C0C, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'l' - 0x0000, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, - 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, - 0x00C0, 0x00C0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'm' - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x3C7C, 0x7EFF, - 0xE3C7, 0xC183, 0xC183, 0xC183, 0xC183, 0xC183, 0xC183, 0xC183, - 0xC183, 0xC183, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'n' - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0798, 0x0FF8, - 0x1C38, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, - 0x1818, 0x1818, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'o' - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x03C0, 0x0FF0, - 0x0C30, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, 0x0C30, - 0x0FF0, 0x03C0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'p' - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x03D8, 0x0FF8, - 0x0C38, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, 0x0C38, - 0x0FF8, 0x03D8, 0x0018, 0x0018, 0x0018, 0x0018, 0x0018, 0x0000, - // 'q' - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x1BC0, 0x1FF0, - 0x1C30, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, 0x1C30, - 0x1FF0, 0x1BC0, 0x1800, 0x1800, 0x1800, 0x1800, 0x1800, 0x0000, - // 'r' - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x07B0, 0x03F0, - 0x0070, 0x0030, 0x0030, 0x0030, 0x0030, 0x0030, 0x0030, 0x0030, - 0x0030, 0x0030, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 's' - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x03E0, 0x03F0, - 0x0E38, 0x0C18, 0x0038, 0x03F0, 0x07C0, 0x0C00, 0x0C18, 0x0E38, - 0x07F0, 0x03E0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 't' - 0x0000, 0x0000, 0x0080, 0x00C0, 0x00C0, 0x00C0, 0x07F0, 0x07F0, - 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, - 0x07C0, 0x0780, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'u' - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x1818, 0x1818, - 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, 0x1C38, - 0x1FF0, 0x19E0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'v' - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x180C, 0x0C18, - 0x0C18, 0x0C18, 0x0630, 0x0630, 0x0630, 0x0360, 0x0360, 0x0360, - 0x01C0, 0x01C0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'w' - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x41C1, 0x41C1, - 0x61C3, 0x6363, 0x6363, 0x6363, 0x3636, 0x3636, 0x3636, 0x1C1C, - 0x1C1C, 0x1C1C, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'x' - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x381C, 0x1C38, - 0x0C30, 0x0660, 0x0360, 0x0360, 0x0360, 0x0360, 0x0660, 0x0C30, - 0x1C38, 0x381C, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // 'y' - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x3018, 0x1830, - 0x1830, 0x1870, 0x0C60, 0x0C60, 0x0CE0, 0x06C0, 0x06C0, 0x0380, - 0x0380, 0x0380, 0x0180, 0x0180, 0x01C0, 0x00F0, 0x0070, 0x0000, - // 'z' - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x1FFC, 0x1FFC, - 0x0C00, 0x0600, 0x0300, 0x0180, 0x00C0, 0x0060, 0x0030, 0x0018, - 0x1FFC, 0x1FFC, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - // '{' - 0x0000, 0x0300, 0x0180, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, - 0x00C0, 0x0060, 0x0060, 0x0030, 0x0060, 0x0040, 0x00C0, 0x00C0, - 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x0180, 0x0300, 0x0000, 0x0000, - // '|' - 0x0000, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, - 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, - 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0000, - // '}' - 0x0000, 0x0060, 0x00C0, 0x01C0, 0x0180, 0x0180, 0x0180, 0x0180, - 0x0180, 0x0300, 0x0300, 0x0600, 0x0300, 0x0100, 0x0180, 0x0180, - 0x0180, 0x0180, 0x0180, 0x0180, 0x00C0, 0x0060, 0x0000, 0x0000, - // '~' - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x10F0, 0x1FF8, 0x0F08, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, -}; - -void disp_char_1624(uint16_t x, uint16_t y, uint8_t c, uint16_t charColor, uint16_t bkColor) { - 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); - } -} - -void disp_string(uint16_t x, uint16_t y, const char * string, uint16_t charColor, uint16_t bkColor) { - while (*string != '\0') { - disp_char_1624(x, y, *string, charColor, bkColor); - string++; - x += 16; - } -} - -//static lv_obj_t * scr_test; -void disp_assets_update() { - SPI_TFT.LCD_clear(0x0000); - disp_string(100, 140, "Assets Updating...", 0xFFFF, 0x0000); -} - -void disp_assets_update_progress(const char *msg) { - char buf[30]; - memset(buf, ' ', COUNT(buf)); - strncpy(buf, msg, strlen(msg)); - buf[COUNT(buf)-1] = '\0'; - disp_string(100, 165, buf, 0xFFFF, 0x0000); -} - -uint8_t mks_test_flag = 0; -const char *MKSTestPath = "MKS_TEST"; - -#if ENABLED(SDSUPPORT) - void mks_test_get() { - SdFile dir, root = card.getroot(); - if (dir.open(&root, MKSTestPath, O_RDONLY)) - mks_test_flag = 0x1E; - } -#endif - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/mks_hardware_test.h b/Marlin/src/lcd/extui/lib/mks_ui/mks_hardware_test.h deleted file mode 100644 index 0e2d8096bac9..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/mks_hardware_test.h +++ /dev/null @@ -1,33 +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 - -#include - -void mks_gpio_test(); -void disp_char_1624(uint16_t x, uint16_t y, uint8_t c, uint16_t charColor, uint16_t bkColor); -void disp_string(uint16_t x, uint16_t y, const char * string, uint16_t charColor, uint16_t bkColor); -void mks_hardware_test(); -void disp_assets_update(); -void disp_assets_update_progress(const char *msg); -void mks_test_get(); -extern uint8_t mks_test_flag; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/printer_operation.cpp b/Marlin/src/lcd/extui/lib/mks_ui/printer_operation.cpp deleted file mode 100644 index 2b6f5f89f6ee..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/printer_operation.cpp +++ /dev/null @@ -1,252 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "../../../../MarlinCore.h" - -#include "lv_conf.h" -#include "draw_ui.h" -#include "../../../../module/temperature.h" -#include "../../../../module/motion.h" -#include "../../../../sd/cardreader.h" -#include "../../../../gcode/queue.h" - -#if ENABLED(POWER_LOSS_RECOVERY) - #include "../../../../feature/powerloss.h" -#endif - -#include "../../../../gcode/gcode.h" -#include "../../../../module/planner.h" - -extern uint32_t To_pre_view; -extern uint8_t flash_preview_begin, default_preview_flg, gcode_preview_over; - -void printer_state_polling() { - if (uiCfg.print_state == PAUSING) { - #if ENABLED(SDSUPPORT) - if (!planner.has_blocks_queued() && card.getIndex() > MIN_FILE_PRINTED) - uiCfg.waitEndMoves++; - - if (uiCfg.waitEndMoves > 20) { - uiCfg.waitEndMoves = 0; - planner.synchronize(); - - gcode.process_subcommands_now_P(PSTR("M25")); - - //save the positon - uiCfg.current_x_position_bak = current_position.x; - uiCfg.current_y_position_bak = current_position.y; - - if (gCfgItems.pausePosZ != (float)-1) { - gcode.process_subcommands_now_P(PSTR("G91")); - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("G1 Z%.1f"), gCfgItems.pausePosZ); - gcode.process_subcommands_now(public_buf_l); - gcode.process_subcommands_now_P(PSTR("G90")); - } - if (gCfgItems.pausePosX != (float)-1 && gCfgItems.pausePosY != (float)-1) { - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("G1 X%.1f Y%.1f"), gCfgItems.pausePosX, gCfgItems.pausePosY); - gcode.process_subcommands_now(public_buf_l); - } - uiCfg.print_state = PAUSED; - uiCfg.current_e_position_bak = current_position.e; - - // #if ENABLED(POWER_LOSS_RECOVERY) - // if (recovery.enabled) recovery.save(true); - // #endif - gCfgItems.pause_reprint = 1; - update_spi_flash(); - } - #endif - } - else - uiCfg.waitEndMoves = 0; - - if (uiCfg.print_state == PAUSED) { - } - - if (uiCfg.print_state == RESUMING) { - if (IS_SD_PAUSED()) { - if (gCfgItems.pausePosX != (float)-1 && gCfgItems.pausePosY != (float)-1) { - ZERO(public_buf_m); - sprintf_P(public_buf_m, PSTR("G1 X%.1f Y%.1f"), uiCfg.current_x_position_bak, uiCfg.current_y_position_bak); - gcode.process_subcommands_now(public_buf_m); - } - if (gCfgItems.pausePosZ != (float)-1) { - gcode.process_subcommands_now_P(PSTR("G91")); - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("G1 Z-%.1f"), gCfgItems.pausePosZ); - gcode.process_subcommands_now(public_buf_l); - gcode.process_subcommands_now_P(PSTR("G90")); - } - gcode.process_subcommands_now_P(PSTR("M24")); - uiCfg.print_state = WORKING; - start_print_time(); - - gCfgItems.pause_reprint = 0; - update_spi_flash(); - } - } - #if ENABLED(POWER_LOSS_RECOVERY) - if (uiCfg.print_state == REPRINTED) { - ZERO(public_buf_m); - #if HAS_HOTEND - HOTEND_LOOP() { - const int16_t et = recovery.info.target_temperature[e]; - if (et) { - #if HAS_MULTI_HOTEND - sprintf_P(public_buf_m, PSTR("T%i"), e); - gcode.process_subcommands_now(public_buf_m); - #endif - sprintf_P(public_buf_m, PSTR("M109 S%i"), et); - gcode.process_subcommands_now(public_buf_m); - } - } - #endif - - recovery.resume(); - #if 0 - // Move back to the saved XY - char str_1[16], str_2[16]; - ZERO(public_buf_m); - sprintf_P(public_buf_m, PSTR("G1 X%s Y%s F2000"), - dtostrf(recovery.info.current_position.x, 1, 3, str_1), - dtostrf(recovery.info.current_position.y, 1, 3, str_2) - ); - gcode.process_subcommands_now(public_buf_m); - - if ((gCfgItems.pause_reprint) == 1 && (gCfgItems.pausePosZ != (float)-1)) { - gcode.process_subcommands_now_P(PSTR("G91")); - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("G1 Z-%.1f"), gCfgItems.pausePosZ); - gcode.process_subcommands_now(public_buf_l); - gcode.process_subcommands_now_P(PSTR("G90")); - } - #endif - uiCfg.print_state = WORKING; - start_print_time(); - - gCfgItems.pause_reprint = 0; - update_spi_flash(); - } - #endif - - if (uiCfg.print_state == WORKING) - filament_check(); - - TERN_(USE_WIFI_FUNCTION, wifi_looping()); -} - -void filament_pin_setup() { - #if PIN_EXISTS(MT_DET_1) - SET_INPUT_PULLUP(MT_DET_1_PIN); - #endif - #if PIN_EXISTS(MT_DET_2) - SET_INPUT_PULLUP(MT_DET_2_PIN); - #endif - #if PIN_EXISTS(MT_DET_3) - SET_INPUT_PULLUP(MT_DET_3_PIN); - #endif -} - -void filament_check() { - const int FIL_DELAY = 20; - #if PIN_EXISTS(MT_DET_1) - static int fil_det_count_1 = 0; - if (!READ(MT_DET_1_PIN) && !MT_DET_PIN_INVERTING) - fil_det_count_1++; - else if (READ(MT_DET_1_PIN) && MT_DET_PIN_INVERTING) - fil_det_count_1++; - else if (fil_det_count_1 > 0) - fil_det_count_1--; - - if (!READ(MT_DET_1_PIN) && !MT_DET_PIN_INVERTING) - fil_det_count_1++; - else if (READ(MT_DET_1_PIN) && MT_DET_PIN_INVERTING) - fil_det_count_1++; - else if (fil_det_count_1 > 0) - fil_det_count_1--; - #endif - - #if PIN_EXISTS(MT_DET_2) - static int fil_det_count_2 = 0; - if (!READ(MT_DET_2_PIN) && !MT_DET_PIN_INVERTING) - fil_det_count_2++; - else if (READ(MT_DET_2_PIN) && MT_DET_PIN_INVERTING) - fil_det_count_2++; - else if (fil_det_count_2 > 0) - fil_det_count_2--; - - if (!READ(MT_DET_2_PIN) && !MT_DET_PIN_INVERTING) - fil_det_count_2++; - else if (READ(MT_DET_2_PIN) && MT_DET_PIN_INVERTING) - fil_det_count_2++; - else if (fil_det_count_2 > 0) - fil_det_count_2--; - #endif - - #if PIN_EXISTS(MT_DET_3) - static int fil_det_count_3 = 0; - if (!READ(MT_DET_3_PIN) && !MT_DET_PIN_INVERTING) - fil_det_count_3++; - else if (READ(MT_DET_3_PIN) && MT_DET_PIN_INVERTING) - fil_det_count_3++; - else if (fil_det_count_3 > 0) - fil_det_count_3--; - - if (!READ(MT_DET_3_PIN) && !MT_DET_PIN_INVERTING) - fil_det_count_3++; - else if (READ(MT_DET_3_PIN) && MT_DET_PIN_INVERTING) - fil_det_count_3++; - else if (fil_det_count_3 > 0) - fil_det_count_3--; - #endif - - if (false - #if PIN_EXISTS(MT_DET_1) - || fil_det_count_1 >= FIL_DELAY - #endif - #if PIN_EXISTS(MT_DET_2) - || fil_det_count_2 >= FIL_DELAY - #endif - #if PIN_EXISTS(MT_DET_3) - || fil_det_count_3 >= FIL_DELAY - #endif - ) { - clear_cur_ui(); - card.pauseSDPrint(); - stop_print_time(); - uiCfg.print_state = PAUSING; - - if (gCfgItems.from_flash_pic == 1) - flash_preview_begin = 1; - else - default_preview_flg = 1; - - lv_draw_printing(); - } -} - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_fr.h b/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_fr.h deleted file mode 100644 index 6944d6b23518..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_fr.h +++ /dev/null @@ -1,281 +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 TOOL_TEXT_FR "prêt" -#define PREHEAT_TEXT_FR "Préchauffe" -#define MOVE_TEXT_FR "Déplace" -#define HOME_TEXT_FR "Acceuil" -#define PRINT_TEXT_FR "Impression" -#define EXTRUDE_TEXT_FR "Extruder" -#define LEVELING_TEXT_FR "Leveling" -#define AUTO_LEVELING_TEXT_FR "AutoLevel" -#define SET_TEXT_FR "Config" -#define MORE_TEXT_FR "Plus" - -#define ADD_TEXT_FR "Ajouter" -#define DEC_TEXT_FR "Réduire" -#define EXTRUDER_1_TEXT_FR "Extr1" -#define EXTRUDER_2_TEXT_FR "Extr2" -#define HEATBED_TEXT_FR "Hotlit" -#define TEXT_1C_FR "1℃" -#define TEXT_5C_FR "5℃" -#define TEXT_10C_FR "10℃" -#define CLOSE_TEXT_FR "Off" - -#define BACK_TEXT_FR "Arrière" - -#define TOOL_PREHEAT_FR "Préchauffe" -#define TOOL_EXTRUDE_FR "Extruder" -#define TOOL_MOVE_FR "Déplace" -#define TOOL_HOME_FR "Acceuil" -#define TOOL_LEVELING_FR "Leveling" -#define TOOL_AUTO_LEVELING_FR "AutoLevel" -#define TOOL_FILAMENT_FR "Filament" -#define TOOL_MORE_FR "Plus" - -#define AXIS_X_ADD_TEXT_FR "X+" -#define AXIS_X_DEC_TEXT_FR "X-" -#define AXIS_Y_ADD_TEXT_FR "Y+" -#define AXIS_Y_DEC_TEXT_FR "Y-" -#define AXIS_Z_ADD_TEXT_FR "Z+" -#define AXIS_Z_DEC_TEXT_FR "Z-" -#define TEXT_01MM_FR "0.1mm" -#define TEXT_1MM_FR "1mm" -#define TEXT_10MM_FR "10mm" - -#define HOME_X_TEXT_FR "X" -#define HOME_Y_TEXT_FR "Y" -#define HOME_Z_TEXT_FR "Z" -#define HOME_ALL_TEXT_FR "ALL" -#define HOME_STOPMOVE_FR "Quickstop" - -#define PAGE_UP_TEXT_FR "En haut" -#define PAGE_DOWN_TEXT_FR "En bas" - -#define EXTRUDER_IN_TEXT_FR "Insérer" -#define EXTRUDER_OUT_TEXT_FR "éjecter" -#define EXTRUDE_1MM_TEXT_FR "1mm" -#define EXTRUDE_5MM_TEXT_FR "5mm" -#define EXTRUDE_10MM_TEXT_FR "10mm" -#define EXTRUDE_LOW_SPEED_TEXT_FR "Lente" -#define EXTRUDE_MEDIUM_SPEED_TEXT_FR "Moyen" -#define EXTRUDE_HIGH_SPEED_TEXT_FR "Rapide" - -#define LEVELING_POINT1_TEXT_FR "Premier" -#define LEVELING_POINT2_TEXT_FR "Seconde" -#define LEVELING_POINT3_TEXT_FR "Troisième" -#define LEVELING_POINT4_TEXT_FR "Quatrième" -#define LEVELING_POINT5_TEXT_FR "Cinquième" - -#define FILESYS_TEXT_FR "Fichier" -#define WIFI_TEXT_FR "WiFi" -#define FAN_TEXT_FR "Fan" -#define ABOUT_TEXT_FR "A propos" -#define BREAK_POINT_TEXT_FR "Continuer" -#define FILAMENT_TEXT_FR "Remplacer" -#define LANGUAGE_TEXT_FR "Langue" -#define MOTOR_OFF_TEXT_FR "M-hors" -#define MOTOR_OFF_XY_TEXT_FR "M-hors-XY" -#define SHUTDOWN_TEXT_FR "Eteindre" -#define MACHINE_PARA_FR "Config" -#define EEPROM_SETTINGS_FR "Eeprom Set" - -#define U_DISK_TEXT_FR "Clé usb" -#define SD_CARD_TEXT_FR "Carte SD" -#define WIFI_NAME_TEXT_FR "WiFi: " -#define WIFI_KEY_TEXT_FR "Key: " -#define WIFI_IP_TEXT_FR "IP: " -#define WIFI_AP_TEXT_FR "Etat: AP" -#define WIFI_STA_TEXT_FR "Etat: STA" -#define WIFI_CONNECTED_TEXT_FR "Connecté" -#define WIFI_DISCONNECTED_TEXT_FR "Déconnecté" -#define WIFI_EXCEPTION_TEXT_FR "Exception" -#define WIFI_RECONNECT_TEXT_FR "Reconnect" -#define CLOUD_TEXT_FR "Cloud" -#define CLOUD_BIND_FR "Lié" -#define CLOUD_UNBIND_FR "Délier" -#define CLOUD_UNBINDING_FR "Délier" -#define CLOUD_DISCONNECTED_FR "Déconnecté" -#define CLOUD_UNBINDED_FR "Délier" -#define CLOUD_BINDED_FR "Lié" -#define CLOUD_DISABLE_FR "Désactiver" - -#define FAN_ADD_TEXT_FR "Ajouter" -#define FAN_DEC_TEXT_FR "Réduire" -#define FAN_OPEN_TEXT_FR "100%" -#define FAN_HALF_TEXT_FR "50%" -#define FAN_CLOSE_TEXT_FR "0%" -#define FAN_TIPS1_TEXT_FR "ventilateur" -#define FAN_TIPS2_TEXT_FR "ventilateur\n0" - -#define FILAMENT_IN_TEXT_FR "Insérer" -#define FILAMENT_OUT_TEXT_FR "éjecter" -#define FILAMENT_EXT0_TEXT_FR "Extr1" -#define FILAMENT_EXT1_TEXT_FR "Extr2" -#define FILAMENT_HEAT_TEXT_FR "Preheat" -#define FILAMENT_STOP_TEXT_FR "Arrêter" -//#define FILAMENT_CHANGE_TEXT_FR "Filament remplacer" -#define FILAMENT_TIPS2_TEXT_FR "T:" -#define FILAMENT_TIPS3_TEXT_FR "Insérer le filament..." -#define FILAMENT_TIPS4_TEXT_FR "éjecter le filament..." -#define FILAMENT_TIPS5_TEXT_FR "Température trop basse pour démarrer, chauffez svp" -#define FILAMENT_TIPS6_TEXT_FR "Terminé" - -#if 0 - #define FILAMENT_REPLAYS_IDLE_TEXT_FR "Please click or <éjecter> \nto replace filament!" - #define FILAMENT_CHANGE_TEXT_FR "Please click or <éjecter>,\nAfter pinter pause." - #define FILAMENT_DIALOG_LOAD_HEAT_TIPS_FR "Heating up the nozzle,please wait..." - #define FILAMENT_DIALOG_UNLOAD_HEAT_TIPS_FR "Heating up the nozzle,please wait..." - #define FILAMENT_DIALOG_LOAD_CONFIRM1_TIPS_FR "Heat completed,please load filament to extruder,and click for start loading." - #define FILAMENT_DIALOG_LOAD_CONFIRM2_TIPS_FR "Please load filament to extruder,and click for start loading." - #define FILAMENT_DIALOG_UNLOAD_CONFIRM_TIPS_FR "Heat completed,please click for start unloading.!" - #define FILAMENT_DIALOG_LOADING_TIPS_FR "Is loading ,please wait!" - #define FILAMENT_DIALOG_UNLOADING_TIPS_FR "Is unloading,please wait!" - #define FILAMENT_DIALOG_LOAD_COMPLETE_TIPS_FR "Load filament completed,click for return!" - #define FILAMENT_DIALOG_UNLOAD_COMPLETE_TIPS_FR "Unload filament completed,click for return!" -#endif -#define FILAMENT_CHANGE_TEXT_FR "Please click \nor ,After \npinter pause." -#define FILAMENT_DIALOG_LOAD_HEAT_TIPS_FR "Heating up the nozzle,\nplease wait..." -#define FILAMENT_DIALOG_UNLOAD_HEAT_TIPS_FR "Heating up the nozzle,\nplease wait..." -#define FILAMENT_DIALOG_LOAD_CONFIRM1_TIPS_FR "Heat completed,please load filament \nto extruder,and click \nfor start loading." -#define FILAMENT_DIALOG_LOAD_CONFIRM2_TIPS_FR "Please load filament to extruder,\nand click for start loading." -#define FILAMENT_DIALOG_UNLOAD_CONFIRM_TIPS_FR "Heat completed,please \nclick for start unloading.!" -#define FILAMENT_DIALOG_LOADING_TIPS_FR "Is loading ,please wait!" -#define FILAMENT_DIALOG_UNLOADING_TIPS_FR "Is unloading,please wait!" -#define FILAMENT_DIALOG_LOAD_COMPLETE_TIPS_FR "Load filament completed,\nclick for return!" -#define FILAMENT_DIALOG_UNLOAD_COMPLETE_TIPS_FR "Unload filament completed,\nclick for return!" - - -#define PRE_HEAT_EXT_TEXT_FR "E" -#define PRE_HEAT_BED_TEXT_FR "Bed" - -#define FILE_LOADING_FR "Chargement......" -#if 0 - #define NO_FILE_AND_CHECK_FR "Aucun fichier trouvé! Insérez une carte SD ou un disque U!" -#else - #define NO_FILE_AND_CHECK_FR "Aucun fichier,vérifiez à nouveau!" -#endif - -#define NO_FILE_FR "Pas de fichier!" - - - -#define EXTRUDER_TEMP_TEXT_FR "Temper" -#define EXTRUDER_E_LENGTH1_TEXT_FR "Extruder1" -#define EXTRUDER_E_LENGTH2_TEXT_FR "Extruder2" -#define EXTRUDER_E_LENGTH3_TEXT_FR "Extruder3" - -#define ABOUT_TYPE_TEXT_FR "Type: " -#define ABOUT_VERSION_TEXT_FR "Firmware: " -#define ABOUT_WIFI_TEXT_FR "Wifi: " - -#define PRINTING_OPERATION_FR "Option" -#define PRINTING_PAUSE_FR "Pause" -#define PRINTING_TEMP_FR "Temp." -#define PRINTING_CHANGESPEED_FR "Speed" -#define PRINTING_RESUME_FR "Reprendre" -#define PRINTING_STOP_FR "Stop" -#define PRINTING_MORE_FR "Plus" -#define PRINTING_EXTRUDER_FR "Extruder" -#define PRINTING_MOVE_FR "Déplace" - -#define EXTRUDER_SPEED_FR "Extruder" -#define MOVE_SPEED_FR "Déplace" -#define EXTRUDER_SPEED_STATE_FR "Vitesse d'extrusion" -#define MOVE_SPEED_STATE_FR "vitesse de déplacement" -#define STEP_1PERCENT_FR "1%" -#define STEP_5PERCENT_FR "5%" -#define STEP_10PERCENT_FR "10%" - -#define TITLE_READYPRINT_FR "Prête" -#define TITLE_PREHEAT_FR "Préchauffe" -#define TITLE_MOVE_FR "Déplace" -#define TITLE_HOME_FR "Acceuil" -#define TITLE_EXTRUDE_FR "Extruder" -#define TITLE_LEVELING_FR "Leveling" -#define TITLE_SET_FR "Paramètres" -#define TITLE_MORE_FR "Plus" -#define TITLE_CHOOSEFILE_FR "Fichier" -#define TITLE_PRINTING_FR "Pimpression" -#define TITLE_OPERATION_FR "Option" -#define TITLE_ADJUST_FR "Réglage" -#define TITLE_WIRELESS_FR "Sans fil" -#define TITLE_FILAMENT_FR "Remplacer" -#define TITLE_ABOUT_FR "A propos" -#define TITLE_FAN_FR "Ventilateur" -#define TITLE_LANGUAGE_FR "Langue" -#define TITLE_PAUSE_FR "Pause" -#define TITLE_CHANGESPEED_FR "Speed" -#define TITLE_CLOUD_TEXT_FR "Cloud" -#define TITLE_DIALOG_CONFIRM_FR "Confirm" -#define TITLE_FILESYS_FR "FileSys" - -#define DIALOG_CLOSE_MACHINE_FR "Closing machine......" - -#define AUTO_SHUTDOWN_FR "Auto" -#define MANUAL_SHUTDOWN_FR "Manuel" - -#define DIALOG_CONFIRM_FR "Confirmer" -#define DIALOG_CANCLE_FR "Annuler" -#define DIALOG_OK_FR "OK" -#define DIALOG_RESET_FR "Réinitialiser" -#define DIALOG_RETRY_FR "Recommencez" -#define DIALOG_DISABLE_FR "Disable" -#define DIALOG_PRINT_MODEL_FR "Imprimer le fichier?" -#define DIALOG_CANCEL_PRINT_FR "Arrêter?" - -#define DIALOG_STOP_FR "Arrêter" -#define DIALOG_REPRINT_FROM_BREAKPOINT_FR "Continuer?" -//#define DIALOG_UNBIND_PRINTER_FR "Non lié?" -#define DIALOG_ERROR_TIPS1_FR "Erreur:error:Aucun fichier, \nvérifiez à nouveau." -#define DIALOG_ERROR_TIPS2_FR "Erreur:La opération a échoué. \nVerifiez que le baudrate de l'écran et de \nla carte mère soient identique!" -#define DIALOG_ERROR_TIPS3_FR "Erreur: le nom du fichier ou le \nchemin d'accès est trop long." -#define DIALOG_UNBIND_PRINTER_FR "Unbind the printer?" -#define DIALOG_FILAMENT_NO_PRESS_FR "Filament detection switch is not pressed" -#define DIALOG_PRINT_FINISH_FR "L'impression est terminée!" -#define DIALOG_PRINT_TIME_FR "Temps d'impression: " -#define DIALOG_REPRINT_FR "Print again" -#define DIALOG_WIFI_ENABLE_TIPS_FR "The wifi module is being configured,\nplease wait a moment....." - -#define MESSAGE_PAUSING_FR "Parking..." -#define MESSAGE_CHANGING_FR "Attente filament pour démarrer" -#define MESSAGE_UNLOAD_FR "Attente retrait du filament" -#define MESSAGE_WAITING_FR "Presser bouton,pour reprendre" -#define MESSAGE_INSERT_FR "Insérer filament et app. bouton pour continuer..." -#define MESSAGE_LOAD_FR "Attente chargement filament" -#define MESSAGE_PURGE_FR "Attente Purge filament" -#define MESSAGE_RESUME_FR "Attente reprise impression" -#define MESSAGE_HEAT_FR "Presser le bouton pour chauffer..." -#define MESSAGE_HEATING_FR "Buse en chauffe Patienter SVP..." -#define MESSAGE_OPTION_FR "Purger davantage ou continuer l'impression?" -#define MESSAGE_PURGE_MORE_FR "Purge" -#define MESSAGE_CONTINUE_PRINT_FR "Impression" -#define EEPROM_SETTINGS_TITLE_FR "Paramètres EEPROM" -#define EEPROM_SETTINGS_STORE_FR "Stocker les paramètres dans l'EEPROM" -#define EEPROM_SETTINGS_READ_FR "Lire les paramètres de l'EEPROM" -#define EEPROM_SETTINGS_REVERT_FR "Rétablir les paramètres par défaut d'usine" - -#define EEPROM_STORE_TIPS_FR "Stocker les paramètres dans l'EEPROM?" -#define EEPROM_READ_TIPS_FR "Lire les paramètres de l'EEPROM?" -#define EEPROM_REVERT_TIPS_FR "Rétablir les paramètres par défaut d'usine?" diff --git a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_ru.h b/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_ru.h deleted file mode 100644 index 9f695b376b59..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_ru.h +++ /dev/null @@ -1,277 +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 TOOL_TEXT_RU "инструмент" -#define PREHEAT_TEXT_RU " нагрев" -#define MOVE_TEXT_RU "движение" -#define HOME_TEXT_RU "домой" -#define PRINT_TEXT_RU " печать" -#define EXTRUDE_TEXT_RU "экструзия" -#define LEVELING_TEXT_RU "уровень" -#define AUTO_LEVELING_TEXT_RU "aвто" -#define SET_TEXT_RU "настройки" -#define MORE_TEXT_RU "больше" - -#define ADD_TEXT_RU "добавить" -#define DEC_TEXT_RU "уменьшить" -#define EXTRUDER_1_TEXT_RU "экструдер1" -#define EXTRUDER_2_TEXT_RU "экструдер2" -#define HEATBED_TEXT_RU "стол" -#define TEXT_1C_RU "1℃" -#define TEXT_5C_RU "5℃" -#define TEXT_10C_RU "10℃" -#define CLOSE_TEXT_RU "выкл" - -#define BACK_TEXT_RU "назад" - -#define TOOL_PREHEAT_RU "нагрев" -#define TOOL_EXTRUDE_RU "экструзия" -#define TOOL_MOVE_RU "движение" -#define TOOL_HOME_RU "домой" -#define TOOL_LEVELING_RU "уровень" -#define TOOL_AUTO_LEVELING_RU "aвто" -#define TOOL_FILAMENT_RU "замена" -#define TOOL_MORE_RU "больше" - -#define AXIS_X_ADD_TEXT_RU "X+" -#define AXIS_X_DEC_TEXT_RU "X-" -#define AXIS_Y_ADD_TEXT_RU "Y+" -#define AXIS_Y_DEC_TEXT_RU "Y-" -#define AXIS_Z_ADD_TEXT_RU "Z+" -#define AXIS_Z_DEC_TEXT_RU "Z-" -#define TEXT_01MM_RU "0.1mm" -#define TEXT_1MM_RU "1mm" -#define TEXT_10MM_RU "10mm" - -#define HOME_X_TEXT_RU "X" -#define HOME_Y_TEXT_RU "Y" -#define HOME_Z_TEXT_RU "Z" -#define HOME_ALL_TEXT_RU "Home" -#define HOME_STOPMOVE_RU "Quickstop" - -#define PAGE_UP_TEXT_RU "вверх" -#define PAGE_DOWN_TEXT_RU "вниз" - -#define EXTRUDER_IN_TEXT_RU "втянуть" -#define EXTRUDER_OUT_TEXT_RU "выдавить" -#define EXTRUDE_1MM_TEXT_RU "1mm" -#define EXTRUDE_5MM_TEXT_RU "5mm" -#define EXTRUDE_10MM_TEXT_RU "10mm" -#define EXTRUDE_LOW_SPEED_TEXT_RU "мин" -#define EXTRUDE_MEDIUM_SPEED_TEXT_RU "сред" -#define EXTRUDE_HIGH_SPEED_TEXT_RU "выс" - -#define LEVELING_POINT1_TEXT_RU "1точка" -#define LEVELING_POINT2_TEXT_RU "2точка" -#define LEVELING_POINT3_TEXT_RU "3точка" -#define LEVELING_POINT4_TEXT_RU "4точка" -#define LEVELING_POINT5_TEXT_RU "5точка" - -#define FILESYS_TEXT_RU "система" -#define WIFI_TEXT_RU "WiFi" -#define FAN_TEXT_RU "вентилятор" -#define ABOUT_TEXT_RU "инфо" -#define BREAK_POINT_TEXT_RU "продолжить" -#define FILAMENT_TEXT_RU "замена" -#define LANGUAGE_TEXT_RU "язык" -#define MOTOR_OFF_TEXT_RU "отклмотор" -#define MOTOR_OFF_XY_TEXT_RU "Off-XY" -#define SHUTDOWN_TEXT_RU "выключение" -#define MACHINE_PARA_RU "конфиг" -#define EEPROM_SETTINGS_RU "Eeprom Set" - -#define U_DISK_TEXT_RU "U диск" -#define SD_CARD_TEXT_RU "SD диск" -#define WIFI_NAME_TEXT_RU "WiFi: " -#define WIFI_KEY_TEXT_RU "пароль: " -#define WIFI_IP_TEXT_RU "IP: " -#define WIFI_AP_TEXT_RU "режим: AP" -#define WIFI_STA_TEXT_RU "режим: STA" -#define WIFI_CONNECTED_TEXT_RU "подключен" -#define WIFI_DISCONNECTED_TEXT_RU "не подключен" -#define WIFI_EXCEPTION_TEXT_RU "исключение" -#define WIFI_RECONNECT_TEXT_RU "Reconnect" -#define CLOUD_TEXT_RU "облако" -#define CLOUD_BIND_RU "соединён" -#define CLOUD_UNBIND_RU "не соединён" -#define CLOUD_UNBINDING_RU "Unbinding" -#define CLOUD_DISCONNECTED_RU "Disconnected" -#define CLOUD_UNBINDED_RU "Unbinded" -#define CLOUD_BINDED_RU "Binded" -#define CLOUD_DISABLE_RU "Disable" - -#define FAN_ADD_TEXT_RU "добавить" -#define FAN_DEC_TEXT_RU "уменьшить" -#define FAN_OPEN_TEXT_RU "100%" -#define FAN_HALF_TEXT_RU "50%" -#define FAN_CLOSE_TEXT_RU "откл" -#define FAN_TIPS1_TEXT_RU "вентилятор" -#define FAN_TIPS2_TEXT_RU "вентилятор\nоткл" - -#define FILAMENT_IN_TEXT_RU "втянуть" -#define FILAMENT_OUT_TEXT_RU "выдавить" -#define FILAMENT_EXT0_TEXT_RU "экструдер1" -#define FILAMENT_EXT1_TEXT_RU "экструдер2" -#define FILAMENT_HEAT_TEXT_RU "нагрев" -#define FILAMENT_STOP_TEXT_RU "стоп" -//#define FILAMENT_CHANGE_TEXT_RU "замена" -#define FILAMENT_TIPS2_TEXT_RU "T:" -#define FILAMENT_TIPS3_TEXT_RU "втянуть..." -#define FILAMENT_TIPS4_TEXT_RU "вядавить..." -#define FILAMENT_TIPS5_TEXT_RU "Низкая температура, \nнеобходим нагрев" -#define FILAMENT_TIPS6_TEXT_RU "завершено" - -#if 0 - #define FILAMENT_REPLAYS_IDLE_TEXT_RU "Please click <втянуть> or <выдавить> \nto replace filament!" - #define FILAMENT_CHANGE_TEXT_RU "Please click <втянуть> or <выдавить>,\nAfter pinter pause." - #define FILAMENT_DIALOG_LOAD_HEAT_TIPS_RU "Heating up the nozzle,please wait..." - #define FILAMENT_DIALOG_UNLOAD_HEAT_TIPS_RU "Heating up the nozzle,please wait..." - #define FILAMENT_DIALOG_LOAD_CONFIRM1_TIPS_RU "Heat completed,please load filament to extruder,and click <да> for start loading." - #define FILAMENT_DIALOG_LOAD_CONFIRM2_TIPS_RU "Please load filament to extruder,and click <да> for start loading." - #define FILAMENT_DIALOG_UNLOAD_CONFIRM_TIPS_RU "Heat completed,please click <да> for start unloading.!" - #define FILAMENT_DIALOG_LOADING_TIPS_RU "Is loading ,please wait!" - #define FILAMENT_DIALOG_UNLOADING_TIPS_RU "Is unloading,please wait!" - #define FILAMENT_DIALOG_LOAD_COMPLETE_TIPS_RU "Load filament completed,click <да> for return!" - #define FILAMENT_DIALOG_UNLOAD_COMPLETE_TIPS_RU "Unload filament completed,click <да> for return!" -#endif -#define FILAMENT_CHANGE_TEXT_RU "Please click \nor ,After \npinter pause." -#define FILAMENT_DIALOG_LOAD_HEAT_TIPS_RU "Heating up the nozzle,\nplease wait..." -#define FILAMENT_DIALOG_UNLOAD_HEAT_TIPS_RU "Heating up the nozzle,\nplease wait..." -#define FILAMENT_DIALOG_LOAD_CONFIRM1_TIPS_RU "Heat completed,please load filament \nto extruder,and click \nfor start loading." -#define FILAMENT_DIALOG_LOAD_CONFIRM2_TIPS_RU "Please load filament to extruder,\nand click for start loading." -#define FILAMENT_DIALOG_UNLOAD_CONFIRM_TIPS_RU "Heat completed,please \nclick for start unloading.!" -#define FILAMENT_DIALOG_LOADING_TIPS_RU "Is loading ,please wait!" -#define FILAMENT_DIALOG_UNLOADING_TIPS_RU "Is unloading,please wait!" -#define FILAMENT_DIALOG_LOAD_COMPLETE_TIPS_RU "Load filament completed,\nclick for return!" -#define FILAMENT_DIALOG_UNLOAD_COMPLETE_TIPS_RU "Unload filament completed,\nclick for return!" - - -#define PRE_HEAT_EXT_TEXT_RU "E" -#define PRE_HEAT_BED_TEXT_RU "стол" - -#define FILE_LOADING_RU "загрузка......" -#if 0 - #define NO_FILE_AND_CHECK_RU "Файлы не найдены! Вставьте SD-карту или диск U!" -#endif -#define NO_FILE_AND_CHECK_RU "нет файла,попробуйте ещё раз!" - -#define NO_FILE_RU "нет файла!" - -#define EXTRUDER_TEMP_TEXT_RU "температура" -#define EXTRUDER_E_LENGTH1_TEXT_RU "экструзия1" -#define EXTRUDER_E_LENGTH2_TEXT_RU "экструзия2" -#define EXTRUDER_E_LENGTH3_TEXT_RU "экструзия3" - -#define ABOUT_TYPE_TEXT_RU "Type: " -#define ABOUT_VERSION_TEXT_RU "Firmware: " -#define ABOUT_WIFI_TEXT_RU "WiFi: " - -#define PRINTING_OPERATION_RU "управление" -#define PRINTING_PAUSE_RU "пауза" -#define PRINTING_TEMP_RU "темп" -#define PRINTING_CHANGESPEED_RU "скорости" -#define PRINTING_RESUME_RU "возобновить" -#define PRINTING_STOP_RU "стоп" -#define PRINTING_MORE_RU "больше" -#define PRINTING_EXTRUDER_RU "экстр" -#define PRINTING_MOVE_RU "движение" - -#define EXTRUDER_SPEED_RU "экстр" -#define MOVE_SPEED_RU "движ" -#define EXTRUDER_SPEED_STATE_RU "скорость экстр" -#define MOVE_SPEED_STATE_RU "скорость движ" -#define STEP_1PERCENT_RU "1%" -#define STEP_5PERCENT_RU "5%" -#define STEP_10PERCENT_RU "10%" - -#define TITLE_READYPRINT_RU "готов к" -#define TITLE_PREHEAT_RU "движение" -#define TITLE_MOVE_RU "движение" -#define TITLE_HOME_RU "Home" -#define TITLE_EXTRUDE_RU "экструзия" -#define TITLE_LEVELING_RU "уровень" -#define TITLE_SET_RU "настройки" -#define TITLE_MORE_RU "больше" -#define TITLE_CHOOSEFILE_RU "файла" -#define TITLE_PRINTING_RU "печать" -#define TITLE_OPERATION_RU "управление" -#define TITLE_ADJUST_RU "регулировать" -#define TITLE_WIRELESS_RU "Wireless" -#define TITLE_FILAMENT_RU "замена" -#define TITLE_ABOUT_RU "инфо" -#define TITLE_FAN_RU "вентилятор" -#define TITLE_LANGUAGE_RU "язык" -#define TITLE_PAUSE_RU "пауза" -#define TITLE_CHANGESPEED_RU "скорости" -#define TILE_TOOL_RU "инструмент" -#define TITLE_CLOUD_TEXT_RU "Cloud" -#define TITLE_DIALOG_CONFIRM_RU "Confirm" -#define TITLE_FILESYS_RU "FileSys" - -#define AUTO_SHUTDOWN_RU "авто-откл" -#define MANUAL_SHUTDOWN_RU "ручн-откл" - -#define DIALOG_CONFIRM_RU "да"//"подтвердить" -#define DIALOG_CANCLE_RU "отмена" -#define DIALOG_OK_RU "да" -#define DIALOG_RESET_RU "сброс" -#define DIALOG_RETRY_RU "повтор" -#define DIALOG_DISABLE_RU "запретить" -#define DIALOG_PRINT_MODEL_RU "печать модели?" -#define DIALOG_CANCEL_PRINT_RU "стоп?" -#define DIALOG_STOP_RU "стоп" -#define DIALOG_REPRINT_FROM_BREAKPOINT_RU "продолжить?" -//#define DIALOG_UNBIND_PRINTER_RU "разрыв?" -#define DIALOG_ERROR_TIPS1_RU "ошибка:нет файла, попробуйте ещё раз." -#define DIALOG_ERROR_TIPS2_RU "ошибка:сбой передачи. установите скорость \nпередачи данных как на плате управления!" -#define DIALOG_ERROR_TIPS3_RU "ошибка: имя файла слишком длинное!" -#define DIALOG_CLOSE_MACHINE_RU "Closing machine......" -#define DIALOG_UNBIND_PRINTER_RU "Unbind the printer?" -#define DIALOG_FILAMENT_NO_PRESS_RU "Filament detection switch is not pressed" -#define DIALOG_PRINT_FINISH_RU "Печать завершена!" -#define DIALOG_PRINT_TIME_RU "Время печати: " -#define DIALOG_REPRINT_RU "Print again" -#define DIALOG_WIFI_ENABLE_TIPS_RU "The wifi module is being configured,\nplease wait a moment....." - -#define MESSAGE_PAUSING_RU "Стоянка..." -#define MESSAGE_CHANGING_RU "Подождите, пока начнется смена филамента" -#define MESSAGE_UNLOAD_RU "Дождитесь выгрузки нити" -#define MESSAGE_WAITING_RU "Нажмите кнопку,чтобы возобновить печать" -#define MESSAGE_INSERT_RU "Вставьте нить и нажмите кнопку,чтобы продолжить" -#define MESSAGE_LOAD_RU "Дождитесь загрузки нити" -#define MESSAGE_PURGE_RU "Дождитесь чистки нити" -#define MESSAGE_RESUME_RU "Подождите,пока печать возобновится ..." -#define MESSAGE_HEAT_RU "Нажмите кнопку, чтобы нагреть форсунку" -#define MESSAGE_HEATING_RU "Подогрев форсунки Пожалуйста, подождите ..." -#define MESSAGE_OPTION_RU "Очистить больше или продолжить печать?" -#define MESSAGE_PURGE_MORE_RU "чистка" -#define MESSAGE_CONTINUE_PRINT_RU "Распечатать" -#define EEPROM_SETTINGS_TITLE_RU "Настройки EEPROM" -#define EEPROM_SETTINGS_STORE_RU "Сохранение настроек в EEPROM" -#define EEPROM_SETTINGS_READ_RU "Чтение настроек из EEPROM" -#define EEPROM_SETTINGS_REVERT_RU "Восстановить заводские настройки по умолчанию" - -#define EEPROM_STORE_TIPS_RU "Сохранить настройки в EEPROM?" -#define EEPROM_READ_TIPS_RU "Читать настройки из EEPROM?" -#define EEPROM_REVERT_TIPS_RU "Revert settings to factory defaults?" diff --git a/Marlin/src/lcd/extui/lib/mks_ui/tft_lvgl_configuration.cpp b/Marlin/src/lcd/extui/lib/mks_ui/tft_lvgl_configuration.cpp deleted file mode 100644 index 5a8c4986089e..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/tft_lvgl_configuration.cpp +++ /dev/null @@ -1,525 +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 . - * - */ - -/** - * @file tft_lvgl_configuration.cpp - * @date 2020-02-21 - */ - -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "SPI_TFT.h" - -#include "tft_lvgl_configuration.h" -#include "draw_ready_print.h" - -#include "pic_manager.h" -#include "mks_hardware_test.h" -#include "draw_ui.h" -#include "SPIFlashStorage.h" -#include - -#include "../../../../MarlinCore.h" -#include "../../../../inc/MarlinConfig.h" - -#include HAL_PATH(../../HAL, tft/xpt2046.h) -#include "../../../ultralcd.h" -XPT2046 touch; - -#if ENABLED(POWER_LOSS_RECOVERY) - #include "../../../../feature/powerloss.h" -#endif - -#include - -#ifndef TFT_WIDTH - #define TFT_WIDTH 480 -#endif -#ifndef TFT_HEIGHT - #define TFT_HEIGHT 320 -#endif - -#if HAS_SPI_FLASH_FONT - extern void init_gb2312_font(); -#endif - -static lv_disp_buf_t disp_buf; -lv_group_t* g; -#if ENABLED(SDSUPPORT) - extern void UpdateAssets(); -#endif -uint16_t DeviceCode = 0x9488; -extern uint8_t sel_id; - -extern uint8_t gcode_preview_over, flash_preview_begin, default_preview_flg; - -uint8_t bmp_public_buf[17 * 1024]; - -void SysTick_Callback() { - lv_tick_inc(1); - print_time_count(); - #if ENABLED(USE_WIFI_FUNCTION) - if (tips_disp.timer == TIPS_TIMER_START) { - tips_disp.timer_count++; - } - #endif - if (uiCfg.filament_loading_time_flg == 1) { - uiCfg.filament_loading_time_cnt++; - uiCfg.filament_rate = (uint32_t)(((uiCfg.filament_loading_time_cnt / (uiCfg.filament_loading_time * 1000.0)) * 100.0) + 0.5); - if (uiCfg.filament_loading_time_cnt >= (uiCfg.filament_loading_time * 1000)) { - uiCfg.filament_loading_time_cnt = 0; - uiCfg.filament_loading_time_flg = 0; - uiCfg.filament_loading_completed = 1; - } - } - if (uiCfg.filament_unloading_time_flg == 1) { - uiCfg.filament_unloading_time_cnt++; - uiCfg.filament_rate = (uint32_t)(((uiCfg.filament_unloading_time_cnt / (uiCfg.filament_unloading_time * 1000.0)) * 100.0) + 0.5); - if (uiCfg.filament_unloading_time_cnt >= (uiCfg.filament_unloading_time * 1000)) { - uiCfg.filament_unloading_time_cnt = 0; - uiCfg.filament_unloading_time_flg = 0; - uiCfg.filament_unloading_completed = 1; - uiCfg.filament_rate = 100; - } - } -} - -extern uint8_t bmp_public_buf[17 * 1024]; - -void tft_lvgl_init() { - - //uint16_t test_id=0; - W25QXX.init(SPI_QUARTER_SPEED); - //test_id=W25QXX.W25QXX_ReadID(); - - gCfgItems_init(); - ui_cfg_init(); - disp_language_init(); - - //init tft first! - SPI_TFT.spi_init(SPI_FULL_SPEED); - SPI_TFT.LCD_init(); - - //spi_flash_read_test(); - #if ENABLED(SDSUPPORT) - watchdog_refresh(); - UpdateAssets(); - #endif - - watchdog_refresh(); - mks_test_get(); - - touch.Init(); - - lv_init(); - - lv_disp_buf_init(&disp_buf, bmp_public_buf, NULL, LV_HOR_RES_MAX * 18); /*Initialize the display buffer*/ - - lv_disp_drv_t disp_drv; /*Descriptor of a display driver*/ - lv_disp_drv_init(&disp_drv); /*Basic initialization*/ - disp_drv.flush_cb = my_disp_flush; /*Set your driver function*/ - disp_drv.buffer = &disp_buf; /*Assign the buffer to the display*/ - lv_disp_drv_register(&disp_drv); /*Finally register the driver*/ - - lv_indev_drv_t indev_drv; - lv_indev_drv_init(&indev_drv); /*Descriptor of a input device driver*/ - indev_drv.type = LV_INDEV_TYPE_POINTER; /*Touch pad is a pointer-like device*/ - indev_drv.read_cb = my_touchpad_read; /*Set your driver function*/ - lv_indev_drv_register(&indev_drv); /*Finally register the driver*/ - - #if HAS_ROTARY_ENCODER - g = lv_group_create(); - lv_indev_drv_t enc_drv; - lv_indev_drv_init(&enc_drv); - enc_drv.type = LV_INDEV_TYPE_ENCODER; - enc_drv.read_cb = my_mousewheel_read; - lv_indev_t * enc_indev = lv_indev_drv_register(&enc_drv); - lv_indev_set_group(enc_indev, g); - #endif - - lv_fs_drv_t spi_flash_drv; - lv_fs_drv_init(&spi_flash_drv); - spi_flash_drv.letter = 'F'; - spi_flash_drv.open_cb = spi_flash_open_cb; - spi_flash_drv.close_cb = spi_flash_close_cb; - spi_flash_drv.read_cb = spi_flash_read_cb; - spi_flash_drv.seek_cb = spi_flash_seek_cb; - spi_flash_drv.tell_cb = spi_flash_tell_cb; - lv_fs_drv_register(&spi_flash_drv); - - lv_fs_drv_t sd_drv; - lv_fs_drv_init(&sd_drv); - sd_drv.letter = 'S'; - sd_drv.open_cb = sd_open_cb; - sd_drv.close_cb = sd_close_cb; - sd_drv.read_cb = sd_read_cb; - sd_drv.seek_cb = sd_seek_cb; - sd_drv.tell_cb = sd_tell_cb; - lv_fs_drv_register(&sd_drv); - - systick_attach_callback(SysTick_Callback); - - #if HAS_SPI_FLASH_FONT - init_gb2312_font(); - #endif - - tft_style_init(); - - filament_pin_setup(); - - lv_encoder_pin_init(); - - #if ENABLED(POWER_LOSS_RECOVERY) - recovery.load(); - if (recovery.valid()) { - if (gCfgItems.from_flash_pic == 1) - flash_preview_begin = 1; - else - default_preview_flg = 1; - - uiCfg.print_state = REPRINTING; - - ZERO(public_buf_m); - strncpy(public_buf_m, recovery.info.sd_filename, sizeof(public_buf_m)); - card.printLongPath(public_buf_m); - - strncpy(list_file.long_name[sel_id], card.longFilename, sizeof(list_file.long_name[sel_id])); - - lv_draw_printing(); - } - else - #endif - lv_draw_ready_print(); - - if (mks_test_flag == 0x1E) - mks_gpio_test(); -} - -void my_disp_flush(lv_disp_drv_t * disp, const lv_area_t * area, lv_color_t * color_p) { - uint16_t i, width, height; - - width = area->x2 - area->x1 + 1; - height = area->y2 - area->y1 + 1; - - SPI_TFT.setWindow((uint16_t)area->x1, (uint16_t)area->y1, width, height); - for (i = 0; i < height; i++) { - SPI_TFT.tftio.WriteSequence((uint16_t*)(color_p + width * i), width); - } - lv_disp_flush_ready(disp); /* Indicate you are ready with the flushing*/ - - 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)); -} - -static bool get_point(int16_t *x, int16_t *y) { - bool is_touched = touch.getRawPoint(x, y); - - if (is_touched) { - *x = int16_t((int32_t(*x) * XPT2046_X_CALIBRATION) >> 16) + XPT2046_X_OFFSET; - *y = int16_t((int32_t(*y) * XPT2046_Y_CALIBRATION) >> 16) + XPT2046_Y_OFFSET; - } - - #if (TFT_ROTATION & TFT_ROTATE_180) - *x = int16_t((TFT_WIDTH) - (int)(*x)); - *y = int16_t((TFT_HEIGHT) - (int)(*y)); - #endif - - return is_touched; -} - -bool my_touchpad_read(lv_indev_drv_t * indev_driver, lv_indev_data_t * data) { - static int16_t last_x = 0, last_y = 0; - static uint8_t last_touch_state = LV_INDEV_STATE_REL; - static int32_t touch_time1 = 0; - uint32_t tmpTime, diffTime = 0; - - tmpTime = millis(); - diffTime = getTickDiff(tmpTime, touch_time1); - /*Save the state and save the pressed coordinate*/ - //data->state = TOUCH_PressValid(last_x, last_y) ? LV_INDEV_STATE_PR : LV_INDEV_STATE_REL; - //if (data->state == LV_INDEV_STATE_PR) ADS7843_Rd_Addata((u16 *)&last_x, (u16 *)&last_y); - //touchpad_get_xy(&last_x, &last_y); - /*Save the pressed coordinates and the state*/ - if (diffTime > 20) { - if (get_point(&last_x, &last_y)) { - - if (last_touch_state == LV_INDEV_STATE_PR) return false; - data->state = LV_INDEV_STATE_PR; - - // Set the coordinates (if released use the last-pressed coordinates) - - data->point.x = last_x; - data->point.y = last_y; - - last_x = last_y = 0; - last_touch_state = LV_INDEV_STATE_PR; - } - else { - if (last_touch_state == LV_INDEV_STATE_PR) - data->state = LV_INDEV_STATE_REL; - last_touch_state = LV_INDEV_STATE_REL; - } - - touch_time1 = tmpTime; - } - - return false; // Return `false` since no data is buffering or left to read -} - -int16_t enc_diff = 0; -lv_indev_state_t state = LV_INDEV_STATE_REL; - -bool my_mousewheel_read(lv_indev_drv_t * indev_drv, lv_indev_data_t * data) { - (void) indev_drv; /*Unused*/ - - data->state = state; - data->enc_diff = enc_diff; - enc_diff = 0; - - return false; /*No more data to read so return false*/ -} - -extern uint8_t currentFlashPage; - -//spi_flash -uint32_t pic_read_base_addr = 0, pic_read_addr_offset = 0; -lv_fs_res_t spi_flash_open_cb (lv_fs_drv_t * drv, void * file_p, const char * path, lv_fs_mode_t mode) { - static char last_path_name[30]; - if (strcasecmp(last_path_name,path) != 0) { - pic_read_base_addr = lv_get_pic_addr((uint8_t *)path); - ZERO(last_path_name); - strcpy(last_path_name,path); - } - else { - W25QXX.init(SPI_QUARTER_SPEED); - currentFlashPage = 0; - } - pic_read_addr_offset = pic_read_base_addr; - return LV_FS_RES_OK; -} - -lv_fs_res_t spi_flash_close_cb (lv_fs_drv_t * drv, void * file_p) { - lv_fs_res_t res = LV_FS_RES_OK; - /* Add your code here*/ - pic_read_addr_offset = pic_read_base_addr; - return res; -} - -lv_fs_res_t spi_flash_read_cb (lv_fs_drv_t * drv, void * file_p, void * buf, uint32_t btr, uint32_t * br) { - lv_pic_test((uint8_t *)buf, pic_read_addr_offset, btr); - *br = btr; - return LV_FS_RES_OK; -} - -lv_fs_res_t spi_flash_seek_cb(lv_fs_drv_t * drv, void * file_p, uint32_t pos) { - #if HAS_SPI_FLASH_COMPRESSION - if (pos == 4) { - uint8_t bmp_header[4]; - SPIFlash.beginRead(pic_read_base_addr); - SPIFlash.readData(bmp_header, 4); - currentFlashPage = 1; - } - pic_read_addr_offset = pic_read_base_addr; - #else - pic_read_addr_offset = pic_read_base_addr + pos; - #endif - return LV_FS_RES_OK; -} - -lv_fs_res_t spi_flash_tell_cb(lv_fs_drv_t * drv, void * file_p, uint32_t * pos_p) { - *pos_p = pic_read_addr_offset - pic_read_base_addr; - return LV_FS_RES_OK; -} - -//sd -char *cur_namefff; -uint32_t sd_read_base_addr = 0,sd_read_addr_offset = 0; -lv_fs_res_t sd_open_cb (lv_fs_drv_t * drv, void * file_p, const char * path, lv_fs_mode_t mode) { - //cur_namefff = strrchr(path, '/'); - char name_buf[100]; - ZERO(name_buf); - strcat(name_buf,"/"); - strcat(name_buf,path); - char *temp = strstr(name_buf,".bin"); - if (temp) { strcpy(temp,".GCO"); } - sd_read_base_addr = lv_open_gcode_file((char *)name_buf); - sd_read_addr_offset = sd_read_base_addr; - if (sd_read_addr_offset == 0) return LV_FS_RES_NOT_EX; - return LV_FS_RES_OK; -} - -lv_fs_res_t sd_close_cb (lv_fs_drv_t * drv, void * file_p) { - /* Add your code here*/ - lv_close_gcode_file(); - return LV_FS_RES_OK; -} - -lv_fs_res_t sd_read_cb (lv_fs_drv_t * drv, void * file_p, void * buf, uint32_t btr, uint32_t * br) { - if (btr == 200) { - lv_gcode_file_read((uint8_t *)buf); - //pic_read_addr_offset += 208; - *br = 200; - } - else if (btr == 4) { - uint8_t header_pic[4] = { 0x04, 0x90, 0x81, 0x0C }; - memcpy(buf, header_pic, 4); - //pic_read_addr_offset += 4; - *br = 4; - } - return LV_FS_RES_OK; -} - -lv_fs_res_t sd_seek_cb(lv_fs_drv_t * drv, void * file_p, uint32_t pos) { - sd_read_addr_offset = sd_read_base_addr + (pos - 4) / 200 * 409; - lv_gcode_file_seek(sd_read_addr_offset); - return LV_FS_RES_OK; -} - -lv_fs_res_t sd_tell_cb(lv_fs_drv_t * drv, void * file_p, uint32_t * pos_p) { - if (sd_read_addr_offset) *pos_p = 0; - else *pos_p = (sd_read_addr_offset - sd_read_base_addr) / 409 * 200 + 4; - return LV_FS_RES_OK; -} - -void lv_encoder_pin_init() { - #if 1 // HAS_DIGITAL_BUTTONS - - #if BUTTON_EXISTS(EN1) - SET_INPUT_PULLUP(BTN_EN1); - #endif - #if BUTTON_EXISTS(EN2) - SET_INPUT_PULLUP(BTN_EN2); - #endif - #if BUTTON_EXISTS(ENC) - SET_INPUT_PULLUP(BTN_ENC); - #endif - - #if BUTTON_EXISTS(BACK) - SET_INPUT_PULLUP(BTN_BACK); - #endif - - #if BUTTON_EXISTS(UP) - SET_INPUT(BTN_UP); - #endif - #if BUTTON_EXISTS(DWN) - SET_INPUT(BTN_DWN); - #endif - #if BUTTON_EXISTS(LFT) - SET_INPUT(BTN_LFT); - #endif - #if BUTTON_EXISTS(RT) - SET_INPUT(BTN_RT); - #endif - - #endif // HAS_DIGITAL_BUTTONS -} - -#if 1 // HAS_ENCODER_ACTION - - //static const int8_t encoderDirection = 1; - //static int16_t enc_Direction; - void lv_update_encoder() { - static uint32_t encoder_time1; - uint32_t tmpTime, diffTime = 0; - tmpTime = millis(); - diffTime = getTickDiff(tmpTime, encoder_time1); - if (diffTime > 50) { - - #if HAS_ENCODER_WHEEL - - #if ANY_BUTTON(EN1, EN2, ENC, BACK) - - uint8_t newbutton = 0; - - #if BUTTON_EXISTS(EN1) - if (BUTTON_PRESSED(EN1)) newbutton |= EN_A; - #endif - #if BUTTON_EXISTS(EN2) - if (BUTTON_PRESSED(EN2)) newbutton |= EN_B; - #endif - #if BUTTON_EXISTS(ENC) - if (BUTTON_PRESSED(ENC)) newbutton |= EN_C; - #endif - #if BUTTON_EXISTS(BACK) - if (BUTTON_PRESSED(BACK)) newbutton |= EN_D; - #endif - - #else - - constexpr uint8_t newbutton = 0; - - #endif - - static uint8_t buttons = 0; - buttons = newbutton; - static uint8_t lastEncoderBits; - - #define encrot0 0 - #define encrot1 1 - #define encrot2 2 - - // Manage encoder rotation - //#define ENCODER_SPIN(_E1, _E2) switch (lastEncoderBits) { case _E1: enc_Direction += encoderDirection; break; case _E2: enc_Direction -= encoderDirection; } - - uint8_t enc = 0; - if (buttons & EN_A) enc |= B01; - if (buttons & EN_B) enc |= B10; - if (enc != lastEncoderBits) { - switch (enc) { - case encrot1: - if (lastEncoderBits == encrot0) { - enc_diff--; - encoder_time1 = tmpTime; - } - break; - case encrot2: - if (lastEncoderBits == encrot0) { - enc_diff++; - encoder_time1 = tmpTime; - } - break; - } - lastEncoderBits = enc; - } - static uint8_t last_button_state = LV_INDEV_STATE_REL; - const uint8_t enc_c = (buttons & EN_C) ? LV_INDEV_STATE_PR : LV_INDEV_STATE_REL; - if (enc_c != last_button_state) { - state = enc_c ? LV_INDEV_STATE_PR : LV_INDEV_STATE_REL; - - last_button_state = enc_c; - } - - #endif // HAS_ENCODER_WHEEL - - } // next_button_update_ms - } - -#endif // HAS_ENCODER_ACTION - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/tft_lvgl_configuration.h b/Marlin/src/lcd/extui/lib/mks_ui/tft_lvgl_configuration.h deleted file mode 100644 index 727ab33aea30..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/tft_lvgl_configuration.h +++ /dev/null @@ -1,65 +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 - -/** - * @file lcd/extui/lib/mks_ui/tft_lvgl_configuration.h - * @date 2020-02-21 - */ - -#ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ -#endif - -#include - -//#define TFT_ROTATION TFT_ROTATE_180 -#define USE_WIFI_FUNCTION 0 - -extern void tft_lvgl_init(); -extern void my_disp_flush(lv_disp_drv_t * disp, const lv_area_t * area, lv_color_t * color_p); -extern bool my_touchpad_read(lv_indev_drv_t * indev_driver, lv_indev_data_t * data); -extern bool my_mousewheel_read(lv_indev_drv_t * indev_drv, lv_indev_data_t * data); - -extern void LCD_Clear(uint16_t Color); -extern void tft_set_point(uint16_t x, uint16_t y, uint16_t point); -extern void LCD_setWindowArea(uint16_t StartX, uint16_t StartY, uint16_t width, uint16_t heigh); -extern void LCD_WriteRAM_Prepare(void); -extern void lcd_draw_logo(); -extern void lv_encoder_pin_init(); -extern void lv_update_encoder(); - -extern lv_fs_res_t spi_flash_open_cb (lv_fs_drv_t * drv, void * file_p, const char * path, lv_fs_mode_t mode); -extern lv_fs_res_t spi_flash_close_cb (lv_fs_drv_t * drv, void * file_p); -extern lv_fs_res_t spi_flash_read_cb (lv_fs_drv_t * drv, void * file_p, void * buf, uint32_t btr, uint32_t * br); -extern lv_fs_res_t spi_flash_seek_cb(lv_fs_drv_t * drv, void * file_p, uint32_t pos); -extern lv_fs_res_t spi_flash_tell_cb(lv_fs_drv_t * drv, void * file_p, uint32_t * pos_p); - -extern lv_fs_res_t sd_open_cb (lv_fs_drv_t * drv, void * file_p, const char * path, lv_fs_mode_t mode); -extern lv_fs_res_t sd_close_cb (lv_fs_drv_t * drv, void * file_p); -extern lv_fs_res_t sd_read_cb (lv_fs_drv_t * drv, void * file_p, void * buf, uint32_t btr, uint32_t * br); -extern lv_fs_res_t sd_seek_cb(lv_fs_drv_t * drv, void * file_p, uint32_t pos); -extern lv_fs_res_t sd_tell_cb(lv_fs_drv_t * drv, void * file_p, uint32_t * pos_p); - -#ifdef __cplusplus - } /* C-declarations for C++ */ -#endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/wifiSerial.cpp b/Marlin/src/lcd/extui/lib/mks_ui/wifiSerial.cpp deleted file mode 100644 index 01c86ad7cb47..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/wifiSerial.cpp +++ /dev/null @@ -1,120 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "draw_ui.h" -#include "wifiSerial.h" - -#if ENABLED(USE_WIFI_FUNCTION) - -#include -#include -#include -#include -#include - -#include "../../../../MarlinCore.h" - -DEFINE_WFSERIAL(WifiSerial1, 1); - -WifiSerial::WifiSerial(usart_dev *usart_device, uint8 tx_pin, uint8 rx_pin) { - this->usart_device = usart_device; - this->tx_pin = tx_pin; - this->rx_pin = rx_pin; -} - -/** - * Set up / tear down - */ -#if STM32_MCU_SERIES == STM32_SERIES_F1 - /* F1 MCUs have no GPIO_AFR[HL], so turn off PWM if there's a conflict - * on this GPIO bit. */ - static void disable_timer_if_necessary(timer_dev *dev, uint8 ch) { - if (dev != nullptr) timer_set_mode(dev, ch, TIMER_DISABLED); - } -#elif STM32_MCU_SERIES == STM32_SERIES_F2 || STM32_MCU_SERIES == STM32_SERIES_F4 - #define disable_timer_if_necessary(dev, ch) ((void)0) -#else - #warning "Unsupported STM32 series; timer conflicts are possible" -#endif - -void WifiSerial::begin(uint32 baud) { begin(baud, SERIAL_8N1); } - -/** - * Roger Clark. - * Note. The config parameter is not currently used. This is a work in progress. - * Code needs to be written to set the config of the hardware serial control register in question. - */ - -void WifiSerial::begin(uint32 baud, uint8_t config) { - //ASSERT(baud <= this->usart_device->max_baud); // Roger Clark. Assert doesn't do anything useful, we may as well save the space in flash and ram etc - - if (baud > this->usart_device->max_baud) return; - - const stm32_pin_info *txi = &PIN_MAP[this->tx_pin], - *rxi = &PIN_MAP[this->rx_pin]; - - disable_timer_if_necessary(txi->timer_device, txi->timer_channel); - - usart_init(this->usart_device); - - // Reinitialize the receive buffer, mks_esp8266 fixed data frame length is 1k bytes - rb_init(this->usart_device->rb, WIFI_RX_BUF_SIZE, wifiRxBuf); - - usart_config_gpios_async(this->usart_device, - rxi->gpio_device, rxi->gpio_bit, - txi->gpio_device, txi->gpio_bit, - config); - usart_set_baud_rate(this->usart_device, USART_USE_PCLK, baud); - usart_enable(this->usart_device); -} - -void WifiSerial::end(void) { - usart_disable(this->usart_device); -} - -int WifiSerial::available(void) { - return usart_data_available(this->usart_device); -} - -// -// I/O -// - -int WifiSerial::read(void) { - if (usart_data_available(usart_device) <= 0) return -1; - return usart_getc(usart_device); -} - -int WifiSerial::write(unsigned char ch) { - usart_putc(this->usart_device, ch); - return 1; -} - -int WifiSerial::wifi_rb_is_full(void) { - return rb_is_full(this->usart_device->rb); -} - -#endif // USE_WIFI_FUNCTION -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/wifiSerial.h b/Marlin/src/lcd/extui/lib/mks_ui/wifiSerial.h deleted file mode 100644 index 9d3946fee79b..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/wifiSerial.h +++ /dev/null @@ -1,102 +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 - -#include "tft_lvgl_configuration.h" - -#if ENABLED(USE_WIFI_FUNCTION) - -#if SERIAL_PORT_2 != -1 - #error "SERIAL_PORT_2 must be set to -1 with HAS_TFT_LVGL_UI and USE_WIFI_FUNCTION." -#endif - -#define WIFI_BAUDRATE 115200 -#define WIFI_UPLOAD_BAUDRATE 1958400 -#define USART_SAFE_INSERT - -#define WIFI_RX_BUF_SIZE (1024+1) - -#include -#include -#include -#include -#include -#include - -#define DEFINE_WFSERIAL(name, n)\ - WifiSerial name(USART##n, \ - BOARD_USART##n##_TX_PIN, \ - BOARD_USART##n##_RX_PIN) - -class WifiSerial { - public: - uint8 wifiRxBuf[WIFI_RX_BUF_SIZE]; - - public: - WifiSerial(struct usart_dev *usart_device, uint8 tx_pin, uint8 rx_pin); - - /* Set up/tear down */ - void begin(uint32 baud); - void begin(uint32 baud,uint8_t config); - void end(); - int available(void); - int read(void); - int write(uint8_t); - inline void wifi_usart_irq(usart_reg_map *regs) { - /* Handling RXNEIE and TXEIE interrupts. - * RXNE signifies availability of a byte in DR. - * - * See table 198 (sec 27.4, p809) in STM document RM0008 rev 15. - * We enable RXNEIE. - */ - if ((regs->CR1 & USART_CR1_RXNEIE) && (regs->SR & USART_SR_RXNE)) { - #ifdef USART_SAFE_INSERT - /* If the buffer is full and the user defines USART_SAFE_INSERT, - * ignore new bytes. */ - rb_safe_insert(this->usart_device->rb, (uint8)regs->DR); - #else - /* By default, push bytes around in the ring buffer. */ - rb_push_insert(this->usart_device->rb, (uint8)regs->DR); - #endif - } - /* TXE signifies readiness to send a byte to DR. */ - if ((regs->CR1 & USART_CR1_TXEIE) && (regs->SR & USART_SR_TXE)) { - if (!rb_is_empty(this->usart_device->wb)) - regs->DR=rb_remove(this->usart_device->wb); - else - regs->CR1 &= ~((uint32)USART_CR1_TXEIE); // disable TXEIE - } - } - - int wifi_rb_is_full(void); - - private: - struct usart_dev *usart_device; - uint8 tx_pin; - uint8 rx_pin; -}; - -extern WifiSerial WifiSerial1; - -#define WIFISERIAL WifiSerial1 - -#endif // USE_WIFI_FUNCTION diff --git a/Marlin/src/lcd/extui/lib/mks_ui/wifi_module.cpp b/Marlin/src/lcd/extui/lib/mks_ui/wifi_module.cpp deleted file mode 100644 index f5d954792ead..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/wifi_module.cpp +++ /dev/null @@ -1,1927 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "draw_ui.h" -#include "wifi_module.h" -#include "wifi_upload.h" - -#if ENABLED(USE_WIFI_FUNCTION) - -#include "../../../../MarlinCore.h" -#include "../../../../module/temperature.h" -#include "../../../../gcode/queue.h" -#include "../../../../gcode/gcode.h" -#include "../../../../lcd/ultralcd.h" -#include "../../../../sd/cardreader.h" -#include "../../../../module/planner.h" -#if ENABLED(POWER_LOSS_RECOVERY) - #include "../../../../feature/powerloss.h" -#endif -#if ENABLED(PARK_HEAD_ON_PAUSE) - #include "../../../../feature/pause.h" -#endif - -#define WIFI_SET() WRITE(WIFI_RESET_PIN, HIGH); -#define WIFI_RESET() WRITE(WIFI_RESET_PIN, LOW); -#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); - -extern uint8_t commands_in_queue; -extern uint8_t sel_id; - -int usartFifoAvailable(SZ_USART_FIFO *fifo); -int readUsartFifo(SZ_USART_FIFO *fifo, int8_t *buf, int32_t len); -int writeUsartFifo(SZ_USART_FIFO * fifo, int8_t * buf, int32_t len); -extern unsigned int getTickDiff(unsigned int curTick, unsigned int lastTick); - -volatile SZ_USART_FIFO WifiRxFifo; - -#define WAIT_ESP_TRANS_TIMEOUT_TICK 10500 - -int cfg_cloud_flag = 0; - -extern PRINT_TIME print_time; - -char wifi_firm_ver[20] = {0}; -WIFI_GCODE_BUFFER espGcodeFifo; -extern uint8_t pause_resum; - -uint8_t wifi_connect_flg = 0; -extern volatile uint8_t get_temp_flag; - - -#define WIFI_MODE 2 -#define WIFI_AP_MODE 3 - -int upload_result = 0; - -uint32_t upload_time = 0; -uint32_t upload_size = 0; - -volatile WIFI_STATE wifi_link_state; -WIFI_PARA wifiPara; -IP_PARA ipPara; -CLOUD_PARA cloud_para; - -char wifi_check_time = 0; - -extern uint8_t gCurDir[100]; - -extern uint32_t wifi_loop_cycle; - -volatile TRANSFER_STATE esp_state; - -uint8_t left_to_send = 0; -uint8_t left_to_save[96] = {0}; - -volatile WIFI_DMA_RCV_FIFO wifiDmaRcvFifo; - -volatile WIFI_TRANS_ERROR wifiTransError; - -static bool need_ok_later = false; - -extern volatile WIFI_STATE wifi_link_state; -extern WIFI_PARA wifiPara; -extern IP_PARA ipPara; -extern CLOUD_PARA cloud_para; - -extern uint8_t once_flag; -extern uint8_t flash_preview_begin; -extern uint8_t default_preview_flg; -extern uint8_t gcode_preview_over; - -extern uint8_t bmp_public_buf[17 * 1024]; - -uint32_t getWifiTick() { - return millis(); -} - -uint32_t getWifiTickDiff(int32_t lastTick, int32_t curTick) { - if (lastTick <= curTick) { - return (curTick - lastTick) * TICK_CYCLE; - } - else { - return (0xFFFFFFFF - lastTick + curTick) * TICK_CYCLE; - } -} - -void wifi_delay(int n) { - uint32_t begin = getWifiTick(); - uint32_t end = begin; - - while (getWifiTickDiff(begin, end) < (uint32_t)n) { - end = getWifiTick(); - } -} - -void wifi_reset() { - uint32_t start, now; - start = getWifiTick(); - now = start; - WIFI_RESET(); - while (getWifiTickDiff(start, now) < 500) { - now = getWifiTick(); - } - WIFI_SET(); - -} - -void mount_file_sys(uint8_t disk_type) { - if (disk_type == FILE_SYS_SD) { - card.mount(); - } - else if (disk_type == FILE_SYS_USB) { - - } -} - -static void dma_init() { - #if 0 - __HAL_RCC_DMA1_CLK_ENABLE(); - - //HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITYGROUP_0); - HAL_NVIC_SetPriority(DMA1_Channel5_IRQn, 4, 0); - HAL_NVIC_EnableIRQ(DMA1_Channel5_IRQn); - - hdma_usart1_rx.Instance = DMA1_Channel5; - //hdma_usart1_rx.Init.Channel = DMA_CHANNEL_4; - hdma_usart1_rx.Init.Direction = DMA_PERIPH_TO_MEMORY; - hdma_usart1_rx.Init.PeriphInc = DMA_PINC_DISABLE; - hdma_usart1_rx.Init.MemInc = DMA_MINC_ENABLE; - hdma_usart1_rx.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE; - hdma_usart1_rx.Init.MemDataAlignment = DMA_PDATAALIGN_BYTE; - hdma_usart1_rx.Init.Mode = DMA_NORMAL; - hdma_usart1_rx.Init.Priority = DMA_PRIORITY_VERY_HIGH; - if (HAL_DMA_Init((DMA_HandleTypeDef *)&hdma_usart1_rx) != HAL_OK) { - Error_Handler(); - } - - - HAL_DMA_Start_IT((DMA_HandleTypeDef *)&hdma_usart1_rx, - (uint32_t)&huart1.Instance->DR, - (uint32_t)(&WifiRxFifo.uartTxBuffer[0]), - UART_RX_BUFFER_SIZE); - - //HAL_UART_Receive_DMA(&huart1,(uint8_t*)&WifiRxFifo.uartTxBuffer[0], UART_RX_BUFFER_SIZE); - - /* Enable the DMA transfer for the receiver request by setting the DMAR bit - in the UART CR3 register */ - SET_BIT(huart1.Instance->CR3, USART_CR3_DMAR); - - #endif - for (uint8_t i = 0; i < TRANS_RCV_FIFO_BLOCK_NUM; i++) { - wifiDmaRcvFifo.bufferAddr[i] = &bmp_public_buf[1024 * i]; - wifiDmaRcvFifo.state[i] = udisk_buf_empty; - } - - memset(wifiDmaRcvFifo.bufferAddr[0], 0, 1024 * TRANS_RCV_FIFO_BLOCK_NUM); - wifiDmaRcvFifo.read_cur = 0; - wifiDmaRcvFifo.write_cur = 0; - -} - -static void wifi_deInit() { - #if 0 - HAL_DMA_Abort((DMA_HandleTypeDef *)&hdma_usart1_rx); - HAL_DMA_DeInit((DMA_HandleTypeDef *)&hdma_usart1_rx); - __HAL_DMA_DISABLE((DMA_HandleTypeDef *)&hdma_usart1_rx); - #endif -} - -extern uint8_t mksUsart1Rx; - -void esp_port_begin(uint8_t interrupt) { - WifiRxFifo.uart_read_point = 0; - WifiRxFifo.uart_write_point = 0; - #if 0 - NVIC_InitTypeDef NVIC_InitStructure; - - USART_InitTypeDef USART_InitStructure; - GPIO_InitTypeDef GPIO_InitStruct; - - WifiRxFifo.uart_read_point = 0; - WifiRxFifo.uart_write_point = 0; - memset((uint8_t*)WifiRxFifo.uartTxBuffer, 0, sizeof(WifiRxFifo.uartTxBuffer)); - - if (interrupt) { - #if TAN - wifi_deInit (); - - //SZ_STM32_COMInit(COM1, 115200); - __HAL_UART_ENABLE_IT(USART1, USART_IT_RXNE); - - USART_InitStructure.USART_BaudRate = 115200; //���ڵIJ����ʣ�����115200 ��ߴ�4.5Mbits/s - USART_InitStructure.USART_WordLength = USART_WordLength_8b; //�����ֳ���(8λ��9λ) - USART_InitStructure.USART_StopBits = USART_StopBits_1; //�����õ�ֹͣλ-֧��1��2��ֹͣλ - USART_InitStructure.USART_Parity = USART_Parity_No; //����żУ�� - USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None; //��Ӳ�������� - USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx; //˫��ģʽ��ʹ�ܷ��ͺͽ��� - - __HAL_RCC_USART1_CLK_ENABLE(); - - GPIO_InitStruct.Pin = TFT_WIFI_TX_Pin|TFT_WIFI_RX_Pin; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; - GPIO_InitStruct.Alternate = GPIO_AF7_USART1; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pin = TFT_WIFI_RX_Pin; - HAL_GPIO_Init(GPIOA,&GPIO_InitStruct); - - USART_Init(USART1, &USART_InitStructure); - - NVIC_InitStructure.NVIC_IRQChannel = USART1_IRQn; - // NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0; - // NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 3; - NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; - NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; - - NVIC_Init(&NVIC_InitStructure); - #else - HAL_UART_DeInit(&huart1); - MX_USART1_UART_Init(3); - //__HAL_UART_ENABLE_IT(&huart1, UART_IT_RXNE); - HAL_UART_Receive_IT(&huart1,&mksUsart1Rx,1); - #endif - } - else{ - #if 0 - NVIC_DisableIRQ(SZ_STM32_COM1_IRQn); - - USART_Cmd(SZ_STM32_COM1, DISABLE); - - RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, DISABLE); - RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE); - - SZ_STM32_COMInit(COM1, 1958400); - - USART_Cmd(SZ_STM32_COM1, ENABLE); - - wifi_delay(10); - - dma_init(); - #endif - HAL_UART_DeInit(&huart1); - MX_USART1_UART_Init(5); - //dma1_5_IRQ_sel = 1; - dma_init(); - } - #endif - if (interrupt) { - #if ENABLED(USE_WIFI_FUNCTION) - WIFISERIAL.end(); - for (uint16_t i = 0; i < 65535; i++); - WIFISERIAL.begin(WIFI_BAUDRATE); - uint32_t serial_connect_timeout = millis() + 1000UL; - while (/*!WIFISERIAL && */PENDING(millis(), serial_connect_timeout)) { /*nada*/ } - //for(uint8_t i=0;i<100;i++)WIFISERIAL.write(0x33); - #endif - } - else { - #if ENABLED(USE_WIFI_FUNCTION) - WIFISERIAL.end(); - for (uint16_t i = 0; i < 65535; i++); - WIFISERIAL.begin(WIFI_UPLOAD_BAUDRATE); - uint32_t serial_connect_timeout = millis() + 1000UL; - while (/*!WIFISERIAL && */PENDING(millis(), serial_connect_timeout)) { /*nada*/ } - //for(uint16_t i=0;i<65535;i++);//WIFISERIAL.write(0x33); - #endif - dma_init(); - } -} - -#if ENABLED(USE_WIFI_FUNCTION) - -int raw_send_to_wifi(char *buf, int len) { - if (buf == 0 || len <= 0) return 0; - - for (int i = 0; i < len; i++) - WIFISERIAL.write(*(buf + i)); - - return len; -} - -#endif // USE_WIFI_FUNCTION - -void wifi_ret_ack() {} - -char buf_to_wifi[256]; -int index_to_wifi = 0; -int package_to_wifi(WIFI_RET_TYPE type,char *buf, int len) { - char wifi_ret_head = 0xA5; - char wifi_ret_tail = 0xFC; - - if (type == WIFI_PARA_SET) { - int data_offset = 4; - int apLen = strlen((const char *)uiCfg.wifi_name); - int keyLen = strlen((const char *)uiCfg.wifi_key); - - memset(buf_to_wifi, 0, sizeof(buf_to_wifi)); - index_to_wifi = 0; - - buf_to_wifi[data_offset] = gCfgItems.wifi_mode_sel; - buf_to_wifi[data_offset + 1] = apLen; - strncpy(&buf_to_wifi[data_offset + 2], (const char *)uiCfg.wifi_name, apLen); - buf_to_wifi[data_offset + apLen + 2] = keyLen; - strncpy(&buf_to_wifi[data_offset + apLen + 3], (const char *)uiCfg.wifi_key, keyLen); - buf_to_wifi[data_offset + apLen + keyLen + 3] = wifi_ret_tail; - - index_to_wifi = apLen + keyLen + 3; - - buf_to_wifi[0] = wifi_ret_head; - buf_to_wifi[1] = type; - buf_to_wifi[2] = index_to_wifi & 0xFF; - buf_to_wifi[3] = (index_to_wifi >> 8) & 0xFF; - - raw_send_to_wifi(buf_to_wifi, 5 + index_to_wifi); - - memset(buf_to_wifi, 0, sizeof(buf_to_wifi)); - index_to_wifi = 0; - - } - else if (type == WIFI_TRANS_INF) { - if (len > (int)(sizeof(buf_to_wifi) - index_to_wifi - 5)) { - memset(buf_to_wifi, 0, sizeof(buf_to_wifi)); - index_to_wifi = 0; - return 0; - } - - if (len > 0) { - memcpy(&buf_to_wifi[4 + index_to_wifi], buf, len); - index_to_wifi += len; - - if (index_to_wifi < 1) - return 0; - - if (buf_to_wifi[index_to_wifi + 3] == '\n') { - //mask "wait" "busy" "X:" - if (((buf_to_wifi[4] == 'w') && (buf_to_wifi[5] == 'a') && (buf_to_wifi[6] == 'i') && (buf_to_wifi[7] == 't') ) - || ((buf_to_wifi[4] == 'b') && (buf_to_wifi[5] == 'u') && (buf_to_wifi[6] == 's') && (buf_to_wifi[7] == 'y') ) - || ((buf_to_wifi[4] == 'X') && (buf_to_wifi[5] == ':') ) - ) { - memset(buf_to_wifi, 0, sizeof(buf_to_wifi)); - index_to_wifi = 0; - return 0; - } - - buf_to_wifi[0] = wifi_ret_head; - buf_to_wifi[1] = type; - buf_to_wifi[2] = index_to_wifi & 0xFF; - buf_to_wifi[3] = (index_to_wifi >> 8) & 0xFF; - buf_to_wifi[4 + index_to_wifi] = wifi_ret_tail; - - raw_send_to_wifi(buf_to_wifi, 5 + index_to_wifi); - - memset(buf_to_wifi, 0, sizeof(buf_to_wifi)); - index_to_wifi = 0; - } - } - } - else if (type == WIFI_EXCEP_INF) { - memset(buf_to_wifi, 0, sizeof(buf_to_wifi)); - - buf_to_wifi[0] = wifi_ret_head; - buf_to_wifi[1] = type; - buf_to_wifi[2] = 1; - buf_to_wifi[3] = 0; - buf_to_wifi[4] = *buf; - buf_to_wifi[5] = wifi_ret_tail; - - raw_send_to_wifi(buf_to_wifi, 6); - - memset(buf_to_wifi, 0, sizeof(buf_to_wifi)); - index_to_wifi = 0; - } - else if (type == WIFI_CLOUD_CFG) { - int data_offset = 4; - int urlLen = strlen((const char *)uiCfg.cloud_hostUrl); - - memset(buf_to_wifi, 0, sizeof(buf_to_wifi)); - index_to_wifi = 0; - - if (gCfgItems.cloud_enable == true) - buf_to_wifi[data_offset] = 0x0A; - else - buf_to_wifi[data_offset] = 0x05; - - buf_to_wifi[data_offset + 1] = urlLen; - strncpy(&buf_to_wifi[data_offset + 2], (const char *)uiCfg.cloud_hostUrl, urlLen); - buf_to_wifi[data_offset + urlLen + 2] = uiCfg.cloud_port & 0xFF; - buf_to_wifi[data_offset + urlLen + 3] = (uiCfg.cloud_port >> 8) & 0xFF; - buf_to_wifi[data_offset + urlLen + 4] = wifi_ret_tail; - - index_to_wifi = urlLen + 4; - - buf_to_wifi[0] = wifi_ret_head; - buf_to_wifi[1] = type; - buf_to_wifi[2] = index_to_wifi & 0xFF; - buf_to_wifi[3] = (index_to_wifi >> 8) & 0xFF; - - raw_send_to_wifi(buf_to_wifi, 5 + index_to_wifi); - - memset(buf_to_wifi, 0, sizeof(buf_to_wifi)); - index_to_wifi = 0; - } - else if (type == WIFI_CLOUD_UNBIND) { - memset(buf_to_wifi, 0, sizeof(buf_to_wifi)); - - buf_to_wifi[0] = wifi_ret_head; - buf_to_wifi[1] = type; - buf_to_wifi[2] = 0; - buf_to_wifi[3] = 0; - buf_to_wifi[4] = wifi_ret_tail; - - raw_send_to_wifi(buf_to_wifi, 5); - - memset(buf_to_wifi, 0, sizeof(buf_to_wifi)); - index_to_wifi = 0; - } -} - - -int send_to_wifi(char *buf, int len) { return package_to_wifi(WIFI_TRANS_INF, buf, len); } - -void set_cur_file_sys(int fileType) { - gCfgItems.fileSysType = fileType; -} - -void get_file_list(char *path) { - if ( path == 0) { - return; - } - - if (gCfgItems.fileSysType == FILE_SYS_SD) { - #if ENABLED(SDSUPPORT) - card.mount(); - #endif - } - else if (gCfgItems.fileSysType == FILE_SYS_USB) { - //udisk - } - Explore_Disk(path, 0); -} - -char wait_ip_back_flag = 0; - -typedef struct { - char write_buf[513]; - int write_index; - uint8_t saveFileName[30]; - uint32_t fileLen; - uint32_t tick_begin; - uint32_t tick_end; -} FILE_WRITER; - -FILE_WRITER file_writer; - -int32_t lastFragment = 0; - -char lastBinaryCmd[50] = {0}; - -int total_write = 0; -char binary_head[2] = {0, 0}; -unsigned char binary_data_len = 0; - -int write_to_file(char *buf, int len) { - int i; - int res; - - for (i = 0; i < len; i++) { - file_writer.write_buf[file_writer.write_index++] = buf[i]; - if (file_writer.write_index >= 512) { - res = card.write(file_writer.write_buf, file_writer.write_index); - if (res == -1) { - return -1; - } - memset(file_writer.write_buf, 0, sizeof(file_writer.write_buf)); - file_writer.write_index = 0; - } - } - return 0; -} - -#define ESP_PROTOC_HEAD (uint8_t)0xA5 -#define ESP_PROTOC_TAIL (uint8_t)0xFC - -#define ESP_TYPE_NET (uint8_t)0x0 -#define ESP_TYPE_GCODE (uint8_t)0x1 -#define ESP_TYPE_FILE_FIRST (uint8_t)0x2 -#define ESP_TYPE_FILE_FRAGMENT (uint8_t)0x3 - -#define ESP_TYPE_WIFI_LIST (uint8_t)0x4 - -uint8_t esp_msg_buf[UART_RX_BUFFER_SIZE] = {0}; -uint16_t esp_msg_index = 0; - -typedef struct { - uint8_t head; - uint8_t type; - uint16_t dataLen; - uint8_t *data; - uint8_t tail; -} ESP_PROTOC_FRAME; - - -static int cut_msg_head(uint8_t *msg, uint16_t msgLen, uint16_t cutLen) { - if (msgLen < cutLen) return 0; - - else if (msgLen == cutLen) { - memset(msg, 0, msgLen); - return 0; - } - - for (int i = 0; i < (msgLen - cutLen); i++) - msg[i] = msg[cutLen + i]; - - memset(&msg[msgLen - cutLen], 0, cutLen); - - return msgLen - cutLen; -} - - -uint8_t Explore_Disk (char* path , uint8_t recu_level) { - char tmp[200]; - char Fstream[200]; - - if (path == 0)return 0; - - const uint8_t fileCnt = card.get_num_Files(); - - for (uint8_t i = 0; i < fileCnt; i++) { - const uint16_t nr = - #if ENABLED(SDCARD_RATHERRECENTFIRST) && DISABLED(SDCARD_SORT_ALPHA) - fileCnt - 1 - - #endif - i; - - #if ENABLED(SDCARD_SORT_ALPHA) - card.getfilename_sorted(nr); - #else - card.getfilename_sorted(nr); - #endif - memset(tmp, 0, sizeof(tmp)); - //if (card.longFilename[0] == 0) - strcpy(tmp, card.filename); - //else - //strcpy(tmp, card.longFilename); - - memset(Fstream, 0, sizeof(Fstream)); - strcpy(Fstream, tmp); - - if (card.flag.filenameIsDir && (recu_level <= 10)) { - strcat(Fstream, ".DIR\r\n"); - send_to_wifi(Fstream, strlen(Fstream)); - } - else { - strcat(Fstream, "\r\n"); - send_to_wifi(Fstream, strlen(Fstream)); - } - } - - return fileCnt; -} - -static void wifi_gcode_exec(uint8_t *cmd_line) { - int8_t tempBuf[100] = {0}; - uint8_t *tmpStr = 0; - int cmd_value; - volatile int print_rate; - if ((strstr((char *)&cmd_line[0], "\n") != 0) && ((strstr((char *)&cmd_line[0], "G") != 0) || (strstr((char *)&cmd_line[0], "M") != 0) || (strstr((char *)&cmd_line[0], "T") != 0) )) { - - tmpStr = (uint8_t *)strstr((char *)&cmd_line[0], "\n"); - if (tmpStr) { - *tmpStr = '\0'; - } - tmpStr = (uint8_t *)strstr((char *)&cmd_line[0], "\r"); - if (tmpStr) { - *tmpStr = '\0'; - } - tmpStr = (uint8_t *)strstr((char *)&cmd_line[0], "*"); - if (tmpStr) { - *tmpStr = '\0'; - } - tmpStr = (uint8_t *)strstr((char *)&cmd_line[0], "M"); - if ( tmpStr) { - cmd_value = atoi((char *)(tmpStr + 1)); - tmpStr = (uint8_t *)strstr((char *)tmpStr, " "); - - switch (cmd_value) { - - case 20: //print sd / udisk file - if (uiCfg.print_state == IDLE) { - int index = 0; - - if (tmpStr == 0) { - gCfgItems.fileSysType = FILE_SYS_SD; - send_to_wifi((char *)"Begin file list\r\n", strlen("Begin file list\r\n")); - - get_file_list((char *)"0:/"); - - send_to_wifi((char *)"End file list\r\n", strlen("End file list\r\n")); - - send_to_wifi((char *)"ok\r\n", strlen("ok\r\n")); - break; - } - - while (tmpStr[index] == ' ') - index++; - - if (gCfgItems.wifi_type == ESP_WIFI) { - char *path = (char *)tempBuf; - - if (strlen((char *)&tmpStr[index]) < 80) { - send_to_wifi((char *)"Begin file list\r\n", strlen("Begin file list\r\n")); - - if (strncmp((char *)&tmpStr[index], "1:", 2) == 0) { - gCfgItems.fileSysType = FILE_SYS_SD; - - } - else if (strncmp((char *)&tmpStr[index], "0:", 2) == 0) { - gCfgItems.fileSysType = FILE_SYS_USB; - } - strcpy((char *)path, (char *)&tmpStr[index]); - get_file_list(path); - send_to_wifi((char *)"End file list\r\n", strlen("End file list\r\n")); - } - send_to_wifi((char *)"ok\r\n", strlen("ok\r\n")); - } - } - break; - - case 21: - /*init sd card*/ - send_to_wifi((char *)"ok\r\n", strlen("ok\r\n")); - break; - - case 23: - /*select the file*/ - if (uiCfg.print_state == IDLE) { - int index = 0; - while (tmpStr[index] == ' ') - index++; - - if (strstr((char *)&tmpStr[index], ".g") || strstr((char *)&tmpStr[index], ".G")) { - if (strlen((char *)&tmpStr[index]) < 80) { - memset(list_file.file_name[sel_id], 0, sizeof(list_file.file_name[sel_id])); - - if (gCfgItems.wifi_type == ESP_WIFI) { - if (strncmp((char *)&tmpStr[index], "1:", 2) == 0) { - gCfgItems.fileSysType = FILE_SYS_SD; - - } - else if (strncmp((char *)&tmpStr[index], "0:", 2) == 0) { - gCfgItems.fileSysType = FILE_SYS_USB; - } - else { - if (tmpStr[index] != '/') - strcat((char *)list_file.file_name[0], "/"); - } - strcat((char *)list_file.file_name[sel_id], (char *)&tmpStr[index]); - - } - 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((char *)"File selected\r\n", strlen("File selected\r\n")); - - } - else { - send_to_wifi((char *)"file.open failed\r\n", strlen("file.open failed\r\n")); - strcpy(list_file.file_name[sel_id], "notValid"); - } - send_to_wifi((char *)"ok\r\n", strlen("ok\r\n")); - - } - - - } - } - break; - - case 24: - if (strcmp(list_file.file_name[sel_id], "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 (gcode_preview_over != 1) { - #if ENABLED(SDSUPPORT) - char *cur_name; - cur_name=strrchr(list_file.file_name[sel_id],'/'); - - SdFile file; - SdFile *curDir; - card.endFilePrint(); - const char * const fname = card.diveToFile(true, 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()) { - feedrate_percentage = 100; - //saved_feedrate_percentage = feedrate_percentage; - planner.flow_percentage[0] = 100; - planner.e_factor[0]= planner.flow_percentage[0]*0.01; - if (EXTRUDERS==2) { - planner.flow_percentage[1] = 100; - planner.e_factor[1]= planner.flow_percentage[1]*0.01; - } - card.startFileprint(); - #if ENABLED(POWER_LOSS_RECOVERY) - recovery.prepare(); - #endif - once_flag = 0; - } - #endif - - } - } - else if (uiCfg.print_state == PAUSED) { - uiCfg.print_state = RESUMING; - clear_cur_ui(); - start_print_time(); - - if (gCfgItems.from_flash_pic==1) - flash_preview_begin = 1; - else - default_preview_flg = 1; - lv_draw_printing(); - } - else if (uiCfg.print_state == REPRINTING) { - uiCfg.print_state = REPRINTED; - clear_cur_ui(); - start_print_time(); - if (gCfgItems.from_flash_pic==1) - flash_preview_begin = 1; - else - default_preview_flg = 1; - lv_draw_printing(); - } - } - send_to_wifi((char *)"ok\r\n", strlen("ok\r\n")); - break; - - case 25: - /*pause print file*/ - if (uiCfg.print_state == WORKING) { - stop_print_time(); - - clear_cur_ui(); - - #if ENABLED(SDSUPPORT) - card.pauseSDPrint(); - uiCfg.print_state = PAUSING; - #endif - if (gCfgItems.from_flash_pic==1) - flash_preview_begin = 1; - else - default_preview_flg = 1; - lv_draw_printing(); - send_to_wifi((char *)"ok\r\n", strlen("ok\r\n")); - } - break; - - case 26: - /*stop print file*/ - if ((uiCfg.print_state == WORKING) || (uiCfg.print_state == PAUSED) || (uiCfg.print_state == REPRINTING)) { - stop_print_time(); - - clear_cur_ui(); - #if ENABLED(SDSUPPORT) - uiCfg.print_state = IDLE; - card.flag.abort_sd_printing = true; - #endif - - lv_draw_ready_print(); - - send_to_wifi((char *)"ok\r\n", strlen("ok\r\n")); - } - break; - - case 27: - /*report print rate*/ - if ((uiCfg.print_state == WORKING) || (uiCfg.print_state == PAUSED)|| (uiCfg.print_state == REPRINTING)) { - print_rate = uiCfg.totalSend; - - memset((char *)tempBuf, 0, sizeof(tempBuf)); - - sprintf((char *)tempBuf, "M27 %d\r\n", print_rate); - - send_to_wifi((char *)tempBuf, strlen((char *)tempBuf)); - - } - - break; - - case 28: - /*begin to transfer file to filesys*/ - if (uiCfg.print_state == IDLE) { - - int index = 0; - while (tmpStr[index] == ' ') - index++; - - if (strstr((char *)&tmpStr[index], ".g") || strstr((char *)&tmpStr[index], ".G")) { - strcpy((char *)file_writer.saveFileName, (char *)&tmpStr[index]); - - if (gCfgItems.fileSysType == FILE_SYS_SD) { - memset(tempBuf, 0, sizeof(tempBuf)); - sprintf((char *)tempBuf, "%s", file_writer.saveFileName); - } - else if (gCfgItems.fileSysType == FILE_SYS_USB) { - memset(tempBuf, 0, sizeof(tempBuf)); - sprintf((char *)tempBuf, "%s", (char *)file_writer.saveFileName); - } - mount_file_sys(gCfgItems.fileSysType); - - #if ENABLED(SDSUPPORT) - char *cur_name=strrchr(list_file.file_name[sel_id],'/'); - card.openFileWrite(cur_name); - if (card.isFileOpen()) { - memset(file_writer.saveFileName, 0, sizeof(file_writer.saveFileName)); - strcpy((char *)file_writer.saveFileName, (char *)&tmpStr[index]); - memset(tempBuf, 0, sizeof(tempBuf)); - sprintf((char *)tempBuf, "Writing to file: %s\r\n", (char *)file_writer.saveFileName); - wifi_ret_ack(); - send_to_wifi((char *)tempBuf, strlen((char *)tempBuf)); - - total_write = 0; - 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; - case 105: - case 991: - memset(tempBuf, 0, sizeof(tempBuf)); - if (cmd_value == 105) { - send_to_wifi((char *)"ok\r\n", strlen("ok\r\n")); - sprintf((char *)tempBuf,"T:%.1f /%.1f B:%.1f /%.1f T0:%.1f /%.1f T1:%.1f /%.1f @:0 B@:0\r\n", - - (float)thermalManager.temp_hotend[0].celsius,(float)thermalManager.temp_hotend[0].target, - #if HAS_HEATED_BED - (float)thermalManager.temp_bed.celsius,(float)thermalManager.temp_bed.target, - #else - (float)0,(float)0, - #endif - (float)thermalManager.temp_hotend[0].celsius,(float)thermalManager.temp_hotend[0].target, - #if !defined(SINGLENOZZLE) && HAS_MULTI_EXTRUDER - (float)thermalManager.temp_hotend[1].celsius,(float)thermalManager.temp_hotend[1].target - #else - (float)0,(float)0 - #endif - ); - } - else { - sprintf((char *)tempBuf,"T:%d /%d B:%d /%d T0:%d /%d T1:%d /%d @:0 B@:0\r\n", - - (int)thermalManager.temp_hotend[0].celsius,(int)thermalManager.temp_hotend[0].target, - #if HAS_HEATED_BED - (int)thermalManager.temp_bed.celsius,(int)thermalManager.temp_bed.target, - #else - 0,0, - #endif - (int)thermalManager.temp_hotend[0].celsius,(int)thermalManager.temp_hotend[0].target, - #if !defined(SINGLENOZZLE) && HAS_MULTI_EXTRUDER - (int)thermalManager.temp_hotend[1].celsius,(int)thermalManager.temp_hotend[1].target - #else - 0,0 - #endif - ); - } - - send_to_wifi((char *)tempBuf, strlen((char *)tempBuf)); - - queue.enqueue_one_P(PSTR("M105")); - - break; - case 992: - if ((uiCfg.print_state == WORKING) || (uiCfg.print_state == PAUSED)) { - memset(tempBuf,0,sizeof(tempBuf)); - sprintf((char *)tempBuf, "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((char *)tempBuf, strlen((char *)tempBuf)); - } - - break; - case 994: - if ((uiCfg.print_state == WORKING) || (uiCfg.print_state == PAUSED)) { - memset(tempBuf,0,sizeof(tempBuf)); - if (strlen((char *)list_file.file_name[sel_id]) > (100-1)) { - return; - } - sprintf((char *)tempBuf, "M994 %s;%d\n", list_file.file_name[sel_id],(int)gCfgItems.curFilesize); - wifi_ret_ack(); - send_to_wifi((char *)tempBuf, strlen((char *)tempBuf)); - } - break; - case 997: - if (uiCfg.print_state == IDLE) { - wifi_ret_ack(); - send_to_wifi((char *)"M997 IDLE\r\n", strlen("M997 IDLE\r\n")); - } - else if (uiCfg.print_state == WORKING) { - wifi_ret_ack(); - send_to_wifi((char *)"M997 PRINTING\r\n", strlen("M997 PRINTING\r\n")); - } - else if (uiCfg.print_state == PAUSED) { - wifi_ret_ack(); - send_to_wifi((char *)"M997 PAUSE\r\n", strlen("M997 PAUSE\r\n")); - } - else if (uiCfg.print_state == REPRINTING) { - wifi_ret_ack(); - send_to_wifi((char *)"M997 PAUSE\r\n", strlen("M997 PAUSE\r\n")); - } - if (uiCfg.command_send == 0) get_wifi_list_command_send(); - break; - - case 998: - if (uiCfg.print_state == IDLE) { - if (atoi((char *)tmpStr) == 0) { - set_cur_file_sys(0); - } - else if (atoi((char *)tmpStr) == 1) { - set_cur_file_sys(1); - } - wifi_ret_ack(); - } - break; - - case 115: - memset(tempBuf,0,sizeof(tempBuf)); - send_to_wifi((char *)"ok\r\n", strlen("ok\r\n")); - send_to_wifi((char *)"FIRMWARE_NAME:Robin_nano\r\n", strlen("FIRMWARE_NAME:Robin_nano\r\n")); - break; - - default: - strcat((char *)cmd_line, "\n"); - - uint32_t left; - - if (espGcodeFifo.wait_tick> 5) { - - if (espGcodeFifo.r > espGcodeFifo.w) - left = espGcodeFifo.r - espGcodeFifo.w - 1; - else - left = WIFI_GCODE_BUFFER_SIZE + espGcodeFifo.r - espGcodeFifo.w - 1; - if (left >= strlen((const char *)cmd_line)) { - uint32_t index = 0; - while (index < strlen((const char *)cmd_line)) { - espGcodeFifo.Buffer[espGcodeFifo.w] = cmd_line[index] ; - espGcodeFifo.w = (espGcodeFifo.w + 1) % WIFI_GCODE_BUFFER_SIZE; - index++; - } - if (left - WIFI_GCODE_BUFFER_LEAST_SIZE >= strlen((const char *)cmd_line)) - send_to_wifi((char *)"ok\r\n", strlen("ok\r\n")); - else - need_ok_later = true; - - } - - } - break; - - } - } - else{ - strcat((char *)cmd_line, "\n"); - uint32_t left_g; - - if (espGcodeFifo.wait_tick > 5) { - - if (espGcodeFifo.r > espGcodeFifo.w) - left_g = espGcodeFifo.r - espGcodeFifo.w - 1; - else - left_g = WIFI_GCODE_BUFFER_SIZE + espGcodeFifo.r - espGcodeFifo.w - 1; - if (left_g >= strlen((const char *)cmd_line)) { - uint32_t index = 0; - while (index < strlen((const char *)cmd_line)) { - espGcodeFifo.Buffer[espGcodeFifo.w] = cmd_line[index] ; - espGcodeFifo.w = (espGcodeFifo.w + 1) % WIFI_GCODE_BUFFER_SIZE; - index++; - } - if (left_g - WIFI_GCODE_BUFFER_LEAST_SIZE >= strlen((const char *)cmd_line)) - send_to_wifi((char *)"ok\r\n", strlen("ok\r\n")); - else - need_ok_later = true; - - } - } - } - } -} - -static int32_t charAtArray(const uint8_t *_array, uint32_t _arrayLen, uint8_t _char) { - for (uint32_t i = 0; i < _arrayLen; i++) - if (*(_array + i) == _char) return i; - return -1; -} - -void get_wifi_list_command_send() { - char buf[6] = {0}; - buf[0] = 0xA5; - buf[1] = 0x07; - buf[2] = 0x00; - buf[3] = 0x00; - buf[4] = 0xFC; - raw_send_to_wifi(buf, 5); -} - -static void net_msg_handle(uint8_t * msg, uint16_t msgLen) { - int wifiNameLen, wifiKeyLen, hostLen, id_len, ver_len; - - if (msgLen <= 0) return; - //ip - sprintf(ipPara.ip_addr, "%d.%d.%d.%d", msg[0], msg[1], msg[2], msg[3]); - - //port - //connect state - if (msg[6] == 0x0A) - wifi_link_state = WIFI_CONNECTED; - else if (msg[6] == 0x0E) - wifi_link_state = WIFI_EXCEPTION; - else - wifi_link_state = WIFI_NOT_CONFIG; - - //mode - wifiPara.mode = msg[7]; - - - //wifi name - wifiNameLen = msg[8]; - wifiKeyLen = msg[9 + wifiNameLen]; - if (wifiNameLen < 32) { - memset(wifiPara.ap_name, 0, sizeof(wifiPara.ap_name)); - memcpy(wifiPara.ap_name, &msg[9], wifiNameLen); - - memset(&wifi_list.wifiConnectedName,0,sizeof(wifi_list.wifiConnectedName)); - memcpy(&wifi_list.wifiConnectedName,&msg[9],wifiNameLen); - - //wifi key - if (wifiKeyLen < 64) { - memset(wifiPara.keyCode, 0, sizeof(wifiPara.keyCode)); - memcpy(wifiPara.keyCode, &msg[10 + wifiNameLen], wifiKeyLen); - } - } - - - cloud_para.state =msg[10 + wifiNameLen + wifiKeyLen]; - hostLen = msg[11 + wifiNameLen + wifiKeyLen]; - if (cloud_para.state) { - if (hostLen < 96) { - memset(cloud_para.hostUrl, 0, sizeof(cloud_para.hostUrl)); - memcpy(cloud_para.hostUrl, &msg[12 + wifiNameLen + wifiKeyLen], hostLen); - } - cloud_para.port = msg[12 + wifiNameLen + wifiKeyLen + hostLen] + (msg[13 + wifiNameLen + wifiKeyLen + hostLen] << 8); - - } - - // id - id_len = msg[14 + wifiNameLen + wifiKeyLen + hostLen]; - if (id_len == 20) { - memset(cloud_para.id, 0, sizeof(cloud_para.id)); - memcpy(cloud_para.id, (const char *)&msg[15 + wifiNameLen + wifiKeyLen + hostLen], id_len); - } - ver_len = msg[15 + wifiNameLen + wifiKeyLen + hostLen + id_len]; - if (ver_len < 20) { - memset(wifi_firm_ver, 0, sizeof(wifi_firm_ver)); - memcpy(wifi_firm_ver, (const char *)&msg[16 + wifiNameLen + wifiKeyLen + hostLen + id_len], ver_len); - } - - if (uiCfg.configWifi == 1) { - if ((wifiPara.mode != gCfgItems.wifi_mode_sel) - || (strncmp(wifiPara.ap_name, (const char *)uiCfg.wifi_name, 32) != 0) - || (strncmp(wifiPara.keyCode, (const char *)uiCfg.wifi_key, 64) != 0)) { - package_to_wifi(WIFI_PARA_SET, (char *)0, 0); - } - else uiCfg.configWifi = 0; - } - if (cfg_cloud_flag == 1) { - if (((cloud_para.state >> 4) != (char)gCfgItems.cloud_enable) - || (strncmp(cloud_para.hostUrl, (const char *)uiCfg.cloud_hostUrl, 96) != 0) - || (cloud_para.port != uiCfg.cloud_port)) { - package_to_wifi(WIFI_CLOUD_CFG, (char *)0, 0); - } - else cfg_cloud_flag = 0; - } -} - -static void wifi_list_msg_handle(uint8_t * msg, uint16_t msgLen) { - int wifiNameLen,wifiMsgIdex=1; - int8_t wifi_name_is_same=0; - int8_t i,j; - int8_t wifi_name_num=0; - uint8_t *str=0; - int8_t valid_name_num; - - if (msgLen <= 0) - return; - if (disp_state == KEY_BOARD_UI) - return; - - wifi_list.getNameNum = msg[0]; - - if (wifi_list.getNameNum < 20) { - uiCfg.command_send = 1; - - memset(wifi_list.wifiName,0,sizeof(wifi_list.wifiName)); - - wifi_name_num = wifi_list.getNameNum; - - valid_name_num=0; - str = wifi_list.wifiName[valid_name_num]; - - if (wifi_list.getNameNum > 0) wifi_list.currentWifipage = 1; - - for (i = 0; i 0x80) { - wifi_name_is_same = 1; - //break; - } - //} - } - if (wifi_name_is_same == 1) { - wifi_name_is_same = 0; - wifiMsgIdex += wifiNameLen; - //wifi_list.RSSI[i] = msg[wifiMsgIdex]; - wifiMsgIdex += 1; - wifi_name_num--; - //i--; - continue; - } - if (i < WIFI_TOTAL_NUMBER-1) { - str = wifi_list.wifiName[++valid_name_num]; - } - } - wifiMsgIdex += wifiNameLen; - wifi_list.RSSI[i] = msg[wifiMsgIdex]; - wifiMsgIdex += 1; - } - wifi_list.getNameNum = wifi_name_num; - if (wifi_list.getNameNum % NUMBER_OF_PAGE == 0) { - wifi_list.getPage = wifi_list.getNameNum/NUMBER_OF_PAGE; - } - else { - wifi_list.getPage = wifi_list.getNameNum/NUMBER_OF_PAGE + 1; - } - wifi_list.nameIndex = 0; - if (disp_state == WIFI_LIST_UI) - disp_wifi_list(); - } -} - -static void gcode_msg_handle(uint8_t * msg, uint16_t msgLen) { - uint8_t gcodeBuf[100] = {0}; - char *index_s; - char *index_e; - - if (msgLen <= 0) - return; - - index_s = (char *)msg; - index_e = (char *)strstr((char *)msg, "\n"); - if (*msg == 'N') { - index_s = (char *)strstr((char *)msg, " "); - while ((*index_s) == ' ') { - index_s++; - } - } - while ((index_e != 0) && ((int)index_s < (int)index_e)) { - if ((int)(index_e - index_s) < (int)sizeof(gcodeBuf)) { - memset(gcodeBuf, 0, sizeof(gcodeBuf)); - - memcpy(gcodeBuf, index_s, index_e - index_s + 1); - - wifi_gcode_exec(gcodeBuf); - } - while ((*index_e == '\r') || (*index_e == '\n')) - index_e++; - - index_s = index_e; - index_e = (char *)strstr(index_s, "\n"); - } -} - -void utf8_2_unicode(uint8_t *source,uint8_t Len) { - uint8_t i=0,char_i=0,char_byte_num=0; - uint16_t u16_h,u16_m,u16_l,u16_value; - uint8_t FileName_unicode[30]; - - memset(FileName_unicode, 0, sizeof(FileName_unicode)); - - while (1) { - char_byte_num = source[i] & 0xF0; - if (source[i] < 0X80) { - //ASCII --1byte - FileName_unicode[char_i] = source[i]; - i += 1; - char_i += 1; - } - else if (char_byte_num == 0XC0 || char_byte_num == 0XD0) { - //--2byte - - u16_h = (((uint16_t)source[i] <<8) & 0x1F00) >> 2; - u16_l = ((uint16_t)source[i+1] & 0x003F); - u16_value = (u16_h | u16_l); - FileName_unicode[char_i] = (uint8_t)((u16_value & 0xFF00) >> 8); - FileName_unicode[char_i + 1] = (uint8_t)(u16_value & 0x00FF); - i += 2; - char_i += 2; - } - else if (char_byte_num == 0XE0) { - //--3byte - u16_h = (((uint16_t)source[i] <<8 ) & 0x0F00) << 4; - u16_m = (((uint16_t)source[i+1] << 8) & 0x3F00) >> 2; - u16_l = ((uint16_t)source[i+2] & 0x003F); - u16_value = (u16_h | u16_m | u16_l); - FileName_unicode[char_i] = (uint8_t)((u16_value & 0xFF00) >> 8); - FileName_unicode[char_i + 1] = (uint8_t)(u16_value & 0x00FF); - i += 3; - char_i += 2; - } - else if (char_byte_num == 0XF0) { - //--4byte - i += 4; - //char_i += 3; - } - else { - break; - } - if (i >= Len || i >= 255)break; - } - memcpy(source, FileName_unicode, sizeof(FileName_unicode)); -} - -char saveFilePath[50]; - -static bool longName2DosName(const char* longName, uint8_t* dosName) { - uint8_t i = 11; - while (i--) dosName[i] = '\0'; - while (*longName) { - uint8_t c = *longName++; - if (c == '.') { // For a dot... - if (i == 0) return false; - else { strcat((char *)dosName,".GCO"); return dosName[0] != '\0'; } - } - 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 - } - if (i >= 5) strcat((char *)dosName,"~1.GCO"); - } - return dosName[0] != '\0'; // Return true if any name was set -} - -static void file_first_msg_handle(uint8_t * msg, uint16_t msgLen) { - uint8_t fileNameLen = *msg; - - if (msgLen != fileNameLen + 5) return; - - file_writer.fileLen = *((uint32_t *)(msg + 1)); - memset(file_writer.saveFileName, 0, sizeof(file_writer.saveFileName)); - - memcpy(file_writer.saveFileName, msg + 5, fileNameLen); - - utf8_2_unicode(file_writer.saveFileName,fileNameLen); - - memset(file_writer.write_buf, 0, sizeof(file_writer.write_buf)); - - if (strlen((const char *)file_writer.saveFileName) > sizeof(saveFilePath)) - return; - - memset(saveFilePath, 0, sizeof(saveFilePath)); - - if (gCfgItems.fileSysType == FILE_SYS_SD) { - //sprintf((char *)saveFilePath, "/%s", file_writer.saveFileName); - card.mount(); - - //ZERO(list_file.long_name[sel_id]); - //memcpy(list_file.long_name[sel_id],file_writer.saveFileName,sizeof(list_file.long_name[sel_id])); - } - else if (gCfgItems.fileSysType == FILE_SYS_USB) { - - } - file_writer.write_index = 0; - lastFragment = -1; - - wifiTransError.flag = 0; - wifiTransError.start_tick = 0; - wifiTransError.now_tick = 0; - - TERN_(SDSUPPORT, card.closefile()); - - wifi_delay(1000); - - #if ENABLED(SDSUPPORT) - - uint8_t dosName[FILENAME_LENGTH]; - - if (!longName2DosName((const char *)file_writer.saveFileName,dosName)) { - clear_cur_ui(); - upload_result = 2; - wifiTransError.flag = 1; - wifiTransError.start_tick = getWifiTick(); - lv_draw_dialog(DIALOG_TYPE_UPLOAD_FILE); - return; - } - sprintf((char *)saveFilePath, "/%s", dosName); - - ZERO(list_file.long_name[sel_id]); - memcpy(list_file.long_name[sel_id],dosName,sizeof(dosName)); - - char *cur_name=strrchr((const char *)saveFilePath,'/'); - - SdFile file; - SdFile *curDir; - card.endFilePrint(); - const char * const fname = card.diveToFile(true, curDir, cur_name); - if (!fname) return; - if (file.open(curDir, fname, O_CREAT | O_APPEND | O_WRITE | O_TRUNC)) { - gCfgItems.curFilesize = file.fileSize(); - } - else { - clear_cur_ui(); - upload_result = 2; - wifiTransError.flag = 1; - wifiTransError.start_tick = getWifiTick(); - lv_draw_dialog(DIALOG_TYPE_UPLOAD_FILE); - return; - } - #endif - - wifi_link_state = WIFI_TRANS_FILE; - - upload_result = 1; - - clear_cur_ui(); - lv_draw_dialog(DIALOG_TYPE_UPLOAD_FILE); - - lv_task_handler(); - - file_writer.tick_begin = getWifiTick(); -} - -#define FRAG_MASK _BV32(31) - -static void file_fragment_msg_handle(uint8_t * msg, uint16_t msgLen) { - uint32_t frag = *((uint32_t *)msg); - - if ((frag & FRAG_MASK) != (uint32_t)(lastFragment + 1)) { - memset(file_writer.write_buf, 0, sizeof(file_writer.write_buf)); - file_writer.write_index = 0; - wifi_link_state = WIFI_CONNECTED; - upload_result = 2; - } - else { - if (write_to_file((char *)msg + 4, msgLen - 4) < 0) { - memset(file_writer.write_buf, 0, sizeof(file_writer.write_buf)); - file_writer.write_index = 0; - wifi_link_state = WIFI_CONNECTED; - upload_result = 2; - return; - } - lastFragment = frag; - - if ((frag & (~FRAG_MASK))) { - int res = card.write(file_writer.write_buf, file_writer.write_index); - if (res == -1) { - memset(file_writer.write_buf, 0, sizeof(file_writer.write_buf)); - file_writer.write_index = 0; - wifi_link_state = WIFI_CONNECTED; - upload_result = 2; - return; - } - memset(file_writer.write_buf, 0, sizeof(file_writer.write_buf)); - file_writer.write_index = 0; - file_writer.tick_end = getWifiTick(); - upload_time = getWifiTickDiff(file_writer.tick_begin, file_writer.tick_end) / 1000; - upload_size = gCfgItems.curFilesize; - wifi_link_state = WIFI_CONNECTED; - upload_result = 3; - } - - } -} - -void esp_data_parser(char *cmdRxBuf, int len) { - int32_t head_pos; - int32_t tail_pos; - uint16_t cpyLen; - int16_t leftLen = len; - bool loop_again = false; - - ESP_PROTOC_FRAME esp_frame; - - while (leftLen > 0 || loop_again) { - loop_again = false; - - if (esp_msg_index != 0) { - head_pos = 0; - cpyLen = (leftLen < (int16_t)((sizeof(esp_msg_buf) - esp_msg_index)) ? leftLen : sizeof(esp_msg_buf) - esp_msg_index); - - memcpy(&esp_msg_buf[esp_msg_index], cmdRxBuf + len - leftLen, cpyLen); - - esp_msg_index += cpyLen; - - leftLen = leftLen - cpyLen; - tail_pos = charAtArray(esp_msg_buf, esp_msg_index, ESP_PROTOC_TAIL); - - if (tail_pos == -1) { - if (esp_msg_index >= sizeof(esp_msg_buf)) { - memset(esp_msg_buf, 0, sizeof(esp_msg_buf)); - esp_msg_index = 0; - } - return; - } - } - else { - head_pos = charAtArray((uint8_t const *)&cmdRxBuf[len - leftLen], leftLen, ESP_PROTOC_HEAD); - if (head_pos == -1) return; - - memset(esp_msg_buf, 0, sizeof(esp_msg_buf)); - memcpy(esp_msg_buf, &cmdRxBuf[len - leftLen + head_pos], leftLen - head_pos); - - esp_msg_index = leftLen - head_pos; - - leftLen = 0; - head_pos = 0; - tail_pos = charAtArray(esp_msg_buf, esp_msg_index, ESP_PROTOC_TAIL); - if (tail_pos == -1) { - if (esp_msg_index >= sizeof(esp_msg_buf)) { - memset(esp_msg_buf, 0, sizeof(esp_msg_buf)); - esp_msg_index = 0; - } - return; - } - } - - esp_frame.type = esp_msg_buf[1]; - if ((esp_frame.type != ESP_TYPE_NET) && (esp_frame.type != ESP_TYPE_GCODE) - && (esp_frame.type != ESP_TYPE_FILE_FIRST) && (esp_frame.type != ESP_TYPE_FILE_FRAGMENT) - &&(esp_frame.type != ESP_TYPE_WIFI_LIST)) { - memset(esp_msg_buf, 0, sizeof(esp_msg_buf)); - esp_msg_index = 0; - return; - } - - esp_frame.dataLen = esp_msg_buf[2] + (esp_msg_buf[3] << 8); - - if ((int)(4 + esp_frame.dataLen) > (int)(sizeof(esp_msg_buf))) { - memset(esp_msg_buf, 0, sizeof(esp_msg_buf)); - esp_msg_index = 0; - return; - } - - if (esp_msg_buf[4 + esp_frame.dataLen] != ESP_PROTOC_TAIL) { - if (esp_msg_index >= sizeof(esp_msg_buf)) { - memset(esp_msg_buf, 0, sizeof(esp_msg_buf)); - esp_msg_index = 0; - } - return; - } - - esp_frame.data = &esp_msg_buf[4]; - switch (esp_frame.type) { - case ESP_TYPE_NET: - net_msg_handle(esp_frame.data, esp_frame.dataLen); - break; - case ESP_TYPE_GCODE: - gcode_msg_handle(esp_frame.data, esp_frame.dataLen); - break; - case ESP_TYPE_FILE_FIRST: - file_first_msg_handle(esp_frame.data, esp_frame.dataLen); - break; - case ESP_TYPE_FILE_FRAGMENT: - file_fragment_msg_handle(esp_frame.data, esp_frame.dataLen); - break; - case ESP_TYPE_WIFI_LIST: - wifi_list_msg_handle(esp_frame.data, esp_frame.dataLen); - break; - default: break; - } - - esp_msg_index = cut_msg_head(esp_msg_buf, esp_msg_index, esp_frame.dataLen + 5); - if (esp_msg_index > 0) { - if (charAtArray(esp_msg_buf, esp_msg_index, ESP_PROTOC_HEAD) == -1) { - memset(esp_msg_buf, 0, sizeof(esp_msg_buf)); - esp_msg_index = 0; - return; - } - - if ((charAtArray(esp_msg_buf, esp_msg_index, ESP_PROTOC_HEAD) != -1) && (charAtArray(esp_msg_buf, esp_msg_index, ESP_PROTOC_TAIL) != -1)) - loop_again = true; - } - } -} - -int32_t tick_net_time1, tick_net_time2; - -int storeRcvData(int32_t len) { - unsigned char tmpW = wifiDmaRcvFifo.write_cur; - if (len <= UDISKBUFLEN && wifiDmaRcvFifo.state[tmpW] == udisk_buf_empty) { - for (uint16_t i = 0; i < len; i++) - wifiDmaRcvFifo.bufferAddr[tmpW][i] = WIFISERIAL.read(); - wifiDmaRcvFifo.state[tmpW] = udisk_buf_full; - wifiDmaRcvFifo.write_cur = (tmpW + 1) % TRANS_RCV_FIFO_BLOCK_NUM; - return 1; - } - return 0; -} - -int32_t readWifiFifo(uint8_t *retBuf, uint32_t bufLen) { - unsigned char tmpR = wifiDmaRcvFifo.read_cur; - if (bufLen >= UDISKBUFLEN && wifiDmaRcvFifo.state[tmpR] == udisk_buf_full) { - memcpy(retBuf, (unsigned char *)wifiDmaRcvFifo.bufferAddr[tmpR], UDISKBUFLEN); - wifiDmaRcvFifo.state[tmpR] = udisk_buf_empty; - wifiDmaRcvFifo.read_cur = (tmpR + 1) % TRANS_RCV_FIFO_BLOCK_NUM; - return UDISKBUFLEN; - } - return 0; -} - -void stopEspTransfer() { - if (wifi_link_state == WIFI_TRANS_FILE) - wifi_link_state = WIFI_CONNECTED; - - TERN_(SDSUPPORT, card.closefile()); - - if (upload_result != 3) { - wifiTransError.flag = 1; - wifiTransError.start_tick = getWifiTick(); - card.removeFile((const char *)saveFilePath); - } - else { - } - wifi_delay(200); - WIFI_IO1_SET(); - //exchangeFlashMode(1); //change spi flash to use dma mode - esp_port_begin(1); - if (wifiTransError.flag != 0x1) WIFI_IO1_RESET(); -} - -void wifi_rcv_handle() { - int32_t len = 0; - uint8_t ucStr[(UART_RX_BUFFER_SIZE) + 1] = {0}; - int8_t getDataF = 0; - - if (wifi_link_state == WIFI_TRANS_FILE) { - #if 0 - if (WIFISERIAL.available() == UART_RX_BUFFER_SIZE) { - for (uint16_t i=0;i 0) { - esp_data_parser((char *)ucStr, len); - if (wifi_link_state == WIFI_CONNECTED) { - clear_cur_ui(); - lv_draw_dialog(DIALOG_TYPE_UPLOAD_FILE); - stopEspTransfer(); - } - getDataF = 1; - } - if (esp_state == TRANSFER_STORE) { - if (storeRcvData(UART_RX_BUFFER_SIZE)) { - esp_state = TRANSFERING; - //esp_dma_pre(); - if (wifiTransError.flag != 0x1) WIFI_IO1_RESET(); - } - else - WIFI_IO1_SET(); - } - } - else { - //len = readUsartFifo((SZ_USART_FIFO *)&WifiRxFifo, (int8_t *)ucStr, UART_RX_BUFFER_SIZE); - len = readWifiBuf((int8_t *)ucStr, UART_RX_BUFFER_SIZE); - if (len > 0) { - esp_data_parser((char *)ucStr, len); - - if (wifi_link_state == WIFI_TRANS_FILE) { - //exchangeFlashMode(0); //change spi flash not use dma mode - wifi_delay(10); - esp_port_begin(0); - wifi_delay(10); - tick_net_time1 = 0; - } - if (wifiTransError.flag != 0x1) WIFI_IO1_RESET(); - getDataF = 1; - } - if (need_ok_later && (queue.length < BUFSIZE)) { - need_ok_later = false; - send_to_wifi((char *)"ok\r\n", strlen("ok\r\n")); - } - } - - if (getDataF == 1) { - tick_net_time1 = getWifiTick(); - } - else { - tick_net_time2 = getWifiTick(); - - if (wifi_link_state == WIFI_TRANS_FILE) { - if ((tick_net_time1 != 0) && (getWifiTickDiff(tick_net_time1, tick_net_time2) > 4500)) { - wifi_link_state = WIFI_CONNECTED; - upload_result = 2; - clear_cur_ui(); - stopEspTransfer(); - lv_draw_dialog(DIALOG_TYPE_UPLOAD_FILE); - } - } - - if ((tick_net_time1 != 0) && (getWifiTickDiff(tick_net_time1, tick_net_time2) > 10000)) - wifi_link_state = WIFI_NOT_CONFIG; - - if ((tick_net_time1 != 0) && (getWifiTickDiff(tick_net_time1, tick_net_time2) > 120000)) { - wifi_link_state = WIFI_NOT_CONFIG; - wifi_reset(); - tick_net_time1 = getWifiTick(); - } - } - - if (wifiTransError.flag == 0x1) { - wifiTransError.now_tick = getWifiTick(); - if (getWifiTickDiff(wifiTransError.start_tick, wifiTransError.now_tick) > WAIT_ESP_TRANS_TIMEOUT_TICK) { - wifiTransError.flag = 0; - WIFI_IO1_RESET(); - } - } -} - -void wifi_looping() { - do { wifi_rcv_handle(); } while (wifi_link_state == WIFI_TRANS_FILE); -} - -void mks_esp_wifi_init() { - wifi_link_state = WIFI_NOT_CONFIG; - - SET_OUTPUT(WIFI_RESET_PIN); - WIFI_SET(); - SET_OUTPUT(WIFI_IO1_PIN); - SET_INPUT_PULLUP(WIFI_IO0_PIN); - WIFI_IO1_SET(); - - esp_state = TRANSFER_IDLE; - esp_port_begin(1); - - wifi_reset(); - - #if 0 - res = f_open(&esp_upload.uploadFile, ESP_FIRMWARE_FILE, FA_OPEN_EXISTING | FA_READ); - - if (res == FR_OK) { - f_close(&esp_upload.uploadFile); - - wifi_delay(2000); - - if (usartFifoAvailable((SZ_USART_FIFO *)&WifiRxFifo) < 20) { - return; - } - - clear_cur_ui(); - - draw_dialog(DIALOG_TYPE_UPDATE_ESP_FIRMARE); - - if (wifi_upload(0) >= 0) { - - f_unlink("1:/MKS_WIFI_CUR"); - f_rename(ESP_FIRMWARE_FILE,"/MKS_WIFI_CUR"); - } - draw_return_ui(); - - update_flag = 1; - } - if (update_flag == 0) { - res = f_open(&esp_upload.uploadFile, ESP_WEB_FIRMWARE_FILE, FA_OPEN_EXISTING | FA_READ); - - if (res == FR_OK) { - f_close(&esp_upload.uploadFile); - - wifi_delay(2000); - - if (usartFifoAvailable((SZ_USART_FIFO *)&WifiRxFifo) < 20) { - return; - } - - clear_cur_ui(); - - draw_dialog(DIALOG_TYPE_UPDATE_ESP_FIRMARE); - if (wifi_upload(1) >= 0) { - - f_unlink("1:/MKS_WIFI_CUR"); - f_rename(ESP_WEB_FIRMWARE_FILE,"/MKS_WIFI_CUR"); - } - draw_return_ui(); - update_flag = 1; - } - - } - if (update_flag == 0) { - res = f_open(&esp_upload.uploadFile, ESP_WEB_FILE, FA_OPEN_EXISTING | FA_READ); - if (res == FR_OK) { - f_close(&esp_upload.uploadFile); - - wifi_delay(2000); - - if (usartFifoAvailable((SZ_USART_FIFO *)&WifiRxFifo) < 20) { - return; - } - - clear_cur_ui(); - - draw_dialog(DIALOG_TYPE_UPDATE_ESP_DATA); - - if (wifi_upload(2) >= 0) { - - f_unlink("1:/MKS_WEB_CONTROL_CUR"); - f_rename(ESP_WEB_FILE,"/MKS_WEB_CONTROL_CUR"); - } - draw_return_ui(); - } - } - #endif - wifiPara.decodeType = WIFI_DECODE_TYPE; - wifiPara.baud = 115200; - wifi_link_state = WIFI_NOT_CONFIG; -} - -#define BUF_INC_POINTER(p) ((p + 1 == UART_FIFO_BUFFER_SIZE) ? 0 : (p + 1)) - -int usartFifoAvailable(SZ_USART_FIFO *fifo) { - int diff = fifo->uart_write_point - fifo->uart_read_point; - if (diff < 0) diff += UART_FIFO_BUFFER_SIZE; - return diff; -} - -int readUsartFifo(SZ_USART_FIFO *fifo, int8_t *buf, int32_t len) { - int i = 0 ; - while (i < len && fifo->uart_read_point != fifo->uart_write_point) { - buf[i++] = fifo->uartTxBuffer[fifo->uart_read_point]; - fifo->uart_read_point = BUF_INC_POINTER(fifo->uart_read_point); - } - return i; -} - -int writeUsartFifo(SZ_USART_FIFO *fifo, int8_t *buf, int32_t len) { - if (buf == 0 || len <= 0) return -1; - - int i = 0 ; - while (i < len && fifo->uart_read_point != BUF_INC_POINTER(fifo->uart_write_point)) { - fifo->uartTxBuffer[fifo->uart_write_point] = buf[i++]; - fifo->uart_write_point = BUF_INC_POINTER(fifo->uart_write_point); - } - return i; -} - -void get_wifi_commands() { - static char wifi_line_buffer[MAX_CMD_SIZE]; - static bool wifi_comment_mode = false; - static int wifi_read_count = 0; - - if (espGcodeFifo.wait_tick > 5) { - while ((queue.length < BUFSIZE) && (espGcodeFifo.r != espGcodeFifo.w)) { - - espGcodeFifo.wait_tick = 0; - - char wifi_char = espGcodeFifo.Buffer[espGcodeFifo.r]; - - espGcodeFifo.r = (espGcodeFifo.r + 1) % WIFI_GCODE_BUFFER_SIZE; - - /** - * If the character ends the line - */ - if (wifi_char == '\n' || wifi_char == '\r') { - - wifi_comment_mode = false; // end of line == end of comment - - if (!wifi_read_count) continue; // skip empty lines - - wifi_line_buffer[wifi_read_count] = 0; // terminate string - wifi_read_count = 0; //reset buffer - - char* command = wifi_line_buffer; - while (*command == ' ') command++; // skip any leading spaces - - // Movement commands alert when stopped - if (IsStopped()) { - char* gpos = strchr(command, 'G'); - if (gpos) { - switch (strtol(gpos + 1, nullptr, 10)) { - case 0 ... 1: - #if ENABLED(ARC_SUPPORT) - case 2 ... 3: - #endif - #if ENABLED(BEZIER_CURVE_SUPPORT) - case 5: - #endif - SERIAL_ECHOLNPGM(STR_ERR_STOPPED); - LCD_MESSAGEPGM(MSG_STOPPED); - break; - } - } - } - - #if DISABLED(EMERGENCY_PARSER) - // Process critical commands early - if (strcmp(command, "M108") == 0) { - wait_for_heatup = false; - TERN_(HAS_LCD_MENU, wait_for_user = false); - } - if (strcmp(command, "M112") == 0) kill(M112_KILL_STR, nullptr, true); - if (strcmp(command, "M410") == 0) quickstop_stepper(); - #endif - - // Add the command to the queue - queue.enqueue_one_P(wifi_line_buffer); - } - else if (wifi_read_count >= MAX_CMD_SIZE - 1) { - - } - else { // it's not a newline, carriage return or escape char - if (wifi_char == ';') wifi_comment_mode = true; - if (!wifi_comment_mode) wifi_line_buffer[wifi_read_count++] = wifi_char; - } - } - }// queue has space, serial has data - else { - espGcodeFifo.wait_tick++; - } -} - -int readWifiBuf(int8_t *buf, int32_t len) { - int i = 0; - while (i < len && WIFISERIAL.available()) - buf[i++] = WIFISERIAL.read(); - return i; -} - -#endif // USE_WIFI_FUNCTION -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/wifi_upload.cpp b/Marlin/src/lcd/extui/lib/mks_ui/wifi_upload.cpp deleted file mode 100644 index 087a3b21105c..000000000000 --- a/Marlin/src/lcd/extui/lib/mks_ui/wifi_upload.cpp +++ /dev/null @@ -1,829 +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 . - * - */ -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "draw_ui.h" -#include "wifi_module.h" -#include "wifi_upload.h" - -#include "../../../../MarlinCore.h" - -#define WIFI_SET() WRITE(WIFI_RESET_PIN, HIGH); -#define WIFI_RESET() WRITE(WIFI_RESET_PIN, LOW); -#define WIFI_IO1_SET() WRITE(WIFI_IO1_PIN, HIGH); -#define WIFI_IO1_RESET() WRITE(WIFI_IO1_PIN, LOW); - -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); -extern void esp_port_begin(uint8_t interrupt); -extern int usartFifoAvailable(SZ_USART_FIFO *fifo); -extern void wifi_delay(int n); - -#define ARRAY_SIZE(a) sizeof(a) / sizeof((a)[0]) - -//typedef signed char bool; - -// ESP8266 command codes -const uint8_t ESP_FLASH_BEGIN = 0x02; -const uint8_t ESP_FLASH_DATA = 0x03; -const uint8_t ESP_FLASH_END = 0x04; -const uint8_t ESP_MEM_BEGIN = 0x05; -const uint8_t ESP_MEM_END = 0x06; -const uint8_t ESP_MEM_DATA = 0x07; -const uint8_t ESP_SYNC = 0x08; -const uint8_t ESP_WRITE_REG = 0x09; -const uint8_t ESP_READ_REG = 0x0A; - -// MAC address storage locations -const uint32_t ESP_OTP_MAC0 = 0x3FF00050; -const uint32_t ESP_OTP_MAC1 = 0x3FF00054; -const uint32_t ESP_OTP_MAC2 = 0x3FF00058; -const uint32_t ESP_OTP_MAC3 = 0x3FF0005C; - -const size_t EspFlashBlockSize = 0x0400; // 1K byte blocks - -const uint8_t ESP_IMAGE_MAGIC = 0xE9; -const uint8_t ESP_CHECKSUM_MAGIC = 0xEF; - -const uint32_t ESP_ERASE_CHIP_ADDR = 0x40004984; // &SPIEraseChip -const uint32_t ESP_SEND_PACKET_ADDR = 0x40003C80; // &send_packet -const uint32_t ESP_SPI_READ_ADDR = 0x40004B1C; // &SPIRead -const uint32_t ESP_UNKNOWN_ADDR = 0x40001121; // not used -const uint32_t ESP_USER_DATA_RAM_ADDR = 0x3FFE8000; // &user data ram -const uint32_t ESP_IRAM_ADDR = 0x40100000; // instruction RAM -const uint32_t ESP_FLASH_ADDR = 0x40200000; // address of start of Flash -//const uint32_t ESP_FLASH_READ_STUB_BEGIN = IRAM_ADDR + 0x18; - -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 - -// Messages corresponding to result codes, should make sense when followed by " error" -const char *resultMessages[] = { - "no", - "timeout", - "comm write", - "connect", - "bad reply", - "file read", - "empty file", - "response header", - "slip frame", - "slip state", - "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. -static const uint32_t uploadBaudRates[] = { 460800, 230400, 115200, 74880 }; - -signed char IsReady() { - return esp_upload.state == upload_idle; -} - -void uploadPort_write(const uint8_t *buf, size_t len) { - #if 0 - int i; - - for (i = 0; i < len; i++) { - while (USART_GetFlagStatus(USART1, USART_FLAG_TC) == RESET) { /* nada */ } - USART_SendData(USART1, *(buf + i)); - } - #endif -} - -char uploadPort_read() { - uint8_t retChar; - if (readUsartFifo(&WifiRxFifo, (int8_t *)&retChar, 1) == 1) - return retChar; - else - return 0; -} - -int uploadPort_available() { - return usartFifoAvailable(&WifiRxFifo); -} - -void uploadPort_begin() { - esp_port_begin(1); -} - -void uploadPort_close() { - //WIFI_COM.end(); - //WIFI_COM.begin(115200, true); - esp_port_begin(0); -} - -void flushInput() { - while (uploadPort_available() != 0) { - (void)uploadPort_read(); - //IWDG_ReloadCounter(); - } -} - -// Extract 1-4 bytes of a value in little-endian order from a buffer beginning at a specified offset -uint32_t getData(unsigned byteCnt, const uint8_t *buf, int ofst) { - uint32_t val = 0; - - if (buf && byteCnt) { - unsigned int shiftCnt = 0; - if (byteCnt > 4) - byteCnt = 4; - do{ - val |= (uint32_t)buf[ofst++] << shiftCnt; - shiftCnt += 8; - } while (--byteCnt); - } - return(val); -} - -// Put 1-4 bytes of a value in little-endian order into a buffer beginning at a specified offset. -void putData(uint32_t val, unsigned byteCnt, uint8_t *buf, int ofst) { - if (buf && byteCnt) { - if (byteCnt > 4) { - byteCnt = 4; - } - do { - buf[ofst++] = (uint8_t)(val & 0xFF); - val >>= 8; - } while (--byteCnt); - } -} - -// 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 - *data = uploadPort_read(); - if (!slipDecode) { - return(1); - } - - if (*data == 0xC0) { - // this shouldn't happen - return(-1); - } - - // if not the SLIP escape, we're done - if (*data != 0xDB) { - return(1); - } - - // SLIP escape, check availability of subsequent byte - if (uploadPort_available() == 0) { - return(-2); - } - - // process the escaped byte - *data = uploadPort_read(); - if (*data == 0xDC) { - *data = 0xC0; - return(2); - } - - if (*data == 0xDD) { - *data = 0xDB; - return(2); - } - // invalid - return(-3); -} -// When we write a sync packet, there must be no gaps between most of the characters. -// So use this function, which does a block write to the UART buffer in the latest CoreNG. -void _writePacketRaw(const uint8_t *buf, size_t len) { - uploadPort_write(buf, len); -} - -// Write a byte to the serial port optionally SLIP encoding. Return the number of bytes actually written. -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(uint8_t b) { - if (b == 0xC0) { - WriteByteRaw(0xDB); - WriteByteRaw(0xDC); - } - else if (b == 0xDB) { - 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 NULL, the response is expected to be two bytes of zero. -// -// If an error occurs, return a negative value. Otherwise, return the number -// of bytes in the response (or zero if the response was not the standard "two bytes of zero"). -EspUploadResult readPacket(uint8_t op, uint32_t *valp, size_t *bodyLen, uint32_t msTimeout) { - typedef enum { - begin = 0, - header, - body, - end, - done - } PacketState; - - uint8_t resp, opRet; - - const size_t headerLength = 8; - - uint32_t startTime = getWifiTick(); - uint8_t hdr[headerLength]; - uint16_t hdrIdx = 0; - - uint16_t bodyIdx = 0; - uint8_t respBuf[2]; - - // wait for the response - uint16_t needBytes = 1; - - PacketState state = begin; - - *bodyLen = 0; - - while (state != done) { - uint8_t c; - EspUploadResult stat; - - //IWDG_ReloadCounter(); - - if (getWifiTickDiff(startTime, getWifiTick()) > msTimeout) { - return(timeout); - } - - if (uploadPort_available() < needBytes) { - // insufficient data available - // preferably, return to Spin() here - continue; - } - - // sufficient bytes have been received for the current state, process them - switch (state) { - case begin: // expecting frame start - c = uploadPort_read(); - if (c != (uint8_t)0xC0) { - break; - } - state = header; - needBytes = 2; - - break; - case end: // expecting frame end - c = uploadPort_read(); - if (c != (uint8_t)0xC0) { - return slipFrame; - } - state = done; - - break; - - case header: // reading an 8-byte header - case body: // reading the response body - { - int rslt; - // retrieve a byte with SLIP decoding - rslt = ReadByte(&c, 1); - if (rslt != 1 && rslt != 2) { - // some error occurred - stat = (rslt == 0 || rslt == -2) ? slipData : slipFrame; - return stat; - } - else if (state == header) { - //store the header byte - hdr[hdrIdx++] = c; - if (hdrIdx >= headerLength) { - // get the body length, prepare a buffer for it - *bodyLen = (uint16_t)getData(2, hdr, 2); - - // extract the value, if requested - if (valp != 0) { - *valp = getData(4, hdr, 4); - } - - if (*bodyLen != 0) { - state = body; - } - else { - needBytes = 1; - state = end; - } - } - } - else { - // Store the response body byte, check for completion - if (bodyIdx < ARRAY_SIZE(respBuf)) { - respBuf[bodyIdx] = c; - } - ++bodyIdx; - if (bodyIdx >= *bodyLen) { - needBytes = 1; - state = end; - } - } - } - break; - - default: // this shouldn't happen - return slipState; - } - } - - // Extract elements from the header - resp = (uint8_t)getData(1, hdr, 0); - opRet = (uint8_t)getData(1, hdr, 1); - // Sync packets often provoke a response with a zero opcode instead of ESP_SYNC - if (resp != 0x01 || opRet != op) { - //printf("resp %02x %02x\n", resp, opRet); //debug - return respHeader; - } - - return success; -} - -// 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; - while (len != 0) { - if (*data == 0xC0) { - outBuf[outIndex++] = 0xDB; - outBuf[outIndex++] = 0xDC; - } - else if (*data == 0xDB) { - outBuf[outIndex++] = 0xDB; - outBuf[outIndex++] = 0xDD; - } - else { - outBuf[outIndex++] = *data; - - } - data++; - --len; - } - uploadPort_write((const uint8_t *)outBuf, outIndex); -} - -// Send a packet to the serial port while performing SLIP framing. The packet data comprises a header and an optional data block. -// A SLIP packet begins and ends with 0xC0. The data encapsulated has the bytes -// 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 - _writePacket(hdr, hdrLen); // send the header - _writePacket(data, dataLen); // send the data block - 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 - _writePacketRaw(hdr, hdrLen); // send the header - _writePacketRaw(data, dataLen); // send the data block in raw mode - WriteByteRaw(0xC0); // send the packet end character -} - -// Send a command to the attached device together with the supplied data, if any. -// The data is supplied via a list of one or more segments. -void sendCommand(uint8_t op, uint32_t checkVal, const uint8_t *data, size_t dataLen) { - // populate the header - uint8_t hdr[8]; - putData(0, 1, hdr, 0); - putData(op, 1, hdr, 1); - putData(dataLen, 2, hdr, 2); - putData(checkVal, 4, hdr, 4); - - // send the packet - //flushInput(); - if (op == ESP_SYNC) - writePacketRaw(hdr, sizeof(hdr), data, dataLen); - else - writePacket(hdr, sizeof(hdr), data, dataLen); -} - -// 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) { - size_t bodyLen; - EspUploadResult stat; - - sendCommand(op, checkVal, data, dataLen); - - stat = readPacket(op, valp, &bodyLen, msTimeout); - if (stat == success && bodyLen != 2) - stat = badReply; - - return stat; -} - -// 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) { - uint8_t buf[36]; - EspUploadResult stat; - int i ; - - // compose the data for the sync attempt - memset(buf, 0x55, sizeof(buf)); - buf[0] = 0x07; - buf[1] = 0x07; - buf[2] = 0x12; - buf[3] = 0x20; - - stat = doCommand(ESP_SYNC, buf, sizeof(buf), 0, 0, timeout); - - // If we got a response other than sync, discard it and wait for a sync response. This happens at higher baud rates. - for (i = 0; i < 10 && stat == respHeader; ++i) { - size_t bodyLen; - stat = readPacket(ESP_SYNC, 0, &bodyLen, timeout); - } - - if (stat == success) { - // Read and discard additional replies - for (;;) { - size_t bodyLen; - EspUploadResult rc = readPacket(ESP_SYNC, 0, &bodyLen, defaultTimeout); - if (rc != success || bodyLen != 2) { - break; - } - } - } - //DEBUG - //else debug//printf("stat=%d\n", (int)stat); - return stat; -} - -// Send a command to the device to begin the Flash process. -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; - - blkCnt = (size + EspFlashBlockSize - 1) / EspFlashBlockSize; - - // ensure that the address is on a block boundary - addr &= ~(EspFlashBlockSize - 1); - - // begin the Flash process - putData(size, 4, buf, 0); - putData(blkCnt, 4, buf, 4); - putData(EspFlashBlockSize, 4, buf, 8); - putData(addr, 4, buf, 12); - - timeout = (size != 0) ? eraseTimeout : defaultTimeout; - return doCommand(ESP_FLASH_BEGIN, buf, sizeof(buf), 0, 0, timeout); -} - -// Send a command to the device to terminate the Flash process -EspUploadResult flashFinish(signed char reboot) { - uint8_t buf[4]; - putData(reboot ? 0 : 1, 4, buf, 0); - return doCommand(ESP_FLASH_END, buf, sizeof(buf), 0, 0, defaultTimeout); -} - -// Compute the checksum of a block of data -uint16_t checksum(const uint8_t *data, uint16_t dataLen, uint16_t cksum) { - if (data != NULL) { - while (dataLen--) { - cksum ^= (uint16_t)*data++; - } - } - return(cksum); -} - -EspUploadResult flashWriteBlock(uint16_t flashParmVal, uint16_t flashParmMask) { - #if 0 - const uint32_t blkSize = EspFlashBlockSize; - int i; - - // Allocate a data buffer for the combined header and block data - const uint16_t hdrOfst = 0; - const uint16_t dataOfst = 16; - const uint16_t blkBufSize = dataOfst + blkSize; - uint32_t blkBuf32[blkBufSize/4]; - uint8_t * const blkBuf = (uint8_t*)(blkBuf32); - uint32_t cnt; - uint16_t cksum; - EspUploadResult stat; - - // Prepare the header for the block - putData(blkSize, 4, blkBuf, hdrOfst + 0); - putData(esp_upload.uploadBlockNumber, 4, blkBuf, hdrOfst + 4); - putData(0, 4, blkBuf, hdrOfst + 8); - putData(0, 4, blkBuf, hdrOfst + 12); - - // Get the data for the block - f_read(&esp_upload.uploadFile, blkBuf + dataOfst, blkSize, &cnt );//->Read(reinterpret_cast(blkBuf + dataOfst), blkSize); - if (cnt != blkSize) { - if (f_tell(&esp_upload.uploadFile) == esp_upload.fileSize) { - // partial last block, fill the remainder - memset(blkBuf + dataOfst + cnt, 0xFF, blkSize - cnt); - } - else { - return fileRead; - } - } - - // Patch the flash parameters into the first block if it is loaded at address 0 - if (esp_upload.uploadBlockNumber == 0 && esp_upload.uploadAddress == 0 && blkBuf[dataOfst] == ESP_IMAGE_MAGIC && flashParmMask != 0) { - // update the Flash parameters - uint32_t flashParm = getData(2, blkBuf + dataOfst + 2, 0) & ~(uint32_t)flashParmMask; - putData(flashParm | flashParmVal, 2, blkBuf + dataOfst + 2, 0); - } - - // Calculate the block checksum - cksum = checksum(blkBuf + dataOfst, blkSize, ESP_CHECKSUM_MAGIC); - - for (i = 0; i < 3; i++) { - if ((stat = doCommand(ESP_FLASH_DATA, blkBuf, blkBufSize, cksum, 0, blockWriteTimeout)) == success) { - break; - } - } - - //printf("Upload %d\%\n", ftell(&esp_upload.uploadFile) * 100 / esp_upload.fileSize); - - return stat; - #else - return success; - #endif -} - -void upload_spin() { - #if 0 - switch (esp_upload.state) { - case resetting: - - if (esp_upload.connectAttemptNumber == 9) { - // Time to give up - //Network::ResetWiFi(); - esp_upload.uploadResult = connected; - esp_upload.state = done; - } - else { - - // Reset the serial port at the new baud rate. Also reset the ESP8266. - // const uint32_t baud = uploadBaudRates[esp_upload.connectAttemptNumber/esp_upload.retriesPerBaudRate]; - if (esp_upload.connectAttemptNumber % esp_upload.retriesPerBaudRate == 0) { - } - //uploadPort.begin(baud); - //uploadPort_close(); - - uploadPort_begin(); - - wifi_delay(2000); - - flushInput(); - - esp_upload.lastAttemptTime = esp_upload.lastResetTime = getWifiTick(); - esp_upload.state = connecting; - } - - break; - - case connecting: - if ((getWifiTickDiff(esp_upload.lastAttemptTime, getWifiTick()) >= connectAttemptInterval) && (getWifiTickDiff(esp_upload.lastResetTime, getWifiTick()) >= 500)) { - // Attempt to establish a connection to the ESP8266. - EspUploadResult res = Sync(5000); - esp_upload.lastAttemptTime = getWifiTick(); - if (res == success) { - // Successful connection - //MessageF(" success on attempt %d\n", (connectAttemptNumber % retriesPerBaudRate) + 1); - //printf("connect success\n"); - esp_upload.state = erasing; - } - else { - // This attempt failed - esp_upload.connectAttemptNumber++; - if (esp_upload.connectAttemptNumber % retriesPerReset == 0) { - esp_upload.state = resetting; // try a reset and a lower baud rate - } - } - } - break; - - case erasing: - if (getWifiTickDiff(esp_upload.lastAttemptTime, getWifiTick()) >= blockWriteInterval) { - uint32_t eraseSize; - const uint32_t sectorsPerBlock = 16; - const uint32_t sectorSize = 4096; - const uint32_t numSectors = (esp_upload.fileSize + sectorSize - 1)/sectorSize; - const uint32_t startSector = esp_upload.uploadAddress/sectorSize; - - uint32_t headSectors = sectorsPerBlock - (startSector % sectorsPerBlock); - NOMORE(headSectors, numSectors); - - eraseSize = (numSectors < 2 * headSectors) - ? (numSectors + 1) / 2 * sectorSize - : (numSectors - headSectors) * sectorSize; - - //MessageF("Erasing %u bytes...\n", fileSize); - esp_upload.uploadResult = flashBegin(esp_upload.uploadAddress, eraseSize); - if (esp_upload.uploadResult == success) { - //MessageF("Uploading file...\n"); - esp_upload.uploadBlockNumber = 0; - esp_upload.uploadNextPercentToReport = percentToReportIncrement; - esp_upload.lastAttemptTime = getWifiTick(); - esp_upload.state = uploading; - } - else { - //MessageF("Erase failed\n"); - esp_upload.state = done; - } - } - break; - - 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; - const uint32_t blkCnt = (esp_upload.fileSize + EspFlashBlockSize - 1) / EspFlashBlockSize; - if (esp_upload.uploadBlockNumber < blkCnt) { - esp_upload.uploadResult = flashWriteBlock(0, 0); - esp_upload.lastAttemptTime = getWifiTick(); - if (esp_upload.uploadResult != success) { - //MessageF("Flash block upload failed\n"); - esp_upload.state = done; - } - percentComplete = (100 * esp_upload.uploadBlockNumber)/blkCnt; - ++esp_upload.uploadBlockNumber; - if (percentComplete >= esp_upload.uploadNextPercentToReport) { - //MessageF("%u%% complete\n", percentComplete); - esp_upload.uploadNextPercentToReport += percentToReportIncrement; - } - } - else { - esp_upload.state = done; - } - } - break; - - case done: - f_close(&esp_upload.uploadFile); - //uploadPort.end(); - //uploadPort_close(); - - //WIFI_COM.begin(115200, true); - //wifi_init(); - - if (esp_upload.uploadResult == success) { - //printf("upload successfully\n"); - } - else { - //printf("upload failed\n"); - } - esp_upload.state = upload_idle;//idle; - break; - - default: - break; - } - #endif -} - -// Try to upload the given file at the given address -void SendUpdateFile(const char *file, uint32_t address) { - #if 0 - FRESULT res = f_open(&esp_upload.uploadFile, file, FA_OPEN_EXISTING | FA_READ); - - if (res != FR_OK) return; - - esp_upload.fileSize = f_size(&esp_upload.uploadFile); - if (esp_upload.fileSize == 0) { - f_close(&esp_upload.uploadFile); - return; - } - f_lseek(&esp_upload.uploadFile, 0); - - esp_upload.uploadAddress = address; - esp_upload.connectAttemptNumber = 0; - esp_upload.state = resetting; - #endif -} - -static const uint32_t FirmwareAddress = 0x00000000, WebFilesAddress = 0x00100000; - -void ResetWiFiForUpload(int begin_or_end) { - #if 0 - uint32_t start, now; - - GPIO_InitTypeDef GPIO_InitStructure; - - #if V1_0_V1_1 - GPIO_InitStructure.Speed = GPIO_SPEED_FREQ_HIGH; - GPIO_InitStructure.Pin = GPIO_Pin_8; - GPIO_InitStructure.Mode = GPIO_MODE_OUTPUT_PP; - HAL_GPIO_Init(GPIOA, &GPIO_InitStructure); - #else - GPIO_InitStructure.Speed = GPIO_SPEED_FREQ_LOW; - GPIO_InitStructure.Pin = GPIO_Pin_13; - GPIO_InitStructure.Mode = GPIO_MODE_OUTPUT_PP; - HAL_GPIO_Init(GPIOC, &GPIO_InitStructure); - #endif - start = getWifiTick(); - now = start; - - if (begin_or_end == 0) { - #if V1_0_V1_1 - HAL_GPIO_WritePin(GPIOA,GPIO_Pin_8,GPIO_PIN_RESET); //update mode - #else - HAL_GPIO_WritePin(GPIOC,GPIO_Pin_13,GPIO_PIN_RESET); //update mode - #endif - } - else { - #if V1_0_V1_1 - #if V1_0_V1_1 - HAL_GPIO_WritePin(GPIOA,GPIO_Pin_8,GPIO_PIN_SET); //boot mode - GPIO_InitStructure.Speed = GPIO_SPEED_FREQ_HIGH; - GPIO_InitStructure.Pin = GPIO_Pin_8; - GPIO_InitStructure.Mode = GPIO_MODE_INPUT; - HAL_GPIO_Init(GPIOA, &GPIO_InitStructure); - #endif - #else - HAL_GPIO_WritePin(GPIOC,GPIO_Pin_13,GPIO_PIN_SET); //boot mode - GPIO_InitStructure.Speed = GPIO_SPEED_FREQ_LOW; - GPIO_InitStructure.Pin = GPIO_Pin_13; - GPIO_InitStructure.Mode = GPIO_MODE_INPUT; - HAL_GPIO_Init(GPIOC, &GPIO_InitStructure); - #endif - } - WIFI_RESET(); - while (getWifiTickDiff(start, now) < 500) now = getWifiTick(); - WIFI_SET(); - #endif -} - -int32_t wifi_upload(int type) { - esp_upload.retriesPerBaudRate = 9; - - ResetWiFiForUpload(0); - - if (type == 0) - SendUpdateFile(ESP_FIRMWARE_FILE, FirmwareAddress); - else if (type == 1) - SendUpdateFile(ESP_WEB_FIRMWARE_FILE, FirmwareAddress); - else if (type == 2) - SendUpdateFile(ESP_WEB_FILE, WebFilesAddress); - else - return -1; - - while (esp_upload.state != upload_idle) { - upload_spin(); - //IWDG_ReloadCounter(); - } - - ResetWiFiForUpload(1); - - return esp_upload.uploadResult == success ? 0 : -1; -} - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/malyan/malyan.cpp b/Marlin/src/lcd/extui/malyan/malyan.cpp new file mode 100644 index 000000000000..12cdcdf004aa --- /dev/null +++ b/Marlin/src/lcd/extui/malyan/malyan.cpp @@ -0,0 +1,420 @@ +/** + * 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 . + * + */ + +/** + * lcd/extui/malyan/malyan.cpp + * + * LCD implementation for Malyan's LCD, a separate ESP8266 MCU running + * on Serial1 for the M200 board. This module outputs a pseudo-gcode + * wrapped in curly braces which the LCD implementation translates into + * actual G-code commands. + * + * Added to Marlin for Mini/Malyan M200 + * Unknown commands as of Jan 2018: {H:} + * Not currently implemented: + * {E:} when sent by LCD. Meaning unknown. + * + * Notes for connecting to boards that are not Malyan: + * The LCD is 3.3v, so if powering from a RAMPS 1.4 board or + * other 5v/12v board, use a buck converter to power the LCD and + * the 3.3v side of a logic level shifter. Aux1 on the RAMPS board + * has Serial1 and 12v, making it perfect for this. + * Copyright (c) 2017 Jason Nelson (xC0000005) + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if ENABLED(MALYAN_LCD) + +//#define DEBUG_MALYAN_LCD + +#include "malyan.h" +#include "../ui_api.h" +#include "../../marlinui.h" + +#include "../../../sd/cardreader.h" +#include "../../../module/temperature.h" +#include "../../../module/stepper.h" +#include "../../../module/motion.h" +#include "../../../libs/duration_t.h" +#include "../../../module/printcounter.h" +#include "../../../gcode/queue.h" + +#define DEBUG_OUT ENABLED(DEBUG_MALYAN_LCD) +#include "../../../core/debug_out.h" + +// This is based on longest sys command + a filename, plus some buffer +// in case we encounter some data we don't recognize +// There is no evidence a line will ever be this long, but better safe than sorry +#define MAX_CURLY_COMMAND (32 + LONG_FILENAME_LENGTH) * 2 + +// Track incoming command bytes from the LCD +uint16_t inbound_count; + +// For sending print completion messages +bool last_printing_status = false; + +// Everything written needs the high bit set. +void write_to_lcd_P(PGM_P const message) { + char encoded_message[MAX_CURLY_COMMAND]; + uint8_t message_length = _MIN(strlen_P(message), sizeof(encoded_message)); + + LOOP_L_N(i, message_length) + encoded_message[i] = pgm_read_byte(&message[i]) | 0x80; + + LCD_SERIAL.Print::write(encoded_message, message_length); +} + +void write_to_lcd(const char * const message) { + char encoded_message[MAX_CURLY_COMMAND]; + const uint8_t message_length = _MIN(strlen(message), sizeof(encoded_message)); + + LOOP_L_N(i, message_length) + encoded_message[i] = message[i] | 0x80; + + LCD_SERIAL.Print::write(encoded_message, message_length); +} + +// {E:} is for error states. +void set_lcd_error_P(PGM_P const error, PGM_P const component/*=nullptr*/) { + write_to_lcd_P(PSTR("{E:")); + write_to_lcd_P(error); + if (component) { + write_to_lcd_P(PSTR(" ")); + write_to_lcd_P(component); + } + write_to_lcd_P(PSTR("}")); +} + + +/** + * Process an LCD 'C' command. + * These are currently all temperature commands + * {C:T0190} + * Set temp for hotend to 190 + * {C:P050} + * Set temp for bed to 50 + * + * {C:S09} set feedrate to 90 %. + * {C:S12} set feedrate to 120 %. + * + * the command portion begins after the : + */ +void process_lcd_c_command(const char *command) { + const int target_val = command[1] ? atoi(command + 1) : -1; + if (target_val < 0) { + DEBUG_ECHOLNPAIR("UNKNOWN C COMMAND ", command); + return; + } + switch (command[0]) { + case 'C': // Cope with both V1 early rev and later LCDs. + case 'S': + feedrate_percentage = target_val * 10; + LIMIT(feedrate_percentage, 10, 999); + break; + + case 'T': + // Sometimes the LCD will send commands to turn off both extruder and bed, though + // this should not happen since the printing screen is up. Better safe than sorry. + if (!print_job_timer.isRunning() || target_val > 0) + ExtUI::setTargetTemp_celsius(target_val, ExtUI::extruder_t::E0); + break; + + #if HAS_HEATED_BED + case 'P': ExtUI::setTargetTemp_celsius(target_val, ExtUI::heater_t::BED); break; + #endif + + default: DEBUG_ECHOLNPAIR("UNKNOWN C COMMAND ", command); + } +} + +/** + * Process an LCD 'B' command. + * {B:0} results in: {T0:008/195}{T1:000/000}{TP:000/000}{TQ:000C}{TT:000000} + * T0/T1 are hot end temperatures, TP is bed, TQ is percent, and TT is probably + * time remaining (HH:MM:SS). The UI can't handle displaying a second hotend, + * but the stock firmware always sends it, and it's always zero. + */ +void process_lcd_eb_command(const char *command) { + char elapsed_buffer[10]; + static uint8_t iteration = 0; + duration_t elapsed; + switch (command[0]) { + case '0': { + elapsed = print_job_timer.duration(); + sprintf_P(elapsed_buffer, PSTR("%02u%02u%02u"), uint16_t(elapsed.hour()), uint16_t(elapsed.minute()) % 60, uint16_t(elapsed.second()) % 60); + + 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 (ExtUI::isPrintingFromMedia() || ExtUI::isPrintingFromMediaPaused()) + done_pct = card.percentDone(); + #endif + + sprintf_P(message_buffer, + PSTR("{T0:%03i/%03i}{T1:000/000}{TP:%03i/%03i}{TQ:%03i}{TT:%s}"), + thermalManager.wholeDegHotend(0), thermalManager.degTargetHotend(0), + #if HAS_HEATED_BED + thermalManager.wholeDegBed(), thermalManager.degTargetBed(), + #else + 0, 0, + #endif + TERN(SDSUPPORT, done_pct, 0), + elapsed_buffer + ); + write_to_lcd(message_buffer); + } break; + + default: DEBUG_ECHOLNPAIR("UNKNOWN E/B COMMAND ", command); + } +} + +/** + * Process an LCD 'J' command. + * These are currently all movement commands. + * The command portion begins after the : + * Move X Axis + * + * {J:E}{J:X-200}{J:E} + * {J:E}{J:X+200}{J:E} + * X, Y, Z, A (extruder) + */ +template +void j_move_axis(const char *command, const T axis) { + const float dist = atof(command + 1) / 10.0; + ExtUI::setAxisPosition_mm(ExtUI::getAxisPosition_mm(axis) + dist, axis); +}; + +void process_lcd_j_command(const char *command) { + switch (command[0]) { + case 'E': break; + case 'A': j_move_axis(command, ExtUI::extruder_t::E0); break; + case 'Y': j_move_axis(command, ExtUI::axis_t::Y); break; + case 'Z': j_move_axis(command, ExtUI::axis_t::Z); break; + case 'X': j_move_axis(command, ExtUI::axis_t::X); break; + default: DEBUG_ECHOLNPAIR("UNKNOWN J COMMAND ", command); + } +} + +/** + * Process an LCD 'P' command, related to homing and printing. + * Cancel: + * {P:X} + * + * Home all axes: + * {P:H} + * + * Print a file: + * {P:000} + * The File number is specified as a three digit value. + * Printer responds with: + * {PRINTFILE:Mini_SNES_Bottom.gcode} + * {SYS:BUILD}echo:Now fresh file: Mini_SNES_Bottom.gcode + * File opened: Mini_SNES_Bottom.gcode Size: 5805813 + * File selected + * {SYS:BUILD} + * T:-2526.8 E:0 + * T:-2533.0 E:0 + * T:-2537.4 E:0 + * Note only the curly brace stuff matters. + */ +void process_lcd_p_command(const char *command) { + + switch (command[0]) { + case 'P': + ExtUI::pausePrint(); + write_to_lcd_P(PSTR("{SYS:PAUSED}")); + break; + case 'R': + ExtUI::resumePrint(); + write_to_lcd_P(PSTR("{SYS:RESUMED}")); + break; + case 'X': + write_to_lcd_P(PSTR("{SYS:CANCELING}")); + ExtUI::stopPrint(); + write_to_lcd_P(PSTR("{SYS:STARTED}")); + break; + case 'H': queue.enqueue_now_P(G28_STR); break; // Home all axes + default: { + #if ENABLED(SDSUPPORT) + // 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. + + // Find the name of the file to print. + // It's needed to echo the PRINTFILE option. + // The {S:L} command should've ensured the SD card was mounted. + card.selectFileByIndex(atoi(command)); + + // There may be a difference in how V1 and V2 LCDs handle subdirectory + // prints. Investigate more. This matches the V1 motion controller actions + // but the V2 LCD switches to "print" mode on {SYS:DIR} response. + if (card.flag.filenameIsDir) { + card.cd(card.filename); + write_to_lcd_P(PSTR("{SYS:DIR}")); + } + else { + char message_buffer[MAX_CURLY_COMMAND]; + sprintf_P(message_buffer, PSTR("{PRINTFILE:%s}"), card.longest_filename()); + write_to_lcd(message_buffer); + write_to_lcd_P(PSTR("{SYS:BUILD}")); + card.openAndPrintFile(card.filename); + } + #endif + } break; // default + } // switch +} + +/** + * Handle an lcd 'S' command + * {S:I} - Temperature request + * {T0:999/000}{T1:000/000}{TP:004/000} + * + * {S:L} - File Listing request + * Printer Response: + * {FILE:buttons.gcode} + * {FILE:update.bin} + * {FILE:nupdate.bin} + * {FILE:fcupdate.flg} + * {SYS:OK} + */ +void process_lcd_s_command(const char *command) { + switch (command[0]) { + case 'I': { + // temperature information + char message_buffer[MAX_CURLY_COMMAND]; + sprintf_P(message_buffer, PSTR("{T0:%03i/%03i}{T1:000/000}{TP:%03i/%03i}"), + thermalManager.wholeDegHotend(0), thermalManager.degTargetHotend(0), + #if HAS_HEATED_BED + thermalManager.wholeDegBed(), thermalManager.degTargetBed() + #else + 0, 0 + #endif + ); + write_to_lcd(message_buffer); + } break; + + case 'L': { + #if ENABLED(SDSUPPORT) + if (!card.isMounted()) card.mount(); + + // A more efficient way to do this would be to + // implement a callback in the ls_SerialPrint code, but + // that requires changes to the core cardreader class that + // would not benefit the majority of users. Since one can't + // 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++) { + card.selectFileByIndex(i); + sprintf_P(message_buffer, card.flag.filenameIsDir ? PSTR("{DIR:%s}") : PSTR("{FILE:%s}"), card.longest_filename()); + write_to_lcd(message_buffer); + } + + write_to_lcd_P(PSTR("{SYS:OK}")); + #endif + } break; + + default: DEBUG_ECHOLNPAIR("UNKNOWN S COMMAND ", command); + } +} + +/** + * Receive a curly brace command and translate to G-code. + * Currently {E:0} is not handled. Its function is unknown, + * but it occurs during the temp window after a sys build. + */ +void process_lcd_command(const char *command) { + const char *current = command; + + byte command_code = *current++; + if (*current == ':') { + + current++; // skip the : + + switch (command_code) { + case 'S': process_lcd_s_command(current); break; + case 'J': process_lcd_j_command(current); break; + case 'P': process_lcd_p_command(current); break; + case 'C': process_lcd_c_command(current); break; + case 'B': + case 'E': process_lcd_eb_command(current); break; + default: DEBUG_ECHOLNPAIR("UNKNOWN COMMAND ", command); + } + } + else + DEBUG_ECHOLNPAIR("UNKNOWN COMMAND FORMAT ", command); +} + +// +// Parse LCD commands mixed with G-Code +// +void parse_lcd_byte(const byte b) { + static char inbound_buffer[MAX_CURLY_COMMAND]; + + static uint8_t parsing = 0; // Parsing state + static bool prevcr = false; // Was the last c a CR? + + const char c = b & 0x7F; + + if (parsing) { + const bool is_lcd = parsing == 1; // 1 for LCD + if ( ( is_lcd && c == '}') // Closing brace on LCD command + || (!is_lcd && c == '\n') // LF on a G-code command + ) { + inbound_buffer[inbound_count] = '\0'; // Reset before processing + inbound_count = 0; // Reset buffer index + if (parsing == 1) + process_lcd_command(inbound_buffer); // Handle the LCD command + else + queue.enqueue_one_now(inbound_buffer); // Handle the G-code command + parsing = 0; // Unflag and... + } + else if (inbound_count < MAX_CURLY_COMMAND - 2) + inbound_buffer[inbound_count++] = is_lcd ? c : b; // Buffer while space remains + } + else { + if (c == '{') parsing = 1; // Brace opens an LCD command + else if (prevcr && c == '\n') parsing = 2; // CRLF indicates G-code + prevcr = (c == '\r'); // Remember if it was a CR + } +} + +/** + * UC means connected. + * UD means disconnected + * The stock firmware considers USB initialized as "connected." + */ +void update_usb_status(const bool forceUpdate) { + static bool last_usb_connected_status = false; + // This is mildly different than stock, which + // appears to use the usb discovery status. + // This is more logical. + if (last_usb_connected_status != MYSERIAL1.connected() || forceUpdate) { + last_usb_connected_status = MYSERIAL1.connected(); + write_to_lcd_P(last_usb_connected_status ? PSTR("{R:UC}\r\n") : PSTR("{R:UD}\r\n")); + } +} + +#endif // MALYAN_LCD diff --git a/Marlin/src/lcd/extui/malyan/malyan.h b/Marlin/src/lcd/extui/malyan/malyan.h new file mode 100644 index 000000000000..e8afbd4a59bd --- /dev/null +++ b/Marlin/src/lcd/extui/malyan/malyan.h @@ -0,0 +1,53 @@ +/** + * 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 + +/** + * lcd/extui/malyan/malyan.h + */ + +#include "../../../HAL/shared/Marduino.h" + +// Track incoming command bytes from the LCD +extern uint16_t inbound_count; + +// For sending print completion messages +extern bool last_printing_status; + +void write_to_lcd_P(PGM_P const message); +void write_to_lcd(const char * const message); + +void set_lcd_error_P(PGM_P const error, PGM_P const component=nullptr); + +void process_lcd_c_command(const char *command); +void process_lcd_eb_command(const char *command); + +template +void j_move_axis(const char *command, const T axis); + +void process_lcd_j_command(const char *command); +void process_lcd_p_command(const char *command); +void process_lcd_s_command(const char *command); +void process_lcd_command(const char *command); + +void parse_lcd_byte(const byte b); +void update_usb_status(const bool forceUpdate); diff --git a/Marlin/src/lcd/extui/malyan/malyan_extui.cpp b/Marlin/src/lcd/extui/malyan/malyan_extui.cpp new file mode 100644 index 000000000000..5815522afca2 --- /dev/null +++ b/Marlin/src/lcd/extui/malyan/malyan_extui.cpp @@ -0,0 +1,164 @@ +/** + * 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 . + * + */ + +/** + * lcd/extui/malyan/malyan_extui.cpp + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if ENABLED(MALYAN_LCD) + +#include "../ui_api.h" +#include "malyan.h" + +//#include "../../marlinui.h" +//#include "../../../sd/cardreader.h" +//#include "../../../module/temperature.h" +//#include "../../../module/stepper.h" +//#include "../../../module/motion.h" +//#include "../../../libs/duration_t.h" +//#include "../../../module/printcounter.h" +//#include "../../../gcode/queue.h" + +namespace ExtUI { + void onStartup() { + /** + * The Malyan LCD actually runs as a separate MCU on Serial 1. + * This code's job is to siphon the weird curly-brace commands from + * it and translate into ExtUI operations where possible. + */ + inbound_count = 0; + + #ifndef LCD_BAUDRATE + #define LCD_BAUDRATE 500000 + #endif + LCD_SERIAL.begin(LCD_BAUDRATE); + + // Signal init + write_to_lcd_P(PSTR("{SYS:STARTED}\r\n")); + + // send a version that says "unsupported" + write_to_lcd_P(PSTR("{VER:99}\r\n")); + + // No idea why it does this twice. + write_to_lcd_P(PSTR("{SYS:STARTED}\r\n")); + update_usb_status(true); + } + + void onIdle() { + /** + * - from printer on startup: + * {SYS:STARTED}{VER:29}{SYS:STARTED}{R:UD} + */ + + // First report USB status. + update_usb_status(false); + + // now drain commands... + while (LCD_SERIAL.available()) + parse_lcd_byte((byte)LCD_SERIAL.read()); + + #if ENABLED(SDSUPPORT) + // 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. + static uint8_t last_percent_done = 100; + + // If there was a print in progress, we need to emit the final + // print status as {TQ:100}. Reset last percent done so a new print will + // issue a percent of 0. + const uint8_t percent_done = (ExtUI::isPrinting() || ExtUI::isPrintingFromMediaPaused()) ? ExtUI::getProgress_percent() : last_printing_status ? 100 : 0; + if (percent_done != last_percent_done) { + char message_buffer[16]; + sprintf_P(message_buffer, PSTR("{TQ:%03i}"), percent_done); + write_to_lcd(message_buffer); + last_percent_done = percent_done; + last_printing_status = ExtUI::isPrinting(); + } + #endif + } + + void onPrinterKilled(PGM_P const error, PGM_P const component) { + set_lcd_error_P(error, component); + } + + #if HAS_PID_HEATING + + void onPidTuning(const result_t rst) { + // Called for temperature PID tuning result + //SERIAL_ECHOLNPAIR("OnPidTuning:", rst); + switch (rst) { + case PID_BAD_EXTRUDER_NUM: + set_lcd_error_P(GET_TEXT(MSG_PID_BAD_EXTRUDER_NUM)); + break; + case PID_TEMP_TOO_HIGH: + set_lcd_error_P(GET_TEXT(MSG_PID_TEMP_TOO_HIGH)); + break; + case PID_TUNING_TIMEOUT: + set_lcd_error_P(GET_TEXT(MSG_PID_TIMEOUT)); + break; + case PID_DONE: + set_lcd_error_P(GET_TEXT(MSG_PID_AUTOTUNE_DONE)); + break; + } + } + + #endif + + void onPrintTimerStarted() { write_to_lcd_P(PSTR("{SYS:BUILD}")); } + void onPrintTimerPaused() {} + void onPrintTimerStopped() { write_to_lcd_P(PSTR("{TQ:100}")); } + + // Not needed for Malyan LCD + void onStatusChanged(const char * const) {} + void onMediaInserted() {} + void onMediaError() {} + void onMediaRemoved() {} + void onPlayTone(const uint16_t, const uint16_t) {} + void onFilamentRunout(const extruder_t extruder) {} + void onUserConfirmRequired(const char * const) {} + void onHomingStart() {} + void onHomingComplete() {} + void onPrintFinished() {} + void onFactoryReset() {} + void onStoreSettings(char*) {} + void onLoadSettings(const char*) {} + void onPostprocessSettings() {} + void onConfigurationStoreWritten(bool) {} + void onConfigurationStoreRead(bool) {} + + #if HAS_MESH + void onMeshLevelingStart() {} + 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 ENABLED(POWER_LOSS_RECOVERY) + void onPowerLossResume() {} + #endif + + void onSteppersDisabled() {} + void onSteppersEnabled() {} +} + +#endif // MALYAN_LCD diff --git a/Marlin/src/lcd/extui/malyan_lcd.cpp b/Marlin/src/lcd/extui/malyan_lcd.cpp deleted file mode 100644 index 79a5fb961aa1..000000000000 --- a/Marlin/src/lcd/extui/malyan_lcd.cpp +++ /dev/null @@ -1,536 +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 . - * - */ - -/** - * malyan_lcd.cpp - * - * LCD implementation for Malyan's LCD, a separate ESP8266 MCU running - * on Serial1 for the M200 board. This module outputs a pseudo-gcode - * wrapped in curly braces which the LCD implementation translates into - * actual G-code commands. - * - * Added to Marlin for Mini/Malyan M200 - * Unknown commands as of Jan 2018: {H:} - * Not currently implemented: - * {E:} when sent by LCD. Meaning unknown. - * - * Notes for connecting to boards that are not Malyan: - * The LCD is 3.3v, so if powering from a RAMPS 1.4 board or - * other 5v/12v board, use a buck converter to power the LCD and - * the 3.3v side of a logic level shifter. Aux1 on the RAMPS board - * has Serial1 and 12v, making it perfect for this. - * Copyright (c) 2017 Jason Nelson (xC0000005) - */ - -#include "../../inc/MarlinConfigPre.h" - -#if ENABLED(MALYAN_LCD) - -//#define DEBUG_MALYAN_LCD - -#include "ui_api.h" - -#include "../ultralcd.h" -#include "../../sd/cardreader.h" -#include "../../module/temperature.h" -#include "../../module/stepper.h" -#include "../../module/motion.h" -#include "../../libs/duration_t.h" -#include "../../module/printcounter.h" -#include "../../gcode/queue.h" - -#define DEBUG_OUT ENABLED(DEBUG_MALYAN_LCD) -#include "../../core/debug_out.h" - -// This is based on longest sys command + a filename, plus some buffer -// in case we encounter some data we don't recognize -// There is no evidence a line will ever be this long, but better safe than sorry -#define MAX_CURLY_COMMAND (32 + LONG_FILENAME_LENGTH) * 2 - -// Track incoming command bytes from the LCD -uint16_t inbound_count; - -// For sending print completion messages -bool last_printing_status = false; - -// Everything written needs the high bit set. -void write_to_lcd_P(PGM_P const message) { - char encoded_message[MAX_CURLY_COMMAND]; - uint8_t message_length = _MIN(strlen_P(message), sizeof(encoded_message)); - - LOOP_L_N(i, message_length) - encoded_message[i] = pgm_read_byte(&message[i]) | 0x80; - - LCD_SERIAL.Print::write(encoded_message, message_length); -} - -void write_to_lcd(const char * const message) { - char encoded_message[MAX_CURLY_COMMAND]; - const uint8_t message_length = _MIN(strlen(message), sizeof(encoded_message)); - - LOOP_L_N(i, message_length) - encoded_message[i] = message[i] | 0x80; - - LCD_SERIAL.Print::write(encoded_message, message_length); -} - -// {E:} is for error states. -void set_lcd_error_P(PGM_P const error, PGM_P const component=nullptr) { - write_to_lcd_P(PSTR("{E:")); - write_to_lcd_P(error); - if (component) { - write_to_lcd_P(PSTR(" ")); - write_to_lcd_P(component); - } - write_to_lcd_P(PSTR("}")); -} - - -/** - * Process an LCD 'C' command. - * These are currently all temperature commands - * {C:T0190} - * Set temp for hotend to 190 - * {C:P050} - * Set temp for bed to 50 - * - * {C:S09} set feedrate to 90 %. - * {C:S12} set feedrate to 120 %. - * - * the command portion begins after the : - */ -void process_lcd_c_command(const char* command) { - const int target_val = command[1] ? atoi(command + 1) : -1; - if (target_val < 0) { - DEBUG_ECHOLNPAIR("UNKNOWN C COMMAND ", command); - return; - } - switch (command[0]) { - case 'C': // Cope with both V1 early rev and later LCDs. - case 'S': - feedrate_percentage = target_val * 10; - LIMIT(feedrate_percentage, 10, 999); - break; - - case 'T': - // Sometimes the LCD will send commands to turn off both extruder and bed, though - // this should not happen since the printing screen is up. Better safe than sorry. - if (!print_job_timer.isRunning() || target_val > 0) - ExtUI::setTargetTemp_celsius(target_val, ExtUI::extruder_t::E0); - break; - - #if HAS_HEATED_BED - case 'P': ExtUI::setTargetTemp_celsius(target_val, ExtUI::heater_t::BED); break; - #endif - - default: DEBUG_ECHOLNPAIR("UNKNOWN C COMMAND ", command); - } -} - -/** - * Process an LCD 'B' command. - * {B:0} results in: {T0:008/195}{T1:000/000}{TP:000/000}{TQ:000C}{TT:000000} - * T0/T1 are hot end temperatures, TP is bed, TQ is percent, and TT is probably - * time remaining (HH:MM:SS). The UI can't handle displaying a second hotend, - * but the stock firmware always sends it, and it's always zero. - */ -void process_lcd_eb_command(const char* command) { - char elapsed_buffer[10]; - static uint8_t iteration = 0; - duration_t elapsed; - switch (command[0]) { - case '0': { - elapsed = print_job_timer.duration(); - sprintf_P(elapsed_buffer, PSTR("%02u%02u%02u"), uint16_t(elapsed.hour()), uint16_t(elapsed.minute()) % 60, uint16_t(elapsed.second()) % 60); - - 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 (ExtUI::isPrintingFromMedia() || ExtUI::isPrintingFromMediaPaused()) - done_pct = card.percentDone(); - #endif - - sprintf_P(message_buffer, - PSTR("{T0:%03i/%03i}{T1:000/000}{TP:%03i/%03i}{TQ:%03i}{TT:%s}"), - int(thermalManager.degHotend(0)), thermalManager.degTargetHotend(0), - #if HAS_HEATED_BED - int(thermalManager.degBed()), thermalManager.degTargetBed(), - #else - 0, 0, - #endif - #if ENABLED(SDSUPPORT) - done_pct, - #else - 0, - #endif - elapsed_buffer - ); - write_to_lcd(message_buffer); - } break; - - default: DEBUG_ECHOLNPAIR("UNKNOWN E/B COMMAND ", command); - } -} - -/** - * Process an LCD 'J' command. - * These are currently all movement commands. - * The command portion begins after the : - * Move X Axis - * - * {J:E}{J:X-200}{J:E} - * {J:E}{J:X+200}{J:E} - * X, Y, Z, A (extruder) - */ -template -void j_move_axis(const char* command, const T axis) { - const float dist = atof(command + 1) / 10.0; - ExtUI::setAxisPosition_mm(ExtUI::getAxisPosition_mm(axis) + dist, axis); -}; - -void process_lcd_j_command(const char* command) { - switch (command[0]) { - case 'E': break; - case 'A': j_move_axis(command, ExtUI::extruder_t::E0); break; - case 'Y': j_move_axis(command, ExtUI::axis_t::Y); break; - case 'Z': j_move_axis(command, ExtUI::axis_t::Z); break; - case 'X': j_move_axis(command, ExtUI::axis_t::X); break; - default: DEBUG_ECHOLNPAIR("UNKNOWN J COMMAND ", command); - } -} - -/** - * Process an LCD 'P' command, related to homing and printing. - * Cancel: - * {P:X} - * - * Home all axes: - * {P:H} - * - * Print a file: - * {P:000} - * The File number is specified as a three digit value. - * Printer responds with: - * {PRINTFILE:Mini_SNES_Bottom.gcode} - * {SYS:BUILD}echo:Now fresh file: Mini_SNES_Bottom.gcode - * File opened: Mini_SNES_Bottom.gcode Size: 5805813 - * File selected - * {SYS:BUILD} - * T:-2526.8 E:0 - * T:-2533.0 E:0 - * T:-2537.4 E:0 - * Note only the curly brace stuff matters. - */ -void process_lcd_p_command(const char* command) { - - switch (command[0]) { - case 'P': - ExtUI::pausePrint(); - write_to_lcd_P(PSTR("{SYS:PAUSED}")); - break; - case 'R': - ExtUI::resumePrint(); - write_to_lcd_P(PSTR("{SYS:RESUMED}")); - break; - case 'X': - write_to_lcd_P(PSTR("{SYS:CANCELING}")); - ExtUI::stopPrint(); - write_to_lcd_P(PSTR("{SYS:STARTED}")); - break; - case 'H': queue.enqueue_now_P(G28_STR); break; // Home all axes - default: { - #if ENABLED(SDSUPPORT) - // 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. - - // Find the name of the file to print. - // It's needed to echo the PRINTFILE option. - // The {S:L} command should've ensured the SD card was mounted. - card.selectFileByIndex(atoi(command)); - - // There may be a difference in how V1 and V2 LCDs handle subdirectory - // prints. Investigate more. This matches the V1 motion controller actions - // but the V2 LCD switches to "print" mode on {SYS:DIR} response. - if (card.flag.filenameIsDir) { - card.cd(card.filename); - write_to_lcd_P(PSTR("{SYS:DIR}")); - } - else { - char message_buffer[MAX_CURLY_COMMAND]; - sprintf_P(message_buffer, PSTR("{PRINTFILE:%s}"), card.longest_filename()); - write_to_lcd(message_buffer); - write_to_lcd_P(PSTR("{SYS:BUILD}")); - card.openAndPrintFile(card.filename); - } - #endif - } break; // default - } // switch -} - -/** - * Handle an lcd 'S' command - * {S:I} - Temperature request - * {T0:999/000}{T1:000/000}{TP:004/000} - * - * {S:L} - File Listing request - * Printer Response: - * {FILE:buttons.gcode} - * {FILE:update.bin} - * {FILE:nupdate.bin} - * {FILE:fcupdate.flg} - * {SYS:OK} - */ -void process_lcd_s_command(const char* command) { - switch (command[0]) { - case 'I': { - // temperature information - char message_buffer[MAX_CURLY_COMMAND]; - sprintf_P(message_buffer, PSTR("{T0:%03i/%03i}{T1:000/000}{TP:%03i/%03i}"), - int(thermalManager.degHotend(0)), thermalManager.degTargetHotend(0), - #if HAS_HEATED_BED - int(thermalManager.degBed()), thermalManager.degTargetBed() - #else - 0, 0 - #endif - ); - write_to_lcd(message_buffer); - } break; - - case 'L': { - #if ENABLED(SDSUPPORT) - if (!card.isMounted()) card.mount(); - - // A more efficient way to do this would be to - // implement a callback in the ls_SerialPrint code, but - // that requires changes to the core cardreader class that - // would not benefit the majority of users. Since one can't - // 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++) { - card.selectFileByIndex(i); - sprintf_P(message_buffer, card.flag.filenameIsDir ? PSTR("{DIR:%s}") : PSTR("{FILE:%s}"), card.longest_filename()); - write_to_lcd(message_buffer); - } - - write_to_lcd_P(PSTR("{SYS:OK}")); - #endif - } break; - - default: DEBUG_ECHOLNPAIR("UNKNOWN S COMMAND ", command); - } -} - -/** - * Receive a curly brace command and translate to G-code. - * Currently {E:0} is not handled. Its function is unknown, - * but it occurs during the temp window after a sys build. - */ -void process_lcd_command(const char* command) { - const char *current = command; - - byte command_code = *current++; - if (*current == ':') { - - current++; // skip the : - - switch (command_code) { - case 'S': process_lcd_s_command(current); break; - case 'J': process_lcd_j_command(current); break; - case 'P': process_lcd_p_command(current); break; - case 'C': process_lcd_c_command(current); break; - case 'B': - case 'E': process_lcd_eb_command(current); break; - default: DEBUG_ECHOLNPAIR("UNKNOWN COMMAND ", command); - } - } - else - DEBUG_ECHOLNPAIR("UNKNOWN COMMAND FORMAT ", command); -} - -// -// Parse LCD commands mixed with G-Code -// -void parse_lcd_byte(const byte b) { - static char inbound_buffer[MAX_CURLY_COMMAND]; - - static uint8_t parsing = 0; // Parsing state - static bool prevcr = false; // Was the last c a CR? - - const char c = b & 0x7F; - - if (parsing) { - const bool is_lcd = parsing == 1; // 1 for LCD - if ( ( is_lcd && c == '}') // Closing brace on LCD command - || (!is_lcd && c == '\n') // LF on a G-code command - ) { - inbound_buffer[inbound_count] = '\0'; // Reset before processing - inbound_count = 0; // Reset buffer index - if (parsing == 1) - process_lcd_command(inbound_buffer); // Handle the LCD command - else - queue.enqueue_one_now(inbound_buffer); // Handle the G-code command - parsing = 0; // Unflag and... - } - else if (inbound_count < MAX_CURLY_COMMAND - 2) - inbound_buffer[inbound_count++] = is_lcd ? c : b; // Buffer while space remains - } - else { - if (c == '{') parsing = 1; // Brace opens an LCD command - else if (prevcr && c == '\n') parsing = 2; // CRLF indicates G-code - prevcr = (c == '\r'); // Remember if it was a CR - } -} - -/** - * UC means connected. - * UD means disconnected - * The stock firmware considers USB initialized as "connected." - */ -void update_usb_status(const bool forceUpdate) { - static bool last_usb_connected_status = false; - // This is mildly different than stock, which - // appears to use the usb discovery status. - // This is more logical. - if (last_usb_connected_status != MYSERIAL0 || forceUpdate) { - last_usb_connected_status = MYSERIAL0; - write_to_lcd_P(last_usb_connected_status ? PSTR("{R:UC}\r\n") : PSTR("{R:UD}\r\n")); - } -} - -namespace ExtUI { - void onStartup() { - /** - * The Malyan LCD actually runs as a separate MCU on Serial 1. - * This code's job is to siphon the weird curly-brace commands from - * it and translate into ExtUI operations where possible. - */ - inbound_count = 0; - - #ifndef LCD_BAUDRATE - #define LCD_BAUDRATE 500000 - #endif - LCD_SERIAL.begin(LCD_BAUDRATE); - - // Signal init - write_to_lcd_P(PSTR("{SYS:STARTED}\r\n")); - - // send a version that says "unsupported" - write_to_lcd_P(PSTR("{VER:99}\r\n")); - - // No idea why it does this twice. - write_to_lcd_P(PSTR("{SYS:STARTED}\r\n")); - update_usb_status(true); - } - - void onIdle() { - /** - * - from printer on startup: - * {SYS:STARTED}{VER:29}{SYS:STARTED}{R:UD} - */ - - // First report USB status. - update_usb_status(false); - - // now drain commands... - while (LCD_SERIAL.available()) - parse_lcd_byte((byte)LCD_SERIAL.read()); - - #if ENABLED(SDSUPPORT) - // 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. - static uint8_t last_percent_done = 100; - - // If there was a print in progress, we need to emit the final - // print status as {TQ:100}. Reset last percent done so a new print will - // issue a percent of 0. - const uint8_t percent_done = (ExtUI::isPrinting() || ExtUI::isPrintingFromMediaPaused()) ? ExtUI::getProgress_percent() : last_printing_status ? 100 : 0; - if (percent_done != last_percent_done) { - char message_buffer[16]; - sprintf_P(message_buffer, PSTR("{TQ:%03i}"), percent_done); - write_to_lcd(message_buffer); - last_percent_done = percent_done; - last_printing_status = ExtUI::isPrinting(); - } - #endif - } - - void onPrinterKilled(PGM_P const error, PGM_P const component) { - set_lcd_error_P(error, component); - } - - #if HAS_PID_HEATING - - void onPidTuning(const result_t rst) { - // Called for temperature PID tuning result - //SERIAL_ECHOLNPAIR("OnPidTuning:", rst); - switch (rst) { - case PID_BAD_EXTRUDER_NUM: - set_lcd_error_P(GET_TEXT(MSG_PID_BAD_EXTRUDER_NUM)); - break; - case PID_TEMP_TOO_HIGH: - set_lcd_error_P(GET_TEXT(MSG_PID_TEMP_TOO_HIGH)); - break; - case PID_TUNING_TIMEOUT: - set_lcd_error_P(GET_TEXT(MSG_PID_TIMEOUT)); - break; - case PID_DONE: - set_lcd_error_P(GET_TEXT(MSG_PID_AUTOTUNE_DONE)); - break; - } - } - - #endif - - void onPrintTimerStarted() { write_to_lcd_P(PSTR("{SYS:BUILD}")); } - void onPrintTimerPaused() {} - void onPrintTimerStopped() { write_to_lcd_P(PSTR("{TQ:100}")); } - - // Not needed for Malyan LCD - void onStatusChanged(const char * const) {} - void onMediaInserted() {}; - void onMediaError() {}; - void onMediaRemoved() {}; - void onPlayTone(const uint16_t, const uint16_t) {} - void onFilamentRunout(const extruder_t extruder) {} - void onUserConfirmRequired(const char * const) {} - void onFactoryReset() {} - void onStoreSettings(char*) {} - void onLoadSettings(const char*) {} - void onConfigurationStoreWritten(bool) {} - void onConfigurationStoreRead(bool) {} - - #if HAS_MESH - void onMeshUpdate(const int8_t xpos, const int8_t ypos, const float zval) {} - void onMeshUpdate(const int8_t xpos, const int8_t ypos, const ExtUI::probe_state_t state) {} - #endif - - #if ENABLED(POWER_LOSS_RECOVERY) - void onPowerLossResume() {} - #endif -} - -#endif // MALYAN_LCD diff --git a/Marlin/src/lcd/extui/lib/mks_ui/SPIFlashStorage.cpp b/Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.cpp similarity index 93% rename from Marlin/src/lcd/extui/lib/mks_ui/SPIFlashStorage.cpp rename to Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.cpp index 3f5712445138..6f3d6bbb6b66 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/SPIFlashStorage.cpp +++ b/Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.cpp @@ -20,11 +20,11 @@ * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI -#include "../../../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #include "SPIFlashStorage.h" extern W25QXXFlash W25QXX; @@ -167,9 +167,8 @@ void SPIFlashStorage::endWrite() { #endif } -void SPIFlashStorage::savePage(uint8_t* buffer) { +void SPIFlashStorage::savePage(uint8_t *buffer) { W25QXX.SPI_FLASH_BufferWrite(buffer, m_startAddress + (SPI_FLASH_PageSize * m_currentPage), SPI_FLASH_PageSize); - // Test env // char fname[256]; // snprintf(fname, sizeof(fname), "./pages/page-%03d.data", m_currentPage); @@ -178,15 +177,13 @@ void SPIFlashStorage::savePage(uint8_t* buffer) { // fclose(fp); } -void SPIFlashStorage::loadPage(uint8_t* buffer) { +void SPIFlashStorage::loadPage(uint8_t *buffer) { W25QXX.SPI_FLASH_BufferRead(buffer, m_startAddress + (SPI_FLASH_PageSize * m_currentPage), SPI_FLASH_PageSize); - // Test env // char fname[256]; - // memset(buffer, 0, SPI_FLASH_PageSize); // snprintf(fname, sizeof(fname), "./pages/page-%03d.data", m_currentPage); // FILE *fp = fopen(fname, "rb"); - // if (fp != NULL) { + // if (fp) { // fread(buffer, 1, SPI_FLASH_PageSize, fp); // fclose(fp); // } @@ -207,7 +204,7 @@ void SPIFlashStorage::flushPage() { return; } - // Part of the m_pageData was compressed, so ajust the pointers, freeing what was processed, shift the buffer + // Part of the m_pageData was compressed, so adjust the pointers, freeing what was processed, shift the buffer // TODO: To avoid this copy, use a circular buffer memmove(m_pageData, m_pageData + inputProcessed, m_pageDataUsed - inputProcessed); m_pageDataUsed -= inputProcessed; @@ -259,7 +256,7 @@ void SPIFlashStorage::readPage() { #endif } -uint16_t SPIFlashStorage::inData(uint8_t* data, uint16_t size) { +uint16_t SPIFlashStorage::inData(uint8_t *data, uint16_t size) { // Don't write more than we can NOMORE(size, pageDataFree()); memcpy(m_pageData + m_pageDataUsed, data, size); @@ -267,7 +264,7 @@ uint16_t SPIFlashStorage::inData(uint8_t* data, uint16_t size) { return size; } -void SPIFlashStorage::writeData(uint8_t* data, uint16_t size) { +void SPIFlashStorage::writeData(uint8_t *data, uint16_t size) { // Flush a page if needed if (pageDataFree() == 0) flushPage(); @@ -292,7 +289,7 @@ void SPIFlashStorage::beginRead(uint32_t startAddress) { #endif } -uint16_t SPIFlashStorage::outData(uint8_t* data, uint16_t size) { +uint16_t SPIFlashStorage::outData(uint8_t *data, uint16_t size) { // Don't read more than we have NOMORE(size, pageDataFree()); memcpy(data, m_pageData + m_pageDataUsed, size); @@ -300,7 +297,7 @@ uint16_t SPIFlashStorage::outData(uint8_t* data, uint16_t size) { return size; } -void SPIFlashStorage::readData(uint8_t* data, uint16_t size) { +void SPIFlashStorage::readData(uint8_t *data, uint16_t size) { // Read a page if needed if (pageDataFree() == 0) readPage(); diff --git a/Marlin/src/lcd/extui/lib/mks_ui/SPIFlashStorage.h b/Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.h similarity index 89% rename from Marlin/src/lcd/extui/lib/mks_ui/SPIFlashStorage.h rename to Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.h index 98c8067bd3c2..4683ff935187 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/SPIFlashStorage.h +++ b/Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.h @@ -21,7 +21,7 @@ */ #pragma once -#include "../../../../libs/W25Qxx.h" +#include "../../../libs/W25Qxx.h" #define HAS_SPI_FLASH_COMPRESSION 1 @@ -55,7 +55,7 @@ * * When reading, it loads a full page from SPI Flash at once and * keeps it in a private SRAM buffer. Data is loaded as needed to - * fullfill requests. Sequential reads are optimal. + * fulfill requests. Sequential reads are optimal. * * SPIFlashStorage.beginRead(myStartAddress); * while (there is data to read) @@ -77,21 +77,21 @@ class SPIFlashStorage { // Write operation static void beginWrite(uint32_t startAddress); static void endWrite(); - static void writeData(uint8_t* data, uint16_t size); + static void writeData(uint8_t *data, uint16_t size); // Read operation static void beginRead(uint32_t startAddress); - static void readData(uint8_t* data, uint16_t size); + static void readData(uint8_t *data, uint16_t size); static uint32_t getCurrentPage() { return m_currentPage; } private: static void flushPage(); - static void savePage(uint8_t* buffer); - static void loadPage(uint8_t* buffer); + static void savePage(uint8_t *buffer); + static void loadPage(uint8_t *buffer); static void readPage(); - static uint16_t inData(uint8_t* data, uint16_t size); - static uint16_t outData(uint8_t* data, uint16_t size); + static uint16_t inData(uint8_t *data, uint16_t size); + static uint16_t outData(uint8_t *data, uint16_t size); static uint8_t m_pageData[SPI_FLASH_PageSize]; static uint32_t m_currentPage; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/SPI_TFT.cpp b/Marlin/src/lcd/extui/mks_ui/SPI_TFT.cpp similarity index 94% rename from Marlin/src/lcd/extui/lib/mks_ui/SPI_TFT.cpp rename to Marlin/src/lcd/extui/mks_ui/SPI_TFT.cpp index 394ce4807572..68e4d9de0423 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/SPI_TFT.cpp +++ b/Marlin/src/lcd/extui/mks_ui/SPI_TFT.cpp @@ -20,7 +20,7 @@ * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI @@ -28,7 +28,7 @@ #include "pic_manager.h" #include "tft_lvgl_configuration.h" -#include "../../../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #include @@ -73,8 +73,6 @@ void TFT::LCD_clear(uint16_t color) { tftio.WriteMultiple(color, (uint32_t)(TFT_WIDTH) * (TFT_HEIGHT)); } -extern unsigned char bmp_public_buf[17 * 1024]; - void TFT::LCD_Draw_Logo() { #if HAS_LOGO_IN_FLASH setWindow(0, 0, TFT_WIDTH, TFT_HEIGHT); diff --git a/Marlin/src/lcd/extui/lib/mks_ui/SPI_TFT.h b/Marlin/src/lcd/extui/mks_ui/SPI_TFT.h similarity index 90% rename from Marlin/src/lcd/extui/lib/mks_ui/SPI_TFT.h rename to Marlin/src/lcd/extui/mks_ui/SPI_TFT.h index 696bc16974be..62a084fb1196 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/SPI_TFT.h +++ b/Marlin/src/lcd/extui/mks_ui/SPI_TFT.h @@ -21,11 +21,8 @@ */ #pragma once -#include "../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "../../../tft_io/tft_io.h" +#include "../../tft_io/tft_io.h" +#include class TFT { public: @@ -39,5 +36,3 @@ class TFT { }; extern TFT SPI_TFT; - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_about.cpp b/Marlin/src/lcd/extui/mks_ui/draw_about.cpp new file mode 100644 index 000000000000..54a8ede64e0e --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_about.cpp @@ -0,0 +1,65 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include + +#include "../../../inc/MarlinConfig.h" + +extern lv_group_t *g; +static lv_obj_t *scr; +static lv_obj_t *fw_type, *board; + +enum { ID_A_RETURN = 1 }; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + switch (obj->mks_obj_id) { + case ID_A_RETURN: + clear_cur_ui(); + draw_return_ui(); + break; + } +} + +void lv_draw_about() { + scr = lv_screen_create(ABOUT_UI); + lv_big_button_create(scr, "F:/bmp_return.bin", common_menu.text_back, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_A_RETURN); + + fw_type = lv_label_create(scr, "Firmware: Marlin " SHORT_BUILD_VERSION); + lv_obj_align(fw_type, nullptr, LV_ALIGN_CENTER, 0, -20); + + board = lv_label_create(scr, "Board: " BOARD_INFO_NAME); + lv_obj_align(board, nullptr, LV_ALIGN_CENTER, 0, -60); +} + +void lv_clear_about() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_about.h b/Marlin/src/lcd/extui/mks_ui/draw_about.h similarity index 90% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_about.h rename to Marlin/src/lcd/extui/mks_ui/draw_about.h index 2ee7ec04c61a..4e7b318eda54 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_about.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_about.h @@ -25,10 +25,9 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_about(void); -extern void lv_clear_about(); +void lv_draw_about(); +void lv_clear_about(); -//extern void disp_temp_ready_print(); #ifdef __cplusplus } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_acceleration_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_acceleration_settings.cpp new file mode 100644 index 000000000000..22196a28b8fc --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_acceleration_settings.cpp @@ -0,0 +1,153 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include + +#include "../../../module/planner.h" +#include "../../../inc/MarlinConfig.h" + +extern lv_group_t *g; +static lv_obj_t *scr; + +enum { + ID_ACCE_RETURN = 1, + ID_ACCE_PRINT, + ID_ACCE_RETRA, + ID_ACCE_TRAVEL, + ID_ACCE_X, + ID_ACCE_Y, + ID_ACCE_Z, + ID_ACCE_E0, + ID_ACCE_E1, + ID_ACCE_UP, + ID_ACCE_DOWN +}; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + switch (obj->mks_obj_id) { + case ID_ACCE_RETURN: + uiCfg.para_ui_page = false; + lv_clear_acceleration_settings(); + draw_return_ui(); + break; + case ID_ACCE_PRINT: + value = PrintAcceleration; + lv_clear_acceleration_settings(); + lv_draw_number_key(); + break; + case ID_ACCE_RETRA: + value = RetractAcceleration; + lv_clear_acceleration_settings(); + lv_draw_number_key(); + break; + case ID_ACCE_TRAVEL: + value = TravelAcceleration; + lv_clear_acceleration_settings(); + lv_draw_number_key(); + break; + case ID_ACCE_X: + value = XAcceleration; + lv_clear_acceleration_settings(); + lv_draw_number_key(); + break; + case ID_ACCE_Y: + value = YAcceleration; + lv_clear_acceleration_settings(); + lv_draw_number_key(); + break; + case ID_ACCE_Z: + value = ZAcceleration; + lv_clear_acceleration_settings(); + lv_draw_number_key(); + break; + case ID_ACCE_E0: + value = E0Acceleration; + lv_clear_acceleration_settings(); + lv_draw_number_key(); + break; + case ID_ACCE_E1: + value = E1Acceleration; + lv_clear_acceleration_settings(); + lv_draw_number_key(); + break; + case ID_ACCE_UP: + uiCfg.para_ui_page = false; + lv_clear_acceleration_settings(); + lv_draw_acceleration_settings(); + break; + case ID_ACCE_DOWN: + uiCfg.para_ui_page = true; + lv_clear_acceleration_settings(); + lv_draw_acceleration_settings(); + break; + } +} + +void lv_draw_acceleration_settings() { + scr = lv_screen_create(ACCELERATION_UI, machine_menu.AccelerationConfTitle); + if (!uiCfg.para_ui_page) { + dtostrf(planner.settings.acceleration, 1, 1, public_buf_l); + lv_screen_menu_item_1_edit(scr, machine_menu.PrintAcceleration, PARA_UI_POS_X, PARA_UI_POS_Y, event_handler, ID_ACCE_PRINT, 0, public_buf_l); + + dtostrf(planner.settings.retract_acceleration, 1, 1, public_buf_l); + lv_screen_menu_item_1_edit(scr, machine_menu.RetractAcceleration, PARA_UI_POS_X, PARA_UI_POS_Y * 2, event_handler, ID_ACCE_RETRA, 1, public_buf_l); + + dtostrf(planner.settings.travel_acceleration, 1, 1, public_buf_l); + lv_screen_menu_item_1_edit(scr, machine_menu.TravelAcceleration, PARA_UI_POS_X, PARA_UI_POS_Y * 3, event_handler, ID_ACCE_TRAVEL, 2, public_buf_l); + + 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, PARA_UI_POS_Y * 4, event_handler, ID_ACCE_X, 3, public_buf_l); + + 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); + } + else { + itoa(planner.settings.max_acceleration_mm_per_s2[Y_AXIS], public_buf_l, 10); + lv_screen_menu_item_1_edit(scr, machine_menu.Y_Acceleration, PARA_UI_POS_X, PARA_UI_POS_Y, event_handler, ID_ACCE_Y, 0, public_buf_l); + + itoa(planner.settings.max_acceleration_mm_per_s2[Z_AXIS], public_buf_l, 10); + lv_screen_menu_item_1_edit(scr, machine_menu.Z_Acceleration, PARA_UI_POS_X, PARA_UI_POS_Y * 2, event_handler, ID_ACCE_Z, 1, public_buf_l); + + itoa(planner.settings.max_acceleration_mm_per_s2[E_AXIS], public_buf_l, 10); + lv_screen_menu_item_1_edit(scr, machine_menu.E0_Acceleration, PARA_UI_POS_X, PARA_UI_POS_Y * 3, event_handler, ID_ACCE_E0, 2, public_buf_l); + + itoa(planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(1)], public_buf_l, 10); + lv_screen_menu_item_1_edit(scr, machine_menu.E1_Acceleration, PARA_UI_POS_X, PARA_UI_POS_Y * 4, event_handler, ID_ACCE_E1, 3, public_buf_l); + + lv_big_button_create(scr, "F:/bmp_back70x40.bin", machine_menu.previous, PARA_UI_TURN_PAGE_POS_X, PARA_UI_TURN_PAGE_POS_Y, event_handler, ID_ACCE_UP, true); + } + + lv_big_button_create(scr, "F:/bmp_back70x40.bin", common_menu.text_back, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y, event_handler, ID_ACCE_RETURN, true); +} + +void lv_clear_acceleration_settings() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_acceleration_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_acceleration_settings.h similarity index 91% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_acceleration_settings.h rename to Marlin/src/lcd/extui/mks_ui/draw_acceleration_settings.h index 6ab49713c9dd..e333e0ae5118 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_acceleration_settings.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_acceleration_settings.h @@ -25,8 +25,8 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_acceleration_settings(void); -extern void lv_clear_acceleration_settings(); +void lv_draw_acceleration_settings(); +void lv_clear_acceleration_settings(); #ifdef __cplusplus } /* C-declarations for C++ */ diff --git a/Marlin/src/lcd/extui/mks_ui/draw_advance_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_advance_settings.cpp new file mode 100644 index 000000000000..a564d86cc10c --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_advance_settings.cpp @@ -0,0 +1,96 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include + +#include "../../../inc/MarlinConfig.h" + +extern lv_group_t *g; +static lv_obj_t *scr; + +enum { + ID_ADVANCE_RETURN = 1, + ID_PAUSE_POS, + ID_WIFI_PARA, + ID_FILAMENT_SETTINGS, + ID_ENCODER_SETTINGS +}; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + switch (obj->mks_obj_id) { + case ID_ADVANCE_RETURN: + lv_clear_advance_settings(); + draw_return_ui(); + break; + case ID_PAUSE_POS: + lv_clear_advance_settings(); + lv_draw_pause_position(); + break; + case ID_FILAMENT_SETTINGS: + lv_clear_advance_settings(); + lv_draw_filament_settings(); + break; + #if ENABLED(MKS_WIFI_MODULE) + case ID_WIFI_PARA: + lv_clear_advance_settings(); + lv_draw_wifi_settings(); + break; + #endif + #if HAS_ROTARY_ENCODER + case ID_ENCODER_SETTINGS: + lv_clear_advance_settings(); + lv_draw_encoder_settings(); + break; + #endif + } +} + +void lv_draw_advance_settings() { + scr = lv_screen_create(ADVANCED_UI, machine_menu.AdvancedConfTitle); + + int index = 0; + lv_screen_menu_item(scr, machine_menu.PausePosition, PARA_UI_POS_X, PARA_UI_POS_Y, event_handler, ID_PAUSE_POS, index++); + lv_screen_menu_item(scr, machine_menu.FilamentConf, PARA_UI_POS_X, PARA_UI_POS_Y * 2, event_handler, ID_FILAMENT_SETTINGS, index++); + #if ENABLED(MKS_WIFI_MODULE) + lv_screen_menu_item(scr, machine_menu.WifiSettings, PARA_UI_POS_X, PARA_UI_POS_Y * 3, event_handler, ID_WIFI_PARA, index++); + #endif + #if HAS_ROTARY_ENCODER + lv_screen_menu_item(scr, machine_menu.EncoderSettings, PARA_UI_POS_X, PARA_UI_POS_Y * (index + 1), event_handler, ID_ENCODER_SETTINGS, index); + index++; + #endif + + lv_big_button_create(scr, "F:/bmp_back70x40.bin", common_menu.text_back, PARA_UI_BACL_POS_X + 10, PARA_UI_BACL_POS_Y, event_handler, ID_ADVANCE_RETURN, true); +} + +void lv_clear_advance_settings() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_advance_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_advance_settings.h similarity index 92% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_advance_settings.h rename to Marlin/src/lcd/extui/mks_ui/draw_advance_settings.h index 84e4a4d4cf60..8848c34451bc 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_advance_settings.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_advance_settings.h @@ -25,8 +25,8 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_advance_settings(void); -extern void lv_clear_advance_settings(); +void lv_draw_advance_settings(); +void lv_clear_advance_settings(); #ifdef __cplusplus } /* C-declarations for C++ */ 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 new file mode 100644 index 000000000000..d52abcff23b5 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_auto_level_offset_settings.cpp @@ -0,0 +1,89 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if BOTH(HAS_TFT_LVGL_UI, HAS_BED_PROBE) + +#include "draw_ui.h" +#include + +#include "../../../module/probe.h" +#include "../../../inc/MarlinConfig.h" + +extern lv_group_t *g; +static lv_obj_t *scr; + +enum { + ID_OFFSET_RETURN = 1, + ID_OFFSET_X, + ID_OFFSET_Y, + ID_OFFSET_Z +}; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + switch (obj->mks_obj_id) { + case ID_OFFSET_RETURN: + lv_clear_auto_level_offset_settings(); + draw_return_ui(); + break; + case ID_OFFSET_X: + value = x_offset; + lv_clear_auto_level_offset_settings(); + lv_draw_number_key(); + break; + case ID_OFFSET_Y: + value = y_offset; + lv_clear_auto_level_offset_settings(); + lv_draw_number_key(); + break; + case ID_OFFSET_Z: + value = z_offset; + lv_clear_auto_level_offset_settings(); + lv_draw_number_key(); + break; + } +} + +void lv_draw_auto_level_offset_settings() { + scr = lv_screen_create(NOZZLE_PROBE_OFFSET_UI, machine_menu.OffsetConfTitle); + + dtostrf(TERN0(HAS_PROBE_XY_OFFSET, probe.offset.x), 1, 1, public_buf_l); + lv_screen_menu_item_1_edit(scr, machine_menu.Xoffset, PARA_UI_POS_X, PARA_UI_POS_Y, event_handler, ID_OFFSET_X, 0, public_buf_l); + + dtostrf(TERN0(HAS_PROBE_XY_OFFSET, probe.offset.y), 1, 1, public_buf_l); + lv_screen_menu_item_1_edit(scr, machine_menu.Yoffset, PARA_UI_POS_X, PARA_UI_POS_Y * 2, event_handler, ID_OFFSET_Y, 1, public_buf_l); + + dtostrf(TERN0(HAS_PROBE_XY_OFFSET, probe.offset.z), 1, 1, public_buf_l); + lv_screen_menu_item_1_edit(scr, machine_menu.Zoffset, PARA_UI_POS_X, PARA_UI_POS_Y * 3, event_handler, ID_OFFSET_Z, 2, public_buf_l); + + lv_big_button_create(scr, "F:/bmp_back70x40.bin", common_menu.text_back, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y, event_handler, ID_OFFSET_RETURN, true); +} + +void lv_clear_auto_level_offset_settings() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI && HAS_BED_PROBE diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_auto_level_offset_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_auto_level_offset_settings.h similarity index 90% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_auto_level_offset_settings.h rename to Marlin/src/lcd/extui/mks_ui/draw_auto_level_offset_settings.h index 688cd205d04f..38314f6bc2df 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_auto_level_offset_settings.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_auto_level_offset_settings.h @@ -25,8 +25,8 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_auto_level_offset_settings(void); -extern void lv_clear_auto_level_offset_settings(); +void lv_draw_auto_level_offset_settings(); +void lv_clear_auto_level_offset_settings(); #ifdef __cplusplus } /* C-declarations for C++ */ diff --git a/Marlin/src/lcd/extui/mks_ui/draw_baby_stepping.cpp b/Marlin/src/lcd/extui/mks_ui/draw_baby_stepping.cpp new file mode 100644 index 000000000000..316519057952 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_baby_stepping.cpp @@ -0,0 +1,181 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include + +#include "../../../gcode/queue.h" +#include "../../../gcode/gcode.h" +#include "../../../inc/MarlinConfig.h" + +#if ENABLED(EEPROM_SETTINGS) + #include "../../../module/settings.h" +#endif + +#if HAS_BED_PROBE + #include "../../../module/probe.h" +#endif + +extern lv_group_t *g; +static lv_obj_t *scr; + +static lv_obj_t *labelV, *buttonV, *zOffsetText; + +enum { + ID_BABY_STEP_X_P = 1, + ID_BABY_STEP_X_N, + ID_BABY_STEP_Y_P, + ID_BABY_STEP_Y_N, + ID_BABY_STEP_Z_P, + ID_BABY_STEP_Z_N, + ID_BABY_STEP_DIST, + ID_BABY_STEP_RETURN +}; + +static float babystep_dist=0.01; +static uint8_t has_adjust_z = 0; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + char baby_buf[30] = { 0 }; + char str_1[16]; + switch (obj->mks_obj_id) { + case ID_BABY_STEP_X_P: + sprintf_P(baby_buf, PSTR("M290 X%s"), dtostrf(babystep_dist, 1, 3, str_1)); + gcode.process_subcommands_now_P(PSTR(baby_buf)); + has_adjust_z = 1; + break; + case ID_BABY_STEP_X_N: + sprintf_P(baby_buf, PSTR("M290 X%s"), dtostrf(-babystep_dist, 1, 3, str_1)); + gcode.process_subcommands_now_P(PSTR(baby_buf)); + has_adjust_z = 1; + break; + case ID_BABY_STEP_Y_P: + sprintf_P(baby_buf, PSTR("M290 Y%s"), dtostrf(babystep_dist, 1, 3, str_1)); + gcode.process_subcommands_now_P(PSTR(baby_buf)); + has_adjust_z = 1; + break; + case ID_BABY_STEP_Y_N: + sprintf_P(baby_buf, PSTR("M290 Y%s"), dtostrf(-babystep_dist, 1, 3, str_1)); + gcode.process_subcommands_now_P(PSTR(baby_buf)); + has_adjust_z = 1; + break; + case ID_BABY_STEP_Z_P: + sprintf_P(baby_buf, PSTR("M290 Z%s"), dtostrf(babystep_dist, 1, 3, str_1)); + gcode.process_subcommands_now_P(PSTR(baby_buf)); + has_adjust_z = 1; + break; + case ID_BABY_STEP_Z_N: + sprintf_P(baby_buf, PSTR("M290 Z%s"), dtostrf(-babystep_dist, 1, 3, str_1)); + gcode.process_subcommands_now_P(PSTR(baby_buf)); + has_adjust_z = 1; + break; + case ID_BABY_STEP_DIST: + if (ABS((int)(100 * babystep_dist)) == 1) + babystep_dist = 0.05; + else if (ABS((int)(100 * babystep_dist)) == 5) + babystep_dist = 0.1; + else + babystep_dist = 0.01; + disp_baby_step_dist(); + break; + case ID_BABY_STEP_RETURN: + if (has_adjust_z == 1) { + TERN_(EEPROM_SETTINGS, (void)settings.save()); + has_adjust_z = 0; + } + clear_cur_ui(); + draw_return_ui(); + break; + } +} + +void lv_draw_baby_stepping() { + scr = lv_screen_create(BABY_STEP_UI); + lv_big_button_create(scr, "F:/bmp_xAdd.bin", move_menu.x_add, INTERVAL_V, titleHeight, event_handler, ID_BABY_STEP_X_P); + lv_big_button_create(scr, "F:/bmp_xDec.bin", move_menu.x_dec, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_BABY_STEP_X_N); + lv_big_button_create(scr, "F:/bmp_yAdd.bin", move_menu.y_add, BTN_X_PIXEL + INTERVAL_V * 2, titleHeight, event_handler, ID_BABY_STEP_Y_P); + lv_big_button_create(scr, "F:/bmp_yDec.bin", move_menu.y_dec, BTN_X_PIXEL + INTERVAL_V * 2, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_BABY_STEP_Y_N); + lv_big_button_create(scr, "F:/bmp_zAdd.bin", move_menu.z_add, BTN_X_PIXEL * 2 + INTERVAL_V * 3, titleHeight, event_handler, ID_BABY_STEP_Z_P); + lv_big_button_create(scr, "F:/bmp_zDec.bin", move_menu.z_dec, BTN_X_PIXEL * 2 + INTERVAL_V * 3, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_BABY_STEP_Z_N); + buttonV = lv_imgbtn_create(scr, nullptr, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight, event_handler, ID_BABY_STEP_DIST); + labelV = lv_label_create_empty(buttonV); + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonV); + } + #endif + + lv_big_button_create(scr, "F:/bmp_return.bin", common_menu.text_back, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_BABY_STEP_RETURN); + + disp_baby_step_dist(); + + zOffsetText = lv_label_create(scr, 290, TITLE_YPOS, nullptr); + disp_z_offset_value(); +} + +void disp_baby_step_dist() { + if ((int)(100 * babystep_dist) == 1) + lv_imgbtn_set_src_both(buttonV, "F:/bmp_baby_move0_01.bin"); + else if ((int)(100 * babystep_dist) == 5) + lv_imgbtn_set_src_both(buttonV, "F:/bmp_baby_move0_05.bin"); + else if ((int)(100 * babystep_dist) == 10) + lv_imgbtn_set_src_both(buttonV, "F:/bmp_baby_move0_1.bin"); + + if (gCfgItems.multiple_language) { + if ((int)(100 * babystep_dist) == 1) { + lv_label_set_text(labelV, move_menu.step_001mm); + lv_obj_align(labelV, buttonV, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + else if ((int)(100 * babystep_dist) == 5) { + lv_label_set_text(labelV, move_menu.step_005mm); + lv_obj_align(labelV, buttonV, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + else if ((int)(100 * babystep_dist) == 10) { + lv_label_set_text(labelV, move_menu.step_01mm); + lv_obj_align(labelV, buttonV, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + } +} + +void disp_z_offset_value() { + char buf[20]; + #if HAS_BED_PROBE + char str_1[16]; + sprintf_P(buf, PSTR("Offset Z: %s mm"), dtostrf(probe.offset.z, 1, 3, str_1)); + #else + strcpy_P(buf, PSTR("Offset Z: 0 mm")); + #endif + lv_label_set_text(zOffsetText, buf); +} + +void lv_clear_baby_stepping() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_baby_stepping.h b/Marlin/src/lcd/extui/mks_ui/draw_baby_stepping.h similarity index 84% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_baby_stepping.h rename to Marlin/src/lcd/extui/mks_ui/draw_baby_stepping.h index 333ba2d59717..f8efeabc4093 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_baby_stepping.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_baby_stepping.h @@ -25,12 +25,11 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_baby_stepping(void); -extern void lv_clear_baby_stepping(); -extern void disp_baby_step_dist(); -extern void disp_z_offset_value(); +void lv_draw_baby_stepping(); +void lv_clear_baby_stepping(); +void disp_baby_step_dist(); +void disp_z_offset_value(); -//extern void disp_temp_ready_print(); #ifdef __cplusplus } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_change_speed.cpp b/Marlin/src/lcd/extui/mks_ui/draw_change_speed.cpp new file mode 100644 index 000000000000..645cd2e6e3c9 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_change_speed.cpp @@ -0,0 +1,225 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include + +#include "../../../module/planner.h" +#include "../../../inc/MarlinConfig.h" + +extern lv_group_t *g; +static lv_obj_t *scr; +static lv_obj_t *labelStep, *buttonStep, *buttonMov, *buttonExt; +static lv_obj_t *labelMov, *labelExt; +static lv_obj_t *printSpeedText; + +enum { + ID_C_ADD = 1, + ID_C_DEC, + ID_C_MOVE, + ID_C_EXT, + ID_C_STEP, + ID_C_RETURN +}; + +static bool editingFlowrate; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + switch (obj->mks_obj_id) { + case ID_C_ADD: + if (!editingFlowrate) { + if (feedrate_percentage < MAX_EXT_SPEED_PERCENT - uiCfg.stepPrintSpeed) + feedrate_percentage += uiCfg.stepPrintSpeed; + else + feedrate_percentage = MAX_EXT_SPEED_PERCENT; + } + else { + if (planner.flow_percentage[0] < MAX_EXT_SPEED_PERCENT - uiCfg.stepPrintSpeed) + planner.flow_percentage[0] += uiCfg.stepPrintSpeed; + else + planner.flow_percentage[0] = MAX_EXT_SPEED_PERCENT; + planner.refresh_e_factor(0); + #if HAS_MULTI_EXTRUDER + planner.flow_percentage[1] = planner.flow_percentage[0]; + planner.refresh_e_factor(1); + #endif + } + disp_print_speed(); + break; + case ID_C_DEC: + if (!editingFlowrate) { + if (feedrate_percentage > MIN_EXT_SPEED_PERCENT + uiCfg.stepPrintSpeed) + feedrate_percentage -= uiCfg.stepPrintSpeed; + else + feedrate_percentage = MIN_EXT_SPEED_PERCENT; + } + else { + if (planner.flow_percentage[0] > MIN_EXT_SPEED_PERCENT + uiCfg.stepPrintSpeed) + planner.flow_percentage[0] -= uiCfg.stepPrintSpeed; + else + planner.flow_percentage[0] = MIN_EXT_SPEED_PERCENT; + planner.refresh_e_factor(0); + #if HAS_MULTI_EXTRUDER + planner.flow_percentage[1] = planner.flow_percentage[0]; + planner.refresh_e_factor(1); + #endif + } + disp_print_speed(); + break; + case ID_C_MOVE: + editingFlowrate = false; + disp_speed_type(); + disp_print_speed(); + break; + case ID_C_EXT: + editingFlowrate = true; + disp_speed_type(); + disp_print_speed(); + break; + case ID_C_STEP: + if (uiCfg.stepPrintSpeed == 1) + uiCfg.stepPrintSpeed = 5; + else if (uiCfg.stepPrintSpeed == 5) + uiCfg.stepPrintSpeed = 10; + else + uiCfg.stepPrintSpeed = 1; + disp_speed_step(); + break; + case ID_C_RETURN: + clear_cur_ui(); + draw_return_ui(); + break; + } +} + +void lv_draw_change_speed() { + scr = lv_screen_create(CHANGE_SPEED_UI); + // Create an Image button + lv_big_button_create(scr, "F:/bmp_Add.bin", speed_menu.add, INTERVAL_V, titleHeight, event_handler, ID_C_ADD); + lv_big_button_create(scr, "F:/bmp_Dec.bin", speed_menu.dec, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight, event_handler, ID_C_DEC); + buttonMov = lv_imgbtn_create(scr, nullptr, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_C_MOVE); + buttonExt = lv_imgbtn_create(scr, nullptr, BTN_X_PIXEL + INTERVAL_V * 2, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_C_EXT); + buttonStep = lv_imgbtn_create(scr, nullptr, BTN_X_PIXEL * 2 + INTERVAL_V * 3, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_C_STEP); + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonMov); + lv_group_add_obj(g, buttonExt); + lv_group_add_obj(g, buttonStep); + } + #endif + lv_big_button_create(scr, "F:/bmp_return.bin", common_menu.text_back, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_C_RETURN); + + // Create labels on the image buttons + labelMov = lv_label_create_empty(buttonMov); + labelExt = lv_label_create_empty(buttonExt); + labelStep = lv_label_create_empty(buttonStep); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonMov); + lv_group_add_obj(g, buttonExt); + lv_group_add_obj(g, buttonStep); + } + #endif + + disp_speed_type(); + disp_speed_step(); + + printSpeedText = lv_label_create_empty(scr); + lv_obj_set_style(printSpeedText, &tft_style_label_rel); + disp_print_speed(); +} + +void disp_speed_step() { + if (uiCfg.stepPrintSpeed == 1) + lv_imgbtn_set_src_both(buttonStep, "F:/bmp_step1_percent.bin"); + else if (uiCfg.stepPrintSpeed == 5) + lv_imgbtn_set_src_both(buttonStep, "F:/bmp_step5_percent.bin"); + else if (uiCfg.stepPrintSpeed == 10) + lv_imgbtn_set_src_both(buttonStep, "F:/bmp_step10_percent.bin"); + + if (gCfgItems.multiple_language) { + if (uiCfg.stepPrintSpeed == 1) { + lv_label_set_text(labelStep, speed_menu.step_1percent); + lv_obj_align(labelStep, buttonStep, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + else if (uiCfg.stepPrintSpeed == 5) { + lv_label_set_text(labelStep, speed_menu.step_5percent); + lv_obj_align(labelStep, buttonStep, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + else if (uiCfg.stepPrintSpeed == 10) { + lv_label_set_text(labelStep, speed_menu.step_10percent); + lv_obj_align(labelStep, buttonStep, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + } +} + +void disp_print_speed() { + char buf[30] = { 0 }; + + public_buf_l[0] = '\0'; + + int16_t val; + const char *lbl; + if (editingFlowrate) { + lbl = speed_menu.extrude_speed; + val = planner.flow_percentage[0]; + } + else { + lbl = speed_menu.move_speed; + val = feedrate_percentage; + } + strcpy(public_buf_l, lbl); + strcat_P(public_buf_l, PSTR(": ")); + sprintf_P(buf, PSTR("%d%%"), val); + strcat(public_buf_l, buf); + lv_label_set_text(printSpeedText, public_buf_l); + lv_obj_align(printSpeedText, nullptr, LV_ALIGN_CENTER, 0, -65); +} + +void disp_speed_type() { + lv_imgbtn_set_src_both(buttonMov, editingFlowrate ? "F:/bmp_mov_changeSpeed.bin" : "F:/bmp_mov_sel.bin"); + lv_imgbtn_set_src_both(buttonExt, editingFlowrate ? "F:/bmp_extruct_sel.bin" : "F:/bmp_speed_extruct.bin"); + lv_obj_refresh_ext_draw_pad(buttonExt); + lv_obj_refresh_ext_draw_pad(buttonMov); + + if (gCfgItems.multiple_language) { + lv_label_set_text(labelMov, speed_menu.move); + lv_obj_align(labelMov, buttonMov, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + + lv_label_set_text(labelExt, speed_menu.extrude); + lv_obj_align(labelExt, buttonExt, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } +} + +void lv_clear_change_speed() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_change_speed.h b/Marlin/src/lcd/extui/mks_ui/draw_change_speed.h similarity index 83% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_change_speed.h rename to Marlin/src/lcd/extui/mks_ui/draw_change_speed.h index c4996a3ef732..66662d8811a1 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_change_speed.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_change_speed.h @@ -28,13 +28,12 @@ #define MIN_EXT_SPEED_PERCENT 10 #define MAX_EXT_SPEED_PERCENT 999 -extern void lv_draw_change_speed(void); -extern void lv_clear_change_speed(); -extern void disp_speed_step(); -extern void disp_print_speed(); -extern void disp_speed_type(); +void lv_draw_change_speed(); +void lv_clear_change_speed(); +void disp_speed_step(); +void disp_print_speed(); +void disp_speed_type(); -//extern void disp_temp_ready_print(); #ifdef __cplusplus } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.cpp b/Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.cpp new file mode 100644 index 000000000000..56b0e8f5caf6 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.cpp @@ -0,0 +1,205 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if BOTH(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) + +#include "lv_conf.h" +#include "draw_ui.h" + +#include "../../../MarlinCore.h" +#include "../../../module/temperature.h" + +#include "QR_Encode.h" + +extern lv_group_t * g; +static lv_obj_t * scr; +static lv_obj_t *button_bind_or_not = nullptr, *label_bind_or_not = nullptr; +static lv_obj_t *buttonReleaseBind = nullptr, *label_ReleaseBind = nullptr; +static lv_obj_t * text_id; + +static uint8_t unbinding_flag = 0; +static uint8_t id_mark = 0; + +#define ID_CLOUD_BIND_RETURN 1 +#define ID_CLOUD_BIND_OR_NOT 2 +#define ID_CLOUD_RELEASE_BIND 3 + +static void event_handler(lv_obj_t * obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + switch (obj->mks_obj_id) { + case ID_CLOUD_BIND_RETURN: + clear_cur_ui(); + draw_return_ui(); + break; + case ID_CLOUD_RELEASE_BIND: + if (cloud_para.state == 0x12) { + clear_cur_ui(); + lv_draw_dialog(DIALOG_TYPE_UNBIND); + } + break; + } +} + +void lv_draw_cloud_bind() { + lv_obj_t *buttonBack = nullptr, *label_Back = nullptr; + scr = lv_screen_create(BIND_UI); + + button_bind_or_not = lv_btn_create(scr, nullptr); + lv_obj_set_pos(button_bind_or_not, TFT_WIDTH - 130, TFT_HEIGHT - 80 * 3); + lv_obj_set_size(button_bind_or_not, PARA_UI_VALUE_BTN_X_SIZE + 15, PARA_UI_VALUE_BTN_Y_SIZE + 15); + lv_obj_set_event_cb_mks(button_bind_or_not, event_handler, ID_CLOUD_BIND_OR_NOT, nullptr, 0); + lv_btn_set_style(button_bind_or_not, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(button_bind_or_not, LV_BTN_STYLE_PR, &style_para_value); + label_bind_or_not = lv_label_create_empty(button_bind_or_not); + + buttonReleaseBind = lv_btn_create(scr, nullptr); + lv_obj_set_pos(buttonReleaseBind, TFT_WIDTH - 130, TFT_HEIGHT - 80 * 2); + lv_obj_set_size(buttonReleaseBind, PARA_UI_VALUE_BTN_X_SIZE + 15, PARA_UI_VALUE_BTN_Y_SIZE + 15); + lv_obj_set_event_cb_mks(buttonReleaseBind, event_handler, ID_CLOUD_RELEASE_BIND, nullptr, 0); + label_ReleaseBind = lv_label_create_empty(buttonReleaseBind); + lv_label_set_text(label_ReleaseBind, cloud_menu.unbind); + lv_obj_align(label_ReleaseBind, buttonReleaseBind, LV_ALIGN_CENTER, 0, 0); + + buttonBack = lv_btn_create(scr, nullptr); + lv_obj_set_pos(buttonBack, TFT_WIDTH - 130, TFT_HEIGHT - 80); + lv_obj_set_size(buttonBack, PARA_UI_VALUE_BTN_X_SIZE + 15, PARA_UI_VALUE_BTN_Y_SIZE + 15); + lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_CLOUD_BIND_RETURN, nullptr, 0); + lv_btn_set_style(buttonBack, LV_BTN_STYLE_REL, &style_para_back); + lv_btn_set_style(buttonBack, LV_BTN_STYLE_PR, &style_para_back); + label_Back = lv_label_create_empty(buttonBack); + lv_label_set_text(label_Back, common_menu.text_back); + lv_obj_align(label_Back, buttonBack, LV_ALIGN_CENTER, 0, 0); + + #if BUTTONS_EXIST(EN1, EN2, ENC) + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonReleaseBind); + lv_group_add_obj(g, buttonBack); + } + #endif + + text_id = lv_label_create_empty(scr); + lv_obj_set_pos(text_id, 50, 60 + 200 + 20); + lv_obj_set_style(text_id, &tft_style_label_rel); + lv_label_set_text(text_id, (char *)cloud_para.id); + + id_mark = 0; + + disp_bind_state(); +} + +void disp_bind_state() { + if (cloud_para.state != 0x12) + unbinding_flag = 0; + + if (unbinding_flag) { + lv_label_set_text(label_bind_or_not, cloud_menu.unbinding); + lv_obj_align(label_bind_or_not, button_bind_or_not, LV_ALIGN_CENTER, 0, 0); + lv_btn_set_style(buttonReleaseBind, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonReleaseBind, LV_BTN_STYLE_PR, &style_para_value); + } + else { + if (cloud_para.state == 0x10) { + lv_label_set_text(label_bind_or_not, cloud_menu.disconnected); + lv_obj_align(label_bind_or_not, button_bind_or_not, LV_ALIGN_CENTER, 0, 0); + } + else if (cloud_para.state == 0x11) { + lv_label_set_text(label_bind_or_not, cloud_menu.unbinded); + lv_obj_align(label_bind_or_not, button_bind_or_not, LV_ALIGN_CENTER, 0, 0); + } + else if (cloud_para.state == 0x12) { + lv_label_set_text(label_bind_or_not, cloud_menu.binded); + lv_obj_align(label_bind_or_not, button_bind_or_not, LV_ALIGN_CENTER, 0, 0); + } + else { + lv_label_set_text(label_bind_or_not, cloud_menu.disable); + lv_obj_align(label_bind_or_not, button_bind_or_not, LV_ALIGN_CENTER, 0, 0); + } + } + + if (cloud_para.state == 0x12 && !unbinding_flag) { + lv_btn_set_style(buttonReleaseBind, LV_BTN_STYLE_REL, &style_para_back); + lv_btn_set_style(buttonReleaseBind, LV_BTN_STYLE_PR, &style_para_back); + } + else { + lv_btn_set_style(buttonReleaseBind, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonReleaseBind, LV_BTN_STYLE_PR, &style_para_value); + } +} + +static char last_cloud_state = 0; +void refresh_bind_ui() { + if ((last_cloud_state != cloud_para.state) || unbinding_flag) { + disp_bind_state(); + last_cloud_state = cloud_para.state; + } + if (cloud_para.id[0]) { + if (!id_mark) { + display_qrcode((uint8_t *)cloud_para.id); + lv_label_set_text(text_id, (char *)cloud_para.id); + } + } + else + id_mark = 0; +} + +void display_qrcode(uint8_t *qrcode_data) { + uint8_t i, j; + uint16_t x, y, p; + + if (!id_mark) { + EncodeData((char *)qrcode_data); + id_mark = 1; + } + + lv_fill_rect(10, QRCODE_Y, 300, QRCODE_Y + 300, LV_COLOR_WHITE); + + if (m_nSymbleSize * 2 > QRCODE_WIDTH) return; + + for (i = 0; i < 40; i++) + if ((m_nSymbleSize * i * 2) > QRCODE_WIDTH) break; + + p = (i - 1) * 2; + + x = QRCODE_X + 70; + y = QRCODE_Y + 70; + + for (i = 0; i < m_nSymbleSize; i++) + for (j = 0; j < m_nSymbleSize; j++) + if (m_byModuleData[i][j] == 1) + lv_fill_rect(x + p * i, y + p * j, x + p * (i + 1) - 1, y + p * (j + 1) - 1, LV_COLOR_BACKGROUND); +} + +void cloud_unbind() { + package_to_wifi(WIFI_CLOUD_UNBIND, nullptr, 0); + unbinding_flag = 1; +} + +void lv_clear_cloud_bind() { + #if BUTTONS_EXIST(EN1, EN2, ENC) + if (gCfgItems.encoder_enable) + lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.h b/Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.h new file mode 100644 index 000000000000..917b52ab0ab0 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.h @@ -0,0 +1,37 @@ +/** + * 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 + +#ifdef __cplusplus +extern "C" { /* C-declarations for C++ */ +#endif + +void lv_draw_cloud_bind(); +void lv_clear_cloud_bind(); +void disp_bind_state(); +void refresh_bind_ui(); +void display_qrcode(uint8_t *qrcode_data); +void cloud_unbind(); + +#ifdef __cplusplus +} /* C-declarations for C++ */ +#endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp b/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp new file mode 100644 index 000000000000..638d0c5ec359 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp @@ -0,0 +1,567 @@ +/** + * 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 . + * + */ + +/** + * draw_dialog.cpp + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include + +#include "../../../sd/cardreader.h" +#include "../../../gcode/queue.h" +#include "../../../module/temperature.h" +#include "../../../module/planner.h" +#include "../../../gcode/gcode.h" +#include "../../../inc/MarlinConfig.h" + +#if ENABLED(EEPROM_SETTINGS) + #include "../../../module/settings.h" +#endif + +#if ENABLED(POWER_LOSS_RECOVERY) + #include "../../../feature/powerloss.h" +#endif + +#if ENABLED(PARK_HEAD_ON_PAUSE) + #include "../../../feature/pause.h" +#endif + +#if ENABLED(TOUCH_SCREEN_CALIBRATION) + #include "../../tft_io/touch_calibration.h" + #include "draw_touch_calibration.h" +#endif + +extern lv_group_t *g; +static lv_obj_t *scr, *tempText1, *filament_bar; + +extern uint8_t sel_id; +extern bool once_flag, gcode_preview_over; +extern int upload_result; +extern uint32_t upload_time_sec; +extern uint32_t upload_size; +extern bool temps_update_flag; + +//#define CANCEL_ON_RIGHT // Put 'Cancel' on the right (as it was before) + +#define BTN_OK_X TERN(CANCEL_ON_RIGHT, 100, 280) +#define BTN_CANCEL_X TERN(CANCEL_ON_RIGHT, 280, 100) +#define BTN_OK_Y 180 +#define BTN_CANCEL_Y 180 + +static void btn_ok_event_cb(lv_obj_t *btn, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + if (DIALOG_IS(TYPE_PRINT_FILE)) { + #if HAS_GCODE_PREVIEW + preview_gcode_prehandle(list_file.file_name[sel_id]); + #endif + reset_print_time(); + start_print_time(); + + uiCfg.print_state = WORKING; + lv_clear_dialog(); + lv_draw_printing(); + + #if ENABLED(SDSUPPORT) + if (!gcode_preview_over) { + char *cur_name; + cur_name = strrchr(list_file.file_name[sel_id], '/'); + + SdFile file, *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()) { + feedrate_percentage = 100; + planner.flow_percentage[0] = 100; + planner.e_factor[0] = planner.flow_percentage[0] * 0.01f; + #if HAS_MULTI_EXTRUDER + planner.flow_percentage[1] = 100; + planner.e_factor[1] = planner.flow_percentage[1] * 0.01f; + #endif + card.startOrResumeFilePrinting(); + #if ENABLED(POWER_LOSS_RECOVERY) + recovery.prepare(); + #endif + once_flag = false; + } + } + #endif + } + else if (DIALOG_IS(TYPE_STOP)) { + wait_for_heatup = false; + stop_print_time(); + lv_clear_dialog(); + lv_draw_ready_print(); + + #if ENABLED(SDSUPPORT) + uiCfg.print_state = IDLE; + card.abortFilePrintSoon(); + #endif + } + else if (DIALOG_IS(TYPE_FINISH_PRINT)) { + clear_cur_ui(); + lv_draw_ready_print(); + } + #if ENABLED(ADVANCED_PAUSE_FEATURE) + else if (DIALOG_IS(PAUSE_MESSAGE_WAITING, PAUSE_MESSAGE_INSERT, PAUSE_MESSAGE_HEAT)) + wait_for_user = false; + else if (DIALOG_IS(PAUSE_MESSAGE_OPTION)) + pause_menu_response = PAUSE_RESPONSE_EXTRUDE_MORE; + else if (DIALOG_IS(PAUSE_MESSAGE_RESUME)) { + clear_cur_ui(); + draw_return_ui(); + } + #endif + else if (DIALOG_IS(STORE_EEPROM_TIPS)) { + TERN_(EEPROM_SETTINGS, (void)settings.save()); + clear_cur_ui(); + draw_return_ui(); + } + else if (DIALOG_IS(READ_EEPROM_TIPS)) { + TERN_(EEPROM_SETTINGS, (void)settings.load()); + clear_cur_ui(); + draw_return_ui(); + } + else if (DIALOG_IS(REVERT_EEPROM_TIPS)) { + TERN_(EEPROM_SETTINGS, (void)settings.reset()); + clear_cur_ui(); + #if ENABLED(TOUCH_SCREEN_CALIBRATION) + const bool do_draw_cal = touch_calibration.need_calibration(); + if (do_draw_cal) { + disp_state_stack._disp_index--; // We are asynchronous from the dialog, so let's remove the dialog from the stack + lv_draw_touch_calibration_screen(); + } + #else + constexpr bool do_draw_cal = false; + #endif + if (!do_draw_cal) draw_return_ui(); + } + else if (DIALOG_IS(WIFI_CONFIG_TIPS)) { + uiCfg.configWifi = true; + clear_cur_ui(); + draw_return_ui(); + } + else if (DIALOG_IS(TYPE_FILAMENT_HEAT_LOAD_COMPLETED)) + uiCfg.filament_heat_completed_load = true; + else if (DIALOG_IS(TYPE_FILAMENT_HEAT_UNLOAD_COMPLETED)) + uiCfg.filament_heat_completed_unload = true; + else if (DIALOG_IS(TYPE_FILAMENT_LOAD_COMPLETED, TYPE_FILAMENT_UNLOAD_COMPLETED)) { + clear_cur_ui(); + draw_return_ui(); + } + #if ENABLED(MKS_WIFI_MODULE) + else if (DIALOG_IS(TYPE_UNBIND)) { + cloud_unbind(); + clear_cur_ui(); + draw_return_ui(); + } + #endif + else { + clear_cur_ui(); + draw_return_ui(); + } +} + +static void btn_cancel_event_cb(lv_obj_t *btn, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + if (DIALOG_IS(PAUSE_MESSAGE_OPTION)) { + TERN_(ADVANCED_PAUSE_FEATURE, pause_menu_response = PAUSE_RESPONSE_RESUME_PRINT); + } + else if (DIALOG_IS(TYPE_FILAMENT_LOAD_HEAT, TYPE_FILAMENT_UNLOAD_HEAT, TYPE_FILAMENT_HEAT_LOAD_COMPLETED, TYPE_FILAMENT_HEAT_UNLOAD_COMPLETED)) { + thermalManager.setTargetHotend(uiCfg.hotendTargetTempBak, uiCfg.extruderIndex); + clear_cur_ui(); + draw_return_ui(); + } + else if (DIALOG_IS(TYPE_FILAMENT_LOADING, TYPE_FILAMENT_UNLOADING)) { + queue.enqueue_one_P(PSTR("M410")); + uiCfg.filament_rate = 0; + uiCfg.filament_loading_completed = false; + uiCfg.filament_unloading_completed = false; + uiCfg.filament_loading_time_flg = false; + uiCfg.filament_loading_time_cnt = 0; + uiCfg.filament_unloading_time_flg = false; + uiCfg.filament_unloading_time_cnt = 0; + thermalManager.setTargetHotend(uiCfg.hotendTargetTempBak, uiCfg.extruderIndex); + clear_cur_ui(); + draw_return_ui(); + } + else { + clear_cur_ui(); + draw_return_ui(); + } +} + +void lv_draw_dialog(uint8_t type) { + lv_obj_t *btnOk = nullptr, *btnCancel = nullptr; + uiCfg.dialogType = type; + scr = lv_screen_create(DIALOG_UI); + + lv_obj_t *labelDialog = lv_label_create(scr, ""); + + if (DIALOG_IS(TYPE_FINISH_PRINT, PAUSE_MESSAGE_RESUME)) { + btnOk = lv_button_btn_create(scr, BTN_OK_X + 90, BTN_OK_Y, 100, 50, btn_ok_event_cb); + lv_obj_t *labelOk = lv_label_create_empty(btnOk); // Add a label to the button + lv_label_set_text(labelOk, print_file_dialog_menu.confirm); // Set the labels text + } + else if (DIALOG_IS(PAUSE_MESSAGE_WAITING, PAUSE_MESSAGE_INSERT, PAUSE_MESSAGE_HEAT)) { + btnOk = lv_button_btn_create(scr, BTN_OK_X + 90, BTN_OK_Y, 100, 50, btn_ok_event_cb); + lv_obj_t *labelOk = lv_label_create_empty(btnOk); // Add a label to the button + lv_label_set_text(labelOk, print_file_dialog_menu.confirm); // Set the labels text + } + else if (DIALOG_IS(PAUSE_MESSAGE_PARKING, PAUSE_MESSAGE_CHANGING, PAUSE_MESSAGE_UNLOAD, PAUSE_MESSAGE_LOAD, PAUSE_MESSAGE_PURGE, PAUSE_MESSAGE_RESUME, PAUSE_MESSAGE_HEATING)) { + // nothing to do + } + else if (DIALOG_IS(WIFI_ENABLE_TIPS)) { + btnCancel = lv_button_btn_create(scr, BTN_OK_X + 90, BTN_OK_Y, 100, 50, btn_cancel_event_cb); + lv_obj_t *labelCancel = lv_label_create_empty(btnCancel); + lv_label_set_text(labelCancel, print_file_dialog_menu.cancel); + } + else if (DIALOG_IS(TRANSFER_NO_DEVICE)) { + btnCancel = lv_button_btn_create(scr, BTN_OK_X + 90, BTN_OK_Y, 100, 50, btn_cancel_event_cb); + lv_obj_t *labelCancel = lv_label_create_empty(btnCancel); + lv_label_set_text(labelCancel, print_file_dialog_menu.cancel); + } + #if ENABLED(MKS_WIFI_MODULE) + else if (DIALOG_IS(TYPE_UPLOAD_FILE)) { + if (upload_result == 2) { + btnCancel = lv_button_btn_create(scr, BTN_OK_X + 90, BTN_OK_Y, 100, 50, btn_cancel_event_cb); + lv_obj_t *labelCancel = lv_label_create_empty(btnCancel); + lv_label_set_text(labelCancel, print_file_dialog_menu.cancel); + } + else if (upload_result == 3) { + btnOk = lv_button_btn_create(scr, BTN_OK_X + 90, BTN_OK_Y, 100, 50, btn_ok_event_cb); + lv_obj_t *labelOk = lv_label_create_empty(btnOk); + lv_label_set_text(labelOk, print_file_dialog_menu.confirm); + } + } + else if (DIALOG_IS(TYPE_UPDATE_ESP_FIRMWARE)) { + // nothing to do + } + #endif + else if (DIALOG_IS(TYPE_FILAMENT_LOAD_HEAT, TYPE_FILAMENT_UNLOAD_HEAT)) { + btnCancel = lv_button_btn_create(scr, BTN_OK_X+90, BTN_OK_Y, 100, 50, btn_cancel_event_cb); + lv_obj_t *labelCancel = lv_label_create_empty(btnCancel); + lv_label_set_text(labelCancel, print_file_dialog_menu.cancel); + + tempText1 = lv_label_create_empty(scr); + filament_sprayer_temp(); + } + else if (DIALOG_IS(TYPE_FILAMENT_LOAD_COMPLETED, TYPE_FILAMENT_UNLOAD_COMPLETED)) { + btnOk = lv_button_btn_create(scr, BTN_OK_X + 90, BTN_OK_Y, 100, 50, btn_ok_event_cb); + lv_obj_t *labelOk = lv_label_create_empty(btnOk); + lv_label_set_text(labelOk, print_file_dialog_menu.confirm); + } + else if (DIALOG_IS(TYPE_FILAMENT_LOADING, TYPE_FILAMENT_UNLOADING)) { + btnCancel = lv_button_btn_create(scr, BTN_OK_X + 90, BTN_OK_Y, 100, 50, btn_cancel_event_cb); + lv_obj_t *labelCancel = lv_label_create_empty(btnCancel); + lv_label_set_text(labelCancel, print_file_dialog_menu.cancel); + + filament_bar = lv_bar_create(scr, nullptr); + lv_obj_set_pos(filament_bar, (TFT_WIDTH-400)/2, ((TFT_HEIGHT - titleHeight)-40)/2); + lv_obj_set_size(filament_bar, 400, 25); + lv_bar_set_style(filament_bar, LV_BAR_STYLE_INDIC, &lv_bar_style_indic); + lv_bar_set_anim_time(filament_bar, 1000); + lv_bar_set_value(filament_bar, 0, LV_ANIM_ON); + } + else { + btnOk = lv_button_btn_create(scr, BTN_OK_X, BTN_OK_Y, 100, 50, btn_ok_event_cb); + lv_obj_t *labelOk = lv_label_create_empty(btnOk); // Add a label to the button + + btnCancel = lv_button_btn_create(scr, BTN_CANCEL_X, BTN_CANCEL_Y, 100, 50, btn_cancel_event_cb); + lv_obj_t *labelCancel = lv_label_create_empty(btnCancel); // Add a label to the button + + if (DIALOG_IS(PAUSE_MESSAGE_OPTION)) { + lv_label_set_text(labelOk, pause_msg_menu.purgeMore); // Set the labels text + lv_label_set_text(labelCancel, pause_msg_menu.continuePrint); + } + else { + lv_label_set_text(labelOk, print_file_dialog_menu.confirm); // Set the labels text + lv_label_set_text(labelCancel, print_file_dialog_menu.cancel); + } + } + if (DIALOG_IS(TYPE_PRINT_FILE)) { + lv_label_set_text(labelDialog, print_file_dialog_menu.print_file); + lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -20); + + lv_obj_t *labelFile = lv_label_create(scr, list_file.long_name[sel_id]); + lv_obj_align(labelFile, nullptr, LV_ALIGN_CENTER, 0, -60); + } + else if (DIALOG_IS(TYPE_STOP)) { + lv_label_set_text(labelDialog, print_file_dialog_menu.cancel_print); + lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -20); + } + else if (DIALOG_IS(TYPE_FINISH_PRINT)) { + lv_label_set_text(labelDialog, print_file_dialog_menu.print_finish); + lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -20); + } + else if (DIALOG_IS(PAUSE_MESSAGE_PARKING)) { + lv_label_set_text(labelDialog, pause_msg_menu.pausing); + lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -20); + } + else if (DIALOG_IS(PAUSE_MESSAGE_CHANGING)) { + lv_label_set_text(labelDialog, pause_msg_menu.changing); + lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -20); + } + else if (DIALOG_IS(PAUSE_MESSAGE_UNLOAD)) { + lv_label_set_text(labelDialog, pause_msg_menu.unload); + lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -20); + } + else if (DIALOG_IS(PAUSE_MESSAGE_WAITING)) { + lv_label_set_text(labelDialog, pause_msg_menu.waiting); + lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -20); + } + else if (DIALOG_IS(PAUSE_MESSAGE_INSERT)) { + lv_label_set_text(labelDialog, pause_msg_menu.insert); + lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -20); + } + else if (DIALOG_IS(PAUSE_MESSAGE_LOAD)) { + lv_label_set_text(labelDialog, pause_msg_menu.load); + lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -20); + } + else if (DIALOG_IS(PAUSE_MESSAGE_PURGE)) { + lv_label_set_text(labelDialog, pause_msg_menu.purge); + lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -20); + } + else if (DIALOG_IS(PAUSE_MESSAGE_RESUME)) { + lv_label_set_text(labelDialog, pause_msg_menu.resume); + lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -20); + } + else if (DIALOG_IS(PAUSE_MESSAGE_HEAT)) { + lv_label_set_text(labelDialog, pause_msg_menu.heat); + lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -20); + } + else if (DIALOG_IS(PAUSE_MESSAGE_HEATING)) { + lv_label_set_text(labelDialog, pause_msg_menu.heating); + lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -20); + } + else if (DIALOG_IS(PAUSE_MESSAGE_OPTION)) { + lv_label_set_text(labelDialog, pause_msg_menu.option); + lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -20); + } + else if (DIALOG_IS(STORE_EEPROM_TIPS)) { + lv_label_set_text(labelDialog, eeprom_menu.storeTips); + lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -20); + } + else if (DIALOG_IS(READ_EEPROM_TIPS)) { + lv_label_set_text(labelDialog, eeprom_menu.readTips); + lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -20); + } + else if (DIALOG_IS(REVERT_EEPROM_TIPS)) { + lv_label_set_text(labelDialog, eeprom_menu.revertTips); + lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -20); + } + else if (DIALOG_IS(WIFI_CONFIG_TIPS)) { + lv_label_set_text(labelDialog, machine_menu.wifiConfigTips); + lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -20); + } + else if (DIALOG_IS(WIFI_ENABLE_TIPS)) { + lv_label_set_text(labelDialog, print_file_dialog_menu.wifi_enable_tips); + lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -20); + } + else if (DIALOG_IS(TRANSFER_NO_DEVICE)) { + 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) { + lv_label_set_text(labelDialog, DIALOG_UPLOAD_ING_EN); + lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -20); + } + else if (upload_result == 2) { + lv_label_set_text(labelDialog, DIALOG_UPLOAD_ERROR_EN); + lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -20); + } + else if (upload_result == 3) { + char buf[200]; + int _index = 0; + + strcpy_P(buf, PSTR(DIALOG_UPLOAD_FINISH_EN)); + _index = strlen(buf); + buf[_index++] = '\n'; + strcat_P(buf, PSTR(DIALOG_UPLOAD_SIZE_EN)); + + _index = strlen(buf); + buf[_index++] = ':'; + sprintf_P(&buf[_index], PSTR(" %d KBytes\n"), (int)(upload_size / 1024)); + + strcat_P(buf, PSTR(DIALOG_UPLOAD_TIME_EN)); + _index = strlen(buf); + buf[_index++] = ':'; + sprintf_P(&buf[_index], PSTR(" %d s\n"), (int)upload_time_sec); + + strcat_P(buf, PSTR(DIALOG_UPLOAD_SPEED_EN)); + _index = strlen(buf); + buf[_index++] = ':'; + sprintf_P(&buf[_index], PSTR(" %d KBytes/s\n"), (int)(upload_size / upload_time_sec / 1024)); + + lv_label_set_text(labelDialog, buf); + lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -20); + } + } + else if (DIALOG_IS(TYPE_UPDATE_ESP_FIRMWARE)) { + lv_label_set_text(labelDialog, DIALOG_UPDATE_WIFI_FIRMWARE_EN); + 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); + } + else if (DIALOG_IS(TYPE_FILAMENT_HEAT_LOAD_COMPLETED)) { + lv_label_set_text(labelDialog, filament_menu.filament_dialog_load_heat_confirm); + lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -20); + } + else if (DIALOG_IS(TYPE_FILAMENT_UNLOAD_HEAT)) { + lv_label_set_text(labelDialog, filament_menu.filament_dialog_unload_heat); + lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -20); + } + else if (DIALOG_IS(TYPE_FILAMENT_HEAT_UNLOAD_COMPLETED)) { + lv_label_set_text(labelDialog, filament_menu.filament_dialog_unload_heat_confirm); + lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -20); + } + else if (DIALOG_IS(TYPE_FILAMENT_LOAD_COMPLETED)) { + lv_label_set_text(labelDialog, filament_menu.filament_dialog_load_completed); + lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -20); + } + else if (DIALOG_IS(TYPE_FILAMENT_UNLOAD_COMPLETED)) { + lv_label_set_text(labelDialog, filament_menu.filament_dialog_unload_completed); + lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -20); + } + else if (DIALOG_IS(TYPE_FILAMENT_LOADING)) { + lv_label_set_text(labelDialog, filament_menu.filament_dialog_loading); + lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -70); + } + else if (DIALOG_IS(TYPE_FILAMENT_UNLOADING)) { + lv_label_set_text(labelDialog, filament_menu.filament_dialog_unloading); + lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -70); + } + #if ENABLED(MKS_WIFI_MODULE) + else if (DIALOG_IS(TYPE_UNBIND)) { + lv_label_set_text(labelDialog, common_menu.unbind_printer_tips); + lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -70); + } + #endif + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + if (btnOk) lv_group_add_obj(g, btnOk); + if (btnCancel) lv_group_add_obj(g, btnCancel); + } + #endif +} + +void filament_sprayer_temp() { + char buf[20] = {0}; + sprintf(buf, preheat_menu.value_state, thermalManager.wholeDegHotend(uiCfg.extruderIndex), thermalManager.degTargetHotend(uiCfg.extruderIndex)); + + strcpy(public_buf_l, uiCfg.extruderIndex < 1 ? extrude_menu.ext1 : extrude_menu.ext2); + strcat_P(public_buf_l, PSTR(": ")); + strcat(public_buf_l, buf); + lv_label_set_text(tempText1, public_buf_l); + lv_obj_align(tempText1, nullptr, LV_ALIGN_CENTER, 0, -50); +} + +void filament_dialog_handle() { + if (temps_update_flag && (DIALOG_IS(TYPE_FILAMENT_LOAD_HEAT, TYPE_FILAMENT_UNLOAD_HEAT))) { + filament_sprayer_temp(); + temps_update_flag = false; + } + if (uiCfg.filament_heat_completed_load) { + uiCfg.filament_heat_completed_load = false; + lv_clear_dialog(); + lv_draw_dialog(DIALOG_TYPE_FILAMENT_LOADING); + planner.synchronize(); + uiCfg.filament_loading_time_flg = true; + uiCfg.filament_loading_time_cnt = 0; + sprintf_P(public_buf_m, PSTR("T%d\nG91\nG1 E%d F%d\nG90"), uiCfg.extruderIndex, gCfgItems.filamentchange_load_length, gCfgItems.filamentchange_load_speed); + queue.inject(public_buf_m); + } + if (uiCfg.filament_heat_completed_unload) { + uiCfg.filament_heat_completed_unload = false; + lv_clear_dialog(); + lv_draw_dialog(DIALOG_TYPE_FILAMENT_UNLOADING); + planner.synchronize(); + uiCfg.filament_unloading_time_flg = true; + uiCfg.filament_unloading_time_cnt = 0; + sprintf_P(public_buf_m, PSTR("T%d\nG91\nG1 E-%d F%d\nG90"), uiCfg.extruderIndex, gCfgItems.filamentchange_unload_length, gCfgItems.filamentchange_unload_speed); + queue.inject(public_buf_m); + } + + if (uiCfg.filament_load_heat_flg) { + const celsius_t diff = thermalManager.wholeDegHotend(uiCfg.extruderIndex) - gCfgItems.filament_limit_temp; + if (ABS(diff) < 2 || diff > 0) { + uiCfg.filament_load_heat_flg = false; + lv_clear_dialog(); + lv_draw_dialog(DIALOG_TYPE_FILAMENT_HEAT_LOAD_COMPLETED); + } + } + + if (uiCfg.filament_loading_completed) { + uiCfg.filament_rate = 0; + uiCfg.filament_loading_completed = false; + lv_clear_dialog(); + lv_draw_dialog(DIALOG_TYPE_FILAMENT_LOAD_COMPLETED); + } + + if (uiCfg.filament_unload_heat_flg) { + const celsius_t diff = thermalManager.wholeDegHotend(uiCfg.extruderIndex) - gCfgItems.filament_limit_temp; + if (ABS(diff) < 2 || diff > 0) { + uiCfg.filament_unload_heat_flg = false; + lv_clear_dialog(); + lv_draw_dialog(DIALOG_TYPE_FILAMENT_HEAT_UNLOAD_COMPLETED); + } + } + + if (uiCfg.filament_unloading_completed) { + uiCfg.filament_rate = 0; + uiCfg.filament_unloading_completed = false; + lv_clear_dialog(); + lv_draw_dialog(DIALOG_TYPE_FILAMENT_UNLOAD_COMPLETED); + } + + if (DIALOG_IS(TYPE_FILAMENT_LOADING, TYPE_FILAMENT_UNLOADING)) + lv_filament_setbar(); +} + +void lv_filament_setbar() { + lv_bar_set_value(filament_bar, uiCfg.filament_rate, LV_ANIM_ON); +} + +void lv_clear_dialog() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_dialog.h b/Marlin/src/lcd/extui/mks_ui/draw_dialog.h new file mode 100644 index 000000000000..7e98a80c0a2b --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_dialog.h @@ -0,0 +1,85 @@ +/** + * 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 + +#ifdef __cplusplus + extern "C" { /* C-declarations for C++ */ +#endif + +enum { + DIALOG_TYPE_STOP = 0, + DIALOG_TYPE_PRINT_FILE, + DIALOG_TYPE_REPRINT_NO_FILE, + + DIALOG_TYPE_M80_FAIL, + DIALOG_TYPE_MESSAGE_ERR1, + + DIALOG_TYPE_UPDATE_ESP_FIRMWARE, + DIALOG_TYPE_UPDATE_ESP_DATA, + DIALOG_TYPE_UPLOAD_FILE, + DIALOG_TYPE_UNBIND, + + DIALOG_TYPE_FILAMENT_LOAD_HEAT, + DIALOG_TYPE_FILAMENT_HEAT_LOAD_COMPLETED, + DIALOG_TYPE_FILAMENT_LOADING, + DIALOG_TYPE_FILAMENT_LOAD_COMPLETED, + DIALOG_TYPE_FILAMENT_UNLOAD_HEAT, + DIALOG_TYPE_FILAMENT_HEAT_UNLOAD_COMPLETED, + DIALOG_TYPE_FILAMENT_UNLOADING, + DIALOG_TYPE_FILAMENT_UNLOAD_COMPLETED, + + DIALOG_TYPE_FILE_LOADING, + + DIALOG_TYPE_FILAMENT_NO_PRESS, + DIALOG_TYPE_FINISH_PRINT, + + DIALOG_WIFI_ENABLE_TIPS, + + DIALOG_PAUSE_MESSAGE_PARKING, + DIALOG_PAUSE_MESSAGE_CHANGING, + DIALOG_PAUSE_MESSAGE_UNLOAD, + DIALOG_PAUSE_MESSAGE_WAITING, + DIALOG_PAUSE_MESSAGE_INSERT, + DIALOG_PAUSE_MESSAGE_LOAD, + DIALOG_PAUSE_MESSAGE_PURGE, + DIALOG_PAUSE_MESSAGE_RESUME, + DIALOG_PAUSE_MESSAGE_HEAT, + DIALOG_PAUSE_MESSAGE_HEATING, + DIALOG_PAUSE_MESSAGE_OPTION, + + DIALOG_STORE_EEPROM_TIPS, + DIALOG_READ_EEPROM_TIPS, + DIALOG_REVERT_EEPROM_TIPS, + + DIALOG_WIFI_CONFIG_TIPS, + DIALOG_TRANSFER_NO_DEVICE +}; + +void lv_draw_dialog(uint8_t type); +void lv_clear_dialog(); +void filament_sprayer_temp(); +void filament_dialog_handle(); +void lv_filament_setbar(); + +#ifdef __cplusplus + } /* C-declarations for C++ */ +#endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_eeprom_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_eeprom_settings.cpp new file mode 100644 index 000000000000..b96c65e5478b --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_eeprom_settings.cpp @@ -0,0 +1,82 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include + +#include "../../../inc/MarlinConfig.h" + +extern lv_group_t *g; +static lv_obj_t *scr; + +enum { + ID_EEPROM_RETURN = 1, + ID_EEPROM_STORE, + ID_EEPROM_STORE_ARROW, + ID_EEPROM_READ, + ID_EEPROM_READ_ARROW, + ID_EEPROM_REVERT, + ID_EEPROM_REVERT_ARROW +}; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + switch (obj->mks_obj_id) { + case ID_EEPROM_RETURN: + lv_clear_eeprom_settings(); + draw_return_ui(); + break; + case ID_EEPROM_STORE: + lv_clear_eeprom_settings(); + lv_draw_dialog(DIALOG_STORE_EEPROM_TIPS); + break; + #if 0 + case ID_EEPROM_READ: + lv_clear_eeprom_settings(); + lv_draw_dialog(DIALOG_READ_EEPROM_TIPS); + break; + #endif + case ID_EEPROM_REVERT: + lv_clear_eeprom_settings(); + lv_draw_dialog(DIALOG_REVERT_EEPROM_TIPS); + break; + } +} + +void lv_draw_eeprom_settings() { + scr = lv_screen_create(EEPROM_SETTINGS_UI); + lv_screen_menu_item(scr, eeprom_menu.revert, PARA_UI_POS_X, PARA_UI_POS_Y, event_handler, ID_EEPROM_REVERT, 0); + lv_screen_menu_item(scr, eeprom_menu.store, PARA_UI_POS_X, PARA_UI_POS_Y * 2, event_handler, ID_EEPROM_STORE, 1); + lv_big_button_create(scr, "F:/bmp_back70x40.bin", common_menu.text_back, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y, event_handler, ID_EEPROM_RETURN, true); +} + +void lv_clear_eeprom_settings() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_eeprom_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_eeprom_settings.h similarity index 92% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_eeprom_settings.h rename to Marlin/src/lcd/extui/mks_ui/draw_eeprom_settings.h index 6d5ecf0870eb..575ebbc6a2e6 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_eeprom_settings.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_eeprom_settings.h @@ -25,8 +25,8 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_eeprom_settings(void); -extern void lv_clear_eeprom_settings(); +void lv_draw_eeprom_settings(); +void lv_clear_eeprom_settings(); #ifdef __cplusplus } /* C-declarations for C++ */ diff --git a/Marlin/src/lcd/extui/mks_ui/draw_encoder_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_encoder_settings.cpp new file mode 100644 index 000000000000..4c56205465c2 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_encoder_settings.cpp @@ -0,0 +1,72 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include + +#include "../../../inc/MarlinConfig.h" + +#if BUTTONS_EXIST(EN1, EN2) + +extern lv_group_t *g; +static lv_obj_t *scr; +static lv_obj_t *buttonEncoderState = nullptr; + +enum { + ID_ENCODER_RETURN = 1, + ID_ENCODER_STATE +}; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + switch (obj->mks_obj_id) { + case ID_ENCODER_RETURN: + lv_clear_encoder_settings(); + draw_return_ui(); + break; + case ID_ENCODER_STATE: + gCfgItems.encoder_enable ^= true; + lv_screen_menu_item_onoff_update(buttonEncoderState, gCfgItems.encoder_enable); + update_spi_flash(); + break; + } +} + +void lv_draw_encoder_settings() { + scr = lv_screen_create(ENCODER_SETTINGS_UI, machine_menu.EncoderConfTitle); + buttonEncoderState = lv_screen_menu_item_onoff(scr, machine_menu.EncoderConfText, PARA_UI_POS_X, PARA_UI_POS_Y, event_handler, ID_ENCODER_STATE, 0, gCfgItems.encoder_enable); + lv_big_button_create(scr, "F:/bmp_back70x40.bin", common_menu.text_back, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y, event_handler, ID_ENCODER_RETURN, true); +} + +void lv_clear_encoder_settings() { + #if HAS_ROTARY_ENCODER + lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // BUTTONS_EXIST(EN1, EN2) + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_encoder_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_encoder_settings.h similarity index 92% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_encoder_settings.h rename to Marlin/src/lcd/extui/mks_ui/draw_encoder_settings.h index 62892a6ec142..bbf0c3485877 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_encoder_settings.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_encoder_settings.h @@ -25,8 +25,8 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_encoder_settings(void); -extern void lv_clear_encoder_settings(); +void lv_draw_encoder_settings(); +void lv_clear_encoder_settings(); #ifdef __cplusplus } /* C-declarations for C++ */ diff --git a/Marlin/src/lcd/extui/mks_ui/draw_error_message.cpp b/Marlin/src/lcd/extui/mks_ui/draw_error_message.cpp new file mode 100644 index 000000000000..48ff56253b81 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_error_message.cpp @@ -0,0 +1,44 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include +#include "tft_lvgl_configuration.h" +#include "SPI_TFT.h" +#include "../../../inc/MarlinConfig.h" +#include "mks_hardware.h" + +static lv_obj_t *scr; + +void lv_draw_error_message(PGM_P const msg) { + SPI_TFT.LCD_clear(0x0000); + if (msg) disp_string((TFT_WIDTH - strlen(msg) * 16) / 2, 100, msg, 0xFFFF, 0x0000); + disp_string((TFT_WIDTH - strlen("PRINTER HALTED") * 16) / 2, 140, "PRINTER HALTED", 0xFFFF, 0x0000); + disp_string((TFT_WIDTH - strlen("Please Reset") * 16) / 2, 180, "Please Reset", 0xFFFF, 0x0000); +} + +void lv_clear_error_message() { lv_obj_del(scr); } + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_error_message.h b/Marlin/src/lcd/extui/mks_ui/draw_error_message.h similarity index 89% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_error_message.h rename to Marlin/src/lcd/extui/mks_ui/draw_error_message.h index 8f64d67f93da..6999ecf5e486 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_error_message.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_error_message.h @@ -29,10 +29,9 @@ #define PGM_P const char * #endif -extern void lv_draw_error_message(PGM_P const msg); -extern void lv_clear_error_message(); +void lv_draw_error_message(PGM_P const msg); +void lv_clear_error_message(); -//extern void disp_temp_ready_print(); #ifdef __cplusplus } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_extrusion.cpp b/Marlin/src/lcd/extui/mks_ui/draw_extrusion.cpp new file mode 100644 index 000000000000..2f9009bcdbdd --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_extrusion.cpp @@ -0,0 +1,254 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include + +#include "../../../module/temperature.h" +#include "../../../gcode/queue.h" +#include "../../../inc/MarlinConfig.h" + +static lv_obj_t *scr; +extern lv_group_t *g; +static lv_obj_t *buttonType, *buttonStep, *buttonSpeed; +static lv_obj_t *labelType; +static lv_obj_t *labelStep; +static lv_obj_t *labelSpeed; +static lv_obj_t *tempText; +static lv_obj_t *ExtruText; + +enum { + ID_E_ADD = 1, + ID_E_DEC, + ID_E_TYPE, + ID_E_STEP, + ID_E_SPEED, + ID_E_RETURN +}; + +static int32_t extrudeAmount; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + switch (obj->mks_obj_id) { + case ID_E_ADD: + if (thermalManager.degHotend(uiCfg.extruderIndex) >= EXTRUDE_MINTEMP) { + sprintf_P((char *)public_buf_l, PSTR("G91\nG1 E%d F%d\nG90"), uiCfg.extruStep, 60 * uiCfg.extruSpeed); + queue.inject(public_buf_l); + extrudeAmount += uiCfg.extruStep; + disp_extru_amount(); + } + break; + case ID_E_DEC: + if (thermalManager.degHotend(uiCfg.extruderIndex) >= EXTRUDE_MINTEMP) { + sprintf_P((char *)public_buf_l, PSTR("G91\nG1 E%d F%d\nG90"), 0 - uiCfg.extruStep, 60 * uiCfg.extruSpeed); + queue.enqueue_one_now(public_buf_l); + extrudeAmount -= uiCfg.extruStep; + disp_extru_amount(); + } + break; + case ID_E_TYPE: + if (ENABLED(HAS_MULTI_EXTRUDER)) { + if (uiCfg.extruderIndex == 0) { + uiCfg.extruderIndex = 1; + queue.inject_P(PSTR("T1")); + } + else { + uiCfg.extruderIndex = 0; + queue.inject_P(PSTR("T0")); + } + } + else + uiCfg.extruderIndex = 0; + + extrudeAmount = 0; + disp_hotend_temp(); + disp_ext_type(); + disp_extru_amount(); + break; + case ID_E_STEP: + switch (ABS(uiCfg.extruStep)) { + case 1: uiCfg.extruStep = 5; break; + case 5: uiCfg.extruStep = 10; break; + case 10: uiCfg.extruStep = 1; break; + default: break; + } + disp_ext_step(); + break; + case ID_E_SPEED: + switch (uiCfg.extruSpeed) { + case 1: uiCfg.extruSpeed = 10; break; + case 10: uiCfg.extruSpeed = 20; break; + case 20: uiCfg.extruSpeed = 1; break; + default: break; + } + disp_ext_speed(); + break; + case ID_E_RETURN: + clear_cur_ui(); + draw_return_ui(); + break; + } +} + +void lv_draw_extrusion() { + scr = lv_screen_create(EXTRUSION_UI); + // Create image buttons + lv_obj_t *buttonAdd = lv_big_button_create(scr, "F:/bmp_in.bin", extrude_menu.in, INTERVAL_V, titleHeight, event_handler, ID_E_ADD); + lv_obj_clear_protect(buttonAdd, LV_PROTECT_FOLLOW); + lv_big_button_create(scr, "F:/bmp_out.bin", extrude_menu.out, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight, event_handler, ID_E_DEC); + + buttonType = lv_imgbtn_create(scr, nullptr, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_E_TYPE); + buttonStep = lv_imgbtn_create(scr, nullptr, BTN_X_PIXEL + INTERVAL_V * 2, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_E_STEP); + buttonSpeed = lv_imgbtn_create(scr, nullptr, BTN_X_PIXEL * 2 + INTERVAL_V * 3, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_E_SPEED); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonType); + lv_group_add_obj(g, buttonStep); + lv_group_add_obj(g, buttonSpeed); + } + #endif + + lv_big_button_create(scr, "F:/bmp_return.bin", common_menu.text_back, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_E_RETURN); + + // Create labels on the image buttons + labelType = lv_label_create_empty(buttonType); + labelStep = lv_label_create_empty(buttonStep); + labelSpeed = lv_label_create_empty(buttonSpeed); + + disp_ext_type(); + disp_ext_step(); + disp_ext_speed(); + + tempText = lv_label_create_empty(scr); + lv_obj_set_style(tempText, &tft_style_label_rel); + disp_hotend_temp(); + + ExtruText = lv_label_create_empty(scr); + lv_obj_set_style(ExtruText, &tft_style_label_rel); + disp_extru_amount(); +} + +void disp_ext_type() { + if (uiCfg.extruderIndex == 1) { + lv_imgbtn_set_src_both(buttonType, "F:/bmp_extru2.bin"); + if (gCfgItems.multiple_language) { + lv_label_set_text(labelType, extrude_menu.ext2); + lv_obj_align(labelType, buttonType, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + } + else { + lv_imgbtn_set_src_both(buttonType, "F:/bmp_extru1.bin"); + if (gCfgItems.multiple_language) { + lv_label_set_text(labelType, extrude_menu.ext1); + lv_obj_align(labelType, buttonType, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + } +} + +void disp_ext_speed() { + if (uiCfg.extruSpeed == 20) + lv_imgbtn_set_src_both(buttonSpeed, "F:/bmp_speed_high.bin"); + else if (uiCfg.extruSpeed == 1) + lv_imgbtn_set_src_both(buttonSpeed, "F:/bmp_speed_slow.bin"); + else + lv_imgbtn_set_src_both(buttonSpeed, "F:/bmp_speed_normal.bin"); + + if (gCfgItems.multiple_language) { + if (uiCfg.extruSpeed == 20) { + lv_label_set_text(labelSpeed, extrude_menu.high); + lv_obj_align(labelSpeed, buttonSpeed, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + else if (uiCfg.extruSpeed == 1) { + lv_label_set_text(labelSpeed, extrude_menu.low); + lv_obj_align(labelSpeed, buttonSpeed, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + else { + lv_label_set_text(labelSpeed, extrude_menu.normal); + lv_obj_align(labelSpeed, buttonSpeed, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + } +} + +void disp_hotend_temp() { + char buf[20] = {0}; + sprintf(buf, extrude_menu.temp_value, thermalManager.wholeDegHotend(uiCfg.extruderIndex), thermalManager.degTargetHotend(uiCfg.extruderIndex)); + strcpy(public_buf_l, extrude_menu.temper_text); + strcat(public_buf_l, buf); + lv_label_set_text(tempText, public_buf_l); + lv_obj_align(tempText, nullptr, LV_ALIGN_CENTER, 0, -50); +} + +void disp_extru_amount() { + char buf1[10] = {0}; + + public_buf_l[0] = '\0'; + + if (extrudeAmount < 999 && extrudeAmount > -99) + sprintf(buf1, extrude_menu.count_value_mm, extrudeAmount); + else if (extrudeAmount < 9999 && extrudeAmount > -999) + sprintf(buf1, extrude_menu.count_value_cm, extrudeAmount / 10); + else + sprintf(buf1, extrude_menu.count_value_m, extrudeAmount / 1000); + strcat(public_buf_l, uiCfg.extruderIndex == 0 ? extrude_menu.ext1 : extrude_menu.ext2); + strcat(public_buf_l, buf1); + + lv_label_set_text(ExtruText, public_buf_l); + lv_obj_align(ExtruText, nullptr, LV_ALIGN_CENTER, 0, -75); +} + +void disp_ext_step() { + if (uiCfg.extruStep == 1) + lv_imgbtn_set_src_both(buttonStep, "F:/bmp_step1_mm.bin"); + else if (uiCfg.extruStep == 5) + lv_imgbtn_set_src_both(buttonStep, "F:/bmp_step5_mm.bin"); + else if (uiCfg.extruStep == 10) + lv_imgbtn_set_src_both(buttonStep, "F:/bmp_step10_mm.bin"); + + if (gCfgItems.multiple_language) { + if (uiCfg.extruStep == 1) { + lv_label_set_text(labelStep, extrude_menu.step_1mm); + lv_obj_align(labelStep, buttonStep, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + else if (uiCfg.extruStep == 5) { + lv_label_set_text(labelStep, extrude_menu.step_5mm); + lv_obj_align(labelStep, buttonStep, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + else if (uiCfg.extruStep == 10) { + lv_label_set_text(labelStep, extrude_menu.step_10mm); + lv_obj_align(labelStep, buttonStep, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + } +} + +void lv_clear_extrusion() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_extrusion.h b/Marlin/src/lcd/extui/mks_ui/draw_extrusion.h similarity index 79% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_extrusion.h rename to Marlin/src/lcd/extui/mks_ui/draw_extrusion.h index 576cc6c66c15..025276776784 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_extrusion.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_extrusion.h @@ -25,15 +25,14 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_extrusion(void); -extern void lv_clear_extrusion(); -extern void disp_ext_type(); -extern void disp_ext_step(); -extern void disp_ext_speed(); -extern void disp_hotend_temp(); -extern void disp_extru_amount(); +void lv_draw_extrusion(); +void lv_clear_extrusion(); +void disp_ext_type(); +void disp_ext_step(); +void disp_ext_speed(); +void disp_hotend_temp(); +void disp_extru_amount(); -//extern void disp_temp_ready_print(); #ifdef __cplusplus } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_fan.cpp b/Marlin/src/lcd/extui/mks_ui/draw_fan.cpp new file mode 100644 index 000000000000..ce804e615dd0 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_fan.cpp @@ -0,0 +1,95 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include + +#include "../../../module/temperature.h" +#include "../../../gcode/queue.h" +#include "../../../gcode/gcode.h" +#include "../../../inc/MarlinConfig.h" + +extern lv_group_t *g; +static lv_obj_t *scr, *fanText; + +enum { + ID_F_ADD = 1, + ID_F_DEC, + ID_F_HIGH, + ID_F_MID, + ID_F_OFF, + ID_F_RETURN +}; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + uint8_t fanPercent = map(thermalManager.fan_speed[0], 0, 255, 0, 100); + switch (obj->mks_obj_id) { + case ID_F_ADD: if (fanPercent < 100) fanPercent++; break; + case ID_F_DEC: if (fanPercent != 0) fanPercent--; break; + case ID_F_HIGH: fanPercent = 100; break; + case ID_F_MID: fanPercent = 50; break; + case ID_F_OFF: fanPercent = 0; break; + case ID_F_RETURN: clear_cur_ui(); draw_return_ui(); return; + } + thermalManager.set_fan_speed(0, map(fanPercent, 0, 100, 0, 255)); +} + +void lv_draw_fan() { + lv_obj_t *buttonAdd; + + scr = lv_screen_create(FAN_UI); + // Create an Image button + buttonAdd = lv_big_button_create(scr, "F:/bmp_Add.bin", fan_menu.add, INTERVAL_V, titleHeight, event_handler, ID_F_ADD); + lv_obj_clear_protect(buttonAdd, LV_PROTECT_FOLLOW); + lv_big_button_create(scr, "F:/bmp_Dec.bin", fan_menu.dec, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight, event_handler, ID_F_DEC); + lv_big_button_create(scr, "F:/bmp_speed255.bin", fan_menu.full, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_F_HIGH); + lv_big_button_create(scr, "F:/bmp_speed127.bin", fan_menu.half, BTN_X_PIXEL + INTERVAL_V * 2, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_F_MID); + lv_big_button_create(scr, "F:/bmp_speed0.bin", fan_menu.off, BTN_X_PIXEL * 2 + INTERVAL_V * 3, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_F_OFF); + lv_big_button_create(scr, "F:/bmp_return.bin", common_menu.text_back, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_F_RETURN); + + fanText = lv_label_create_empty(scr); + lv_obj_set_style(fanText, &tft_style_label_rel); + disp_fan_value(); +} + +void disp_fan_value() { + #if HAS_FAN + sprintf_P(public_buf_l, PSTR("%s: %3d%%"), fan_menu.state, (int)map(thermalManager.fan_speed[0], 0, 255, 0, 100)); + #else + sprintf_P(public_buf_l, PSTR("%s: ---"), fan_menu.state); + #endif + lv_label_set_text(fanText, public_buf_l); + lv_obj_align(fanText, nullptr, LV_ALIGN_CENTER, 0, -65); +} + +void lv_clear_fan() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_fan.h b/Marlin/src/lcd/extui/mks_ui/draw_fan.h similarity index 88% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_fan.h rename to Marlin/src/lcd/extui/mks_ui/draw_fan.h index 602d02c6c044..0db87eb4f64e 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_fan.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_fan.h @@ -25,11 +25,10 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_fan(void); -extern void lv_clear_fan(); -extern void disp_fan_value(); +void lv_draw_fan(); +void lv_clear_fan(); +void disp_fan_value(); -//extern void disp_temp_ready_print(); #ifdef __cplusplus } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_filament_change.cpp b/Marlin/src/lcd/extui/mks_ui/draw_filament_change.cpp new file mode 100644 index 000000000000..311894825daa --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_filament_change.cpp @@ -0,0 +1,172 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include + +#include "../../../module/temperature.h" +#include "../../../gcode/gcode.h" +#include "../../../module/motion.h" +#include "../../../module/planner.h" +#include "../../../inc/MarlinConfig.h" + +extern lv_group_t *g; +static lv_obj_t *scr; +static lv_obj_t *buttonType; +static lv_obj_t *labelType; +static lv_obj_t *tempText1; + +enum { + ID_FILAMNT_IN = 1, + ID_FILAMNT_OUT, + ID_FILAMNT_TYPE, + ID_FILAMNT_RETURN +}; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + switch (obj->mks_obj_id) { + case ID_FILAMNT_IN: + uiCfg.filament_load_heat_flg = true; + if (ABS(thermalManager.degTargetHotend(uiCfg.extruderIndex) - thermalManager.wholeDegHotend(uiCfg.extruderIndex)) <= 1 + || gCfgItems.filament_limit_temp <= thermalManager.wholeDegHotend(uiCfg.extruderIndex)) { + lv_clear_filament_change(); + lv_draw_dialog(DIALOG_TYPE_FILAMENT_HEAT_LOAD_COMPLETED); + } + else { + lv_clear_filament_change(); + lv_draw_dialog(DIALOG_TYPE_FILAMENT_LOAD_HEAT); + if (thermalManager.degTargetHotend(uiCfg.extruderIndex) < gCfgItems.filament_limit_temp) { + thermalManager.setTargetHotend(gCfgItems.filament_limit_temp, uiCfg.extruderIndex); + thermalManager.start_watching_hotend(uiCfg.extruderIndex); + } + } + break; + case ID_FILAMNT_OUT: + uiCfg.filament_unload_heat_flg = true; + if (thermalManager.degTargetHotend(uiCfg.extruderIndex) + && (ABS(thermalManager.degTargetHotend(uiCfg.extruderIndex) - thermalManager.wholeDegHotend(uiCfg.extruderIndex)) <= 1 + || thermalManager.wholeDegHotend(uiCfg.extruderIndex) >= gCfgItems.filament_limit_temp) + ) { + lv_clear_filament_change(); + lv_draw_dialog(DIALOG_TYPE_FILAMENT_HEAT_UNLOAD_COMPLETED); + } + else { + lv_clear_filament_change(); + lv_draw_dialog(DIALOG_TYPE_FILAMENT_UNLOAD_HEAT); + if (thermalManager.degTargetHotend(uiCfg.extruderIndex) < gCfgItems.filament_limit_temp) { + thermalManager.setTargetHotend(gCfgItems.filament_limit_temp, uiCfg.extruderIndex); + thermalManager.start_watching_hotend(uiCfg.extruderIndex); + } + filament_sprayer_temp(); + } + break; + case ID_FILAMNT_TYPE: + #if HAS_MULTI_EXTRUDER + uiCfg.extruderIndex = !uiCfg.extruderIndex; + #endif + disp_filament_type(); + break; + case ID_FILAMNT_RETURN: + #if HAS_MULTI_EXTRUDER + if (uiCfg.print_state != IDLE && uiCfg.print_state != REPRINTED) + gcode.process_subcommands_now_P(uiCfg.extruderIndexBak == 1 ? PSTR("T1") : PSTR("T0")); + #endif + feedrate_mm_s = (float)uiCfg.moveSpeed_bak; + if (uiCfg.print_state == PAUSED) + planner.set_e_position_mm((destination.e = current_position.e = uiCfg.current_e_position_bak)); + thermalManager.setTargetHotend(uiCfg.hotendTargetTempBak, uiCfg.extruderIndex); + + clear_cur_ui(); + draw_return_ui(); + break; + } +} + +void lv_draw_filament_change() { + scr = lv_screen_create(FILAMENTCHANGE_UI); + // Create an Image button + lv_obj_t *buttonIn = lv_big_button_create(scr, "F:/bmp_in.bin", filament_menu.in, INTERVAL_V, titleHeight, event_handler, ID_FILAMNT_IN); + lv_obj_clear_protect(buttonIn, LV_PROTECT_FOLLOW); + lv_big_button_create(scr, "F:/bmp_out.bin", filament_menu.out, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight, event_handler, ID_FILAMNT_OUT); + + buttonType = lv_imgbtn_create(scr, nullptr, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_FILAMNT_TYPE); + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonType); + } + #endif + + lv_big_button_create(scr, "F:/bmp_return.bin", common_menu.text_back, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_FILAMNT_RETURN); + + // Create labels on the image buttons + labelType = lv_label_create_empty(buttonType); + + disp_filament_type(); + + tempText1 = lv_label_create_empty(scr); + lv_obj_set_style(tempText1, &tft_style_label_rel); + disp_filament_temp(); +} + +void disp_filament_type() { + if (uiCfg.extruderIndex == 1) { + lv_imgbtn_set_src_both(buttonType, "F:/bmp_extru2.bin"); + if (gCfgItems.multiple_language) { + lv_label_set_text(labelType, preheat_menu.ext2); + lv_obj_align(labelType, buttonType, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + } + else { + lv_imgbtn_set_src_both(buttonType, "F:/bmp_extru1.bin"); + if (gCfgItems.multiple_language) { + lv_label_set_text(labelType, preheat_menu.ext1); + lv_obj_align(labelType, buttonType, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + } +} + +void disp_filament_temp() { + char buf[20] = {0}; + + public_buf_l[0] = '\0'; + + strcat(public_buf_l, uiCfg.extruderIndex < 1 ? preheat_menu.ext1 : preheat_menu.ext2); + sprintf(buf, preheat_menu.value_state, thermalManager.wholeDegHotend(uiCfg.extruderIndex), thermalManager.degTargetHotend(uiCfg.extruderIndex)); + + strcat_P(public_buf_l, PSTR(": ")); + strcat(public_buf_l, buf); + lv_label_set_text(tempText1, public_buf_l); + lv_obj_align(tempText1, nullptr, LV_ALIGN_CENTER, 0, -50); +} + +void lv_clear_filament_change() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_filament_change.h b/Marlin/src/lcd/extui/mks_ui/draw_filament_change.h similarity index 84% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_filament_change.h rename to Marlin/src/lcd/extui/mks_ui/draw_filament_change.h index b0068f7f0f32..d3536a380ad1 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_filament_change.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_filament_change.h @@ -25,12 +25,11 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_filament_change(void); -extern void lv_clear_filament_change(); -extern void disp_filament_type(); -extern void disp_filament_temp(); +void lv_draw_filament_change(); +void lv_clear_filament_change(); +void disp_filament_type(); +void disp_filament_temp(); -//extern void disp_temp_ready_print(); #ifdef __cplusplus } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_filament_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_filament_settings.cpp new file mode 100644 index 000000000000..97680f3a0cb3 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_filament_settings.cpp @@ -0,0 +1,126 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include + +#include "../../../inc/MarlinConfig.h" + +extern lv_group_t *g; +static lv_obj_t *scr; + +enum { + ID_FILAMENT_SET_RETURN = 1, + ID_FILAMENT_SET_IN_LENGTH, + ID_FILAMENT_SET_IN_SPEED, + ID_FILAMENT_SET_OUT_LENGTH, + ID_FILAMENT_SET_OUT_SPEED, + ID_FILAMENT_SET_TEMP, + ID_FILAMENT_SET_DOWN, + ID_FILAMENT_SET_UP +}; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + switch (obj->mks_obj_id) { + case ID_FILAMENT_SET_RETURN: + uiCfg.para_ui_page = false; + lv_clear_filament_settings(); + draw_return_ui(); + break; + case ID_FILAMENT_SET_IN_LENGTH: + value = load_length; + lv_clear_filament_settings(); + lv_draw_number_key(); + break; + case ID_FILAMENT_SET_IN_SPEED: + value = load_speed; + lv_clear_filament_settings(); + lv_draw_number_key(); + break; + case ID_FILAMENT_SET_OUT_LENGTH: + value = unload_length; + lv_clear_filament_settings(); + lv_draw_number_key(); + break; + case ID_FILAMENT_SET_OUT_SPEED: + value = unload_speed; + lv_clear_filament_settings(); + lv_draw_number_key(); + break; + case ID_FILAMENT_SET_TEMP: + value = filament_temp; + lv_clear_filament_settings(); + lv_draw_number_key(); + break; + case ID_FILAMENT_SET_UP: + uiCfg.para_ui_page = false; + lv_clear_filament_settings(); + lv_draw_filament_settings(); + break; + case ID_FILAMENT_SET_DOWN: + uiCfg.para_ui_page = true; + lv_clear_filament_settings(); + lv_draw_filament_settings(); + break; + } +} + +void lv_draw_filament_settings() { + scr = lv_screen_create(FILAMENT_SETTINGS_UI, machine_menu.FilamentConfTitle); + + if (!uiCfg.para_ui_page) { + itoa(gCfgItems.filamentchange_load_length, public_buf_l, 10); + lv_screen_menu_item_1_edit(scr, machine_menu.InLength, PARA_UI_POS_X, PARA_UI_POS_Y, event_handler, ID_FILAMENT_SET_IN_LENGTH, 0, public_buf_l); + + itoa(gCfgItems.filamentchange_load_speed, public_buf_l, 10); + lv_screen_menu_item_1_edit(scr, machine_menu.InSpeed, PARA_UI_POS_X, PARA_UI_POS_Y * 2, event_handler, ID_FILAMENT_SET_IN_SPEED, 1, public_buf_l); + + itoa(gCfgItems.filamentchange_unload_length, public_buf_l, 10); + lv_screen_menu_item_1_edit(scr, machine_menu.OutLength, PARA_UI_POS_X, PARA_UI_POS_Y * 3, event_handler, ID_FILAMENT_SET_OUT_LENGTH, 2, public_buf_l); + + itoa(gCfgItems.filamentchange_unload_speed, public_buf_l, 10); + lv_screen_menu_item_1_edit(scr, machine_menu.OutSpeed, PARA_UI_POS_X, PARA_UI_POS_Y * 4, event_handler, ID_FILAMENT_SET_OUT_SPEED, 3, public_buf_l); + + 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_FILAMENT_SET_DOWN, true); + } + else { + itoa(gCfgItems.filament_limit_temp, public_buf_l, 10); + lv_screen_menu_item_1_edit(scr, machine_menu.FilamentTemperature, PARA_UI_POS_X, PARA_UI_POS_Y, event_handler, ID_FILAMENT_SET_TEMP, 0, public_buf_l); + + lv_big_button_create(scr, "F:/bmp_back70x40.bin", machine_menu.previous, PARA_UI_TURN_PAGE_POS_X, PARA_UI_TURN_PAGE_POS_Y, event_handler, ID_FILAMENT_SET_UP, true); + } + + lv_big_button_create(scr, "F:/bmp_back70x40.bin", common_menu.text_back, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y, event_handler, ID_FILAMENT_SET_RETURN, true); +} + +void lv_clear_filament_settings() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_filament_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_filament_settings.h similarity index 92% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_filament_settings.h rename to Marlin/src/lcd/extui/mks_ui/draw_filament_settings.h index a5ae54289534..3d190e99c731 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_filament_settings.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_filament_settings.h @@ -25,8 +25,8 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_filament_settings(void); -extern void lv_clear_filament_settings(); +void lv_draw_filament_settings(); +void lv_clear_filament_settings(); #ifdef __cplusplus } /* C-declarations for C++ */ diff --git a/Marlin/src/lcd/extui/mks_ui/draw_gcode.cpp b/Marlin/src/lcd/extui/mks_ui/draw_gcode.cpp new file mode 100644 index 000000000000..bded5df7e7f5 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_gcode.cpp @@ -0,0 +1,109 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include + +#include "../../../inc/MarlinConfig.h" + +extern lv_group_t *g; +static lv_obj_t *scr,*outL,*outV = 0; +static int currentWritePos = 0; +extern uint8_t public_buf[513]; +extern "C" { extern char public_buf_m[100]; } + +enum { + ID_GCODE_RETURN = 1, + ID_GCODE_COMMAND, +}; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + lv_clear_gcode(); + switch (obj->mks_obj_id) { + case ID_GCODE_RETURN: + lv_draw_more(); + return; + case ID_GCODE_COMMAND: + keyboard_value = GCodeCommand; + lv_draw_keyboard(); + break; + } +} + +void lv_show_gcode_output(void * that, const char * txt) { + // Ignore echo of command + if (!memcmp(txt, "echo:", 5)) { + public_buf[0] = 0; // Clear output buffer + return; + } + + // Avoid overflow if the answer is too large + size_t len = strlen((const char*)public_buf), tlen = strlen(txt); + if (len + tlen + 1 < sizeof(public_buf)) { + memcpy(public_buf + len, txt, tlen); + public_buf[len + tlen] = '\n'; + } +} + +void lv_serial_capt_hook(void * userPointer, uint8_t c) +{ + if (c == '\n' || currentWritePos == sizeof(public_buf_m) - 1) { // End of line, probably end of command anyway + public_buf_m[currentWritePos] = 0; + lv_show_gcode_output(userPointer, public_buf_m); + currentWritePos = 0; + } + else public_buf_m[currentWritePos++] = c; +} +void lv_eom_hook(void *) +{ + // Message is done, let's remove the hook now + MYSERIAL1.setHook(); + // We are back from the keyboard, so let's redraw ourselves + draw_return_ui(); +} + +void lv_draw_gcode(bool clear) { + if (clear) { + currentWritePos = 0; + public_buf[0] = 0; + } + scr = lv_screen_create(GCODE_UI, more_menu.gcode); + lv_screen_menu_item(scr, more_menu.entergcode, PARA_UI_POS_X, PARA_UI_POS_Y, event_handler, ID_GCODE_COMMAND, 1); + outL = lv_label_create(scr, PARA_UI_POS_X, PARA_UI_POS_Y * 2, "Result:"); + outV = lv_label_create(scr, PARA_UI_POS_X, PARA_UI_POS_Y * 3, (const char*)public_buf); + + lv_big_button_create(scr, "F:/bmp_back70x40.bin", common_menu.text_back, PARA_UI_BACL_POS_X + 10, PARA_UI_BACL_POS_Y, event_handler, ID_GCODE_RETURN, true); +} + +void lv_clear_gcode() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); + outV = 0; +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_gcode.h b/Marlin/src/lcd/extui/mks_ui/draw_gcode.h new file mode 100644 index 000000000000..4e1610431ef9 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_gcode.h @@ -0,0 +1,33 @@ +/** + * 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 + +#ifdef __cplusplus + extern "C" { /* C-declarations for C++ */ +#endif + +void lv_draw_gcode(bool clear = false); +void lv_clear_gcode(); + +#ifdef __cplusplus + } /* C-declarations for C++ */ +#endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_home.cpp b/Marlin/src/lcd/extui/mks_ui/draw_home.cpp new file mode 100644 index 000000000000..447fadd55dcf --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_home.cpp @@ -0,0 +1,93 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ready_print.h" +#include "draw_set.h" +#include "draw_ui.h" +#include + +#include "../../../gcode/queue.h" +#include "../../../inc/MarlinConfig.h" + +extern lv_group_t *g; +static lv_obj_t *scr; + +enum { + ID_H_ALL = 1, + ID_H_X, + ID_H_Y, + ID_H_Z, + ID_H_RETURN, + ID_H_OFF_ALL, + ID_H_OFF_XY +}; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + switch (obj->mks_obj_id) { + case ID_H_ALL: + queue.inject_P(G28_STR); + break; + case ID_H_X: + queue.inject_P(PSTR("G28X")); + break; + case ID_H_Y: + queue.inject_P(PSTR("G28Y")); + break; + case ID_H_Z: + queue.inject_P(PSTR("G28Z")); + break; + case ID_H_OFF_ALL: + queue.inject_P(PSTR("M84")); + break; + case ID_H_OFF_XY: + queue.inject_P(PSTR("M84XY")); + break; + case ID_H_RETURN: + clear_cur_ui(); + draw_return_ui(); + break; + } +} + +void lv_draw_home() { + scr = lv_screen_create(ZERO_UI); + lv_big_button_create(scr, "F:/bmp_zeroAll.bin", home_menu.home_all, INTERVAL_V, titleHeight, event_handler, ID_H_ALL); + lv_big_button_create(scr, "F:/bmp_zeroX.bin", home_menu.home_x, BTN_X_PIXEL + INTERVAL_V * 2, titleHeight, event_handler, ID_H_X); + lv_big_button_create(scr, "F:/bmp_zeroY.bin", home_menu.home_y, BTN_X_PIXEL * 2 + INTERVAL_V * 3, titleHeight, event_handler, ID_H_Y); + lv_big_button_create(scr, "F:/bmp_zeroZ.bin", home_menu.home_z, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight, event_handler, ID_H_Z); + lv_big_button_create(scr, "F:/bmp_function1.bin", set_menu.motoroff, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_H_OFF_ALL); + lv_big_button_create(scr, "F:/bmp_function1.bin", set_menu.motoroffXY, BTN_X_PIXEL + INTERVAL_V * 2, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_H_OFF_XY); + lv_big_button_create(scr, "F:/bmp_return.bin", common_menu.text_back, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_H_RETURN); +} + +void lv_clear_home() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_home.h b/Marlin/src/lcd/extui/mks_ui/draw_home.h similarity index 90% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_home.h rename to Marlin/src/lcd/extui/mks_ui/draw_home.h index c5060127a876..7375dc7aa8cb 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_home.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_home.h @@ -25,10 +25,9 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_home(void); -extern void lv_clear_home(); +void lv_draw_home(); +void lv_clear_home(); -//extern void disp_temp_ready_print(); #ifdef __cplusplus } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_homing_sensitivity_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_homing_sensitivity_settings.cpp new file mode 100644 index 000000000000..e1ab58ee7bc4 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_homing_sensitivity_settings.cpp @@ -0,0 +1,104 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfig.h" + +#if HAS_TFT_LVGL_UI && USE_SENSORLESS + +#include "draw_ui.h" +#include + +#include "../../../module/planner.h" +#include "../../../module/probe.h" +#include "../../../module/stepper/indirection.h" +#include "../../../feature/tmc_util.h" + +extern lv_group_t *g; +static lv_obj_t *scr; + +enum { + ID_SENSITIVITY_RETURN = 1, + ID_SENSITIVITY_X, + ID_SENSITIVITY_Y, + ID_SENSITIVITY_Z, + ID_SENSITIVITY_Z2 +}; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + switch (obj->mks_obj_id) { + case ID_SENSITIVITY_RETURN: + lv_clear_homing_sensitivity_settings(); + draw_return_ui(); + break; + case ID_SENSITIVITY_X: + value = x_sensitivity; + lv_clear_homing_sensitivity_settings(); + lv_draw_number_key(); + break; + case ID_SENSITIVITY_Y: + value = y_sensitivity; + lv_clear_homing_sensitivity_settings(); + lv_draw_number_key(); + break; + case ID_SENSITIVITY_Z: + value = z_sensitivity; + lv_clear_homing_sensitivity_settings(); + lv_draw_number_key(); + break; + #if Z2_SENSORLESS + case ID_SENSITIVITY_Z2: + value = z2_sensitivity; + lv_clear_homing_sensitivity_settings(); + lv_draw_number_key(); + break; + #endif + } +} + +void lv_draw_homing_sensitivity_settings() { + scr = lv_screen_create(HOMING_SENSITIVITY_UI, machine_menu.HomingSensitivityConfTitle); + + itoa(TERN(X_SENSORLESS, stepperX.homing_threshold(), 0), public_buf_l, 10); + lv_screen_menu_item_1_edit(scr, machine_menu.X_Sensitivity, PARA_UI_POS_X, PARA_UI_POS_Y, event_handler, ID_SENSITIVITY_X, 0, public_buf_l); + + itoa(TERN(Y_SENSORLESS, stepperY.homing_threshold(), 0), public_buf_l, 10); + lv_screen_menu_item_1_edit(scr, machine_menu.Y_Sensitivity, PARA_UI_POS_X, PARA_UI_POS_Y * 2, event_handler, ID_SENSITIVITY_Y, 1, public_buf_l); + + itoa(TERN(Z_SENSORLESS, stepperZ.homing_threshold(), 0), public_buf_l, 10); + lv_screen_menu_item_1_edit(scr, machine_menu.Z_Sensitivity, PARA_UI_POS_X, PARA_UI_POS_Y * 3, event_handler, ID_SENSITIVITY_Z, 2, public_buf_l); + + #if Z2_SENSORLESS + itoa(TERN(Z2_SENSORLESS, stepperZ2.homing_threshold(), 0), public_buf_l, 10); + lv_screen_menu_item_1_edit(scr, machine_menu.Z2_Sensitivity, PARA_UI_POS_X, PARA_UI_POS_Y * 4, event_handler, ID_SENSITIVITY_Z2, 3, public_buf_l); + #endif + + lv_big_button_create(scr, "F:/bmp_back70x40.bin", common_menu.text_back, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y, event_handler, ID_SENSITIVITY_RETURN, true); +} + +void lv_clear_homing_sensitivity_settings() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI && USE_SENSORLESS diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_homing_sensitivity_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_homing_sensitivity_settings.h similarity index 90% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_homing_sensitivity_settings.h rename to Marlin/src/lcd/extui/mks_ui/draw_homing_sensitivity_settings.h index 0c554702b1c6..e08639137341 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_homing_sensitivity_settings.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_homing_sensitivity_settings.h @@ -25,8 +25,8 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_homing_sensitivity_settings(void); -extern void lv_clear_homing_sensitivity_settings(); +void lv_draw_homing_sensitivity_settings(); +void lv_clear_homing_sensitivity_settings(); #ifdef __cplusplus } /* C-declarations for C++ */ diff --git a/Marlin/src/lcd/extui/mks_ui/draw_jerk_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_jerk_settings.cpp new file mode 100644 index 000000000000..8a97e304674e --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_jerk_settings.cpp @@ -0,0 +1,98 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if BOTH(HAS_TFT_LVGL_UI, HAS_CLASSIC_JERK) + +#include "draw_ui.h" +#include + +#include "../../../module/planner.h" +#include "../../../inc/MarlinConfig.h" + +extern lv_group_t *g; +static lv_obj_t *scr; + +enum { + ID_JERK_RETURN = 1, + ID_JERK_X, + ID_JERK_Y, + ID_JERK_Z, + ID_JERK_E +}; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + switch (obj->mks_obj_id) { + case ID_JERK_RETURN: + lv_clear_jerk_settings(); + draw_return_ui(); + break; + case ID_JERK_X: + value = XJerk; + lv_clear_jerk_settings(); + lv_draw_number_key(); + break; + case ID_JERK_Y: + value = YJerk; + lv_clear_jerk_settings(); + lv_draw_number_key(); + break; + case ID_JERK_Z: + value = ZJerk; + lv_clear_jerk_settings(); + lv_draw_number_key(); + break; + case ID_JERK_E: + value = EJerk; + lv_clear_jerk_settings(); + lv_draw_number_key(); + break; + } +} + +void lv_draw_jerk_settings() { + scr = lv_screen_create(JERK_UI, machine_menu.JerkConfTitle); + + dtostrf(planner.max_jerk[X_AXIS], 1, 1, public_buf_l); + lv_screen_menu_item_1_edit(scr, machine_menu.X_Jerk, PARA_UI_POS_X, PARA_UI_POS_Y, event_handler, ID_JERK_X, 0, public_buf_l); + + dtostrf(planner.max_jerk[Y_AXIS], 1, 1, public_buf_l); + lv_screen_menu_item_1_edit(scr, machine_menu.Y_Jerk, PARA_UI_POS_X, PARA_UI_POS_Y * 2, event_handler, ID_JERK_Y, 1, public_buf_l); + + dtostrf(planner.max_jerk[Z_AXIS], 1, 1, public_buf_l); + lv_screen_menu_item_1_edit(scr, machine_menu.Z_Jerk, PARA_UI_POS_X, PARA_UI_POS_Y * 3, event_handler, ID_JERK_Z, 2, public_buf_l); + + dtostrf(planner.max_jerk[E_AXIS], 1, 1, public_buf_l); + lv_screen_menu_item_1_edit(scr, machine_menu.E_Jerk, PARA_UI_POS_X, PARA_UI_POS_Y * 4, event_handler, ID_JERK_E, 3, public_buf_l); + + lv_big_button_create(scr, "F:/bmp_back70x40.bin", common_menu.text_back, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y, event_handler, ID_JERK_RETURN, true); +} + +void lv_clear_jerk_settings() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI && HAS_CLASSIC_JERK diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_jerk_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_jerk_settings.h similarity index 92% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_jerk_settings.h rename to Marlin/src/lcd/extui/mks_ui/draw_jerk_settings.h index 0531dae9da96..7f5ffc3ac50d 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_jerk_settings.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_jerk_settings.h @@ -25,8 +25,8 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_jerk_settings(void); -extern void lv_clear_jerk_settings(); +void lv_draw_jerk_settings(); +void lv_clear_jerk_settings(); #ifdef __cplusplus } /* C-declarations for C++ */ diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_keyboard.cpp b/Marlin/src/lcd/extui/mks_ui/draw_keyboard.cpp similarity index 77% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_keyboard.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_keyboard.cpp index 902472b8842a..671939cbff9e 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_keyboard.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_keyboard.cpp @@ -19,18 +19,18 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI -#include "lv_conf.h" #include "draw_ui.h" +#include -#include "../../../../../Configuration.h" -#include "../../../../MarlinCore.h" +#include "../../../inc/MarlinConfig.h" +#include "../../../gcode/queue.h" -extern lv_group_t * g; -static lv_obj_t * scr; +extern lv_group_t *g; +static lv_obj_t *scr; #define LV_KB_CTRL_BTN_FLAGS (LV_BTNM_CTRL_NO_REPEAT | LV_BTNM_CTRL_CLICK_TRIG) @@ -56,13 +56,13 @@ static const lv_btnm_ctrl_t kb_ctrl_uc_map[] = { 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, LV_KB_CTRL_BTN_FLAGS | 2, 2, 6, 2, LV_KB_CTRL_BTN_FLAGS | 2}; -static const char * kb_map_spec[] = {"0", "1", "2", "3", "4" ,"5", "6", "7", "8", "9", LV_SYMBOL_BACKSPACE, "\n", +static const char * kb_map_spec[] = {"0", "1", "2", "3", "4" ,"5", "6", "7", "8", "9", ".", LV_SYMBOL_BACKSPACE, "\n", "abc", "+", "-", "/", "*", "=", "%", "!", "?", "#", "<", ">", "\n", "\\", "@", "$", "(", ")", "{", "}", "[", "]", ";", "\"", "'", "\n", LV_SYMBOL_CLOSE, LV_SYMBOL_LEFT, " ", LV_SYMBOL_RIGHT, LV_SYMBOL_OK, ""}; static const lv_btnm_ctrl_t kb_ctrl_spec_map[] = { - 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, LV_KB_CTRL_BTN_FLAGS | 2, + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, LV_KB_CTRL_BTN_FLAGS | 2, LV_KB_CTRL_BTN_FLAGS | 2, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, LV_KB_CTRL_BTN_FLAGS | 2, 2, 6, 2, LV_KB_CTRL_BTN_FLAGS | 2}; @@ -73,9 +73,7 @@ static const lv_btnm_ctrl_t kb_ctrl_num_map[] = { 1, 1, 1, 2, 1, 1, 1, 1, 1}; -static void lv_kb_event_cb(lv_obj_t * kb, lv_event_t event) { - //LV_ASSERT_OBJ(kb, LV_OBJX_NAME); - +static void lv_kb_event_cb(lv_obj_t *kb, lv_event_t event) { if (event != LV_EVENT_VALUE_CHANGED) return; lv_kb_ext_t * ext = (lv_kb_ext_t * )lv_obj_get_ext_attr(kb); @@ -85,7 +83,7 @@ static void lv_kb_event_cb(lv_obj_t * kb, lv_event_t event) { if (lv_btnm_get_btn_ctrl(kb, btn_id, LV_BTNM_CTRL_NO_REPEAT) && event == LV_EVENT_LONG_PRESSED_REPEAT) return; const char * txt = lv_btnm_get_active_btn_text(kb); - if (txt == NULL) return; + if (!txt) return; // Do the corresponding action according to the text of the button if (strcmp(txt, "abc") == 0) { @@ -105,25 +103,21 @@ static void lv_kb_event_cb(lv_obj_t * kb, lv_event_t event) { } else if (strcmp(txt, LV_SYMBOL_CLOSE) == 0) { if (kb->event_cb != lv_kb_def_event_cb) { - //lv_res_t res = lv_event_send(kb, LV_EVENT_CANCEL, NULL); - //if (res != LV_RES_OK) return; lv_clear_keyboard(); draw_return_ui(); } else { - lv_kb_set_ta(kb, NULL); /*De-assign the text area to hide it cursor if needed*/ + lv_kb_set_ta(kb, nullptr); // De-assign the text area to hide its cursor if needed lv_obj_del(kb); return; } - return; + return; } else if (strcmp(txt, LV_SYMBOL_OK) == 0) { if (kb->event_cb != lv_kb_def_event_cb) { - //lv_res_t res = lv_event_send(kb, LV_EVENT_APPLY, NULL); - //if (res != LV_RES_OK) return; const char * ret_ta_txt = lv_ta_get_text(ext->ta); switch (keyboard_value) { - #if ENABLED(USE_WIFI_FUNCTION) + #if ENABLED(MKS_WIFI_MODULE) case wifiName: memcpy(uiCfg.wifi_name,ret_ta_txt,sizeof(uiCfg.wifi_name)); lv_clear_keyboard(); @@ -135,17 +129,15 @@ static void lv_kb_event_cb(lv_obj_t * kb, lv_event_t event) { draw_return_ui(); break; case wifiConfig: - memset((void *)uiCfg.wifi_name, 0, sizeof(uiCfg.wifi_name)); + ZERO(uiCfg.wifi_name); memcpy((void *)uiCfg.wifi_name, wifi_list.wifiName[wifi_list.nameIndex], 32); - memset((void *)uiCfg.wifi_key, 0, sizeof(uiCfg.wifi_key)); + ZERO(uiCfg.wifi_key); memcpy((void *)uiCfg.wifi_key, ret_ta_txt, sizeof(uiCfg.wifi_key)); gCfgItems.wifi_mode_sel = STA_MODEL; - package_to_wifi(WIFI_PARA_SET, (char *)0, 0); - - memset(public_buf_l,0,sizeof(public_buf_l)); + package_to_wifi(WIFI_PARA_SET, nullptr, 0); public_buf_l[0] = 0xA5; public_buf_l[1] = 0x09; @@ -154,32 +146,40 @@ static void lv_kb_event_cb(lv_obj_t * kb, lv_event_t event) { public_buf_l[4] = 0x01; public_buf_l[5] = 0xFC; public_buf_l[6] = 0x00; - raw_send_to_wifi(public_buf_l, 6); + raw_send_to_wifi((uint8_t*)public_buf_l, 6); - last_disp_state = KEY_BOARD_UI; + last_disp_state = KEYBOARD_UI; lv_clear_keyboard(); wifi_tips_type = TIPS_TYPE_JOINING; lv_draw_wifi_tips(); break; - #endif // USE_WIFI_FUNCTION - case gcodeCommand: + #endif // MKS_WIFI_MODULE + case autoLevelGcodeCommand: uint8_t buf[100]; strncpy((char *)buf,ret_ta_txt,sizeof(buf)); update_gcode_command(AUTO_LEVELING_COMMAND_ADDR,buf); lv_clear_keyboard(); draw_return_ui(); break; + case GCodeCommand: + if (!queue.ring_buffer.full(3)) { + // Hook anything that goes to the serial port + MYSERIAL1.setHook(lv_serial_capt_hook, lv_eom_hook, 0); + queue.enqueue_one_now(ret_ta_txt); + } + lv_clear_keyboard(); + // draw_return_ui is called in the end of message hook + break; default: break; } } - else { - lv_kb_set_ta(kb, NULL); /*De-assign the text area to hide it cursor if needed*/ - } + else + lv_kb_set_ta(kb, nullptr); // De-assign the text area to hide it cursor if needed return; } - /*Add the characters to the text area if set*/ - if (ext->ta == NULL) return; + // Add the characters to the text area if set + if (!ext->ta) return; if (strcmp(txt, "Enter") == 0 || strcmp(txt, LV_SYMBOL_NEW_LINE) == 0) lv_ta_add_char(ext->ta, '\n'); @@ -216,21 +216,9 @@ static void lv_kb_event_cb(lv_obj_t * kb, lv_event_t event) { } void lv_draw_keyboard() { - if (disp_state_stack._disp_state[disp_state_stack._disp_index] != KEY_BOARD_UI) { - disp_state_stack._disp_index++; - disp_state_stack._disp_state[disp_state_stack._disp_index] = KEY_BOARD_UI; - } - disp_state = KEY_BOARD_UI; - - scr = lv_obj_create(NULL, NULL); - - lv_obj_set_style(scr, &tft_style_scr); - lv_scr_load(scr); - lv_obj_clean(scr); - - lv_refr_now(lv_refr_get_disp_refreshing()); + scr = lv_screen_create(KEYBOARD_UI, ""); - /*Create styles for the keyboard*/ + // Create styles for the keyboard static lv_style_t rel_style, pr_style; lv_style_copy(&rel_style, &lv_style_btn_rel); @@ -245,8 +233,8 @@ void lv_draw_keyboard() { pr_style.body.main_color = lv_color_make(0x72, 0x42, 0x15); pr_style.body.grad_color = lv_color_make(0x6A, 0x3A, 0x0C); - /*Create a keyboard and apply the styles*/ - lv_obj_t *kb = lv_kb_create(scr, NULL); + // Create a keyboard and apply the styles + lv_obj_t *kb = lv_kb_create(scr, nullptr); lv_obj_set_event_cb(kb, lv_kb_event_cb); lv_kb_set_cursor_manage(kb, true); lv_kb_set_style(kb, LV_KB_STYLE_BG, &lv_style_transp_tight); @@ -254,31 +242,32 @@ void lv_draw_keyboard() { lv_kb_set_style(kb, LV_KB_STYLE_BTN_PR, &pr_style); #if HAS_ROTARY_ENCODER if (gCfgItems.encoder_enable) { - //lv_group_add_obj(g, kb); - //lv_group_set_editing(g, true); } #endif - /*Create a text area. The keyboard will write here*/ - lv_obj_t *ta = lv_ta_create(scr, NULL); - lv_obj_align(ta, NULL, LV_ALIGN_IN_TOP_MID, 0, 10); - if (keyboard_value == gcodeCommand) { + // Create a text area. The keyboard will write here + lv_obj_t *ta = lv_ta_create(scr, nullptr); + lv_obj_align(ta, nullptr, LV_ALIGN_IN_TOP_MID, 0, 10); + switch (keyboard_value) { + case autoLevelGcodeCommand: get_gcode_command(AUTO_LEVELING_COMMAND_ADDR,(uint8_t *)public_buf_m); public_buf_m[sizeof(public_buf_m)-1] = 0; lv_ta_set_text(ta, public_buf_m); - } - else { + break; + case GCodeCommand: + // Start with uppercase by default + lv_btnm_set_map(kb, kb_map_uc); + lv_btnm_set_ctrl_map(kb, kb_ctrl_uc_map); + // Fallthrough + default: lv_ta_set_text(ta, ""); } - /*Assign the text area to the keyboard*/ + // Assign the text area to the keyboard lv_kb_set_ta(kb, ta); } void lv_clear_keyboard() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { /* lv_group_remove_all_objs(g); */ } - #endif lv_obj_del(scr); } diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_keyboard.h b/Marlin/src/lcd/extui/mks_ui/draw_keyboard.h similarity index 93% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_keyboard.h rename to Marlin/src/lcd/extui/mks_ui/draw_keyboard.h index 0013dc4030ea..d89806c272d4 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_keyboard.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_keyboard.h @@ -25,8 +25,8 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_keyboard(); -extern void lv_clear_keyboard(); +void lv_draw_keyboard(); +void lv_clear_keyboard(); #ifdef __cplusplus } /* C-declarations for C++ */ diff --git a/Marlin/src/lcd/extui/mks_ui/draw_language.cpp b/Marlin/src/lcd/extui/mks_ui/draw_language.cpp new file mode 100644 index 000000000000..3db22583aae8 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_language.cpp @@ -0,0 +1,208 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include + +#include "../../../inc/MarlinConfig.h" +#include + +enum { + ID_CN = 1, + ID_T_CN, + ID_EN, + ID_RU, + ID_ES, + ID_FR, + ID_IT, + ID_L_RETURN +}; + +#define SELECTED 1 +#define UNSELECTED 0 + +static void disp_language(uint8_t language, uint8_t state); + +extern lv_group_t *g; +static lv_obj_t *scr; +static lv_obj_t *buttonCN, *buttonT_CN, *buttonEN, *buttonRU; +static lv_obj_t *buttonES, *buttonFR, *buttonIT; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + switch (obj->mks_obj_id) { + case ID_CN: + disp_language(gCfgItems.language, UNSELECTED); + lv_imgbtn_set_src_both(buttonCN, "F:/bmp_simplified_cn_sel.bin"); + lv_obj_refresh_ext_draw_pad(buttonCN); + gCfgItems.language = LANG_SIMPLE_CHINESE; + update_spi_flash(); + disp_language_init(); + break; + case ID_T_CN: + disp_language(gCfgItems.language, UNSELECTED); + lv_imgbtn_set_src_both(buttonT_CN, "F:/bmp_traditional_cn_sel.bin"); + lv_obj_refresh_ext_draw_pad(buttonT_CN); + gCfgItems.language = LANG_COMPLEX_CHINESE; + update_spi_flash(); + disp_language_init(); + break; + case ID_EN: + disp_language(gCfgItems.language, UNSELECTED); + lv_imgbtn_set_src_both(buttonEN, "F:/bmp_english_sel.bin"); + lv_obj_refresh_ext_draw_pad(buttonEN); + gCfgItems.language = LANG_ENGLISH; + update_spi_flash(); + disp_language_init(); + break; + case ID_RU: + disp_language(gCfgItems.language, UNSELECTED); + lv_imgbtn_set_src_both(buttonRU, "F:/bmp_russian_sel.bin"); + lv_obj_refresh_ext_draw_pad(buttonRU); + gCfgItems.language = LANG_RUSSIAN; + update_spi_flash(); + disp_language_init(); + break; + case ID_ES: + disp_language(gCfgItems.language, UNSELECTED); + lv_imgbtn_set_src_both(buttonES, "F:/bmp_spanish_sel.bin"); + lv_obj_refresh_ext_draw_pad(buttonES); + gCfgItems.language = LANG_SPANISH; + update_spi_flash(); + disp_language_init(); + break; + case ID_FR: + disp_language(gCfgItems.language, UNSELECTED); + lv_imgbtn_set_src_both(buttonFR, "F:/bmp_french_sel.bin"); + lv_obj_refresh_ext_draw_pad(buttonFR); + gCfgItems.language = LANG_FRENCH; + update_spi_flash(); + disp_language_init(); + break; + case ID_IT: + disp_language(gCfgItems.language, UNSELECTED); + lv_imgbtn_set_src_both(buttonIT, "F:/bmp_italy_sel.bin"); + lv_obj_refresh_ext_draw_pad(buttonIT); + gCfgItems.language = LANG_ITALY; + update_spi_flash(); + disp_language_init(); + break; + case ID_L_RETURN: + buttonCN = nullptr; + buttonT_CN = nullptr; + buttonEN = nullptr; + buttonRU = nullptr; + buttonES = nullptr; + buttonFR = nullptr; + buttonFR = nullptr; + buttonIT = nullptr; + lv_clear_language(); + lv_draw_set(); + break; + } +} + +static void disp_language(uint8_t language, uint8_t state) { + uint16_t id; + lv_obj_t *obj; + + public_buf_l[0] = '\0'; + + switch (language) { + case LANG_SIMPLE_CHINESE: + id = ID_CN; + strcpy_P(public_buf_l, PSTR("F:/bmp_simplified_cn")); + obj = buttonCN; + break; + case LANG_COMPLEX_CHINESE: + id = ID_T_CN; + strcpy_P(public_buf_l, PSTR("F:/bmp_traditional_cn")); + obj = buttonT_CN; + break; + case LANG_ENGLISH: + id = ID_EN; + strcpy_P(public_buf_l, PSTR("F:/bmp_english")); + obj = buttonEN; + break; + case LANG_RUSSIAN: + id = ID_RU; + strcpy_P(public_buf_l, PSTR("F:/bmp_russian")); + obj = buttonRU; + break; + case LANG_SPANISH: + id = ID_ES; + strcpy_P(public_buf_l, PSTR("F:/bmp_spanish")); + obj = buttonES; + break; + case LANG_FRENCH: + id = ID_FR; + strcpy_P(public_buf_l, PSTR("F:/bmp_french")); + obj = buttonFR; + break; + case LANG_ITALY: + id = ID_IT; + strcpy_P(public_buf_l, PSTR("F:/bmp_italy")); + obj = buttonIT; + break; + default: + id = ID_CN; + strcpy_P(public_buf_l, PSTR("F:/bmp_simplified_cn")); + obj = buttonCN; + break; + } + + if (state == SELECTED) strcat_P(public_buf_l, PSTR("_sel")); + + strcat_P(public_buf_l, PSTR(".bin")); + + lv_obj_set_event_cb_mks(obj, event_handler, id, "", 0); + lv_imgbtn_set_src_both(obj, public_buf_l); + + if (state == UNSELECTED) lv_obj_refresh_ext_draw_pad(obj); +} + +void lv_draw_language() { + scr = lv_screen_create(LANGUAGE_UI); + // Create image buttons + buttonCN = lv_big_button_create(scr, "F:/bmp_simplified_cn.bin", language_menu.chinese_s, INTERVAL_V, titleHeight, event_handler, ID_CN); + lv_obj_clear_protect(buttonCN, LV_PROTECT_FOLLOW); + buttonT_CN = lv_big_button_create(scr, "F:/bmp_traditional_cn.bin", language_menu.chinese_t, BTN_X_PIXEL + INTERVAL_V * 2, titleHeight, event_handler, ID_T_CN); + buttonEN = lv_big_button_create(scr, "F:/bmp_english.bin", language_menu.english, BTN_X_PIXEL * 2 + INTERVAL_V * 3, titleHeight, event_handler, ID_EN); + buttonRU = lv_big_button_create(scr, "F:/bmp_russian.bin", language_menu.russian, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight, event_handler, ID_RU); + buttonES = lv_big_button_create(scr, "F:/bmp_spanish.bin", language_menu.spanish, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_ES); + buttonFR = lv_big_button_create(scr, "F:/bmp_french.bin", language_menu.french, BTN_X_PIXEL + INTERVAL_V * 2, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_FR); + buttonIT = lv_big_button_create(scr, "F:/bmp_italy.bin", language_menu.italy, BTN_X_PIXEL * 2 + INTERVAL_V * 3, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_IT); + lv_big_button_create(scr, "F:/bmp_return.bin", common_menu.text_back, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_L_RETURN); + disp_language(gCfgItems.language, SELECTED); +} + +void lv_clear_language() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_language.h b/Marlin/src/lcd/extui/mks_ui/draw_language.h similarity index 90% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_language.h rename to Marlin/src/lcd/extui/mks_ui/draw_language.h index ca6d40bfc3ca..4f51856f4f55 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_language.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_language.h @@ -25,10 +25,9 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_language(void); -extern void lv_clear_language(); +void lv_draw_language(); +void lv_clear_language(); -//extern void disp_temp_ready_print(); #ifdef __cplusplus } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_level_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_level_settings.cpp new file mode 100644 index 000000000000..8c8dec891381 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_level_settings.cpp @@ -0,0 +1,80 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include + +#include "../../../inc/MarlinConfig.h" + +extern lv_group_t *g; +static lv_obj_t *scr; + +enum { + ID_LEVEL_RETURN = 1, + ID_LEVEL_POSITION, + ID_LEVEL_COMMAND, + ID_LEVEL_ZOFFSET +}; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + lv_clear_level_settings(); + switch (obj->mks_obj_id) { + case ID_LEVEL_RETURN: + draw_return_ui(); + break; + case ID_LEVEL_POSITION: + lv_draw_tramming_pos_settings(); + break; + case ID_LEVEL_COMMAND: + keyboard_value = autoLevelGcodeCommand; + lv_draw_keyboard(); + break; + #if HAS_BED_PROBE + case ID_LEVEL_ZOFFSET: + lv_draw_auto_level_offset_settings(); + break; + #endif + } +} + +void lv_draw_level_settings() { + scr = lv_screen_create(LEVELING_PARA_UI, machine_menu.LevelingParaConfTitle); + lv_screen_menu_item(scr, machine_menu.TrammingPosConf, PARA_UI_POS_X, PARA_UI_POS_Y, event_handler, ID_LEVEL_POSITION, 0); + lv_screen_menu_item(scr, machine_menu.LevelingAutoCommandConf, PARA_UI_POS_X, PARA_UI_POS_Y * 2, event_handler, ID_LEVEL_COMMAND, 1); + #if HAS_BED_PROBE + lv_screen_menu_item(scr, machine_menu.LevelingAutoZoffsetConf, PARA_UI_POS_X, PARA_UI_POS_Y * 3, event_handler, ID_LEVEL_ZOFFSET, 2); + #endif + lv_big_button_create(scr, "F:/bmp_back70x40.bin", common_menu.text_back, PARA_UI_BACL_POS_X + 10, PARA_UI_BACL_POS_Y, event_handler, ID_LEVEL_RETURN, true); +} + +void lv_clear_level_settings() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_level_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_level_settings.h similarity index 92% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_level_settings.h rename to Marlin/src/lcd/extui/mks_ui/draw_level_settings.h index ce290172b6e5..06283d20955b 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_level_settings.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_level_settings.h @@ -25,8 +25,8 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_level_settings(void); -extern void lv_clear_level_settings(); +void lv_draw_level_settings(); +void lv_clear_level_settings(); #ifdef __cplusplus } /* C-declarations for C++ */ diff --git a/Marlin/src/lcd/extui/mks_ui/draw_machine_para.cpp b/Marlin/src/lcd/extui/mks_ui/draw_machine_para.cpp new file mode 100644 index 000000000000..890db3b5cd06 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_machine_para.cpp @@ -0,0 +1,84 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include + +#include "../../../inc/MarlinConfig.h" + +extern lv_group_t *g; +static lv_obj_t *scr; + +enum { + ID_PARA_RETURN = 1, + ID_PARA_MACHINE, + ID_PARA_MOTOR, + ID_PARA_LEVEL, + ID_PARA_ADVANCE +}; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + switch (obj->mks_obj_id) { + case ID_PARA_RETURN: + lv_clear_machine_para(); + draw_return_ui(); + break; + case ID_PARA_MACHINE: + lv_clear_machine_para(); + lv_draw_machine_settings(); + break; + case ID_PARA_MOTOR: + lv_clear_machine_para(); + lv_draw_motor_settings(); + break; + case ID_PARA_LEVEL: + lv_clear_machine_para(); + lv_draw_level_settings(); + break; + case ID_PARA_ADVANCE: + lv_clear_machine_para(); + lv_draw_advance_settings(); + break; + } +} + +void lv_draw_machine_para() { + scr = lv_screen_create(MACHINE_PARA_UI); + lv_screen_menu_item(scr, MachinePara_menu.MachineSetting, PARA_UI_POS_X, PARA_UI_POS_Y, event_handler, ID_PARA_MACHINE, 0); + lv_screen_menu_item(scr, MachinePara_menu.MotorSetting, PARA_UI_POS_X, PARA_UI_POS_Y * 2, event_handler, ID_PARA_MOTOR, 1); + lv_screen_menu_item(scr, MachinePara_menu.leveling, PARA_UI_POS_X, PARA_UI_POS_Y * 3, event_handler, ID_PARA_LEVEL, 2); + lv_screen_menu_item(scr, MachinePara_menu.AdvanceSetting, PARA_UI_POS_X, PARA_UI_POS_Y * 4, event_handler, ID_PARA_ADVANCE, 3); + lv_big_button_create(scr, "F:/bmp_back70x40.bin", common_menu.text_back, PARA_UI_BACL_POS_X + 10, PARA_UI_BACL_POS_Y, event_handler, ID_PARA_RETURN, true); +} + +void lv_clear_machine_para() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_machine_para.h b/Marlin/src/lcd/extui/mks_ui/draw_machine_para.h similarity index 92% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_machine_para.h rename to Marlin/src/lcd/extui/mks_ui/draw_machine_para.h index e830f75db7e5..f495e8b35e5e 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_machine_para.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_machine_para.h @@ -25,8 +25,8 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_machine_para(void); -extern void lv_clear_machine_para(); +void lv_draw_machine_para(); +void lv_clear_machine_para(); #ifdef __cplusplus } /* C-declarations for C++ */ diff --git a/Marlin/src/lcd/extui/mks_ui/draw_machine_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_machine_settings.cpp new file mode 100644 index 000000000000..3f43da992cac --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_machine_settings.cpp @@ -0,0 +1,82 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include + +#include "../../../inc/MarlinConfig.h" + +extern lv_group_t *g; +static lv_obj_t *scr; + +enum { + ID_MACHINE_RETURN = 1, + ID_MACHINE_ACCELERATION, + ID_MACHINE_FEEDRATE, + ID_MACHINE_JERK +}; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + switch (obj->mks_obj_id) { + case ID_MACHINE_RETURN: + lv_clear_machine_settings(); + draw_return_ui(); + break; + case ID_MACHINE_ACCELERATION: + lv_clear_machine_settings(); + lv_draw_acceleration_settings(); + break; + case ID_MACHINE_FEEDRATE: + lv_clear_machine_settings(); + lv_draw_max_feedrate_settings(); + break; + #if HAS_CLASSIC_JERK + case ID_MACHINE_JERK: + lv_clear_machine_settings(); + lv_draw_jerk_settings(); + break; + #endif + } +} + +void lv_draw_machine_settings() { + scr = lv_screen_create(MACHINE_SETTINGS_UI, machine_menu.MachineConfigTitle); + lv_screen_menu_item(scr, machine_menu.AccelerationConf, PARA_UI_POS_X, PARA_UI_POS_Y, event_handler, ID_MACHINE_ACCELERATION, 0); + lv_screen_menu_item(scr, machine_menu.MaxFeedRateConf, PARA_UI_POS_X, PARA_UI_POS_Y * 2, event_handler, ID_MACHINE_FEEDRATE, 1); + #if HAS_CLASSIC_JERK + lv_screen_menu_item(scr, machine_menu.JerkConf, PARA_UI_POS_X, PARA_UI_POS_Y * 3, event_handler, ID_MACHINE_JERK, 2); + #endif + lv_big_button_create(scr, "F:/bmp_back70x40.bin", common_menu.text_back, PARA_UI_BACL_POS_X + 10, PARA_UI_BACL_POS_Y, event_handler, ID_MACHINE_RETURN, true); +} + +void lv_clear_machine_settings() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_machine_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_machine_settings.h similarity index 92% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_machine_settings.h rename to Marlin/src/lcd/extui/mks_ui/draw_machine_settings.h index 38d02e718948..f113f65fc1b0 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_machine_settings.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_machine_settings.h @@ -25,8 +25,8 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_machine_settings(void); -extern void lv_clear_machine_settings(); +void lv_draw_machine_settings(); +void lv_clear_machine_settings(); #ifdef __cplusplus } /* C-declarations for C++ */ diff --git a/Marlin/src/lcd/extui/mks_ui/draw_manuaLevel.cpp b/Marlin/src/lcd/extui/mks_ui/draw_manuaLevel.cpp new file mode 100644 index 000000000000..b927b99b76f3 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_manuaLevel.cpp @@ -0,0 +1,87 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include + +#include "../../../gcode/queue.h" +#include "../../../inc/MarlinConfig.h" + +extern const char G28_STR[]; + +extern lv_group_t *g; +static lv_obj_t *scr; + +enum { + ID_M_POINT1 = 1, + ID_M_POINT2, + ID_M_POINT3, + ID_M_POINT4, + ID_M_POINT5, + ID_MANUAL_RETURN +}; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + + switch (obj->mks_obj_id) { + case ID_M_POINT1 ... ID_M_POINT5: + if (queue.ring_buffer.empty()) { + if (uiCfg.leveling_first_time) { + uiCfg.leveling_first_time = false; + queue.inject_P(G28_STR); + } + const int ind = obj->mks_obj_id - ID_M_POINT1; + sprintf_P(public_buf_l, PSTR("G1Z10\nG1X%dY%d\nG1Z0"), gCfgItems.trammingPos[ind].x, gCfgItems.trammingPos[ind].y); + queue.inject(public_buf_l); + } + break; + case ID_MANUAL_RETURN: + lv_clear_manualLevel(); + lv_draw_tool(); + break; + } +} + +void lv_draw_manualLevel() { + scr = lv_screen_create(LEVELING_UI); + // Create an Image button + lv_obj_t *buttonPoint1 = lv_big_button_create(scr, "F:/bmp_leveling1.bin", leveling_menu.position1, INTERVAL_V, titleHeight, event_handler, ID_M_POINT1); + lv_obj_clear_protect(buttonPoint1, LV_PROTECT_FOLLOW); + lv_big_button_create(scr, "F:/bmp_leveling2.bin", leveling_menu.position2, BTN_X_PIXEL + INTERVAL_V * 2, titleHeight, event_handler, ID_M_POINT2); + lv_big_button_create(scr, "F:/bmp_leveling3.bin", leveling_menu.position3, BTN_X_PIXEL * 2 + INTERVAL_V * 3, titleHeight, event_handler, ID_M_POINT3); + lv_big_button_create(scr, "F:/bmp_leveling4.bin", leveling_menu.position4, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight, event_handler, ID_M_POINT4); + lv_big_button_create(scr, "F:/bmp_leveling5.bin", leveling_menu.position5, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_M_POINT5); + lv_big_button_create(scr, "F:/bmp_return.bin", common_menu.text_back, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_MANUAL_RETURN); +} + +void lv_clear_manualLevel() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_manuaLevel.h b/Marlin/src/lcd/extui/mks_ui/draw_manuaLevel.h similarity index 89% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_manuaLevel.h rename to Marlin/src/lcd/extui/mks_ui/draw_manuaLevel.h index cfa10370e128..29c8fa144ed3 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_manuaLevel.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_manuaLevel.h @@ -25,10 +25,9 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_manualLevel(void); -extern void lv_clear_manualLevel(); +void lv_draw_manualLevel(); +void lv_clear_manualLevel(); -//extern void disp_temp_ready_print(); #ifdef __cplusplus } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_max_feedrate_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_max_feedrate_settings.cpp new file mode 100644 index 000000000000..2cccf899b458 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_max_feedrate_settings.cpp @@ -0,0 +1,117 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include + +#include "../../../module/planner.h" +#include "../../../inc/MarlinConfig.h" + +extern lv_group_t *g; +static lv_obj_t *scr; + +enum { + ID_FEED_RETURN = 1, + ID_FEED_X, + ID_FEED_Y, + ID_FEED_Z, + ID_FEED_E0, + ID_FEED_E1, + ID_FEED_DOWN, + ID_FEED_UP +}; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + + lv_clear_max_feedrate_settings(); + switch (obj->mks_obj_id) { + case ID_FEED_RETURN: + uiCfg.para_ui_page = false; + draw_return_ui(); + return; + case ID_FEED_X: + value = XMaxFeedRate; + break; + case ID_FEED_Y: + value = YMaxFeedRate; + break; + case ID_FEED_Z: + value = ZMaxFeedRate; + break; + case ID_FEED_E0: + value = E0MaxFeedRate; + break; + case ID_FEED_E1: + value = E1MaxFeedRate; + break; + case ID_FEED_UP: + uiCfg.para_ui_page = false; + lv_draw_max_feedrate_settings(); + return; + case ID_FEED_DOWN: + uiCfg.para_ui_page = true; + lv_draw_max_feedrate_settings(); + return; + } + lv_draw_number_key(); +} + +void lv_draw_max_feedrate_settings() { + scr = lv_screen_create(MAXFEEDRATE_UI, machine_menu.MaxFeedRateConfTitle); + + if (!uiCfg.para_ui_page) { + dtostrf(planner.settings.max_feedrate_mm_s[X_AXIS], 1, 1, public_buf_l); + lv_screen_menu_item_1_edit(scr, machine_menu.XMaxFeedRate, PARA_UI_POS_X, PARA_UI_POS_Y, event_handler, ID_FEED_X, 0, public_buf_l); + + dtostrf(planner.settings.max_feedrate_mm_s[Y_AXIS], 1, 1, public_buf_l); + lv_screen_menu_item_1_edit(scr, machine_menu.YMaxFeedRate, PARA_UI_POS_X, PARA_UI_POS_Y * 2, event_handler, ID_FEED_Y, 1, public_buf_l); + + dtostrf(planner.settings.max_feedrate_mm_s[Z_AXIS], 1, 1, public_buf_l); + lv_screen_menu_item_1_edit(scr, machine_menu.ZMaxFeedRate, PARA_UI_POS_X, PARA_UI_POS_Y * 3, event_handler, ID_FEED_Z, 2, public_buf_l); + + dtostrf(planner.settings.max_feedrate_mm_s[E_AXIS], 1, 1, public_buf_l); + lv_screen_menu_item_1_edit(scr, machine_menu.E0MaxFeedRate, PARA_UI_POS_X, PARA_UI_POS_Y * 4, event_handler, ID_FEED_E0, 3, public_buf_l); + + 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_FEED_DOWN, true); + } + else { + dtostrf(planner.settings.max_feedrate_mm_s[E_AXIS_N(1)], 1, 1, public_buf_l); + lv_screen_menu_item_1_edit(scr, machine_menu.E1MaxFeedRate, PARA_UI_POS_X, PARA_UI_POS_Y, event_handler, ID_FEED_E1, 0, public_buf_l); + + lv_big_button_create(scr, "F:/bmp_back70x40.bin", machine_menu.previous, PARA_UI_TURN_PAGE_POS_X, PARA_UI_TURN_PAGE_POS_Y, event_handler, ID_FEED_UP, true); + } + + lv_big_button_create(scr, "F:/bmp_back70x40.bin", common_menu.text_back, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y, event_handler, ID_FEED_RETURN, true); +} + +void lv_clear_max_feedrate_settings() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_max_feedrate_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_max_feedrate_settings.h similarity index 91% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_max_feedrate_settings.h rename to Marlin/src/lcd/extui/mks_ui/draw_max_feedrate_settings.h index 78caca5adea4..45c3fd29db22 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_max_feedrate_settings.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_max_feedrate_settings.h @@ -25,8 +25,8 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_max_feedrate_settings(void); -extern void lv_clear_max_feedrate_settings(); +void lv_draw_max_feedrate_settings(); +void lv_clear_max_feedrate_settings(); #ifdef __cplusplus } /* C-declarations for C++ */ diff --git a/Marlin/src/lcd/extui/mks_ui/draw_media_select.cpp b/Marlin/src/lcd/extui/mks_ui/draw_media_select.cpp new file mode 100644 index 000000000000..81c82dc02dfa --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_media_select.cpp @@ -0,0 +1,73 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if BOTH(HAS_TFT_LVGL_UI, MULTI_VOLUME) + +#include "draw_ui.h" +#include + +#include "../../../inc/MarlinConfig.h" +#include "../../../sd/cardreader.h" + +extern lv_group_t *g; +static lv_obj_t *scr; + +enum { + ID_T_USB_DISK = 1, + ID_T_SD_DISK, + ID_T_RETURN +}; + +#if ENABLED(MKS_TEST) + extern uint8_t current_disp_ui; +#endif + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + lv_clear_media_select(); + switch (obj->mks_obj_id) { + case ID_T_USB_DISK: card.changeMedia(&card.media_driver_usbFlash); break; + case ID_T_SD_DISK: card.changeMedia(&card.media_driver_sdcard); break; + case ID_T_RETURN: + TERN_(MKS_TEST, current_disp_ui = 1); + lv_draw_ready_print(); + return; + } + lv_draw_print_file(); +} + +void lv_draw_media_select() { + scr = lv_screen_create(MEDIA_SELECT_UI); + lv_big_button_create(scr, "F:/bmp_sd.bin", media_select_menu.sd_disk, INTERVAL_V, titleHeight, event_handler, ID_T_SD_DISK); + lv_big_button_create(scr, "F:/bmp_usb_disk.bin", media_select_menu.usb_disk, BTN_X_PIXEL + INTERVAL_V * 2, titleHeight, event_handler, ID_T_USB_DISK); + lv_big_button_create(scr, "F:/bmp_return.bin", common_menu.text_back, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_T_RETURN); +} + +void lv_clear_media_select() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_media_select.h b/Marlin/src/lcd/extui/mks_ui/draw_media_select.h new file mode 100644 index 000000000000..a698714a9dce --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_media_select.h @@ -0,0 +1,33 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#ifdef __cplusplus + extern "C" { /* C-declarations for C++ */ +#endif + +extern void lv_draw_media_select(); +extern void lv_clear_media_select(); + +#ifdef __cplusplus + } /* C-declarations for C++ */ +#endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_more.cpp b/Marlin/src/lcd/extui/mks_ui/draw_more.cpp new file mode 100644 index 000000000000..e89e2f3e8ae0 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_more.cpp @@ -0,0 +1,202 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "../../../MarlinCore.h" +#include "draw_ready_print.h" +#include "draw_set.h" +#include "lv_conf.h" +#include "draw_ui.h" +#include "../../../gcode/queue.h" + +extern lv_group_t * g; +static lv_obj_t * scr; + +enum { + ID_GCODE = 1, + #if HAS_USER_ITEM(1) + ID_CUSTOM_1, + #endif + #if HAS_USER_ITEM(2) + ID_CUSTOM_2, + #endif + #if HAS_USER_ITEM(3) + ID_CUSTOM_3, + #endif + #if HAS_USER_ITEM(4) + ID_CUSTOM_4, + #endif + #if HAS_USER_ITEM(5) + ID_CUSTOM_5, + #endif + #if HAS_USER_ITEM(6) + ID_CUSTOM_6, + #endif + ID_M_RETURN, +}; + +static void event_handler(lv_obj_t * obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + switch (obj->mks_obj_id) { + case ID_GCODE: lv_clear_more(); lv_draw_gcode(true); break; + #if HAS_USER_ITEM(1) + case ID_CUSTOM_1: queue.inject_P(PSTR(MAIN_MENU_ITEM_1_GCODE)); break; + #endif + #if HAS_USER_ITEM(2) + case ID_CUSTOM_2: queue.inject_P(PSTR(MAIN_MENU_ITEM_2_GCODE)); break; + #endif + #if HAS_USER_ITEM(3) + case ID_CUSTOM_3: queue.inject_P(PSTR(MAIN_MENU_ITEM_3_GCODE)); break; + #endif + #if HAS_USER_ITEM(4) + case ID_CUSTOM_4: queue.inject_P(PSTR(MAIN_MENU_ITEM_4_GCODE)); break; + #endif + #if HAS_USER_ITEM(5) + case ID_CUSTOM_5: queue.inject_P(PSTR(MAIN_MENU_ITEM_5_GCODE)); break; + #endif + #if HAS_USER_ITEM(6) + case ID_CUSTOM_6: queue.inject_P(PSTR(MAIN_MENU_ITEM_6_GCODE)); break; + #endif + case ID_M_RETURN: + lv_clear_more(); + lv_draw_tool(); + break; + } +} + +void lv_draw_more() { + scr = lv_screen_create(MORE_UI); + + const bool enc_ena = TERN0(HAS_ROTARY_ENCODER, gCfgItems.encoder_enable); + + lv_obj_t *buttonGCode = lv_imgbtn_create(scr, "F:/bmp_machine_para.bin", INTERVAL_V, titleHeight, event_handler, ID_GCODE); + if (enc_ena) lv_group_add_obj(g, buttonGCode); + lv_obj_t *labelGCode = lv_label_create_empty(buttonGCode); + + #if HAS_USER_ITEM(1) + lv_obj_t *buttonCustom1 = lv_imgbtn_create(scr, "F:/bmp_custom1.bin", BTN_X_PIXEL + INTERVAL_V * 2, titleHeight, event_handler, ID_CUSTOM_1); + if (enc_ena) lv_group_add_obj(g, buttonCustom1); + lv_obj_t *labelCustom1 = lv_label_create_empty(buttonCustom1); + #endif + + #if HAS_USER_ITEM(2) + lv_obj_t *buttonCustom2 = lv_imgbtn_create(scr, "F:/bmp_custom2.bin", BTN_X_PIXEL * 2 + INTERVAL_V * 3, titleHeight, event_handler, ID_CUSTOM_2); + if (enc_ena) lv_group_add_obj(g, buttonCustom2); + lv_obj_t *labelCustom2 = lv_label_create_empty(buttonCustom2); + #endif + + #if HAS_USER_ITEM(3) + lv_obj_t *buttonCustom3 = lv_imgbtn_create(scr, "F:/bmp_custom3.bin", BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight, event_handler, ID_CUSTOM_3); + if (enc_ena) lv_group_add_obj(g, buttonCustom3); + lv_obj_t *labelCustom3 = lv_label_create_empty(buttonCustom3); + #endif + + #if HAS_USER_ITEM(4) + lv_obj_t *buttonCustom4 = lv_imgbtn_create(scr, "F:/bmp_custom4.bin", INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_CUSTOM_4); + if (enc_ena) lv_group_add_obj(g, buttonCustom4); + lv_obj_t *labelCustom4 = lv_label_create_empty(buttonCustom4); + #endif + + #if HAS_USER_ITEM(5) + lv_obj_t *buttonCustom5 = lv_imgbtn_create(scr, "F:/bmp_custom5.bin", BTN_X_PIXEL + INTERVAL_V * 2, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_CUSTOM_5); + if (enc_ena) lv_group_add_obj(g, buttonCustom5); + lv_obj_t *labelCustom5 = lv_label_create_empty(buttonCustom5); + #endif + + #if HAS_USER_ITEM(6) + lv_obj_t *buttonCustom6 = lv_imgbtn_create(scr, "F:/bmp_custom6.bin", BTN_X_PIXEL * 2 + INTERVAL_V * 3, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_CUSTOM_6); + if (enc_ena) lv_group_add_obj(g, buttonCustom6); + lv_obj_t *labelCustom6 = lv_label_create_empty(buttonCustom6); + #endif + + lv_obj_t *buttonBack = lv_imgbtn_create(scr, "F:/bmp_return.bin", BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_M_RETURN); + if (enc_ena) lv_group_add_obj(g, buttonBack); + lv_obj_t *label_Back = lv_label_create_empty(buttonBack); + + if (gCfgItems.multiple_language != 0) { + lv_label_set_text(labelGCode, more_menu.gcode); + lv_obj_align(labelGCode, buttonGCode, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + + #if HAS_USER_ITEM(1) + lv_label_set_text(labelCustom1, more_menu.custom1); + lv_obj_align(labelCustom1, buttonCustom1, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + #endif + #if HAS_USER_ITEM(2) + lv_label_set_text(labelCustom2, more_menu.custom2); + lv_obj_align(labelCustom2, buttonCustom2, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + #endif + #if HAS_USER_ITEM(3) + lv_label_set_text(labelCustom3, more_menu.custom3); + lv_obj_align(labelCustom3, buttonCustom3, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + #endif + #if HAS_USER_ITEM(4) + lv_label_set_text(labelCustom4, more_menu.custom4); + lv_obj_align(labelCustom4, buttonCustom4, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + #endif + #if HAS_USER_ITEM(5) + lv_label_set_text(labelCustom5, more_menu.custom5); + lv_obj_align(labelCustom5, buttonCustom5, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + #endif + #if HAS_USER_ITEM(6) + lv_label_set_text(labelCustom6, more_menu.custom6); + lv_obj_align(labelCustom6, buttonCustom6, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + #endif + lv_label_set_text(label_Back, common_menu.text_back); + lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + + #if BUTTONS_EXIST(EN1, EN2, ENC) + if (enc_ena) { + lv_group_add_obj(g, buttonGCode); + #if HAS_USER_ITEM(1) + lv_group_add_obj(g, buttonCustom1); + #endif + #if HAS_USER_ITEM(2) + lv_group_add_obj(g, buttonCustom2); + #endif + #if HAS_USER_ITEM(3) + lv_group_add_obj(g, buttonCustom3); + #endif + #if HAS_USER_ITEM(4) + lv_group_add_obj(g, buttonCustom4); + #endif + #if HAS_USER_ITEM(5) + lv_group_add_obj(g, buttonCustom5); + #endif + #if HAS_USER_ITEM(6) + lv_group_add_obj(g, buttonCustom6); + #endif + lv_group_add_obj(g, buttonBack); + } + #endif +} + +void lv_clear_more() { + #if BUTTONS_EXIST(EN1, EN2, ENC) + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_more.h b/Marlin/src/lcd/extui/mks_ui/draw_more.h new file mode 100644 index 000000000000..74ac7e994db4 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_more.h @@ -0,0 +1,33 @@ +/** + * 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 + +#ifdef __cplusplus +extern "C" { /* C-declarations for C++ */ +#endif + +void lv_draw_more(); +void lv_clear_more(); + +#ifdef __cplusplus +} /* C-declarations for C++ */ +#endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_motor_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_motor_settings.cpp new file mode 100644 index 000000000000..b86370e35a42 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_motor_settings.cpp @@ -0,0 +1,98 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include + +#include "../../../inc/MarlinConfig.h" + +extern lv_group_t *g; +static lv_obj_t *scr; + +enum { + ID_MOTOR_RETURN = 1, + ID_MOTOR_STEPS, + ID_MOTOR_TMC_CURRENT, + ID_MOTOR_STEP_MODE, + ID_HOME_SENSE +}; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + lv_clear_motor_settings(); + switch (obj->mks_obj_id) { + case ID_MOTOR_RETURN: + draw_return_ui(); + break; + case ID_MOTOR_STEPS: + lv_draw_step_settings(); + break; + #if USE_SENSORLESS + case ID_HOME_SENSE: + lv_draw_homing_sensitivity_settings(); + break; + #endif + + #if HAS_TRINAMIC_CONFIG + case ID_MOTOR_TMC_CURRENT: + lv_draw_tmc_current_settings(); + break; + #if HAS_STEALTHCHOP + case ID_MOTOR_STEP_MODE: + lv_draw_tmc_step_mode_settings(); + break; + #endif + #endif + } +} + +void lv_draw_motor_settings() { + int index = 0; + + scr = lv_screen_create(MOTOR_SETTINGS_UI, machine_menu.MotorConfTitle); + lv_screen_menu_item(scr, machine_menu.StepsConf, PARA_UI_POS_X, PARA_UI_POS_Y, event_handler, ID_MOTOR_STEPS, index++); + #if USE_SENSORLESS + lv_screen_menu_item(scr, machine_menu.HomingSensitivityConf, PARA_UI_POS_X, PARA_UI_POS_Y * (index + 1), event_handler, ID_HOME_SENSE, index); + index++; + #endif + #if HAS_TRINAMIC_CONFIG + lv_screen_menu_item(scr, machine_menu.TMCcurrentConf, PARA_UI_POS_X, PARA_UI_POS_Y * (index + 1), event_handler, ID_MOTOR_TMC_CURRENT, index); + index++; + #if HAS_STEALTHCHOP + lv_screen_menu_item(scr, machine_menu.TMCStepModeConf, PARA_UI_POS_X, PARA_UI_POS_Y * (index + 1), event_handler, ID_MOTOR_STEP_MODE, index); + index++; + #endif + #endif + lv_big_button_create(scr, "F:/bmp_back70x40.bin", common_menu.text_back, PARA_UI_BACL_POS_X + 10, PARA_UI_BACL_POS_Y, event_handler, ID_MOTOR_RETURN, true); +} + +void lv_clear_motor_settings() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_motor_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_motor_settings.h similarity index 92% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_motor_settings.h rename to Marlin/src/lcd/extui/mks_ui/draw_motor_settings.h index 9a1c7a4db517..5d26a402d034 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_motor_settings.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_motor_settings.h @@ -25,8 +25,8 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_motor_settings(void); -extern void lv_clear_motor_settings(); +void lv_draw_motor_settings(); +void lv_clear_motor_settings(); #ifdef __cplusplus } /* C-declarations for C++ */ diff --git a/Marlin/src/lcd/extui/mks_ui/draw_move_motor.cpp b/Marlin/src/lcd/extui/mks_ui/draw_move_motor.cpp new file mode 100644 index 000000000000..7a37dc6a1556 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_move_motor.cpp @@ -0,0 +1,164 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include + +#include "../../../gcode/queue.h" +#include "../../../module/motion.h" +#include "../../../inc/MarlinConfig.h" + +extern lv_group_t *g; +static lv_obj_t *scr; + +static lv_obj_t *labelV, *buttonV, *labelP; +static lv_task_t *updatePosTask; +static char cur_label = 'Z'; +static float cur_pos = 0; + +enum { + ID_M_X_P = 1, + ID_M_X_N, + ID_M_Y_P, + ID_M_Y_N, + ID_M_Z_P, + ID_M_Z_N, + ID_M_STEP, + ID_M_RETURN +}; + +void disp_cur_pos() { + char str_1[16]; + sprintf_P(public_buf_l, PSTR("%c:%s mm"), cur_label, dtostrf(cur_pos, 1, 1, str_1)); + if (labelP) lv_label_set_text(labelP, public_buf_l); +} + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + char str_1[16]; + if (event != LV_EVENT_RELEASED) return; + if (!queue.ring_buffer.full(3)) { + bool do_inject = true; + float dist = uiCfg.move_dist; + switch (obj->mks_obj_id) { + case ID_M_X_N: dist *= -1; case ID_M_X_P: cur_label = 'X'; break; + case ID_M_Y_N: dist *= -1; case ID_M_Y_P: cur_label = 'Y'; break; + case ID_M_Z_N: dist *= -1; case ID_M_Z_P: cur_label = 'Z'; break; + default: do_inject = false; + } + if (do_inject) { + sprintf_P(public_buf_l, PSTR("G91\nG1 %c%s F%d\nG90"), cur_label, dtostrf(dist, 1, 3, str_1), uiCfg.moveSpeed); + queue.inject(public_buf_l); + } + } + + switch (obj->mks_obj_id) { + case ID_M_STEP: + if (ABS(10 * (int)uiCfg.move_dist) == 100) + uiCfg.move_dist = 0.1; + else + uiCfg.move_dist *= 10.0f; + disp_move_dist(); + break; + case ID_M_RETURN: + clear_cur_ui(); + draw_return_ui(); + return; + } + disp_cur_pos(); +} + +void refresh_pos(lv_task_t *) { + switch (cur_label) { + case 'X': cur_pos = current_position.x; break; + case 'Y': cur_pos = current_position.y; break; + case 'Z': cur_pos = current_position.z; break; + default: return; + } + disp_cur_pos(); +} + +void lv_draw_move_motor() { + scr = lv_screen_create(MOVE_MOTOR_UI); + lv_obj_t *buttonXI = lv_big_button_create(scr, "F:/bmp_xAdd.bin", move_menu.x_add, INTERVAL_V, titleHeight, event_handler, ID_M_X_P); + lv_obj_clear_protect(buttonXI, LV_PROTECT_FOLLOW); + lv_big_button_create(scr, "F:/bmp_xDec.bin", move_menu.x_dec, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_M_X_N); + lv_big_button_create(scr, "F:/bmp_yAdd.bin", move_menu.y_add, BTN_X_PIXEL + INTERVAL_V * 2, titleHeight, event_handler, ID_M_Y_P); + lv_big_button_create(scr, "F:/bmp_yDec.bin", move_menu.y_dec, BTN_X_PIXEL + INTERVAL_V * 2, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_M_Y_N); + lv_big_button_create(scr, "F:/bmp_zAdd.bin", move_menu.z_add, BTN_X_PIXEL * 2 + INTERVAL_V * 3, titleHeight, event_handler, ID_M_Z_P); + lv_big_button_create(scr, "F:/bmp_zDec.bin", move_menu.z_dec, BTN_X_PIXEL * 2 + INTERVAL_V * 3, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_M_Z_N); + + // button with image and label changed dynamically by disp_move_dist + buttonV = lv_imgbtn_create(scr, nullptr, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight, event_handler, ID_M_STEP); + labelV = lv_label_create_empty(buttonV); + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonV); + #endif + + lv_big_button_create(scr, "F:/bmp_return.bin", common_menu.text_back, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_M_RETURN); + + // We need to patch the title to leave some space on the right for displaying the status + lv_obj_t * title = lv_obj_get_child_back(scr, nullptr); + if (title != nullptr) lv_obj_set_width(title, TFT_WIDTH - 101); + labelP = lv_label_create(scr, TFT_WIDTH - 100, TITLE_YPOS, "Z:0.0mm"); + if (labelP != nullptr) + updatePosTask = lv_task_create(refresh_pos, 300, LV_TASK_PRIO_LOWEST, 0); + + disp_move_dist(); + disp_cur_pos(); +} + +void disp_move_dist() { + if ((int)(10 * uiCfg.move_dist) == 1) + lv_imgbtn_set_src_both(buttonV, "F:/bmp_step_move0_1.bin"); + else if ((int)(10 * uiCfg.move_dist) == 10) + lv_imgbtn_set_src_both(buttonV, "F:/bmp_step_move1.bin"); + else if ((int)(10 * uiCfg.move_dist) == 100) + lv_imgbtn_set_src_both(buttonV, "F:/bmp_step_move10.bin"); + + if (gCfgItems.multiple_language) { + if ((int)(10 * uiCfg.move_dist) == 1) { + lv_label_set_text(labelV, move_menu.step_01mm); + lv_obj_align(labelV, buttonV, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + else if ((int)(10 * uiCfg.move_dist) == 10) { + lv_label_set_text(labelV, move_menu.step_1mm); + lv_obj_align(labelV, buttonV, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + else if ((int)(10 * uiCfg.move_dist) == 100) { + lv_label_set_text(labelV, move_menu.step_10mm); + lv_obj_align(labelV, buttonV, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + } +} + +void lv_clear_move_motor() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_task_del(updatePosTask); + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_move_motor.h b/Marlin/src/lcd/extui/mks_ui/draw_move_motor.h similarity index 87% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_move_motor.h rename to Marlin/src/lcd/extui/mks_ui/draw_move_motor.h index fdbb61f6f95f..133a0444c157 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_move_motor.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_move_motor.h @@ -25,11 +25,10 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_move_motor(void); -extern void lv_clear_move_motor(); -extern void disp_move_dist(); +void lv_draw_move_motor(); +void lv_clear_move_motor(); +void disp_move_dist(); -//extern void disp_temp_ready_print(); #ifdef __cplusplus } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_number_key.cpp b/Marlin/src/lcd/extui/mks_ui/draw_number_key.cpp new file mode 100644 index 000000000000..ae770a8925cb --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_number_key.cpp @@ -0,0 +1,539 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include + +#include "../../../gcode/gcode.h" +#include "../../../gcode/queue.h" +#include "../../../module/planner.h" +#include "../../../inc/MarlinConfig.h" + +#if ENABLED(POWER_LOSS_RECOVERY) + #include "../../../feature/powerloss.h" +#endif + +#if HAS_TRINAMIC_CONFIG + #include "../../../module/stepper/indirection.h" + #include "../../../feature/tmc_util.h" +#endif + +#if HAS_BED_PROBE + #include "../../../module/probe.h" +#endif + +extern lv_group_t *g; +static lv_obj_t *scr; +static lv_obj_t *buttonValue = nullptr; +static lv_obj_t *labelValue = nullptr; + +static char key_value[11] = { 0 }; +static uint8_t cnt = 0; +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_BACK, + ID_NUM_RESET, + ID_NUM_CONFIRM, + ID_NUM_POINT, + ID_NUM_NEGATIVE +}; + +static void disp_key_value() { + char *temp; + TERN_(HAS_TRINAMIC_CONFIG, float milliamps); + + switch (value) { + case PrintAcceleration: + dtostrf(planner.settings.acceleration, 1, 1, public_buf_m); + break; + case RetractAcceleration: + dtostrf(planner.settings.retract_acceleration, 1, 1, public_buf_m); + break; + case TravelAcceleration: + dtostrf(planner.settings.travel_acceleration, 1, 1, public_buf_m); + break; + case XAcceleration: + itoa(planner.settings.max_acceleration_mm_per_s2[X_AXIS], public_buf_m, 10); + break; + case YAcceleration: + itoa(planner.settings.max_acceleration_mm_per_s2[Y_AXIS], public_buf_m, 10); + break; + case ZAcceleration: + itoa(planner.settings.max_acceleration_mm_per_s2[Z_AXIS], public_buf_m, 10); + break; + case E0Acceleration: + itoa(planner.settings.max_acceleration_mm_per_s2[E_AXIS], public_buf_m, 10); + break; + case E1Acceleration: + itoa(planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(1)], public_buf_m, 10); + break; + case XMaxFeedRate: + dtostrf(planner.settings.max_feedrate_mm_s[X_AXIS], 1, 1, public_buf_m); + break; + case YMaxFeedRate: + dtostrf(planner.settings.max_feedrate_mm_s[Y_AXIS], 1, 1, public_buf_m); + break; + case ZMaxFeedRate: + dtostrf(planner.settings.max_feedrate_mm_s[Z_AXIS], 1, 1, public_buf_m); + break; + case E0MaxFeedRate: + dtostrf(planner.settings.max_feedrate_mm_s[E_AXIS], 1, 1, public_buf_m); + break; + case E1MaxFeedRate: + dtostrf(planner.settings.max_feedrate_mm_s[E_AXIS_N(1)], 1, 1, public_buf_m); + break; + + case XJerk: + #if HAS_CLASSIC_JERK + dtostrf(planner.max_jerk[X_AXIS], 1, 1, public_buf_m); + #endif + break; + case YJerk: + #if HAS_CLASSIC_JERK + dtostrf(planner.max_jerk[Y_AXIS], 1, 1, public_buf_m); + #endif + break; + case ZJerk: + #if HAS_CLASSIC_JERK + dtostrf(planner.max_jerk[Z_AXIS], 1, 1, public_buf_m); + #endif + break; + case EJerk: + #if HAS_CLASSIC_JERK + dtostrf(planner.max_jerk[E_AXIS], 1, 1, public_buf_m); + #endif + break; + + case Xstep: + dtostrf(planner.settings.axis_steps_per_mm[X_AXIS], 1, 1, public_buf_m); + break; + case Ystep: + dtostrf(planner.settings.axis_steps_per_mm[Y_AXIS], 1, 1, public_buf_m); + + break; + case Zstep: + dtostrf(planner.settings.axis_steps_per_mm[Z_AXIS], 1, 1, public_buf_m); + + break; + case E0step: + dtostrf(planner.settings.axis_steps_per_mm[E_AXIS], 1, 1, public_buf_m); + + break; + case E1step: + dtostrf(planner.settings.axis_steps_per_mm[E_AXIS_N(1)], 1, 1, public_buf_m); + break; + + case Xcurrent: + #if AXIS_IS_TMC(X) + milliamps = stepperX.getMilliamps(); + dtostrf(milliamps, 1, 1, public_buf_m); + #endif + break; + + case Ycurrent: + #if AXIS_IS_TMC(Y) + milliamps = stepperY.getMilliamps(); + dtostrf(milliamps, 1, 1, public_buf_m); + #endif + break; + + case Zcurrent: + #if AXIS_IS_TMC(Z) + milliamps = stepperZ.getMilliamps(); + dtostrf(milliamps, 1, 1, public_buf_m); + #endif + break; + + case E0current: + #if AXIS_IS_TMC(E0) + milliamps = stepperE0.getMilliamps(); + dtostrf(milliamps, 1, 1, public_buf_m); + #endif + break; + + case E1current: + #if AXIS_IS_TMC(E1) + milliamps = stepperE1.getMilliamps(); + dtostrf(milliamps, 1, 1, public_buf_m); + #endif + break; + + case pause_pos_x: + dtostrf(gCfgItems.pausePosX, 1, 1, public_buf_m); + break; + case pause_pos_y: + dtostrf(gCfgItems.pausePosY, 1, 1, public_buf_m); + break; + case pause_pos_z: + dtostrf(gCfgItems.pausePosZ, 1, 1, public_buf_m); + break; + case level_pos_x1: + itoa(gCfgItems.trammingPos[0].x, public_buf_m, 10); + break; + case level_pos_y1: + itoa(gCfgItems.trammingPos[0].y, public_buf_m, 10); + break; + case level_pos_x2: + itoa(gCfgItems.trammingPos[1].x, public_buf_m, 10); + break; + case level_pos_y2: + itoa(gCfgItems.trammingPos[1].y, public_buf_m, 10); + break; + case level_pos_x3: + itoa(gCfgItems.trammingPos[2].x, public_buf_m, 10); + break; + case level_pos_y3: + itoa(gCfgItems.trammingPos[2].y, public_buf_m, 10); + break; + case level_pos_x4: + itoa(gCfgItems.trammingPos[3].x, public_buf_m, 10); + break; + case level_pos_y4: + itoa(gCfgItems.trammingPos[3].y, public_buf_m, 10); + break; + case level_pos_x5: + itoa(gCfgItems.trammingPos[4].x, public_buf_m, 10); + break; + case level_pos_y5: + itoa(gCfgItems.trammingPos[4].y, public_buf_m, 10); + break; + #if HAS_BED_PROBE + case x_offset: + #if HAS_PROBE_XY_OFFSET + dtostrf(probe.offset.x, 1, 3, public_buf_m); + #endif + break; + case y_offset: + #if HAS_PROBE_XY_OFFSET + dtostrf(probe.offset.y, 1, 3, public_buf_m); + #endif + break; + case z_offset: + dtostrf(probe.offset.z, 1, 3, public_buf_m); + break; + #endif + case load_length: + itoa(gCfgItems.filamentchange_load_length, public_buf_m, 10); + break; + case load_speed: + itoa(gCfgItems.filamentchange_load_speed, public_buf_m, 10); + break; + case unload_length: + itoa(gCfgItems.filamentchange_unload_length, public_buf_m, 10); + break; + case unload_speed: + itoa(gCfgItems.filamentchange_unload_speed, public_buf_m, 10); + break; + case filament_temp: + itoa(gCfgItems.filament_limit_temp, public_buf_m, 10); + break; + case x_sensitivity: + #if X_SENSORLESS + itoa(TERN(X_SENSORLESS, stepperX.homing_threshold(), 0), public_buf_m, 10); + #endif + break; + case y_sensitivity: + #if Y_SENSORLESS + itoa(TERN(Y_SENSORLESS, stepperY.homing_threshold(), 0), public_buf_m, 10); + #endif + break; + case z_sensitivity: + #if Z_SENSORLESS + itoa(TERN(Z_SENSORLESS, stepperZ.homing_threshold(), 0), public_buf_m, 10); + #endif + break; + case z2_sensitivity: + #if Z2_SENSORLESS + itoa(TERN(Z2_SENSORLESS, stepperZ2.homing_threshold(), 0), public_buf_m, 10); + #endif + break; + } + + strcpy(key_value, public_buf_m); + cnt = strlen(key_value); + temp = strchr(key_value, '.'); + point_flag = !temp; + lv_label_set_text(labelValue, key_value); + lv_obj_align(labelValue, buttonValue, LV_ALIGN_CENTER, 0, 0); + +} + +static void set_value_confirm() { + switch (value) { + case PrintAcceleration: planner.settings.acceleration = atof(key_value); break; + case RetractAcceleration: planner.settings.retract_acceleration = atof(key_value); break; + case TravelAcceleration: planner.settings.travel_acceleration = atof(key_value); break; + case XAcceleration: planner.settings.max_acceleration_mm_per_s2[X_AXIS] = atof(key_value); break; + case YAcceleration: planner.settings.max_acceleration_mm_per_s2[Y_AXIS] = atof(key_value); break; + case ZAcceleration: planner.settings.max_acceleration_mm_per_s2[Z_AXIS] = atof(key_value); break; + case E0Acceleration: planner.settings.max_acceleration_mm_per_s2[E_AXIS] = atof(key_value); break; + case E1Acceleration: planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(1)] = atof(key_value); break; + case XMaxFeedRate: planner.settings.max_feedrate_mm_s[X_AXIS] = atof(key_value); break; + case YMaxFeedRate: planner.settings.max_feedrate_mm_s[Y_AXIS] = atof(key_value); break; + case ZMaxFeedRate: planner.settings.max_feedrate_mm_s[Z_AXIS] = atof(key_value); break; + case E0MaxFeedRate: planner.settings.max_feedrate_mm_s[E_AXIS] = atof(key_value); break; + case E1MaxFeedRate: planner.settings.max_feedrate_mm_s[E_AXIS_N(1)] = atof(key_value); break; + case XJerk: TERN_(HAS_CLASSIC_JERK, planner.max_jerk[X_AXIS] = atof(key_value)); break; + case YJerk: TERN_(HAS_CLASSIC_JERK, planner.max_jerk[Y_AXIS] = atof(key_value)); break; + case ZJerk: TERN_(HAS_CLASSIC_JERK, planner.max_jerk[Z_AXIS] = atof(key_value)); break; + case EJerk: TERN_(HAS_CLASSIC_JERK, planner.max_jerk[E_AXIS] = atof(key_value)); break; + case Xstep: planner.settings.axis_steps_per_mm[X_AXIS] = atof(key_value); planner.refresh_positioning(); break; + case Ystep: planner.settings.axis_steps_per_mm[Y_AXIS] = atof(key_value); planner.refresh_positioning(); break; + case Zstep: planner.settings.axis_steps_per_mm[Z_AXIS] = atof(key_value); planner.refresh_positioning(); break; + case E0step: planner.settings.axis_steps_per_mm[E_AXIS] = atof(key_value); planner.refresh_positioning(); break; + case E1step: planner.settings.axis_steps_per_mm[E_AXIS_N(1)] = atof(key_value); planner.refresh_positioning(); break; + case Xcurrent: + #if AXIS_IS_TMC(X) + stepperX.rms_current(atoi(key_value)); + #endif + break; + case Ycurrent: + #if AXIS_IS_TMC(Y) + stepperY.rms_current(atoi(key_value)); + #endif + break; + case Zcurrent: + #if AXIS_IS_TMC(Z) + stepperZ.rms_current(atoi(key_value)); + #endif + break; + case E0current: + #if AXIS_IS_TMC(E0) + stepperE0.rms_current(atoi(key_value)); + #endif + break; + case E1current: + #if AXIS_IS_TMC(E1) + stepperE1.rms_current(atoi(key_value)); + #endif + break; + case pause_pos_x: gCfgItems.pausePosX = atof(key_value); update_spi_flash(); break; + case pause_pos_y: gCfgItems.pausePosY = atof(key_value); update_spi_flash(); break; + case pause_pos_z: gCfgItems.pausePosZ = atof(key_value); update_spi_flash(); break; + case level_pos_x1: gCfgItems.trammingPos[0].x = atoi(key_value); update_spi_flash(); break; + case level_pos_y1: gCfgItems.trammingPos[0].y = atoi(key_value); update_spi_flash(); break; + case level_pos_x2: gCfgItems.trammingPos[1].x = atoi(key_value); update_spi_flash(); break; + case level_pos_y2: gCfgItems.trammingPos[1].y = atoi(key_value); update_spi_flash(); break; + case level_pos_x3: gCfgItems.trammingPos[2].x = atoi(key_value); update_spi_flash(); break; + case level_pos_y3: gCfgItems.trammingPos[2].y = atoi(key_value); update_spi_flash(); break; + case level_pos_x4: gCfgItems.trammingPos[3].x = atoi(key_value); update_spi_flash(); break; + case level_pos_y4: gCfgItems.trammingPos[3].y = atoi(key_value); update_spi_flash(); break; + case level_pos_x5: gCfgItems.trammingPos[4].x = atoi(key_value); update_spi_flash(); break; + case level_pos_y5: gCfgItems.trammingPos[4].y = atoi(key_value); update_spi_flash(); break; + #if HAS_BED_PROBE + case x_offset: { + #if HAS_PROBE_XY_OFFSET + const float x = atof(key_value); + if (WITHIN(x, -(X_BED_SIZE), X_BED_SIZE)) + probe.offset.x = x; + #endif + } break; + case y_offset: { + #if HAS_PROBE_XY_OFFSET + const float y = atof(key_value); + if (WITHIN(y, -(Y_BED_SIZE), Y_BED_SIZE)) + probe.offset.y = y; + #endif + } break; + case z_offset: { + const float z = atof(key_value); + if (WITHIN(z, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX)) + probe.offset.z = z; + } break; + #endif + case load_length: + gCfgItems.filamentchange_load_length = atoi(key_value); + uiCfg.filament_loading_time = (uint32_t)((gCfgItems.filamentchange_load_length*60.0/gCfgItems.filamentchange_load_speed)+0.5); + update_spi_flash(); + break; + case load_speed: + gCfgItems.filamentchange_load_speed = atoi(key_value); + uiCfg.filament_loading_time = (uint32_t)((gCfgItems.filamentchange_load_length*60.0/gCfgItems.filamentchange_load_speed)+0.5); + update_spi_flash(); + break; + case unload_length: + gCfgItems.filamentchange_unload_length = atoi(key_value); + uiCfg.filament_unloading_time = (uint32_t)((gCfgItems.filamentchange_unload_length*60.0/gCfgItems.filamentchange_unload_speed)+0.5); + update_spi_flash(); + break; + case unload_speed: + gCfgItems.filamentchange_unload_speed = atoi(key_value); + uiCfg.filament_unloading_time = (uint32_t)((gCfgItems.filamentchange_unload_length*60.0/gCfgItems.filamentchange_unload_speed)+0.5); + update_spi_flash(); + break; + case filament_temp: + gCfgItems.filament_limit_temp = atoi(key_value); + update_spi_flash(); + break; + case x_sensitivity: TERN_(X_SENSORLESS, stepperX.homing_threshold(atoi(key_value))); break; + case y_sensitivity: TERN_(Y_SENSORLESS, stepperY.homing_threshold(atoi(key_value))); break; + case z_sensitivity: TERN_(Z_SENSORLESS, stepperZ.homing_threshold(atoi(key_value))); break; + case z2_sensitivity: TERN_(Z2_SENSORLESS, stepperZ2.homing_threshold(atoi(key_value))); break; + } + gcode.process_subcommands_now_P(PSTR("M500")); +} + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + switch (obj->mks_obj_id) { + case ID_NUM_KEY1 ... ID_NUM_KEY0: + if (cnt <= 10) { + key_value[cnt] = (obj->mks_obj_id == ID_NUM_KEY0) ? (char)'0' : char('1' + obj->mks_obj_id - ID_NUM_KEY1); + lv_label_set_text(labelValue, key_value); + lv_obj_align(labelValue, buttonValue, LV_ALIGN_CENTER, 0, 0); + cnt++; + } + break; + case ID_NUM_BACK: + if (cnt > 0) cnt--; + if (key_value[cnt] == (char)'.') point_flag = true; + key_value[cnt] = (char)'\0'; + lv_label_set_text(labelValue, key_value); + lv_obj_align(labelValue, buttonValue, LV_ALIGN_CENTER, 0, 0); + break; + case ID_NUM_RESET: + ZERO(key_value); + cnt = 0; + key_value[cnt] = (char)'0'; + point_flag = true; + lv_label_set_text(labelValue, key_value); + lv_obj_align(labelValue, buttonValue, LV_ALIGN_CENTER, 0, 0); + break; + case ID_NUM_POINT: + if (cnt != 0 && point_flag) { + point_flag = false; + key_value[cnt] = (char)'.'; + lv_label_set_text(labelValue, key_value); + lv_obj_align(labelValue, buttonValue, LV_ALIGN_CENTER, 0, 0); + cnt++; + } + break; + case ID_NUM_NEGATIVE: + if (cnt == 0) { + key_value[cnt] = (char)'-'; + lv_label_set_text(labelValue, key_value); + lv_obj_align(labelValue, buttonValue, LV_ALIGN_CENTER, 0, 0); + cnt++; + } + break; + case ID_NUM_CONFIRM: + last_disp_state = NUMBER_KEY_UI; + if (strlen(key_value) != 0) set_value_confirm(); + lv_clear_number_key(); + draw_return_ui(); + break; + } +} + +void lv_draw_number_key() { + scr = lv_screen_create(NUMBER_KEY_UI, ""); + + buttonValue = lv_btn_create(scr, 92, 40, 296, 40, event_handler, ID_NUM_KEY1, &style_num_text); + labelValue = lv_label_create_empty(buttonValue); + + #define DRAW_NUMBER_KEY(N,X,Y) \ + lv_obj_t *NumberKey_##N = lv_btn_create(scr, X, Y, 68, 40, event_handler, ID_NUM_KEY##N, &style_num_key_pre); \ + lv_obj_t *labelKey_##N = lv_label_create_empty(NumberKey_##N); \ + lv_label_set_text(labelKey_##N, machine_menu.key_##N); \ + lv_obj_align(labelKey_##N, NumberKey_##N, LV_ALIGN_CENTER, 0, 0) + + DRAW_NUMBER_KEY(1, 92, 90); + DRAW_NUMBER_KEY(2, 168, 90); + DRAW_NUMBER_KEY(3, 244, 90); + DRAW_NUMBER_KEY(4, 92, 140); + DRAW_NUMBER_KEY(5, 168, 140); + DRAW_NUMBER_KEY(6, 244, 140); + DRAW_NUMBER_KEY(7, 92, 190); + DRAW_NUMBER_KEY(8, 168, 190); + DRAW_NUMBER_KEY(9, 244, 190); + DRAW_NUMBER_KEY(0, 92, 240); + + lv_obj_t *KeyBack = lv_btn_create(scr, 320, 90, 68, 40, event_handler, ID_NUM_BACK, &style_num_key_pre); + lv_obj_t *labelKeyBack = lv_label_create_empty(KeyBack); + lv_label_set_text(labelKeyBack, machine_menu.key_back); + lv_obj_align(labelKeyBack, KeyBack, LV_ALIGN_CENTER, 0, 0); + + lv_obj_t *KeyReset = lv_btn_create(scr, 320, 140, 68, 40, event_handler, ID_NUM_RESET, &style_num_key_pre); + lv_obj_t *labelKeyReset = lv_label_create_empty(KeyReset); + lv_label_set_text(labelKeyReset, machine_menu.key_reset); + lv_obj_align(labelKeyReset, KeyReset, LV_ALIGN_CENTER, 0, 0); + + lv_obj_t *KeyConfirm = lv_btn_create(scr, 320, 190, 68, 90, event_handler, ID_NUM_CONFIRM, &style_num_key_pre); + lv_obj_t *labelKeyConfirm = lv_label_create_empty(KeyConfirm); + lv_label_set_text(labelKeyConfirm, machine_menu.key_confirm); + lv_obj_align(labelKeyConfirm, KeyConfirm, LV_ALIGN_CENTER, 0, 0); + + lv_obj_t *KeyPoint = lv_btn_create(scr, 244, 240, 68, 40, event_handler, ID_NUM_POINT, &style_num_key_pre); + lv_obj_t *labelKeyPoint = lv_label_create_empty(KeyPoint); + lv_label_set_text(labelKeyPoint, machine_menu.key_point); + lv_obj_align(labelKeyPoint, KeyPoint, LV_ALIGN_CENTER, 0, 0); + + lv_obj_t *Minus = lv_btn_create(scr, 168, 240, 68, 40, event_handler, ID_NUM_NEGATIVE, &style_num_key_pre); + lv_obj_t *labelMinus = lv_label_create_empty(Minus); + lv_label_set_text(labelMinus, machine_menu.negative); + lv_obj_align(labelMinus, Minus, LV_ALIGN_CENTER, 0, 0); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, NumberKey_1); + lv_group_add_obj(g, NumberKey_2); + lv_group_add_obj(g, NumberKey_3); + lv_group_add_obj(g, KeyBack); + lv_group_add_obj(g, NumberKey_4); + lv_group_add_obj(g, NumberKey_5); + lv_group_add_obj(g, NumberKey_6); + lv_group_add_obj(g, KeyReset); + lv_group_add_obj(g, NumberKey_7); + lv_group_add_obj(g, NumberKey_8); + lv_group_add_obj(g, NumberKey_9); + lv_group_add_obj(g, NumberKey_0); + lv_group_add_obj(g, Minus); + lv_group_add_obj(g, KeyPoint); + lv_group_add_obj(g, KeyConfirm); + } + #endif + + disp_key_value(); +} + +void lv_clear_number_key() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_number_key.h b/Marlin/src/lcd/extui/mks_ui/draw_number_key.h similarity index 93% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_number_key.h rename to Marlin/src/lcd/extui/mks_ui/draw_number_key.h index 7902da36493a..fcff280d3b52 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_number_key.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_number_key.h @@ -25,8 +25,8 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_number_key(void); -extern void lv_clear_number_key(); +void lv_draw_number_key(); +void lv_clear_number_key(); #ifdef __cplusplus } /* C-declarations for C++ */ diff --git a/Marlin/src/lcd/extui/mks_ui/draw_operation.cpp b/Marlin/src/lcd/extui/mks_ui/draw_operation.cpp new file mode 100644 index 000000000000..9b87df1fdfe4 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_operation.cpp @@ -0,0 +1,229 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include + +#include "../../../module/temperature.h" +#include "../../../module/motion.h" +#include "../../../sd/cardreader.h" +#include "../../../inc/MarlinConfig.h" + +extern lv_group_t *g; +static lv_obj_t *scr; + +enum { + ID_O_PRE_HEAT = 1, + ID_O_EXTRUCT, + ID_O_MOV, + ID_O_FILAMENT, + ID_O_SPEED, + ID_O_RETURN, + ID_O_FAN, + ID_O_POWER_OFF, + ID_O_BABY_STEP +}; + +static lv_obj_t *label_PowerOff; +static lv_obj_t *buttonPowerOff; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + switch (obj->mks_obj_id) { + case ID_O_PRE_HEAT: + lv_clear_operation(); + lv_draw_preHeat(); + break; + case ID_O_EXTRUCT: + lv_clear_operation(); + lv_draw_extrusion(); + break; + case ID_O_MOV: + lv_clear_operation(); + lv_draw_move_motor(); + break; + case ID_O_FILAMENT: + #if HAS_MULTI_EXTRUDER + uiCfg.extruderIndexBak = active_extruder; + #endif + if (uiCfg.print_state == WORKING) { + #if ENABLED(SDSUPPORT) + card.pauseSDPrint(); + stop_print_time(); + uiCfg.print_state = PAUSING; + #endif + } + uiCfg.moveSpeed_bak = (uint16_t)feedrate_mm_s; + uiCfg.hotendTargetTempBak = thermalManager.degTargetHotend(active_extruder); + lv_clear_operation(); + lv_draw_filament_change(); + break; + case ID_O_FAN: + lv_clear_operation(); + lv_draw_fan(); + break; + case ID_O_SPEED: + lv_clear_operation(); + lv_draw_change_speed(); + break; + case ID_O_RETURN: + clear_cur_ui(); + draw_return_ui(); + break; + case ID_O_POWER_OFF: + if (gCfgItems.finish_power_off) { + gCfgItems.finish_power_off = false; + lv_imgbtn_set_src_both(buttonPowerOff, "F:/bmp_manual_off.bin"); + lv_label_set_text(label_PowerOff, printing_more_menu.manual); + } + else { + gCfgItems.finish_power_off = true; + lv_imgbtn_set_src_both(buttonPowerOff, "F:/bmp_auto_off.bin"); + lv_label_set_text(label_PowerOff, printing_more_menu.auto_close); + } + lv_obj_align(label_PowerOff, buttonPowerOff, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + lv_obj_refresh_ext_draw_pad(label_PowerOff); + update_spi_flash(); + break; + case ID_O_BABY_STEP: + lv_clear_operation(); + lv_draw_baby_stepping(); + break; + } +} + +void lv_draw_operation() { + lv_obj_t *buttonExtrusion = nullptr, *buttonSpeed = nullptr, + *buttonBack = nullptr, + *labelPreHeat = nullptr, *labelExtrusion = nullptr, + *label_Back = nullptr, *label_Speed = nullptr, *label_Fan = nullptr, + *buttonMove = nullptr, *label_Move = nullptr, + *buttonBabyStep = nullptr, *label_BabyStep = nullptr, + *label_Filament = nullptr; + + scr = lv_screen_create(OPERATE_UI); + + // Create image buttons + lv_obj_t *buttonPreHeat = lv_imgbtn_create(scr, "F:/bmp_temp.bin", INTERVAL_V, titleHeight, event_handler, ID_O_PRE_HEAT); + lv_obj_t *buttonFilament = lv_imgbtn_create(scr, "F:/bmp_filamentchange.bin", BTN_X_PIXEL + INTERVAL_V * 2, titleHeight, event_handler, ID_O_FILAMENT); + lv_obj_t *buttonFan = lv_imgbtn_create(scr, "F:/bmp_fan.bin", BTN_X_PIXEL * 2 + INTERVAL_V * 3, titleHeight, event_handler, ID_O_FAN); + buttonPowerOff = lv_imgbtn_create(scr, gCfgItems.finish_power_off ? "F:/bmp_auto_off.bin" : "F:/bmp_manual_off.bin", BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight, event_handler, ID_O_POWER_OFF); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonPreHeat); + lv_group_add_obj(g, buttonFilament); + lv_group_add_obj(g, buttonFan); + lv_group_add_obj(g, buttonPowerOff); + } + #endif + + if (uiCfg.print_state != WORKING) { + buttonExtrusion = lv_imgbtn_create(scr, "F:/bmp_extrude_opr.bin", INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_O_EXTRUCT); + buttonMove = lv_imgbtn_create(scr, "F:/bmp_move_opr.bin", BTN_X_PIXEL + INTERVAL_V * 2, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_O_MOV); + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonExtrusion); + lv_group_add_obj(g, buttonMove); + } + #endif + } + else { + buttonSpeed = lv_imgbtn_create(scr, "F:/bmp_speed.bin", INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_O_SPEED); + buttonBabyStep = lv_imgbtn_create(scr, "F:/bmp_mov.bin", BTN_X_PIXEL + INTERVAL_V * 2, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_O_BABY_STEP); + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonSpeed); + lv_group_add_obj(g, buttonBabyStep); + } + #endif + } + + buttonBack = lv_imgbtn_create(scr, "F:/bmp_return.bin", BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_O_RETURN); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonBack); + #endif + + // Create labels on the image buttons + labelPreHeat = lv_label_create_empty(buttonPreHeat); + label_Filament = lv_label_create_empty(buttonFilament); + label_Fan = lv_label_create_empty(buttonFan); + label_PowerOff = lv_label_create_empty(buttonPowerOff); + + if (uiCfg.print_state != WORKING) { + labelExtrusion = lv_label_create_empty(buttonExtrusion); + label_Move = lv_label_create_empty(buttonMove); + } + else { + label_Speed = lv_label_create_empty(buttonSpeed); + label_BabyStep = lv_label_create_empty(buttonBabyStep); + } + label_Back = lv_label_create_empty(buttonBack); + + if (gCfgItems.multiple_language) { + lv_label_set_text(labelPreHeat, operation_menu.temp); + lv_obj_align(labelPreHeat, buttonPreHeat, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + + lv_label_set_text(label_Filament, operation_menu.filament); + lv_obj_align(label_Filament, buttonFilament, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + + lv_label_set_text(label_Fan, operation_menu.fan); + lv_obj_align(label_Fan, buttonFan, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + + if (gCfgItems.finish_power_off) + lv_label_set_text(label_PowerOff, printing_more_menu.auto_close); + else + lv_label_set_text(label_PowerOff, printing_more_menu.manual); + lv_obj_align(label_PowerOff, buttonPowerOff, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + + if (uiCfg.print_state != WORKING) { + lv_label_set_text(labelExtrusion, operation_menu.extr); + lv_obj_align(labelExtrusion, buttonExtrusion, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + + lv_label_set_text(label_Move, operation_menu.move); + lv_obj_align(label_Move, buttonMove, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + else { + lv_label_set_text(label_Speed, operation_menu.speed); + lv_obj_align(label_Speed, buttonSpeed, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + + lv_label_set_text(label_BabyStep, operation_menu.babystep); + lv_obj_align(label_BabyStep, buttonBabyStep, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + + lv_label_set_text(label_Back, common_menu.text_back); + lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } +} + +void lv_clear_operation() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_operation.h b/Marlin/src/lcd/extui/mks_ui/draw_operation.h similarity index 90% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_operation.h rename to Marlin/src/lcd/extui/mks_ui/draw_operation.h index cca1f6a2a5aa..d58b3307b8f6 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_operation.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_operation.h @@ -25,10 +25,9 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_operation(void); -extern void lv_clear_operation(); +void lv_draw_operation(); +void lv_clear_operation(); -//extern void disp_temp_ready_print(); #ifdef __cplusplus } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_pause_message.cpp b/Marlin/src/lcd/extui/mks_ui/draw_pause_message.cpp similarity index 83% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_pause_message.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_pause_message.cpp index f7dd2060b8f6..485e010251dc 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_pause_message.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_pause_message.cpp @@ -19,23 +19,19 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if BOTH(HAS_TFT_LVGL_UI, ADVANCED_PAUSE_FEATURE) #include "draw_ui.h" -#include "lv_conf.h" -//#include "../lvgl/src/lv_objx/lv_imgbtn.h" -//#include "../lvgl/src/lv_objx/lv_img.h" -//#include "../lvgl/src/lv_core/lv_disp.h" -//#include "../lvgl/src/lv_core/lv_refr.h" +#include -#include "../../../../MarlinCore.h" -#include "../../../../feature/pause.h" +#include "../../../feature/pause.h" +#include "../../../inc/MarlinConfig.h" void lv_draw_pause_message(const PauseMessage msg) { switch (msg) { - case PAUSE_MESSAGE_PAUSING: clear_cur_ui(); lv_draw_dialog(DIALOG_PAUSE_MESSAGE_PAUSING); break; + case PAUSE_MESSAGE_PARKING: clear_cur_ui(); lv_draw_dialog(DIALOG_PAUSE_MESSAGE_PARKING); break; case PAUSE_MESSAGE_CHANGING: clear_cur_ui(); lv_draw_dialog(DIALOG_PAUSE_MESSAGE_CHANGING); break; case PAUSE_MESSAGE_UNLOAD: clear_cur_ui(); lv_draw_dialog(DIALOG_PAUSE_MESSAGE_UNLOAD); break; case PAUSE_MESSAGE_WAITING: clear_cur_ui(); lv_draw_dialog(DIALOG_PAUSE_MESSAGE_WAITING); break; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_pause_message.h b/Marlin/src/lcd/extui/mks_ui/draw_pause_message.h similarity index 91% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_pause_message.h rename to Marlin/src/lcd/extui/mks_ui/draw_pause_message.h index 7d55d8375601..c3df8118a42d 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_pause_message.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_pause_message.h @@ -25,9 +25,8 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_pause_message(const PauseMessage msg); +void lv_draw_pause_message(const PauseMessage msg); -//extern void disp_temp_ready_print(); #ifdef __cplusplus } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_pause_position.cpp b/Marlin/src/lcd/extui/mks_ui/draw_pause_position.cpp new file mode 100644 index 000000000000..771a98c11fd1 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_pause_position.cpp @@ -0,0 +1,84 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include + +#include "../../../module/planner.h" +#include "../../../inc/MarlinConfig.h" + +extern lv_group_t *g; +static lv_obj_t *scr; + +enum { + ID_PAUSE_RETURN = 1, + ID_PAUSE_X, + ID_PAUSE_Y, + ID_PAUSE_Z +}; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + lv_clear_pause_position(); + switch (obj->mks_obj_id) { + case ID_PAUSE_RETURN: + draw_return_ui(); + return; + case ID_PAUSE_X: + value = pause_pos_x; + break; + case ID_PAUSE_Y: + value = pause_pos_y; + break; + case ID_PAUSE_Z: + value = pause_pos_z; + break; + } + lv_draw_number_key(); +} + +void lv_draw_pause_position() { + scr = lv_screen_create(PAUSE_POS_UI, machine_menu.PausePosText); + + dtostrf(gCfgItems.pausePosX, 1, 1, public_buf_l); + lv_screen_menu_item_1_edit(scr, machine_menu.xPos, PARA_UI_POS_X, PARA_UI_POS_Y, event_handler, ID_PAUSE_X, 0, public_buf_l); + + dtostrf(gCfgItems.pausePosY, 1, 1, public_buf_l); + lv_screen_menu_item_1_edit(scr, machine_menu.yPos, PARA_UI_POS_X, PARA_UI_POS_Y * 2, event_handler, ID_PAUSE_Y, 1, public_buf_l); + + dtostrf(gCfgItems.pausePosZ, 1, 1, public_buf_l); + lv_screen_menu_item_1_edit(scr, machine_menu.zPos, PARA_UI_POS_X, PARA_UI_POS_Y * 3, event_handler, ID_PAUSE_Z, 2, public_buf_l); + + lv_big_button_create(scr, "F:/bmp_back70x40.bin", common_menu.text_back, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y, event_handler, ID_PAUSE_RETURN, true); +} + +void lv_clear_pause_position() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_pause_position.h b/Marlin/src/lcd/extui/mks_ui/draw_pause_position.h similarity index 92% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_pause_position.h rename to Marlin/src/lcd/extui/mks_ui/draw_pause_position.h index 3e9e0798271b..fd5459c64767 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_pause_position.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_pause_position.h @@ -25,8 +25,8 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_pause_position(void); -extern void lv_clear_pause_position(); +void lv_draw_pause_position(); +void lv_clear_pause_position(); #ifdef __cplusplus } /* C-declarations for C++ */ diff --git a/Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp b/Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp new file mode 100644 index 000000000000..54f09177741a --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp @@ -0,0 +1,267 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include + +#include "../../../module/temperature.h" +#include "../../../inc/MarlinConfig.h" + +static lv_obj_t *scr; +extern lv_group_t* g; +static lv_obj_t *buttonType, *buttonStep; +static lv_obj_t *labelType; +static lv_obj_t *labelStep; +static lv_obj_t *tempText1; + +enum { + ID_P_ADD = 1, + ID_P_DEC, + ID_P_TYPE, + ID_P_STEP, + ID_P_OFF, + ID_P_RETURN +}; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + switch (obj->mks_obj_id) { + case ID_P_ADD: { + if (uiCfg.curTempType == 0) { + int16_t max_target; + thermalManager.temp_hotend[uiCfg.extruderIndex].target += uiCfg.stepHeat; + if (uiCfg.extruderIndex == 0) + max_target = HEATER_0_MAXTEMP - (WATCH_TEMP_INCREASE + TEMP_HYSTERESIS + 1); + #if HAS_MULTI_HOTEND + else + max_target = HEATER_1_MAXTEMP - (WATCH_TEMP_INCREASE + TEMP_HYSTERESIS + 1); + #endif + if (thermalManager.degTargetHotend(uiCfg.extruderIndex) > max_target) + thermalManager.setTargetHotend(max_target, uiCfg.extruderIndex); + thermalManager.start_watching_hotend(uiCfg.extruderIndex); + } + else { + #if HAS_HEATED_BED + constexpr int16_t max_target = BED_MAXTEMP - (WATCH_BED_TEMP_INCREASE + TEMP_BED_HYSTERESIS + 1); + thermalManager.temp_bed.target += uiCfg.stepHeat; + if (thermalManager.degTargetBed() > max_target) + thermalManager.setTargetBed(max_target); + thermalManager.start_watching_bed(); + #endif + } + disp_desire_temp(); + } break; + + case ID_P_DEC: + if (uiCfg.curTempType == 0) { + if (thermalManager.degTargetHotend(uiCfg.extruderIndex) > uiCfg.stepHeat) + thermalManager.temp_hotend[uiCfg.extruderIndex].target -= uiCfg.stepHeat; + else + thermalManager.setTargetHotend(0, uiCfg.extruderIndex); + thermalManager.start_watching_hotend(uiCfg.extruderIndex); + } + #if HAS_HEATED_BED + else { + if (thermalManager.degTargetBed() > uiCfg.stepHeat) + thermalManager.temp_bed.target -= uiCfg.stepHeat; + else + thermalManager.setTargetBed(0); + + thermalManager.start_watching_bed(); + } + #endif + disp_desire_temp(); + break; + case ID_P_TYPE: + if (uiCfg.curTempType == 0) { + if (ENABLED(HAS_MULTI_EXTRUDER)) { + if (uiCfg.extruderIndex == 0) { + uiCfg.extruderIndex = 1; + } + else if (uiCfg.extruderIndex == 1) { + if (TEMP_SENSOR_BED != 0) { + uiCfg.curTempType = 1; + } + else { + uiCfg.curTempType = 0; + uiCfg.extruderIndex = 0; + } + } + } + else if (uiCfg.extruderIndex == 0) { + if (TEMP_SENSOR_BED != 0) + uiCfg.curTempType = 1; + else + uiCfg.curTempType = 0; + } + } + else if (uiCfg.curTempType == 1) { + uiCfg.extruderIndex = 0; + uiCfg.curTempType = 0; + } + disp_temp_type(); + break; + case ID_P_STEP: + switch (uiCfg.stepHeat) { + case 1: uiCfg.stepHeat = 5; break; + case 5: uiCfg.stepHeat = 10; break; + case 10: uiCfg.stepHeat = 1; break; + default: break; + } + disp_step_heat(); + break; + case ID_P_OFF: + if (uiCfg.curTempType == 0) { + thermalManager.setTargetHotend(0, uiCfg.extruderIndex); + thermalManager.start_watching_hotend(uiCfg.extruderIndex); + } + #if HAS_HEATED_BED + else { + thermalManager.temp_bed.target = 0; + thermalManager.start_watching_bed(); + } + #endif + disp_desire_temp(); + break; + case ID_P_RETURN: + clear_cur_ui(); + draw_return_ui(); + break; + } +} + +void lv_draw_preHeat() { + scr = lv_screen_create(PRE_HEAT_UI); + + // Create image buttons + lv_big_button_create(scr, "F:/bmp_Add.bin", preheat_menu.add, INTERVAL_V, titleHeight, event_handler, ID_P_ADD); + lv_big_button_create(scr, "F:/bmp_Dec.bin", preheat_menu.dec, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight, event_handler, ID_P_DEC); + + buttonType = lv_imgbtn_create(scr, nullptr, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_P_TYPE); + buttonStep = lv_imgbtn_create(scr, nullptr, BTN_X_PIXEL + INTERVAL_V * 2, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_P_STEP); + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonType); + lv_group_add_obj(g, buttonStep); + } + #endif + + lv_big_button_create(scr, "F:/bmp_speed0.bin", preheat_menu.off, BTN_X_PIXEL * 2 + INTERVAL_V * 3, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_P_OFF); + lv_big_button_create(scr, "F:/bmp_return.bin", common_menu.text_back, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_P_RETURN); + + // Create labels on the image buttons + labelType = lv_label_create_empty(buttonType); + labelStep = lv_label_create_empty(buttonStep); + + disp_temp_type(); + disp_step_heat(); + + tempText1 = lv_label_create_empty(scr); + lv_obj_set_style(tempText1, &tft_style_label_rel); + disp_desire_temp(); +} + +void disp_temp_type() { + if (uiCfg.curTempType == 0) { + if (uiCfg.extruderIndex == 1) { + lv_imgbtn_set_src_both(buttonType, "F:/bmp_extru2.bin"); + if (gCfgItems.multiple_language) { + lv_label_set_text(labelType, preheat_menu.ext2); + lv_obj_align(labelType, buttonType, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + } + else { + lv_imgbtn_set_src_both(buttonType, "F:/bmp_extru1.bin"); + if (gCfgItems.multiple_language) { + lv_label_set_text(labelType, preheat_menu.ext1); + lv_obj_align(labelType, buttonType, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + } + + } + else { + lv_imgbtn_set_src_both(buttonType, "F:/bmp_bed.bin"); + if (gCfgItems.multiple_language) { + lv_label_set_text(labelType, preheat_menu.hotbed); + lv_obj_align(labelType, buttonType, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + } +} + +void disp_desire_temp() { + char buf[20] = { 0 }; + public_buf_l[0] = '\0'; + + if (uiCfg.curTempType == 0) { + strcat(public_buf_l, uiCfg.extruderIndex < 1 ? preheat_menu.ext1 : preheat_menu.ext2); + sprintf(buf, preheat_menu.value_state, thermalManager.wholeDegHotend(uiCfg.extruderIndex), thermalManager.degTargetHotend(uiCfg.extruderIndex)); + } + else { + #if HAS_HEATED_BED + strcat(public_buf_l, preheat_menu.hotbed); + sprintf(buf, preheat_menu.value_state, thermalManager.wholeDegBed(), thermalManager.degTargetBed()); + #endif + } + strcat_P(public_buf_l, PSTR(": ")); + strcat(public_buf_l, buf); + lv_label_set_text(tempText1, public_buf_l); + lv_obj_align(tempText1, nullptr, LV_ALIGN_CENTER, 0, -50); +} + +void disp_step_heat() { + if (uiCfg.stepHeat == 1) { + lv_imgbtn_set_src_both(buttonStep, "F:/bmp_step1_degree.bin"); + } + else if (uiCfg.stepHeat == 5) { + lv_imgbtn_set_src_both(buttonStep, "F:/bmp_step5_degree.bin"); + } + else if (uiCfg.stepHeat == 10) { + lv_imgbtn_set_src_both(buttonStep, "F:/bmp_step10_degree.bin"); + } + + if (gCfgItems.multiple_language) { + if (uiCfg.stepHeat == 1) { + lv_label_set_text(labelStep, preheat_menu.step_1c); + lv_obj_align(labelStep, buttonStep, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + else if (uiCfg.stepHeat == 5) { + lv_label_set_text(labelStep, preheat_menu.step_5c); + lv_obj_align(labelStep, buttonStep, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + else if (uiCfg.stepHeat == 10) { + lv_label_set_text(labelStep, preheat_menu.step_10c); + lv_obj_align(labelStep, buttonStep, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + } +} + +void lv_clear_preHeat() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_preHeat.h b/Marlin/src/lcd/extui/mks_ui/draw_preHeat.h similarity index 83% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_preHeat.h rename to Marlin/src/lcd/extui/mks_ui/draw_preHeat.h index c8de942f3f60..2993a95f0092 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_preHeat.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_preHeat.h @@ -25,13 +25,12 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_preHeat(void); -extern void lv_clear_preHeat(); -extern void disp_temp_type(); -extern void disp_step_heat(); -extern void disp_desire_temp(); +void lv_draw_preHeat(); +void lv_clear_preHeat(); +void disp_temp_type(); +void disp_step_heat(); +void disp_desire_temp(); -//extern void disp_temp_ready_print(); #ifdef __cplusplus } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_print_file.cpp b/Marlin/src/lcd/extui/mks_ui/draw_print_file.cpp new file mode 100644 index 000000000000..5e1dfae5d1d1 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_print_file.cpp @@ -0,0 +1,554 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include +//#include "../lvgl/src/lv_objx/lv_imgbtn.h" +//#include "../lvgl/src/lv_objx/lv_img.h" +//#include "../lvgl/src/lv_core/lv_disp.h" +//#include "../lvgl/src/lv_core/lv_refr.h" + +#include "../../../sd/cardreader.h" +#include "../../../inc/MarlinConfig.h" + +static lv_obj_t *scr; +extern lv_group_t* g; + +static lv_obj_t *buttonPageUp, *buttonPageDown, *buttonBack, + *buttonGcode[FILE_BTN_CNT], *labelPageUp[FILE_BTN_CNT], *buttonText[FILE_BTN_CNT]; + +enum { + ID_P_UP = 7, + ID_P_DOWN, + ID_P_RETURN +}; + +int8_t curDirLever = 0; +LIST_FILE list_file; +DIR_OFFSET dir_offset[10]; + +extern uint8_t public_buf[513]; +extern char public_buf_m[100]; + +uint8_t sel_id = 0; + +#if ENABLED(SDSUPPORT) + + static uint8_t search_file() { + int valid_name_cnt = 0; + //char tmp[SHORT_NEME_LEN*MAX_DIR_LEVEL+1]; + + list_file.Sd_file_cnt = 0; + //list_file.Sd_file_offset = dir_offset[curDirLever].cur_page_first_offset; + + //root2.rewind(); + //SERIAL_ECHOLN(list_file.curDirPath); + + if (curDirLever != 0) + card.cd(list_file.curDirPath); + else + card.cdroot(); + + const uint16_t fileCnt = card.get_num_Files(); + + for (uint16_t i = 0; i < fileCnt; i++) { + if (list_file.Sd_file_cnt == list_file.Sd_file_offset) { + card.getfilename_sorted(SD_ORDER(i, fileCnt)); + + list_file.IsFolder[valid_name_cnt] = card.flag.filenameIsDir; + strcpy(list_file.file_name[valid_name_cnt], list_file.curDirPath); + strcat_P(list_file.file_name[valid_name_cnt], PSTR("/")); + strcat(list_file.file_name[valid_name_cnt], card.filename); + strcpy(list_file.long_name[valid_name_cnt], card.longest_filename()); + + valid_name_cnt++; + if (valid_name_cnt == 1) + dir_offset[curDirLever].cur_page_first_offset = list_file.Sd_file_offset; + if (valid_name_cnt >= FILE_NUM) { + dir_offset[curDirLever].cur_page_last_offset = list_file.Sd_file_offset; + list_file.Sd_file_offset++; + break; + } + list_file.Sd_file_offset++; + } + list_file.Sd_file_cnt++; + } + //card.closefile(false); + return valid_name_cnt; + } + +#endif // SDSUPPORT + +bool have_pre_pic(char *path) { + #if ENABLED(SDSUPPORT) + char *ps1, *ps2, *cur_name = strrchr(path, '/'); + card.openFileRead(cur_name); + card.read(public_buf, 512); + ps1 = strstr((char *)public_buf, ";simage:"); + card.read(public_buf, 512); + ps2 = strstr((char *)public_buf, ";simage:"); + card.closefile(); + if (ps1 || ps2) return true; + #endif + + return false; +} + +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 + list_file.Sd_file_cnt = 0; + + 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 + if (file_count != 0) { + dir_offset[curDirLever].curPage--; + lv_clear_print_file(); + disp_gcode_icon(file_count); + } + } + } + else if (obj->mks_obj_id == ID_P_DOWN) { + 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 + if (file_count != 0) { + dir_offset[curDirLever].curPage++; + lv_clear_print_file(); + disp_gcode_icon(file_count); + } + if (file_count < FILE_NUM) + dir_offset[curDirLever].cur_page_last_offset = 0; + } + } + else if (obj->mks_obj_id == ID_P_RETURN) { + if (curDirLever > 0) { + int8_t *ch = (int8_t *)strrchr(list_file.curDirPath, '/'); + if (ch) { + *ch = 0; + #if ENABLED(SDSUPPORT) + card.cdup(); + #endif + 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 + lv_clear_print_file(); + disp_gcode_icon(file_count); + } + } + else { + lv_clear_print_file(); + TERN(MULTI_VOLUME, lv_draw_media_select(), lv_draw_ready_print()); + } + } + else { + for (i = 0; i < FILE_BTN_CNT; i++) { + if (obj->mks_obj_id == (i + 1)) { + if (list_file.file_name[i][0] != 0) { + if (list_file.IsFolder[i]) { + 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 + lv_clear_print_file(); + disp_gcode_icon(file_count); + } + else { + sel_id = i; + lv_clear_print_file(); + lv_draw_dialog(DIALOG_TYPE_PRINT_FILE); + } + break; + } + } + } + } +} + +void lv_draw_print_file() { + //uint8_t i; + uint8_t file_count; + + curDirLever = 0; + dir_offset[curDirLever].curPage = 0; + + list_file.Sd_file_offset = 0; + list_file.Sd_file_cnt = 0; + + ZERO(dir_offset); + ZERO(list_file.IsFolder); + ZERO(list_file.curDirPath); + + list_file.Sd_file_offset = dir_offset[curDirLever].cur_page_first_offset; + #if ENABLED(SDSUPPORT) + card.mount(); + file_count = search_file(); + #endif + disp_gcode_icon(file_count); + + //lv_obj_t *labelPageUp = lv_label_create_empty(buttonPageUp); + //lv_obj_t *labelPageDown = lv_label_create_empty(buttonPageDown); + //lv_obj_t *label_Back = lv_label_create_empty(buttonBack); + + /* + if (gCfgItems.multiple_language) { + lv_label_set_text(labelPageUp, tool_menu.preheat); + lv_obj_align(labelPageUp, buttonPageUp, LV_ALIGN_IN_BOTTOM_MID,0, BUTTON_TEXT_Y_OFFSET); + + lv_label_set_text(labelPageDown, tool_menu.extrude); + lv_obj_align(labelPageDown, buttonPageDown, LV_ALIGN_IN_BOTTOM_MID,0, BUTTON_TEXT_Y_OFFSET); + + lv_label_set_text(label_Back, common_menu.text_back); + lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID,0, BUTTON_TEXT_Y_OFFSET); + } + */ +} +static char test_public_buf_l[40]; +void disp_gcode_icon(uint8_t file_num) { + uint8_t i; + + // TODO: set current media title?! + scr = lv_screen_create(PRINT_FILE_UI, ""); + + // Create image buttons + buttonPageUp = lv_imgbtn_create(scr, "F:/bmp_pageUp.bin", OTHER_BTN_XPIEL * 3 + INTERVAL_V * 4, titleHeight, event_handler, ID_P_UP); + buttonPageDown = lv_imgbtn_create(scr, "F:/bmp_pageDown.bin", OTHER_BTN_XPIEL * 3 + INTERVAL_V * 4, titleHeight + OTHER_BTN_YPIEL + INTERVAL_H, event_handler, ID_P_DOWN); + buttonBack = lv_imgbtn_create(scr, "F:/bmp_back.bin", OTHER_BTN_XPIEL * 3 + INTERVAL_V * 4, titleHeight + OTHER_BTN_YPIEL * 2 + INTERVAL_H * 2, event_handler, ID_P_RETURN); + + // Create labels on the image buttons + for (i = 0; i < FILE_BTN_CNT; i++) { + /* + if (seq) { + j = (FILE_BTN_CNT-1) - i; + back_flg = 1; + } + else { + j = i; + back_flg = 0; + } + */ + if (i >= file_num) break; + + #ifdef TFT35 + buttonGcode[i] = lv_imgbtn_create(scr, nullptr); + + lv_imgbtn_use_label_style(buttonGcode[i]); + lv_obj_clear_protect(buttonGcode[i], LV_PROTECT_FOLLOW); + lv_btn_set_layout(buttonGcode[i], LV_LAYOUT_OFF); + + ZERO(public_buf_m); + cutFileName((char *)list_file.long_name[i], 16, 8, (char *)public_buf_m); + + if (list_file.IsFolder[i]) { + lv_obj_set_event_cb_mks(buttonGcode[i], event_handler, (i + 1), "", 0); + lv_imgbtn_set_src_both(buttonGcode[i], "F:/bmp_dir.bin"); + if (i < 3) + lv_obj_set_pos(buttonGcode[i], BTN_X_PIXEL * i + INTERVAL_V * (i + 1), titleHeight); + else + lv_obj_set_pos(buttonGcode[i], BTN_X_PIXEL * (i - 3) + INTERVAL_V * ((i - 3) + 1), BTN_Y_PIXEL + INTERVAL_H + titleHeight); + + labelPageUp[i] = lv_label_create(buttonGcode[i], public_buf_m); + lv_obj_align(labelPageUp[i], buttonGcode[i], LV_ALIGN_IN_BOTTOM_MID, 0, -5); + } + else { + if (have_pre_pic((char *)list_file.file_name[i])) { + + //lv_obj_set_event_cb_mks(buttonGcode[i], event_handler, (i + 1), list_file.file_name[i], 1); + + strcpy(test_public_buf_l, "S:"); + strcat(test_public_buf_l, list_file.file_name[i]); + char *temp = strstr(test_public_buf_l, ".GCO"); + if (temp) strcpy(temp, ".bin"); + lv_obj_set_event_cb_mks(buttonGcode[i], event_handler, (i + 1), test_public_buf_l, 0); + lv_imgbtn_set_src_both(buttonGcode[i], buttonGcode[i]->mks_pic_name); + if (i < 3) { + lv_obj_set_pos(buttonGcode[i], BTN_X_PIXEL * i + INTERVAL_V * (i + 1) + FILE_PRE_PIC_X_OFFSET, titleHeight + FILE_PRE_PIC_Y_OFFSET); + buttonText[i] = lv_btn_create(scr, nullptr); + //lv_obj_set_event_cb(buttonText[i], event_handler); + + lv_btn_use_label_style(buttonText[i]); + lv_obj_clear_protect(buttonText[i], LV_PROTECT_FOLLOW); + lv_btn_set_layout(buttonText[i], LV_LAYOUT_OFF); + //lv_obj_set_event_cb_mks(buttonText[i], event_handler,(i+10),"", 0); + lv_obj_set_pos(buttonText[i], BTN_X_PIXEL * i + INTERVAL_V * (i + 1) + FILE_PRE_PIC_X_OFFSET, titleHeight + FILE_PRE_PIC_Y_OFFSET + 100); + lv_obj_set_size(buttonText[i], 100, 40); + } + else { + lv_obj_set_pos(buttonGcode[i], BTN_X_PIXEL * (i - 3) + INTERVAL_V * ((i - 3) + 1) + FILE_PRE_PIC_X_OFFSET, BTN_Y_PIXEL + INTERVAL_H + titleHeight + FILE_PRE_PIC_Y_OFFSET); + buttonText[i] = lv_btn_create(scr, nullptr); + //lv_obj_set_event_cb(buttonText[i], event_handler); + + lv_btn_use_label_style(buttonText[i]); + lv_obj_clear_protect(buttonText[i], LV_PROTECT_FOLLOW); + lv_btn_set_layout(buttonText[i], LV_LAYOUT_OFF); + //lv_obj_set_event_cb_mks(buttonText[i], event_handler,(i+10),"", 0); + lv_obj_set_pos(buttonText[i], BTN_X_PIXEL * (i - 3) + INTERVAL_V * ((i - 3) + 1) + FILE_PRE_PIC_X_OFFSET, BTN_Y_PIXEL + INTERVAL_H + titleHeight + FILE_PRE_PIC_Y_OFFSET + 100); + lv_obj_set_size(buttonText[i], 100, 40); + } + labelPageUp[i] = lv_label_create(buttonText[i], public_buf_m); + lv_obj_align(labelPageUp[i], buttonText[i], LV_ALIGN_IN_BOTTOM_MID, 0, 0); + } + else { + lv_obj_set_event_cb_mks(buttonGcode[i], event_handler, (i + 1), "", 0); + lv_imgbtn_set_src_both(buttonGcode[i], "F:/bmp_file.bin"); + if (i < 3) + lv_obj_set_pos(buttonGcode[i], BTN_X_PIXEL * i + INTERVAL_V * (i + 1), titleHeight); + else + lv_obj_set_pos(buttonGcode[i], BTN_X_PIXEL * (i - 3) + INTERVAL_V * ((i - 3) + 1), BTN_Y_PIXEL + INTERVAL_H + titleHeight); + + labelPageUp[i] = lv_label_create(buttonGcode[i], public_buf_m); + lv_obj_align(labelPageUp[i], buttonGcode[i], LV_ALIGN_IN_BOTTOM_MID, 0, -5); + } + } + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonGcode[i]); + #endif + + #else // !TFT35 + #endif // !TFT35 + } + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonPageUp); + lv_group_add_obj(g, buttonPageDown); + lv_group_add_obj(g, buttonBack); + } + #endif +} + +uint32_t lv_open_gcode_file(char *path) { + #if ENABLED(SDSUPPORT) + uint32_t *ps4; + uintptr_t pre_sread_cnt = UINTPTR_MAX; + char *cur_name; + + cur_name = strrchr(path, '/'); + + card.openFileRead(cur_name); + card.read(public_buf, 512); + ps4 = (uint32_t *)strstr((char *)public_buf, ";simage:"); + // Ignore the beginning message of gcode file + if (ps4) { + pre_sread_cnt = (uintptr_t)ps4 - (uintptr_t)((uint32_t *)(&public_buf[0])); + card.setIndex(pre_sread_cnt); + } + return pre_sread_cnt; + #endif // SDSUPPORT +} + +int ascii2dec_test(char *ascii) { + int result = 0; + if (ascii == 0) return 0; + + if (*(ascii) >= '0' && *(ascii) <= '9') + result = *(ascii) - '0'; + else if (*(ascii) >= 'a' && *(ascii) <= 'f') + result = *(ascii) - 'a' + 0x0A; + else if (*(ascii) >= 'A' && *(ascii) <= 'F') + result = *(ascii) - 'A' + 0x0A; + else + return 0; + + return result; +} + +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; + bool ignore_start = true; + char temp_test[200]; + volatile uint16_t *p_index; + + watchdog_refresh(); + memset(public_buf, 0, 200); + + while (card.isFileOpen()) { + if (ignore_start) card.read(temp_test, 8); // line start -> ignore + card.read(temp_test, 200); // data + // \r;;gimage: we got the bit img, so stop here + if (temp_test[1] == ';') { + card.closefile(); + break; + } + for (i = 0; i < 200;) { + public_buf[row_1 * 200 + 100 * k + j] = (char)(ascii2dec_test(&temp_test[i]) << 4 | ascii2dec_test(&temp_test[i + 1])); + j++; + i += 2; + } + + uint16_t c = card.get(); + // check for more data or end of line (CR or LF) + if (ISEOL(c)) { + c = card.get(); // more eol? + if (!ISEOL(c)) card.setIndex(card.getIndex() - 1); + break; + } + card.setIndex(card.getIndex() - 1); + k++; + j = 0; + ignore_start = false; + if (k > 1) { + card.closefile(); + 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 + memcpy(data_buf, public_buf, 200); + #endif // SDSUPPORT +} + +void lv_close_gcode_file() {TERN_(SDSUPPORT, card.closefile());} + +void lv_gcode_file_seek(uint32_t pos) { + card.setIndex(pos); +} + +void cutFileName(char *path, int len, int bytePerLine, char *outStr) { + #if _LFN_UNICODE + TCHAR *tmpFile; + TCHAR *strIndex1 = 0, *strIndex2 = 0, *beginIndex; + TCHAR secSeg[10] = {0}; + TCHAR gFileTail[4] = {'~', '.', 'g', '\0'}; + #else + char *tmpFile; + char *strIndex1 = 0, *strIndex2 = 0, *beginIndex; + char secSeg[10] = {0}; + #endif + + if (path == 0 || len <= 3 || outStr == 0) return; + + tmpFile = path; + #if _LFN_UNICODE + strIndex1 = (WCHAR *)wcsstr((const WCHAR *)tmpFile, (const WCHAR *)'/'); + strIndex2 = (WCHAR *)wcsstr((const WCHAR *)tmpFile, (const WCHAR *)'.'); + #else + strIndex1 = (char *)strrchr(tmpFile, '/'); + strIndex2 = (char *)strrchr(tmpFile, '.'); + #endif + + beginIndex = (strIndex1 != 0 + //&& (strIndex2 != 0) && (strIndex1 < strIndex2) + ) ? strIndex1 + 1 : tmpFile; + + if (strIndex2 == 0 || (strIndex1 > strIndex2)) { // not gcode file + #if _LFN_UNICODE + if (wcslen(beginIndex) > len) + wcsncpy(outStr, beginIndex, len); + else + wcscpy(outStr, beginIndex); + #else + if ((int)strlen(beginIndex) > len) + strncpy(outStr, beginIndex, len); + else + strcpy(outStr, beginIndex); + #endif + } + else { // gcode file + if (strIndex2 - beginIndex > (len - 2)) { + #if _LFN_UNICODE + 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 { + #if _LFN_UNICODE + wcsncpy(outStr, (const WCHAR *)beginIndex, strIndex2 - beginIndex + 1); + wcscat(outStr, (const WCHAR *)&gFileTail[3]); + #else + strncpy(outStr, beginIndex, strIndex2 - beginIndex + 1); + strcat_P(outStr, PSTR("g")); + #endif + } + } + + #if _LFN_UNICODE + if (wcslen(outStr) > bytePerLine) { + wcscpy(secSeg, (const WCHAR *)&outStr[bytePerLine]); + outStr[bytePerLine] = '\n'; + outStr[bytePerLine + 1] = '\0'; + wcscat(outStr, (const WCHAR *)secSeg); + } + #else + if ((int)strlen(outStr) > bytePerLine) { + strcpy(secSeg, &outStr[bytePerLine]); + outStr[bytePerLine] = '\n'; + outStr[bytePerLine + 1] = '\0'; + strcat(outStr, secSeg); + } + else { + strcat_P(outStr, PSTR("\n")); + } + #endif +} + +void lv_clear_print_file() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_print_file.h b/Marlin/src/lcd/extui/mks_ui/draw_print_file.h new file mode 100644 index 000000000000..85eadc0a6bcc --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_print_file.h @@ -0,0 +1,64 @@ +/** + * 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 + +#ifdef __cplusplus + extern "C" { /* C-declarations for C++ */ +#endif + +typedef struct { + int cur_page_first_offset; + int cur_page_last_offset; + int curPage; +} DIR_OFFSET; +extern DIR_OFFSET dir_offset[10]; + +#define FILE_NUM 6 +#define SHORT_NAME_LEN 13 +#define NAME_CUT_LEN 23 + +#define MAX_DIR_LEVEL 10 + +typedef struct { + char file_name[FILE_NUM][SHORT_NAME_LEN * MAX_DIR_LEVEL + 1]; + char curDirPath[SHORT_NAME_LEN * MAX_DIR_LEVEL + 1]; + char long_name[FILE_NUM][SHORT_NAME_LEN * 2 + 1]; + bool IsFolder[FILE_NUM]; + char Sd_file_cnt; + char sd_file_index; + char Sd_file_offset; +} LIST_FILE; +extern LIST_FILE list_file; + +void disp_gcode_icon(uint8_t file_num); +void lv_draw_print_file(); +uint32_t lv_open_gcode_file(char *path); +void lv_gcode_file_read(uint8_t *data_buf); +void lv_close_gcode_file(); +void cutFileName(char *path, int len, int bytePerLine, char *outStr); +int ascii2dec_test(char *ascii); +void lv_clear_print_file(); +void lv_gcode_file_seek(uint32_t pos); + +#ifdef __cplusplus + } /* C-declarations for C++ */ +#endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp b/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp new file mode 100644 index 000000000000..e3915adeb088 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp @@ -0,0 +1,326 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include + +#include "../../../MarlinCore.h" // for marlin_state +#include "../../../module/temperature.h" +#include "../../../module/motion.h" +#include "../../../sd/cardreader.h" +#include "../../../gcode/queue.h" +#include "../../../gcode/gcode.h" +#include "../../../inc/MarlinConfig.h" + +#if ENABLED(POWER_LOSS_RECOVERY) + #include "../../../feature/powerloss.h" +#endif + +#if BOTH(LCD_SET_PROGRESS_MANUALLY, USE_M73_REMAINING_TIME) + #include "../../marlinui.h" +#endif + +extern lv_group_t *g; +static lv_obj_t *scr; +static lv_obj_t *labelExt1, *labelFan, *labelZpos, *labelTime; +static lv_obj_t *labelPause, *labelStop, *labelOperat; +static lv_obj_t *bar1, *bar1ValueText; +static lv_obj_t *buttonPause, *buttonOperat, *buttonStop, *buttonExt1, *buttonFanstate, *buttonZpos; + +#if HAS_MULTI_EXTRUDER + static lv_obj_t *labelExt2; + static lv_obj_t *buttonExt2; +#endif + +#if HAS_HEATED_BED + static lv_obj_t* labelBed; + static lv_obj_t* buttonBedstate; +#endif + +enum { + ID_PAUSE = 1, + ID_STOP, + ID_OPTION, + ID_TEMP_EXT, + ID_TEMP_BED, + ID_BABYSTEP, + ID_FAN +}; + +bool once_flag; // = false +extern bool flash_preview_begin, default_preview_flg, gcode_preview_over; +extern uint32_t To_pre_view; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + if (gcode_preview_over) return; + switch (obj->mks_obj_id) { + case ID_PAUSE: + if (uiCfg.print_state == WORKING) { + #if ENABLED(SDSUPPORT) + card.pauseSDPrint(); + stop_print_time(); + uiCfg.print_state = PAUSING; + #endif + lv_imgbtn_set_src_both(buttonPause, "F:/bmp_resume.bin"); + lv_label_set_text(labelPause, printing_menu.resume); + lv_obj_align(labelPause, buttonPause, LV_ALIGN_CENTER, 30, 0); + } + else if (uiCfg.print_state == PAUSED) { + uiCfg.print_state = RESUMING; + lv_imgbtn_set_src_both(obj, "F:/bmp_pause.bin"); + lv_label_set_text(labelPause, printing_menu.pause); + lv_obj_align(labelPause, buttonPause, LV_ALIGN_CENTER, 30, 0); + } + #if ENABLED(POWER_LOSS_RECOVERY) + else if (uiCfg.print_state == REPRINTING) { + uiCfg.print_state = REPRINTED; + lv_imgbtn_set_src_both(obj, "F:/bmp_pause.bin"); + lv_label_set_text(labelPause, printing_menu.pause); + lv_obj_align(labelPause, buttonPause, LV_ALIGN_CENTER, 30, 0); + print_time.minutes = recovery.info.print_job_elapsed / 60; + print_time.seconds = recovery.info.print_job_elapsed % 60; + print_time.hours = print_time.minutes / 60; + } + #endif + break; + case ID_STOP: + lv_clear_printing(); + lv_draw_dialog(DIALOG_TYPE_STOP); + break; + case ID_OPTION: + lv_clear_printing(); + lv_draw_operation(); + break; + case ID_TEMP_EXT: + uiCfg.curTempType = 0; + lv_clear_printing(); + lv_draw_preHeat(); + break; + case ID_TEMP_BED: + uiCfg.curTempType = 1; + lv_clear_printing(); + lv_draw_preHeat(); + break; + case ID_BABYSTEP: + lv_clear_printing(); + lv_draw_baby_stepping(); + break; + case ID_FAN: + lv_clear_printing(); + lv_draw_fan(); + break; + } +} + +void lv_draw_printing() { + disp_state_stack._disp_index = 0; + ZERO(disp_state_stack._disp_state); + scr = lv_screen_create(PRINTING_UI); + + // Create image buttons + buttonExt1 = lv_imgbtn_create(scr, "F:/bmp_ext1_state.bin", 206, 136, event_handler, ID_TEMP_EXT); + + #if HAS_MULTI_EXTRUDER + buttonExt2 = lv_imgbtn_create(scr, "F:/bmp_ext2_state.bin", 350, 136, event_handler, ID_TEMP_EXT); + #endif + + #if HAS_HEATED_BED + buttonBedstate = lv_imgbtn_create(scr, "F:/bmp_bed_state.bin", 206, 186, event_handler, ID_TEMP_BED); + #endif + + buttonFanstate = lv_imgbtn_create(scr, "F:/bmp_fan_state.bin", 350, 186, event_handler, ID_FAN); + + lv_obj_t *buttonTime = lv_img_create(scr, nullptr); + lv_img_set_src(buttonTime, "F:/bmp_time_state.bin"); + lv_obj_set_pos(buttonTime, 206, 86); + + buttonZpos = lv_imgbtn_create(scr, "F:/bmp_zpos_state.bin", 350, 86, event_handler, ID_BABYSTEP); + + buttonPause = lv_imgbtn_create(scr, uiCfg.print_state == WORKING ? "F:/bmp_pause.bin" : "F:/bmp_resume.bin", 5, 240, event_handler, ID_PAUSE); + buttonStop = lv_imgbtn_create(scr, "F:/bmp_stop.bin", 165, 240, event_handler, ID_STOP); + buttonOperat = lv_imgbtn_create(scr, "F:/bmp_operate.bin", 325, 240, event_handler, ID_OPTION); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonPause); + lv_group_add_obj(g, buttonStop); + lv_group_add_obj(g, buttonOperat); + lv_group_add_obj(g, buttonPause); + lv_group_add_obj(g, buttonPause); + lv_group_add_obj(g, buttonPause); + } + #endif + + labelExt1 = lv_label_create(scr, 250, 146, nullptr); + + #if HAS_MULTI_EXTRUDER + labelExt2 = lv_label_create(scr, 395, 146, nullptr); + #endif + + #if HAS_HEATED_BED + labelBed = lv_label_create(scr, 250, 196, nullptr); + #endif + + labelFan = lv_label_create(scr, 395, 196, nullptr); + labelTime = lv_label_create(scr, 250, 96, nullptr); + labelZpos = lv_label_create(scr, 395, 96, nullptr); + + labelPause = lv_label_create_empty(buttonPause); + labelStop = lv_label_create_empty(buttonStop); + labelOperat = lv_label_create_empty(buttonOperat); + + if (gCfgItems.multiple_language) { + lv_label_set_text(labelPause, uiCfg.print_state == WORKING ? printing_menu.pause : printing_menu.resume); + lv_obj_align(labelPause, buttonPause, LV_ALIGN_CENTER, 20, 0); + + lv_label_set_text(labelStop, printing_menu.stop); + lv_obj_align(labelStop, buttonStop, LV_ALIGN_CENTER, 20, 0); + + lv_label_set_text(labelOperat, printing_menu.option); + lv_obj_align(labelOperat, buttonOperat, LV_ALIGN_CENTER, 20, 0); + } + + bar1 = lv_bar_create(scr, nullptr); + lv_obj_set_pos(bar1, 205, 36); + lv_obj_set_size(bar1, 270, 40); + lv_bar_set_style(bar1, LV_BAR_STYLE_INDIC, &lv_bar_style_indic); + lv_bar_set_anim_time(bar1, 1000); + lv_bar_set_value(bar1, 0, LV_ANIM_ON); + bar1ValueText = lv_label_create_empty(bar1); + lv_label_set_text(bar1ValueText,"0%"); + lv_obj_align(bar1ValueText, bar1, LV_ALIGN_CENTER, 0, 0); + + disp_ext_temp(); + disp_bed_temp(); + disp_fan_speed(); + disp_print_time(); + disp_fan_Zpos(); +} + +void disp_ext_temp() { + sprintf(public_buf_l, printing_menu.temp1, thermalManager.wholeDegHotend(0), thermalManager.degTargetHotend(0)); + lv_label_set_text(labelExt1, public_buf_l); + + #if HAS_MULTI_EXTRUDER + sprintf(public_buf_l, printing_menu.temp1, thermalManager.wholeDegHotend(1), thermalManager.degTargetHotend(1)); + lv_label_set_text(labelExt2, public_buf_l); + #endif +} + +void disp_bed_temp() { + #if HAS_HEATED_BED + sprintf(public_buf_l, printing_menu.bed_temp, thermalManager.wholeDegBed(), thermalManager.degTargetBed()); + lv_label_set_text(labelBed, public_buf_l); + #endif +} + +void disp_fan_speed() { + sprintf_P(public_buf_l, PSTR("%d%%"), (int)thermalManager.fanSpeedPercent(0)); + lv_label_set_text(labelFan, public_buf_l); +} + +void disp_print_time() { + #if BOTH(LCD_SET_PROGRESS_MANUALLY, USE_M73_REMAINING_TIME) + const uint32_t r = ui.get_remaining_time(); + sprintf_P(public_buf_l, PSTR("%02d:%02d R"), r / 3600, (r % 3600) / 60); + #else + sprintf_P(public_buf_l, PSTR("%d%d:%d%d:%d%d"), print_time.hours / 10, print_time.hours % 10, print_time.minutes / 10, print_time.minutes % 10, print_time.seconds / 10, print_time.seconds % 10); + #endif + lv_label_set_text(labelTime, public_buf_l); +} + +void disp_fan_Zpos() { + dtostrf(current_position.z, 1, 3, public_buf_l); + lv_label_set_text(labelZpos, public_buf_l); +} + +void reset_print_time() { + print_time.hours = 0; + print_time.minutes = 0; + print_time.seconds = 0; + print_time.ms_10 = 0; +} + +void start_print_time() { print_time.start = 1; } + +void stop_print_time() { print_time.start = 0; } + +void setProBarRate() { + int rate; + volatile long long rate_tmp_r; + + if (!gCfgItems.from_flash_pic) { + #if ENABLED(SDSUPPORT) + rate_tmp_r = (long long)card.getIndex() * 100; + #endif + rate = rate_tmp_r / gCfgItems.curFilesize; + } + else { + #if ENABLED(SDSUPPORT) + 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)); + } + + if (rate <= 0) return; + + if (disp_state == PRINTING_UI) { + lv_bar_set_value(bar1, rate, LV_ANIM_ON); + sprintf_P(public_buf_l, "%d%%", rate); + lv_label_set_text(bar1ValueText,public_buf_l); + lv_obj_align(bar1ValueText, bar1, LV_ALIGN_CENTER, 0, 0); + + if (marlin_state == MF_SD_COMPLETE) { + if (once_flag == 0) { + stop_print_time(); + + flash_preview_begin = false; + default_preview_flg = false; + lv_clear_printing(); + lv_draw_dialog(DIALOG_TYPE_FINISH_PRINT); + + once_flag = true; + + #if HAS_SUICIDE + if (gCfgItems.finish_power_off) { + gcode.process_subcommands_now_P(PSTR("M1001")); + queue.inject_P(PSTR("M81")); + marlin_state = MF_RUNNING; + } + #endif + } + } + } +} + +void lv_clear_printing() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_printing.h b/Marlin/src/lcd/extui/mks_ui/draw_printing.h new file mode 100644 index 000000000000..b2a02a62da54 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_printing.h @@ -0,0 +1,53 @@ +/** + * 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 + +#ifdef __cplusplus + extern "C" { /* C-declarations for C++ */ +#endif + +enum { + IDLE, + WORKING, + PAUSING, + PAUSED, + REPRINTING, + REPRINTED, + RESUMING, + STOP +}; + +void lv_draw_printing(); +void lv_clear_printing(); +void disp_ext_temp(); +void disp_bed_temp(); +void disp_fan_speed(); +void disp_print_time(); +void disp_fan_Zpos(); +void reset_print_time(); +void start_print_time(); +void stop_print_time(); +void setProBarRate(); + +#ifdef __cplusplus + } /* C-declarations for C++ */ +#endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp b/Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp new file mode 100644 index 000000000000..d324d8d7befc --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp @@ -0,0 +1,247 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ready_print.h" +#include "draw_tool.h" +#include +#include "tft_lvgl_configuration.h" +#include "draw_ui.h" + +#include + +#include "../../../module/temperature.h" +#include "../../../inc/MarlinConfig.h" + +#if ENABLED(TOUCH_SCREEN_CALIBRATION) + #include "../../tft_io/touch_calibration.h" + #include "draw_touch_calibration.h" +#endif + +#include "mks_hardware.h" +#include + +#define ICON_POS_Y 38 +#define TARGET_LABEL_MOD_Y -36 +#define LABEL_MOD_Y 30 + +extern lv_group_t* g; +static lv_obj_t *scr; +static lv_obj_t *buttonExt1, *labelExt1, *buttonFanstate, *labelFan; + +#if HAS_MULTI_HOTEND + static lv_obj_t *labelExt2; + static lv_obj_t *buttonExt2; +#endif + +#if HAS_HEATED_BED + static lv_obj_t* labelBed; + static lv_obj_t* buttonBedstate; +#endif + +#if ENABLED(MKS_TEST) + uint8_t current_disp_ui = 0; +#endif + +enum { ID_TOOL = 1, ID_SET, ID_PRINT, ID_INFO_EXT, ID_INFO_BED, ID_INFO_FAN }; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + lv_clear_ready_print(); + switch (obj->mks_obj_id) { + case ID_TOOL: lv_draw_tool(); break; + case ID_SET: lv_draw_set(); break; + case ID_INFO_EXT: uiCfg.curTempType = 0; lv_draw_preHeat(); break; + case ID_INFO_BED: uiCfg.curTempType = 1; lv_draw_preHeat(); break; + case ID_INFO_FAN: lv_draw_fan(); break; + case ID_PRINT: TERN(MULTI_VOLUME, lv_draw_media_select(), lv_draw_print_file()); break; + } +} + +lv_obj_t *limit_info, *det_info; +lv_style_t limit_style, det_style; +void disp_Limit_ok() { + limit_style.text.color.full = 0xFFFF; + lv_obj_set_style(limit_info, &limit_style); + lv_label_set_text(limit_info, "Limit:ok"); +} +void disp_Limit_error() { + limit_style.text.color.full = 0xF800; + lv_obj_set_style(limit_info, &limit_style); + lv_label_set_text(limit_info, "Limit:error"); +} + +void disp_det_ok() { + det_style.text.color.full = 0xFFFF; + lv_obj_set_style(det_info, &det_style); + lv_label_set_text(det_info, "det:ok"); +} +void disp_det_error() { + det_style.text.color.full = 0xF800; + lv_obj_set_style(det_info, &det_style); + lv_label_set_text(det_info, "det:error"); +} + +lv_obj_t *e1, *e2, *e3, *bed; +void mks_disp_test() { + char buf[30] = {0}; + #if HAS_HOTEND + sprintf_P(buf, PSTR("e1:%d"), thermalManager.wholeDegHotend(0)); + lv_label_set_text(e1, buf); + #endif + #if HAS_MULTI_HOTEND + sprintf_P(buf, PSTR("e2:%d"), thermalManager.wholeDegHotend(1)); + lv_label_set_text(e2, buf); + #endif + #if HAS_HEATED_BED + sprintf_P(buf, PSTR("bed:%d"), thermalManager.wholeDegBed()); + lv_label_set_text(bed, buf); + #endif +} + +void lv_draw_ready_print() { + char buf[30] = {0}; + lv_obj_t *buttonTool; + + disp_state_stack._disp_index = 0; + ZERO(disp_state_stack._disp_state); + scr = lv_screen_create(PRINT_READY_UI, ""); + + if (mks_test_flag == 0x1E) { + // Create image buttons + buttonTool = lv_imgbtn_create(scr, "F:/bmp_tool.bin", event_handler, ID_TOOL); + + lv_obj_set_pos(buttonTool, 360, 180); + + lv_obj_t *label_tool = lv_label_create_empty(buttonTool); + if (gCfgItems.multiple_language) { + lv_label_set_text(label_tool, main_menu.tool); + lv_obj_align(label_tool, buttonTool, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + + #if HAS_HOTEND + e1 = lv_label_create_empty(scr); + lv_obj_set_pos(e1, 20, 20); + sprintf_P(buf, PSTR("e1: %d"), thermalManager.wholeDegHotend(0)); + lv_label_set_text(e1, buf); + #endif + #if HAS_MULTI_HOTEND + e2 = lv_label_create_empty(scr); + lv_obj_set_pos(e2, 20, 45); + sprintf_P(buf, PSTR("e2: %d"), thermalManager.wholeDegHotend(1)); + lv_label_set_text(e2, buf); + #endif + #if HAS_HEATED_BED + bed = lv_label_create_empty(scr); + lv_obj_set_pos(bed, 20, 95); + sprintf_P(buf, PSTR("bed: %d"), thermalManager.wholeDegBed()); + lv_label_set_text(bed, buf); + #endif + + limit_info = lv_label_create_empty(scr); + + lv_style_copy(&limit_style, &lv_style_scr); + limit_style.body.main_color.full = 0x0000; + limit_style.body.grad_color.full = 0x0000; + limit_style.text.color.full = 0xFFFF; + lv_obj_set_style(limit_info, &limit_style); + + lv_obj_set_pos(limit_info, 20, 120); + lv_label_set_text(limit_info, " "); + + det_info = lv_label_create_empty(scr); + + lv_style_copy(&det_style, &lv_style_scr); + det_style.body.main_color.full = 0x0000; + det_style.body.grad_color.full = 0x0000; + det_style.text.color.full = 0xFFFF; + lv_obj_set_style(det_info, &det_style); + + lv_obj_set_pos(det_info, 20, 145); + lv_label_set_text(det_info, " "); + } + else { + lv_big_button_create(scr, "F:/bmp_tool.bin", main_menu.tool, 20, 150, event_handler, ID_TOOL); + lv_big_button_create(scr, "F:/bmp_set.bin", main_menu.set, 180, 150, event_handler, ID_SET); + lv_big_button_create(scr, "F:/bmp_printing.bin", main_menu.print, 340, 150, event_handler, ID_PRINT); + + // Monitoring + #if HAS_HOTEND + buttonExt1 = lv_big_button_create(scr, "F:/bmp_ext1_state.bin", " ", 55, ICON_POS_Y, event_handler, ID_INFO_EXT); + #endif + #if HAS_MULTI_HOTEND + buttonExt2 = lv_big_button_create(scr, "F:/bmp_ext2_state.bin", " ", 163, ICON_POS_Y, event_handler, ID_INFO_EXT); + #endif + #if HAS_HEATED_BED + buttonBedstate = lv_big_button_create(scr, "F:/bmp_bed_state.bin", " ", TERN(HAS_MULTI_HOTEND, 271, 210), ICON_POS_Y, event_handler, ID_INFO_BED); + #endif + + TERN_(HAS_HOTEND, labelExt1 = lv_label_create_empty(scr)); + TERN_(HAS_MULTI_HOTEND, labelExt2 = lv_label_create_empty(scr)); + TERN_(HAS_HEATED_BED, labelBed = lv_label_create_empty(scr)); + TERN_(HAS_FAN, labelFan = lv_label_create_empty(scr)); + + lv_temp_refr(); + } + + #if ENABLED(TOUCH_SCREEN_CALIBRATION) + // If calibration is required, let's trigger it now, handles the case when there is default value in configuration files + if (!touch_calibration.calibration_loaded()) { + lv_clear_ready_print(); + lv_draw_touch_calibration_screen(); + } + #endif +} + +void lv_temp_refr() { + #if HAS_HOTEND + sprintf(public_buf_l, printing_menu.temp1, thermalManager.wholeDegHotend(0), thermalManager.degTargetHotend(0)); + lv_label_set_text(labelExt1, public_buf_l); + lv_obj_align(labelExt1, buttonExt1, LV_ALIGN_OUT_BOTTOM_MID, 0, 0); + #endif + #if HAS_MULTI_HOTEND + sprintf(public_buf_l, printing_menu.temp1, thermalManager.wholeDegHotend(1), thermalManager.degTargetHotend(1)); + lv_label_set_text(labelExt2, public_buf_l); + lv_obj_align(labelExt2, buttonExt2, LV_ALIGN_OUT_BOTTOM_MID, 0, 0); + #endif + #if HAS_HEATED_BED + sprintf(public_buf_l, printing_menu.bed_temp, thermalManager.wholeDegBed(), thermalManager.degTargetBed()); + lv_label_set_text(labelBed, public_buf_l); + lv_obj_align(labelBed, buttonBedstate, LV_ALIGN_OUT_BOTTOM_MID, 0, 0); + #endif + #if HAS_FAN + sprintf_P(public_buf_l, PSTR("%d%%"), (int)thermalManager.fanSpeedPercent(0)); + lv_label_set_text(labelFan, public_buf_l); + lv_obj_align(labelFan, buttonFanstate, LV_ALIGN_OUT_BOTTOM_MID, 0, 0); + #endif +} + +void lv_clear_ready_print() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_ready_print.h b/Marlin/src/lcd/extui/mks_ui/draw_ready_print.h similarity index 79% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_ready_print.h rename to Marlin/src/lcd/extui/mks_ui/draw_ready_print.h index 5cefe8b59b36..873be528ed1d 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_ready_print.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_ready_print.h @@ -25,15 +25,15 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_ready_print(void); -extern void mks_disp_test(); -extern void disp_Limit_ok(); -extern void disp_Limit_error(); -extern void disp_det_error(); -extern void disp_det_ok(); -extern void lv_clear_ready_print(); +void lv_draw_ready_print(); +void mks_disp_test(); +void disp_Limit_ok(); +void disp_Limit_error(); +void disp_det_error(); +void disp_det_ok(); +void lv_clear_ready_print(); +void lv_temp_refr(); -//extern void disp_temp_ready_print(); #ifdef __cplusplus } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_set.cpp b/Marlin/src/lcd/extui/mks_ui/draw_set.cpp new file mode 100644 index 000000000000..a765d0e58ab8 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_set.cpp @@ -0,0 +1,135 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ready_print.h" +#include "draw_set.h" +#include "draw_ui.h" +#include + +#include "pic_manager.h" + +#include "../../../gcode/queue.h" +#include "../../../inc/MarlinConfig.h" + +#if HAS_SUICIDE + #include "../../../MarlinCore.h" +#endif + +static lv_obj_t *scr; +extern lv_group_t* g; + +enum { + ID_S_WIFI = 1, + ID_S_FAN, + ID_S_ABOUT, + ID_S_CONTINUE, + ID_S_MOTOR_OFF, + ID_S_LANGUAGE, + ID_S_MACHINE_PARA, + ID_S_EEPROM_SET, + ID_S_RETURN +}; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + if (obj->mks_obj_id == ID_S_CONTINUE) return; + if (obj->mks_obj_id == ID_S_MOTOR_OFF) { + TERN(HAS_SUICIDE, suicide(), queue.enqueue_now_P(PSTR("M84"))); + return; + } + lv_clear_set(); + switch (obj->mks_obj_id) { + case ID_S_FAN: + lv_draw_fan(); + break; + case ID_S_ABOUT: + lv_draw_about(); + break; + case ID_S_LANGUAGE: + lv_draw_language(); + break; + case ID_S_MACHINE_PARA: + lv_draw_machine_para(); + break; + case ID_S_EEPROM_SET: + lv_draw_eeprom_settings(); + break; + case ID_S_RETURN: + lv_draw_ready_print(); + break; + + #if ENABLED(MKS_WIFI_MODULE) + case ID_S_WIFI: + if (gCfgItems.wifi_mode_sel == STA_MODEL) { + if (wifi_link_state == WIFI_CONNECTED) { + last_disp_state = SET_UI; + lv_draw_wifi(); + } + else { + if (uiCfg.command_send) { + uint8_t cmd_wifi_list[] = { 0xA5, 0x07, 0x00, 0x00, 0xFC }; + raw_send_to_wifi(cmd_wifi_list, COUNT(cmd_wifi_list)); + last_disp_state = SET_UI; + lv_draw_wifi_list(); + } + else { + last_disp_state = SET_UI; + lv_draw_dialog(DIALOG_WIFI_ENABLE_TIPS); + } + } + } + else { + last_disp_state = SET_UI; + lv_draw_wifi(); + } + break; + #endif + } +} + +void lv_draw_set() { + scr = lv_screen_create(SET_UI); + lv_big_button_create(scr, "F:/bmp_eeprom_settings.bin", set_menu.eepromSet, INTERVAL_V, titleHeight, event_handler, ID_S_EEPROM_SET); + lv_big_button_create(scr, "F:/bmp_fan.bin", set_menu.fan, BTN_X_PIXEL + INTERVAL_V * 2, titleHeight, event_handler, ID_S_FAN); + lv_big_button_create(scr, "F:/bmp_about.bin", set_menu.about, BTN_X_PIXEL * 2 + INTERVAL_V * 3, titleHeight, event_handler, ID_S_ABOUT); + lv_big_button_create(scr, ENABLED(HAS_SUICIDE) ? "F:/bmp_manual_off.bin" : "F:/bmp_function1.bin", set_menu.TERN(HAS_SUICIDE, shutdown, motoroff), BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight, event_handler, ID_S_MOTOR_OFF); + lv_big_button_create(scr, "F:/bmp_machine_para.bin", set_menu.machine_para, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_S_MACHINE_PARA); + #if HAS_LANG_SELECT_SCREEN + lv_big_button_create(scr, "F:/bmp_language.bin", set_menu.language, BTN_X_PIXEL + INTERVAL_V * 2, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_S_LANGUAGE); + #endif + #if ENABLED(MKS_WIFI_MODULE) + lv_big_button_create(scr, "F:/bmp_wifi.bin", set_menu.wifi, BTN_X_PIXEL * 2 + INTERVAL_V * 3, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_S_WIFI); + #endif + lv_big_button_create(scr, "F:/bmp_return.bin", common_menu.text_back, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_S_RETURN); +} + +void lv_clear_set() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_set.h b/Marlin/src/lcd/extui/mks_ui/draw_set.h similarity index 91% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_set.h rename to Marlin/src/lcd/extui/mks_ui/draw_set.h index b243bca296ad..a270308e074e 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_set.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_set.h @@ -25,10 +25,9 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_set(void); -extern void lv_clear_set(); +void lv_draw_set(); +void lv_clear_set(); -//extern void disp_temp_ready_print(); #ifdef __cplusplus } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_step_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_step_settings.cpp new file mode 100644 index 000000000000..d4ab028eec12 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_step_settings.cpp @@ -0,0 +1,116 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include + +#include "../../../module/planner.h" +#include "../../../inc/MarlinConfig.h" + +extern lv_group_t *g; +static lv_obj_t *scr; + +enum { + ID_STEP_RETURN = 1, + ID_STEP_X, + ID_STEP_Y, + ID_STEP_Z, + ID_STEP_E0, + ID_STEP_E1, + ID_STEP_DOWN, + ID_STEP_UP +}; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + lv_clear_step_settings(); + switch (obj->mks_obj_id) { + case ID_STEP_RETURN: + uiCfg.para_ui_page = false; + draw_return_ui(); + return; + case ID_STEP_X: + value = Xstep; + break; + case ID_STEP_Y: + value = Ystep; + break; + case ID_STEP_Z: + value = Zstep; + break; + case ID_STEP_E0: + value = E0step; + break; + case ID_STEP_E1: + value = E1step; + break; + case ID_STEP_UP: + uiCfg.para_ui_page = false; + lv_draw_step_settings(); + return; + case ID_STEP_DOWN: + uiCfg.para_ui_page = true; + lv_draw_step_settings(); + return; + } + lv_draw_number_key(); +} + +void lv_draw_step_settings() { + scr = lv_screen_create(STEPS_UI, machine_menu.StepsConfTitle); + + if (!uiCfg.para_ui_page) { + dtostrf(planner.settings.axis_steps_per_mm[X_AXIS], 1, 1, public_buf_l); + lv_screen_menu_item_1_edit(scr, machine_menu.X_Steps, PARA_UI_POS_X, PARA_UI_POS_Y, event_handler, ID_STEP_X, 0, public_buf_l); + + dtostrf(planner.settings.axis_steps_per_mm[Y_AXIS], 1, 1, public_buf_l); + lv_screen_menu_item_1_edit(scr, machine_menu.Y_Steps, PARA_UI_POS_X, PARA_UI_POS_Y * 2, event_handler, ID_STEP_Y, 1, public_buf_l); + + dtostrf(planner.settings.axis_steps_per_mm[Z_AXIS], 1, 1, public_buf_l); + lv_screen_menu_item_1_edit(scr, machine_menu.Z_Steps, PARA_UI_POS_X, PARA_UI_POS_Y * 3, event_handler, ID_STEP_Z, 2, public_buf_l); + + dtostrf(planner.settings.axis_steps_per_mm[E_AXIS], 1, 1, public_buf_l); + lv_screen_menu_item_1_edit(scr, machine_menu.E0_Steps, PARA_UI_POS_X, PARA_UI_POS_Y * 4, event_handler, ID_STEP_E0, 3, public_buf_l); + + 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_STEP_DOWN, true); + } + else { + dtostrf(planner.settings.axis_steps_per_mm[E_AXIS_N(1)], 1, 1, public_buf_l); + lv_screen_menu_item_1_edit(scr, machine_menu.E1_Steps, PARA_UI_POS_X, PARA_UI_POS_Y, event_handler, ID_STEP_E1, 0, public_buf_l); + + lv_big_button_create(scr, "F:/bmp_back70x40.bin", machine_menu.previous, PARA_UI_TURN_PAGE_POS_X, PARA_UI_TURN_PAGE_POS_Y, event_handler, ID_STEP_UP, true); + } + + lv_big_button_create(scr, "F:/bmp_back70x40.bin", common_menu.text_back, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y, event_handler, ID_STEP_RETURN, true); +} + +void lv_clear_step_settings() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_step_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_step_settings.h similarity index 92% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_step_settings.h rename to Marlin/src/lcd/extui/mks_ui/draw_step_settings.h index b7eaeb4c61e3..4f32f0a6c2b0 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_step_settings.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_step_settings.h @@ -25,8 +25,8 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_step_settings(void); -extern void lv_clear_step_settings(); +void lv_draw_step_settings(); +void lv_clear_step_settings(); #ifdef __cplusplus } /* C-declarations for C++ */ 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 new file mode 100644 index 000000000000..5117bd4802f7 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_tmc_current_settings.cpp @@ -0,0 +1,155 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if BOTH(HAS_TFT_LVGL_UI, HAS_TRINAMIC_CONFIG) + +#include "draw_ui.h" +#include + +#include "../../../module/stepper/indirection.h" +#include "../../../feature/tmc_util.h" +#include "../../../inc/MarlinConfig.h" + +extern lv_group_t *g; +static lv_obj_t *scr; + +enum { + ID_TMC_CURRENT_RETURN = 1, + ID_TMC_CURRENT_X, + ID_TMC_CURRENT_Y, + ID_TMC_CURRENT_Z, + ID_TMC_CURRENT_E0, + ID_TMC_CURRENT_E1, + ID_TMC_CURRENT_DOWN, + ID_TMC_CURRENT_UP +}; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + lv_clear_tmc_current_settings(); + switch (obj->mks_obj_id) { + case ID_TMC_CURRENT_RETURN: + uiCfg.para_ui_page = false; + draw_return_ui(); + return; + #if AXIS_IS_TMC(X) + case ID_TMC_CURRENT_X: + value = Xcurrent; + break; + #endif + #if AXIS_IS_TMC(Y) + case ID_TMC_CURRENT_Y: + value = Ycurrent; + break; + #endif + #if AXIS_IS_TMC(Z) + case ID_TMC_CURRENT_Z: + value = Zcurrent; + break; + #endif + #if AXIS_IS_TMC(E0) + case ID_TMC_CURRENT_E0: + value = E0current; + break; + #endif + #if AXIS_IS_TMC(E1) + case ID_TMC_CURRENT_E1: + value = E1current; + break; + #endif + + case ID_TMC_CURRENT_UP: + uiCfg.para_ui_page = false; + lv_draw_tmc_current_settings(); + return; + case ID_TMC_CURRENT_DOWN: + uiCfg.para_ui_page = true; + lv_draw_tmc_current_settings(); + return; + } + lv_draw_number_key(); + +} + +void lv_draw_tmc_current_settings() { + scr = lv_screen_create(TMC_CURRENT_UI, machine_menu.TmcCurrentConfTitle); + + float milliamps; + if (!uiCfg.para_ui_page) { + #if AXIS_IS_TMC(X) + milliamps = stepperX.getMilliamps(); + #else + milliamps = -1; + #endif + dtostrf(milliamps, 1, 1, public_buf_l); + lv_screen_menu_item_1_edit(scr, machine_menu.X_Current, PARA_UI_POS_X, PARA_UI_POS_Y, event_handler, ID_TMC_CURRENT_X, 0, public_buf_l); + + #if AXIS_IS_TMC(Y) + milliamps = stepperY.getMilliamps(); + #else + milliamps = -1; + #endif + dtostrf(milliamps, 1, 1, public_buf_l); + lv_screen_menu_item_1_edit(scr, machine_menu.Y_Current, PARA_UI_POS_X, PARA_UI_POS_Y * 2, event_handler, ID_TMC_CURRENT_Y, 1, public_buf_l); + + #if AXIS_IS_TMC(Z) + milliamps = stepperZ.getMilliamps(); + #else + milliamps = -1; + #endif + dtostrf(milliamps, 1, 1, public_buf_l); + lv_screen_menu_item_1_edit(scr, machine_menu.Z_Current, PARA_UI_POS_X, PARA_UI_POS_Y * 3, event_handler, ID_TMC_CURRENT_Z, 2, public_buf_l); + + #if AXIS_IS_TMC(E0) + milliamps = stepperE0.getMilliamps(); + #else + milliamps = -1; + #endif + dtostrf(milliamps, 1, 1, public_buf_l); + lv_screen_menu_item_1_edit(scr, machine_menu.E0_Current, PARA_UI_POS_X, PARA_UI_POS_Y * 4, event_handler, ID_TMC_CURRENT_E0, 3, public_buf_l); + + 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_TMC_CURRENT_DOWN, true); + } + else { + #if AXIS_IS_TMC(E1) + milliamps = stepperE1.getMilliamps(); + #else + milliamps = -1; + #endif + dtostrf(milliamps, 1, 1, public_buf_l); + lv_screen_menu_item_1_edit(scr, machine_menu.E1_Current, PARA_UI_POS_X, PARA_UI_POS_Y, event_handler, ID_TMC_CURRENT_E1, 0, public_buf_l); + + lv_big_button_create(scr, "F:/bmp_back70x40.bin", machine_menu.previous, PARA_UI_TURN_PAGE_POS_X, PARA_UI_TURN_PAGE_POS_Y, event_handler, ID_TMC_CURRENT_UP, true); + } + + lv_big_button_create(scr, "F:/bmp_back70x40.bin", common_menu.text_back, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y, event_handler, ID_TMC_CURRENT_RETURN, true); +} + +void lv_clear_tmc_current_settings() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI && HAS_TRINAMIC_CONFIG diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_current_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_tmc_current_settings.h similarity index 91% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_current_settings.h rename to Marlin/src/lcd/extui/mks_ui/draw_tmc_current_settings.h index 927db37138e6..99589a3a17c7 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_current_settings.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_tmc_current_settings.h @@ -25,10 +25,9 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_tmc_current_settings(void); -extern void lv_clear_tmc_current_settings(); +void lv_draw_tmc_current_settings(); +void lv_clear_tmc_current_settings(); #ifdef __cplusplus } /* C-declarations for C++ */ #endif - 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 new file mode 100644 index 000000000000..bf1b9c3459ab --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.cpp @@ -0,0 +1,134 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if BOTH(HAS_TFT_LVGL_UI, HAS_STEALTHCHOP) + +#include "draw_ui.h" +#include + +#include "../../../module/stepper/indirection.h" +#include "../../../feature/tmc_util.h" +#include "../../../inc/MarlinConfig.h" + +#if ENABLED(EEPROM_SETTINGS) + #include "../../../module/settings.h" +#endif + +extern lv_group_t *g; +static lv_obj_t *scr; + +enum { + ID_TMC_MODE_RETURN = 1, + ID_TMC_MODE_X, + ID_TMC_MODE_Y, + ID_TMC_MODE_Z, + ID_TMC_MODE_E0, + ID_TMC_MODE_E1, + ID_TMC_MODE_DOWN, + ID_TMC_MODE_UP +}; + +static lv_obj_t *buttonXState = nullptr, *buttonYState = nullptr, *buttonZState = nullptr, *buttonE0State = nullptr; + +static lv_obj_t *buttonE1State = nullptr; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + + auto toggle_chop = [&](auto &stepper, auto &button) { + const bool isena = stepper.toggle_stepping_mode(); + lv_screen_menu_item_onoff_update(button, isena); + TERN_(EEPROM_SETTINGS, (void)settings.save()); + }; + + switch (obj->mks_obj_id) { + case ID_TMC_MODE_RETURN: + uiCfg.para_ui_page = false; + lv_clear_tmc_step_mode_settings(); + draw_return_ui(); + break; + + #if X_HAS_STEALTHCHOP + case ID_TMC_MODE_X: toggle_chop(stepperX, buttonXState); break; + #endif + #if Y_HAS_STEALTHCHOP + case ID_TMC_MODE_Y: toggle_chop(stepperY, buttonYState); break; + #endif + #if Z_HAS_STEALTHCHOP + case ID_TMC_MODE_Z: toggle_chop(stepperZ, buttonZState); break; + #endif + #if E0_HAS_STEALTHCHOP + case ID_TMC_MODE_E0: toggle_chop(stepperE0, buttonE0State); break; + #endif + #if E1_HAS_STEALTHCHOP + case ID_TMC_MODE_E1: toggle_chop(stepperE1, buttonE1State); break; + #endif + + case ID_TMC_MODE_UP: + uiCfg.para_ui_page = false; + lv_clear_tmc_step_mode_settings(); + lv_draw_tmc_step_mode_settings(); + break; + case ID_TMC_MODE_DOWN: + uiCfg.para_ui_page = true; + lv_clear_tmc_step_mode_settings(); + lv_draw_tmc_step_mode_settings(); + break; + } +} + +void lv_draw_tmc_step_mode_settings() { + buttonXState = buttonYState = buttonZState = buttonE0State = buttonE1State = nullptr; + + scr = lv_screen_create(TMC_MODE_UI, machine_menu.TmcStepModeConfTitle); + + bool stealth_X = false, stealth_Y = false, stealth_Z = false, stealth_E0 = false, stealth_E1 = false; + TERN_(X_HAS_STEALTHCHOP, stealth_X = stepperX.get_stealthChop()); + TERN_(Y_HAS_STEALTHCHOP, stealth_Y = stepperY.get_stealthChop()); + TERN_(Z_HAS_STEALTHCHOP, stealth_Z = stepperZ.get_stealthChop()); + TERN_(E0_HAS_STEALTHCHOP, stealth_E0 = stepperE0.get_stealthChop()); + TERN_(E1_HAS_STEALTHCHOP, stealth_E1 = stepperE1.get_stealthChop()); + + if (!uiCfg.para_ui_page) { + buttonXState = lv_screen_menu_item_onoff(scr, machine_menu.X_StepMode, PARA_UI_POS_X, PARA_UI_POS_Y, event_handler, ID_TMC_MODE_X, 0, stealth_X); + buttonYState = lv_screen_menu_item_onoff(scr, machine_menu.Y_StepMode, PARA_UI_POS_X, PARA_UI_POS_Y * 2, event_handler, ID_TMC_MODE_Y, 1, stealth_Y); + buttonZState = lv_screen_menu_item_onoff(scr, machine_menu.Z_StepMode, PARA_UI_POS_X, PARA_UI_POS_Y * 3, event_handler, ID_TMC_MODE_Z, 2, stealth_Z); + buttonE0State = lv_screen_menu_item_onoff(scr, machine_menu.E0_StepMode, PARA_UI_POS_X, PARA_UI_POS_Y * 4, event_handler, ID_TMC_MODE_E0, 2, stealth_E0); + 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_TMC_MODE_DOWN, true); + } + else { + buttonE1State = lv_screen_menu_item_onoff(scr, machine_menu.E1_StepMode, PARA_UI_POS_X, PARA_UI_POS_Y, event_handler, ID_TMC_MODE_E1, 0, stealth_E1); + lv_big_button_create(scr, "F:/bmp_back70x40.bin", machine_menu.previous, PARA_UI_TURN_PAGE_POS_X, PARA_UI_TURN_PAGE_POS_Y, event_handler, ID_TMC_MODE_UP, true); + } + + lv_big_button_create(scr, "F:/bmp_back70x40.bin", common_menu.text_back, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y, event_handler, ID_TMC_MODE_RETURN, true); +} + +void lv_clear_tmc_step_mode_settings() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI && HAS_STEALTHCHOP diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_step_mode_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.h similarity index 91% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_step_mode_settings.h rename to Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.h index 35c57ab0cc01..aa42d9b87dba 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_step_mode_settings.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.h @@ -25,8 +25,8 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_tmc_step_mode_settings(void); -extern void lv_clear_tmc_step_mode_settings(); +void lv_draw_tmc_step_mode_settings(); +void lv_clear_tmc_step_mode_settings(); #ifdef __cplusplus } /* C-declarations for C++ */ diff --git a/Marlin/src/lcd/extui/mks_ui/draw_tool.cpp b/Marlin/src/lcd/extui/mks_ui/draw_tool.cpp new file mode 100644 index 000000000000..8b9747972d59 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_tool.cpp @@ -0,0 +1,103 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include + +#include "../../../gcode/queue.h" +#include "../../../module/temperature.h" +#include "../../../inc/MarlinConfig.h" + +extern lv_group_t *g; +static lv_obj_t *scr; + +enum { + ID_T_PRE_HEAT = 1, + ID_T_EXTRUCT, + ID_T_MOV, + ID_T_HOME, + ID_T_LEVELING, + ID_T_FILAMENT, + ID_T_MORE, + ID_T_RETURN +}; + +#if ENABLED(MKS_TEST) + extern uint8_t current_disp_ui; +#endif + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + if (TERN1(AUTO_BED_LEVELING_BILINEAR, obj->mks_obj_id != ID_T_LEVELING)) + lv_clear_tool(); + switch (obj->mks_obj_id) { + case ID_T_PRE_HEAT: lv_draw_preHeat(); break; + case ID_T_EXTRUCT: lv_draw_extrusion(); break; + case ID_T_MOV: lv_draw_move_motor(); break; + case ID_T_HOME: lv_draw_home(); break; + case ID_T_LEVELING: + #if ENABLED(AUTO_BED_LEVELING_BILINEAR) + get_gcode_command(AUTO_LEVELING_COMMAND_ADDR,(uint8_t *)public_buf_m); + public_buf_m[sizeof(public_buf_m)-1] = 0; + queue.inject_P(PSTR(public_buf_m)); + #else + uiCfg.leveling_first_time = true; + lv_draw_manualLevel(); + #endif + break; + case ID_T_FILAMENT: + uiCfg.hotendTargetTempBak = thermalManager.degTargetHotend(uiCfg.extruderIndex); + lv_draw_filament_change(); + break; + case ID_T_MORE: + lv_draw_more(); + break; + case ID_T_RETURN: + TERN_(MKS_TEST, current_disp_ui = 1); + lv_draw_ready_print(); + break; + } +} + +void lv_draw_tool() { + scr = lv_screen_create(TOOL_UI); + lv_big_button_create(scr, "F:/bmp_preHeat.bin", tool_menu.preheat, INTERVAL_V, titleHeight, event_handler, ID_T_PRE_HEAT); + lv_big_button_create(scr, "F:/bmp_extruct.bin", tool_menu.extrude, BTN_X_PIXEL + INTERVAL_V * 2, titleHeight, event_handler, ID_T_EXTRUCT); + lv_big_button_create(scr, "F:/bmp_mov.bin", tool_menu.move, BTN_X_PIXEL * 2 + INTERVAL_V * 3, titleHeight, event_handler, ID_T_MOV); + lv_big_button_create(scr, "F:/bmp_zero.bin", tool_menu.home, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight, event_handler, ID_T_HOME); + lv_big_button_create(scr, "F:/bmp_leveling.bin", tool_menu.TERN(AUTO_BED_LEVELING_BILINEAR, autoleveling, leveling), INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_T_LEVELING); + lv_big_button_create(scr, "F:/bmp_filamentchange.bin", tool_menu.filament, BTN_X_PIXEL+INTERVAL_V*2,BTN_Y_PIXEL+INTERVAL_H+titleHeight, event_handler,ID_T_FILAMENT); + lv_big_button_create(scr, "F:/bmp_more.bin", tool_menu.more, BTN_X_PIXEL * 2 + INTERVAL_V * 3, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_T_MORE); + lv_big_button_create(scr, "F:/bmp_return.bin", common_menu.text_back, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_T_RETURN); +} + +void lv_clear_tool() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_tool.h b/Marlin/src/lcd/extui/mks_ui/draw_tool.h similarity index 90% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_tool.h rename to Marlin/src/lcd/extui/mks_ui/draw_tool.h index 8a033e2c40b9..0dc86b703072 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_tool.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_tool.h @@ -25,10 +25,9 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_tool(void); -extern void lv_clear_tool(); +void lv_draw_tool(); +void lv_clear_tool(); -//extern void disp_temp_ready_print(); #ifdef __cplusplus } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.cpp b/Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.cpp new file mode 100644 index 000000000000..e10a07c6de40 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.cpp @@ -0,0 +1,122 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if BOTH(HAS_TFT_LVGL_UI, TOUCH_SCREEN_CALIBRATION) + +#include "draw_ui.h" +#include "draw_touch_calibration.h" +#include + +#include "../../../inc/MarlinConfig.h" +#include "../../tft_io/touch_calibration.h" +#include "SPI_TFT.h" + +static lv_obj_t *scr; +static lv_obj_t *status_label; + +#if ENABLED(MKS_TEST) + extern uint8_t current_disp_ui; +#endif + +static void event_handler(lv_obj_t *obj, lv_event_t event); + +enum { + ID_TC_RETURN = 1 +}; + +static void drawCross(uint16_t x, uint16_t y, uint16_t color) { + SPI_TFT.tftio.set_window(x - 15, y, x + 15, y); + SPI_TFT.tftio.WriteMultiple(color, 31); + SPI_TFT.tftio.set_window(x, y - 15, x, y + 15); + SPI_TFT.tftio.WriteMultiple(color, 31); +} + +void lv_update_touch_calibration_screen() { + uint16_t x, y; + + calibrationState calibration_stage = touch_calibration.get_calibration_state(); + if (calibration_stage == CALIBRATION_NONE) { + // start and clear screen + calibration_stage = touch_calibration.calibration_start(); + } + else { + // clear last cross + x = touch_calibration.calibration_points[_MIN(calibration_stage - 1, CALIBRATION_BOTTOM_RIGHT)].x; + y = touch_calibration.calibration_points[_MIN(calibration_stage - 1, CALIBRATION_BOTTOM_RIGHT)].y; + drawCross(x, y, LV_COLOR_BACKGROUND.full); + } + + const char *str = nullptr; + if (calibration_stage < CALIBRATION_SUCCESS) { + // handle current state + switch (calibration_stage) { + case CALIBRATION_TOP_LEFT: str = GET_TEXT(MSG_TOP_LEFT); break; + case CALIBRATION_BOTTOM_LEFT: str = GET_TEXT(MSG_BOTTOM_LEFT); break; + case CALIBRATION_TOP_RIGHT: str = GET_TEXT(MSG_TOP_RIGHT); break; + case CALIBRATION_BOTTOM_RIGHT: str = GET_TEXT(MSG_BOTTOM_RIGHT); break; + default: break; + } + + x = touch_calibration.calibration_points[calibration_stage].x; + y = touch_calibration.calibration_points[calibration_stage].y; + drawCross(x, y, LV_COLOR_WHITE.full); + } + else { + // end calibration + str = calibration_stage == CALIBRATION_SUCCESS ? GET_TEXT(MSG_CALIBRATION_COMPLETED) : GET_TEXT(MSG_CALIBRATION_FAILED); + touch_calibration.calibration_end(); + lv_big_button_create(scr, "F:/bmp_return.bin", common_menu.text_back, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_TC_RETURN); + } + + // draw current message + lv_label_set_text(status_label, str); + lv_obj_align(status_label, nullptr, LV_ALIGN_CENTER, 0, 0); +} + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + switch (obj->mks_obj_id) { + case ID_TC_RETURN: + TERN_(MKS_TEST, current_disp_ui = 1); + lv_clear_touch_calibration_screen(); + draw_return_ui(); + break; + } +} + +void lv_draw_touch_calibration_screen() { + scr = lv_screen_create(TOUCH_CALIBRATION_UI, ""); + + status_label = lv_label_create(scr, ""); + lv_obj_align(status_label, nullptr, LV_ALIGN_CENTER, 0, 0); + + lv_refr_now(lv_refr_get_disp_refreshing()); + + lv_update_touch_calibration_screen(); +} + +void lv_clear_touch_calibration_screen() { + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI && TOUCH_SCREEN_CALIBRATION diff --git a/Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.h b/Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.h new file mode 100644 index 000000000000..567256a792e1 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.h @@ -0,0 +1,34 @@ +/** + * 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 + +#ifdef __cplusplus + extern "C" { /* C-declarations for C++ */ +#endif + +void lv_draw_touch_calibration_screen(); +void lv_clear_touch_calibration_screen(); +void lv_update_touch_calibration_screen(); + +#ifdef __cplusplus + } /* C-declarations for C++ */ +#endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_tramming_pos_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_tramming_pos_settings.cpp new file mode 100644 index 000000000000..c4a21542e2a8 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_tramming_pos_settings.cpp @@ -0,0 +1,146 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include + +#include "../../../module/planner.h" +#include "../../../inc/MarlinConfig.h" + +extern lv_group_t *g; +static lv_obj_t *scr; + +enum { + ID_MANUAL_POS_RETURN = 1, + ID_MANUAL_POS_X1, + ID_MANUAL_POS_Y1, + ID_MANUAL_POS_X2, + ID_MANUAL_POS_Y2, + ID_MANUAL_POS_X3, + ID_MANUAL_POS_Y3, + ID_MANUAL_POS_X4, + ID_MANUAL_POS_Y4, + ID_MANUAL_POS_X5, + ID_MANUAL_POS_Y5, + ID_MANUAL_POS_DOWN, + ID_MANUAL_POS_UP +}; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + switch (obj->mks_obj_id) { + case ID_MANUAL_POS_RETURN: + uiCfg.para_ui_page = false; + lv_clear_tramming_pos_settings(); + draw_return_ui(); + return; + case ID_MANUAL_POS_X1: + value = level_pos_x1; + break; + case ID_MANUAL_POS_Y1: + value = level_pos_y1; + break; + case ID_MANUAL_POS_X2: + value = level_pos_x2; + break; + case ID_MANUAL_POS_Y2: + value = level_pos_y2; + break; + case ID_MANUAL_POS_X3: + value = level_pos_x3; + break; + case ID_MANUAL_POS_Y3: + value = level_pos_y3; + break; + case ID_MANUAL_POS_X4: + value = level_pos_x4; + break; + case ID_MANUAL_POS_Y4: + value = level_pos_y4; + break; + case ID_MANUAL_POS_X5: + value = level_pos_x5; + break; + case ID_MANUAL_POS_Y5: + value = level_pos_y5; + break; + case ID_MANUAL_POS_UP: + uiCfg.para_ui_page = false; + lv_clear_tramming_pos_settings(); + lv_draw_tramming_pos_settings(); + return; + case ID_MANUAL_POS_DOWN: + uiCfg.para_ui_page = true; + lv_clear_tramming_pos_settings(); + lv_draw_tramming_pos_settings(); + return; + } + lv_clear_tramming_pos_settings(); + lv_draw_number_key(); +} + +void lv_draw_tramming_pos_settings() { + char buf2[50]; + + scr = lv_screen_create(MANUAL_LEVELING_POSIGION_UI, machine_menu.LevelingParaConfTitle); + + if (!uiCfg.para_ui_page) { + itoa(gCfgItems.trammingPos[0].x, public_buf_l, 10); + itoa(gCfgItems.trammingPos[0].y, buf2, 10); + lv_screen_menu_item_2_edit(scr, leveling_menu.position1, PARA_UI_POS_X, PARA_UI_POS_Y, event_handler, ID_MANUAL_POS_Y1, 0, buf2, ID_MANUAL_POS_X1, public_buf_l); + + itoa(gCfgItems.trammingPos[1].x, public_buf_l, 10); + itoa(gCfgItems.trammingPos[1].y, buf2, 10); + lv_screen_menu_item_2_edit(scr, leveling_menu.position2, PARA_UI_POS_X, PARA_UI_POS_Y * 2, event_handler, ID_MANUAL_POS_Y2, 1, buf2, ID_MANUAL_POS_X2, public_buf_l); + + itoa(gCfgItems.trammingPos[2].x, public_buf_l, 10); + itoa(gCfgItems.trammingPos[2].y, buf2, 10); + lv_screen_menu_item_2_edit(scr, leveling_menu.position3, PARA_UI_POS_X, PARA_UI_POS_Y * 3, event_handler, ID_MANUAL_POS_Y3, 2, buf2, ID_MANUAL_POS_X3, public_buf_l); + + itoa(gCfgItems.trammingPos[3].x, public_buf_l, 10); + itoa(gCfgItems.trammingPos[3].y, buf2, 10); + lv_screen_menu_item_2_edit(scr, leveling_menu.position4, PARA_UI_POS_X, PARA_UI_POS_Y * 4, event_handler, ID_MANUAL_POS_Y4, 3, buf2, ID_MANUAL_POS_X4, public_buf_l); + + 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_MANUAL_POS_DOWN, true); + } + else { + itoa(gCfgItems.trammingPos[4].x, public_buf_l, 10); + itoa(gCfgItems.trammingPos[4].y, buf2, 10); + lv_screen_menu_item_2_edit(scr, leveling_menu.position5, PARA_UI_POS_X, PARA_UI_POS_Y, event_handler, ID_MANUAL_POS_Y5, 0, buf2, ID_MANUAL_POS_X5, public_buf_l); + + lv_big_button_create(scr, "F:/bmp_back70x40.bin", machine_menu.previous, PARA_UI_TURN_PAGE_POS_X, PARA_UI_TURN_PAGE_POS_Y, event_handler, ID_MANUAL_POS_UP, true); + } + + lv_big_button_create(scr, "F:/bmp_back70x40.bin", common_menu.text_back, PARA_UI_BACL_POS_X + 10, PARA_UI_BACL_POS_Y, event_handler, ID_MANUAL_POS_RETURN, true); +} + +void lv_clear_tramming_pos_settings() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_tramming_pos_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_tramming_pos_settings.h new file mode 100644 index 000000000000..863ff6fc7e84 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_tramming_pos_settings.h @@ -0,0 +1,33 @@ +/** + * 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 + +#ifdef __cplusplus + extern "C" { /* C-declarations for C++ */ +#endif + +void lv_draw_tramming_pos_settings(); +void lv_clear_tramming_pos_settings(); + +#ifdef __cplusplus + } /* C-declarations for C++ */ +#endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp new file mode 100644 index 000000000000..7dfbea5bae18 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp @@ -0,0 +1,1384 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "SPI_TFT.h" + +#include "tft_lvgl_configuration.h" + +#include "pic_manager.h" + +#include "draw_ui.h" + +#include + +#include "../../../MarlinCore.h" // for marlin_state +#include "../../../sd/cardreader.h" +#include "../../../module/motion.h" +#include "../../../module/planner.h" +#include "../../../inc/MarlinConfig.h" + +#if ENABLED(POWER_LOSS_RECOVERY) + #include "../../../feature/powerloss.h" +#endif + +#if ENABLED(PARK_HEAD_ON_PAUSE) + #include "../../../feature/pause.h" +#endif + +#if ENABLED(TOUCH_SCREEN_CALIBRATION) + #include "draw_touch_calibration.h" +#endif + +#if ENABLED(MKS_TEST) + #include "mks_hardware.h" +#endif + +CFG_ITMES gCfgItems; +UI_CFG uiCfg; +DISP_STATE_STACK disp_state_stack; +DISP_STATE disp_state = MAIN_UI; +DISP_STATE last_disp_state; +PRINT_TIME print_time; +num_key_value_state value; +keyboard_value_state keyboard_value; + +uint32_t To_pre_view; +bool gcode_preview_over, flash_preview_begin, default_preview_flg; +uint32_t size = 809; +uint16_t row; +bool temps_update_flag; +uint8_t printing_rate_update_flag; + +extern bool once_flag; +extern uint8_t sel_id; +extern lv_group_t *g; + +void LCD_IO_WriteData(uint16_t RegValue); + +static const char custom_gcode_command[][100] = { + "G29N\nM500", + "G28", + "G28", + "G28", + "G28" +}; + +lv_point_t line_points[4][2] = { + {{PARA_UI_POS_X, PARA_UI_POS_Y + PARA_UI_SIZE_Y}, {TFT_WIDTH, PARA_UI_POS_Y + PARA_UI_SIZE_Y}}, + {{PARA_UI_POS_X, PARA_UI_POS_Y*2 + PARA_UI_SIZE_Y}, {TFT_WIDTH, PARA_UI_POS_Y*2 + PARA_UI_SIZE_Y}}, + {{PARA_UI_POS_X, PARA_UI_POS_Y*3 + PARA_UI_SIZE_Y}, {TFT_WIDTH, PARA_UI_POS_Y*3 + PARA_UI_SIZE_Y}}, + {{PARA_UI_POS_X, PARA_UI_POS_Y*4 + PARA_UI_SIZE_Y}, {TFT_WIDTH, PARA_UI_POS_Y*4 + PARA_UI_SIZE_Y}} +}; +void gCfgItems_init() { + gCfgItems.multiple_language = MULTI_LANGUAGE_ENABLE; + #if 1 // LCD_LANGUAGE == en + gCfgItems.language = LANG_ENGLISH; + #elif LCD_LANGUAGE == zh_CN + gCfgItems.language = LANG_SIMPLE_CHINESE; + #elif LCD_LANGUAGE == zh_TW + gCfgItems.language = LANG_COMPLEX_CHINESE; + #elif LCD_LANGUAGE == jp_kana + gCfgItems.language = LANG_JAPAN; + #elif LCD_LANGUAGE == de + gCfgItems.language = LANG_GERMAN; + #elif LCD_LANGUAGE == fr + gCfgItems.language = LANG_FRENCH; + #elif LCD_LANGUAGE == ru + gCfgItems.language = LANG_RUSSIAN; + #elif LCD_LANGUAGE == ko_KR + gCfgItems.language = LANG_KOREAN; + #elif LCD_LANGUAGE == tr + gCfgItems.language = LANG_TURKISH; + #elif LCD_LANGUAGE == es + gCfgItems.language = LANG_SPANISH; + #elif LCD_LANGUAGE == el + gCfgItems.language = LANG_GREEK; + #elif LCD_LANGUAGE == it + gCfgItems.language = LANG_ITALY; + #elif LCD_LANGUAGE == pt + gCfgItems.language = LANG_PORTUGUESE; + #endif + gCfgItems.leveling_mode = 0; + gCfgItems.from_flash_pic = false; + gCfgItems.curFilesize = 0; + gCfgItems.finish_power_off = false; + gCfgItems.pause_reprint = false; + gCfgItems.pausePosX = -1; + gCfgItems.pausePosY = -1; + gCfgItems.pausePosZ = 5; + gCfgItems.trammingPos[0].x = X_MIN_POS + 30; + gCfgItems.trammingPos[0].y = Y_MIN_POS + 30; + gCfgItems.trammingPos[1].x = X_MAX_POS - 30; + gCfgItems.trammingPos[1].y = Y_MIN_POS + 30; + gCfgItems.trammingPos[2].x = X_MAX_POS - 30; + gCfgItems.trammingPos[2].y = Y_MAX_POS - 30; + gCfgItems.trammingPos[3].x = X_MIN_POS + 30; + gCfgItems.trammingPos[3].y = Y_MAX_POS - 30; + gCfgItems.trammingPos[4].x = X_BED_SIZE / 2; + gCfgItems.trammingPos[4].y = Y_BED_SIZE / 2; + gCfgItems.cloud_enable = false; + gCfgItems.wifi_mode_sel = STA_MODEL; + gCfgItems.fileSysType = FILE_SYS_SD; + gCfgItems.wifi_type = ESP_WIFI; + gCfgItems.filamentchange_load_length = 200; + gCfgItems.filamentchange_load_speed = 1000; + gCfgItems.filamentchange_unload_length = 200; + gCfgItems.filamentchange_unload_speed = 1000; + gCfgItems.filament_limit_temp = 200; + + gCfgItems.encoder_enable = true; + + W25QXX.SPI_FLASH_BufferRead((uint8_t *)&gCfgItems.spi_flash_flag, VAR_INF_ADDR, sizeof(gCfgItems.spi_flash_flag)); + if (gCfgItems.spi_flash_flag == FLASH_INF_VALID_FLAG) { + W25QXX.SPI_FLASH_BufferRead((uint8_t *)&gCfgItems, VAR_INF_ADDR, sizeof(gCfgItems)); + } + else { + gCfgItems.spi_flash_flag = FLASH_INF_VALID_FLAG; + W25QXX.SPI_FLASH_SectorErase(VAR_INF_ADDR); + W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&gCfgItems, VAR_INF_ADDR, sizeof(gCfgItems)); + //init gcode command + W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&custom_gcode_command[0], AUTO_LEVELING_COMMAND_ADDR, 100); + W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&custom_gcode_command[1], OTHERS_COMMAND_ADDR_1, 100); + W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&custom_gcode_command[2], OTHERS_COMMAND_ADDR_2, 100); + W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&custom_gcode_command[3], OTHERS_COMMAND_ADDR_3, 100); + W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&custom_gcode_command[4], OTHERS_COMMAND_ADDR_4, 100); + } + + const byte rot = (TFT_ROTATION & TFT_ROTATE_180) ? 0xEE : 0x00; + if (gCfgItems.disp_rotation_180 != rot) { + gCfgItems.disp_rotation_180 = rot; + update_spi_flash(); + } + + uiCfg.F[0] = 'N'; + uiCfg.F[1] = 'A'; + uiCfg.F[2] = 'N'; + uiCfg.F[3] = 'O'; + W25QXX.SPI_FLASH_BlockErase(REFLSHE_FLGA_ADD + 32 - 64*1024); + W25QXX.SPI_FLASH_BufferWrite(uiCfg.F,REFLSHE_FLGA_ADD,4); +} + +void ui_cfg_init() { + uiCfg.curTempType = 0; + uiCfg.extruderIndex = 0; + uiCfg.stepHeat = 10; + uiCfg.leveling_first_time = false; + uiCfg.para_ui_page = false; + uiCfg.extruStep = 5; + uiCfg.extruSpeed = 10; + uiCfg.move_dist = 1; + uiCfg.moveSpeed = 3000; + uiCfg.stepPrintSpeed = 10; + uiCfg.command_send = false; + uiCfg.dialogType = 0; + uiCfg.filament_heat_completed_load = false; + uiCfg.filament_rate = 0; + uiCfg.filament_loading_completed = false; + uiCfg.filament_unloading_completed = false; + uiCfg.filament_loading_time_flg = false; + uiCfg.filament_loading_time_cnt = 0; + uiCfg.filament_unloading_time_flg = false; + uiCfg.filament_unloading_time_cnt = 0; + + #if ENABLED(MKS_WIFI_MODULE) + memset(&wifiPara, 0, sizeof(wifiPara)); + memset(&ipPara, 0, sizeof(ipPara)); + strcpy_P(wifiPara.ap_name, PSTR(WIFI_AP_NAME)); + strcpy_P(wifiPara.keyCode, PSTR(WIFI_KEY_CODE)); + //client + strcpy_P(ipPara.ip_addr, PSTR(IP_ADDR)); + strcpy_P(ipPara.mask, PSTR(IP_MASK)); + strcpy_P(ipPara.gate, PSTR(IP_GATE)); + strcpy_P(ipPara.dns, PSTR(IP_DNS)); + + ipPara.dhcp_flag = IP_DHCP_FLAG; + + //AP + strcpy_P(ipPara.dhcpd_ip, PSTR(AP_IP_ADDR)); + strcpy_P(ipPara.dhcpd_mask, PSTR(AP_IP_MASK)); + strcpy_P(ipPara.dhcpd_gate, PSTR(AP_IP_GATE)); + strcpy_P(ipPara.dhcpd_dns, PSTR(AP_IP_DNS)); + strcpy_P(ipPara.start_ip_addr, PSTR(IP_START_IP)); + strcpy_P(ipPara.end_ip_addr, PSTR(IP_END_IP)); + + ipPara.dhcpd_flag = AP_IP_DHCP_FLAG; + + strcpy_P((char*)uiCfg.cloud_hostUrl, PSTR("baizhongyun.cn")); + uiCfg.cloud_port = 10086; + #endif + + uiCfg.filament_loading_time = (uint32_t)((gCfgItems.filamentchange_load_length * 60.0f / gCfgItems.filamentchange_load_speed) + 0.5f); + uiCfg.filament_unloading_time = (uint32_t)((gCfgItems.filamentchange_unload_length * 60.0f / gCfgItems.filamentchange_unload_speed) + 0.5f); +} + +void update_spi_flash() { + uint8_t command_buf[512]; + + W25QXX.init(SPI_QUARTER_SPEED); + //read back the gcode command before erase spi flash + W25QXX.SPI_FLASH_BufferRead((uint8_t *)&command_buf, GCODE_COMMAND_ADDR, sizeof(command_buf)); + W25QXX.SPI_FLASH_SectorErase(VAR_INF_ADDR); + W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&gCfgItems, VAR_INF_ADDR, sizeof(gCfgItems)); + W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&command_buf, GCODE_COMMAND_ADDR, sizeof(command_buf)); +} + +void update_gcode_command(int addr,uint8_t *s) { + uint8_t command_buf[512]; + + W25QXX.init(SPI_QUARTER_SPEED); + //read back the gcode command before erase spi flash + W25QXX.SPI_FLASH_BufferRead((uint8_t *)&command_buf, GCODE_COMMAND_ADDR, sizeof(command_buf)); + W25QXX.SPI_FLASH_SectorErase(VAR_INF_ADDR); + W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&gCfgItems, VAR_INF_ADDR, sizeof(gCfgItems)); + switch (addr) { + case AUTO_LEVELING_COMMAND_ADDR: memcpy(&command_buf[0*100], s, 100); break; + case OTHERS_COMMAND_ADDR_1: memcpy(&command_buf[1*100], s, 100); break; + case OTHERS_COMMAND_ADDR_2: memcpy(&command_buf[2*100], s, 100); break; + case OTHERS_COMMAND_ADDR_3: memcpy(&command_buf[3*100], s, 100); break; + case OTHERS_COMMAND_ADDR_4: memcpy(&command_buf[4*100], s, 100); break; + default: break; + } + W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&command_buf, GCODE_COMMAND_ADDR, sizeof(command_buf)); +} + +void get_gcode_command(int addr,uint8_t *d) { + W25QXX.init(SPI_QUARTER_SPEED); + W25QXX.SPI_FLASH_BufferRead((uint8_t *)d, addr, 100); +} + +lv_style_t tft_style_scr; +lv_style_t tft_style_label_pre; +lv_style_t tft_style_label_rel; +lv_style_t style_line; +lv_style_t style_para_value_pre; +lv_style_t style_para_value_rel; + +lv_style_t style_num_key_pre; +lv_style_t style_num_key_rel; + +lv_style_t style_num_text; +lv_style_t style_sel_text; + +lv_style_t style_para_value; +lv_style_t style_para_back; + +lv_style_t lv_bar_style_indic; + +lv_style_t style_btn_pr; +lv_style_t style_btn_rel; + +void tft_style_init() { + lv_style_copy(&tft_style_scr, &lv_style_scr); + tft_style_scr.body.main_color = LV_COLOR_BACKGROUND; + tft_style_scr.body.grad_color = LV_COLOR_BACKGROUND; + tft_style_scr.text.color = LV_COLOR_TEXT; + tft_style_scr.text.sel_color = LV_COLOR_TEXT; + tft_style_scr.line.width = 0; + tft_style_scr.text.letter_space = 0; + tft_style_scr.text.line_space = 0; + + lv_style_copy(&tft_style_label_pre, &lv_style_scr); + lv_style_copy(&tft_style_label_rel, &lv_style_scr); + tft_style_label_pre.body.main_color = LV_COLOR_BACKGROUND; + tft_style_label_pre.body.grad_color = LV_COLOR_BACKGROUND; + tft_style_label_pre.text.color = LV_COLOR_TEXT; + tft_style_label_pre.text.sel_color = LV_COLOR_TEXT; + tft_style_label_rel.body.main_color = LV_COLOR_BACKGROUND; + tft_style_label_rel.body.grad_color = LV_COLOR_BACKGROUND; + tft_style_label_rel.text.color = LV_COLOR_TEXT; + tft_style_label_rel.text.sel_color = LV_COLOR_TEXT; + tft_style_label_pre.text.font = TERN(HAS_SPI_FLASH_FONT, &gb2312_puhui32, LV_FONT_DEFAULT); + tft_style_label_rel.text.font = TERN(HAS_SPI_FLASH_FONT, &gb2312_puhui32, LV_FONT_DEFAULT); + tft_style_label_pre.line.width = 0; + tft_style_label_rel.line.width = 0; + tft_style_label_pre.text.letter_space = 0; + tft_style_label_rel.text.letter_space = 0; + tft_style_label_pre.text.line_space = -5; + tft_style_label_rel.text.line_space = -5; + + lv_style_copy(&style_para_value_pre, &lv_style_scr); + lv_style_copy(&style_para_value_rel, &lv_style_scr); + style_para_value_pre.body.main_color = LV_COLOR_BACKGROUND; + style_para_value_pre.body.grad_color = LV_COLOR_BACKGROUND; + style_para_value_pre.text.color = LV_COLOR_TEXT; + style_para_value_pre.text.sel_color = LV_COLOR_TEXT; + style_para_value_rel.body.main_color = LV_COLOR_BACKGROUND; + style_para_value_rel.body.grad_color = LV_COLOR_BACKGROUND; + style_para_value_rel.text.color = LV_COLOR_BLACK; + style_para_value_rel.text.sel_color = LV_COLOR_BLACK; + style_para_value_pre.text.font = TERN(HAS_SPI_FLASH_FONT, &gb2312_puhui32, LV_FONT_DEFAULT); + style_para_value_rel.text.font = TERN(HAS_SPI_FLASH_FONT, &gb2312_puhui32, LV_FONT_DEFAULT); + style_para_value_pre.line.width = 0; + style_para_value_rel.line.width = 0; + style_para_value_pre.text.letter_space = 0; + style_para_value_rel.text.letter_space = 0; + style_para_value_pre.text.line_space = -5; + style_para_value_rel.text.line_space = -5; + + lv_style_copy(&style_num_key_pre, &lv_style_scr); + lv_style_copy(&style_num_key_rel, &lv_style_scr); + style_num_key_pre.body.main_color = LV_COLOR_KEY_BACKGROUND; + style_num_key_pre.body.grad_color = LV_COLOR_KEY_BACKGROUND; + style_num_key_pre.text.color = LV_COLOR_TEXT; + style_num_key_pre.text.sel_color = LV_COLOR_TEXT; + style_num_key_rel.body.main_color = LV_COLOR_KEY_BACKGROUND; + style_num_key_rel.body.grad_color = LV_COLOR_KEY_BACKGROUND; + style_num_key_rel.text.color = LV_COLOR_TEXT; + style_num_key_rel.text.sel_color = LV_COLOR_TEXT; + #if HAS_SPI_FLASH_FONT + style_num_key_pre.text.font = &gb2312_puhui32; + style_num_key_rel.text.font = &gb2312_puhui32; + #else + style_num_key_pre.text.font = LV_FONT_DEFAULT; + style_num_key_rel.text.font = LV_FONT_DEFAULT; + #endif + + style_num_key_pre.line.width = 0; + style_num_key_rel.line.width = 0; + style_num_key_pre.text.letter_space = 0; + style_num_key_rel.text.letter_space = 0; + style_num_key_pre.text.line_space = -5; + style_num_key_rel.text.line_space = -5; + lv_style_copy(&style_num_text, &lv_style_scr); + + style_num_text.body.main_color = LV_COLOR_WHITE; + style_num_text.body.grad_color = LV_COLOR_WHITE; + style_num_text.text.color = LV_COLOR_BLACK; + style_num_text.text.sel_color = LV_COLOR_BLACK; + style_num_text.text.font = TERN(HAS_SPI_FLASH_FONT, &gb2312_puhui32, LV_FONT_DEFAULT); + style_num_text.line.width = 0; + style_num_text.text.letter_space = 0; + style_num_text.text.line_space = -5; + + lv_style_copy(&style_sel_text, &lv_style_scr); + style_sel_text.body.main_color = LV_COLOR_BACKGROUND; + style_sel_text.body.grad_color = LV_COLOR_BACKGROUND; + style_sel_text.text.color = LV_COLOR_YELLOW; + style_sel_text.text.sel_color = LV_COLOR_YELLOW; + style_sel_text.text.font = TERN(HAS_SPI_FLASH_FONT, &gb2312_puhui32, LV_FONT_DEFAULT); + style_sel_text.line.width = 0; + style_sel_text.text.letter_space = 0; + style_sel_text.text.line_space = -5; + lv_style_copy(&style_line, &lv_style_plain); + style_line.line.color = LV_COLOR_MAKE(0x49, 0x54, 0xFF); + style_line.line.width = 1; + style_line.line.rounded = 1; + + lv_style_copy(&style_para_value, &lv_style_plain); + style_para_value.body.border.color = LV_COLOR_BACKGROUND; + style_para_value.body.border.width = 1; + style_para_value.body.main_color = LV_COLOR_WHITE; + style_para_value.body.grad_color = LV_COLOR_WHITE; + style_para_value.body.shadow.width = 0; + style_para_value.body.radius = 3; + style_para_value.text.color = LV_COLOR_BLACK; + style_para_value.text.font = &TERN(HAS_SPI_FLASH_FONT, gb2312_puhui32, lv_font_roboto_22); + + lv_style_copy(&style_para_back, &lv_style_plain); + style_para_back.body.border.color = LV_COLOR_BACKGROUND; + style_para_back.body.border.width = 1; + style_para_back.body.main_color = TFT_LV_PARA_BACK_BODY_COLOR; + style_para_back.body.grad_color = TFT_LV_PARA_BACK_BODY_COLOR; + style_para_back.body.shadow.width = 0; + style_para_back.body.radius = 3; + style_para_back.text.color = LV_COLOR_WHITE; + style_para_back.text.font = &TERN(HAS_SPI_FLASH_FONT, gb2312_puhui32, lv_font_roboto_22); + + lv_style_copy(&style_btn_rel, &lv_style_plain); + style_btn_rel.body.border.color = lv_color_hex3(0x269); + style_btn_rel.body.border.width = 1; + style_btn_rel.body.main_color = lv_color_hex3(0xADF); + style_btn_rel.body.grad_color = lv_color_hex3(0x46B); + style_btn_rel.body.shadow.width = 4; + style_btn_rel.body.shadow.type = LV_SHADOW_BOTTOM; + style_btn_rel.body.radius = LV_RADIUS_CIRCLE; + style_btn_rel.text.color = lv_color_hex3(0xDEF); + style_btn_rel.text.font = &TERN(HAS_SPI_FLASH_FONT, gb2312_puhui32, lv_font_roboto_22); + + lv_style_copy(&style_btn_pr, &style_btn_rel); + style_btn_pr.body.border.color = lv_color_hex3(0x46B); + style_btn_pr.body.main_color = lv_color_hex3(0x8BD); + style_btn_pr.body.grad_color = lv_color_hex3(0x24A); + style_btn_pr.body.shadow.width = 2; + style_btn_pr.text.color = lv_color_hex3(0xBCD); + style_btn_pr.text.font = &TERN(HAS_SPI_FLASH_FONT, gb2312_puhui32, lv_font_roboto_22); + + lv_style_copy(&lv_bar_style_indic, &lv_style_pretty_color); + lv_bar_style_indic.text.color = lv_color_hex3(0xADF); + lv_bar_style_indic.image.color = lv_color_hex3(0xADF); + lv_bar_style_indic.line.color = lv_color_hex3(0xADF); + lv_bar_style_indic.body.main_color = lv_color_hex3(0xADF); + lv_bar_style_indic.body.grad_color = lv_color_hex3(0xADF); + lv_bar_style_indic.body.border.color = lv_color_hex3(0xADF); +} + +#define MAX_TITLE_LEN 28 + +char public_buf_m[100] = {0}; +char public_buf_l[30]; + +void titleText_cat(char *str, int strSize, char *addPart) { + if (str == 0 || addPart == 0) return; + if ((int)(strlen(str) + strlen(addPart)) >= strSize) return; + strcat(str, addPart); +} + +char *getDispText(int index) { + + ZERO(public_buf_l); + + switch (disp_state_stack._disp_state[index]) { + case PRINT_READY_UI: strcpy(public_buf_l, main_menu.title); break; + case PRINT_FILE_UI: strcpy(public_buf_l, file_menu.title); break; + case PRINTING_UI: + switch (disp_state_stack._disp_state[disp_state_stack._disp_index]) { + IF_DISABLED(TFT35, case OPERATE_UI: case PAUSE_UI:) + case PRINTING_UI: strcpy(public_buf_l, common_menu.print_special_title); break; + default: strcpy(public_buf_l, printing_menu.title); break; + } + break; + case MOVE_MOTOR_UI: strcpy(public_buf_l, move_menu.title); break; + case OPERATE_UI: + switch (disp_state_stack._disp_state[disp_state_stack._disp_index]) { + IF_DISABLED(TFT35, case OPERATE_UI: case PAUSE_UI:) + case PRINTING_UI: strcpy(public_buf_l, common_menu.operate_special_title); break; + default: strcpy(public_buf_l, operation_menu.title); break; + } + break; + + case PAUSE_UI: + switch (disp_state_stack._disp_state[disp_state_stack._disp_index]) { + case OPERATE_UI: + case PAUSE_UI: + case PRINTING_UI: strcpy(public_buf_l, common_menu.pause_special_title); break; + default: strcpy(public_buf_l, pause_menu.title); break; + } + break; + case EXTRUSION_UI: strcpy(public_buf_l, extrude_menu.title); break; + case CHANGE_SPEED_UI: strcpy(public_buf_l, speed_menu.title); break; + case FAN_UI: strcpy(public_buf_l, fan_menu.title); break; + case PRE_HEAT_UI: + switch (disp_state_stack._disp_state[disp_state_stack._disp_index]) { + case OPERATE_UI: strcpy(public_buf_l, preheat_menu.adjust_title); + default: strcpy(public_buf_l, preheat_menu.title); break; + } + break; + case SET_UI: strcpy(public_buf_l, set_menu.title); break; + case ZERO_UI: strcpy(public_buf_l, home_menu.title); break; + case SPRAYER_UI: break; + case MACHINE_UI: break; + case LANGUAGE_UI: strcpy(public_buf_l, language_menu.title); break; + case ABOUT_UI: strcpy(public_buf_l, about_menu.title); break; + case LOG_UI: break; + case DISK_UI: strcpy(public_buf_l, filesys_menu.title); break; + case DIALOG_UI: strcpy(public_buf_l, common_menu.dialog_confirm_title); break; + case WIFI_UI: strcpy(public_buf_l, wifi_menu.title); break; + case MORE_UI: + case PRINT_MORE_UI: strcpy(public_buf_l, more_menu.title); break; + case FILAMENTCHANGE_UI: strcpy(public_buf_l, filament_menu.title); break; + case LEVELING_UI: + case MESHLEVELING_UI: strcpy(public_buf_l, leveling_menu.title); break; + case BIND_UI: strcpy(public_buf_l, cloud_menu.title); break; + case TOOL_UI: strcpy(public_buf_l, tool_menu.title); break; + case WIFI_LIST_UI: TERN_(MKS_WIFI_MODULE, strcpy(public_buf_l, list_menu.title)); break; + case MACHINE_PARA_UI: strcpy(public_buf_l, MachinePara_menu.title); break; + case BABY_STEP_UI: strcpy(public_buf_l, operation_menu.babystep); break; + case EEPROM_SETTINGS_UI: strcpy(public_buf_l, eeprom_menu.title); break; + case MEDIA_SELECT_UI: strcpy(public_buf_l, media_select_menu.title); break; + default: break; + } + + return public_buf_l; +} + +char *creat_title_text() { + int index = 0; + char *tmpText = 0; + char tmpCurFileStr[20]; + + ZERO(tmpCurFileStr); + + cutFileName(list_file.long_name[sel_id], 16, 16, tmpCurFileStr); + + ZERO(public_buf_m); + + while (index <= disp_state_stack._disp_index) { + tmpText = getDispText(index); + if ((*tmpText == 0) || (tmpText == 0)) { + index++; + continue; + } + + titleText_cat(public_buf_m, sizeof(public_buf_m), tmpText); + if (index < disp_state_stack._disp_index) titleText_cat(public_buf_m, sizeof(public_buf_m), (char *)">"); + + index++; + } + + if (disp_state_stack._disp_state[disp_state_stack._disp_index] == PRINTING_UI) { + titleText_cat(public_buf_m, sizeof(public_buf_m), (char *)":"); + titleText_cat(public_buf_m, sizeof(public_buf_m), tmpCurFileStr); + } + + if (strlen(public_buf_m) > MAX_TITLE_LEN) { + ZERO(public_buf_m); + tmpText = 0; + for (index = 0; index <= disp_state_stack._disp_index && (!tmpText || *tmpText == 0); index++) + tmpText = getDispText(index); + if (*tmpText != 0) { + titleText_cat(public_buf_m, sizeof(public_buf_m), tmpText); + titleText_cat(public_buf_m, sizeof(public_buf_m), (char *)">...>"); + tmpText = getDispText(disp_state_stack._disp_index); + if (*tmpText != 0) titleText_cat(public_buf_m, sizeof(public_buf_m), tmpText); + } + } + + return public_buf_m; +} + +#if HAS_GCODE_PREVIEW + + uintptr_t gPicturePreviewStart = 0; + + void preview_gcode_prehandle(char *path) { + #if ENABLED(SDSUPPORT) + uintptr_t pre_read_cnt = 0; + uint32_t *p1; + char *cur_name; + + gPicturePreviewStart = 0; + cur_name = strrchr(path, '/'); + card.openFileRead(cur_name); + card.read(public_buf, 512); + p1 = (uint32_t *)strstr((char *)public_buf, ";simage:"); + + if (p1) { + pre_read_cnt = (uintptr_t)p1 - (uintptr_t)((uint32_t *)(&public_buf[0])); + + To_pre_view = pre_read_cnt; + gcode_preview_over = true; + gCfgItems.from_flash_pic = true; + update_spi_flash(); + } + else { + gcode_preview_over = false; + default_preview_flg = true; + gCfgItems.from_flash_pic = false; + update_spi_flash(); + } + card.closefile(); + #endif + } + + void gcode_preview(char *path, int xpos_pixel, int ypos_pixel) { + #if ENABLED(SDSUPPORT) + volatile uint32_t i, j; + volatile uint16_t *p_index; + char *cur_name; + + cur_name = strrchr(path, '/'); + card.openFileRead(cur_name); + + if (gPicturePreviewStart <= 0) { + while (1) { + uint32_t br = card.read(public_buf, 400); + uint32_t *p1 = (uint32_t *)strstr((char *)public_buf, ";gimage:"); + if (p1) { + gPicturePreviewStart += (uintptr_t)p1 - (uintptr_t)((uint32_t *)(&public_buf[0])); + break; + } + else { + gPicturePreviewStart += br; + } + if (br < 400) break; + } + } + + card.setIndex(gPicturePreviewStart + size * row + 8); + SPI_TFT.setWindow(xpos_pixel, ypos_pixel + row, 200, 1); + + j = i = 0; + + while (1) { + card.read(public_buf, 400); + for (i = 0; i < 400;) { + bmp_public_buf[j] = ascii2dec_test((char*)&public_buf[i]) << 4 | ascii2dec_test((char*)&public_buf[i + 1]); + i += 2; + j++; + } + if (j >= 400) break; + } + for (i = 0; i < 400; i += 2) { + p_index = (uint16_t *)(&bmp_public_buf[i]); + if (*p_index == 0x0000) *p_index = LV_COLOR_BACKGROUND.full; + } + SPI_TFT.tftio.WriteSequence((uint16_t*)bmp_public_buf, 200); + #if HAS_BAK_VIEW_IN_FLASH + W25QXX.init(SPI_QUARTER_SPEED); + if (row < 20) W25QXX.SPI_FLASH_SectorErase(BAK_VIEW_ADDR_TFT35 + row * 4096); + W25QXX.SPI_FLASH_BufferWrite(bmp_public_buf, BAK_VIEW_ADDR_TFT35 + row * 400, 400); + #endif + row++; + card.abortFilePrintNow(); + if (row >= 200) { + size = 809; + row = 0; + + gcode_preview_over = false; + + char *cur_name = strrchr(list_file.file_name[sel_id], '/'); + + SdFile file; + SdFile *curDir; + 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()) { + feedrate_percentage = 100; + planner.flow_percentage[0] = 100; + planner.e_factor[0] = planner.flow_percentage[0] * 0.01; + #if HAS_MULTI_EXTRUDER + planner.flow_percentage[1] = 100; + planner.e_factor[1] = planner.flow_percentage[1] * 0.01; + #endif + card.startOrResumeFilePrinting(); + TERN_(POWER_LOSS_RECOVERY, recovery.prepare()); + once_flag = false; + } + return; + } + #endif // SDSUPPORT + } + + void draw_default_preview(int xpos_pixel, int ypos_pixel, uint8_t sel) { + int index; + int y_off = 0; + W25QXX.init(SPI_QUARTER_SPEED); + for (index = 0; index < 10; index++) { // 200*200 + #if HAS_BAK_VIEW_IN_FLASH + if (sel == 1) { + flash_view_Read(bmp_public_buf, 8000); // 20k + } + else { + default_view_Read(bmp_public_buf, DEFAULT_VIEW_MAX_SIZE / 10); // 8k + } + #else + default_view_Read(bmp_public_buf, DEFAULT_VIEW_MAX_SIZE / 10); // 8k + #endif + + SPI_TFT.setWindow(xpos_pixel, y_off * 20 + ypos_pixel, 200, 20); // 200*200 + SPI_TFT.tftio.WriteSequence((uint16_t*)(bmp_public_buf), DEFAULT_VIEW_MAX_SIZE / 20); + + y_off++; + } + W25QXX.init(SPI_QUARTER_SPEED); + } + + void disp_pre_gcode(int xpos_pixel, int ypos_pixel) { + if (gcode_preview_over) gcode_preview(list_file.file_name[sel_id], xpos_pixel, ypos_pixel); + #if HAS_BAK_VIEW_IN_FLASH + if (flash_preview_begin) { + flash_preview_begin = false; + draw_default_preview(xpos_pixel, ypos_pixel, 1); + } + #endif + #if HAS_GCODE_DEFAULT_VIEW_IN_FLASH + if (default_preview_flg) { + draw_default_preview(xpos_pixel, ypos_pixel, 0); + default_preview_flg = false; + } + #endif + } +#endif // HAS_GCODE_PREVIEW + +void print_time_run() { + static uint8_t lastSec = 0; + + if (print_time.seconds >= 60) { + print_time.seconds = 0; + print_time.minutes++; + if (print_time.minutes >= 60) { + print_time.minutes = 0; + print_time.hours++; + } + } + if (disp_state == PRINTING_UI) { + if (lastSec != print_time.seconds) disp_print_time(); + lastSec = print_time.seconds; + } +} + +void GUI_RefreshPage() { + if ((systick_uptime_millis % 1000) == 0) temps_update_flag = true; + if ((systick_uptime_millis % 3000) == 0) printing_rate_update_flag = true; + + switch (disp_state) { + case MAIN_UI: + break; + case EXTRUSION_UI: + if (temps_update_flag) { + temps_update_flag = false; + disp_hotend_temp(); + } + break; + case PRE_HEAT_UI: + if (temps_update_flag) { + temps_update_flag = false; + disp_desire_temp(); + } + break; + case PRINT_READY_UI: + if (temps_update_flag) { + temps_update_flag = false; + lv_temp_refr(); + } + break; + + case PRINT_FILE_UI: break; + + case PRINTING_UI: + if (temps_update_flag) { + temps_update_flag = false; + disp_ext_temp(); + disp_bed_temp(); + disp_fan_speed(); + disp_print_time(); + disp_fan_Zpos(); + } + if (printing_rate_update_flag || marlin_state == MF_SD_COMPLETE) { + printing_rate_update_flag = false; + if (!gcode_preview_over) setProBarRate(); + } + break; + + case OPERATE_UI: break; + + case PAUSE_UI: break; + + case FAN_UI: + if (temps_update_flag) { + temps_update_flag = false; + disp_fan_value(); + } + break; + + case MOVE_MOTOR_UI: break; + + #if ENABLED(MKS_WIFI_MODULE) + case WIFI_UI: + if (temps_update_flag) { + temps_update_flag = false; + disp_wifi_state(); + } + break; + + case BIND_UI: refresh_bind_ui(); break; + #endif + + case FILAMENTCHANGE_UI: + if (temps_update_flag) { + temps_update_flag = false; + disp_filament_temp(); + } + break; + case DIALOG_UI: + filament_dialog_handle(); + TERN_(MKS_WIFI_MODULE, wifi_scan_handle()); + break; + case MESHLEVELING_UI: break; + case HARDWARE_TEST_UI: break; + case WIFI_LIST_UI: + #if ENABLED(MKS_WIFI_MODULE) + if (printing_rate_update_flag) { + disp_wifi_list(); + printing_rate_update_flag = false; + } + #endif + break; + case KEYBOARD_UI: break; + + #if ENABLED(MKS_WIFI_MODULE) + case WIFI_TIPS_UI: + switch (wifi_tips_type) { + case TIPS_TYPE_JOINING: + if (wifi_link_state == WIFI_CONNECTED && strcmp((const char *)wifi_list.wifiConnectedName,(const char *)wifi_list.wifiName[wifi_list.nameIndex]) == 0) { + tips_disp.timer = TIPS_TIMER_STOP; + tips_disp.timer_count = 0; + + lv_clear_wifi_tips(); + wifi_tips_type = TIPS_TYPE_WIFI_CONECTED; + lv_draw_wifi_tips(); + + } + if (tips_disp.timer_count >= SEC_TO_MS(30)) { + tips_disp.timer = TIPS_TIMER_STOP; + tips_disp.timer_count = 0; + lv_clear_wifi_tips(); + wifi_tips_type = TIPS_TYPE_TAILED_JOIN; + lv_draw_wifi_tips(); + } + break; + case TIPS_TYPE_TAILED_JOIN: + if (tips_disp.timer_count >= SEC_TO_MS(3)) { + tips_disp.timer = TIPS_TIMER_STOP; + tips_disp.timer_count = 0; + + last_disp_state = WIFI_TIPS_UI; + lv_clear_wifi_tips(); + lv_draw_wifi_list(); + } + break; + case TIPS_TYPE_WIFI_CONECTED: + if (tips_disp.timer_count >= SEC_TO_MS(3)) { + tips_disp.timer = TIPS_TIMER_STOP; + tips_disp.timer_count = 0; + + last_disp_state = WIFI_TIPS_UI; + lv_clear_wifi_tips(); + lv_draw_wifi(); + } + break; + default: break; + } + break; + #endif + + case BABY_STEP_UI: + if (temps_update_flag) { + temps_update_flag = false; + disp_z_offset_value(); + } + break; + + default: break; + } + + print_time_run(); +} + +void clear_cur_ui() { + last_disp_state = disp_state_stack._disp_state[disp_state_stack._disp_index]; + + switch (disp_state_stack._disp_state[disp_state_stack._disp_index]) { + case PRINT_READY_UI: lv_clear_ready_print(); break; + case PRINT_FILE_UI: lv_clear_print_file(); break; + case PRINTING_UI: lv_clear_printing(); break; + case MOVE_MOTOR_UI: lv_clear_move_motor(); break; + case OPERATE_UI: lv_clear_operation(); break; + case PAUSE_UI: break; + case EXTRUSION_UI: lv_clear_extrusion(); break; + case PRE_HEAT_UI: lv_clear_preHeat(); break; + case CHANGE_SPEED_UI: lv_clear_change_speed(); break; + case FAN_UI: lv_clear_fan(); break; + case SET_UI: lv_clear_set(); break; + case ZERO_UI: lv_clear_home(); break; + case SPRAYER_UI: break; + case MACHINE_UI: break; + case LANGUAGE_UI: lv_clear_language(); break; + case ABOUT_UI: lv_clear_about(); break; + case LOG_UI: break; + case DISK_UI: break; + #if ENABLED(MKS_WIFI_MODULE) + case WIFI_UI: lv_clear_wifi(); break; + #endif + case MORE_UI: lv_clear_more(); break; + case FILETRANSFER_UI: break; + case DIALOG_UI: lv_clear_dialog(); break; + case FILETRANSFERSTATE_UI: break; + case PRINT_MORE_UI: break; + case FILAMENTCHANGE_UI: lv_clear_filament_change(); break; + case LEVELING_UI: lv_clear_manualLevel(); break; + #if ENABLED(MKS_WIFI_MODULE) + case BIND_UI: lv_clear_cloud_bind(); break; + #endif + #if HAS_BED_PROBE + case NOZZLE_PROBE_OFFSET_UI: lv_clear_auto_level_offset_settings(); break; + #endif + case TOOL_UI: lv_clear_tool(); break; + case MESHLEVELING_UI: break; + case HARDWARE_TEST_UI: break; + #if ENABLED(MKS_WIFI_MODULE) + case WIFI_LIST_UI: lv_clear_wifi_list(); break; + #endif + case KEYBOARD_UI: lv_clear_keyboard(); break; + #if ENABLED(MKS_WIFI_MODULE) + case WIFI_TIPS_UI: lv_clear_wifi_tips(); break; + #endif + case MACHINE_PARA_UI: lv_clear_machine_para(); break; + case MACHINE_SETTINGS_UI: lv_clear_machine_settings(); break; + case TEMPERATURE_SETTINGS_UI: break; + case MOTOR_SETTINGS_UI: lv_clear_motor_settings(); break; + case MACHINETYPE_UI: break; + case STROKE_UI: break; + case HOME_DIR_UI: break; + case ENDSTOP_TYPE_UI: break; + case FILAMENT_SETTINGS_UI: break; + case LEVELING_SETTIGNS_UI: break; + case LEVELING_PARA_UI: lv_clear_level_settings(); break; + case DELTA_LEVELING_PARA_UI: break; + case MANUAL_LEVELING_POSIGION_UI: lv_clear_tramming_pos_settings(); break; + case MAXFEEDRATE_UI: lv_clear_max_feedrate_settings(); break; + case STEPS_UI: lv_clear_step_settings(); break; + case ACCELERATION_UI: lv_clear_acceleration_settings(); break; + case JERK_UI: TERN_(HAS_CLASSIC_JERK, lv_clear_jerk_settings()); break; + case MOTORDIR_UI: break; + case HOMESPEED_UI: break; + case NOZZLE_CONFIG_UI: break; + case HOTBED_CONFIG_UI: break; + case ADVANCED_UI: lv_clear_advance_settings(); break; + case DOUBLE_Z_UI: break; + case ENABLE_INVERT_UI: break; + case NUMBER_KEY_UI: lv_clear_number_key(); break; + case BABY_STEP_UI: lv_clear_baby_stepping(); break; + case PAUSE_POS_UI: lv_clear_pause_position(); break; + #if HAS_TRINAMIC_CONFIG + case TMC_CURRENT_UI: lv_clear_tmc_current_settings(); break; + #endif + case EEPROM_SETTINGS_UI: lv_clear_eeprom_settings(); break; + #if HAS_STEALTHCHOP + case TMC_MODE_UI: lv_clear_tmc_step_mode_settings(); break; + #endif + #if ENABLED(MKS_WIFI_MODULE) + case WIFI_SETTINGS_UI: lv_clear_wifi_settings(); break; + #endif + #if USE_SENSORLESS + case HOMING_SENSITIVITY_UI: lv_clear_homing_sensitivity_settings(); break; + #endif + #if HAS_ROTARY_ENCODER + case ENCODER_SETTINGS_UI: lv_clear_encoder_settings(); break; + #endif + #if ENABLED(TOUCH_SCREEN_CALIBRATION) + case TOUCH_CALIBRATION_UI: lv_clear_touch_calibration_screen(); break; + #endif + #if ENABLED(MULTI_VOLUME) + case MEDIA_SELECT_UI: lv_clear_media_select(); break; + #endif + default: break; + } +} + +void draw_return_ui() { + if (disp_state_stack._disp_index > 0) { + disp_state_stack._disp_index--; + + switch (disp_state_stack._disp_state[disp_state_stack._disp_index]) { + case PRINT_READY_UI: lv_draw_ready_print(); break; + case PRINT_FILE_UI: lv_draw_print_file(); break; + + case PRINTING_UI: if (gCfgItems.from_flash_pic) + flash_preview_begin = true; + else + default_preview_flg = true; + lv_draw_printing(); + break; + + case MOVE_MOTOR_UI: lv_draw_move_motor(); break; + case OPERATE_UI: lv_draw_operation(); break; + case PAUSE_UI: break; + case EXTRUSION_UI: lv_draw_extrusion(); break; + case PRE_HEAT_UI: lv_draw_preHeat(); break; + case CHANGE_SPEED_UI: lv_draw_change_speed(); break; + case FAN_UI: lv_draw_fan(); break; + case SET_UI: lv_draw_set(); break; + case ZERO_UI: lv_draw_home(); break; + case SPRAYER_UI: break; + case MACHINE_UI: break; + case LANGUAGE_UI: lv_draw_language(); break; + case ABOUT_UI: lv_draw_about(); break; + + case CALIBRATE_UI: break; + case DISK_UI: break; + #if ENABLED(MKS_WIFI_MODULE) + case WIFI_UI: lv_draw_wifi(); break; + #endif + case MORE_UI: break; + case PRINT_MORE_UI: lv_draw_more(); break; + case FILAMENTCHANGE_UI: lv_draw_filament_change(); break; + case LEVELING_UI: lv_draw_manualLevel(); break; + #if ENABLED(MKS_WIFI_MODULE) + case BIND_UI: lv_draw_cloud_bind(); break; + #endif + #if HAS_BED_PROBE + case NOZZLE_PROBE_OFFSET_UI: lv_draw_auto_level_offset_settings(); break; + #endif + case TOOL_UI: lv_draw_tool(); break; + case GCODE_UI: lv_draw_gcode(); break; + case MESHLEVELING_UI: break; + case HARDWARE_TEST_UI: break; + #if ENABLED(MKS_WIFI_MODULE) + case WIFI_LIST_UI: lv_draw_wifi_list(); break; + #endif + case KEYBOARD_UI: lv_draw_keyboard(); break; + #if ENABLED(MKS_WIFI_MODULE) + case WIFI_TIPS_UI: lv_draw_wifi_tips(); break; + #endif + case MACHINE_PARA_UI: lv_draw_machine_para(); break; + case MACHINE_SETTINGS_UI: lv_draw_machine_settings(); break; + case TEMPERATURE_SETTINGS_UI: break; + case MOTOR_SETTINGS_UI: lv_draw_motor_settings(); break; + case MACHINETYPE_UI: break; + case STROKE_UI: break; + case HOME_DIR_UI: break; + case ENDSTOP_TYPE_UI: break; + case FILAMENT_SETTINGS_UI: lv_draw_filament_settings(); break; + case LEVELING_SETTIGNS_UI: break; + case LEVELING_PARA_UI: lv_draw_level_settings(); break; + case DELTA_LEVELING_PARA_UI: break; + case MANUAL_LEVELING_POSIGION_UI: lv_draw_tramming_pos_settings(); break; + case MAXFEEDRATE_UI: lv_draw_max_feedrate_settings(); break; + case STEPS_UI: lv_draw_step_settings(); break; + case ACCELERATION_UI: lv_draw_acceleration_settings(); break; + #if HAS_CLASSIC_JERK + case JERK_UI: lv_draw_jerk_settings(); break; + #endif + case MOTORDIR_UI: break; + case HOMESPEED_UI: break; + case NOZZLE_CONFIG_UI: break; + case HOTBED_CONFIG_UI: break; + case ADVANCED_UI: lv_draw_advance_settings(); break; + case DOUBLE_Z_UI: break; + case ENABLE_INVERT_UI: break; + case NUMBER_KEY_UI: lv_draw_number_key(); break; + case DIALOG_UI: break; + case BABY_STEP_UI: lv_draw_baby_stepping(); break; + case PAUSE_POS_UI: lv_draw_pause_position(); break; + #if HAS_TRINAMIC_CONFIG + case TMC_CURRENT_UI: lv_draw_tmc_current_settings(); break; + #endif + case EEPROM_SETTINGS_UI: lv_draw_eeprom_settings(); break; + #if HAS_STEALTHCHOP + case TMC_MODE_UI: lv_draw_tmc_step_mode_settings(); break; + #endif + #if ENABLED(MKS_WIFI_MODULE) + case WIFI_SETTINGS_UI: lv_draw_wifi_settings(); break; + #endif + #if USE_SENSORLESS + case HOMING_SENSITIVITY_UI: lv_draw_homing_sensitivity_settings(); break; + #endif + #if HAS_ROTARY_ENCODER + case ENCODER_SETTINGS_UI: lv_draw_encoder_settings(); break; + #endif + default: break; + } + } +} + +// Set the same image for both Released and Pressed +void lv_imgbtn_set_src_both(lv_obj_t *imgbtn, const void *src) { + lv_imgbtn_set_src(imgbtn, LV_BTN_STATE_REL, src); + lv_imgbtn_set_src(imgbtn, LV_BTN_STATE_PR, src); +} + +// Use label style for the image button +void lv_imgbtn_use_label_style(lv_obj_t *imgbtn) { + lv_imgbtn_set_style(imgbtn, LV_BTN_STATE_REL, &tft_style_label_rel); + lv_imgbtn_set_style(imgbtn, LV_BTN_STATE_PR, &tft_style_label_pre); +} + +// Use label style for the button +void lv_btn_use_label_style(lv_obj_t *btn) { + lv_btn_set_style(btn, LV_BTN_STYLE_REL, &tft_style_label_rel); + lv_btn_set_style(btn, LV_BTN_STYLE_PR, &tft_style_label_pre); +} + +// Use button style for the button +void lv_btn_use_button_style(lv_obj_t *btn) { + lv_btn_set_style(btn, LV_BTN_STYLE_REL, &style_btn_rel); + lv_btn_set_style(btn, LV_BTN_STYLE_PR, &style_btn_pr); +} + +// Use a single style for both Released and Pressed +void lv_btn_set_style_both(lv_obj_t *btn, lv_style_t *style) { + lv_btn_set_style(btn, LV_BTN_STYLE_REL, style); + lv_btn_set_style(btn, LV_BTN_STYLE_PR, style); +} + +// Create a screen +lv_obj_t* lv_screen_create(DISP_STATE newScreenType, const char *title) { + lv_obj_t *scr = lv_obj_create(nullptr, nullptr); + lv_obj_set_style(scr, &tft_style_scr); + lv_scr_load(scr); + lv_obj_clean(scr); + + // breadcrumbs + if (disp_state_stack._disp_state[disp_state_stack._disp_index] != newScreenType) { + disp_state_stack._disp_index++; + disp_state_stack._disp_state[disp_state_stack._disp_index] = newScreenType; + } + disp_state = newScreenType; + + // title + lv_obj_t *titleLabel = nullptr; + if (!title) + titleLabel = lv_label_create(scr, TITLE_XPOS, TITLE_YPOS, creat_title_text()); + else if (title[0] != '\0') + titleLabel = lv_label_create(scr, TITLE_XPOS, TITLE_YPOS, title); + if (titleLabel) + lv_obj_set_style(titleLabel, &tft_style_label_rel); + + lv_refr_now(lv_refr_get_disp_refreshing()); + + return scr; +} + +// Create an empty label +lv_obj_t* lv_label_create_empty(lv_obj_t *par) { + lv_obj_t *label = lv_label_create(par, (lv_obj_t*)nullptr); + return label; +} + +// Create a label with style and text +lv_obj_t* lv_label_create(lv_obj_t *par, const char *text) { + lv_obj_t *label = lv_label_create_empty(par); + if (text) lv_label_set_text(label, text); + lv_obj_set_style(label, &tft_style_label_rel); + return label; +} + +// Create a label with style, position, and text +lv_obj_t* lv_label_create(lv_obj_t *par, lv_coord_t x, lv_coord_t y, const char *text) { + lv_obj_t *label = lv_label_create(par, text); + lv_obj_set_pos(label, x, y); + return label; +} + +// Create a button with callback, ID, and Style. +lv_obj_t* lv_btn_create(lv_obj_t *par, lv_event_cb_t cb, const int id/*=0*/, lv_style_t *style/*=&style_para_value*/) { + lv_obj_t *btn = lv_btn_create(par, nullptr); + if (id) + lv_obj_set_event_cb_mks(btn, cb, id, "", 0); + else + lv_obj_set_event_cb(btn, cb); + lv_btn_set_style_both(btn, style); + return btn; +} + +// Create a button with callback and ID, with label style. +lv_obj_t* lv_label_btn_create(lv_obj_t *par, lv_event_cb_t cb, const int id/*=0*/) { + lv_obj_t *btn = lv_btn_create(par, cb, id, nullptr); + lv_btn_use_label_style(btn); + return btn; +} + +// Create a button with callback and ID, with button style. +lv_obj_t* lv_button_btn_create(lv_obj_t *par, lv_event_cb_t cb, const int id/*=0*/) { + lv_obj_t *btn = lv_btn_create(par, cb, id, nullptr); + lv_btn_use_button_style(btn); + return btn; +} + +// Create a button with position, size, callback, ID, and style. +lv_obj_t* lv_btn_create(lv_obj_t *par, lv_coord_t x, lv_coord_t y, lv_coord_t w, lv_coord_t h, lv_event_cb_t cb, const int id, lv_style_t *style) { + lv_obj_t *btn = lv_btn_create(par, cb, id, style); + lv_obj_set_pos(btn, x, y); + lv_obj_set_size(btn, w, h); + return btn; +} + +// Create a button with position, size, callback, and ID. Style set to style_para_value. +lv_obj_t* lv_btn_create(lv_obj_t *par, lv_coord_t x, lv_coord_t y, lv_coord_t w, lv_coord_t h, lv_event_cb_t cb, const int id/*=0*/) { + lv_obj_t *btn = lv_btn_create(par, x, y, w, h, cb, id, &style_para_value); + return btn; +} + +// Create a button with position, size, callback, and ID, with label style. +lv_obj_t* lv_label_btn_create(lv_obj_t *par, lv_coord_t x, lv_coord_t y, lv_coord_t w, lv_coord_t h, lv_event_cb_t cb, const int id/*=0*/) { + lv_obj_t *btn = lv_label_btn_create(par, cb, id); + lv_obj_set_pos(btn, x, y); + lv_obj_set_size(btn, w, h); + return btn; +} + +// Create a button with position, size, callback, and ID, with label style. +lv_obj_t* lv_button_btn_create(lv_obj_t *par, lv_coord_t x, lv_coord_t y, lv_coord_t w, lv_coord_t h, lv_event_cb_t cb, const int id/*=0*/) { + lv_obj_t *btn = lv_button_btn_create(par, cb, id); + lv_obj_set_pos(btn, x, y); + lv_obj_set_size(btn, w, h); + return btn; +} + +// Create a button with callback and ID. Style set to style_para_back. +lv_obj_t* lv_btn_create_back(lv_obj_t *par, lv_event_cb_t cb, const int id/*=0*/) { + return lv_btn_create(par, cb, id, &style_para_back); +} +// Create a button with position, size, callback, and ID. Style set to style_para_back. +lv_obj_t* lv_btn_create_back(lv_obj_t *par, lv_coord_t x, lv_coord_t y, lv_coord_t w, lv_coord_t h, lv_event_cb_t cb, const int id/*=0*/) { + lv_obj_t *btn = lv_btn_create_back(par, cb, id); + lv_obj_set_pos(btn, x, y); + lv_obj_set_size(btn, w, h); + return btn; +} + +// Create an image button with image, callback, and ID. Use label style. +lv_obj_t* lv_imgbtn_create(lv_obj_t *par, const char *img, lv_event_cb_t cb, const int id/*=0*/) { + lv_obj_t *btn = lv_imgbtn_create(par, nullptr); + if (img) lv_imgbtn_set_src_both(btn, img); + if (id) + lv_obj_set_event_cb_mks(btn, cb, id, "", 0); + else + lv_obj_set_event_cb(btn, cb); + lv_imgbtn_use_label_style(btn); + lv_btn_set_layout(btn, LV_LAYOUT_OFF); + return btn; +} + +// Create an image button with image, position, callback, and ID. Use label style. +lv_obj_t* lv_imgbtn_create(lv_obj_t *par, const char *img, lv_coord_t x, lv_coord_t y, lv_event_cb_t cb, const int id/*=0*/) { + lv_obj_t *btn = lv_imgbtn_create(par, img, cb, id); + lv_obj_set_pos(btn, x, y); + return btn; +} + +lv_obj_t* lv_big_button_create(lv_obj_t *par, const char *img, const char *text, lv_coord_t x, lv_coord_t y, lv_event_cb_t cb, const int id, bool centerLabel) { + lv_obj_t *btn = lv_imgbtn_create(par, img, cb, id); + lv_obj_set_pos(btn, x, y); + lv_obj_t *label = lv_label_create_empty(btn); + if (gCfgItems.multiple_language) { + lv_label_set_text(label, text); + if (centerLabel) + lv_obj_align(label, btn, LV_ALIGN_CENTER, 0, 0); + else + lv_obj_align(label, btn, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + if (TERN0(HAS_ROTARY_ENCODER, gCfgItems.encoder_enable)) + lv_group_add_obj(g, btn); + return btn; +} + +lv_obj_t* lv_screen_menu_item(lv_obj_t *par, const char *text, lv_coord_t x, lv_coord_t y, lv_event_cb_t cb, const int id, const int index, bool drawArrow) { + lv_obj_t *btn = lv_btn_create(par, nullptr); /*Add a button the current screen*/ + lv_obj_set_pos(btn, x, y); /*Set its position*/ + lv_obj_set_size(btn, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ + if (id > -1) lv_obj_set_event_cb_mks(btn, cb, id, "", 0); + lv_btn_use_label_style(btn); + lv_btn_set_layout(btn, LV_LAYOUT_OFF); + lv_obj_t *label = lv_label_create_empty(btn); /*Add a label to the button*/ + if (gCfgItems.multiple_language) { + lv_label_set_text(label, text); + lv_obj_align(label, btn, LV_ALIGN_IN_LEFT_MID, 0, 0); + } + if (TERN0(HAS_ROTARY_ENCODER, gCfgItems.encoder_enable)) + lv_group_add_obj(g, btn); + + if (drawArrow) (void)lv_imgbtn_create(par, "F:/bmp_arrow.bin", x + PARA_UI_SIZE_X, y + PARA_UI_ARROW_V, cb, id); + + lv_obj_t *line1 = lv_line_create(par, nullptr); + lv_ex_line(line1, line_points[index]); + + return btn; +} + +lv_obj_t* lv_screen_menu_item_1_edit(lv_obj_t *par, const char *text, lv_coord_t x, lv_coord_t y, lv_event_cb_t cb, const int id, const int index, const char *editValue) { + lv_obj_t *btn = lv_screen_menu_item(par, text, x, y, cb, -1, index, false); + lv_obj_t *btnValue = lv_btn_create(par, PARA_UI_VALUE_POS_X, y + PARA_UI_VALUE_V, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE, cb, id); + lv_obj_t *labelValue = lv_label_create_empty(btnValue); + lv_label_set_text(labelValue, editValue); + lv_obj_align(labelValue, btnValue, LV_ALIGN_CENTER, 0, 0); + return btn; +} + +lv_obj_t* lv_screen_menu_item_2_edit(lv_obj_t *par, const char *text, lv_coord_t x, lv_coord_t y, lv_event_cb_t cb, const int id, const int index, const char *editValue, const int idEdit2, const char *editValue2) { + lv_obj_t *btn = lv_screen_menu_item(par, text, x, y, cb, -1, index, false); + + lv_obj_t *btnValue = lv_btn_create(par, PARA_UI_VALUE_POS_X_2, y + PARA_UI_VALUE_V_2, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE, cb, idEdit2); + lv_obj_t *labelValue = lv_label_create_empty(btnValue); + lv_label_set_text(labelValue, editValue2); + lv_obj_align(labelValue, btnValue, LV_ALIGN_CENTER, 0, 0); + + btnValue = lv_btn_create(par, PARA_UI_VALUE_POS_X, y + PARA_UI_VALUE_V, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE, cb, id); + labelValue = lv_label_create_empty(btnValue); + lv_label_set_text(labelValue, editValue); + lv_obj_align(labelValue, btnValue, LV_ALIGN_CENTER, 0, 0); + + return btn; +} + +lv_obj_t* lv_screen_menu_item_onoff(lv_obj_t *par, const char *text, lv_coord_t x, lv_coord_t y, lv_event_cb_t cb, const int id, const int index, const bool curValue) { + lv_screen_menu_item(par, text, x, y, cb, -1, index, false); + lv_obj_t *btnValue = lv_imgbtn_create(par, curValue ? "F:/bmp_enable.bin" : "F:/bmp_disable.bin", PARA_UI_STATE_POS_X, y + PARA_UI_STATE_V, cb, id); + lv_obj_t *labelValue = lv_label_create_empty(btnValue); + lv_label_set_text(labelValue, curValue ? machine_menu.enable : machine_menu.disable); + lv_obj_align(labelValue, btnValue, LV_ALIGN_CENTER, 0, 0); + return btnValue; +} + +void lv_screen_menu_item_onoff_update(lv_obj_t *btn, const bool curValue) { + lv_imgbtn_set_src_both(btn, curValue ? "F:/bmp_enable.bin" : "F:/bmp_disable.bin"); + lv_label_set_text((lv_obj_t*)btn->child_ll.head, curValue ? machine_menu.enable : machine_menu.disable); +} + + +#if ENABLED(SDSUPPORT) + + void sd_detection() { + static bool last_sd_status; + const bool sd_status = IS_SD_INSERTED(); + if (sd_status != last_sd_status) { + last_sd_status = sd_status; + if (sd_status) card.mount(); else card.release(); + } + } + +#endif + +void lv_ex_line(lv_obj_t *line, lv_point_t *points) { + // Copy the previous line and apply the new style + lv_line_set_points(line, points, 2); // Set the points + lv_line_set_style(line, LV_LINE_STYLE_MAIN, &style_line); + lv_obj_align(line, nullptr, LV_ALIGN_IN_TOP_MID, 0, 0); +} + +extern volatile uint32_t systick_uptime_millis; + +void print_time_count() { + if ((systick_uptime_millis % 1000) == 0) + if (print_time.start == 1) print_time.seconds++; +} + +void LV_TASK_HANDLER() { + lv_task_handler(); + + #if BOTH(MKS_TEST, SDSUPPORT) + if (mks_test_flag == 0x1E) mks_hardware_test(); + #endif + + TERN_(HAS_GCODE_PREVIEW, disp_pre_gcode(2, 36)); + + GUI_RefreshPage(); + + TERN_(MKS_WIFI_MODULE, get_wifi_commands()); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_update_encoder(); + #endif +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ui.h b/Marlin/src/lcd/extui/mks_ui/draw_ui.h new file mode 100644 index 000000000000..37b19ebd46bd --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_ui.h @@ -0,0 +1,542 @@ +/** + * 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 + +#include + +#include +#include + +// the colors of the last MKS Ui +#undef LV_COLOR_BACKGROUND +#define LV_COLOR_BACKGROUND LV_COLOR_MAKE(0x1A, 0x1A, 0x1A) + +#define TFT_LV_PARA_BACK_BODY_COLOR LV_COLOR_MAKE(0x4A, 0x52, 0xFF) + +#include "tft_lvgl_configuration.h" +#include "tft_multi_language.h" +#include "pic_manager.h" +#include "draw_ready_print.h" +#include "draw_language.h" +#include "draw_set.h" +#include "draw_tool.h" +#include "draw_print_file.h" +#include "draw_dialog.h" +#include "draw_printing.h" +#include "draw_operation.h" +#include "draw_preHeat.h" +#include "draw_extrusion.h" +#include "draw_home.h" +#include "draw_gcode.h" +#include "draw_more.h" +#include "draw_move_motor.h" +#include "draw_fan.h" +#include "draw_about.h" +#include "draw_change_speed.h" +#include "draw_manuaLevel.h" +#include "draw_error_message.h" +#include "printer_operation.h" +#include "draw_machine_para.h" +#include "draw_machine_settings.h" +#include "draw_motor_settings.h" +#include "draw_advance_settings.h" +#include "draw_acceleration_settings.h" +#include "draw_number_key.h" +#include "draw_jerk_settings.h" +#include "draw_pause_position.h" +#include "draw_step_settings.h" +#include "draw_tmc_current_settings.h" +#include "draw_eeprom_settings.h" +#include "draw_max_feedrate_settings.h" +#include "draw_tmc_step_mode_settings.h" +#include "draw_level_settings.h" +#include "draw_tramming_pos_settings.h" +#include "draw_auto_level_offset_settings.h" +#include "draw_filament_change.h" +#include "draw_filament_settings.h" +#include "draw_homing_sensitivity_settings.h" +#include "draw_baby_stepping.h" +#include "draw_keyboard.h" +#include "draw_media_select.h" +#include "draw_encoder_settings.h" + +#include "../../../inc/MarlinConfigPre.h" + +#if ENABLED(MKS_WIFI_MODULE) + #include "wifiSerial.h" + #include "wifi_module.h" + #include "wifi_upload.h" + #include "draw_wifi_settings.h" + #include "draw_wifi.h" + #include "draw_wifi_list.h" + #include "draw_wifi_tips.h" + #include "draw_cloud_bind.h" +#endif + +#define ESP_WIFI 0x02 +#define AP_MODEL 0x01 +#define STA_MODEL 0x02 + +#define FILE_SYS_USB 0 +#define FILE_SYS_SD 1 + +#define TICK_CYCLE 1 + +#define PARA_SEL_ICON_TEXT_COLOR LV_COLOR_MAKE(0x4A, 0x52, 0xFF); + +#define TFT35 + +#ifdef TFT35 + + #define TFT_WIDTH 480 + #define TFT_HEIGHT 320 + + #define titleHeight 36 // TFT_screen.title_high + #define INTERVAL_H 2 // TFT_screen.gap_h // 2 + #define INTERVAL_V 2 // TFT_screen.gap_v // 2 + #define BTN_X_PIXEL 117 // TFT_screen.btn_x_pixel + #define BTN_Y_PIXEL 140 // TFT_screen.btn_y_pixel + + #define SIMPLE_FIRST_PAGE_GRAP 30 + + #define BUTTON_TEXT_Y_OFFSET -20 + + #define TITLE_XPOS 3 // TFT_screen.title_xpos + #define TITLE_YPOS 5 // TFT_screen.title_ypos + + #define FILE_BTN_CNT 6 + + #define OTHER_BTN_XPIEL 117 + #define OTHER_BTN_YPIEL 92 + + #define FILE_PRE_PIC_X_OFFSET 8 + #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) + + // machine parameter ui + #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_ARROW_V 12 + + #define PARA_UI_BACL_POS_X 400 + #define PARA_UI_BACL_POS_Y 270 + + #define PARA_UI_TURN_PAGE_POS_X 320 + #define PARA_UI_TURN_PAGE_POS_Y 270 + + #define PARA_UI_VALUE_SIZE_X 370 + #define PARA_UI_VALUE_POS_X 400 + #define PARA_UI_VALUE_V 5 + + #define PARA_UI_STATE_POS_X 380 + #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_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 QRCODE_X 20 + #define QRCODE_Y 40 + #define QRCODE_WIDTH 160 + +#else // ifdef TFT35 + + #define TFT_WIDTH 320 + #define TFT_HEIGHT 240 + +#endif // ifdef TFT35 + +#ifdef __cplusplus + extern "C" { /* C-declarations for C++ */ +#endif + +extern char public_buf_m[100]; +extern char public_buf_l[30]; + +typedef struct { + uint32_t spi_flash_flag; + uint8_t disp_rotation_180; + bool multiple_language; + uint8_t language; + uint8_t leveling_mode; + bool from_flash_pic; + bool finish_power_off; + bool pause_reprint; + uint8_t wifi_mode_sel; + uint8_t fileSysType; + uint8_t wifi_type; + bool cloud_enable, + encoder_enable; + xy_int_t trammingPos[5]; + int filamentchange_load_length, + filamentchange_load_speed, + filamentchange_unload_length, + filamentchange_unload_speed; + celsius_t filament_limit_temp; + float pausePosX, pausePosY, pausePosZ; + uint32_t curFilesize; +} CFG_ITMES; + +typedef struct { + uint8_t curTempType:1, + extruderIndex:3, + stepHeat:4, + extruderIndexBak:4; + bool leveling_first_time:1, + para_ui_page:1, + configWifi:1, + command_send:1, + filament_load_heat_flg:1, + filament_heat_completed_load:1, + filament_unload_heat_flg:1, + filament_heat_completed_unload:1, + filament_loading_completed:1, + filament_unloading_completed:1, + filament_loading_time_flg:1, + filament_unloading_time_flg:1; + uint8_t wifi_name[32]; + uint8_t wifi_key[64]; + uint8_t cloud_hostUrl[96]; + uint8_t extruStep; + uint8_t extruSpeed; + uint8_t print_state; + uint8_t stepPrintSpeed; + uint8_t waitEndMoves; + uint8_t dialogType; + uint8_t F[4]; + uint8_t filament_rate; + uint16_t moveSpeed; + uint16_t cloud_port; + uint16_t moveSpeed_bak; + uint32_t totalSend; + uint32_t filament_loading_time, + filament_unloading_time, + filament_loading_time_cnt, + filament_unloading_time_cnt; + float move_dist; + celsius_t hotendTargetTempBak; + float current_x_position_bak, + current_y_position_bak, + current_z_position_bak, + current_e_position_bak; +} UI_CFG; + +typedef enum { + MAIN_UI, + PRINT_READY_UI, + PRINT_FILE_UI, + PRINTING_UI, + MOVE_MOTOR_UI, + OPERATE_UI, + PAUSE_UI, + EXTRUSION_UI, + FAN_UI, + PRE_HEAT_UI, + CHANGE_SPEED_UI, + TEMP_UI, + SET_UI, + ZERO_UI, + SPRAYER_UI, + MACHINE_UI, + LANGUAGE_UI, + ABOUT_UI, + LOG_UI, + DISK_UI, + CALIBRATE_UI, + DIALOG_UI, + WIFI_UI, + MORE_UI, + FILETRANSFER_UI, + FILETRANSFERSTATE_UI, + PRINT_MORE_UI, + FILAMENTCHANGE_UI, + LEVELING_UI, + MESHLEVELING_UI, + BIND_UI, + #if HAS_BED_PROBE + NOZZLE_PROBE_OFFSET_UI, + #endif + TOOL_UI, + HARDWARE_TEST_UI, + WIFI_LIST_UI, + KEYBOARD_UI, + WIFI_TIPS_UI, + MACHINE_PARA_UI, + MACHINE_SETTINGS_UI, + TEMPERATURE_SETTINGS_UI, + MOTOR_SETTINGS_UI, + MACHINETYPE_UI, + STROKE_UI, + HOME_DIR_UI, + ENDSTOP_TYPE_UI, + FILAMENT_SETTINGS_UI, + LEVELING_SETTIGNS_UI, + LEVELING_PARA_UI, + DELTA_LEVELING_PARA_UI, + MANUAL_LEVELING_POSIGION_UI, + MAXFEEDRATE_UI, + STEPS_UI, + ACCELERATION_UI, + JERK_UI, + MOTORDIR_UI, + HOMESPEED_UI, + NOZZLE_CONFIG_UI, + HOTBED_CONFIG_UI, + ADVANCED_UI, + DOUBLE_Z_UI, + ENABLE_INVERT_UI, + NUMBER_KEY_UI, + BABY_STEP_UI, + ERROR_MESSAGE_UI, + PAUSE_POS_UI, + TMC_CURRENT_UI, + TMC_MODE_UI, + EEPROM_SETTINGS_UI, + WIFI_SETTINGS_UI, + HOMING_SENSITIVITY_UI, + ENCODER_SETTINGS_UI, + TOUCH_CALIBRATION_UI, + GCODE_UI, + MEDIA_SELECT_UI, +} DISP_STATE; + +typedef struct { + DISP_STATE _disp_state[100]; + int _disp_index; +} DISP_STATE_STACK; + +typedef struct { + int16_t days; + uint16_t hours; + uint8_t minutes; + volatile int8_t seconds; + int8_t ms_10; + int8_t start; +} PRINT_TIME; +extern PRINT_TIME print_time; + +typedef enum { + PrintAcceleration, + RetractAcceleration, + TravelAcceleration, + XAcceleration, + YAcceleration, + ZAcceleration, + E0Acceleration, + E1Acceleration, + + XMaxFeedRate, + YMaxFeedRate, + ZMaxFeedRate, + E0MaxFeedRate, + E1MaxFeedRate, + + XJerk, + YJerk, + ZJerk, + EJerk, + + Xstep, + Ystep, + Zstep, + E0step, + E1step, + + Xcurrent, + Ycurrent, + Zcurrent, + E0current, + E1current, + + pause_pos_x, + pause_pos_y, + pause_pos_z, + + level_pos_x1, + level_pos_y1, + level_pos_x2, + level_pos_y2, + level_pos_x3, + level_pos_y3, + level_pos_x4, + level_pos_y4, + level_pos_x5, + level_pos_y5, + #if HAS_BED_PROBE + x_offset, + y_offset, + z_offset, + #endif + load_length, + load_speed, + unload_length, + unload_speed, + filament_temp, + + x_sensitivity, + y_sensitivity, + z_sensitivity, + z2_sensitivity +} num_key_value_state; +extern num_key_value_state value; + +typedef enum { + wifiName, + wifiPassWord, + wifiConfig, + autoLevelGcodeCommand, + GCodeCommand, +} keyboard_value_state; +extern keyboard_value_state keyboard_value; + +extern CFG_ITMES gCfgItems; +extern UI_CFG uiCfg; +extern DISP_STATE disp_state; +extern DISP_STATE last_disp_state; +extern DISP_STATE_STACK disp_state_stack; + +extern lv_style_t tft_style_scr; +extern lv_style_t tft_style_label_pre; +extern lv_style_t tft_style_label_rel; +extern lv_style_t style_line; +extern lv_style_t style_para_value_pre; +extern lv_style_t style_para_value_rel; +extern lv_style_t style_num_key_pre; +extern lv_style_t style_num_key_rel; +extern lv_style_t style_num_text; +extern lv_style_t style_sel_text; +extern lv_style_t style_para_value; +extern lv_style_t style_para_back; +extern lv_style_t lv_bar_style_indic; +extern lv_style_t style_btn_pr; +extern lv_style_t style_btn_rel; + +extern lv_point_t line_points[4][2]; + +void gCfgItems_init(); +void ui_cfg_init(); +void tft_style_init(); +extern char *creat_title_text(); +void preview_gcode_prehandle(char *path); +void update_spi_flash(); +void update_gcode_command(int addr,uint8_t *s); +void get_gcode_command(int addr,uint8_t *d); +void lv_serial_capt_hook(void *, uint8_t); +void lv_eom_hook(void *); +#if HAS_GCODE_PREVIEW + void disp_pre_gcode(int xpos_pixel, int ypos_pixel); +#endif +void GUI_RefreshPage(); +void clear_cur_ui(); +void draw_return_ui(); +void sd_detection(); +void gCfg_to_spiFlah(); +void print_time_count(); + +void LV_TASK_HANDLER(); +void lv_ex_line(lv_obj_t *line, lv_point_t *points); + +#ifdef __cplusplus + } /* C-declarations for C++ */ +#endif + +// Set the same image for both Released and Pressed +void lv_imgbtn_set_src_both(lv_obj_t *imgbtn, const void *src); + +// Set label styles for Released and Pressed +void lv_imgbtn_use_label_style(lv_obj_t *imgbtn); + +// Set label styles for Released and Pressed +void lv_btn_use_label_style(lv_obj_t *btn); + +// Set the same style for both Released and Pressed +void lv_btn_set_style_both(lv_obj_t *btn, lv_style_t *style); + +// Create a screen +lv_obj_t* lv_screen_create(DISP_STATE newScreenType, const char *title = nullptr); + +// Create an empty label +lv_obj_t* lv_label_create_empty(lv_obj_t *par); + +// Create a label with style and text +lv_obj_t* lv_label_create(lv_obj_t *par, const char *text); + +// Create a label with style, position, and text +lv_obj_t* lv_label_create(lv_obj_t *par, lv_coord_t x, lv_coord_t y, const char *text); + +// Create a button with callback, ID, and Style. +lv_obj_t* lv_btn_create(lv_obj_t *par, lv_event_cb_t cb, const int id, lv_style_t *style=&style_para_value); + +// Create a button with callback and ID, with label style. +lv_obj_t* lv_label_btn_create(lv_obj_t *par, lv_event_cb_t cb, const int id=0); + +// Create a button with callback and ID, with button style. +lv_obj_t* lv_button_btn_create(lv_obj_t *par, lv_event_cb_t cb, const int id=0); + +// Create a button with position, size, callback, ID, and style. +lv_obj_t* lv_btn_create(lv_obj_t *par, lv_coord_t x, lv_coord_t y, lv_coord_t w, lv_coord_t h, lv_event_cb_t cb, const int id, lv_style_t *style); + +// Create a button with position, size, callback, and ID. Style set to style_para_value. +lv_obj_t* lv_btn_create(lv_obj_t *par, lv_coord_t x, lv_coord_t y, lv_coord_t w, lv_coord_t h, lv_event_cb_t cb, const int id=0); + +// Create a button with position, size, callback, and ID, with label style. +lv_obj_t* lv_label_btn_create(lv_obj_t *par, lv_coord_t x, lv_coord_t y, lv_coord_t w, lv_coord_t h, lv_event_cb_t cb, const int id=0); + +// Create a button with position, size, callback, and ID, with button style. +lv_obj_t* lv_button_btn_create(lv_obj_t *par, lv_coord_t x, lv_coord_t y, lv_coord_t w, lv_coord_t h, lv_event_cb_t cb, const int id=0); + +// Create a button with callback and ID. Style set to style_para_back. +lv_obj_t* lv_btn_create_back(lv_obj_t *par, lv_event_cb_t cb, const int id=0); + +// Create a button with position, size, callback, and ID. Style set to style_para_back. +lv_obj_t* lv_btn_create_back(lv_obj_t *par, lv_coord_t x, lv_coord_t y, lv_coord_t w, lv_coord_t h, lv_event_cb_t cb, const int id=0); + +// Create an image button with image, callback, and ID. Use label style. +lv_obj_t* lv_imgbtn_create(lv_obj_t *par, const char *img, lv_event_cb_t cb, const int id=0); + +// Create an image button with image, position, callback, and ID. Use label style. +lv_obj_t* lv_imgbtn_create(lv_obj_t *par, const char *img, lv_coord_t x, lv_coord_t y, lv_event_cb_t cb, const int id=0); + +// Create a big image button with a label, follow the LVGL UI standard. +lv_obj_t* lv_big_button_create(lv_obj_t *par, const char *img, const char *text, lv_coord_t x, lv_coord_t y, lv_event_cb_t cb, const int id, bool centerLabel = false); + +// Create a menu item, follow the LVGL UI standard. +lv_obj_t* lv_screen_menu_item(lv_obj_t *par, const char *text, lv_coord_t x, lv_coord_t y, lv_event_cb_t cb, const int id, const int index, bool drawArrow = true); +lv_obj_t* lv_screen_menu_item_1_edit(lv_obj_t *par, const char *text, lv_coord_t x, lv_coord_t y, lv_event_cb_t cb, const int id, const int index, const char *editValue); +lv_obj_t* lv_screen_menu_item_2_edit(lv_obj_t *par, const char *text, lv_coord_t x, lv_coord_t y, lv_event_cb_t cb, const int id, const int index, const char *editValue, const int idEdit2, const char *editValue2); +lv_obj_t* lv_screen_menu_item_onoff(lv_obj_t *par, const char *text, lv_coord_t x, lv_coord_t y, lv_event_cb_t cb, const int id, const int index, const bool curValue); +void lv_screen_menu_item_onoff_update(lv_obj_t *btn, const bool curValue); + +#define _DIA_1(T) (uiCfg.dialogType == DIALOG_##T) +#define DIALOG_IS(V...) DO(DIA,||,V) diff --git a/Marlin/src/lcd/extui/mks_ui/draw_wifi.cpp b/Marlin/src/lcd/extui/mks_ui/draw_wifi.cpp new file mode 100644 index 000000000000..34b2abd0945c --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_wifi.cpp @@ -0,0 +1,166 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include +#include "tft_lvgl_configuration.h" + +#if ENABLED(MKS_WIFI_MODULE) + +#include "draw_ui.h" + +extern lv_group_t *g; +static lv_obj_t *scr, *wifi_name_text, *wifi_key_text, *wifi_state_text, *wifi_ip_text; + +enum { + ID_W_RETURN = 1, + ID_W_CLOUD, + ID_W_RECONNECT +}; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + clear_cur_ui(); + switch (obj->mks_obj_id) { + case ID_W_RETURN: + lv_draw_set(); + break; + case ID_W_CLOUD: + lv_draw_cloud_bind(); + break; + #if ENABLED(MKS_WIFI_MODULE) + case ID_W_RECONNECT: { + uint8_t cmd_wifi_list[] = { 0xA5, 0x07, 0x00, 0x00, 0xFC }; + raw_send_to_wifi(cmd_wifi_list, COUNT(cmd_wifi_list)); + lv_draw_wifi_list(); + } break; + #endif + } +} + +void lv_draw_wifi() { + scr = lv_screen_create(WIFI_UI); + + lv_obj_t *buttonReconnect = nullptr, *label_Reconnect = nullptr; + lv_obj_t *buttonCloud = nullptr, *label_Cloud = nullptr; + + const bool enc_ena = TERN0(HAS_ROTARY_ENCODER, gCfgItems.encoder_enable); + + if (gCfgItems.wifi_mode_sel == STA_MODEL) { + + if (gCfgItems.cloud_enable) + buttonCloud = lv_imgbtn_create(scr, "F:/bmp_cloud.bin", BTN_X_PIXEL+INTERVAL_V*2, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_W_CLOUD); + + buttonReconnect = lv_imgbtn_create(scr, "F:/bmp_wifi.bin", BTN_X_PIXEL * 2 + INTERVAL_V * 3, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_W_RECONNECT); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.cloud_enable) lv_group_add_obj(g, buttonCloud); + if (enc_ena) lv_group_add_obj(g, buttonReconnect); + #endif + + label_Reconnect = lv_label_create_empty(buttonReconnect); + if (gCfgItems.cloud_enable) label_Cloud = lv_label_create_empty(buttonCloud); + } + + // Create an Image button + lv_obj_t *buttonBack = lv_imgbtn_create(scr, "F:/bmp_return.bin", BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_W_RETURN); + if (enc_ena) lv_group_add_obj(g, buttonBack); + lv_obj_t *label_Back = lv_label_create_empty(buttonBack); + + if (gCfgItems.multiple_language) { + if (gCfgItems.wifi_mode_sel == STA_MODEL) { + if (gCfgItems.cloud_enable) { + lv_label_set_text(label_Cloud, wifi_menu.cloud); + lv_obj_align(label_Cloud, buttonCloud, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + lv_label_set_text(label_Reconnect, wifi_menu.reconnect); + lv_obj_align(label_Reconnect, buttonReconnect, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + lv_label_set_text(label_Back, common_menu.text_back); + lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + + wifi_ip_text = lv_label_create_empty(scr); + lv_obj_set_style(wifi_ip_text, &tft_style_label_rel); + wifi_name_text = lv_label_create_empty(scr); + lv_obj_set_style(wifi_name_text, &tft_style_label_rel); + wifi_key_text = lv_label_create_empty(scr); + lv_obj_set_style(wifi_key_text, &tft_style_label_rel); + wifi_state_text = lv_label_create_empty(scr); + lv_obj_set_style(wifi_state_text, &tft_style_label_rel); + + disp_wifi_state(); +} + +void disp_wifi_state() { + strcpy(public_buf_m, wifi_menu.ip); + strcat(public_buf_m, ipPara.ip_addr); + lv_label_set_text(wifi_ip_text, public_buf_m); + lv_obj_align(wifi_ip_text, nullptr, LV_ALIGN_CENTER, 0, -100); + + strcpy(public_buf_m, wifi_menu.wifi); + strcat(public_buf_m, wifiPara.ap_name); + lv_label_set_text(wifi_name_text, public_buf_m); + lv_obj_align(wifi_name_text, nullptr, LV_ALIGN_CENTER, 0, -70); + + if (wifiPara.mode == AP_MODEL) { + strcpy(public_buf_m, wifi_menu.key); + strcat(public_buf_m, wifiPara.keyCode); + lv_label_set_text(wifi_key_text, public_buf_m); + lv_obj_align(wifi_key_text, nullptr, LV_ALIGN_CENTER, 0, -40); + + strcpy(public_buf_m, wifi_menu.state_ap); + if (wifi_link_state == WIFI_CONNECTED) + strcat(public_buf_m, wifi_menu.connected); + else if (wifi_link_state == WIFI_NOT_CONFIG) + strcat(public_buf_m, wifi_menu.disconnected); + else + strcat(public_buf_m, wifi_menu.exception); + lv_label_set_text(wifi_state_text, public_buf_m); + lv_obj_align(wifi_state_text, nullptr, LV_ALIGN_CENTER, 0, -10); + } + else { + strcpy(public_buf_m, wifi_menu.state_sta); + if (wifi_link_state == WIFI_CONNECTED) + strcat(public_buf_m, wifi_menu.connected); + else if (wifi_link_state == WIFI_NOT_CONFIG) + strcat(public_buf_m, wifi_menu.disconnected); + else + strcat(public_buf_m, wifi_menu.exception); + lv_label_set_text(wifi_state_text, public_buf_m); + lv_obj_align(wifi_state_text, nullptr, LV_ALIGN_CENTER, 0, -40); + + lv_label_set_text(wifi_key_text, ""); + lv_obj_align(wifi_key_text, nullptr, LV_ALIGN_CENTER, 0, -10); + } +} + +void lv_clear_wifi() { + if (TERN0(HAS_ROTARY_ENCODER, gCfgItems.encoder_enable)) + lv_group_remove_all_objs(g); + lv_obj_del(scr); +} + +#endif // MKS_WIFI_MODULE +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi.h b/Marlin/src/lcd/extui/mks_ui/draw_wifi.h similarity index 91% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_wifi.h rename to Marlin/src/lcd/extui/mks_ui/draw_wifi.h index 966a84d3b19b..4fa642b39c1e 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_wifi.h @@ -26,13 +26,10 @@ #endif -extern void lv_draw_wifi(void); -extern void lv_clear_wifi(); -extern void disp_wifi_state(); +void lv_draw_wifi(); +void lv_clear_wifi(); +void disp_wifi_state(); #ifdef __cplusplus } /* C-declarations for C++ */ #endif - - - diff --git a/Marlin/src/lcd/extui/mks_ui/draw_wifi_list.cpp b/Marlin/src/lcd/extui/mks_ui/draw_wifi_list.cpp new file mode 100644 index 000000000000..2c3957fe9c9e --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_wifi_list.cpp @@ -0,0 +1,177 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include +#include "tft_lvgl_configuration.h" + +#if ENABLED(MKS_WIFI_MODULE) + +#include "draw_ui.h" + +#define NAME_BTN_X 330 +#define NAME_BTN_Y 48 + +#define MARK_BTN_X 0 +#define MARK_BTN_Y 68 + +WIFI_LIST wifi_list; +list_menu_def list_menu; + +extern lv_group_t *g; +static lv_obj_t *scr; +static lv_obj_t *buttonWifiN[NUMBER_OF_PAGE]; +static lv_obj_t *labelWifiText[NUMBER_OF_PAGE]; +static lv_obj_t *labelPageText; + +#define ID_WL_RETURN 11 +#define ID_WL_DOWN 12 + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + + if (obj->mks_obj_id == ID_WL_RETURN) { + clear_cur_ui(); + lv_draw_set(); + } + else if (obj->mks_obj_id == ID_WL_DOWN) { + if (wifi_list.getNameNum > 0) { + if ((wifi_list.nameIndex + NUMBER_OF_PAGE) >= wifi_list.getNameNum) { + wifi_list.nameIndex = 0; + wifi_list.currentWifipage = 1; + } + else { + wifi_list.nameIndex += NUMBER_OF_PAGE; + wifi_list.currentWifipage++; + } + disp_wifi_list(); + } + } + else { + for (uint8_t i = 0; i < NUMBER_OF_PAGE; i++) { + if (obj->mks_obj_id == i + 1) { + if (wifi_list.getNameNum != 0) { + const bool do_wifi = wifi_link_state == WIFI_CONNECTED && strcmp((const char *)wifi_list.wifiConnectedName, (const char *)wifi_list.wifiName[wifi_list.nameIndex + i]) == 0; + wifi_list.nameIndex += i; + last_disp_state = WIFI_LIST_UI; + lv_clear_wifi_list(); + if (do_wifi) + lv_draw_wifi(); + else { + keyboard_value = wifiConfig; + lv_draw_keyboard(); + } + } + } + } + } +} + +void lv_draw_wifi_list() { + scr = lv_screen_create(WIFI_LIST_UI); + + lv_obj_t *buttonDown = lv_imgbtn_create(scr, "F:/bmp_pageDown.bin", OTHER_BTN_XPIEL * 3 + INTERVAL_V * 4, titleHeight + OTHER_BTN_YPIEL + INTERVAL_H, event_handler, ID_WL_DOWN); + lv_obj_t *buttonBack = lv_imgbtn_create(scr, "F:/bmp_back.bin", OTHER_BTN_XPIEL * 3 + INTERVAL_V * 4, titleHeight + (OTHER_BTN_YPIEL + INTERVAL_H) * 2, event_handler, ID_WL_RETURN); + + for (uint8_t i = 0; i < NUMBER_OF_PAGE; i++) { + buttonWifiN[i] = lv_label_btn_create(scr, 0, NAME_BTN_Y * i + 10 + titleHeight, NAME_BTN_X, NAME_BTN_Y, event_handler, i + 1); + labelWifiText[i] = lv_label_create_empty(buttonWifiN[i]); + #if HAS_ROTARY_ENCODER + uint8_t j = 0; + if (gCfgItems.encoder_enable) { + j = wifi_list.nameIndex + i; + if (j < wifi_list.getNameNum) lv_group_add_obj(g, buttonWifiN[i]); + } + #endif + } + + labelPageText = lv_label_create_empty(scr); + lv_obj_set_style(labelPageText, &tft_style_label_rel); + + wifi_list.nameIndex = 0; + wifi_list.currentWifipage = 1; + + if (wifi_link_state == WIFI_CONNECTED && wifiPara.mode == STA_MODEL) { + ZERO(wifi_list.wifiConnectedName); + memcpy(wifi_list.wifiConnectedName, wifiPara.ap_name, sizeof(wifi_list.wifiConnectedName)); + } + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonDown); + lv_group_add_obj(g, buttonBack); + } + #else + UNUSED(buttonDown); + UNUSED(buttonBack); + #endif + + disp_wifi_list(); +} + +void disp_wifi_list() { + int8_t tmpStr[WIFI_NAME_BUFFER_SIZE] = { 0 }; + uint8_t i, j; + + sprintf((char *)tmpStr, list_menu.file_pages, wifi_list.currentWifipage, wifi_list.getPage); + lv_label_set_text(labelPageText, (const char *)tmpStr); + lv_obj_align(labelPageText, nullptr, LV_ALIGN_CENTER, 50, -100); + + for (i = 0; i < NUMBER_OF_PAGE; i++) { + ZERO(tmpStr); + + j = wifi_list.nameIndex + i; + if (j >= wifi_list.getNameNum) { + lv_label_set_text(labelWifiText[i], (const char *)tmpStr); + lv_obj_align(labelWifiText[i], buttonWifiN[i], LV_ALIGN_IN_LEFT_MID, 20, 0); + } + else { + lv_label_set_text(labelWifiText[i], (char const *)wifi_list.wifiName[j]); + lv_obj_align(labelWifiText[i], buttonWifiN[i], LV_ALIGN_IN_LEFT_MID, 20, 0); + + const bool btext = (wifi_link_state == WIFI_CONNECTED && strcmp((const char *)wifi_list.wifiConnectedName, (const char *)wifi_list.wifiName[j]) == 0); + lv_btn_set_style(buttonWifiN[i], LV_BTN_STYLE_REL, btext ? &style_sel_text : &tft_style_label_rel); + } + } +} + +void wifi_scan_handle() { + if (!DIALOG_IS(WIFI_ENABLE_TIPS) || !uiCfg.command_send) return; + last_disp_state = DIALOG_UI; + lv_clear_dialog(); + if (wifi_link_state == WIFI_CONNECTED && wifiPara.mode != AP_MODEL) + lv_draw_wifi(); + else + lv_draw_wifi_list(); +} + +void lv_clear_wifi_list() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // MKS_WIFI_MODULE +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_list.h b/Marlin/src/lcd/extui/mks_ui/draw_wifi_list.h similarity index 90% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_list.h rename to Marlin/src/lcd/extui/mks_ui/draw_wifi_list.h index e2d9275ef918..e2005d5cbc32 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_list.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_wifi_list.h @@ -25,11 +25,11 @@ extern "C" { /* C-declarations for C++ */ #endif -extern void lv_draw_wifi_list(); -extern void lv_clear_wifi_list(); -extern void disp_wifi_list(void); -extern void cutWifiName(char *name, int len,char *outStr); -extern void wifi_scan_handle(); +void lv_draw_wifi_list(); +void lv_clear_wifi_list(); +void disp_wifi_list(); +void cutWifiName(char *name, int len,char *outStr); +void wifi_scan_handle(); #define NUMBER_OF_PAGE 5 diff --git a/Marlin/src/lcd/extui/mks_ui/draw_wifi_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_wifi_settings.cpp new file mode 100644 index 000000000000..8509cc3ac1e2 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_wifi_settings.cpp @@ -0,0 +1,188 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include +#include "tft_lvgl_configuration.h" + +#if ENABLED(MKS_WIFI_MODULE) + +#include "draw_ui.h" + +extern lv_group_t *g; +static lv_obj_t *scr, *labelModelValue = nullptr, *buttonModelValue = nullptr, *labelCloudValue = nullptr; + +enum { + ID_WIFI_RETURN = 1, + ID_WIFI_MODEL, + ID_WIFI_NAME, + ID_WIFI_PASSWORD, + ID_WIFI_CLOUD, + ID_WIFI_CONFIG +}; + +static void event_handler(lv_obj_t *obj, lv_event_t event) { + if (event != LV_EVENT_RELEASED) return; + switch (obj->mks_obj_id) { + case ID_WIFI_RETURN: + lv_clear_wifi_settings(); + draw_return_ui(); + break; + case ID_WIFI_MODEL: + if (gCfgItems.wifi_mode_sel == AP_MODEL) { + gCfgItems.wifi_mode_sel = STA_MODEL; + lv_label_set_text(labelModelValue, WIFI_STA_TEXT); + lv_obj_align(labelModelValue, buttonModelValue, LV_ALIGN_CENTER, 0, 0); + update_spi_flash(); + } + else { + gCfgItems.wifi_mode_sel = AP_MODEL; + lv_label_set_text(labelModelValue, WIFI_AP_TEXT); + lv_obj_align(labelModelValue, buttonModelValue, LV_ALIGN_CENTER, 0, 0); + update_spi_flash(); + } + break; + case ID_WIFI_NAME: + keyboard_value = wifiName; + lv_clear_wifi_settings(); + lv_draw_keyboard(); + break; + case ID_WIFI_PASSWORD: + keyboard_value = wifiPassWord; + lv_clear_wifi_settings(); + lv_draw_keyboard(); + break; + case ID_WIFI_CLOUD: + if (gCfgItems.cloud_enable) { + gCfgItems.cloud_enable = false; + lv_obj_set_event_cb_mks(obj, event_handler, ID_WIFI_CLOUD, "bmp_disable.bin", 0); + lv_label_set_text(labelCloudValue, machine_menu.disable); + } + else { + gCfgItems.cloud_enable = true; + lv_obj_set_event_cb_mks(obj, event_handler, ID_WIFI_CLOUD, "bmp_enable.bin", 0); + lv_label_set_text(labelCloudValue, machine_menu.enable); + } + update_spi_flash(); + break; + case ID_WIFI_CONFIG: + lv_clear_wifi_settings(); + lv_draw_dialog(DIALOG_WIFI_CONFIG_TIPS); + break; + } +} + +void lv_draw_wifi_settings() { + scr = lv_screen_create(WIFI_SETTINGS_UI, machine_menu.WifiConfTitle); + + lv_label_create(scr, PARA_UI_POS_X, PARA_UI_POS_Y + 10, machine_menu.wifiMode); + + lv_obj_t *buttonModelValue = lv_imgbtn_create(scr, "F:/bmp_blank_sel.bin", PARA_UI_VALUE_POS_X, PARA_UI_POS_Y + PARA_UI_VALUE_V, event_handler, ID_WIFI_MODEL); + lv_btn_set_style_both(buttonModelValue, &style_para_value_pre); + labelModelValue = lv_label_create_empty(buttonModelValue); + + lv_obj_t *line1 = lv_line_create(scr, nullptr); + lv_ex_line(line1, line_points[0]); + + lv_obj_t *labelNameText = lv_label_create(scr, PARA_UI_POS_X, PARA_UI_POS_Y * 2 + 10, nullptr); + lv_obj_t *buttonNameValue = lv_btn_create(scr, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 2 + PARA_UI_VALUE_V, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE, event_handler, ID_WIFI_NAME); + lv_obj_t *labelNameValue = lv_label_create_empty(buttonNameValue); + + lv_obj_t *line2 = lv_line_create(scr, nullptr); + lv_ex_line(line2, line_points[1]); + + lv_obj_t *labelPassWordText = lv_label_create(scr, PARA_UI_POS_X, PARA_UI_POS_Y * 3 + 10, nullptr); + lv_obj_t *buttonPassWordValue = lv_btn_create(scr, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 3 + PARA_UI_VALUE_V, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE, event_handler, ID_WIFI_PASSWORD); + lv_obj_t *labelPassWordValue = lv_label_create_empty(buttonPassWordValue); + + lv_obj_t *line3 = lv_line_create(scr, nullptr); + lv_ex_line(line3, line_points[2]); + + lv_label_create(scr, PARA_UI_POS_X, PARA_UI_POS_Y * 4 + 10, machine_menu.wifiCloud); + lv_obj_t *buttonCloudValue = lv_imgbtn_create(scr, gCfgItems.cloud_enable ? "F:/bmp_enable.bin" : "F:/bmp_disable.bin", PARA_UI_STATE_POS_X, PARA_UI_POS_Y * 4 + PARA_UI_STATE_V, event_handler, ID_WIFI_CLOUD); + labelCloudValue = lv_label_create_empty(buttonCloudValue); + + lv_obj_t *line4 = lv_line_create(scr, nullptr); + lv_ex_line(line4, line_points[3]); + + lv_obj_t *buttonConfig = lv_imgbtn_create(scr, "F:/bmp_back70x40.bin", PARA_UI_TURN_PAGE_POS_X, PARA_UI_TURN_PAGE_POS_Y, event_handler, ID_WIFI_CONFIG); + lv_obj_t *labelConfig = lv_label_create_empty(buttonConfig); + + lv_obj_t *buttonBack = lv_imgbtn_create(scr, "F:/bmp_back70x40.bin", PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y, event_handler, ID_WIFI_RETURN); + lv_obj_t *label_Back = lv_label_create_empty(buttonBack); + + if (gCfgItems.multiple_language) { + if (gCfgItems.wifi_mode_sel == AP_MODEL) { + lv_label_set_text(labelModelValue, WIFI_AP_TEXT); + lv_obj_align(labelModelValue, buttonModelValue, LV_ALIGN_CENTER, 0, 0); + } + else { + lv_label_set_text(labelModelValue, WIFI_STA_TEXT); + lv_obj_align(labelModelValue, buttonModelValue, LV_ALIGN_CENTER, 0, 0); + } + strcpy(public_buf_m, machine_menu.wifiName); + strcat(public_buf_m, (const char *)uiCfg.wifi_name); + lv_label_set_text(labelNameText, public_buf_m); + + lv_label_set_text(labelNameValue, machine_menu.wifiEdit); + lv_obj_align(labelNameValue, buttonNameValue, LV_ALIGN_CENTER, 0, 0); + + strcpy(public_buf_m, machine_menu.wifiPassWord); + strcat(public_buf_m, (const char *)uiCfg.wifi_key); + lv_label_set_text(labelPassWordText, public_buf_m); + + lv_label_set_text(labelPassWordValue, machine_menu.wifiEdit); + lv_obj_align(labelPassWordValue, buttonPassWordValue, LV_ALIGN_CENTER, 0, 0); + + lv_label_set_text(labelCloudValue, gCfgItems.cloud_enable ? machine_menu.enable : machine_menu.disable); + lv_obj_align(labelCloudValue, buttonCloudValue, LV_ALIGN_CENTER, 0, 0); + + lv_label_set_text(labelConfig, machine_menu.wifiConfig); + lv_obj_align(labelConfig, buttonConfig, LV_ALIGN_CENTER, 0, 0); + + lv_label_set_text(label_Back, common_menu.text_back); + lv_obj_align(label_Back, buttonBack, LV_ALIGN_CENTER, 0, 0); + } + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonModelValue); + lv_group_add_obj(g, buttonNameValue); + lv_group_add_obj(g, buttonPassWordValue); + lv_group_add_obj(g, buttonCloudValue); + lv_group_add_obj(g, buttonConfig); + lv_group_add_obj(g, buttonBack); + } + #endif +} + +void lv_clear_wifi_settings() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // MKS_WIFI_MODULE +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_wifi_settings.h similarity index 93% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_settings.h rename to Marlin/src/lcd/extui/mks_ui/draw_wifi_settings.h index c0d6e0ccdd78..ff2739704953 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_settings.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_wifi_settings.h @@ -28,8 +28,8 @@ #define WIFI_AP_TEXT "AP" #define WIFI_STA_TEXT "STA" -extern void lv_draw_wifi_settings(void); -extern void lv_clear_wifi_settings(); +void lv_draw_wifi_settings(); +void lv_clear_wifi_settings(); #ifdef __cplusplus } /* C-declarations for C++ */ diff --git a/Marlin/src/lcd/extui/mks_ui/draw_wifi_tips.cpp b/Marlin/src/lcd/extui/mks_ui/draw_wifi_tips.cpp new file mode 100644 index 000000000000..c337d1892230 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/draw_wifi_tips.cpp @@ -0,0 +1,68 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include +#include "tft_lvgl_configuration.h" + +#if ENABLED(MKS_WIFI_MODULE) + +#include "draw_ui.h" + +static lv_obj_t *scr; + +TIPS_TYPE wifi_tips_type; +TIPS_DISP tips_disp; +tips_menu_def tips_menu; + +void lv_draw_wifi_tips() { + static lv_obj_t *text_tips,*wifi_name; + + scr = lv_screen_create(WIFI_TIPS_UI, ""); + + wifi_name = lv_label_create(scr, (const char *)wifi_list.wifiName[wifi_list.nameIndex]); + lv_obj_align(wifi_name, nullptr, LV_ALIGN_CENTER, 0, -20); + + text_tips = lv_label_create_empty(scr); + if (wifi_tips_type == TIPS_TYPE_JOINING) { + lv_label_set_text(text_tips, tips_menu.joining); + lv_obj_align(text_tips, nullptr, LV_ALIGN_CENTER, 0, -60); + } + else if (wifi_tips_type == TIPS_TYPE_TAILED_JOIN) { + lv_label_set_text(text_tips, tips_menu.failedJoin); + lv_obj_align(text_tips, nullptr, LV_ALIGN_CENTER, 0, -60); + } + else if (wifi_tips_type == TIPS_TYPE_WIFI_CONECTED) { + lv_label_set_text(text_tips, tips_menu.wifiConected); + lv_obj_align(text_tips, nullptr, LV_ALIGN_CENTER, 0, -60); + } + + tips_disp.timer = TIPS_TIMER_START; + tips_disp.timer_count = 0; +} + +void lv_clear_wifi_tips() { lv_obj_del(scr); } + +#endif // MKS_WIFI_MODULE +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_tips.h b/Marlin/src/lcd/extui/mks_ui/draw_wifi_tips.h similarity index 94% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_tips.h rename to Marlin/src/lcd/extui/mks_ui/draw_wifi_tips.h index 4f81f00a434d..4ffe6c1312a3 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_tips.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_wifi_tips.h @@ -26,8 +26,8 @@ #endif -extern void lv_draw_wifi_tips(void); -extern void lv_clear_wifi_tips(); +void lv_draw_wifi_tips(); +void lv_clear_wifi_tips(); typedef enum { TIPS_TYPE_JOINING, @@ -48,4 +48,3 @@ extern TIPS_DISP tips_disp; #ifdef __cplusplus } /* C-declarations for C++ */ #endif - diff --git a/Marlin/src/lcd/extui/lib/mks_ui/gb2312_puhui16.cpp b/Marlin/src/lcd/extui/mks_ui/gb2312_puhui16.cpp similarity index 86% rename from Marlin/src/lcd/extui/lib/mks_ui/gb2312_puhui16.cpp rename to Marlin/src/lcd/extui/mks_ui/gb2312_puhui16.cpp index 856d645e9ed4..b1f0e0e1bb97 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/gb2312_puhui16.cpp +++ b/Marlin/src/lcd/extui/mks_ui/gb2312_puhui16.cpp @@ -19,14 +19,14 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI #include "pic_manager.h" #include -#include "../../../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #if HAS_SPI_FLASH_FONT @@ -50,10 +50,8 @@ static x_header_t __g_xbf_hd = { .min = 0, .max = 0, .bpp = 0 }; static uint8_t __g_font_buf[63]; static uint8_t *__user_font_getdata(int offset, int size) { - //ZERO(__g_font_buf); get_spi_flash_data((char *)__g_font_buf, offset, size); return __g_font_buf; - //return &buf_test[offset]; } static const uint8_t * __user_font_get_bitmap(const lv_font_t * font, uint32_t unicode_letter) { @@ -62,17 +60,15 @@ static const uint8_t * __user_font_get_bitmap(const lv_font_t * font, uint32_t u memcpy(&__g_xbf_hd, p, sizeof(x_header_t)); } if (unicode_letter > __g_xbf_hd.max || unicode_letter < __g_xbf_hd.min) - return NULL; + return nullptr; uint32_t unicode_offset = sizeof(x_header_t) + (unicode_letter - __g_xbf_hd.min) * 4; uint32_t *p_pos = (uint32_t *)__user_font_getdata(unicode_offset, 4); if (p_pos[0] != 0) { uint32_t pos = p_pos[0]; - //glyph_dsc_t * gdsc = (glyph_dsc_t*)__user_font_getdata(pos, 2); __user_font_getdata(pos, 2); - //return __user_font_getdata(pos+2, gdsc->box_w*__g_xbf_hd.bpp/8); return __user_font_getdata(pos + 2, sizeof(__g_font_buf)); } - return NULL; + return nullptr; } static bool __user_font_get_glyph_dsc(const lv_font_t * font, lv_font_glyph_dsc_t * dsc_out, uint32_t unicode_letter, uint32_t unicode_letter_next) { @@ -81,7 +77,7 @@ static bool __user_font_get_glyph_dsc(const lv_font_t * font, lv_font_glyph_dsc_ memcpy(&__g_xbf_hd, p, sizeof(x_header_t)); } if (unicode_letter > __g_xbf_hd.max || unicode_letter < __g_xbf_hd.min) - return NULL; + return false; uint32_t unicode_offset = sizeof(x_header_t) + (unicode_letter - __g_xbf_hd.min) * 4; uint32_t *p_pos = (uint32_t *)__user_font_getdata(unicode_offset, 4); if (p_pos[0] != 0) { @@ -97,12 +93,6 @@ static bool __user_font_get_glyph_dsc(const lv_font_t * font, lv_font_glyph_dsc_ return false; } -/*lv_font_t gb2312_puhui32 = { -.get_glyph_bitmap = __user_font_get_bitmap, -.get_glyph_dsc = __user_font_get_glyph_dsc, -.line_height = 25, -.base_line = 0, -};*/ lv_font_t gb2312_puhui32; void init_gb2312_font() { gb2312_puhui32.get_glyph_bitmap = __user_font_get_bitmap; diff --git a/Marlin/src/lcd/extui/mks_ui/irq_overrid.cpp b/Marlin/src/lcd/extui/mks_ui/irq_overrid.cpp new file mode 100644 index 000000000000..f3c87c03c4b5 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/irq_overrid.cpp @@ -0,0 +1,60 @@ +/** + * 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 __STM32F1__ + +#include "../../../inc/MarlinConfigPre.h" + +#if BOTH(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) + +#include "tft_lvgl_configuration.h" + +#include "draw_ui.h" +#include "wifiSerial.h" + +#include +#include +#include +#include +#include + +#include "../../../inc/MarlinConfig.h" + +#ifdef __cplusplus + extern "C" { /* C-declarations for C++ */ +#endif + +#define WIFI_IO1_SET() WRITE(WIFI_IO1_PIN, HIGH); +#define WIFI_IO1_RESET() WRITE(WIFI_IO1_PIN, LOW); + +void __irq_usart1() { + if ((USART1_BASE->CR1 & USART_CR1_RXNEIE) && (USART1_BASE->SR & USART_SR_RXNE)) + WRITE(WIFI_IO1_PIN, HIGH); + + WIFISERIAL.wifi_usart_irq(USART1_BASE); +} + +#ifdef __cplusplus + } /* C-declarations for C++ */ +#endif + +#endif // HAS_TFT_LVGL_UI && MKS_WIFI_MODULE +#endif // __STM32F1__ diff --git a/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp b/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp new file mode 100644 index 000000000000..5cd1a4c525e9 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp @@ -0,0 +1,730 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "SPI_TFT.h" + +#include "tft_lvgl_configuration.h" +#include "draw_ready_print.h" +#include "draw_ui.h" +#include "pic_manager.h" +#include + +#include "../../../MarlinCore.h" +#include "../../../module/temperature.h" +#include "../../../sd/cardreader.h" + +#if ENABLED(MKS_TEST) + + #include "mks_hardware.h" + #include "../../../module/endstops.h" + + bool pw_det_sta, pw_off_sta, mt_det_sta; + #if PIN_EXISTS(MT_DET_2) + bool mt_det2_sta; + #endif + #if HAS_X_MIN || HAS_X_MAX + bool endstopx1_sta; + #else + constexpr static bool endstopx1_sta = true; + #endif + #if HAS_X2_MIN || HAS_X2_MAX + bool endstopx2_sta; + #else + constexpr static bool endstopx2_sta = true; + #endif + #if HAS_Y_MIN || HAS_Y_MAX + bool endstopy1_sta; + #else + constexpr static bool endstopy1_sta = true; + #endif + #if HAS_Y2_MIN || HAS_Y2_MAX + bool endstopy2_sta; + #else + constexpr static bool endstopy2_sta = true; + #endif + #if HAS_Z_MIN || HAS_Z_MAX + bool endstopz1_sta; + #else + constexpr static bool endstopz1_sta = true; + #endif + #if HAS_Z2_MIN || HAS_Z2_MAX + bool endstopz2_sta; + #else + constexpr static bool endstopz2_sta = true; + #endif + + #define ESTATE(S) (READ(S##_PIN) != S##_ENDSTOP_INVERTING) + + void test_gpio_readlevel_L() { + WRITE(WIFI_IO0_PIN, HIGH); + delay(10); + pw_det_sta = (READ(MKS_TEST_POWER_LOSS_PIN) == LOW); + pw_off_sta = (READ(MKS_TEST_PS_ON_PIN) == LOW); + mt_det_sta = (READ(MT_DET_1_PIN) == LOW); + #if PIN_EXISTS(MT_DET_2) + mt_det2_sta = (READ(MT_DET_2_PIN) == LOW); + #endif + #if HAS_X_MIN + endstopx1_sta = ESTATE(X_MIN); + #elif HAS_X_MAX + endstopx1_sta = ESTATE(X_MAX); + #endif + #if HAS_X2_MIN + endstopx2_sta = ESTATE(X2_MIN); + #elif HAS_X2_MAX + endstopx2_sta = ESTATE(X2_MAX); + #endif + #if HAS_Y_MIN + endstopy1_sta = ESTATE(Y_MIN); + #elif HAS_Y_MAX + endstopy1_sta = ESTATE(Y_MAX); + #endif + #if HAS_Y2_MIN + endstopy2_sta = ESTATE(Y2_MIN); + #elif HAS_Y2_MAX + endstopy2_sta = ESTATE(Y2_MAX); + #endif + #if HAS_Z_MIN + endstopz1_sta = ESTATE(Z_MIN); + #elif HAS_Z_MAX + endstopz1_sta = ESTATE(Z_MAX); + #endif + #if HAS_Z2_MIN + endstopz2_sta = ESTATE(Z2_MIN); + #elif HAS_Z2_MAX + endstopz2_sta = ESTATE(Z2_MAX); + #endif + } + + void test_gpio_readlevel_H() { + WRITE(WIFI_IO0_PIN, LOW); + delay(10); + pw_det_sta = (READ(MKS_TEST_POWER_LOSS_PIN) == HIGH); + pw_off_sta = (READ(MKS_TEST_PS_ON_PIN) == HIGH); + mt_det_sta = (READ(MT_DET_1_PIN) == HIGH); + #if PIN_EXISTS(MT_DET_2) + mt_det2_sta = (READ(MT_DET_2_PIN) == HIGH); + #endif + #if HAS_X_MIN + endstopx1_sta = !ESTATE(X_MIN); + #elif HAS_X_MAX + endstopx1_sta = !ESTATE(X_MAX); + #endif + #if HAS_X2_MIN + endstopx2_sta = !ESTATE(X2_MIN); + #elif HAS_X2_MAX + endstopx2_sta = !ESTATE(X2_MAX); + #endif + #if HAS_Y_MIN + endstopy1_sta = !ESTATE(Y_MIN); + #elif HAS_Y_MAX + endstopy1_sta = !ESTATE(Y_MAX); + #endif + #if HAS_Y2_MIN + endstopy2_sta = !ESTATE(Y2_MIN); + #elif HAS_Y2_MAX + endstopy2_sta = !ESTATE(Y2_MAX); + #endif + #if HAS_Z_MIN + endstopz1_sta = !ESTATE(Z_MIN); + #elif HAS_Z_MAX + endstopz1_sta = !ESTATE(Z_MAX); + #endif + #if HAS_Z2_MIN + endstopz2_sta = !ESTATE(Z2_MIN); + #elif HAS_Z2_MAX + endstopz2_sta = !ESTATE(Z2_MAX); + #endif + } + + void init_test_gpio() { + endstops.init(); + + SET_OUTPUT(WIFI_IO0_PIN); + + #if PIN_EXISTS(MT_DET_1) + SET_INPUT_PULLUP(MT_DET_1_PIN); + #endif + #if PIN_EXISTS(MT_DET_2) + SET_INPUT_PULLUP(MT_DET_2_PIN); + #endif + + SET_INPUT_PULLUP(MKS_TEST_POWER_LOSS_PIN); + SET_INPUT_PULLUP(MKS_TEST_PS_ON_PIN); + SET_INPUT_PULLUP(SERVO0_PIN); + + OUT_WRITE(X_ENABLE_PIN, LOW); + #if HAS_Y_AXIS + OUT_WRITE(Y_ENABLE_PIN, LOW); + #endif + #if HAS_Z_AXIS + OUT_WRITE(Z_ENABLE_PIN, LOW); + #endif + #if HAS_EXTRUDERS + OUT_WRITE(E0_ENABLE_PIN, LOW); + #endif + #if HAS_MULTI_EXTRUDER && DISABLED(MKS_HARDWARE_TEST_ONLY_E0) + OUT_WRITE(E1_ENABLE_PIN, LOW); + #endif + + #if ENABLED(MKS_HARDWARE_TEST_ONLY_E0) + SET_INPUT_PULLUP(PA1); + SET_INPUT_PULLUP(PA3); + SET_INPUT_PULLUP(PC2); + SET_INPUT_PULLUP(PD8); + SET_INPUT_PULLUP(PE5); + SET_INPUT_PULLUP(PE6); + SET_INPUT_PULLUP(PE7); + #endif + } + + void mks_test_beeper() { + WRITE(BEEPER_PIN, HIGH); + delay(100); + WRITE(BEEPER_PIN, LOW); + delay(100); + } + + #if ENABLED(SDSUPPORT) + + void mks_gpio_test() { + init_test_gpio(); + + test_gpio_readlevel_L(); + test_gpio_readlevel_H(); + test_gpio_readlevel_L(); + if (pw_det_sta && pw_off_sta && mt_det_sta + #if PIN_EXISTS(MT_DET_2) + && mt_det2_sta + #endif + #if ENABLED(MKS_HARDWARE_TEST_ONLY_E0) + && (READ(PA1) == LOW) + && (READ(PA3) == LOW) + && (READ(PC2) == LOW) + && (READ(PD8) == LOW) + && (READ(PE5) == LOW) + && (READ(PE6) == LOW) + && (READ(PE7) == LOW) + #endif + ) + disp_det_ok(); + else + disp_det_error(); + + if (endstopx1_sta && endstopy1_sta && endstopz1_sta && endstopz2_sta) + disp_Limit_ok(); + else + disp_Limit_error(); + } + + void mks_hardware_test() { + if (millis() % 2000 < 1000) { + thermalManager.fan_speed[0] = 255; + WRITE(X_DIR_PIN, LOW); + #if HAS_Y_AXIS + WRITE(Y_DIR_PIN, LOW); + #endif + #if HAS_Z_AXIS + WRITE(Z_DIR_PIN, LOW); + #endif + #if HAS_EXTRUDERS + WRITE(E0_DIR_PIN, LOW); + #endif + #if HAS_MULTI_EXTRUDER && DISABLED(MKS_HARDWARE_TEST_ONLY_E0) + WRITE(E1_DIR_PIN, LOW); + #endif + #if HAS_MULTI_HOTEND && DISABLED(MKS_HARDWARE_TEST_ONLY_E0) + WRITE(HEATER_1_PIN, HIGH); // HE1 + #endif + #if HAS_HOTEND + WRITE(HEATER_0_PIN, HIGH); // HE0 + #endif + #if HAS_HEATED_BED + WRITE(HEATER_BED_PIN, HIGH); // HOT-BED + #endif + } + else { + thermalManager.fan_speed[0] = 0; + WRITE(X_DIR_PIN, HIGH); + #if HAS_Y_AXIS + WRITE(Y_DIR_PIN, HIGH); + #endif + #if HAS_Y_AXIS + WRITE(Z_DIR_PIN, HIGH); + #endif + #if HAS_EXTRUDERS + WRITE(E0_DIR_PIN, HIGH); + #endif + #if HAS_MULTI_EXTRUDER && DISABLED(MKS_HARDWARE_TEST_ONLY_E0) + WRITE(E1_DIR_PIN, HIGH); + #endif + #if HAS_MULTI_HOTEND && DISABLED(MKS_HARDWARE_TEST_ONLY_E0) + WRITE(HEATER_1_PIN, LOW); // HE1 + #endif + #if HAS_HOTEND + WRITE(HEATER_0_PIN, LOW); // HE0 + #endif + #if HAS_HEATED_BED + WRITE(HEATER_BED_PIN, LOW); // HOT-BED + #endif + } + + if (endstopx1_sta && endstopx2_sta && endstopy1_sta && endstopy2_sta && endstopz1_sta && endstopz2_sta) { + // nothing here + } + else { + } + + if (disp_state == PRINT_READY_UI) + mks_disp_test(); + } + + #endif + +#endif // MKS_TEST + +static const uint16_t ASCII_Table_16x24[] PROGMEM = { + // Space ' ' + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // '!' + 0x0000, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, + 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0000, 0x0000, + 0x0180, 0x0180, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // '"' + 0x0000, 0x0000, 0x00CC, 0x00CC, 0x00CC, 0x00CC, 0x00CC, 0x00CC, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // '#' + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0C60, 0x0C60, + 0x0C60, 0x0630, 0x0630, 0x1FFE, 0x1FFE, 0x0630, 0x0738, 0x0318, + 0x1FFE, 0x1FFE, 0x0318, 0x0318, 0x018C, 0x018C, 0x018C, 0x0000, + // '$' + 0x0000, 0x0080, 0x03E0, 0x0FF8, 0x0E9C, 0x1C8C, 0x188C, 0x008C, + 0x0098, 0x01F8, 0x07E0, 0x0E80, 0x1C80, 0x188C, 0x188C, 0x189C, + 0x0CB8, 0x0FF0, 0x03E0, 0x0080, 0x0080, 0x0000, 0x0000, 0x0000, + // '%' + 0x0000, 0x0000, 0x0000, 0x180E, 0x0C1B, 0x0C11, 0x0611, 0x0611, + 0x0311, 0x0311, 0x019B, 0x018E, 0x38C0, 0x6CC0, 0x4460, 0x4460, + 0x4430, 0x4430, 0x4418, 0x6C18, 0x380C, 0x0000, 0x0000, 0x0000, + // '&' + 0x0000, 0x01E0, 0x03F0, 0x0738, 0x0618, 0x0618, 0x0330, 0x01F0, + 0x00F0, 0x00F8, 0x319C, 0x330E, 0x1E06, 0x1C06, 0x1C06, 0x3F06, + 0x73FC, 0x21F0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // "'" + 0x0000, 0x0000, 0x000C, 0x000C, 0x000C, 0x000C, 0x000C, 0x000C, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // '(' + 0x0000, 0x0200, 0x0300, 0x0180, 0x00C0, 0x00C0, 0x0060, 0x0060, + 0x0030, 0x0030, 0x0030, 0x0030, 0x0030, 0x0030, 0x0030, 0x0030, + 0x0060, 0x0060, 0x00C0, 0x00C0, 0x0180, 0x0300, 0x0200, 0x0000, + // ')' + 0x0000, 0x0020, 0x0060, 0x00C0, 0x0180, 0x0180, 0x0300, 0x0300, + 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, + 0x0300, 0x0300, 0x0180, 0x0180, 0x00C0, 0x0060, 0x0020, 0x0000, + // '*' + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x00C0, 0x00C0, + 0x06D8, 0x07F8, 0x01E0, 0x0330, 0x0738, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // '+' + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0180, 0x0180, + 0x0180, 0x0180, 0x0180, 0x3FFC, 0x3FFC, 0x0180, 0x0180, 0x0180, + 0x0180, 0x0180, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // ',' + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0180, 0x0180, 0x0100, 0x0100, 0x0080, 0x0000, 0x0000, + // '-' + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x07E0, 0x07E0, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // '.' + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x00C0, 0x00C0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // '/' + 0x0000, 0x0C00, 0x0C00, 0x0600, 0x0600, 0x0600, 0x0300, 0x0300, + 0x0300, 0x0380, 0x0180, 0x0180, 0x0180, 0x00C0, 0x00C0, 0x00C0, + 0x0060, 0x0060, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // '0' + 0x0000, 0x03E0, 0x07F0, 0x0E38, 0x0C18, 0x180C, 0x180C, 0x180C, + 0x180C, 0x180C, 0x180C, 0x180C, 0x180C, 0x180C, 0x0C18, 0x0E38, + 0x07F0, 0x03E0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // '1' + 0x0000, 0x0100, 0x0180, 0x01C0, 0x01F0, 0x0198, 0x0188, 0x0180, + 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, + 0x0180, 0x0180, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // '2' + 0x0000, 0x03E0, 0x0FF8, 0x0C18, 0x180C, 0x180C, 0x1800, 0x1800, + 0x0C00, 0x0600, 0x0300, 0x0180, 0x00C0, 0x0060, 0x0030, 0x0018, + 0x1FFC, 0x1FFC, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // '3' + 0x0000, 0x01E0, 0x07F8, 0x0E18, 0x0C0C, 0x0C0C, 0x0C00, 0x0600, + 0x03C0, 0x07C0, 0x0C00, 0x1800, 0x1800, 0x180C, 0x180C, 0x0C18, + 0x07F8, 0x03E0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // '4' + 0x0000, 0x0C00, 0x0E00, 0x0F00, 0x0F00, 0x0D80, 0x0CC0, 0x0C60, + 0x0C60, 0x0C30, 0x0C18, 0x0C0C, 0x3FFC, 0x3FFC, 0x0C00, 0x0C00, + 0x0C00, 0x0C00, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // '5' + 0x0000, 0x0FF8, 0x0FF8, 0x0018, 0x0018, 0x000C, 0x03EC, 0x07FC, + 0x0E1C, 0x1C00, 0x1800, 0x1800, 0x1800, 0x180C, 0x0C1C, 0x0E18, + 0x07F8, 0x03E0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // '6' + 0x0000, 0x07C0, 0x0FF0, 0x1C38, 0x1818, 0x0018, 0x000C, 0x03CC, + 0x0FEC, 0x0E3C, 0x1C1C, 0x180C, 0x180C, 0x180C, 0x1C18, 0x0E38, + 0x07F0, 0x03E0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // '7' + 0x0000, 0x1FFC, 0x1FFC, 0x0C00, 0x0600, 0x0600, 0x0300, 0x0380, + 0x0180, 0x01C0, 0x00C0, 0x00E0, 0x0060, 0x0060, 0x0070, 0x0030, + 0x0030, 0x0030, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // '8' + 0x0000, 0x03E0, 0x07F0, 0x0E38, 0x0C18, 0x0C18, 0x0C18, 0x0638, + 0x07F0, 0x07F0, 0x0C18, 0x180C, 0x180C, 0x180C, 0x180C, 0x0C38, + 0x0FF8, 0x03E0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // '9' + 0x0000, 0x03E0, 0x07F0, 0x0E38, 0x0C1C, 0x180C, 0x180C, 0x180C, + 0x1C1C, 0x1E38, 0x1BF8, 0x19E0, 0x1800, 0x0C00, 0x0C00, 0x0E1C, + 0x07F8, 0x01F0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // ':' + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0180, 0x0180, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0180, 0x0180, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // ';' + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0180, 0x0180, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0180, 0x0180, 0x0100, 0x0100, 0x0080, 0x0000, 0x0000, 0x0000, + // '<' + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x1000, 0x1C00, 0x0F80, 0x03E0, 0x00F8, 0x0018, 0x00F8, 0x03E0, + 0x0F80, 0x1C00, 0x1000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // '=' + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x1FF8, 0x0000, 0x0000, 0x0000, 0x1FF8, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // '>' + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0008, 0x0038, 0x01F0, 0x07C0, 0x1F00, 0x1800, 0x1F00, 0x07C0, + 0x01F0, 0x0038, 0x0008, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // '?' + 0x0000, 0x03E0, 0x0FF8, 0x0C18, 0x180C, 0x180C, 0x1800, 0x0C00, + 0x0600, 0x0300, 0x0180, 0x00C0, 0x00C0, 0x00C0, 0x0000, 0x0000, + 0x00C0, 0x00C0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // '@' + 0x0000, 0x0000, 0x07E0, 0x1818, 0x2004, 0x29C2, 0x4A22, 0x4411, + 0x4409, 0x4409, 0x4409, 0x2209, 0x1311, 0x0CE2, 0x4002, 0x2004, + 0x1818, 0x07E0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'A' + 0x0000, 0x0380, 0x0380, 0x06C0, 0x06C0, 0x06C0, 0x0C60, 0x0C60, + 0x1830, 0x1830, 0x1830, 0x3FF8, 0x3FF8, 0x701C, 0x600C, 0x600C, + 0xC006, 0xC006, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'B' + 0x0000, 0x03FC, 0x0FFC, 0x0C0C, 0x180C, 0x180C, 0x180C, 0x0C0C, + 0x07FC, 0x0FFC, 0x180C, 0x300C, 0x300C, 0x300C, 0x300C, 0x180C, + 0x1FFC, 0x07FC, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'C' + 0x0000, 0x07C0, 0x1FF0, 0x3838, 0x301C, 0x700C, 0x6006, 0x0006, + 0x0006, 0x0006, 0x0006, 0x0006, 0x0006, 0x6006, 0x700C, 0x301C, + 0x1FF0, 0x07E0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'D' + 0x0000, 0x03FE, 0x0FFE, 0x0E06, 0x1806, 0x1806, 0x3006, 0x3006, + 0x3006, 0x3006, 0x3006, 0x3006, 0x3006, 0x1806, 0x1806, 0x0E06, + 0x0FFE, 0x03FE, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'E' + 0x0000, 0x3FFC, 0x3FFC, 0x000C, 0x000C, 0x000C, 0x000C, 0x000C, + 0x1FFC, 0x1FFC, 0x000C, 0x000C, 0x000C, 0x000C, 0x000C, 0x000C, + 0x3FFC, 0x3FFC, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'F' + 0x0000, 0x3FF8, 0x3FF8, 0x0018, 0x0018, 0x0018, 0x0018, 0x0018, + 0x1FF8, 0x1FF8, 0x0018, 0x0018, 0x0018, 0x0018, 0x0018, 0x0018, + 0x0018, 0x0018, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'G' + 0x0000, 0x0FE0, 0x3FF8, 0x783C, 0x600E, 0xE006, 0xC007, 0x0003, + 0x0003, 0xFE03, 0xFE03, 0xC003, 0xC007, 0xC006, 0xC00E, 0xF03C, + 0x3FF8, 0x0FE0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'H' + 0x0000, 0x300C, 0x300C, 0x300C, 0x300C, 0x300C, 0x300C, 0x300C, + 0x3FFC, 0x3FFC, 0x300C, 0x300C, 0x300C, 0x300C, 0x300C, 0x300C, + 0x300C, 0x300C, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'I' + 0x0000, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, + 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, + 0x0180, 0x0180, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'J' + 0x0000, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, + 0x0600, 0x0600, 0x0600, 0x0600, 0x0600, 0x0618, 0x0618, 0x0738, + 0x03F0, 0x01E0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'K' + 0x0000, 0x3006, 0x1806, 0x0C06, 0x0606, 0x0306, 0x0186, 0x00C6, + 0x0066, 0x0076, 0x00DE, 0x018E, 0x0306, 0x0606, 0x0C06, 0x1806, + 0x3006, 0x6006, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'L' + 0x0000, 0x0018, 0x0018, 0x0018, 0x0018, 0x0018, 0x0018, 0x0018, + 0x0018, 0x0018, 0x0018, 0x0018, 0x0018, 0x0018, 0x0018, 0x0018, + 0x1FF8, 0x1FF8, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'M' + 0x0000, 0xE00E, 0xF01E, 0xF01E, 0xF01E, 0xD836, 0xD836, 0xD836, + 0xD836, 0xCC66, 0xCC66, 0xCC66, 0xC6C6, 0xC6C6, 0xC6C6, 0xC6C6, + 0xC386, 0xC386, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'N' + 0x0000, 0x300C, 0x301C, 0x303C, 0x303C, 0x306C, 0x306C, 0x30CC, + 0x30CC, 0x318C, 0x330C, 0x330C, 0x360C, 0x360C, 0x3C0C, 0x3C0C, + 0x380C, 0x300C, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'O' + 0x0000, 0x07E0, 0x1FF8, 0x381C, 0x700E, 0x6006, 0xC003, 0xC003, + 0xC003, 0xC003, 0xC003, 0xC003, 0xC003, 0x6006, 0x700E, 0x381C, + 0x1FF8, 0x07E0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'P' + 0x0000, 0x0FFC, 0x1FFC, 0x380C, 0x300C, 0x300C, 0x300C, 0x300C, + 0x180C, 0x1FFC, 0x07FC, 0x000C, 0x000C, 0x000C, 0x000C, 0x000C, + 0x000C, 0x000C, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'Q' + 0x0000, 0x07E0, 0x1FF8, 0x381C, 0x700E, 0x6006, 0xE003, 0xC003, + 0xC003, 0xC003, 0xC003, 0xC003, 0xE007, 0x6306, 0x3F0E, 0x3C1C, + 0x3FF8, 0xF7E0, 0xC000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'R' + 0x0000, 0x0FFE, 0x1FFE, 0x3806, 0x3006, 0x3006, 0x3006, 0x3806, + 0x1FFE, 0x07FE, 0x0306, 0x0606, 0x0C06, 0x1806, 0x1806, 0x3006, + 0x3006, 0x6006, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'S' + 0x0000, 0x03E0, 0x0FF8, 0x0C1C, 0x180C, 0x180C, 0x000C, 0x001C, + 0x03F8, 0x0FE0, 0x1E00, 0x3800, 0x3006, 0x3006, 0x300E, 0x1C1C, + 0x0FF8, 0x07E0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'T' + 0x0000, 0x7FFE, 0x7FFE, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, + 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, + 0x0180, 0x0180, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'U' + 0x0000, 0x300C, 0x300C, 0x300C, 0x300C, 0x300C, 0x300C, 0x300C, + 0x300C, 0x300C, 0x300C, 0x300C, 0x300C, 0x300C, 0x300C, 0x1818, + 0x1FF8, 0x07E0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'V' + 0x0000, 0x6003, 0x3006, 0x3006, 0x3006, 0x180C, 0x180C, 0x180C, + 0x0C18, 0x0C18, 0x0E38, 0x0630, 0x0630, 0x0770, 0x0360, 0x0360, + 0x01C0, 0x01C0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'W' + 0x0000, 0x6003, 0x61C3, 0x61C3, 0x61C3, 0x3366, 0x3366, 0x3366, + 0x3366, 0x3366, 0x3366, 0x1B6C, 0x1B6C, 0x1B6C, 0x1A2C, 0x1E3C, + 0x0E38, 0x0E38, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'X' + 0x0000, 0xE00F, 0x700C, 0x3018, 0x1830, 0x0C70, 0x0E60, 0x07C0, + 0x0380, 0x0380, 0x03C0, 0x06E0, 0x0C70, 0x1C30, 0x1818, 0x300C, + 0x600E, 0xE007, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'Y' + 0x0000, 0xC003, 0x6006, 0x300C, 0x381C, 0x1838, 0x0C30, 0x0660, + 0x07E0, 0x03C0, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, + 0x0180, 0x0180, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'Z' + 0x0000, 0x7FFC, 0x7FFC, 0x6000, 0x3000, 0x1800, 0x0C00, 0x0600, + 0x0300, 0x0180, 0x00C0, 0x0060, 0x0030, 0x0018, 0x000C, 0x0006, + 0x7FFE, 0x7FFE, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // '[' + 0x0000, 0x03E0, 0x03E0, 0x0060, 0x0060, 0x0060, 0x0060, 0x0060, + 0x0060, 0x0060, 0x0060, 0x0060, 0x0060, 0x0060, 0x0060, 0x0060, + 0x0060, 0x0060, 0x0060, 0x0060, 0x0060, 0x03E0, 0x03E0, 0x0000, + // '\' + 0x0000, 0x0030, 0x0030, 0x0060, 0x0060, 0x0060, 0x00C0, 0x00C0, + 0x00C0, 0x01C0, 0x0180, 0x0180, 0x0180, 0x0300, 0x0300, 0x0300, + 0x0600, 0x0600, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // ']' + 0x0000, 0x03E0, 0x03E0, 0x0300, 0x0300, 0x0300, 0x0300, 0x0300, + 0x0300, 0x0300, 0x0300, 0x0300, 0x0300, 0x0300, 0x0300, 0x0300, + 0x0300, 0x0300, 0x0300, 0x0300, 0x0300, 0x03E0, 0x03E0, 0x0000, + // '^' + 0x0000, 0x0000, 0x01C0, 0x01C0, 0x0360, 0x0360, 0x0360, 0x0630, + 0x0630, 0x0C18, 0x0C18, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // '_' + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0xFFFF, 0xFFFF, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // ''' + 0x0000, 0x000C, 0x000C, 0x000C, 0x000C, 0x000C, 0x000C, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'a' + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x03F0, 0x07F8, + 0x0C1C, 0x0C0C, 0x0F00, 0x0FF0, 0x0CF8, 0x0C0C, 0x0C0C, 0x0F1C, + 0x0FF8, 0x18F0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'b' + 0x0000, 0x0018, 0x0018, 0x0018, 0x0018, 0x0018, 0x03D8, 0x0FF8, + 0x0C38, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, 0x0C38, + 0x0FF8, 0x03D8, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'c' + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x03C0, 0x07F0, + 0x0E30, 0x0C18, 0x0018, 0x0018, 0x0018, 0x0018, 0x0C18, 0x0E30, + 0x07F0, 0x03C0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'd' + 0x0000, 0x1800, 0x1800, 0x1800, 0x1800, 0x1800, 0x1BC0, 0x1FF0, + 0x1C30, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, 0x1C30, + 0x1FF0, 0x1BC0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'e' + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x03C0, 0x0FF0, + 0x0C30, 0x1818, 0x1FF8, 0x1FF8, 0x0018, 0x0018, 0x1838, 0x1C30, + 0x0FF0, 0x07C0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'f' + 0x0000, 0x0F80, 0x0FC0, 0x00C0, 0x00C0, 0x00C0, 0x07F0, 0x07F0, + 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, + 0x00C0, 0x00C0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'g' + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0DE0, 0x0FF8, + 0x0E18, 0x0C0C, 0x0C0C, 0x0C0C, 0x0C0C, 0x0C0C, 0x0C0C, 0x0E18, + 0x0FF8, 0x0DE0, 0x0C00, 0x0C0C, 0x061C, 0x07F8, 0x01F0, 0x0000, + // 'h' + 0x0000, 0x0018, 0x0018, 0x0018, 0x0018, 0x0018, 0x07D8, 0x0FF8, + 0x1C38, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, + 0x1818, 0x1818, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'i' + 0x0000, 0x00C0, 0x00C0, 0x0000, 0x0000, 0x0000, 0x00C0, 0x00C0, + 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, + 0x00C0, 0x00C0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'j' + 0x0000, 0x00C0, 0x00C0, 0x0000, 0x0000, 0x0000, 0x00C0, 0x00C0, + 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, + 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00F8, 0x0078, 0x0000, + // 'k' + 0x0000, 0x000C, 0x000C, 0x000C, 0x000C, 0x000C, 0x0C0C, 0x060C, + 0x030C, 0x018C, 0x00CC, 0x006C, 0x00FC, 0x019C, 0x038C, 0x030C, + 0x060C, 0x0C0C, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'l' + 0x0000, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, + 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, + 0x00C0, 0x00C0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'm' + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x3C7C, 0x7EFF, + 0xE3C7, 0xC183, 0xC183, 0xC183, 0xC183, 0xC183, 0xC183, 0xC183, + 0xC183, 0xC183, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'n' + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0798, 0x0FF8, + 0x1C38, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, + 0x1818, 0x1818, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'o' + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x03C0, 0x0FF0, + 0x0C30, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, 0x0C30, + 0x0FF0, 0x03C0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'p' + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x03D8, 0x0FF8, + 0x0C38, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, 0x0C38, + 0x0FF8, 0x03D8, 0x0018, 0x0018, 0x0018, 0x0018, 0x0018, 0x0000, + // 'q' + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x1BC0, 0x1FF0, + 0x1C30, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, 0x1C30, + 0x1FF0, 0x1BC0, 0x1800, 0x1800, 0x1800, 0x1800, 0x1800, 0x0000, + // 'r' + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x07B0, 0x03F0, + 0x0070, 0x0030, 0x0030, 0x0030, 0x0030, 0x0030, 0x0030, 0x0030, + 0x0030, 0x0030, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 's' + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x03E0, 0x03F0, + 0x0E38, 0x0C18, 0x0038, 0x03F0, 0x07C0, 0x0C00, 0x0C18, 0x0E38, + 0x07F0, 0x03E0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 't' + 0x0000, 0x0000, 0x0080, 0x00C0, 0x00C0, 0x00C0, 0x07F0, 0x07F0, + 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, + 0x07C0, 0x0780, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'u' + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x1818, 0x1818, + 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, 0x1818, 0x1C38, + 0x1FF0, 0x19E0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'v' + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x180C, 0x0C18, + 0x0C18, 0x0C18, 0x0630, 0x0630, 0x0630, 0x0360, 0x0360, 0x0360, + 0x01C0, 0x01C0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'w' + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x41C1, 0x41C1, + 0x61C3, 0x6363, 0x6363, 0x6363, 0x3636, 0x3636, 0x3636, 0x1C1C, + 0x1C1C, 0x1C1C, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'x' + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x381C, 0x1C38, + 0x0C30, 0x0660, 0x0360, 0x0360, 0x0360, 0x0360, 0x0660, 0x0C30, + 0x1C38, 0x381C, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // 'y' + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x3018, 0x1830, + 0x1830, 0x1870, 0x0C60, 0x0C60, 0x0CE0, 0x06C0, 0x06C0, 0x0380, + 0x0380, 0x0380, 0x0180, 0x0180, 0x01C0, 0x00F0, 0x0070, 0x0000, + // 'z' + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x1FFC, 0x1FFC, + 0x0C00, 0x0600, 0x0300, 0x0180, 0x00C0, 0x0060, 0x0030, 0x0018, + 0x1FFC, 0x1FFC, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + // '{' + 0x0000, 0x0300, 0x0180, 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x00C0, + 0x00C0, 0x0060, 0x0060, 0x0030, 0x0060, 0x0040, 0x00C0, 0x00C0, + 0x00C0, 0x00C0, 0x00C0, 0x00C0, 0x0180, 0x0300, 0x0000, 0x0000, + // '|' + 0x0000, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, + 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, + 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0180, 0x0000, + // '}' + 0x0000, 0x0060, 0x00C0, 0x01C0, 0x0180, 0x0180, 0x0180, 0x0180, + 0x0180, 0x0300, 0x0300, 0x0600, 0x0300, 0x0100, 0x0180, 0x0180, + 0x0180, 0x0180, 0x0180, 0x0180, 0x00C0, 0x0060, 0x0000, 0x0000, + // '~' + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x10F0, 0x1FF8, 0x0F08, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, +}; + +void disp_char_1624(uint16_t x, uint16_t y, uint8_t c, uint16_t charColor, uint16_t bkColor) { + 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); + } +} + +void disp_string(uint16_t x, uint16_t y, const char * string, uint16_t charColor, uint16_t bkColor) { + while (*string != '\0') { + disp_char_1624(x, y, *string, charColor, bkColor); + string++; + x += 16; + } +} + +void disp_assets_update() { + SPI_TFT.LCD_clear(0x0000); + disp_string(100, 140, "Assets Updating...", 0xFFFF, 0x0000); +} + +void disp_assets_update_progress(const char *msg) { + char buf[30]; + memset(buf, ' ', COUNT(buf)); + strncpy(buf, msg, strlen(msg)); + buf[COUNT(buf)-1] = '\0'; + disp_string(100, 165, buf, 0xFFFF, 0x0000); +} + +#if BOTH(MKS_TEST, SDSUPPORT) + uint8_t mks_test_flag = 0; + const char *MKSTestPath = "MKS_TEST"; + void mks_test_get() { + SdFile dir, root = card.getroot(); + if (dir.open(&root, MKSTestPath, O_RDONLY)) + mks_test_flag = 0x1E; + } +#endif + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/mks_hardware.h b/Marlin/src/lcd/extui/mks_ui/mks_hardware.h new file mode 100644 index 000000000000..531326566277 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/mks_hardware.h @@ -0,0 +1,41 @@ +/** + * 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 + +#include "../../../inc/MarlinConfigPre.h" + +#include + +// Functions for MKS_TEST +#if BOTH(MKS_TEST, SDSUPPORT) + void mks_hardware_test(); + void mks_test_get(); + void mks_gpio_test(); + extern uint8_t mks_test_flag; +#else + #define mks_test_flag 0 +#endif + +// String display and assets +void disp_string(uint16_t x, uint16_t y, const char * string, uint16_t charColor, uint16_t bkColor); +void disp_assets_update(); +void disp_assets_update_progress(const char *msg); diff --git a/Marlin/src/lcd/extui/lib/mks_ui/pic_manager.cpp b/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp similarity index 92% rename from Marlin/src/lcd/extui/lib/mks_ui/pic_manager.cpp rename to Marlin/src/lcd/extui/mks_ui/pic_manager.cpp index 07ac56380262..0a5f5cd550a7 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/pic_manager.cpp +++ b/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp @@ -19,7 +19,7 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI @@ -27,23 +27,20 @@ #include "draw_ui.h" #include "pic_manager.h" #include "draw_ready_print.h" -#include "mks_hardware_test.h" - +#include "mks_hardware.h" #include "SPIFlashStorage.h" -#include "../../../../libs/W25Qxx.h" - -#include "../../../../sd/cardreader.h" -#include "../../../../MarlinCore.h" +#include "../../../libs/W25Qxx.h" +#include "../../../sd/cardreader.h" +#include "../../../MarlinCore.h" extern uint16_t DeviceCode; -extern unsigned char bmp_public_buf[17 * 1024]; #if ENABLED(SDSUPPORT) extern char *createFilename(char * const buffer, const dir_t &p); #endif static const char assets[][LONG_FILENAME_LENGTH] = { - //homing screen + // Homing screen "bmp_zeroAll.bin", "bmp_zero.bin", "bmp_zeroX.bin", @@ -51,33 +48,27 @@ static const char assets[][LONG_FILENAME_LENGTH] = { "bmp_zeroZ.bin", "bmp_manual_off.bin", - //tool screen + // Tool screen "bmp_preHeat.bin", "bmp_extruct.bin", "bmp_mov.bin", - // "bmp_Zero.bin", "bmp_leveling.bin", "bmp_filamentchange.bin", + "bmp_more.bin", - //fan screen + // Fan screen "bmp_Add.bin", "bmp_Dec.bin", "bmp_speed255.bin", "bmp_speed127.bin", "bmp_speed0.bin", - //preheat screen - // "bmp_Add.bin", - // "bmp_Dec.bin", - "bmp_speed0.bin", - // "bmp_Extru2.bin", - // "bmp_Extru1.bin", "bmp_bed.bin", "bmp_step1_degree.bin", "bmp_step5_degree.bin", "bmp_step10_degree.bin", - //extrusion screen + // Extrusion screen "bmp_in.bin", "bmp_out.bin", "bmp_extru1.bin", @@ -91,15 +82,15 @@ static const char assets[][LONG_FILENAME_LENGTH] = { "bmp_step5_mm.bin", "bmp_step10_mm.bin", - //select file screen + // Select file screen "bmp_pageUp.bin", "bmp_pageDown.bin", "bmp_back.bin", //TODO: why two back buttons? Why not just one? (return / back) "bmp_dir.bin", "bmp_file.bin", - //move motor screen - //TODO: 6 equal icons, just in diffenct rotation... it may be optimized too + // Move motor screen + // TODO: 6 equal icons, just in diffenct rotation... it may be optimized too "bmp_xAdd.bin", "bmp_xDec.bin", "bmp_yAdd.bin", @@ -110,26 +101,24 @@ static const char assets[][LONG_FILENAME_LENGTH] = { "bmp_step_move1.bin", "bmp_step_move10.bin", - //operation screen + // Operation screen "bmp_auto_off.bin", "bmp_speed.bin", - //"bmp_Mamual.bin", //TODO: didn't find it.. changed to bmp_manual_off.bin "bmp_fan.bin", "bmp_temp.bin", "bmp_extrude_opr.bin", "bmp_move_opr.bin", - //change speed screen + // Change speed screen "bmp_step1_percent.bin", "bmp_step5_percent.bin", "bmp_step10_percent.bin", "bmp_extruct_sel.bin", "bmp_mov_changespeed.bin", - // "bmp_extrude_opr.bin", equal to "bmp_Extruct.bin" "bmp_mov_sel.bin", "bmp_speed_extruct.bin", - //printing screen + // Printing screen "bmp_pause.bin", "bmp_resume.bin", "bmp_stop.bin", @@ -143,7 +132,7 @@ static const char assets[][LONG_FILENAME_LENGTH] = { "bmp_zpos_state.bin", "bmp_operate.bin", - //manual leval screen (only if disabled auto level) + // Manual Level screen (only if auto level is disabled) #if DISABLED(AUTO_BED_LEVELING_BILINEAR) "bmp_leveling1.bin", "bmp_leveling2.bin", @@ -152,7 +141,7 @@ static const char assets[][LONG_FILENAME_LENGTH] = { "bmp_leveling5.bin", #endif - //lang select screen + // Language Select screen #if HAS_LANG_SELECT_SCREEN "bmp_language.bin", "bmp_simplified_cn.bin", @@ -171,7 +160,7 @@ static const char assets[][LONG_FILENAME_LENGTH] = { "bmp_italy_sel.bin", #endif // HAS_LANG_SELECT_SCREEN - // gcode preview + // G-code preview #if HAS_GCODE_DEFAULT_VIEW_IN_FLASH "bmp_preview.bin", #endif @@ -180,23 +169,18 @@ static const char assets[][LONG_FILENAME_LENGTH] = { "bmp_logo.bin", #endif - // settings screen + // Settings screen "bmp_about.bin", - //"bmp_Language.bin", - //"bmp_Fan.bin", - //"bmp_manual_off.bin", + "bmp_eeprom_settings.bin", + "bmp_machine_para.bin", + "bmp_function1.bin", - //start screen + // Start screen "bmp_printing.bin", "bmp_set.bin", "bmp_tool.bin", - // settings screen - "bmp_eeprom_settings.bin", - "bmp_machine_para.bin", - "bmp_function1.bin", - - // base icons + // Base icons "bmp_arrow.bin", "bmp_back70x40.bin", "bmp_value_blank.bin", @@ -205,15 +189,32 @@ static const char assets[][LONG_FILENAME_LENGTH] = { "bmp_enable.bin", "bmp_return.bin", - #if ENABLED(USE_WIFI_FUNCTION) - //wifi screen + #if ENABLED(MKS_WIFI_MODULE) + // Wifi screen "bmp_wifi.bin", + "bmp_cloud.bin", #endif - //babystep screen + #if ENABLED(MULTI_VOLUME) + "bmp_usb_disk.bin", + // "bmp_usb_disk_sel.bin", + "bmp_sd.bin", + // "bmp_sd_sel.bin", + #endif + + // Babystep screen "bmp_baby_move0_01.bin", "bmp_baby_move0_05.bin", - "bmp_baby_move0_1.bin" + "bmp_baby_move0_1.bin", + + // More screen + "bmp_custom1.bin", + "bmp_custom2.bin", + "bmp_custom3.bin", + "bmp_custom4.bin", + "bmp_custom5.bin", + "bmp_custom6.bin", + "bmp_custom7.bin" }; #if HAS_SPI_FLASH_FONT @@ -247,14 +248,13 @@ uint32_t lv_get_pic_addr(uint8_t *Pname) { } while (PIC.name[j++] != '\0'); if ((strcasecmp((char*)Pname, (char*)PIC.name)) == 0) { - if ((DeviceCode == 0x9488) || (DeviceCode == 0x5761)) + if (DeviceCode == 0x9488 || DeviceCode == 0x5761) addr = PIC_DATA_ADDR_TFT35 + i * PER_PIC_MAX_SPACE_TFT35; else addr = PIC_DATA_ADDR_TFT32 + i * PER_PIC_MAX_SPACE_TFT32; return addr; } } - return addr; } @@ -373,11 +373,9 @@ uint32_t Pic_Info_Write(uint8_t *P_name, uint32_t P_size) { return Pic_SaveAddr; } -uint8_t public_buf[512]; - #if ENABLED(SDSUPPORT) - static void dosName2LongName(const char dosName[11], char* longName) { + static void dosName2LongName(const char dosName[11], char *longName) { uint8_t j = 0; LOOP_L_N(i, 11) { if (i == 8) longName[j++] = '.'; @@ -387,7 +385,7 @@ uint8_t public_buf[512]; longName[j] = '\0'; } - static int8_t arrayFindStr(const char arr[][LONG_FILENAME_LENGTH], uint8_t arraySize, const char* str) { + static int8_t arrayFindStr(const char arr[][LONG_FILENAME_LENGTH], uint8_t arraySize, const char *str) { for (uint8_t a = 0; a < arraySize; a++) { if (strcasecmp(arr[a], str) == 0) return a; @@ -488,6 +486,7 @@ uint8_t public_buf[512]; } void UpdateAssets() { + if (!card.isMounted()) return; SdFile dir, root = card.getroot(); if (dir.open(&root, assetsPath, O_RDONLY)) { @@ -504,7 +503,7 @@ uint8_t public_buf[512]; disp_assets_update_progress("Reading files..."); dir_t d; while (dir.readDir(&d, card.longFilename) > 0) { - // If we dont get a long name, but gets a short one, try it + // If we don't get a long name, but gets a short one, try it if (card.longFilename[0] == 0 && d.name[0] != 0) dosName2LongName((const char*)d.name, card.longFilename); if (card.longFilename[0] == 0) continue; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/pic_manager.h b/Marlin/src/lcd/extui/mks_ui/pic_manager.h similarity index 85% rename from Marlin/src/lcd/extui/lib/mks_ui/pic_manager.h rename to Marlin/src/lcd/extui/mks_ui/pic_manager.h index ea75915df363..90e2407ab05c 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/pic_manager.h +++ b/Marlin/src/lcd/extui/mks_ui/pic_manager.h @@ -21,9 +21,9 @@ */ #pragma once -#include "../../../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" -#include "../../../../libs/W25Qxx.h" +#include "../../../libs/W25Qxx.h" #include @@ -95,9 +95,7 @@ #define PIC_NAME_ADDR 0x003000 // Pic information addr #define PIC_SIZE_ADDR 0x007000 // Pic size information addr #define PIC_COUNTER_ADDR 0x008000 // Pic total number - //#define PER_PIC_SAVE_ADDR 0x009000 // Storage address of each picture #define PIC_LOGO_ADDR 0x009000 // Logo addr - //#define PIC_DATA_ADDR 0x02F000 // // TFT35 #define DEFAULT_VIEW_ADDR_TFT35 0xC5800 @@ -118,11 +116,11 @@ #endif // Flash flag -#define REFLSHE_FLGA_ADD (0X800000-32) +#define REFLSHE_FLGA_ADD (0x800000-32) // SD card information first addr #define VAR_INF_ADDR 0x000000 -#define FLASH_INF_VALID_FLAG 0x20200831 +#define FLASH_INF_VALID_FLAG 0x20201118 //Store some gcode commands, such as auto leveling commands #define GCODE_COMMAND_ADDR VAR_INF_ADDR + 3*1024 @@ -156,14 +154,14 @@ typedef struct pic_msg PIC_MSG; #define PIC_SIZE_xM 6 #define FONT_SIZE_xM 2 -extern void Pic_Read(uint8_t *Pname, uint8_t *P_Rbuff); -extern void Pic_Logo_Read(uint8_t *LogoName,uint8_t *Logo_Rbuff,uint32_t LogoReadsize); -extern void lv_pic_test(uint8_t *P_Rbuff, uint32_t addr, uint32_t size); -extern uint32_t lv_get_pic_addr(uint8_t *Pname); -extern void get_spi_flash_data(const char *rec_buf, int offset, int size); -extern void spi_flash_read_test(); -extern void default_view_Read(uint8_t *default_view_Rbuff, uint32_t default_view_Readsize); -extern void flash_view_Read(uint8_t *flash_view_Rbuff, uint32_t flash_view_Readsize); +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 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); +void spi_flash_read_test(); +void default_view_Read(uint8_t *default_view_Rbuff, uint32_t default_view_Readsize); +void flash_view_Read(uint8_t *flash_view_Rbuff, uint32_t flash_view_Readsize); #ifdef __cplusplus } /* C-declarations for C++ */ diff --git a/Marlin/src/lcd/extui/mks_ui/printer_operation.cpp b/Marlin/src/lcd/extui/mks_ui/printer_operation.cpp new file mode 100644 index 000000000000..1bb17bb4f224 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/printer_operation.cpp @@ -0,0 +1,213 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include + +#include "../../../gcode/gcode.h" +#include "../../../module/planner.h" +#include "../../../module/motion.h" +#include "../../../sd/cardreader.h" +#include "../../../inc/MarlinConfig.h" +#include "../../../MarlinCore.h" +#include "../../../gcode/queue.h" + +#if ENABLED(POWER_LOSS_RECOVERY) + #include "../../../feature/powerloss.h" +#endif + +extern uint32_t To_pre_view; +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 (!planner.has_blocks_queued() && card.getIndex() > MIN_FILE_PRINTED) + uiCfg.waitEndMoves++; + + if (uiCfg.waitEndMoves > 20) { + uiCfg.waitEndMoves = 0; + planner.synchronize(); + + gcode.process_subcommands_now_P(PSTR("M25")); + + //save the position + uiCfg.current_x_position_bak = current_position.x; + uiCfg.current_y_position_bak = current_position.y; + uiCfg.current_z_position_bak = current_position.z; + + if (gCfgItems.pausePosZ != (float)-1) { + sprintf_P(public_buf_l, PSTR("G91\nG1 Z%s\nG90"), dtostrf(gCfgItems.pausePosZ, 1, 1, str_1)); + gcode.process_subcommands_now(public_buf_l); + } + if (gCfgItems.pausePosX != (float)-1 && gCfgItems.pausePosY != (float)-1) { + sprintf_P(public_buf_l, PSTR("G1 X%s Y%s"), dtostrf(gCfgItems.pausePosX, 1, 1, str_1), dtostrf(gCfgItems.pausePosY, 1, 1, str_1)); + gcode.process_subcommands_now(public_buf_l); + } + uiCfg.print_state = PAUSED; + uiCfg.current_e_position_bak = current_position.e; + + gCfgItems.pause_reprint = true; + update_spi_flash(); + } + #endif + } + else + uiCfg.waitEndMoves = 0; + + if (uiCfg.print_state == PAUSED) { + } + + if (uiCfg.print_state == RESUMING) { + if (IS_SD_PAUSED()) { + if (gCfgItems.pausePosX != (float)-1 && gCfgItems.pausePosY != (float)-1) { + sprintf_P(public_buf_m, PSTR("G1 X%s Y%s"), dtostrf(uiCfg.current_x_position_bak, 1, 1, str_1), dtostrf(uiCfg.current_y_position_bak, 1, 1, str_1)); + gcode.process_subcommands_now(public_buf_m); + } + if (gCfgItems.pausePosZ != (float)-1) { + ZERO(public_buf_m); + sprintf_P(public_buf_m, PSTR("G1 Z%s"), dtostrf(uiCfg.current_z_position_bak, 1, 1, str_1)); + gcode.process_subcommands_now(public_buf_m); + } + gcode.process_subcommands_now_P(M24_STR); + uiCfg.print_state = WORKING; + start_print_time(); + + gCfgItems.pause_reprint = false; + update_spi_flash(); + } + } + #if ENABLED(POWER_LOSS_RECOVERY) + if (uiCfg.print_state == REPRINTED) { + #if HAS_HOTEND + HOTEND_LOOP() { + const int16_t et = recovery.info.target_temperature[e]; + if (et) { + #if HAS_MULTI_HOTEND + sprintf_P(public_buf_m, PSTR("T%i"), e); + gcode.process_subcommands_now(public_buf_m); + #endif + sprintf_P(public_buf_m, PSTR("M109 S%i"), et); + gcode.process_subcommands_now(public_buf_m); + } + } + #endif + + recovery.resume(); + #if 0 + // Move back to the saved XY + char str_1[16], str_2[16]; + sprintf_P(public_buf_m, PSTR("G1 X%s Y%s F2000"), + dtostrf(recovery.info.current_position.x, 1, 3, str_1), + dtostrf(recovery.info.current_position.y, 1, 3, str_2) + ); + gcode.process_subcommands_now(public_buf_m); + + if (gCfgItems.pause_reprint && gCfgItems.pausePosZ != -1.0f) { + sprintf_P(public_buf_l, PSTR("G91\nG1 Z-%s\nG90"), dtostrf(gCfgItems.pausePosZ, 1, 1, str_2)); + gcode.process_subcommands_now(public_buf_l); + } + #endif + uiCfg.print_state = WORKING; + start_print_time(); + + gCfgItems.pause_reprint = false; + update_spi_flash(); + } + #endif + + if (uiCfg.print_state == WORKING) + filament_check(); + + TERN_(MKS_WIFI_MODULE, wifi_looping()); +} + +void filament_pin_setup() { + #if PIN_EXISTS(MT_DET_1) + SET_INPUT_PULLUP(MT_DET_1_PIN); + #endif + #if PIN_EXISTS(MT_DET_2) + SET_INPUT_PULLUP(MT_DET_2_PIN); + #endif + #if PIN_EXISTS(MT_DET_3) + SET_INPUT_PULLUP(MT_DET_3_PIN); + #endif +} + +void filament_check() { + #if ANY_PIN(MT_DET_1, MT_DET_2, MT_DET_3) + const int FIL_DELAY = 20; + #endif + #if PIN_EXISTS(MT_DET_1) + static int fil_det_count_1 = 0; + if (READ(MT_DET_1_PIN) == MT_DET_PIN_INVERTING) + fil_det_count_1++; + else if (fil_det_count_1 > 0) + fil_det_count_1--; + #endif + + #if PIN_EXISTS(MT_DET_2) + static int fil_det_count_2 = 0; + if (READ(MT_DET_2_PIN) == MT_DET_PIN_INVERTING) + fil_det_count_2++; + else if (fil_det_count_2 > 0) + fil_det_count_2--; + #endif + + #if PIN_EXISTS(MT_DET_3) + static int fil_det_count_3 = 0; + if (READ(MT_DET_3_PIN) == MT_DET_PIN_INVERTING) + fil_det_count_3++; + else if (fil_det_count_3 > 0) + fil_det_count_3--; + #endif + + if (false + #if PIN_EXISTS(MT_DET_1) + || fil_det_count_1 >= FIL_DELAY + #endif + #if PIN_EXISTS(MT_DET_2) + || fil_det_count_2 >= FIL_DELAY + #endif + #if PIN_EXISTS(MT_DET_3) + || fil_det_count_3 >= FIL_DELAY + #endif + ) { + clear_cur_ui(); + card.pauseSDPrint(); + stop_print_time(); + uiCfg.print_state = PAUSING; + + if (gCfgItems.from_flash_pic) + flash_preview_begin = true; + else + default_preview_flg = true; + + lv_draw_printing(); + } +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/printer_operation.h b/Marlin/src/lcd/extui/mks_ui/printer_operation.h similarity index 91% rename from Marlin/src/lcd/extui/lib/mks_ui/printer_operation.h rename to Marlin/src/lcd/extui/mks_ui/printer_operation.h index f30415882451..499799c6c78b 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/printer_operation.h +++ b/Marlin/src/lcd/extui/mks_ui/printer_operation.h @@ -27,9 +27,9 @@ #define MIN_FILE_PRINTED 100 //5000 -extern void printer_state_polling(); -extern void filament_pin_setup(); -extern void filament_check(); +void printer_state_polling(); +void filament_pin_setup(); +void filament_check(); #ifdef __cplusplus } /* C-declarations for C++ */ diff --git a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_en.h b/Marlin/src/lcd/extui/mks_ui/tft_Language_en.h similarity index 85% rename from Marlin/src/lcd/extui/lib/mks_ui/tft_Language_en.h rename to Marlin/src/lcd/extui/mks_ui/tft_Language_en.h index fa8d5a52a496..e1a2a256d947 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_en.h +++ b/Marlin/src/lcd/extui/mks_ui/tft_Language_en.h @@ -48,7 +48,7 @@ #define MACHINE_TYPE_CNOFIG_EN "Machine settings" #define MOTOR_CONFIG_EN "Motor settings" #define MACHINE_LEVELING_CONFIG_EN "Leveling settings" -#define ADVANCE_CONFIG_EN "Adavance settings" +#define ADVANCE_CONFIG_EN "Advanced settings" #define MACHINE_CONFIG_TITLE_EN "Machine Settings" #define MACHINE_TYPE_EN "Machine type" @@ -82,9 +82,9 @@ #define MIN_ENDSTOP_X_EN "X-axis minimum Endstop" #define MIN_ENDSTOP_Y_EN "Y-axis minimum Endstop" #define MIN_ENDSTOP_Z_EN "Z-axis minimum Endstop" -#define MAX_ENDSTOP_X_EN "X axis maximum Endstop" -#define MAX_ENDSTOP_Y_EN "Y axis maximum Endstop" -#define MAX_ENDSTOP_Z_EN "Z axis maximum Endstop" +#define MAX_ENDSTOP_X_EN "X-axis maximum Endstop" +#define MAX_ENDSTOP_Y_EN "Y-axis maximum Endstop" +#define MAX_ENDSTOP_Z_EN "Z-axis maximum Endstop" #define ENDSTOP_FIL_EN "Filament sensor" #define ENDSTOP_LEVEL_EN "Leveling sensor" #define ENDSTOP_OPENED_EN "Open" @@ -99,21 +99,22 @@ #define LEVELING_CONF_TITLE_EN "Machine Settings>Leveling settings" #define LEVELING_PARA_CONF_EN "Leveling settings" -#define LEVELING_MANUAL_POS_EN "Manual leveling coordinate settings" +#define TRAMMING_POS_EN "Manual leveling coordinate settings" #define LEVELING_AUTO_COMMAND_EN "AutoLeveling command settings" #define LEVELING_AUTO_ZOFFSET_EN "Nozzle-to-probe offsets settings" #define LEVELING_PARA_CONF_TITLE_EN "leveling setting" #define AUTO_LEVELING_ENABLE_EN "Enable auto leveling" -#define BLTOUCH_LEVELING_ENABLE_EN "Enable BLtouch" +#define BLTOUCH_LEVELING_ENABLE_EN "Enable BLTouch" #define PROBE_PORT_EN "Probe connector" -#define PROBE_X_OFFSET_EN "Probe x axis offset" -#define PROBE_Y_OFFSET_EN "Probe y axis offset" -#define PROBE_Z_OFFSET_EN "Probe z axis offset" -#define PROBE_XY_SPEED_EN "Probe xy axis speed" -#define PROBE_Z_SPEED_EN "Probe z axis speed" +#define PROBE_X_OFFSET_EN "Probe X-axis offset" +#define PROBE_Y_OFFSET_EN "Probe Y-axis offset" +#define PROBE_Z_OFFSET_EN "Probe Z-axis offset" +#define PROBE_XY_SPEED_EN "Probe XY-axis speed" +#define PROBE_Z_SPEED_EN "Probe Z-axis speed" #define ENABLE_EN "YES" #define DISABLE_EN "NO" +#define LOCKED_EN "N/A" #define Z_MIN_EN "ZMin" #define Z_MAX_EN "ZMax" @@ -162,11 +163,11 @@ #define HOMEFEEDRATECONF_EN "Home speed setting" #define MAXFEEDRATE_CONF_TITLE_EN "Machine Settings>Maximum speed" -#define X_MAXFEEDRATE_EN "X axis maximum speed" -#define Y_MAXFEEDRATE_EN "Y axis maximum speed" -#define Z_MAXFEEDRATE_EN "Z axis maximum speed" -#define E0_MAXFEEDRATE_EN "E0 axis maximum speed" -#define E1_MAXFEEDRATE_EN "E1 axis maximum speed" +#define X_MAXFEEDRATE_EN "X-axis maximum speed" +#define Y_MAXFEEDRATE_EN "Y-axis maximum speed" +#define Z_MAXFEEDRATE_EN "Z-axis maximum speed" +#define E0_MAXFEEDRATE_EN "E0 maximum speed" +#define E1_MAXFEEDRATE_EN "E1 maximum speed" #define ACCELERATION_CONF_TITLE_EN "Machine Settings>Acceleration" #define PRINT_ACCELERATION_EN "Print acceleration" @@ -175,49 +176,49 @@ #define X_ACCELERATION_EN "X-axis acceleration" #define Y_ACCELERATION_EN "Y-axis acceleration" #define Z_ACCELERATION_EN "Z-axis acceleration" -#define E0_ACCELERATION_EN "E0-axis acceleration" -#define E1_ACCELERATION_EN "E1-axis acceleration" +#define E0_ACCELERATION_EN "E0 acceleration" +#define E1_ACCELERATION_EN "E1 acceleration" #define JERK_CONF_TITLE_EN "Machine Settings>Jerk speed" #define X_JERK_EN "X-axis jerk speed" #define Y_JERK_EN "Y-axis jerk speed" -#define Z_JERK_EN "J-axis jerk speed" -#define E_JERK_EN "E-axis jerk speed" +#define Z_JERK_EN "Z-axis jerk speed" +#define E_JERK_EN "Extruder jerk speed" #define STEPS_CONF_TITLE_EN "Machine Settings>Steps settings" #define X_STEPS_EN "X-axis steps" -#define Y_STEPS_EN "Y-axis stepS" -#define Z_STEPS_EN "Z-axis stepS" -#define E0_STEPS_EN "E0-axis steps" -#define E1_STEPS_EN "E1-axis steps" +#define Y_STEPS_EN "Y-axis steps" +#define Z_STEPS_EN "Z-axis steps" +#define E0_STEPS_EN "E0 steps" +#define E1_STEPS_EN "E1 steps" #define TMC_CURRENT_CONF_TITLE_EN "Machine Settings>TMC current settings" -#define X_TMC_CURRENT_EN "X axis current (mA)" -#define Y_TMC_CURRENT_EN "Y axis current (mA)" -#define Z_TMC_CURRENT_EN "Z axis current (mA)" -#define E0_TMC_CURRENT_EN "E0 axis current (mA)" -#define E1_TMC_CURRENT_EN "E1 axis current (mA)" +#define X_TMC_CURRENT_EN "X-axis current (mA)" +#define Y_TMC_CURRENT_EN "Y-axis current (mA)" +#define Z_TMC_CURRENT_EN "Z-axis current (mA)" +#define E0_TMC_CURRENT_EN "E0 current (mA)" +#define E1_TMC_CURRENT_EN "E1 current (mA)" #define TMC_MODE_CONF_TITLE_EN "Machine Settings>TMC step mode settings" -#define X_TMC_MODE_EN "Whether X axis enable stealthChop modes" -#define Y_TMC_MODE_EN "Whether Y axis enable stealthChop modes" -#define Z_TMC_MODE_EN "Whether Z axis enable stealthChop modes" -#define E0_TMC_MODE_EN "Whether E0 axis enable stealthChop modes" -#define E1_TMC_MODE_EN "Whether E1 axis enable stealthChop modes" +#define X_TMC_MODE_EN "Whether X-axis enables stealthChop mode" +#define Y_TMC_MODE_EN "Whether Y-axis enables stealthChop mode" +#define Z_TMC_MODE_EN "Whether Z-axis enables stealthChop mode" +#define E0_TMC_MODE_EN "Whether E0 enables stealthChop mode" +#define E1_TMC_MODE_EN "Whether E1 enables stealthChop mode" #define MOTORDIR_CONF_TITLE_EN "Machine Settings>Motor direction" #define X_MOTORDIR_EN "X-axis motor direction invert" #define Y_MOTORDIR_EN "Y-axis motor direction invert" #define Z_MOTORDIR_EN "Z-axis motor direction invert" -#define E0_MOTORDIR_EN "E0-axis motor direction invert" -#define E1_MOTORDIR_EN "E1-axis motor direction invert" +#define E0_MOTORDIR_EN "E0 motor direction invert" +#define E1_MOTORDIR_EN "E1 motor direction invert" #define INVERT_P_EN "YES" #define INVERT_N_EN "NO" #define HOMEFEEDRATE_CONF_TITLE_EN "Machine Settings>Home speed" -#define X_HOMESPEED_EN "XY-axis Home speed" -#define Y_HOMESPEED_EN "Y-axis Home speed" -#define Z_HOMESPEED_EN "Z-axis Home speed" +#define X_HOMESPEED_EN "XY-axis home speed" +#define Y_HOMESPEED_EN "Y-axis home speed" +#define Z_HOMESPEED_EN "Z-axis home speed" #define ADVANCED_CONF_TITLE_EN "Machine Settings>Advance" #define PWROFF_DECTION_EN "power off dection module" @@ -241,9 +242,9 @@ #define E_ENABLE_PINS_INVERT_EN "E_ENABLE_PIN_INVERT" #define PAUSE_POSITION_EN "Printing pause position settings" -#define PAUSE_POSITION_X_EN "X axis position (Absolute position,-1 invalid)" -#define PAUSE_POSITION_Y_EN "Y axis position (Absolute position,-1 invalid)" -#define PAUSE_POSITION_Z_EN "Z axis position (Relative position,-1 invalid)" +#define PAUSE_POSITION_X_EN "X-axis position (Absolute position,-1 invalid)" +#define PAUSE_POSITION_Y_EN "Y-axis position (Absolute position,-1 invalid)" +#define PAUSE_POSITION_Z_EN "Z-axis position (Relative position,-1 invalid)" #define WIFI_SETTINGS_TITLE_EN "Machine Settings>Wi-Fi Parameter" #define WIFI_SETTINGS_MODE_EN "Wi-Fi Mode" @@ -260,10 +261,10 @@ #define OFFSET_Z_EN "Z offset" #define HOMING_SENSITIVITY_CONF_TITLE_EN "Machine Settings>Sensitivity" -#define X_SENSITIVITY_EN "X Axis Sensitivity" -#define Y_SENSITIVITY_EN "Y Axis Sensitivity" -#define Z_SENSITIVITY_EN "Z Axis Sensitivity" -#define Z2_SENSITIVITY_EN "Z2 Axis Sensitivity" +#define X_SENSITIVITY_EN "X-axis sensitivity" +#define Y_SENSITIVITY_EN "Y-axis sensitivity" +#define Z_SENSITIVITY_EN "Z-axis sensitivity" +#define Z2_SENSITIVITY_EN "Z2-axis sensitivity" #define ENCODER_CONF_TITLE_EN "Machine Settings>Rotary encoder settings" #define ENCODER_CONF_TEXT_EN "Is the encoder function used?" @@ -278,6 +279,8 @@ #define AUTO_LEVELING_TEXT_EN "AutoLevel" #define SET_TEXT_EN "Settings" #define MORE_TEXT_EN "More" +#define MORE_GCODE_EN "G-Code" +#define MORE_ENTER_GCODE_EN "Enter G-Code" #define ADD_TEXT_EN "Add" #define DEC_TEXT_EN "Dec" @@ -381,28 +384,12 @@ #define FILAMENT_EXT1_TEXT_EN "Extrusion2" #define FILAMENT_HEAT_TEXT_EN "Preheat" #define FILAMENT_STOP_TEXT_EN "Stop" -//#define FILAMENT_CHANGE_TEXT_EN "Filament replace" #define FILAMENT_TIPS2_TEXT_EN "T:" #define FILAMENT_TIPS3_TEXT_EN "Loading..." #define FILAMENT_TIPS4_TEXT_EN "Unloading..." #define FILAMENT_TIPS5_TEXT_EN "Temp is too low to go,please heat" #define FILAMENT_TIPS6_TEXT_EN "Completed" -#if 0 - #define FILAMENT_REPLAYS_IDLE_TEXT_EN "Please click or \nto replace filament!" - #define FILAMENT_CHANGE_TEXT_EN "Please click or ,\nAfter pinter pause." - #define FILAMENT_DIALOG_LOAD_HEAT_TIPS_EN "Heating up the nozzle,please wait..." - #define FILAMENT_DIALOG_UNLOAD_HEAT_TIPS_EN "Heating up the nozzle,please wait..." - #define FILAMENT_DIALOG_LOAD_CONFIRM1_TIPS_EN "Heat completed,please load filament to extruder,and click for start loading." - #define FILAMENT_DIALOG_LOAD_CONFIRM2_TIPS_EN "Please load filament to extruder,and click for start loading." - #define FILAMENT_DIALOG_UNLOAD_CONFIRM_TIPS_EN "Heat completed,please click for start unloading.!" - #define FILAMENT_DIALOG_LOADING_TIPS_EN "Is loading ,please wait!" - #define FILAMENT_DIALOG_UNLOADING_TIPS_EN "Is unloading,please wait!" - #define FILAMENT_DIALOG_LOAD_COMPLETE_TIPS_EN "Load filament completed,click for return!" - #define FILAMENT_DIALOG_UNLOAD_COMPLETE_TIPS_EN "Unload filament completed,click for return!" -#endif - - #define FILAMENT_CHANGE_TEXT_EN "Please click \nor ,After \npinter pause." #define FILAMENT_DIALOG_LOAD_HEAT_TIPS_EN "Heating up the nozzle,\nplease wait..." #define FILAMENT_DIALOG_UNLOAD_HEAT_TIPS_EN "Heating up the nozzle,\nplease wait..." @@ -414,16 +401,11 @@ #define FILAMENT_DIALOG_LOAD_COMPLETE_TIPS_EN "Load filament completed,\nclick for return!" #define FILAMENT_DIALOG_UNLOAD_COMPLETE_TIPS_EN "Unload filament completed,\nclick for return!" - #define PRE_HEAT_EXT_TEXT_EN "E" #define PRE_HEAT_BED_TEXT_EN "Bed" #define FILE_LOADING_EN "Loading......" -#if 0 - #define NO_FILE_AND_CHECK_EN "No files found!Please insert SD card or U disk!" -#else - #define NO_FILE_AND_CHECK_EN " No files found!\n Check the file system configuration!" -#endif +#define NO_FILE_AND_CHECK_EN " No files found!\n Check the file system configuration!" #define NO_FILE_EN "No files found!" @@ -491,7 +473,6 @@ #define DIALOG_RETRY_EN "Retry" #define DIALOG_STOP_EN "Stop" #define DIALOG_REPRINT_FROM_BREAKPOINT_EN "Reprint from breakpoint?" -//#define DIALOG_UNBIND_PRINTER_EN "Unbind the printer?" #define DIALOG_ERROR_TIPS1_EN "Error:no file,please check it again." #define DIALOG_ERROR_TIPS2_EN "Error:transaction failed.please check display baudrate \nwhether as the same as mainboard!" #define DIALOG_ERROR_TIPS3_EN "Error:file name or path is too long!" @@ -559,6 +540,7 @@ #define USB_DRIVE_BACK_EN "< Back" #define FILE_PAGES_EN "%d/%d" #define FILE_NEXT_PAGE_EN "Next Page" +#define MEDIA_SELECT_TITLE_EN "Select Media" //BUILD PLATE #define PLATE_TITLE_EN "Build Plate" @@ -691,34 +673,16 @@ //manual ip #define MANUAL_IP_TITLE_EN "Manual IP" -#define MANUAL_IP_CANCEL_EN "< Cancel" +#define MANUAL_IP_CANCEL_EN "< Cancel" #define MANUAL_IP_APPLY_EN "Join >" #define MANUAL_IP_ADDRESS_EN "IP Address" #define MANUAL_IP_MASK_EN "Subnet Mask" #define MANUAL_IP_GATEWAY_EN "Default Gateway" #define MANUAL_IP_SERVER_EN "Name Server" #define MANUAL_IP_INIT_DATA_EN "0.0.0.0" -#define MANUAL_TEXT_POINT_EN "." +#define MANUAL_TEXT_POINT_EN "." #define MANUAL_TEXT_ENTER_EN "enter" -//Wifi name -//#define TEXT_WIFI_MENU_TITLE_EN "WI-FI" -//#define TEXT_WIFI_SAPCE_EN "space" -//#define TEXT_WIFI_LETTER_EN "abc" -//#define TEXT_WIFI_DIGITAL_EN "123" -//#define TEXT_WIFI_SYMBOL_EN "#+=" -//#define TEXT_WIFI_PASSWORD_EN "Password" - -//#define TEXT_WIFI_POINT_BOLD_EN "`" - -//#define TEXT_WIFI_JOINING_EN "Joining\nNetwork..." -//#define TEXT_WIFI_FAILED_JOIN_EN "Failed to\nJoin Wi-Fi" -//#define TEXT_WIFI_WIFI_CONECTED_EN "Wi-Fi\nConnected" - -//#define TEXT_BUTTON_DISCONECTED_EN "Disconnect" -//#define TEXT_WIFI_FORGET_EN "Forget Network" -//#define TEXT_DISCONECTED_EN "Wi-Fi Connected" - #define TEXT_FORGET_TIPS_TITLE_EN "Forget Network" #define TEXT_FORGET_NETWORK_TIPS1_EN "Are you sure you want to\nforget this network?" #define TEXT_FORGET_NETWORK_TIPS2_EN "This machine will no longer\njoin this Wi-Fi Network." @@ -764,3 +728,10 @@ #define EEPROM_STORE_TIPS_EN "Store settings to EEPROM?" #define EEPROM_READ_TIPS_EN "Read settings from EEPROM?" #define EEPROM_REVERT_TIPS_EN "Revert settings to factory defaults?" + +#define MORE_CUSTOM1_TEXT_EN MAIN_MENU_ITEM_1_DESC +#define MORE_CUSTOM2_TEXT_EN MAIN_MENU_ITEM_2_DESC +#define MORE_CUSTOM3_TEXT_EN MAIN_MENU_ITEM_3_DESC +#define MORE_CUSTOM4_TEXT_EN MAIN_MENU_ITEM_4_DESC +#define MORE_CUSTOM5_TEXT_EN MAIN_MENU_ITEM_5_DESC +#define MORE_CUSTOM6_TEXT_EN MAIN_MENU_ITEM_6_DESC diff --git a/Marlin/src/lcd/extui/mks_ui/tft_Language_fr.h b/Marlin/src/lcd/extui/mks_ui/tft_Language_fr.h new file mode 100644 index 000000000000..f0b19d4e0275 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/tft_Language_fr.h @@ -0,0 +1,268 @@ +/** + * 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 TOOL_TEXT_FR "Prêt" +#define PREHEAT_TEXT_FR "Préchauffe" +#define MOVE_TEXT_FR "Déplace" +#define HOME_TEXT_FR "Acceuil" +#define PRINT_TEXT_FR "Impression" +#define EXTRUDE_TEXT_FR "Extruder" +#define LEVELING_TEXT_FR "Leveling" +#define AUTO_LEVELING_TEXT_FR "AutoLevel" +#define SET_TEXT_FR "Config" +#define MORE_TEXT_FR "Plus" +#define MORE_GCODE_FR "G-Code" +#define MORE_ENTER_GCODE_FR "Saisir G-Code" + +#define ADD_TEXT_FR "Ajouter" +#define DEC_TEXT_FR "Réduire" +#define EXTRUDER_1_TEXT_FR "Extr1" +#define EXTRUDER_2_TEXT_FR "Extr2" +#define HEATBED_TEXT_FR "Hotlit" +#define TEXT_1C_FR "1℃" +#define TEXT_5C_FR "5℃" +#define TEXT_10C_FR "10℃" +#define CLOSE_TEXT_FR "Off" + +#define BACK_TEXT_FR "Arrière" + +#define TOOL_PREHEAT_FR "Préchauffe" +#define TOOL_EXTRUDE_FR "Extruder" +#define TOOL_MOVE_FR "Déplace" +#define TOOL_HOME_FR "Acceuil" +#define TOOL_LEVELING_FR "Leveling" +#define TOOL_AUTO_LEVELING_FR "AutoLevel" +#define TOOL_FILAMENT_FR "Filament" +#define TOOL_MORE_FR "Plus" + +#define AXIS_X_ADD_TEXT_FR "X+" +#define AXIS_X_DEC_TEXT_FR "X-" +#define AXIS_Y_ADD_TEXT_FR "Y+" +#define AXIS_Y_DEC_TEXT_FR "Y-" +#define AXIS_Z_ADD_TEXT_FR "Z+" +#define AXIS_Z_DEC_TEXT_FR "Z-" +#define TEXT_01MM_FR "0.1mm" +#define TEXT_1MM_FR "1mm" +#define TEXT_10MM_FR "10mm" + +#define HOME_X_TEXT_FR "X" +#define HOME_Y_TEXT_FR "Y" +#define HOME_Z_TEXT_FR "Z" +#define HOME_ALL_TEXT_FR "ALL" +#define HOME_STOPMOVE_FR "Quickstop" + +#define PAGE_UP_TEXT_FR "En haut" +#define PAGE_DOWN_TEXT_FR "En bas" + +#define EXTRUDER_IN_TEXT_FR "Insérer" +#define EXTRUDER_OUT_TEXT_FR "Éjecter" +#define EXTRUDE_1MM_TEXT_FR "1mm" +#define EXTRUDE_5MM_TEXT_FR "5mm" +#define EXTRUDE_10MM_TEXT_FR "10mm" +#define EXTRUDE_LOW_SPEED_TEXT_FR "Lente" +#define EXTRUDE_MEDIUM_SPEED_TEXT_FR "Moyen" +#define EXTRUDE_HIGH_SPEED_TEXT_FR "Rapide" + +#define LEVELING_POINT1_TEXT_FR "Premier" +#define LEVELING_POINT2_TEXT_FR "Seconde" +#define LEVELING_POINT3_TEXT_FR "Troisième" +#define LEVELING_POINT4_TEXT_FR "Quatrième" +#define LEVELING_POINT5_TEXT_FR "Cinquième" + +#define FILESYS_TEXT_FR "Fichier" +#define WIFI_TEXT_FR "WiFi" +#define FAN_TEXT_FR "Fan" +#define ABOUT_TEXT_FR "À propos" +#define BREAK_POINT_TEXT_FR "Continuer" +#define FILAMENT_TEXT_FR "Remplacer" +#define LANGUAGE_TEXT_FR "Langue" +#define MOTOR_OFF_TEXT_FR "M-hors" +#define MOTOR_OFF_XY_TEXT_FR "M-hors-XY" +#define SHUTDOWN_TEXT_FR "Éteindre" +#define MACHINE_PARA_FR "Config" +#define EEPROM_SETTINGS_FR "Eeprom Set" + +#define U_DISK_TEXT_FR "Clé usb" +#define SD_CARD_TEXT_FR "Carte SD" +#define WIFI_NAME_TEXT_FR "WiFi: " +#define WIFI_KEY_TEXT_FR "Key: " +#define WIFI_IP_TEXT_FR "IP: " +#define WIFI_AP_TEXT_FR "Etat: AP" +#define WIFI_STA_TEXT_FR "Etat: STA" +#define WIFI_CONNECTED_TEXT_FR "Connecté" +#define WIFI_DISCONNECTED_TEXT_FR "Déconnecté" +#define WIFI_EXCEPTION_TEXT_FR "Exception" +#define WIFI_RECONNECT_TEXT_FR "Reconnect" +#define CLOUD_TEXT_FR "Cloud" +#define CLOUD_BIND_FR "Lié" +#define CLOUD_UNBIND_FR "Délier" +#define CLOUD_UNBINDING_FR "Délier" +#define CLOUD_DISCONNECTED_FR "Déconnecté" +#define CLOUD_UNBINDED_FR "Délier" +#define CLOUD_BINDED_FR "Lié" +#define CLOUD_DISABLE_FR "Désactiver" + +#define FAN_ADD_TEXT_FR "Ajouter" +#define FAN_DEC_TEXT_FR "Réduire" +#define FAN_OPEN_TEXT_FR "100%" +#define FAN_HALF_TEXT_FR "50%" +#define FAN_CLOSE_TEXT_FR "0%" +#define FAN_TIPS1_TEXT_FR "ventilateur" +#define FAN_TIPS2_TEXT_FR "ventilateur\n0" + +#define FILAMENT_IN_TEXT_FR "Insérer" +#define FILAMENT_OUT_TEXT_FR "Éjecter" +#define FILAMENT_EXT0_TEXT_FR "Extr1" +#define FILAMENT_EXT1_TEXT_FR "Extr2" +#define FILAMENT_HEAT_TEXT_FR "Preheat" +#define FILAMENT_STOP_TEXT_FR "Arrêter" +#define FILAMENT_TIPS2_TEXT_FR "T:" +#define FILAMENT_TIPS3_TEXT_FR "Insérer le filament..." +#define FILAMENT_TIPS4_TEXT_FR "Éjecter le filament..." +#define FILAMENT_TIPS5_TEXT_FR "Température trop basse pour démarrer, chauffez svp" +#define FILAMENT_TIPS6_TEXT_FR "Terminé" + +#define FILAMENT_CHANGE_TEXT_FR "Veuillez presser \nou , après \nla pause." +#define FILAMENT_DIALOG_LOAD_HEAT_TIPS_FR "Chauffe de la tête\nPatientez SVP..." +#define FILAMENT_DIALOG_UNLOAD_HEAT_TIPS_FR "Chauffe de la tête\nPatientez SVP..." +#define FILAMENT_DIALOG_LOAD_CONFIRM1_TIPS_FR "Tête chaude, veuillez charger le\nfilament dans l'extruder & \nle chargement." +#define FILAMENT_DIALOG_LOAD_CONFIRM2_TIPS_FR "Veuillez charger le filament dans\nl'extruder & le chargement." +#define FILAMENT_DIALOG_UNLOAD_CONFIRM_TIPS_FR "Tête chaude, \npour le déchargement." +#define FILAMENT_DIALOG_LOADING_TIPS_FR "Chargement, patientez SVP." +#define FILAMENT_DIALOG_UNLOADING_TIPS_FR "Déchargement, patientez SVP." +#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" + +#define FILE_LOADING_FR "Chargement......" +#define NO_FILE_AND_CHECK_FR "Aucun fichier, vérifiez à nouveau!" +#define NO_FILE_FR "Pas de fichier!" + +#define EXTRUDER_TEMP_TEXT_FR "Temper" +#define EXTRUDER_E_LENGTH1_TEXT_FR "Extruder1" +#define EXTRUDER_E_LENGTH2_TEXT_FR "Extruder2" +#define EXTRUDER_E_LENGTH3_TEXT_FR "Extruder3" + +#define ABOUT_TYPE_TEXT_FR "Type: " +#define ABOUT_VERSION_TEXT_FR "Firmware: " +#define ABOUT_WIFI_TEXT_FR "Wifi: " + +#define PRINTING_OPERATION_FR "Option" +#define PRINTING_PAUSE_FR "Pause" +#define PRINTING_TEMP_FR "Temp." +#define PRINTING_CHANGESPEED_FR "Speed" +#define PRINTING_RESUME_FR "Reprendre" +#define PRINTING_STOP_FR "Stop" +#define PRINTING_MORE_FR "Plus" +#define PRINTING_EXTRUDER_FR "Extruder" +#define PRINTING_MOVE_FR "Déplace" + +#define EXTRUDER_SPEED_FR "Extruder" +#define MOVE_SPEED_FR "Déplace" +#define EXTRUDER_SPEED_STATE_FR "Vitesse d'extrusion" +#define MOVE_SPEED_STATE_FR "vitesse de déplacement" +#define STEP_1PERCENT_FR "1%" +#define STEP_5PERCENT_FR "5%" +#define STEP_10PERCENT_FR "10%" + +#define TITLE_READYPRINT_FR "Prête" +#define TITLE_PREHEAT_FR "Préchauffe" +#define TITLE_MOVE_FR "Déplace" +#define TITLE_HOME_FR "Acceuil" +#define TITLE_EXTRUDE_FR "Extruder" +#define TITLE_LEVELING_FR "Leveling" +#define TITLE_SET_FR "Paramètres" +#define TITLE_MORE_FR "Plus" +#define TITLE_CHOOSEFILE_FR "Fichier" +#define TITLE_PRINTING_FR "Pimpression" +#define TITLE_OPERATION_FR "Option" +#define TITLE_ADJUST_FR "Réglage" +#define TITLE_WIRELESS_FR "Sans fil" +#define TITLE_FILAMENT_FR "Remplacer" +#define TITLE_ABOUT_FR "À propos" +#define TITLE_FAN_FR "Ventilateur" +#define TITLE_LANGUAGE_FR "Langue" +#define TITLE_PAUSE_FR "Pause" +#define TITLE_CHANGESPEED_FR "Vitesse" +#define TITLE_CLOUD_TEXT_FR "Cloud" +#define TITLE_DIALOG_CONFIRM_FR "Confirmer" +#define TITLE_FILESYS_FR "FileSys" + +#define DIALOG_CLOSE_MACHINE_FR "Extinction..." + +#define AUTO_SHUTDOWN_FR "Auto" +#define MANUAL_SHUTDOWN_FR "Manuel" + +#define DIALOG_CONFIRM_FR "Confirmer" +#define DIALOG_CANCLE_FR "Annuler" +#define DIALOG_OK_FR "OK" +#define DIALOG_RESET_FR "Réinitialiser" +#define DIALOG_RETRY_FR "Recommencez" +#define DIALOG_DISABLE_FR "Désactiver" +#define DIALOG_PRINT_MODEL_FR "Imprimer le fichier?" +#define DIALOG_CANCEL_PRINT_FR "Arrêter?" + +#define DIALOG_STOP_FR "Arrêter" +#define DIALOG_REPRINT_FROM_BREAKPOINT_FR "Continuer?" +#define DIALOG_ERROR_TIPS1_FR "Erreur:error:Aucun fichier, \nvérifiez à nouveau." +#define DIALOG_ERROR_TIPS2_FR "Erreur:La opération a échoué. \nVerifiez que le baudrate de l'écran et de \nla carte mère soient identique!" +#define DIALOG_ERROR_TIPS3_FR "Erreur: le nom du fichier ou le \nchemin d'accès est trop long." +#define DIALOG_UNBIND_PRINTER_FR "Déconnecter l'imprimante?" +#define DIALOG_FILAMENT_NO_PRESS_FR "Détecteur de filament non pressé" +#define DIALOG_PRINT_FINISH_FR "L'impression est terminée!" +#define DIALOG_PRINT_TIME_FR "Temps d'impression: " +#define DIALOG_REPRINT_FR "Réimprimer" +#define DIALOG_WIFI_ENABLE_TIPS_FR "Le module WIFI se charge\nAttendez SVP..." + +#define MESSAGE_PAUSING_FR "Parking..." +#define MESSAGE_CHANGING_FR "Attente filament pour démarrer" +#define MESSAGE_UNLOAD_FR "Attente retrait du filament" +#define MESSAGE_WAITING_FR "Presser bouton, pour reprendre" +#define MESSAGE_INSERT_FR "Insérer filament et app. bouton pour continuer..." +#define MESSAGE_LOAD_FR "Attente chargement filament" +#define MESSAGE_PURGE_FR "Attente purge filament" +#define MESSAGE_RESUME_FR "Attente reprise impression" +#define MESSAGE_HEAT_FR "Presser le bouton pour chauffer..." +#define MESSAGE_HEATING_FR "Buse en chauffe Patienter SVP..." +#define MESSAGE_OPTION_FR "Purger davantage ou continuer l'impression?" +#define MESSAGE_PURGE_MORE_FR "Purge" +#define MESSAGE_CONTINUE_PRINT_FR "Impression" +#define EEPROM_SETTINGS_TITLE_FR "Paramètres EEPROM" +#define EEPROM_SETTINGS_STORE_FR "Stocker les paramètres dans l'EEPROM" +#define EEPROM_SETTINGS_READ_FR "Lire les paramètres de l'EEPROM" +#define EEPROM_SETTINGS_REVERT_FR "Rétablir les paramètres par défaut d'usine" + +#define EEPROM_STORE_TIPS_FR "Stocker les paramètres dans l'EEPROM?" +#define EEPROM_READ_TIPS_FR "Lire les paramètres de l'EEPROM?" +#define EEPROM_REVERT_TIPS_FR "Rétablir les paramètres par défaut d'usine?" + +#define MORE_CUSTOM1_TEXT_FR MAIN_MENU_ITEM_1_DESC +#define MORE_CUSTOM2_TEXT_FR MAIN_MENU_ITEM_2_DESC +#define MORE_CUSTOM3_TEXT_FR MAIN_MENU_ITEM_3_DESC +#define MORE_CUSTOM4_TEXT_FR MAIN_MENU_ITEM_4_DESC +#define MORE_CUSTOM5_TEXT_FR MAIN_MENU_ITEM_5_DESC +#define MORE_CUSTOM6_TEXT_FR MAIN_MENU_ITEM_6_DESC diff --git a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_it.h b/Marlin/src/lcd/extui/mks_ui/tft_Language_it.h similarity index 90% rename from Marlin/src/lcd/extui/lib/mks_ui/tft_Language_it.h rename to Marlin/src/lcd/extui/mks_ui/tft_Language_it.h index f64ca4df79df..b74842afef1c 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_it.h +++ b/Marlin/src/lcd/extui/mks_ui/tft_Language_it.h @@ -32,6 +32,8 @@ #define AUTO_LEVELING_TEXT_IT "AutoLevel" #define SET_TEXT_IT "Imposta" #define MORE_TEXT_IT "Di più" +#define MORE_GCODE_IT "G-Code" +#define MORE_ENTER_GCODE_IT "Inserisci il G-Code" #define ADD_TEXT_IT "Aumentare" #define DEC_TEXT_IT "Ridurre" @@ -135,26 +137,12 @@ #define FILAMENT_EXT1_TEXT_IT "Estrude2" #define FILAMENT_HEAT_TEXT_IT "Preriscaldamento" #define FILAMENT_STOP_TEXT_IT "Stop" -//#define FILAMENT_CHANGE_TEXT_IT "Filamento" #define FILAMENT_TIPS2_TEXT_IT "T:" #define FILAMENT_TIPS3_TEXT_IT "Inserimento del filamento..." #define FILAMENT_TIPS4_TEXT_IT "Estrazione del filamento..." #define FILAMENT_TIPS5_TEXT_IT "Temp is too low to go,please heat" #define FILAMENT_TIPS6_TEXT_IT "Completato" -#if 0 - #define FILAMENT_REPLAYS_IDLE_TEXT_IT "Please click or \nto replace filament!" - #define FILAMENT_CHANGE_TEXT_IT "Please click or ,\nAfter pinter pause." - #define FILAMENT_DIALOG_LOAD_HEAT_TIPS_IT "Heating up the nozzle,please wait..." - #define FILAMENT_DIALOG_UNLOAD_HEAT_TIPS_IT "Heating up the nozzle,please wait..." - #define FILAMENT_DIALOG_LOAD_CONFIRM1_TIPS_IT "Heat completed,please load filament to extruder,and click for start loading." - #define FILAMENT_DIALOG_LOAD_CONFIRM2_TIPS_IT "Please load filament to extruder,and click for start loading." - #define FILAMENT_DIALOG_UNLOAD_CONFIRM_TIPS_IT "Heat completed,please click for start unloading.!" - #define FILAMENT_DIALOG_LOADING_TIPS_IT "Is loading ,please wait!" - #define FILAMENT_DIALOG_UNLOADING_TIPS_IT "Is unloading,please wait!" - #define FILAMENT_DIALOG_LOAD_COMPLETE_TIPS_IT "Load filament completed,click for return!" - #define FILAMENT_DIALOG_UNLOAD_COMPLETE_TIPS_IT "Unload filament completed,click for return!" -#endif #define FILAMENT_CHANGE_TEXT_IT "Please click \nor ,After \npinter pause." #define FILAMENT_DIALOG_LOAD_HEAT_TIPS_IT "Heating up the nozzle,please wait..." #define FILAMENT_DIALOG_UNLOAD_HEAT_TIPS_IT "Heating up the nozzle,please wait..." @@ -166,16 +154,11 @@ #define FILAMENT_DIALOG_LOAD_COMPLETE_TIPS_IT "Load filament completed,\nclick for return!" #define FILAMENT_DIALOG_UNLOAD_COMPLETE_TIPS_IT "Unload filament completed,\nclick for return!" - #define PRE_HEAT_EXT_TEXT_IT "E" #define PRE_HEAT_BED_TEXT_IT "Piano" #define FILE_LOADING_IT "Caricamento......" -#if 0 - #define NO_FILE_AND_CHECK_IT "Nessun file trovato! Inserisci la scheda SD o il disco U!" -#endif #define NO_FILE_AND_CHECK_IT "Nessun file,\n per favore controllare di nuovo!" - #define NO_FILE_IT "Nessun file!" #define EXTRUDER_TEMP_TEXT_IT "Temper" @@ -241,7 +224,6 @@ #define DIALOG_CANCEL_PRINT_IT "Stop stampa?" #define DIALOG_STOP_IT "Stop" #define DIALOG_REPRINT_FROM_BREAKPOINT_IT "Continua a stampare dal \npunto di interruzione?" -//#define DIALOG_UNBIND_PRINTER_IT "Libero?" #define DIALOG_ERROR_TIPS1_IT "Errore: nessun file, \nper favore controllare di nuovo." #define DIALOG_ERROR_TIPS2_IT "Errore: operazione non riuscita, \nsi prega di controllare se il baudrate del \ndisplay è lo stesso scheda madre" #define DIALOG_ERROR_TIPS3_IT "Errore: il nome del file o il \npercorso è troppo lungo!" @@ -274,3 +256,10 @@ #define EEPROM_STORE_TIPS_IT "Memorizzare le impostazioni su EEPROM?" #define EEPROM_READ_TIPS_IT "Leggi le impostazioni dalla EEPROM?" #define EEPROM_REVERT_TIPS_IT "Ripristinare le impostazioni predefinite?" + +#define MORE_CUSTOM1_TEXT_IT MAIN_MENU_ITEM_1_DESC +#define MORE_CUSTOM2_TEXT_IT MAIN_MENU_ITEM_2_DESC +#define MORE_CUSTOM3_TEXT_IT MAIN_MENU_ITEM_3_DESC +#define MORE_CUSTOM4_TEXT_IT MAIN_MENU_ITEM_4_DESC +#define MORE_CUSTOM5_TEXT_IT MAIN_MENU_ITEM_5_DESC +#define MORE_CUSTOM6_TEXT_IT MAIN_MENU_ITEM_6_DESC diff --git a/Marlin/src/lcd/extui/mks_ui/tft_Language_ru.h b/Marlin/src/lcd/extui/mks_ui/tft_Language_ru.h new file mode 100644 index 000000000000..f6b3231737d8 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/tft_Language_ru.h @@ -0,0 +1,363 @@ +/** + * 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 TOOL_TEXT_RU "инструмент" +#define PREHEAT_TEXT_RU " нагрев" +#define MOVE_TEXT_RU "движение" +#define HOME_TEXT_RU "домой" +#define PRINT_TEXT_RU " печать" +#define EXTRUDE_TEXT_RU "экструзия" +#define LEVELING_TEXT_RU "уровень" +#define AUTO_LEVELING_TEXT_RU "aвтоуровень" +#define SET_TEXT_RU "настройки" +#define MORE_TEXT_RU "больше" +#define MORE_GCODE_RU "G-код" +#define MORE_ENTER_GCODE_RU "Введите G-код" + +#define ADD_TEXT_RU "добавить" +#define DEC_TEXT_RU "уменьшить" +#define EXTRUDER_1_TEXT_RU "экструдер1" +#define EXTRUDER_2_TEXT_RU "экструдер2" +#define HEATBED_TEXT_RU "стол" +#define TEXT_1C_RU "1℃" +#define TEXT_5C_RU "5℃" +#define TEXT_10C_RU "10℃" +#define CLOSE_TEXT_RU "выкл" + +#define BACK_TEXT_RU "назад" + +#define TOOL_PREHEAT_RU "нагрев" +#define TOOL_EXTRUDE_RU "экструдер" +#define TOOL_MOVE_RU "движение" +#define TOOL_HOME_RU "домой" +#define TOOL_LEVELING_RU "уровень" +#define TOOL_AUTO_LEVELING_RU "aвтоуровень" +#define TOOL_FILAMENT_RU "замена" +#define TOOL_MORE_RU "больше" + +#define AXIS_X_ADD_TEXT_RU "X +" +#define AXIS_X_DEC_TEXT_RU "X -" +#define AXIS_Y_ADD_TEXT_RU "Y +" +#define AXIS_Y_DEC_TEXT_RU "Y -" +#define AXIS_Z_ADD_TEXT_RU "Z +" +#define AXIS_Z_DEC_TEXT_RU "Z -" +#define TEXT_01MM_RU "0.1 mm" +#define TEXT_1MM_RU "1 mm" +#define TEXT_10MM_RU "10 mm" + +#define HOME_X_TEXT_RU "X" +#define HOME_Y_TEXT_RU "Y" +#define HOME_Z_TEXT_RU "Z" +#define HOME_ALL_TEXT_RU "Home" +#define HOME_STOPMOVE_RU "Quickstop" + +#define PAGE_UP_TEXT_RU "вверх" +#define PAGE_DOWN_TEXT_RU "вниз" + +#define EXTRUDER_IN_TEXT_RU "втянуть" +#define EXTRUDER_OUT_TEXT_RU "выдавить" +#define EXTRUDE_1MM_TEXT_RU "1 mm" +#define EXTRUDE_5MM_TEXT_RU "5 mm" +#define EXTRUDE_10MM_TEXT_RU "10 mm" +#define EXTRUDE_LOW_SPEED_TEXT_RU "мин" +#define EXTRUDE_MEDIUM_SPEED_TEXT_RU "сред" +#define EXTRUDE_HIGH_SPEED_TEXT_RU "выс" + +#define LEVELING_POINT1_TEXT_RU "1 точка" +#define LEVELING_POINT2_TEXT_RU "2 точка" +#define LEVELING_POINT3_TEXT_RU "3 точка" +#define LEVELING_POINT4_TEXT_RU "4 точка" +#define LEVELING_POINT5_TEXT_RU "5 точка" + +#define FILESYS_TEXT_RU "система" +#define WIFI_TEXT_RU "WiFi" +#define FAN_TEXT_RU "вентилятор" +#define ABOUT_TEXT_RU "инфо" +#define BREAK_POINT_TEXT_RU "продолжить" +#define FILAMENT_TEXT_RU "замена" +#define LANGUAGE_TEXT_RU "язык" +#define MOTOR_OFF_TEXT_RU "откл. мотор" +#define MOTOR_OFF_XY_TEXT_RU "Off-XY" +#define SHUTDOWN_TEXT_RU "выключение" +#define MACHINE_PARA_RU "конфиг" + +#define U_DISK_TEXT_RU "U диск" +#define SD_CARD_TEXT_RU "SD диск" +#define WIFI_NAME_TEXT_RU "WiFi: " +#define WIFI_KEY_TEXT_RU "пароль: " +#define WIFI_IP_TEXT_RU "IP: " +#define WIFI_AP_TEXT_RU "режим: AP" +#define WIFI_STA_TEXT_RU "режим: STA" +#define WIFI_CONNECTED_TEXT_RU "подключен" +#define WIFI_DISCONNECTED_TEXT_RU "не подключен" +#define WIFI_EXCEPTION_TEXT_RU "исключение" +#define WIFI_RECONNECT_TEXT_RU "выбор сети" +#define CLOUD_TEXT_RU "облако" +#define CLOUD_BIND_RU "соединён" +#define CLOUD_UNBIND_RU "отсоед." +#define CLOUD_UNBINDING_RU "отвязано" +#define CLOUD_DISCONNECTED_RU "отключено" +#define CLOUD_UNBINDED_RU "несвяз." +#define CLOUD_BINDED_RU "связано" +#define CLOUD_DISABLE_RU "Disable" + +#define FAN_ADD_TEXT_RU "добавить" +#define FAN_DEC_TEXT_RU "уменьшить" +#define FAN_OPEN_TEXT_RU "100%" +#define FAN_HALF_TEXT_RU "50%" +#define FAN_CLOSE_TEXT_RU "откл" +#define FAN_TIPS1_TEXT_RU "вентилятор" +#define FAN_TIPS2_TEXT_RU "вентилятор\nоткл" + +#define FILAMENT_IN_TEXT_RU "втянуть" +#define FILAMENT_OUT_TEXT_RU "выдавить" +#define FILAMENT_EXT0_TEXT_RU "экструдер1" +#define FILAMENT_EXT1_TEXT_RU "экструдер2" +#define FILAMENT_HEAT_TEXT_RU "нагрев" +#define FILAMENT_STOP_TEXT_RU "стоп" +#define FILAMENT_TIPS2_TEXT_RU "T:" +#define FILAMENT_TIPS3_TEXT_RU "втянуть..." +#define FILAMENT_TIPS4_TEXT_RU "вядавить..." +#define FILAMENT_TIPS5_TEXT_RU "Низкая температура, \nнеобходим нагрев" +#define FILAMENT_TIPS6_TEXT_RU "завершено" + +#define FILAMENT_CHANGE_TEXT_RU "Please click \nor ,After \npinter pause." +#define FILAMENT_DIALOG_LOAD_HEAT_TIPS_RU "Heating up the nozzle,\nplease wait..." +#define FILAMENT_DIALOG_UNLOAD_HEAT_TIPS_RU "Heating up the nozzle,\nplease wait..." +#define FILAMENT_DIALOG_LOAD_CONFIRM1_TIPS_RU "Heat completed,please load filament \nto extruder,and click \nfor start loading." +#define FILAMENT_DIALOG_LOAD_CONFIRM2_TIPS_RU "Please load filament to extruder,\nand click for start loading." +#define FILAMENT_DIALOG_UNLOAD_CONFIRM_TIPS_RU "Heat completed,please \nclick for start unloading.!" +#define FILAMENT_DIALOG_LOADING_TIPS_RU "Is loading ,please wait!" +#define FILAMENT_DIALOG_UNLOADING_TIPS_RU "Is unloading,please wait!" +#define FILAMENT_DIALOG_LOAD_COMPLETE_TIPS_RU "Load filament completed,\nclick for return!" +#define FILAMENT_DIALOG_UNLOAD_COMPLETE_TIPS_RU "Unload filament completed,\nclick for return!" + +#define PRE_HEAT_EXT_TEXT_RU "E" +#define PRE_HEAT_BED_TEXT_RU "стол" + +#define FILE_LOADING_RU "загрузка......" +#define NO_FILE_AND_CHECK_RU "нет файла,попробуйте ещё раз!" + +#define NO_FILE_RU "нет файла!" + +#define EXTRUDER_TEMP_TEXT_RU "температура" +#define EXTRUDER_E_LENGTH1_TEXT_RU "экструзия1" +#define EXTRUDER_E_LENGTH2_TEXT_RU "экструзия2" +#define EXTRUDER_E_LENGTH3_TEXT_RU "экструзия3" + +#define ABOUT_TYPE_TEXT_RU "Type: " +#define ABOUT_VERSION_TEXT_RU "Firmware: " +#define ABOUT_WIFI_TEXT_RU "WiFi: " + +#define PRINTING_OPERATION_RU "опции" +#define PRINTING_PAUSE_RU "пауза" +#define PRINTING_TEMP_RU "темп" +#define PRINTING_CHANGESPEED_RU "скорости" +#define PRINTING_RESUME_RU "возобн. " +#define PRINTING_STOP_RU "стоп" +#define PRINTING_MORE_RU "больше" +#define PRINTING_EXTRUDER_RU "экстр" +#define PRINTING_MOVE_RU "движение" + +#define EXTRUDER_SPEED_RU "экстр" +#define MOVE_SPEED_RU "движ" +#define EXTRUDER_SPEED_STATE_RU "скорость экстр" +#define MOVE_SPEED_STATE_RU "скорость движ" +#define STEP_1PERCENT_RU "1%" +#define STEP_5PERCENT_RU "5%" +#define STEP_10PERCENT_RU "10%" + +#define TITLE_READYPRINT_RU "готов к" +#define TITLE_PREHEAT_RU "движение" +#define TITLE_MOVE_RU "движение" +#define TITLE_HOME_RU "Home" +#define TITLE_EXTRUDE_RU "экструзия" +#define TITLE_LEVELING_RU "уровень" +#define TITLE_MLEVELING_RU "углы" +#define TITLE_SET_RU "настройки" +#define TITLE_MORE_RU "больше" +#define TITLE_CHOOSEFILE_RU "файла" +#define TITLE_PRINTING_RU "печать" +#define TITLE_OPERATION_RU "управление" +#define TITLE_ADJUST_RU "регулировать" +#define TITLE_WIRELESS_RU "Wireless" +#define TITLE_FILAMENT_RU "замена" +#define TITLE_ABOUT_RU "инфо" +#define TITLE_FAN_RU "вентилятор" +#define TITLE_LANGUAGE_RU "язык" +#define TITLE_PAUSE_RU "пауза" +#define TITLE_CHANGESPEED_RU "скорости" +#define TILE_TOOL_RU "инструмент" +#define TITLE_CLOUD_TEXT_RU "Cloud" +#define TITLE_DIALOG_CONFIRM_RU "Confirm" +#define TITLE_FILESYS_RU "FileSys" + +#define AUTO_SHUTDOWN_RU "авто-откл" +#define MANUAL_SHUTDOWN_RU "ручн-откл" + +#define DIALOG_CONFIRM_RU "да"//"подтвердить" +#define DIALOG_CANCLE_RU "отмена" +#define DIALOG_OK_RU "да" +#define DIALOG_RESET_RU "сброс" +#define DIALOG_RETRY_RU "повтор" +#define DIALOG_DISABLE_RU "запретить" +#define DIALOG_PRINT_MODEL_RU "печать модели?" +#define DIALOG_CANCEL_PRINT_RU "стоп?" +#define DIALOG_STOP_RU "стоп" +#define DIALOG_REPRINT_FROM_BREAKPOINT_RU "продолжить?" +#define DIALOG_ERROR_TIPS1_RU "ошибка:нет файла, попробуйте ещё раз." +#define DIALOG_ERROR_TIPS2_RU "ошибка:сбой передачи. установите скорость \nпередачи данных как на плате управления!" +#define DIALOG_ERROR_TIPS3_RU "ошибка: имя файла слишком длинное!" +#define DIALOG_CLOSE_MACHINE_RU "Closing machine......" +#define DIALOG_UNBIND_PRINTER_RU "Unbind the printer?" +#define DIALOG_FILAMENT_NO_PRESS_RU "Filament detection switch is not pressed" +#define DIALOG_PRINT_FINISH_RU "печать завершена!" +#define DIALOG_PRINT_TIME_RU "Время печати: " +#define DIALOG_REPRINT_RU "Print again" +#define DIALOG_WIFI_ENABLE_TIPS_RU "The wifi module is being configured,\nplease wait a moment....." + +#define MESSAGE_PAUSING_RU "Стоянка..." +#define MESSAGE_CHANGING_RU "Подождите, пока начнется смена филамента" +#define MESSAGE_UNLOAD_RU "Дождитесь выгрузки нити" +#define MESSAGE_WAITING_RU "Нажмите кнопку,чтобы возобновить печать" +#define MESSAGE_INSERT_RU "Вставьте нить и нажмите кнопку,чтобы продолжить" +#define MESSAGE_LOAD_RU "Дождитесь загрузки нити" +#define MESSAGE_PURGE_RU "Дождитесь чистки нити" +#define MESSAGE_RESUME_RU "Подождите,пока печать возобновится ..." +#define MESSAGE_HEAT_RU "Нажмите кнопку, чтобы нагреть форсунку" +#define MESSAGE_HEATING_RU "Подогрев форсунки Пожалуйста, подождите ..." +#define MESSAGE_OPTION_RU "Очистить больше или продолжить печать?" +#define MESSAGE_PURGE_MORE_RU "чистка" +#define MESSAGE_CONTINUE_PRINT_RU "Распечатать" +#define EEPROM_SETTINGS_TITLE_RU "Настройки EEPROM" +#define EEPROM_SETTINGS_STORE_RU "Cохранение настроек в EEPROM" +#define EEPROM_SETTINGS_READ_RU "Чтение настроек из EEPROM" +#define EEPROM_SETTINGS_REVERT_RU "Bосстановить заводские настройки по умолчанию" + +#define MORE_CUSTOM1_TEXT_RU MAIN_MENU_ITEM_1_DESC +#define MORE_CUSTOM2_TEXT_RU MAIN_MENU_ITEM_2_DESC +#define MORE_CUSTOM3_TEXT_RU MAIN_MENU_ITEM_3_DESC +#define MORE_CUSTOM4_TEXT_RU MAIN_MENU_ITEM_4_DESC +#define MORE_CUSTOM5_TEXT_RU MAIN_MENU_ITEM_5_DESC +#define MORE_CUSTOM6_TEXT_RU MAIN_MENU_ITEM_6_DESC + +#define EEPROM_STORE_TIPS_RU "Cохранить настройки в EEPROM?" +#define EEPROM_READ_TIPS_RU "читать настройки из EEPROM?" +#define EEPROM_REVERT_TIPS_RU "Cбросить настройки к значениям по умолчанию?" +#define EEPROM_SETTINGS_RU "EEPROM" + +#define NEXT_RU "след." +#define PREVIOUS_RU "пред." +#define ENABLE_RU "да " +#define DISABLE_RU "нет" +#define KEY_CONFIRM_RU "OK" + +#define MACHINE_PARA_TITLE_RU "настройки" +#define MACHINE_TYPE_CNOFIG_RU "Hастройки принтера" +#define MOTOR_CONFIG_RU "Hастройки моторов" +#define MACHINE_LEVELING_CONFIG_RU "Hастройки уровня" +#define ADVANCE_CONFIG_RU "Pасширенные настройки" +#define MACHINE_FILAMENT_CONFIG_RU "Hастройки филамента" +#define ENCODER_SETTINGS_RU "Hастройки энкодера" + +#define LEVELING_CONF_TITLE_RU "Hастройки принтера>Hастройки уровня" +#define LEVELING_PARA_CONF_RU "настройки уровня" +#define TRAMMING_POS_RU "настройки координат для уровня" +#define LEVELING_AUTO_COMMAND_RU "настройки комманд увтоуровня" +#define LEVELING_AUTO_ZOFFSET_RU "координаты смещения сопла" + +#define MACHINE_CONFIG_TITLE_RU "Hастройки принтера>настройки притера" +#define MAXFEEDRATE_CONF_RU "настройки максимальной скорости" +#define ACCELERATION_CONF_RU "настройки ускорений" +#define JERKCONF_RU "настройки рывков" + +#define MOTOR_CONF_TITLE_RU "Hастройки принтера>Hастройки моторов" +#define STEPSCONF_RU "настройки шагов" +#define TMC_CURRENT_RU "TMC настройки токов" +#define TMC_STEP_MODE_RU "TMC настрйоки режима шагов" + +#define ACCELERATION_CONF_TITLE_RU "Hастройки принтера>ускорения" +#define PRINT_ACCELERATION_RU "ускорение печати" +#define RETRACT_ACCELERATION_RU "ускорение ретракта" +#define TRAVEL_ACCELERATION_RU "ускорение перемещений" +#define X_ACCELERATION_RU "ускорение оси X" +#define Y_ACCELERATION_RU "ускорение оси Y" +#define Z_ACCELERATION_RU "ускорение оси Z" +#define E0_ACCELERATION_RU "ускорение E0" +#define E1_ACCELERATION_RU "ускорение E1" + +#define MAXFEEDRATE_CONF_TITLE_RU "Hастройки принтера>максимальная скорость" +#define X_MAXFEEDRATE_RU "максимальная скорость оси X" +#define Y_MAXFEEDRATE_RU "максимальная скорость оси Y" +#define Z_MAXFEEDRATE_RU "максимальная скорость оси Z" +#define E0_MAXFEEDRATE_RU "максимальная скорость E0" +#define E1_MAXFEEDRATE_RU "максимальная скорость E1" + +#define JERK_CONF_TITLE_RU "Hастройки принтера>скорость рывка" +#define X_JERK_RU "скорость рывка оси X" +#define Y_JERK_RU "скорость рывка оси Y" +#define Z_JERK_RU "скорость рывка оси Z" +#define E_JERK_RU "скорость рывка оси E" + +#define STEPS_CONF_TITLE_RU "Hастройки принтера>настройки шагов" +#define X_STEPS_RU "шаги оси X" +#define Y_STEPS_RU "шаги оси Y" +#define Z_STEPS_RU "шаги оси Z" +#define E0_STEPS_RU "шаги E0" +#define E1_STEPS_RU "шаги E1" + +#define TMC_CURRENT_CONF_TITLE_RU "Hастройки принтера>TMC настройка токов" +#define X_TMC_CURRENT_RU "ток оси X (mA)" +#define Y_TMC_CURRENT_RU "ток оси Y (mA)" +#define Z_TMC_CURRENT_RU "ток оси Z (mA)" +#define E0_TMC_CURRENT_RU "ток E0 (mA)" +#define E1_TMC_CURRENT_RU "ток E1 (mA)" + +#define TMC_MODE_CONF_TITLE_RU "Hастройки принтера>TMC настройки режима шагов" +#define X_TMC_MODE_RU "включает ли двигатель X режим StealthChop" +#define Y_TMC_MODE_RU "включает ли ось Y режим StealthChop" +#define Z_TMC_MODE_RU "включает ли ось Z режим StealthChop" +#define E0_TMC_MODE_RU "включает ли E0 режим StealthChop" +#define E1_TMC_MODE_RU "включает ли E1 режим StealthChop" + +#define ADVANCED_CONF_TITLE_RU "Hастройки принтера>Pасширенные" +#define PAUSE_POSITION_RU "Hастройки позиции паузы печати" +#define PAUSE_POSITION_X_RU "положение по X (абс. полож., -1 недействит.)" +#define PAUSE_POSITION_Y_RU "положение по Y (абс. полож., -1 недействит.)" +#define PAUSE_POSITION_Z_RU "положение по Z (абс. полож., -1 недействит.)" + +#define OFFSET_TITLE_RU "Hастройки принтера>отступ" +#define OFFSET_X_RU "X отступ" +#define OFFSET_Y_RU "Y отступ" +#define OFFSET_Z_RU "Z отступ" + +#define FILAMENT_CONF_TITLE_RU "Hастройки принтера>Hастройки филамента" +#define FILAMENT_IN_LENGTH_RU "длинна загрузки" +#define FILAMENT_IN_SPEED_RU "скорость загрузки" +#define FILAMENT_TEMPERATURE_RU "температура филамента" +#define FILAMENT_OUT_LENGTH_RU "длинна извлечения" +#define FILAMENT_OUT_SPEED_RU "скорость извлечения" + +#define ENCODER_CONF_TITLE_RU "Hастройки принтера>Hастройки энкодера" +#define ENCODER_CONF_TEXT_RU "энкодер используется?" diff --git a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_s_cn.h b/Marlin/src/lcd/extui/mks_ui/tft_Language_s_cn.h similarity index 84% rename from Marlin/src/lcd/extui/lib/mks_ui/tft_Language_s_cn.h rename to Marlin/src/lcd/extui/mks_ui/tft_Language_s_cn.h index 118992777048..59de8c7db93e 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_s_cn.h +++ b/Marlin/src/lcd/extui/mks_ui/tft_Language_s_cn.h @@ -84,13 +84,13 @@ #define LEVELING_CONF_TITLE_CN "机器参数>调平设置" #define LEVELING_PARA_CONF_CN "调平设置" -#define LEVELING_MANUAL_POS_CN "手动调平坐标设置" +#define TRAMMING_POS_CN "手动调平坐标设置" #define LEVELING_AUTO_COMMAND_CN "自动调平指令设置" #define LEVELING_AUTO_ZOFFSET_CN "挤出头与调平开关偏移设置" #define LEVELING_PARA_CONF_TITLE_CN "调平参数" #define AUTO_LEVELING_ENABLE_CN "自动调平" -#define BLTOUCH_LEVELING_ENABLE_CN "启动BLtouch" +#define BLTOUCH_LEVELING_ENABLE_CN "启动BLTouch" #define PROBE_PORT_CN "调平探针接口" #define PROBE_X_OFFSET_CN "探针X方向偏移" #define PROBE_Y_OFFSET_CN "探针Y方向偏移" @@ -99,6 +99,7 @@ #define PROBE_Z_SPEED_CN "探针Z方向移动速度" #define ENABLE_CN "是" #define DISABLE_CN "否" +#define LOCKED_CN "否" #define Z_MIN_CN "ZMin" #define Z_MAX_CN "ZMax" @@ -177,42 +178,42 @@ #define E0_STEPS_CN "E0轴脉冲" #define E1_STEPS_CN "E1轴脉冲" -#define TMC_CURRENT_CONF_TITLE_CN "机器参数>TMC电流设置" -#define X_TMC_CURRENT_CN "X轴电流(毫安)" -#define Y_TMC_CURRENT_CN "Y轴电流(毫安)" -#define Z_TMC_CURRENT_CN "Z轴电流(毫安)" -#define E0_TMC_CURRENT_CN "E0轴电流(毫安)" -#define E1_TMC_CURRENT_CN "E1轴电流(毫安)" - -#define TMC_MODE_CONF_TITLE_CN "机器参数>TMC模式设置" -#define X_TMC_MODE_CN "X轴是否使能静音模式" -#define Y_TMC_MODE_CN "Y轴是否使能静音模式" -#define Z_TMC_MODE_CN "Z轴是否使能静音模式" -#define E0_TMC_MODE_CN "E0轴是否使能静音模式" -#define E1_TMC_MODE_CN "E1轴是否使能静音模式" - -#define MOTORDIR_CONF_TITLE_CN "机器参数>电机方向" -#define X_MOTORDIR_CN "X轴电机方向" -#define Y_MOTORDIR_CN "Y轴电机方向" -#define Z_MOTORDIR_CN "Z轴电机方向" -#define E0_MOTORDIR_CN "E0轴电机方向" -#define E1_MOTORDIR_CN "E1轴电机方向" -#define INVERT_P_CN "正向" -#define INVERT_N_CN "反向" - -#define HOMEFEEDRATE_CONF_TITLE_CN "机器参数>归零速度" -#define X_HOMESPEED_CN "XY轴归零速度" -#define Y_HOMESPEED_CN "Y轴归零速度" -#define Z_HOMESPEED_CN "Z轴归零速度" - -#define ADVANCED_CONF_TITLE_CN "机器参数>高级设置" -#define PWROFF_DECTION_CN "断电检测模块" -#define PWROFF_AFTER_PRINT_CN "启动打完关机功能" -#define HAVE_UPS_CN "机器配备UPS电源" -#define Z2_AND_Z2ENDSTOP_CONF_CN "双Z轴双限位功能设置" -#define ENABLE_PINS_CONF_CN "电机使能脚电平设置" -#define WIFI_SETTINGS_CN "Wi-Fi参数设置" -#define ENCODER_SETTINGS_CN "旋钮设置" +#define TMC_CURRENT_CONF_TITLE_CN "机器参数>TMC电流设置" +#define X_TMC_CURRENT_CN "X轴电流(毫安)" +#define Y_TMC_CURRENT_CN "Y轴电流(毫安)" +#define Z_TMC_CURRENT_CN "Z轴电流(毫安)" +#define E0_TMC_CURRENT_CN "E0轴电流(毫安)" +#define E1_TMC_CURRENT_CN "E1轴电流(毫安)" + +#define TMC_MODE_CONF_TITLE_CN "机器参数>TMC模式设置" +#define X_TMC_MODE_CN "X轴是否使能静音模式" +#define Y_TMC_MODE_CN "Y轴是否使能静音模式" +#define Z_TMC_MODE_CN "Z轴是否使能静音模式" +#define E0_TMC_MODE_CN "E0轴是否使能静音模式" +#define E1_TMC_MODE_CN "E1轴是否使能静音模式" + +#define MOTORDIR_CONF_TITLE_CN "机器参数>电机方向" +#define X_MOTORDIR_CN "X轴电机方向" +#define Y_MOTORDIR_CN "Y轴电机方向" +#define Z_MOTORDIR_CN "Z轴电机方向" +#define E0_MOTORDIR_CN "E0轴电机方向" +#define E1_MOTORDIR_CN "E1轴电机方向" +#define INVERT_P_CN "正向" +#define INVERT_N_CN "反向" + +#define HOMEFEEDRATE_CONF_TITLE_CN "机器参数>归零速度" +#define X_HOMESPEED_CN "XY轴归零速度" +#define Y_HOMESPEED_CN "Y轴归零速度" +#define Z_HOMESPEED_CN "Z轴归零速度" + +#define ADVANCED_CONF_TITLE_CN "机器参数>高级设置" +#define PWROFF_DECTION_CN "断电检测模块" +#define PWROFF_AFTER_PRINT_CN "启动打完关机功能" +#define HAVE_UPS_CN "机器配备UPS电源" +#define Z2_AND_Z2ENDSTOP_CONF_CN "双Z轴双限位功能设置" +#define ENABLE_PINS_CONF_CN "电机使能脚电平设置" +#define WIFI_SETTINGS_CN "Wi-Fi参数设置" +#define ENCODER_SETTINGS_CN "旋钮设置" #define Z2_AND_Z2ENDSTOP_CONF_TITLE_CN "双z双限位设置" #define Z2_ENABLE_CN "启用Z2轴" @@ -225,23 +226,23 @@ #define Z_ENABLE_PINS_INVERT_CN "Z轴电机使能电平" #define E_ENABLE_PINS_INVERT_CN "E轴电机使能电平" -#define PAUSE_POSITION_CN "打印暂停位置设置" -#define PAUSE_POSITION_X_CN "X轴暂停位置(绝对位置,-1无效)" -#define PAUSE_POSITION_Y_CN "Y轴暂停位置(绝对位置,-1无效)" -#define PAUSE_POSITION_Z_CN "Z轴暂停位置(相对位置,-1无效)" -#define WIFI_SETTINGS_TITLE_CN "机器参数>Wi-Fi设置" -#define WIFI_SETTINGS_MODE_CN "Wi-Fi 模式" -#define WIFI_SETTINGS_NAME_CN "Wi-Fi 名称: " -#define WIFI_SETTINGS_PASSWORD_CN "Wi-Fi 密码: " -#define WIFI_SETTINGS_CLOUD_CN "是否使用云服务?" -#define WIFI_SETTINGS_CONFIG_CN "配置" -#define WIFI_SETTINGS_EDIT_CN "编辑" -#define WIFI_CONFIG_TIPS_CN "进行Wi-Fi配置?" - -#define OFFSET_TITLE_CN "机器参数>偏移设置" -#define OFFSET_X_CN "X轴与调平开关偏移" -#define OFFSET_Y_CN "Y轴与调平开关偏移" -#define OFFSET_Z_CN "Z轴与调平开关偏移" +#define PAUSE_POSITION_CN "打印暂停位置设置" +#define PAUSE_POSITION_X_CN "X轴暂停位置(绝对位置,-1无效)" +#define PAUSE_POSITION_Y_CN "Y轴暂停位置(绝对位置,-1无效)" +#define PAUSE_POSITION_Z_CN "Z轴暂停位置(相对位置,-1无效)" +#define WIFI_SETTINGS_TITLE_CN "机器参数>Wi-Fi设置" +#define WIFI_SETTINGS_MODE_CN "Wi-Fi 模式" +#define WIFI_SETTINGS_NAME_CN "Wi-Fi 名称: " +#define WIFI_SETTINGS_PASSWORD_CN "Wi-Fi 密码: " +#define WIFI_SETTINGS_CLOUD_CN "是否使用云服务?" +#define WIFI_SETTINGS_CONFIG_CN "配置" +#define WIFI_SETTINGS_EDIT_CN "编辑" +#define WIFI_CONFIG_TIPS_CN "进行Wi-Fi配置?" + +#define OFFSET_TITLE_CN "机器参数>偏移设置" +#define OFFSET_X_CN "X轴与调平开关偏移" +#define OFFSET_Y_CN "Y轴与调平开关偏移" +#define OFFSET_Z_CN "Z轴与调平开关偏移" #define HOMING_SENSITIVITY_CONF_TITLE_CN "机器参数>灵敏度调节" #define X_SENSITIVITY_CN "X轴灵敏度" @@ -262,6 +263,8 @@ #define AUTO_LEVELING_TEXT_CN "自动调平" #define SET_TEXT_CN "设置" #define MORE_TEXT_CN "更多" +#define MORE_GCODE_CN "G-Code" +#define MORE_ENTER_GCODE_CN "Enter G-Code" #define ADD_TEXT_CN "增加" #define DEC_TEXT_CN "减少" @@ -364,12 +367,7 @@ #define FILAMENT_EXT1_TEXT_CN "喷头2" #define FILAMENT_HEAT_TEXT_CN "预热" #define FILAMENT_STOP_TEXT_CN "停止" -#if 0 - #define FILAMENT_REPLAYS_IDLE_TEXT_CN "请按<进料>或<退料>进行换料!" - #define FILAMENT_CHANGE_TEXT_CN "待打印机暂停后,请按<进料>或<退料>进行换料!" -#else - #define FILAMENT_CHANGE_TEXT_CN "待打印机暂停后,\n请按<进料>或<退料>" -#endif +#define FILAMENT_CHANGE_TEXT_CN "待打印机暂停后,\n请按<进料>或<退料>" #define FILAMENT_DIALOG_LOAD_HEAT_TIPS_CN "准备进料,正在加热,请稍等!" #define FILAMENT_DIALOG_UNLOAD_HEAT_TIPS_CN "准备退料,正在加热,请稍等!" @@ -456,7 +454,6 @@ #define DIALOG_RETRY_CN "重试" #define DIALOG_STOP_CN "停止" #define DIALOG_REPRINT_FROM_BREAKPOINT_CN "从断点续打?" -//#define DIALOG_UNBIND_PRINTER_CN "解除绑定 ?" #define DIALOG_ERROR_TIPS1_CN "错误:找不到文件,请插入sd卡/u盘!" #define DIALOG_ERROR_TIPS2_CN "错误:通信失败,请检查波特率或主板硬件!" #define DIALOG_ERROR_TIPS3_CN "错误:文件名或文件路径太长 !" @@ -497,3 +494,10 @@ #define EEPROM_STORE_TIPS_CN "是否保存参数到EEPROM?" #define EEPROM_READ_TIPS_CN "是否使用EEPROM参数?" #define EEPROM_REVERT_TIPS_CN "是否恢复默认参数?" + +#define MORE_CUSTOM1_TEXT_CN MAIN_MENU_ITEM_1_DESC +#define MORE_CUSTOM2_TEXT_CN MAIN_MENU_ITEM_2_DESC +#define MORE_CUSTOM3_TEXT_CN MAIN_MENU_ITEM_3_DESC +#define MORE_CUSTOM4_TEXT_CN MAIN_MENU_ITEM_4_DESC +#define MORE_CUSTOM5_TEXT_CN MAIN_MENU_ITEM_5_DESC +#define MORE_CUSTOM6_TEXT_CN MAIN_MENU_ITEM_6_DESC diff --git a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_sp.h b/Marlin/src/lcd/extui/mks_ui/tft_Language_sp.h similarity index 79% rename from Marlin/src/lcd/extui/lib/mks_ui/tft_Language_sp.h rename to Marlin/src/lcd/extui/mks_ui/tft_Language_sp.h index 2babbaba93c4..a75bc69ab738 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_sp.h +++ b/Marlin/src/lcd/extui/mks_ui/tft_Language_sp.h @@ -23,15 +23,18 @@ //****************西班牙语*************************** #define TOOL_TEXT_SP "Ajustes" -#define PREHEAT_TEXT_SP "Precalentar"//"precalent\nar" +#define PREHEAT_TEXT_SP "Precalentar" #define MOVE_TEXT_SP "Mover" #define HOME_TEXT_SP "Origen" #define PRINT_TEXT_SP "Imprimir" #define EXTRUDE_TEXT_SP "Extrusor" -#define LEVELING_TEXT_SP "Leveling"//"nivelac\nión" -#define AUTO_LEVELING_TEXT_SP "Autolevel"//"auto\nnivelación" +#define LEVELING_TEXT_SP "Leveling" +#define MLEVELING_TEXT_SP "Leveling" +#define AUTO_LEVELING_TEXT_SP "Autolevel" #define SET_TEXT_SP "Config" #define MORE_TEXT_SP "Más" +#define MORE_GCODE_SP "G-Code" +#define MORE_ENTER_GCODE_SP "Introduzca el G-Code" #define ADD_TEXT_SP "Más" #define DEC_TEXT_SP "Menos" @@ -50,6 +53,7 @@ #define TOOL_MOVE_SP "Mover" #define TOOL_HOME_SP "Origen" #define TOOL_LEVELING_SP "Leveling" +#define TOOL_MLEVELING_SP "Leveling" #define TOOL_AUTO_LEVELING_SP "Autolevel" #define TOOL_FILAMENT_SP "Filamento" #define TOOL_MORE_SP "Más" @@ -135,50 +139,30 @@ #define FILAMENT_EXT1_TEXT_SP "Extrusor2" #define FILAMENT_HEAT_TEXT_SP "Precalentar" #define FILAMENT_STOP_TEXT_SP "Parar" -//#define FILAMENT_CHANGE_TEXT_SP "Filamento" #define FILAMENT_TIPS2_TEXT_SP "T:" #define FILAMENT_TIPS3_TEXT_SP "Dentro..." #define FILAMENT_TIPS4_TEXT_SP "Fuera..." #define FILAMENT_TIPS5_TEXT_SP "Temperatura demasiado baja, por favor calentar" #define FILAMENT_TIPS6_TEXT_SP "Completado" -#if 0 - #define FILAMENT_REPLAYS_IDLE_TEXT_SP "Please click or \nto replace filament!" - #define FILAMENT_CHANGE_TEXT_SP "Please click or ,\nAfter pinter pause." - #define FILAMENT_DIALOG_LOAD_HEAT_TIPS_SP "Calentando el extrusor, por favor espere..." - #define FILAMENT_DIALOG_UNLOAD_HEAT_TIPS_SP "Calentando el extrusor, por favor espere..." - #define FILAMENT_DIALOG_LOAD_CONFIRM1_TIPS_SP "Temperatura alcanzada.Inserte el filamento y luego presione\"Confirmar\"para comenzar la carga." - #define FILAMENT_DIALOG_LOAD_CONFIRM2_TIPS_SP "Inserte el filamento y luego presione\"Confirmar\"para comenzar la carga." - #define FILAMENT_DIALOG_UNLOAD_CONFIRM_TIPS_SP "Temperatura alcanzada.Presione\"Confirmar\"para retirar el filamento." - #define FILAMENT_DIALOG_LOADING_TIPS_SP "Cargando filamento,por favor espere." - #define FILAMENT_DIALOG_UNLOADING_TIPS_SP "Retirando filamento,por favor espere." - #define FILAMENT_DIALOG_LOAD_COMPLETE_TIPS_SP "Filamento cargado,presione\"Confirmar\"." - #define FILAMENT_DIALOG_UNLOAD_COMPLETE_TIPS_SP "Filamento retirado,presione\"Confirmar\"." -#else - #define FILAMENT_CHANGE_TEXT_SP "Please click \nor ,After \npinter pause." - #define FILAMENT_DIALOG_LOAD_HEAT_TIPS_SP "Calentando el extrusor,\npor favor espere..." - #define FILAMENT_DIALOG_UNLOAD_HEAT_TIPS_SP "Calentando el extrusor,\npor favor espere..." - #define FILAMENT_DIALOG_LOAD_CONFIRM1_TIPS_SP "Temperatura alcanzada.Inserte el \nfilamento y luego presione\"Confirmar\"\npara comenzar la carga." - #define FILAMENT_DIALOG_LOAD_CONFIRM2_TIPS_SP "Inserte el filamento y \nluego presione\"Confirmar\"para \ncomenzar la carga." - #define FILAMENT_DIALOG_UNLOAD_CONFIRM_TIPS_SP "Temperatura alcanzada.\nPresione\"Confirmar\"para retirar \nel filamento." - #define FILAMENT_DIALOG_LOADING_TIPS_SP "Cargando filamento,\npor favor espere." - #define FILAMENT_DIALOG_UNLOADING_TIPS_SP "Retirando filamento,\npor favor espere." - #define FILAMENT_DIALOG_LOAD_COMPLETE_TIPS_SP "Filamento cargado,\npresione\"Confirmar\"." - #define FILAMENT_DIALOG_UNLOAD_COMPLETE_TIPS_SP "Filamento retirado,\npresione\"Confirmar\"." -#endif + +#define FILAMENT_CHANGE_TEXT_SP "Please click \nor ,After \npinter pause." +#define FILAMENT_DIALOG_LOAD_HEAT_TIPS_SP "Calentando el extrusor,\npor favor espere..." +#define FILAMENT_DIALOG_UNLOAD_HEAT_TIPS_SP "Calentando el extrusor,\npor favor espere..." +#define FILAMENT_DIALOG_LOAD_CONFIRM1_TIPS_SP "Temperatura alcanzada.Inserte el \nfilamento y luego presione\"Confirmar\"\npara comenzar la carga." +#define FILAMENT_DIALOG_LOAD_CONFIRM2_TIPS_SP "Inserte el filamento y \nluego presione\"Confirmar\"para \ncomenzar la carga." +#define FILAMENT_DIALOG_UNLOAD_CONFIRM_TIPS_SP "Temperatura alcanzada.\nPresione\"Confirmar\"para retirar \nel filamento." +#define FILAMENT_DIALOG_LOADING_TIPS_SP "Cargando filamento,\npor favor espere." +#define FILAMENT_DIALOG_UNLOADING_TIPS_SP "Retirando filamento,\npor favor espere." +#define FILAMENT_DIALOG_LOAD_COMPLETE_TIPS_SP "Filamento cargado,\npresione\"Confirmar\"." +#define FILAMENT_DIALOG_UNLOAD_COMPLETE_TIPS_SP "Filamento retirado,\npresione\"Confirmar\"." #define PRE_HEAT_EXT_TEXT_SP "Extrusor" #define PRE_HEAT_BED_TEXT_SP "cama" #define FILE_LOADING_SP "Cargando......" -#if 0 - #define NO_FILE_AND_CHECK_SP "No se encontraron archivos! Por favor, inserte la tarjeta SD o el disco U!" -#endif #define NO_FILE_AND_CHECK_SP "Archivo no encontrado,\n por favor insertar SD o disco USB!" - #define NO_FILE_SP "Sin archivo!" - - #define EXTRUDER_TEMP_TEXT_SP "Temper" #define EXTRUDER_E_LENGTH1_TEXT_SP "Extrusor1" #define EXTRUDER_E_LENGTH2_TEXT_SP "Extrusor2" @@ -245,7 +229,6 @@ #define DIALOG_RETRY_SP "Reintentar" #define DIALOG_STOP_SP "Stop" #define DIALOG_REPRINT_FROM_BREAKPOINT_SP "Reprint from breakpoint?" -//#define DIALOG_UNBIND_PRINTER_SP "Unbind the printer?" #define DIALOG_ERROR_TIPS1_SP "Error:archivo no encontrado, \npor favor insertar SD o disco USB." #define DIALOG_ERROR_TIPS2_SP "error:transacción fallida, \nconfigurar baudrate del \ndisplay para la placa base!" #define DIALOG_ERROR_TIPS3_SP "Error : nombre de archivo o \nruta demasiado largo!" @@ -282,3 +265,10 @@ #define EEPROM_STORE_TIPS_SP "¿Guardar ajustes en EEPROM?" #define EEPROM_READ_TIPS_SP "Leer la configuración de EEPROM?" #define EEPROM_REVERT_TIPS_SP "Revert settings to factory defaults?" + +#define MORE_CUSTOM1_TEXT_SP MAIN_MENU_ITEM_1_DESC +#define MORE_CUSTOM2_TEXT_SP MAIN_MENU_ITEM_2_DESC +#define MORE_CUSTOM3_TEXT_SP MAIN_MENU_ITEM_3_DESC +#define MORE_CUSTOM4_TEXT_SP MAIN_MENU_ITEM_4_DESC +#define MORE_CUSTOM5_TEXT_SP MAIN_MENU_ITEM_5_DESC +#define MORE_CUSTOM6_TEXT_SP MAIN_MENU_ITEM_6_DESC diff --git a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_t_cn.h b/Marlin/src/lcd/extui/mks_ui/tft_Language_t_cn.h similarity index 96% rename from Marlin/src/lcd/extui/lib/mks_ui/tft_Language_t_cn.h rename to Marlin/src/lcd/extui/mks_ui/tft_Language_t_cn.h index d956e14aadf1..c9607187ef78 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_t_cn.h +++ b/Marlin/src/lcd/extui/mks_ui/tft_Language_t_cn.h @@ -84,13 +84,13 @@ #define LEVELING_CONF_TITLE_T_CN "機器參數>調平設置" #define LEVELING_PARA_CONF_T_CN "調平設置" -#define LEVELING_MANUAL_POS_T_CN "手動調平坐標設置" +#define TRAMMING_POS_T_CN "手動調平坐標設置" #define LEVELING_AUTO_COMMAND_T_CN "自動調平指令設置" #define LEVELING_AUTO_ZOFFSET_T_CN "擠出頭與調平開關偏移設置" #define LEVELING_PARA_CONF_TITLE_T_CN "調平參數" #define AUTO_LEVELING_ENABLE_T_CN "自動調平" -#define BLTOUCH_LEVELING_ENABLE_T_CN "啟動BLtouch" +#define BLTOUCH_LEVELING_ENABLE_T_CN "啟動BLTouch" #define PROBE_PORT_T_CN "調平探針接口" #define PROBE_X_OFFSET_T_CN "探針X方向偏移" #define PROBE_Y_OFFSET_T_CN "探针Y方向偏移" @@ -99,6 +99,7 @@ #define PROBE_Z_SPEED_T_CN "探针Z方向移動速度" #define ENABLE_T_CN "是" #define DISABLE_T_CN "否" +#define LOCKED_T_CN "否" #define Z_MIN_T_CN "ZMin" #define Z_MAX_T_CN "ZMax" @@ -254,7 +255,7 @@ #define TOOL_TEXT_T_CN "工具" #define PREHEAT_TEXT_T_CN "預熱" -#define MOVE_TEXT_T_CN "移動" +#define MOVE_TEXT_T_CN "移動" #define HOME_TEXT_T_CN "回零" #define PRINT_TEXT_T_CN "打印" #define EXTRUDE_TEXT_T_CN "擠出" @@ -262,6 +263,8 @@ #define AUTO_LEVELING_TEXT_T_CN "自動調平" #define SET_TEXT_T_CN "設置" #define MORE_TEXT_T_CN "更多" +#define MORE_GCODE_T_CN "G-Code" +#define MORE_ENTER_GCODE_T_CN "Enter G-Code" #define ADD_TEXT_T_CN "增加" #define DEC_TEXT_T_CN "減少" @@ -364,19 +367,12 @@ #define FILAMENT_EXT1_TEXT_T_CN "噴頭2" #define FILAMENT_HEAT_TEXT_T_CN "預熱" #define FILAMENT_STOP_TEXT_T_CN "停止" -//#define FILAMENT_CHANGE_TEXT_T_CN "準備換料" #define FILAMENT_TIPS2_TEXT_T_CN "T:" #define FILAMENT_TIPS3_TEXT_T_CN "正在進料" #define FILAMENT_TIPS4_TEXT_T_CN "正在退料" #define FILAMENT_TIPS5_TEXT_T_CN "溫度太低,請先預熱" #define FILAMENT_TIPS6_TEXT_T_CN "換料完成" - -#if 0 - #define FILAMENT_REPLAYS_IDLE_TEXT_T_CN "請按<進料>或<退料>進行換料!" - #define FILAMENT_CHANGE_TEXT_T_CN "待打印機暫停后,請按<進料>或<退料>進行換料!" -#endif - - #define FILAMENT_CHANGE_TEXT_T_CN "待打印機暫停后,\n請按<進料>或<退料>" +#define FILAMENT_CHANGE_TEXT_T_CN "待打印機暫停后,\n請按<進料>或<退料>" #define FILAMENT_DIALOG_LOAD_HEAT_TIPS_T_CN "準備進料,正在加熱,請稍等" #define FILAMENT_DIALOG_UNLOAD_HEAT_TIPS_T_CN "準備退料,正在加熱,請稍等" @@ -434,8 +430,8 @@ #define TITLE_PRINTING_T_CN "正在打印" #define TITLE_OPERATION_T_CN "操作" #define TITLE_ADJUST_T_CN "調整" -#define TITLE_WIRELESS_T_CN "無線網絡" -#define TITLE_FILAMENT_T_CN "換料" +#define TITLE_WIRELESS_T_CN "無線網絡" +#define TITLE_FILAMENT_T_CN "換料" #define TITLE_ABOUT_T_CN "關於" #define TITLE_FAN_T_CN "風扇" #define TITLE_LANGUAGE_T_CN "語言" @@ -459,7 +455,6 @@ #define DIALOG_RETRY_T_CN "重試" #define DIALOG_STOP_T_CN "停止" #define DIALOG_REPRINT_FROM_BREAKPOINT_T_CN "從斷點續打?" -//#define DIALOG_UNBIND_PRINTER_T_CN "解除綁定?" #define DIALOG_ERROR_TIPS1_T_CN "錯誤:找不到文件,請插入sd卡/u盤!" #define DIALOG_ERROR_TIPS2_T_CN "錯誤:通信失敗,請檢查波特率或主板硬件!" #define DIALOG_ERROR_TIPS3_T_CN "錯誤:文件名或文件路徑太長!" @@ -497,3 +492,10 @@ #define EEPROM_STORE_TIPS_T_CN "是否保存參數到EEPROM?" #define EEPROM_READ_TIPS_T_CN "是否使用EEPROM參數?" #define EEPROM_REVERT_TIPS_T_CN "是否恢復默認參數?" + +#define MORE_CUSTOM1_TEXT_T_CN MAIN_MENU_ITEM_1_DESC +#define MORE_CUSTOM2_TEXT_T_CN MAIN_MENU_ITEM_2_DESC +#define MORE_CUSTOM3_TEXT_T_CN MAIN_MENU_ITEM_3_DESC +#define MORE_CUSTOM4_TEXT_T_CN MAIN_MENU_ITEM_4_DESC +#define MORE_CUSTOM5_TEXT_T_CN MAIN_MENU_ITEM_5_DESC +#define MORE_CUSTOM6_TEXT_T_CN MAIN_MENU_ITEM_6_DESC diff --git a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp new file mode 100644 index 000000000000..cfd6db15fdae --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp @@ -0,0 +1,539 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "SPI_TFT.h" + +#include "tft_lvgl_configuration.h" +#include "draw_ready_print.h" + +#include "pic_manager.h" +#include "mks_hardware.h" +#include "draw_ui.h" +#include "SPIFlashStorage.h" +#include + +#include "../../../MarlinCore.h" +#include "../../../inc/MarlinConfig.h" + +#include HAL_PATH(../../../HAL, tft/xpt2046.h) +#include "../../marlinui.h" +XPT2046 touch; + +#if ENABLED(POWER_LOSS_RECOVERY) + #include "../../../feature/powerloss.h" +#endif + +#if HAS_SERVOS + #include "../../../module/servo.h" +#endif + +#if EITHER(PROBE_TARE, HAS_Z_SERVO_PROBE) + #include "../../../module/probe.h" +#endif + +#if ENABLED(TOUCH_SCREEN_CALIBRATION) + #include "../../tft_io/touch_calibration.h" + #include "draw_touch_calibration.h" +#endif + +#if ENABLED(MKS_WIFI_MODULE) + #include "wifi_module.h" +#endif + +#include + +#ifndef TFT_WIDTH + #define TFT_WIDTH 480 +#endif +#ifndef TFT_HEIGHT + #define TFT_HEIGHT 320 +#endif + +#if HAS_SPI_FLASH_FONT + void init_gb2312_font(); +#endif + +static lv_disp_buf_t disp_buf; +lv_group_t* g; +#if ENABLED(SDSUPPORT) + void UpdateAssets(); +#endif +uint16_t DeviceCode = 0x9488; +extern uint8_t sel_id; + +uint8_t bmp_public_buf[14 * 1024]; +uint8_t public_buf[513]; + +extern bool flash_preview_begin, default_preview_flg, gcode_preview_over; + +void SysTick_Callback() { + lv_tick_inc(1); + print_time_count(); + #if ENABLED(MKS_WIFI_MODULE) + if (tips_disp.timer == TIPS_TIMER_START) + tips_disp.timer_count++; + #endif + if (uiCfg.filament_loading_time_flg) { + uiCfg.filament_loading_time_cnt++; + uiCfg.filament_rate = uint32_t(100.0f * uiCfg.filament_loading_time_cnt / SEC_TO_MS(uiCfg.filament_loading_time) + 0.5f); + if (uiCfg.filament_loading_time_cnt >= SEC_TO_MS(uiCfg.filament_loading_time)) { + uiCfg.filament_loading_time_cnt = 0; + uiCfg.filament_loading_time_flg = false; + uiCfg.filament_loading_completed = true; + } + } + if (uiCfg.filament_unloading_time_flg) { + uiCfg.filament_unloading_time_cnt++; + uiCfg.filament_rate = uint32_t(100.0f * uiCfg.filament_unloading_time_cnt / SEC_TO_MS(uiCfg.filament_unloading_time) + 0.5f); + if (uiCfg.filament_unloading_time_cnt >= SEC_TO_MS(uiCfg.filament_unloading_time)) { + uiCfg.filament_unloading_time_cnt = 0; + uiCfg.filament_unloading_time_flg = false; + uiCfg.filament_unloading_completed = true; + uiCfg.filament_rate = 100; + } + } +} + +void tft_lvgl_init() { + + W25QXX.init(SPI_QUARTER_SPEED); + + gCfgItems_init(); + ui_cfg_init(); + disp_language_init(); + + watchdog_refresh(); // LVGL init takes time + + #if MB(MKS_ROBIN_NANO) + OUT_WRITE(PB0, LOW); // HE1 + #endif + + // Init TFT first! + SPI_TFT.spi_init(SPI_FULL_SPEED); + SPI_TFT.LCD_init(); + + watchdog_refresh(); // LVGL init takes time + + #if ENABLED(SDSUPPORT) + UpdateAssets(); + watchdog_refresh(); // LVGL init takes time + TERN_(MKS_TEST, mks_test_get()); + #endif + + touch.Init(); + + lv_init(); + + lv_disp_buf_init(&disp_buf, bmp_public_buf, nullptr, LV_HOR_RES_MAX * 14); // Initialize the display buffer + + lv_disp_drv_t disp_drv; // Descriptor of a display driver + lv_disp_drv_init(&disp_drv); // Basic initialization + disp_drv.flush_cb = my_disp_flush; // Set your driver function + disp_drv.buffer = &disp_buf; // Assign the buffer to the display + lv_disp_drv_register(&disp_drv); // Finally register the driver + + lv_indev_drv_t indev_drv; + lv_indev_drv_init(&indev_drv); // Descriptor of a input device driver + indev_drv.type = LV_INDEV_TYPE_POINTER; // Touch pad is a pointer-like device + indev_drv.read_cb = my_touchpad_read; // Set your driver function + lv_indev_drv_register(&indev_drv); // Finally register the driver + + #if HAS_ROTARY_ENCODER + g = lv_group_create(); + lv_indev_drv_t enc_drv; + lv_indev_drv_init(&enc_drv); + enc_drv.type = LV_INDEV_TYPE_ENCODER; + enc_drv.read_cb = my_mousewheel_read; + lv_indev_t * enc_indev = lv_indev_drv_register(&enc_drv); + lv_indev_set_group(enc_indev, g); + #endif + + lv_fs_drv_t spi_flash_drv; + lv_fs_drv_init(&spi_flash_drv); + spi_flash_drv.letter = 'F'; + spi_flash_drv.open_cb = spi_flash_open_cb; + spi_flash_drv.close_cb = spi_flash_close_cb; + spi_flash_drv.read_cb = spi_flash_read_cb; + spi_flash_drv.seek_cb = spi_flash_seek_cb; + spi_flash_drv.tell_cb = spi_flash_tell_cb; + lv_fs_drv_register(&spi_flash_drv); + + lv_fs_drv_t sd_drv; + lv_fs_drv_init(&sd_drv); + sd_drv.letter = 'S'; + sd_drv.open_cb = sd_open_cb; + sd_drv.close_cb = sd_close_cb; + sd_drv.read_cb = sd_read_cb; + sd_drv.seek_cb = sd_seek_cb; + sd_drv.tell_cb = sd_tell_cb; + lv_fs_drv_register(&sd_drv); + + systick_attach_callback(SysTick_Callback); + + #if HAS_SPI_FLASH_FONT + init_gb2312_font(); + #endif + + tft_style_init(); + filament_pin_setup(); + lv_encoder_pin_init(); + + #if ENABLED(MKS_WIFI_MODULE) + mks_esp_wifi_init(); + mks_wifi_firmware_update(); + #endif + TERN_(HAS_SERVOS, servo_init()); + TERN_(HAS_Z_SERVO_PROBE, probe.servo_probe_init()); + bool ready = true; + #if ENABLED(POWER_LOSS_RECOVERY) + recovery.load(); + if (recovery.valid()) { + ready = false; + if (gCfgItems.from_flash_pic) + flash_preview_begin = true; + else + default_preview_flg = true; + + uiCfg.print_state = REPRINTING; + + #if ENABLED(LONG_FILENAME_HOST_SUPPORT) + strncpy(public_buf_m, recovery.info.sd_filename, sizeof(public_buf_m)); + card.printLongPath(public_buf_m); + strncpy(list_file.long_name[sel_id], card.longFilename, sizeof(list_file.long_name[0])); + #else + strncpy(list_file.long_name[sel_id], recovery.info.sd_filename, sizeof(list_file.long_name[0])); + #endif + lv_draw_printing(); + } + #endif + + if (ready) lv_draw_ready_print(); + + #if BOTH(MKS_TEST, SDSUPPORT) + if (mks_test_flag == 0x1E) mks_gpio_test(); + #endif +} + +void my_disp_flush(lv_disp_drv_t * disp, const lv_area_t * area, lv_color_t * color_p) { + uint16_t width = area->x2 - area->x1 + 1, + height = area->y2 - area->y1 + 1; + + SPI_TFT.setWindow((uint16_t)area->x1, (uint16_t)area->y1, width, height); + + for (uint16_t i = 0; i < height; i++) + SPI_TFT.tftio.WriteSequence((uint16_t*)(color_p + width * i), width); + + lv_disp_flush_ready(disp); // Indicate you are ready with the flushing + + W25QXX.init(SPI_QUARTER_SPEED); +} + +void lv_fill_rect(lv_coord_t x1, lv_coord_t y1, lv_coord_t x2, lv_coord_t y2, lv_color_t bk_color) { + uint16_t width, height; + width = x2 - x1 + 1; + height = y2 - y1 + 1; + SPI_TFT.setWindow((uint16_t)x1, (uint16_t)y1, width, height); + SPI_TFT.tftio.WriteMultiple(bk_color.full, width * height); + 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)); +} + +static bool get_point(int16_t *x, int16_t *y) { + bool is_touched = touch.getRawPoint(x, y); + + if (!is_touched) 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 (touch_calibration.handleTouch(*x, *y)) lv_update_touch_calibration_screen(); + return false; + } + *x = int16_t((int32_t(*x) * touch_calibration.calibration.x) >> 16) + touch_calibration.calibration.offset_x; + *y = int16_t((int32_t(*y) * touch_calibration.calibration.y) >> 16) + touch_calibration.calibration.offset_y; + #else + *x = int16_t((int32_t(*x) * TOUCH_CALIBRATION_X) >> 16) + TOUCH_OFFSET_X; + *y = int16_t((int32_t(*y) * TOUCH_CALIBRATION_Y) >> 16) + TOUCH_OFFSET_Y; + #endif + + return true; +} + +bool my_touchpad_read(lv_indev_drv_t * indev_driver, lv_indev_data_t * data) { + static int16_t last_x = 0, last_y = 0; + static uint8_t last_touch_state = LV_INDEV_STATE_REL; + static int32_t touch_time1 = 0; + uint32_t tmpTime, diffTime = 0; + + tmpTime = millis(); + diffTime = getTickDiff(tmpTime, touch_time1); + if (diffTime > 20) { + if (get_point(&last_x, &last_y)) { + + if (last_touch_state == LV_INDEV_STATE_PR) return false; + data->state = LV_INDEV_STATE_PR; + + // Set the coordinates (if released use the last-pressed coordinates) + data->point.x = last_x; + data->point.y = last_y; + + last_x = last_y = 0; + last_touch_state = LV_INDEV_STATE_PR; + } + else { + if (last_touch_state == LV_INDEV_STATE_PR) + data->state = LV_INDEV_STATE_REL; + last_touch_state = LV_INDEV_STATE_REL; + } + + touch_time1 = tmpTime; + } + + return false; // Return `false` since no data is buffering or left to read +} + +int16_t enc_diff = 0; +lv_indev_state_t state = LV_INDEV_STATE_REL; + +bool my_mousewheel_read(lv_indev_drv_t * indev_drv, lv_indev_data_t * data) { + (void) indev_drv; // Unused + + data->state = state; + data->enc_diff = enc_diff; + enc_diff = 0; + + return false; // No more data to read so return false +} + +extern uint8_t currentFlashPage; + +//spi_flash +uint32_t pic_read_base_addr = 0, pic_read_addr_offset = 0; +lv_fs_res_t spi_flash_open_cb (lv_fs_drv_t * drv, void * file_p, const char * path, lv_fs_mode_t mode) { + static char last_path_name[30]; + if (strcasecmp(last_path_name, path) != 0) { + pic_read_base_addr = lv_get_pic_addr((uint8_t *)path); + strcpy(last_path_name, path); + } + else { + W25QXX.init(SPI_QUARTER_SPEED); + currentFlashPage = 0; + } + pic_read_addr_offset = pic_read_base_addr; + return LV_FS_RES_OK; +} + +lv_fs_res_t spi_flash_close_cb (lv_fs_drv_t * drv, void * file_p) { + lv_fs_res_t res = LV_FS_RES_OK; + /* Add your code here */ + pic_read_addr_offset = pic_read_base_addr; + return res; +} + +lv_fs_res_t spi_flash_read_cb (lv_fs_drv_t * drv, void * file_p, void * buf, uint32_t btr, uint32_t * br) { + lv_pic_test((uint8_t *)buf, pic_read_addr_offset, btr); + *br = btr; + return LV_FS_RES_OK; +} + +lv_fs_res_t spi_flash_seek_cb(lv_fs_drv_t * drv, void * file_p, uint32_t pos) { + #if HAS_SPI_FLASH_COMPRESSION + if (pos == 4) { + uint8_t bmp_header[4]; + SPIFlash.beginRead(pic_read_base_addr); + SPIFlash.readData(bmp_header, 4); + currentFlashPage = 1; + } + pic_read_addr_offset = pic_read_base_addr; + #else + pic_read_addr_offset = pic_read_base_addr + pos; + #endif + return LV_FS_RES_OK; +} + +lv_fs_res_t spi_flash_tell_cb(lv_fs_drv_t * drv, void * file_p, uint32_t * pos_p) { + *pos_p = pic_read_addr_offset - pic_read_base_addr; + return LV_FS_RES_OK; +} + +//sd +char *cur_namefff; +uint32_t sd_read_base_addr = 0, sd_read_addr_offset = 0, small_image_size = 409; +lv_fs_res_t sd_open_cb (lv_fs_drv_t * drv, void * file_p, const char * path, lv_fs_mode_t mode) { + char name_buf[100]; + *name_buf = '/'; + strcpy(name_buf + 1, path); + char *temp = strstr(name_buf, ".bin"); + if (temp) strcpy(temp, ".GCO"); + sd_read_base_addr = lv_open_gcode_file((char *)name_buf); + sd_read_addr_offset = sd_read_base_addr; + if (sd_read_addr_offset == UINT32_MAX) return LV_FS_RES_NOT_EX; + // find small image size + card.read(public_buf, 512); + public_buf[511] = '\0'; + const char* eol = strpbrk((const char*)public_buf, "\n\r"); + small_image_size = (uintptr_t)eol - (uintptr_t)((uint32_t *)(&public_buf[0])) + 1; + return LV_FS_RES_OK; +} + +lv_fs_res_t sd_close_cb (lv_fs_drv_t * drv, void * file_p) { + /* Add your code here */ + lv_close_gcode_file(); + return LV_FS_RES_OK; +} + +lv_fs_res_t sd_read_cb (lv_fs_drv_t * drv, void * file_p, void * buf, uint32_t btr, uint32_t * br) { + if (btr == 200) { + lv_gcode_file_read((uint8_t *)buf); + //pic_read_addr_offset += 208; + *br = 200; + } + else if (btr == 4) { + uint8_t header_pic[4] = { 0x04, 0x90, 0x81, 0x0C }; + memcpy(buf, header_pic, 4); + *br = 4; + } + return LV_FS_RES_OK; +} + +lv_fs_res_t sd_seek_cb(lv_fs_drv_t * drv, void * file_p, uint32_t pos) { + sd_read_addr_offset = sd_read_base_addr + (pos - 4) / 200 * small_image_size; + lv_gcode_file_seek(sd_read_addr_offset); + return LV_FS_RES_OK; +} + +lv_fs_res_t sd_tell_cb(lv_fs_drv_t * drv, void * file_p, uint32_t * pos_p) { + if (sd_read_addr_offset) *pos_p = 0; + else *pos_p = (sd_read_addr_offset - sd_read_base_addr) / small_image_size * 200 + 4; + return LV_FS_RES_OK; +} + +void lv_encoder_pin_init() { + #if BUTTON_EXISTS(EN1) + SET_INPUT_PULLUP(BTN_EN1); + #endif + #if BUTTON_EXISTS(EN2) + SET_INPUT_PULLUP(BTN_EN2); + #endif + #if BUTTON_EXISTS(ENC) + SET_INPUT_PULLUP(BTN_ENC); + #endif + + #if BUTTON_EXISTS(BACK) + SET_INPUT_PULLUP(BTN_BACK); + #endif + + #if BUTTON_EXISTS(UP) + SET_INPUT(BTN_UP); + #endif + #if BUTTON_EXISTS(DWN) + SET_INPUT(BTN_DWN); + #endif + #if BUTTON_EXISTS(LFT) + SET_INPUT(BTN_LFT); + #endif + #if BUTTON_EXISTS(RT) + SET_INPUT(BTN_RT); + #endif +} + +#if 1 // HAS_ENCODER_ACTION + void lv_update_encoder() { + static uint32_t encoder_time1; + uint32_t tmpTime, diffTime = 0; + tmpTime = millis(); + diffTime = getTickDiff(tmpTime, encoder_time1); + if (diffTime > 50) { + + #if HAS_ENCODER_WHEEL + + #if ANY_BUTTON(EN1, EN2, ENC, BACK) + + uint8_t newbutton = 0; + if (BUTTON_PRESSED(EN1)) newbutton |= EN_A; + if (BUTTON_PRESSED(EN2)) newbutton |= EN_B; + if (BUTTON_PRESSED(ENC)) newbutton |= EN_C; + if (BUTTON_PRESSED(BACK)) newbutton |= EN_D; + + #else + + constexpr uint8_t newbutton = 0; + + #endif + + static uint8_t buttons = 0; + buttons = newbutton; + static uint8_t lastEncoderBits; + + #define encrot0 0 + #define encrot1 1 + #define encrot2 2 + + uint8_t enc = 0; + if (buttons & EN_A) enc |= B01; + if (buttons & EN_B) enc |= B10; + if (enc != lastEncoderBits) { + switch (enc) { + case encrot1: + if (lastEncoderBits == encrot0) { + enc_diff--; + encoder_time1 = tmpTime; + } + break; + case encrot2: + if (lastEncoderBits == encrot0) { + enc_diff++; + encoder_time1 = tmpTime; + } + break; + } + lastEncoderBits = enc; + } + static uint8_t last_button_state = LV_INDEV_STATE_REL; + const uint8_t enc_c = (buttons & EN_C) ? LV_INDEV_STATE_PR : LV_INDEV_STATE_REL; + if (enc_c != last_button_state) { + state = enc_c ? LV_INDEV_STATE_PR : LV_INDEV_STATE_REL; + last_button_state = enc_c; + } + + #endif // HAS_ENCODER_WHEEL + + } // next_button_update_ms + } + +#endif // HAS_ENCODER_ACTION + +#if __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) {} +#endif + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.h b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.h new file mode 100644 index 000000000000..e2786fd452cf --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.h @@ -0,0 +1,69 @@ +/** + * 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 + +/** + * @file lcd/extui/mks_ui/tft_lvgl_configuration.h + * @date 2020-02-21 + */ + +#ifdef __cplusplus + extern "C" { /* C-declarations for C++ */ +#endif + +#include + +//#define TFT_ROTATION TFT_ROTATE_180 + +extern uint8_t bmp_public_buf[14 * 1024]; +extern uint8_t public_buf[513]; + +void tft_lvgl_init(); +void my_disp_flush(lv_disp_drv_t * disp, const lv_area_t * area, lv_color_t * color_p); +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 lv_encoder_pin_init(); +void lv_update_encoder(); + +lv_fs_res_t spi_flash_open_cb(lv_fs_drv_t * drv, void * file_p, const char * path, lv_fs_mode_t mode); +lv_fs_res_t spi_flash_close_cb(lv_fs_drv_t * drv, void * file_p); +lv_fs_res_t spi_flash_read_cb(lv_fs_drv_t * drv, void * file_p, void * buf, uint32_t btr, uint32_t * br); +lv_fs_res_t spi_flash_seek_cb(lv_fs_drv_t * drv, void * file_p, uint32_t pos); +lv_fs_res_t spi_flash_tell_cb(lv_fs_drv_t * drv, void * file_p, uint32_t * pos_p); + +lv_fs_res_t sd_open_cb(lv_fs_drv_t * drv, void * file_p, const char * path, lv_fs_mode_t mode); +lv_fs_res_t sd_close_cb(lv_fs_drv_t * drv, void * file_p); +lv_fs_res_t sd_read_cb(lv_fs_drv_t * drv, void * file_p, void * buf, uint32_t btr, uint32_t * br); +lv_fs_res_t sd_seek_cb(lv_fs_drv_t * drv, void * file_p, uint32_t pos); +lv_fs_res_t sd_tell_cb(lv_fs_drv_t * drv, void * file_p, uint32_t * pos_p); + +void lv_fill_rect(lv_coord_t x1, lv_coord_t y1, lv_coord_t x2, lv_coord_t y2, lv_color_t bk_color); + +#ifdef __cplusplus + } /* C-declarations for C++ */ +#endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/tft_multi_language.cpp b/Marlin/src/lcd/extui/mks_ui/tft_multi_language.cpp similarity index 89% rename from Marlin/src/lcd/extui/lib/mks_ui/tft_multi_language.cpp rename to Marlin/src/lcd/extui/mks_ui/tft_multi_language.cpp index e230195eabac..0771a31cb415 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/tft_multi_language.cpp +++ b/Marlin/src/lcd/extui/mks_ui/tft_multi_language.cpp @@ -19,12 +19,10 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI -#include "../../../../MarlinCore.h" - #include "draw_ui.h" #include "tft_multi_language.h" @@ -58,6 +56,9 @@ tool_menu_def tool_menu; MachinePara_menu_def MachinePara_menu; pause_msg_def pause_msg_menu; eeprom_def eeprom_menu; +media_select_menu_def media_select_menu; + +// TODO: Make all strings PSTR and update accessors for the benefit of AVR machine_common_def machine_menu; void machine_setting_disp() { @@ -121,7 +122,7 @@ void machine_setting_disp() { machine_menu.LevelingParaConfTitle = LEVELING_CONF_TITLE_CN; machine_menu.LevelingParaConf = LEVELING_PARA_CONF_CN; - machine_menu.LevelingManuPosConf = LEVELING_MANUAL_POS_CN; + machine_menu.TrammingPosConf = TRAMMING_POS_CN; machine_menu.LevelingAutoCommandConf = LEVELING_AUTO_COMMAND_CN; machine_menu.LevelingAutoZoffsetConf = LEVELING_AUTO_ZOFFSET_CN; @@ -136,6 +137,7 @@ void machine_setting_disp() { machine_menu.ProbeZspeed = PROBE_Z_SPEED_CN; machine_menu.enable = ENABLE_CN; machine_menu.disable = DISABLE_CN; + machine_menu.locked = LOCKED_CN; machine_menu.z_min = Z_MIN_CN; machine_menu.z_max = Z_MAX_CN; @@ -149,10 +151,6 @@ void machine_setting_disp() { machine_menu.CalibrationRadius = CALIBRATION_RADIUS_CN; machine_menu.LevelingSubXYZConfTitle = XYZ_LEVEL_CONF_TITLE_CN; - // machine_menu.ProbeMaxLeft=PROBE_REACH_MAX_LEFT_CN; - // machine_menu.ProbeMaxRigh=PROBE_REACH_MAX_RIGHT_CN; - // machine_menu.ProbeMaxfront=PROBE_REACH_MAX_FRONT_CN; - // machine_menu.ProbeMaxback=PROBE_REACH_MAX_BACK_CN; machine_menu.TemperatureConfTitle = TEMPERATURE_CONF_TITLE_CN; machine_menu.NozzleConf = NOZZLE_CONF_CN; @@ -167,7 +165,6 @@ void machine_setting_disp() { machine_menu.NozzleMaxTemperature = NOZZLE_MAX_TEMPERATURE_CN; machine_menu.Extrude_Min_Temper = EXTRUD_MIN_TEMPER_CN; - // machine_menu.HotbedEnable=HOTBED_ENABLE_CN; machine_menu.HotbedConfTitle = HOTBED_CONF_TITLE_CN; machine_menu.HotbedAjustType = HOTBED_ADJUST_CN; machine_menu.HotbedMinTemperature = HOTBED_MIN_TEMPERATURE_CN; @@ -242,7 +239,6 @@ void machine_setting_disp() { machine_menu.HomeFeedRateConfTitle = HOMEFEEDRATE_CONF_TITLE_CN; machine_menu.XY_HomeFeedRate = X_HOMESPEED_CN; - // machine_menu.Y_HomeFeedRate=Y_HOMESPEED_CN; machine_menu.Z_HomeFeedRate = Z_HOMESPEED_CN; machine_menu.AdvancedConfTitle = ADVANCED_CONF_TITLE_CN; @@ -354,7 +350,7 @@ void machine_setting_disp() { machine_menu.LevelingParaConfTitle = LEVELING_CONF_TITLE_T_CN; machine_menu.LevelingParaConf = LEVELING_PARA_CONF_T_CN; - machine_menu.LevelingManuPosConf = LEVELING_MANUAL_POS_T_CN; + machine_menu.TrammingPosConf = TRAMMING_POS_T_CN; machine_menu.LevelingAutoCommandConf = LEVELING_AUTO_COMMAND_T_CN; machine_menu.LevelingAutoZoffsetConf = LEVELING_AUTO_ZOFFSET_T_CN; @@ -369,6 +365,7 @@ void machine_setting_disp() { machine_menu.ProbeZspeed = PROBE_Z_SPEED_T_CN; machine_menu.enable = ENABLE_T_CN; machine_menu.disable = DISABLE_T_CN; + machine_menu.locked = LOCKED_T_CN; machine_menu.z_min = Z_MIN_T_CN; machine_menu.z_max = Z_MAX_T_CN; @@ -382,10 +379,6 @@ void machine_setting_disp() { machine_menu.CalibrationRadius = CALIBRATION_RADIUS_T_CN; machine_menu.LevelingSubXYZConfTitle = XYZ_LEVEL_CONF_TITLE_T_CN; - // machine_menu.ProbeMaxLeft=PROBE_REACH_MAX_LEFT_T_CN; - // machine_menu.ProbeMaxRigh=PROBE_REACH_MAX_RIGHT_T_CN; - // machine_menu.ProbeMaxfront=PROBE_REACH_MAX_FRONT_T_CN; - // machine_menu.ProbeMaxback=PROBE_REACH_MAX_BACK_T_CN; machine_menu.TemperatureConfTitle = TEMPERATURE_CONF_TITLE_T_CN; machine_menu.NozzleConf = NOZZLE_CONF_T_CN; @@ -400,7 +393,6 @@ void machine_setting_disp() { machine_menu.NozzleMaxTemperature = NOZZLE_MAX_TEMPERATURE_T_CN; machine_menu.Extrude_Min_Temper = EXTRUD_MIN_TEMPER_T_CN; - // machine_menu.HotbedEnable=HOTBED_ENABLE_T_CN; machine_menu.HotbedConfTitle = HOTBED_CONF_TITLE_T_CN; machine_menu.HotbedAjustType = HOTBED_ADJUST_T_CN; machine_menu.HotbedMinTemperature = HOTBED_MIN_TEMPERATURE_T_CN; @@ -475,7 +467,6 @@ void machine_setting_disp() { machine_menu.HomeFeedRateConfTitle = HOMEFEEDRATE_CONF_TITLE_T_CN; machine_menu.XY_HomeFeedRate = X_HOMESPEED_T_CN; - // machine_menu.Y_HomeFeedRate=Y_HOMESPEED_T_CN; machine_menu.Z_HomeFeedRate = Z_HOMESPEED_T_CN; machine_menu.AdvancedConfTitle = ADVANCED_CONF_TITLE_T_CN; @@ -499,8 +490,6 @@ void machine_setting_disp() { machine_menu.key_back = KEY_BACK_T_CN; machine_menu.key_reset = KEY_REST_T_CN; machine_menu.key_confirm = KEY_CONFIRM_T_CN; - // machine_menu.high_level = MOTOR_EN_HIGH_LEVEL_T_CN; - // machine_menu.low_level = MOTOR_EN_LOW_LEVEL_T_CN; machine_menu.PausePosText = PAUSE_POSITION_T_CN; machine_menu.xPos = PAUSE_POSITION_X_T_CN; @@ -590,7 +579,7 @@ void machine_setting_disp() { machine_menu.LevelingParaConfTitle = LEVELING_CONF_TITLE_EN; machine_menu.LevelingParaConf = LEVELING_PARA_CONF_EN; - machine_menu.LevelingManuPosConf = LEVELING_MANUAL_POS_EN; + machine_menu.TrammingPosConf = TRAMMING_POS_EN; machine_menu.LevelingAutoCommandConf = LEVELING_AUTO_COMMAND_EN; machine_menu.LevelingAutoZoffsetConf = LEVELING_AUTO_ZOFFSET_EN; @@ -605,6 +594,7 @@ void machine_setting_disp() { machine_menu.ProbeZspeed = PROBE_Z_SPEED_EN; machine_menu.enable = ENABLE_EN; machine_menu.disable = DISABLE_EN; + machine_menu.locked = LOCKED_EN; machine_menu.z_min = Z_MIN_EN; machine_menu.z_max = Z_MAX_EN; @@ -618,10 +608,6 @@ void machine_setting_disp() { machine_menu.CalibrationRadius = CALIBRATION_RADIUS_EN; machine_menu.LevelingSubXYZConfTitle = XYZ_LEVEL_CONF_TITLE_EN; - // machine_menu.Level_positon=PROBE_REACH_MAX_LEFT_EN; - // machine_menu.ProbeMaxRigh=PROBE_REACH_MAX_RIGHT_EN; - // machine_menu.ProbeMaxfront=PROBE_REACH_MAX_FRONT_EN; - // machine_menu.ProbeMaxback=PROBE_REACH_MAX_BACK_EN; machine_menu.TemperatureConfTitle = TEMPERATURE_CONF_TITLE_EN; machine_menu.NozzleConf = NOZZLE_CONF_EN; @@ -711,7 +697,6 @@ void machine_setting_disp() { machine_menu.HomeFeedRateConfTitle = HOMEFEEDRATE_CONF_TITLE_EN; machine_menu.XY_HomeFeedRate = X_HOMESPEED_EN; - // machine_menu.Y_HomeFeedRate=Y_HOMESPEED_EN; machine_menu.Z_HomeFeedRate = Z_HOMESPEED_EN; machine_menu.AdvancedConfTitle = ADVANCED_CONF_TITLE_EN; @@ -823,7 +808,6 @@ void disp_language_init() { about_menu.type_name = ABOUT_TYPE_TEXT; about_menu.firmware_v = ABOUT_VERSION_TEXT; - // about_menu.wifi = ABOUT_WIFI_TEXT; wifi_menu.ip = WIFI_IP_TEXT; wifi_menu.wifi = WIFI_NAME_TEXT; @@ -834,12 +818,16 @@ void disp_language_init() { wifi_menu.disconnected = WIFI_DISCONNECTED_TEXT; wifi_menu.exception = WIFI_EXCEPTION_TEXT; - printing_menu.temp1 = TEXT_VALUE; - printing_menu.temp2 = TEXT_VALUE; - printing_menu.bed_temp = TEXT_VALUE; + printing_menu.temp1 = TEXT_VALUE_TARGET; + printing_menu.temp2 = TEXT_VALUE_TARGET; + printing_menu.bed_temp = TEXT_VALUE_TARGET; filament_menu.stat_temp = TEXT_VALUE; + media_select_menu.title = MEDIA_SELECT_TITLE_EN; + media_select_menu.sd_disk = SD_CARD_TITLE_EN; + media_select_menu.usb_disk = USB_DRIVE_TITLE_EN; + machine_menu.key_0 = KEYBOARD_KEY0_EN; machine_menu.key_1 = KEYBOARD_KEY1_EN; machine_menu.key_2 = KEYBOARD_KEY2_EN; @@ -853,7 +841,7 @@ void disp_language_init() { machine_menu.key_point = KEYBOARD_KEY_POINT_EN; machine_menu.negative = KEYBOARD_KEY_NEGATIVE_EN; // wifi-list - #if ENABLED(USE_WIFI_FUNCTION) + #if ENABLED(MKS_WIFI_MODULE) list_menu.title = TEXT_WIFI_MENU_TITLE_EN; list_menu.file_pages = FILE_PAGES_EN; @@ -861,7 +849,7 @@ void disp_language_init() { tips_menu.joining = TEXT_WIFI_JOINING_EN; tips_menu.failedJoin = TEXT_WIFI_FAILED_JOIN_EN; tips_menu.wifiConected = TEXT_WIFI_WIFI_CONECTED_EN; - #endif //USE_WIFI_FUNCTION + #endif machine_setting_disp(); operation_menu.babystep = TEXT_BABY_STEP_EN; @@ -923,7 +911,7 @@ void disp_language_init() { file_menu.page_down = PAGE_DOWN_TEXT_CN; file_menu.file_loading = FILE_LOADING_CN; file_menu.no_file = NO_FILE_CN; - file_menu.no_file_and_check = NO_FILE_CN;// NO_FILE_AND_CHECK_CN; + file_menu.no_file_and_check = NO_FILE_CN; // extrude_menu.title = TITLE_EXTRUDE_CN; extrude_menu.in = EXTRUDER_IN_TEXT_CN; @@ -961,12 +949,29 @@ void disp_language_init() { filesys_menu.sd_sys = SD_CARD_TEXT_CN; filesys_menu.usb_sys = U_DISK_TEXT_CN; // - more_menu.title = TITLE_MORE_CN; + more_menu.title = TITLE_MORE_CN; + more_menu.gcode = MORE_GCODE_CN; + more_menu.entergcode = MORE_ENTER_GCODE_CN; + #if HAS_USER_ITEM(1) + more_menu.custom1 = MORE_CUSTOM1_TEXT_CN; + #endif + #if HAS_USER_ITEM(2) + more_menu.custom2 = MORE_CUSTOM2_TEXT_CN; + #endif + #if HAS_USER_ITEM(3) + more_menu.custom3 = MORE_CUSTOM3_TEXT_CN; + #endif + #if HAS_USER_ITEM(4) + more_menu.custom4 = MORE_CUSTOM4_TEXT_CN; + #endif + #if HAS_USER_ITEM(5) + more_menu.custom5 = MORE_CUSTOM5_TEXT_CN; + #endif + #if HAS_USER_ITEM(6) + more_menu.custom6 = MORE_CUSTOM6_TEXT_CN; + #endif // WIFI wifi_menu.title = WIFI_TEXT; - // wifi_menu.key = WIFI_KEY_TEXT_CN; - // wifi_menu.ip = WIFI_IP_TEXT_CN; - // wifi_menu.state = WIFI_STA_TEXT_CN; wifi_menu.cloud = CLOUD_TEXT_CN; wifi_menu.reconnect = WIFI_RECONNECT_TEXT_CN; // CLOUD @@ -976,6 +981,7 @@ void disp_language_init() { cloud_menu.unbind = CLOUD_UNBIND_CN; cloud_menu.unbinding = CLOUD_UNBINDED_CN; cloud_menu.disconnected = CLOUD_DISCONNECTED_CN; + cloud_menu.unbinded = CLOUD_UNBINDED_CN; cloud_menu.disable = CLOUD_DISABLE_CN; // about_menu.title = ABOUT_TEXT_CN; @@ -1004,7 +1010,6 @@ void disp_language_init() { filament_menu.filament_dialog_unloading = FILAMENT_DIALOG_UNLOADING_TIPS_CN; filament_menu.filament_dialog_unload_completed = FILAMENT_DIALOG_UNLOAD_COMPLETE_TIPS_CN; - // language_menu.title = TITLE_LANGUAGE_CN; language_menu.next = PAGE_DOWN_TEXT_CN; @@ -1055,11 +1060,10 @@ void disp_language_init() { printing_more_menu.speed = PRINTING_CHANGESPEED_CN; printing_more_menu.temp = PRINTING_TEMP_CN; - // print_file_dialog_menu.title = TITLE_DIALOG_CONFIRM_CN; print_file_dialog_menu.confirm = DIALOG_CONFIRM_CN; - print_file_dialog_menu.cancle = DIALOG_CANCLE_CN; + print_file_dialog_menu.cancel = DIALOG_CANCLE_CN; print_file_dialog_menu.print_file = DIALOG_PRINT_MODEL_CN; - print_file_dialog_menu.cancle_print = DIALOG_CANCEL_PRINT_CN; + print_file_dialog_menu.cancel_print = DIALOG_CANCEL_PRINT_CN; print_file_dialog_menu.retry = DIALOG_RETRY_CN; print_file_dialog_menu.stop = DIALOG_STOP_CN; print_file_dialog_menu.no_file_print_tips = DIALOG_ERROR_TIPS1_CN; @@ -1091,8 +1095,8 @@ void disp_language_init() { eeprom_menu.read = EEPROM_SETTINGS_READ_CN; eeprom_menu.revert = EEPROM_SETTINGS_REVERT_CN; eeprom_menu.storeTips = EEPROM_STORE_TIPS_CN; - eeprom_menu.readTips = EEPROM_READ_TIPS_CN; - eeprom_menu.revertTips = EEPROM_REVERT_TIPS_CN; + eeprom_menu.readTips = EEPROM_READ_TIPS_CN; + eeprom_menu.revertTips = EEPROM_REVERT_TIPS_CN; break; #if 1 @@ -1153,7 +1157,7 @@ void disp_language_init() { file_menu.page_down = PAGE_DOWN_TEXT_T_CN; file_menu.file_loading = FILE_LOADING_T_CN; file_menu.no_file = NO_FILE_T_CN; - file_menu.no_file_and_check = NO_FILE_T_CN;// NO_FILE_AND_CHECK_T_CN; + file_menu.no_file_and_check = NO_FILE_T_CN; // extrude_menu.title = TITLE_EXTRUDE_T_CN; extrude_menu.in = EXTRUDER_IN_TEXT_T_CN; @@ -1190,12 +1194,29 @@ void disp_language_init() { filesys_menu.sd_sys = SD_CARD_TEXT_T_CN; filesys_menu.usb_sys = U_DISK_TEXT_T_CN; // - more_menu.title = TITLE_MORE_T_CN; + more_menu.title = TITLE_MORE_T_CN; + more_menu.gcode = MORE_GCODE_T_CN; + more_menu.entergcode = MORE_ENTER_GCODE_T_CN; + #if HAS_USER_ITEM(1) + more_menu.custom1 = MORE_CUSTOM1_TEXT_CN; + #endif + #if HAS_USER_ITEM(2) + more_menu.custom2 = MORE_CUSTOM2_TEXT_CN; + #endif + #if HAS_USER_ITEM(3) + more_menu.custom3 = MORE_CUSTOM3_TEXT_CN; + #endif + #if HAS_USER_ITEM(4) + more_menu.custom4 = MORE_CUSTOM4_TEXT_CN; + #endif + #if HAS_USER_ITEM(5) + more_menu.custom5 = MORE_CUSTOM5_TEXT_CN; + #endif + #if HAS_USER_ITEM(6) + more_menu.custom6 = MORE_CUSTOM6_TEXT_CN; + #endif // WIFI - wifi_menu.title = WIFI_TEXT; - // wifi_menu.key = WIFI_KEY_TEXT_CN; - // wifi_menu.ip = WIFI_IP_TEXT_CN; - // wifi_menu.state= WIFI_STA_TEXT_CN; + wifi_menu.title = WIFI_TEXT; wifi_menu.cloud = CLOUD_TEXT_T_CN; wifi_menu.reconnect = WIFI_RECONNECT_TEXT_T_CN; // CLOUD @@ -1205,6 +1226,7 @@ void disp_language_init() { cloud_menu.unbind = CLOUD_UNBIND_T_CN; cloud_menu.unbinding = CLOUD_UNBINDED_T_CN; cloud_menu.disconnected = CLOUD_DISCONNECTED_T_CN; + cloud_menu.unbinded = CLOUD_UNBINDED_T_CN; cloud_menu.disable = CLOUD_DISABLE_T_CN; // about_menu.title = ABOUT_TEXT_T_CN; @@ -1233,7 +1255,6 @@ void disp_language_init() { filament_menu.filament_dialog_unloading = FILAMENT_DIALOG_UNLOADING_TIPS_T_CN; filament_menu.filament_dialog_unload_completed = FILAMENT_DIALOG_UNLOAD_COMPLETE_TIPS_T_CN; - // language_menu.title = TITLE_LANGUAGE_T_CN; language_menu.next = PAGE_DOWN_TEXT_T_CN; @@ -1284,11 +1305,10 @@ void disp_language_init() { printing_more_menu.speed = PRINTING_CHANGESPEED_T_CN; printing_more_menu.temp = PRINTING_TEMP_T_CN; - // print_file_dialog_menu.title = TITLE_DIALOG_CONFIRM_CN; print_file_dialog_menu.confirm = DIALOG_CONFIRM_T_CN; - print_file_dialog_menu.cancle = DIALOG_CANCLE_T_CN; + print_file_dialog_menu.cancel = DIALOG_CANCLE_T_CN; print_file_dialog_menu.print_file = DIALOG_PRINT_MODEL_T_CN; - print_file_dialog_menu.cancle_print = DIALOG_CANCEL_PRINT_T_CN; + print_file_dialog_menu.cancel_print = DIALOG_CANCEL_PRINT_T_CN; print_file_dialog_menu.retry = DIALOG_RETRY_T_CN; print_file_dialog_menu.stop = DIALOG_STOP_T_CN; print_file_dialog_menu.no_file_print_tips = DIALOG_ERROR_TIPS1_T_CN; @@ -1319,8 +1339,8 @@ void disp_language_init() { eeprom_menu.read = EEPROM_SETTINGS_READ_T_CN; eeprom_menu.revert = EEPROM_SETTINGS_REVERT_T_CN; eeprom_menu.storeTips = EEPROM_STORE_TIPS_T_CN; - eeprom_menu.readTips = EEPROM_READ_TIPS_T_CN; - eeprom_menu.revertTips = EEPROM_REVERT_TIPS_T_CN; + eeprom_menu.readTips = EEPROM_READ_TIPS_T_CN; + eeprom_menu.revertTips = EEPROM_REVERT_TIPS_T_CN; break; case LANG_ENGLISH: common_menu.dialog_confirm_title = TITLE_DIALOG_CONFIRM_EN; @@ -1363,7 +1383,7 @@ void disp_language_init() { preheat_menu.hotbed = HEATBED_TEXT_EN; preheat_menu.off = CLOSE_TEXT_EN; // - move_menu.title = TITLE_MOVE_EN; + move_menu.title = TITLE_MOVE_EN; // home_menu.title = TITLE_HOME_EN; home_menu.stopmove = HOME_STOPMOVE_EN; @@ -1373,7 +1393,7 @@ void disp_language_init() { file_menu.page_down = PAGE_DOWN_TEXT_EN; file_menu.file_loading = FILE_LOADING_EN; file_menu.no_file = NO_FILE_EN; - file_menu.no_file_and_check = NO_FILE_EN;// NO_FILE_AND_CHECK_EN; + file_menu.no_file_and_check = NO_FILE_EN; // extrude_menu.title = TITLE_EXTRUDE_EN; extrude_menu.in = EXTRUDER_IN_TEXT_EN; @@ -1405,16 +1425,35 @@ void disp_language_init() { set_menu.shutdown = SHUTDOWN_TEXT_EN; set_menu.machine_para = MACHINE_PARA_EN; set_menu.eepromSet = EEPROM_SETTINGS_EN; + // more_menu.title = TITLE_MORE_EN; + more_menu.gcode = MORE_GCODE_EN; + more_menu.entergcode = MORE_ENTER_GCODE_EN; + #if HAS_USER_ITEM(1) + more_menu.custom1 = MORE_CUSTOM1_TEXT_EN; + #endif + #if HAS_USER_ITEM(2) + more_menu.custom2 = MORE_CUSTOM2_TEXT_EN; + #endif + #if HAS_USER_ITEM(3) + more_menu.custom3 = MORE_CUSTOM3_TEXT_EN; + #endif + #if HAS_USER_ITEM(4) + more_menu.custom4 = MORE_CUSTOM4_TEXT_EN; + #endif + #if HAS_USER_ITEM(5) + more_menu.custom5 = MORE_CUSTOM5_TEXT_EN; + #endif + #if HAS_USER_ITEM(6) + more_menu.custom6 = MORE_CUSTOM6_TEXT_EN; + #endif + // filesys_menu.title = TITLE_FILESYS_EN; filesys_menu.sd_sys = SD_CARD_TEXT_EN; filesys_menu.usb_sys = U_DISK_TEXT_EN; // WIFI - wifi_menu.title = WIFI_TEXT; - // wifi_menu.key = WIFI_KEY_TEXT_EN; - // wifi_menu.ip = WIFI_IP_TEXT_EN; - // wifi_menu.state = WIFI_STA_TEXT_EN; + wifi_menu.title = WIFI_TEXT; wifi_menu.cloud = CLOUD_TEXT_EN; wifi_menu.reconnect = WIFI_RECONNECT_TEXT_EN; @@ -1424,6 +1463,7 @@ void disp_language_init() { cloud_menu.unbind = CLOUD_UNBIND_EN; cloud_menu.unbinding = CLOUD_UNBINDED_EN; cloud_menu.disconnected = CLOUD_DISCONNECTED_EN; + cloud_menu.unbinded = CLOUD_UNBINDED_EN; cloud_menu.disable = CLOUD_DISABLE_EN; // about_menu.title = TITLE_ABOUT_EN; @@ -1500,11 +1540,10 @@ void disp_language_init() { printing_more_menu.speed = PRINTING_CHANGESPEED_EN; printing_more_menu.temp = PRINTING_TEMP_EN; - // print_file_dialog_menu.title = TITLE_DIALOG_CONFIRM_EN; print_file_dialog_menu.confirm = DIALOG_CONFIRM_EN; - print_file_dialog_menu.cancle = DIALOG_CANCLE_EN; + print_file_dialog_menu.cancel = DIALOG_CANCLE_EN; print_file_dialog_menu.print_file = DIALOG_PRINT_MODEL_EN; - print_file_dialog_menu.cancle_print = DIALOG_CANCEL_PRINT_EN; + print_file_dialog_menu.cancel_print = DIALOG_CANCEL_PRINT_EN; print_file_dialog_menu.retry = DIALOG_RETRY_EN; print_file_dialog_menu.stop = DIALOG_STOP_EN; print_file_dialog_menu.no_file_print_tips = DIALOG_ERROR_TIPS1_EN; @@ -1534,8 +1573,8 @@ void disp_language_init() { eeprom_menu.read = EEPROM_SETTINGS_READ_EN; eeprom_menu.revert = EEPROM_SETTINGS_REVERT_EN; eeprom_menu.storeTips = EEPROM_STORE_TIPS_EN; - eeprom_menu.readTips = EEPROM_READ_TIPS_EN; - eeprom_menu.revertTips = EEPROM_REVERT_TIPS_EN; + eeprom_menu.readTips = EEPROM_READ_TIPS_EN; + eeprom_menu.revertTips = EEPROM_REVERT_TIPS_EN; break; case LANG_RUSSIAN: common_menu.dialog_confirm_title = TITLE_DIALOG_CONFIRM_RU; @@ -1578,7 +1617,7 @@ void disp_language_init() { preheat_menu.hotbed = HEATBED_TEXT_RU; preheat_menu.off = CLOSE_TEXT_RU; // - move_menu.title = MOVE_TEXT_RU; + move_menu.title = MOVE_TEXT_RU; // home_menu.title = TITLE_HOME_RU; home_menu.stopmove = HOME_STOPMOVE_RU; @@ -1588,7 +1627,7 @@ void disp_language_init() { file_menu.page_down = PAGE_DOWN_TEXT_RU; file_menu.file_loading = FILE_LOADING_RU; file_menu.no_file = NO_FILE_RU; - file_menu.no_file_and_check = NO_FILE_RU;// NO_FILE_AND_CHECK_RU; + file_menu.no_file_and_check = NO_FILE_RU; // extrude_menu.title = TITLE_EXTRUDE_RU; extrude_menu.in = EXTRUDER_IN_TEXT_RU; @@ -1621,18 +1660,128 @@ void disp_language_init() { set_menu.machine_para = MACHINE_PARA_RU; set_menu.eepromSet = EEPROM_SETTINGS_RU; more_menu.title = TITLE_MORE_RU; + more_menu.gcode = MORE_GCODE_RU; + more_menu.entergcode = MORE_ENTER_GCODE_RU; + #if HAS_USER_ITEM(1) + more_menu.custom1 = MORE_CUSTOM1_TEXT_RU; + #endif + #if HAS_USER_ITEM(2) + more_menu.custom2 = MORE_CUSTOM2_TEXT_RU; + #endif + #if HAS_USER_ITEM(3) + more_menu.custom3 = MORE_CUSTOM3_TEXT_RU; + #endif + #if HAS_USER_ITEM(4) + more_menu.custom4 = MORE_CUSTOM4_TEXT_RU; + #endif + #if HAS_USER_ITEM(5) + more_menu.custom5 = MORE_CUSTOM5_TEXT_RU; + #endif + #if HAS_USER_ITEM(6) + more_menu.custom6 = MORE_CUSTOM6_TEXT_RU; + #endif // filesys_menu.title = TITLE_FILESYS_RU; filesys_menu.sd_sys = SD_CARD_TEXT_RU; filesys_menu.usb_sys = U_DISK_TEXT_RU; // WIFI - wifi_menu.title = WIFI_TEXT; - // wifi_menu.key = WIFI_KEY_TEXT_RU; - // wifi_menu.ip = WIFI_IP_TEXT_RU; - // wifi_menu.state = WIFI_STA_TEXT_RU; + wifi_menu.title = WIFI_TEXT; wifi_menu.cloud = CLOUD_TEXT_RU; wifi_menu.reconnect = WIFI_RECONNECT_TEXT_RU; + machine_menu.next = NEXT_RU; + machine_menu.previous = PREVIOUS_RU; + machine_menu.enable = ENABLE_RU; + machine_menu.disable = DISABLE_RU; + machine_menu.key_confirm = KEY_CONFIRM_RU; + + MachinePara_menu.MachineSetting = MACHINE_TYPE_CNOFIG_RU; + MachinePara_menu.title = MACHINE_PARA_TITLE_RU; + machine_menu.MachineConfigTitle = MACHINE_CONFIG_TITLE_RU; + MachinePara_menu.MotorSetting = MOTOR_CONFIG_RU; + MachinePara_menu.leveling = MACHINE_LEVELING_CONFIG_RU; + MachinePara_menu.AdvanceSetting = ADVANCE_CONFIG_RU; + machine_menu.MotorConfTitle = MOTOR_CONF_TITLE_RU; + machine_menu.MaxFeedRateConf = MAXFEEDRATE_CONF_RU; + machine_menu.AccelerationConf = ACCELERATION_CONF_RU; + machine_menu.JerkConf = JERKCONF_RU; + machine_menu.StepsConf = STEPSCONF_RU; + machine_menu.TMCcurrentConf = TMC_CURRENT_RU; + machine_menu.TMCStepModeConf = TMC_STEP_MODE_RU; + machine_menu.PausePosition = PAUSE_POSITION_RU; + machine_menu.FilamentConf = MACHINE_FILAMENT_CONFIG_RU; + machine_menu.EncoderSettings = ENCODER_SETTINGS_RU; + machine_menu.AdvancedConfTitle = ADVANCED_CONF_TITLE_RU; + + machine_menu.LevelingParaConfTitle = LEVELING_CONF_TITLE_RU; + machine_menu.LevelingParaConf = LEVELING_PARA_CONF_RU; + machine_menu.TrammingPosConf = TRAMMING_POS_RU; + machine_menu.LevelingAutoCommandConf = LEVELING_AUTO_COMMAND_RU; + machine_menu.LevelingAutoZoffsetConf = LEVELING_AUTO_ZOFFSET_RU; + + machine_menu.AccelerationConfTitle = ACCELERATION_CONF_TITLE_RU; + machine_menu.PrintAcceleration = PRINT_ACCELERATION_RU; + machine_menu.RetractAcceleration = RETRACT_ACCELERATION_RU; + machine_menu.TravelAcceleration = TRAVEL_ACCELERATION_RU; + machine_menu.X_Acceleration = X_ACCELERATION_RU; + machine_menu.Y_Acceleration = Y_ACCELERATION_RU; + machine_menu.Z_Acceleration = Z_ACCELERATION_RU; + machine_menu.E0_Acceleration = E0_ACCELERATION_RU; + machine_menu.E1_Acceleration = E1_ACCELERATION_RU; + + machine_menu.MaxFeedRateConfTitle = MAXFEEDRATE_CONF_TITLE_RU; + machine_menu.XMaxFeedRate = X_MAXFEEDRATE_RU; + machine_menu.YMaxFeedRate = Y_MAXFEEDRATE_RU; + machine_menu.ZMaxFeedRate = Z_MAXFEEDRATE_RU; + machine_menu.E0MaxFeedRate = E0_MAXFEEDRATE_RU; + machine_menu.E1MaxFeedRate = E1_MAXFEEDRATE_RU; + + machine_menu.JerkConfTitle = JERK_CONF_TITLE_RU; + machine_menu.X_Jerk = X_JERK_RU; + machine_menu.Y_Jerk = Y_JERK_RU; + machine_menu.Z_Jerk = Z_JERK_RU; + machine_menu.E_Jerk = E_JERK_RU; + + machine_menu.StepsConfTitle = STEPS_CONF_TITLE_RU; + machine_menu.X_Steps = X_STEPS_RU; + machine_menu.Y_Steps = Y_STEPS_RU; + machine_menu.Z_Steps = Z_STEPS_RU; + machine_menu.E0_Steps = E0_STEPS_RU; + machine_menu.E1_Steps = E1_STEPS_RU; + + machine_menu.TmcCurrentConfTitle = TMC_CURRENT_CONF_TITLE_RU; + machine_menu.X_Current = X_TMC_CURRENT_RU; + machine_menu.Y_Current = Y_TMC_CURRENT_RU; + machine_menu.Z_Current = Z_TMC_CURRENT_RU; + machine_menu.E0_Current = E0_TMC_CURRENT_RU; + machine_menu.E1_Current = E1_TMC_CURRENT_RU; + + machine_menu.TmcStepModeConfTitle = TMC_MODE_CONF_TITLE_RU; + machine_menu.X_StepMode = X_TMC_MODE_RU; + machine_menu.Y_StepMode = Y_TMC_MODE_RU; + machine_menu.Z_StepMode = Z_TMC_MODE_RU; + machine_menu.E0_StepMode = E0_TMC_MODE_RU; + machine_menu.E1_StepMode = E1_TMC_MODE_RU; + + machine_menu.PausePosText = PAUSE_POSITION_RU; + machine_menu.xPos = PAUSE_POSITION_X_RU; + machine_menu.yPos = PAUSE_POSITION_Y_RU; + machine_menu.zPos = PAUSE_POSITION_Z_RU; + + machine_menu.OffsetConfTitle = OFFSET_TITLE_RU; + machine_menu.Xoffset = OFFSET_X_RU; + machine_menu.Yoffset = OFFSET_Y_RU; + machine_menu.Zoffset = OFFSET_Z_RU; + + machine_menu.FilamentConfTitle = FILAMENT_CONF_TITLE_RU; + machine_menu.InLength = FILAMENT_IN_LENGTH_RU; + machine_menu.InSpeed = FILAMENT_IN_SPEED_RU; + machine_menu.FilamentTemperature = FILAMENT_TEMPERATURE_RU; + machine_menu.OutLength = FILAMENT_OUT_LENGTH_RU; + machine_menu.OutSpeed = FILAMENT_OUT_SPEED_RU; + + machine_menu.EncoderConfTitle = ENCODER_CONF_TITLE_RU; + machine_menu.EncoderConfText = ENCODER_CONF_TEXT_RU; cloud_menu.title = TITLE_CLOUD_TEXT_RU; cloud_menu.bind = CLOUD_BINDED_RU; @@ -1640,6 +1789,7 @@ void disp_language_init() { cloud_menu.unbind = CLOUD_UNBIND_RU; cloud_menu.unbinding = CLOUD_UNBINDED_RU; cloud_menu.disconnected = CLOUD_DISCONNECTED_RU; + cloud_menu.unbinded = CLOUD_UNBINDED_RU; cloud_menu.disable = CLOUD_DISABLE_RU; // about_menu.title = ABOUT_TEXT_RU; @@ -1715,11 +1865,10 @@ void disp_language_init() { printing_more_menu.manual = MANUAL_SHUTDOWN_RU; printing_more_menu.speed = PRINTING_CHANGESPEED_RU; printing_more_menu.temp = PRINTING_TEMP_RU; - // print_file_dialog_menu.title = TITLE_DIALOG_CONFIRM_RU; print_file_dialog_menu.confirm = DIALOG_CONFIRM_RU; - print_file_dialog_menu.cancle = DIALOG_CANCLE_RU; + print_file_dialog_menu.cancel = DIALOG_CANCLE_RU; print_file_dialog_menu.print_file = DIALOG_PRINT_MODEL_RU; - print_file_dialog_menu.cancle_print = DIALOG_CANCEL_PRINT_RU; + print_file_dialog_menu.cancel_print = DIALOG_CANCEL_PRINT_RU; print_file_dialog_menu.retry = DIALOG_RETRY_RU; print_file_dialog_menu.stop = DIALOG_STOP_RU; print_file_dialog_menu.no_file_print_tips = DIALOG_ERROR_TIPS1_RU; @@ -1749,8 +1898,8 @@ void disp_language_init() { eeprom_menu.read = EEPROM_SETTINGS_READ_RU; eeprom_menu.revert = EEPROM_SETTINGS_REVERT_RU; eeprom_menu.storeTips = EEPROM_STORE_TIPS_RU; - eeprom_menu.readTips = EEPROM_READ_TIPS_RU; - eeprom_menu.revertTips = EEPROM_REVERT_TIPS_RU; + eeprom_menu.readTips = EEPROM_READ_TIPS_RU; + eeprom_menu.revertTips = EEPROM_REVERT_TIPS_RU; break; case LANG_SPANISH: common_menu.dialog_confirm_title = TITLE_DIALOG_CONFIRM_SP; @@ -1807,7 +1956,7 @@ void disp_language_init() { file_menu.page_down = PAGE_DOWN_TEXT_SP; file_menu.file_loading = FILE_LOADING_SP; file_menu.no_file = NO_FILE_SP; - file_menu.no_file_and_check = NO_FILE_SP;// NO_FILE_AND_CHECK_SP; + file_menu.no_file_and_check = NO_FILE_SP; // extrude_menu.title = TITLE_EXTRUDE_SP; extrude_menu.in = EXTRUDER_IN_TEXT_SP; @@ -1840,16 +1989,33 @@ void disp_language_init() { set_menu.machine_para = MACHINE_PARA_SP; set_menu.eepromSet = EEPROM_SETTINGS_SP; more_menu.title = TITLE_MORE_SP; + more_menu.gcode = MORE_GCODE_SP; + more_menu.entergcode = MORE_ENTER_GCODE_SP; + #if HAS_USER_ITEM(1) + more_menu.custom1 = MORE_CUSTOM1_TEXT_SP; + #endif + #if HAS_USER_ITEM(2) + more_menu.custom2 = MORE_CUSTOM2_TEXT_SP; + #endif + #if HAS_USER_ITEM(3) + more_menu.custom3 = MORE_CUSTOM3_TEXT_SP; + #endif + #if HAS_USER_ITEM(4) + more_menu.custom4 = MORE_CUSTOM4_TEXT_SP; + #endif + #if HAS_USER_ITEM(5) + more_menu.custom5 = MORE_CUSTOM5_TEXT_SP; + #endif + #if HAS_USER_ITEM(6) + more_menu.custom6 = MORE_CUSTOM6_TEXT_SP; + #endif // filesys_menu.title = TITLE_FILESYS_SP; filesys_menu.sd_sys = SD_CARD_TEXT_SP; filesys_menu.usb_sys = U_DISK_TEXT_SP; // WIFI - wifi_menu.title = WIFI_TEXT; - // wifi_menu.key = WIFI_KEY_TEXT_SP; - // wifi_menu.ip = WIFI_IP_TEXT_SP; - // wifi_menu.state = WIFI_STA_TEXT_SP; + wifi_menu.title = WIFI_TEXT; wifi_menu.cloud = CLOUD_TEXT_SP; wifi_menu.reconnect = WIFI_RECONNECT_TEXT_SP; @@ -1859,6 +2025,7 @@ void disp_language_init() { cloud_menu.unbind = CLOUD_UNBIND_SP; cloud_menu.unbinding = CLOUD_UNBINDED_SP; cloud_menu.disconnected = CLOUD_DISCONNECTED_SP; + cloud_menu.unbinded = CLOUD_UNBINDED_SP; cloud_menu.disable = CLOUD_DISABLE_SP; // about_menu.title = ABOUT_TEXT_SP; @@ -1935,11 +2102,10 @@ void disp_language_init() { printing_more_menu.speed = PRINTING_CHANGESPEED_SP; printing_more_menu.temp = PRINTING_TEMP_SP; - // print_file_dialog_menu.title = TITLE_DIALOG_CONFIRM_SP; print_file_dialog_menu.confirm = DIALOG_CONFIRM_SP; - print_file_dialog_menu.cancle = DIALOG_CANCLE_SP; + print_file_dialog_menu.cancel = DIALOG_CANCLE_SP; print_file_dialog_menu.print_file = DIALOG_PRINT_MODEL_SP; - print_file_dialog_menu.cancle_print = DIALOG_CANCEL_PRINT_SP; + print_file_dialog_menu.cancel_print = DIALOG_CANCEL_PRINT_SP; print_file_dialog_menu.retry = DIALOG_RETRY_SP; print_file_dialog_menu.stop = DIALOG_STOP_SP; print_file_dialog_menu.no_file_print_tips = DIALOG_ERROR_TIPS1_SP; @@ -1969,8 +2135,8 @@ void disp_language_init() { eeprom_menu.read = EEPROM_SETTINGS_READ_SP; eeprom_menu.revert = EEPROM_SETTINGS_REVERT_SP; eeprom_menu.storeTips = EEPROM_STORE_TIPS_SP; - eeprom_menu.readTips = EEPROM_READ_TIPS_SP; - eeprom_menu.revertTips = EEPROM_REVERT_TIPS_SP; + eeprom_menu.readTips = EEPROM_READ_TIPS_SP; + eeprom_menu.revertTips = EEPROM_REVERT_TIPS_SP; break; #endif // if 1 @@ -2057,19 +2223,35 @@ void disp_language_init() { set_menu.machine_para = MACHINE_PARA_FR; set_menu.eepromSet = EEPROM_SETTINGS_FR; more_menu.title = TITLE_MORE_FR; + more_menu.gcode = MORE_GCODE_FR; + more_menu.entergcode = MORE_ENTER_GCODE_FR; + #if HAS_USER_ITEM(1) + more_menu.custom1 = MORE_CUSTOM1_TEXT_FR; + #endif + #if HAS_USER_ITEM(2) + more_menu.custom2 = MORE_CUSTOM2_TEXT_FR; + #endif + #if HAS_USER_ITEM(3) + more_menu.custom3 = MORE_CUSTOM3_TEXT_FR; + #endif + #if HAS_USER_ITEM(4) + more_menu.custom4 = MORE_CUSTOM4_TEXT_FR; + #endif + #if HAS_USER_ITEM(5) + more_menu.custom5 = MORE_CUSTOM5_TEXT_FR; + #endif + #if HAS_USER_ITEM(6) + more_menu.custom6 = MORE_CUSTOM6_TEXT_FR; + #endif // filesys_menu.title = TITLE_FILESYS_FR; filesys_menu.sd_sys = SD_CARD_TEXT_FR; filesys_menu.usb_sys = U_DISK_TEXT_FR; file_menu.file_loading = FILE_LOADING_FR; file_menu.no_file = NO_FILE_FR; - file_menu.no_file_and_check = NO_FILE_FR;// NO_FILE_AND_CHECK_FR; + file_menu.no_file_and_check = NO_FILE_FR; // WIFI - wifi_menu.title = WIFI_NAME_TEXT_FR; - // wifi_menu.key = WIFI_KEY_TEXT_FR; - // wifi_menu.ip = WIFI_IP_TEXT_FR; - // wifi_menu.state = WIFI_STA_TEXT_FR; - // wifi_menu.cloud = CLOSE_TEXT_FR; + wifi_menu.title = WIFI_NAME_TEXT_FR; wifi_menu.cloud = CLOUD_TEXT_FR; wifi_menu.reconnect = WIFI_RECONNECT_TEXT_FR; @@ -2079,6 +2261,7 @@ void disp_language_init() { cloud_menu.unbind = CLOUD_UNBIND_FR; cloud_menu.unbinding = CLOUD_UNBINDED_FR; cloud_menu.disconnected = CLOUD_DISCONNECTED_FR; + cloud_menu.unbinded = CLOUD_UNBINDED_FR; cloud_menu.disable = CLOUD_DISABLE_FR; // about_menu.title = ABOUT_TEXT_FR; @@ -2153,11 +2336,10 @@ void disp_language_init() { printing_more_menu.speed = PRINTING_CHANGESPEED_FR; printing_more_menu.temp = PRINTING_TEMP_FR; - // print_file_dialog_menu.title = TITLE_DIALOG_CONFIRM_SP; print_file_dialog_menu.confirm = DIALOG_CONFIRM_FR; - print_file_dialog_menu.cancle = DIALOG_CANCLE_FR; + print_file_dialog_menu.cancel = DIALOG_CANCLE_FR; print_file_dialog_menu.print_file = DIALOG_PRINT_MODEL_FR; - print_file_dialog_menu.cancle_print = DIALOG_CANCEL_PRINT_FR; + print_file_dialog_menu.cancel_print = DIALOG_CANCEL_PRINT_FR; print_file_dialog_menu.retry = DIALOG_RETRY_FR; print_file_dialog_menu.stop = DIALOG_STOP_FR; print_file_dialog_menu.no_file_print_tips = DIALOG_ERROR_TIPS1_FR; @@ -2187,8 +2369,8 @@ void disp_language_init() { eeprom_menu.read = EEPROM_SETTINGS_READ_FR; eeprom_menu.revert = EEPROM_SETTINGS_REVERT_FR; eeprom_menu.storeTips = EEPROM_STORE_TIPS_FR; - eeprom_menu.readTips = EEPROM_READ_TIPS_FR; - eeprom_menu.revertTips = EEPROM_REVERT_TIPS_FR; + eeprom_menu.readTips = EEPROM_READ_TIPS_FR; + eeprom_menu.revertTips = EEPROM_REVERT_TIPS_FR; break; case LANG_ITALY: @@ -2243,7 +2425,7 @@ void disp_language_init() { file_menu.page_down = PAGE_DOWN_TEXT_IT; file_menu.file_loading = FILE_LOADING_IT; file_menu.no_file = NO_FILE_IT; - file_menu.no_file_and_check = NO_FILE_IT;// NO_FILE_AND_CHECK_IT; + file_menu.no_file_and_check = NO_FILE_IT; // extrude_menu.title = TITLE_EXTRUDE_IT; extrude_menu.in = EXTRUDER_IN_TEXT_IT; @@ -2276,16 +2458,33 @@ void disp_language_init() { set_menu.machine_para = MACHINE_PARA_IT; set_menu.eepromSet = EEPROM_SETTINGS_IT; more_menu.title = TITLE_MORE_IT; + more_menu.gcode = MORE_GCODE_IT; + more_menu.entergcode = MORE_ENTER_GCODE_IT; + #if HAS_USER_ITEM(1) + more_menu.custom1 = MORE_CUSTOM1_TEXT_IT; + #endif + #if HAS_USER_ITEM(2) + more_menu.custom2 = MORE_CUSTOM2_TEXT_IT; + #endif + #if HAS_USER_ITEM(3) + more_menu.custom3 = MORE_CUSTOM3_TEXT_IT; + #endif + #if HAS_USER_ITEM(4) + more_menu.custom4 = MORE_CUSTOM4_TEXT_IT; + #endif + #if HAS_USER_ITEM(5) + more_menu.custom5 = MORE_CUSTOM5_TEXT_IT; + #endif + #if HAS_USER_ITEM(6) + more_menu.custom6 = MORE_CUSTOM6_TEXT_IT; + #endif // filesys_menu.title = TITLE_FILESYS_IT; filesys_menu.sd_sys = SD_CARD_TEXT_IT; filesys_menu.usb_sys = U_DISK_TEXT_IT; // WIFI - wifi_menu.title = WIFI_NAME_TEXT_IT; - // wifi_menu.key = WIFI_KEY_TEXT_IT; - // wifi_menu.ip = WIFI_IP_TEXT_IT; - // wifi_menu.state = WIFI_STA_TEXT_IT; + wifi_menu.title = WIFI_NAME_TEXT_IT; wifi_menu.cloud = CLOSE_TEXT_IT; wifi_menu.reconnect = WIFI_RECONNECT_TEXT_IT; @@ -2295,6 +2494,7 @@ void disp_language_init() { cloud_menu.unbind = CLOUD_UNBIND_IT; cloud_menu.unbinding = CLOUD_UNBINDED_IT; cloud_menu.disconnected = CLOUD_DISCONNECTED_IT; + cloud_menu.unbinded = CLOUD_UNBINDED_IT; cloud_menu.disable = CLOUD_DISABLE_IT; // about_menu.title = ABOUT_TEXT_IT; @@ -2369,11 +2569,10 @@ void disp_language_init() { printing_more_menu.temp = PRINTING_TEMP_IT; printing_more_menu.speed = PRINTING_CHANGESPEED_IT; - // print_file_dialog_menu.title = TITLE_DIALOG_CONFIRM_SP; print_file_dialog_menu.confirm = DIALOG_CONFIRM_IT; - print_file_dialog_menu.cancle = DIALOG_CANCLE_IT; + print_file_dialog_menu.cancel = DIALOG_CANCLE_IT; print_file_dialog_menu.print_file = DIALOG_PRINT_MODEL_IT; - print_file_dialog_menu.cancle_print = DIALOG_CANCEL_PRINT_IT; + print_file_dialog_menu.cancel_print = DIALOG_CANCEL_PRINT_IT; print_file_dialog_menu.retry = DIALOG_RETRY_IT; print_file_dialog_menu.stop = DIALOG_STOP_IT; print_file_dialog_menu.no_file_print_tips = DIALOG_ERROR_TIPS1_IT; @@ -2403,8 +2602,8 @@ void disp_language_init() { eeprom_menu.read = EEPROM_SETTINGS_READ_IT; eeprom_menu.revert = EEPROM_SETTINGS_REVERT_IT; eeprom_menu.storeTips = EEPROM_STORE_TIPS_IT; - eeprom_menu.readTips = EEPROM_READ_TIPS_IT; - eeprom_menu.revertTips = EEPROM_REVERT_TIPS_IT; + eeprom_menu.readTips = EEPROM_READ_TIPS_IT; + eeprom_menu.revertTips = EEPROM_REVERT_TIPS_IT; break; #endif // if 1 @@ -2460,7 +2659,7 @@ void disp_language_init() { file_menu.page_down = PAGE_DOWN_TEXT_EN; file_menu.file_loading = FILE_LOADING_EN; file_menu.no_file = NO_FILE_EN; - file_menu.no_file_and_check = NO_FILE_EN;// NO_FILE_AND_CHECK_EN; + file_menu.no_file_and_check = NO_FILE_EN; // extrude_menu.title = TITLE_EXTRUDE_EN; extrude_menu.in = EXTRUDER_IN_TEXT_EN; @@ -2493,16 +2692,33 @@ void disp_language_init() { set_menu.machine_para = MACHINE_PARA_EN; set_menu.eepromSet = EEPROM_SETTINGS_EN; // - more_menu.title = TITLE_MORE_EN; + more_menu.title = TITLE_MORE_EN; + more_menu.gcode = MORE_GCODE_EN; + more_menu.entergcode = MORE_ENTER_GCODE_EN; + #if HAS_USER_ITEM(1) + more_menu.custom1 = MORE_CUSTOM1_TEXT_EN; + #endif + #if HAS_USER_ITEM(2) + more_menu.custom2 = MORE_CUSTOM2_TEXT_EN; + #endif + #if HAS_USER_ITEM(3) + more_menu.custom3 = MORE_CUSTOM3_TEXT_EN; + #endif + #if HAS_USER_ITEM(4) + more_menu.custom4 = MORE_CUSTOM4_TEXT_EN; + #endif + #if HAS_USER_ITEM(5) + more_menu.custom5 = MORE_CUSTOM5_TEXT_EN; + #endif + #if HAS_USER_ITEM(6) + more_menu.custom6 = MORE_CUSTOM6_TEXT_EN; + #endif // filesys_menu.title = TITLE_FILESYS_EN; filesys_menu.sd_sys = SD_CARD_TEXT_EN; filesys_menu.usb_sys = U_DISK_TEXT_EN; // WIFI - wifi_menu.title = WIFI_TEXT; - // wifi_menu.key = WIFI_KEY_TEXT_EN; - // wifi_menu.ip = WIFI_IP_TEXT_EN; - // wifi_menu.state = WIFI_STA_TEXT_EN; + wifi_menu.title = WIFI_TEXT; wifi_menu.cloud = CLOUD_TEXT_EN; wifi_menu.reconnect = WIFI_RECONNECT_TEXT_EN; @@ -2512,6 +2728,7 @@ void disp_language_init() { cloud_menu.unbind = CLOUD_UNBIND_EN; cloud_menu.unbinding = CLOUD_UNBINDED_EN; cloud_menu.disconnected = CLOUD_DISCONNECTED_EN; + cloud_menu.unbinded = CLOUD_UNBINDED_EN; cloud_menu.disable = CLOUD_DISABLE_EN; // about_menu.title = TITLE_ABOUT_EN; @@ -2588,11 +2805,10 @@ void disp_language_init() { printing_more_menu.speed = PRINTING_CHANGESPEED_EN; printing_more_menu.temp = PRINTING_TEMP_EN; - // print_file_dialog_menu.title = TITLE_DIALOG_CONFIRM_EN; print_file_dialog_menu.confirm = DIALOG_CONFIRM_EN; - print_file_dialog_menu.cancle = DIALOG_CANCLE_EN; + print_file_dialog_menu.cancel = DIALOG_CANCLE_EN; print_file_dialog_menu.print_file = DIALOG_PRINT_MODEL_EN; - print_file_dialog_menu.cancle_print = DIALOG_CANCEL_PRINT_EN; + print_file_dialog_menu.cancel_print = DIALOG_CANCEL_PRINT_EN; print_file_dialog_menu.retry = DIALOG_RETRY_EN; print_file_dialog_menu.stop = DIALOG_STOP_EN; print_file_dialog_menu.no_file_print_tips = DIALOG_ERROR_TIPS1_EN; @@ -2622,8 +2838,8 @@ void disp_language_init() { eeprom_menu.read = EEPROM_SETTINGS_READ_EN; eeprom_menu.revert = EEPROM_SETTINGS_REVERT_EN; eeprom_menu.storeTips = EEPROM_STORE_TIPS_EN; - eeprom_menu.readTips = EEPROM_READ_TIPS_EN; - eeprom_menu.revertTips = EEPROM_REVERT_TIPS_EN; + eeprom_menu.readTips = EEPROM_READ_TIPS_EN; + eeprom_menu.revertTips = EEPROM_REVERT_TIPS_EN; break; } } diff --git a/Marlin/src/lcd/extui/lib/mks_ui/tft_multi_language.h b/Marlin/src/lcd/extui/mks_ui/tft_multi_language.h similarity index 94% rename from Marlin/src/lcd/extui/lib/mks_ui/tft_multi_language.h rename to Marlin/src/lcd/extui/mks_ui/tft_multi_language.h index 675fd41f168e..79faad74e208 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/tft_multi_language.h +++ b/Marlin/src/lcd/extui/mks_ui/tft_multi_language.h @@ -29,7 +29,7 @@ #include "tft_Language_sp.h" #include "tft_Language_it.h" -extern void disp_language_init(); +void disp_language_init(); #define LANG_SIMPLE_CHINESE 1 #define LANG_COMPLEX_CHINESE 2 @@ -103,7 +103,7 @@ typedef struct machine_common_disp{ const char *LevelingParaConfTitle; const char *LevelingParaConf; - const char *LevelingManuPosConf; + const char *TrammingPosConf; const char *LevelingAutoCommandConf; const char *LevelingAutoZoffsetConf; @@ -118,6 +118,7 @@ typedef struct machine_common_disp{ const char *ProbeZspeed; const char *enable; const char *disable; + const char *locked; const char *z_min; const char *z_max; @@ -131,10 +132,6 @@ typedef struct machine_common_disp{ const char *CalibrationRadius; const char *LevelingSubXYZConfTitle; - //const char *Level_positon1; - //const char *Level_positon2; - //const char *Level_positon3; - //const char *Level_positon4; const char *TemperatureConfTitle; const char *NozzleConf; @@ -460,6 +457,15 @@ extern filesys_menu_def filesys_menu; typedef struct more_menu_disp { const char *title; + const char *custom1; + const char *custom2; + const char *custom3; + const char *custom4; + const char *custom5; + const char *custom6; + const char *custom7; + const char *gcode; + const char *entergcode; const char *back; } more_menu_def; @@ -667,9 +673,9 @@ extern dialog_menu_def dialog_menu; typedef struct print_file_dialog_disp { const char *title; const char *confirm; - const char *cancle; + const char *cancel; const char *print_file; - const char *cancle_print; + const char *cancel_print; const char *retry; const char *stop; const char *no_file_print_tips; @@ -700,6 +706,14 @@ typedef struct tool_menu_disp { extern tool_menu_def tool_menu; +typedef struct media_select_menu_disp { + const char *title; + const char *sd_disk; + const char *usb_disk; +} media_select_menu_def; + +extern media_select_menu_def media_select_menu; + typedef struct MachinePara_menu_disp { const char *title; const char *MachineSetting; @@ -740,12 +754,9 @@ typedef struct eeprom_disp{ extern eeprom_def eeprom_menu; /*****************************************/ -//********************************************// -//#if defined(TFT70) // -//#elif defined(TFT35) #define TEXT_VALUE "%d/%d" -//#endif +#define TEXT_VALUE_TARGET "%d -> %d" #define TEXT_VALUE_T ": %d℃" #define TEXT_VALUE_mm ": %dmm" @@ -765,15 +776,15 @@ extern eeprom_def eeprom_menu; #define AXIS_Y_DEC_TEXT "Y-" #define AXIS_Z_ADD_TEXT "Z+" #define AXIS_Z_DEC_TEXT "Z-" -#define TEXT_001MM "0.01mm" -#define TEXT_005MM "0.05mm" -#define TEXT_01MM "0.1mm" -#define TEXT_1MM "1mm" -#define TEXT_10MM "10mm" +#define TEXT_001MM "0.01 mm" +#define TEXT_005MM "0.05 mm" +#define TEXT_01MM "0.1 mm" +#define TEXT_1MM "1 mm" +#define TEXT_10MM "10 mm" -#define EXTRUDE_1MM_TEXT "1mm" -#define EXTRUDE_5MM_TEXT "5mm" -#define EXTRUDE_10MM_TEXT "10mm" +#define EXTRUDE_1MM_TEXT "1 mm" +#define EXTRUDE_5MM_TEXT "5 mm" +#define EXTRUDE_10MM_TEXT "10 mm" #define STEP_1PERCENT "1%" #define STEP_5PERCENT "5%" @@ -796,19 +807,14 @@ extern eeprom_def eeprom_menu; #define HOME_Y_TEXT "Y" #define HOME_Z_TEXT "Z" #define HOME_ALL_TEXT "All" -//#if defined(MKS_ROBIN_NANO) + #define ABOUT_TYPE_TEXT "MKS Robin Pro" -//#elif defined(MKS_ROBIN_MINI) -//#define ABOUT_TYPE_TEXT "MKS Robin Mini" -//#endif + #define ABOUT_VERSION_TEXT "1.0.0" -//#define ABOUT_WIFI_TEXT "WiFi:" #define FAN_OPEN_TEXT "100%" #define FAN_HALF_TEXT "50%" #define FAN_CLOSE_TEXT "0%" -//#define FAN_TIPS1_TEXT "FAN" -//#define FAN_TIPS2_TEXT "FAN\nClose" #define WIFI_TEXT "WIFI" #define WIFI_IP_TEXT "IP: " @@ -830,8 +836,8 @@ extern eeprom_def eeprom_menu; #define DIALOG_UPLOAD_SPEED_EN "Speed" #define DIALOG_UPDATE_WIFI_FIRMWARE_EN "Updating wifi model firmware" #define DIALOG_UPDATE_WIFI_WEB_EN "Updating wifi model web data" -#define DIALOG_UPDATE_NO_DEVICE_EN "please check \nwether memory device insert!" +#define DIALOG_UPDATE_NO_DEVICE_EN "Please check whether\nmemory device inserted!" -#define ZOFFSET_STEP001 "0.01mm" -#define ZOFFSET_STEP01 "0.1mm" -#define ZOFFSET_STEP1 "1mm" +#define ZOFFSET_STEP001 "0.01 mm" +#define ZOFFSET_STEP01 "0.1 mm" +#define ZOFFSET_STEP1 "1 mm" diff --git a/Marlin/src/lcd/extui/mks_ui/wifiSerial.h b/Marlin/src/lcd/extui/mks_ui/wifiSerial.h new file mode 100644 index 000000000000..1a3e9aae9b2d --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/wifiSerial.h @@ -0,0 +1,44 @@ +/** + * 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 + +#ifdef SERIAL_PORT_2 + #error "SERIAL_PORT_2 must be disabled with TFT_LVGL_UI* and MKS_WIFI_MODULE." +#endif + +#define WIFI_BAUDRATE 115200 +#define WIFI_UPLOAD_BAUDRATE 1958400 +#define USART_SAFE_INSERT + +#define WIFI_RX_BUF_SIZE (1024) +#define WIFI_TX_BUF_SIZE (64) + +#include "tft_lvgl_configuration.h" + +#ifdef __STM32F1__ + #include "wifiSerial_STM32F1.h" +#else + #include "wifiSerial_STM32.h" +#endif + +extern WifiSerial WifiSerial1; +#define WIFISERIAL WifiSerial1 diff --git a/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.cpp b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.cpp new file mode 100644 index 000000000000..6607e7531f0e --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.cpp @@ -0,0 +1,354 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../HAL/platforms.h" + +#ifdef HAL_STM32 + +#include "../../../inc/MarlinConfigPre.h" + +#if BOTH(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) + +#include "tft_lvgl_configuration.h" + +#include "draw_ui.h" +#include "wifiSerial.h" + +WifiSerial WifiSerial1(USART1); + +void WifiSerial::setRx(uint32_t _rx) { _serial.pin_rx = digitalPinToPinName(_rx); } +void WifiSerial::setTx(uint32_t _tx) { _serial.pin_tx = digitalPinToPinName(_tx); } +void WifiSerial::setRx(PinName _rx) { _serial.pin_rx = _rx; } +void WifiSerial::setTx(PinName _tx) { _serial.pin_tx = _tx; } + +void WifiSerial::init(PinName _rx, PinName _tx) { + _serial.pin_rx = (_rx == _tx) ? NC : _rx; + _serial.pin_tx = _tx; + _serial.rx_buff = wifiRxBuf; + _serial.rx_head = 0; + _serial.rx_tail = 0; + _serial.tx_buff = wifiTxBuf; + _serial.tx_head = 0; + _serial.tx_tail = 0; +} + +WifiSerial::WifiSerial(void *peripheral) { + // If PIN_SERIALy_RX is not defined assume half-duplex + _serial.pin_rx = NC; + // If Serial is defined in variant set + // the Rx/Tx pins for com port if defined + #if defined(Serial) && defined(PIN_SERIAL_TX) + if ((void *)this == (void *)&Serial) { + #ifdef PIN_SERIAL_RX + setRx(PIN_SERIAL_RX); + #endif + setTx(PIN_SERIAL_TX); + } else + #endif + #if defined(PIN_SERIAL1_TX) && defined(USART1_BASE) + if (peripheral == USART1) { + #ifdef PIN_SERIAL1_RX + setRx(PIN_SERIAL1_RX); + #endif + setTx(PIN_SERIAL1_TX); + } else + #endif + #if defined(PIN_SERIAL2_TX) && defined(USART2_BASE) + if (peripheral == USART2) { + #ifdef PIN_SERIAL2_RX + setRx(PIN_SERIAL2_RX); + #endif + setTx(PIN_SERIAL2_TX); + } else + #endif + #if defined(PIN_SERIAL3_TX) && defined(USART3_BASE) + if (peripheral == USART3) { + #ifdef PIN_SERIAL3_RX + setRx(PIN_SERIAL3_RX); + #endif + setTx(PIN_SERIAL3_TX); + } else + #endif + #ifdef PIN_SERIAL4_TX + if (false + #ifdef USART4_BASE + || peripheral == USART4 + #elif defined(UART4_BASE) + || peripheral == UART4 + #endif + ) { + #ifdef PIN_SERIAL4_RX + setRx(PIN_SERIAL4_RX); + #endif + setTx(PIN_SERIAL4_TX); + } else + #endif + #ifdef PIN_SERIAL5_TX + if (false + #ifdef USART5_BASE + || peripheral == USART5 + #elif defined(UART5_BASE) + || peripheral == UART5 + #endif + ) { + #ifdef PIN_SERIAL5_RX + setRx(PIN_SERIAL5_RX); + #endif + setTx(PIN_SERIAL5_TX); + } else + #endif + #if defined(PIN_SERIAL6_TX) && defined(USART6_BASE) + if (peripheral == USART6) { + #ifdef PIN_SERIAL6_RX + setRx(PIN_SERIAL6_RX); + #endif + setTx(PIN_SERIAL6_TX); + } else + #endif + #ifdef PIN_SERIAL7_TX + if (false + #ifdef USART7_BASE + || peripheral == USART7 + #elif defined(UART7_BASE) + || peripheral == UART7 + #endif + ) { + #ifdef PIN_SERIAL7_RX + setRx(PIN_SERIAL7_RX); + #endif + setTx(PIN_SERIAL7_TX); + } else + #endif + #ifdef PIN_SERIAL8_TX + if (false + #ifdef USART8_BASE + || peripheral == USART8 + #elif defined(UART8_BASE) + || peripheral == UART8 + #endif + ) { + #ifdef PIN_SERIAL8_RX + setRx(PIN_SERIAL8_RX); + #endif + setTx(PIN_SERIAL8_TX); + } else + #endif + #if defined(PIN_SERIAL9_TX) && defined(UART9_BASE) + if (peripheral == UART9) { + #ifdef PIN_SERIAL9_RX + setRx(PIN_SERIAL9_RX); + #endif + setTx(PIN_SERIAL9_TX); + } else + #endif + #ifdef PIN_SERIAL10_TX + if (false + #ifdef USART10_BASE + || peripheral == USART10 + #elif defined(UART10_BASE) + || peripheral == UART10 + #endif + ) { + #ifdef PIN_SERIAL10_RX + setRx(PIN_SERIAL10_RX); + #endif + setTx(PIN_SERIAL10_TX); + } else + #endif + #if defined(PIN_SERIALLP1_TX) && defined(LPUART1_BASE) + if (peripheral == LPUART1) { + #ifdef PIN_SERIALLP1_RX + setRx(PIN_SERIALLP1_RX); + #endif + setTx(PIN_SERIALLP1_TX); + } else + #endif + // else get the pins of the first peripheral occurrence in PinMap + { + _serial.pin_rx = pinmap_pin(peripheral, PinMap_UART_RX); + _serial.pin_tx = pinmap_pin(peripheral, PinMap_UART_TX); + } + //if (halfDuplex == HALF_DUPLEX_ENABLED) _serial.pin_rx = NC; + init(_serial.pin_rx, _serial.pin_tx); +} + +void WifiSerial::flush() { + // If we have never written a byte, no need to flush. This special + // case is needed since there is no way to force the TXC (transmit + // complete) bit to 1 during initialization + if (!_written) return; + + while ((_serial.tx_head != _serial.tx_tail)) { + // nop, the interrupt handler will free up space for us + } + // If we get here, nothing is queued anymore (DRIE is disabled) and + // the hardware finished transmission (TXC is set). +} + +bool WifiSerial::isHalfDuplex() const { return _serial.pin_rx == NC; } + +void WifiSerial::enableHalfDuplexRx() { + if (isHalfDuplex()) { + // In half-duplex mode we have to wait for all TX characters to + // be transmitted before we can receive data. + flush(); + if (!_rx_enabled) { + _rx_enabled = true; + uart_enable_rx(&_serial); + } + } +} + +// Actual interrupt handlers ////////////////////////////////////////////////////////////// + +void WifiSerial::_rx_complete_irq(serial_t *obj) { + // No Parity error, read byte and store it in the buffer if there is room + unsigned char c; + + if (uart_getc(obj, &c) == 0) { + + WRITE(WIFI_IO1_PIN, HIGH); + + rx_buffer_index_t i = (unsigned int)(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 + // current location of the tail), we're about to overflow the buffer + // and so we don't write the character or advance the head. + if (i != obj->rx_tail) { + obj->rx_buff[obj->rx_head] = c; + obj->rx_head = i; + } + } +} + +// Actual interrupt handlers ////////////////////////////////////////////////////////////// + +int WifiSerial::_tx_complete_irq(serial_t *obj) { + // If interrupts are enabled, there must be more data in the output + // buffer. Send the next byte + obj->tx_tail = (obj->tx_tail + 1) % WIFI_TX_BUF_SIZE; + + return (obj->tx_head == obj->tx_tail) ? -1 : 0; +} + +void WifiSerial::begin(unsigned long baud) { begin(baud, SERIAL_8N1); } + +void WifiSerial::begin(unsigned long baud, byte config) { + uint32_t databits = 0, stopbits = 0, parity = 0; + + _baud = baud; + _config = config; + + // Manage databits + switch (config & 0x07) { + case 0x02: databits = 6; break; + case 0x04: databits = 7; break; + case 0x06: databits = 8; break; + default: databits = 0; break; + } + + if ((config & 0x30) == 0x30) { + parity = UART_PARITY_ODD; + databits++; + } + else if ((config & 0x20) == 0x20) { + parity = UART_PARITY_EVEN; + databits++; + } + else + parity = UART_PARITY_NONE; + + stopbits = ((config & 0x08) == 0x08) ? UART_STOPBITS_2 : UART_STOPBITS_1; + + switch (databits) { + #ifdef UART_WORDLENGTH_7B + case 7: databits = UART_WORDLENGTH_7B; break; + #endif + case 8: databits = UART_WORDLENGTH_8B; break; + case 9: databits = UART_WORDLENGTH_9B; break; + default: + case 0: Error_Handler(); break; + } + + uart_init(&_serial, (uint32_t)baud, databits, parity, stopbits); + enableHalfDuplexRx(); + if (baud == WIFI_BAUDRATE) + uart_attach_rx_callback(&_serial, _rx_complete_irq); + else + USART1->CR1 |= USART_CR1_RE; // Preserve word length, etc. Use 'or' to preserve USART_CR1_M_8N1 +} + +void WifiSerial::end() { + // wait for transmission of outgoing data + flush(); + + uart_deinit(&_serial); + + // clear any received data + _serial.rx_head = _serial.rx_tail; +} + +int WifiSerial::available() { + return ((unsigned int)(WIFI_RX_BUF_SIZE + _serial.rx_head - _serial.rx_tail)) % WIFI_RX_BUF_SIZE; +} + +// +// I/O +// +int WifiSerial::read() { + enableHalfDuplexRx(); + // 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]; + _serial.rx_tail = (rx_buffer_index_t)(_serial.rx_tail + 1) % WIFI_RX_BUF_SIZE; + return c; +} + +int WifiSerial::write(uint8_t c) { + _written = true; + if (isHalfDuplex()) { + if (_rx_enabled) { + _rx_enabled = false; + uart_enable_tx(&_serial); + } + } + + tx_buffer_index_t i = (_serial.tx_head + 1) % WIFI_TX_BUF_SIZE; + + // If the output buffer is full, there's nothing for it other than to + // wait for the interrupt handler to empty it a bit + while (i == _serial.tx_tail) { + // nop, the interrupt handler will free up space for us + } + + _serial.tx_buff[_serial.tx_head] = c; + _serial.tx_head = i; + + if (!serial_tx_active(&_serial)) + uart_attach_tx_callback(&_serial, _tx_complete_irq); + + return 1; +} + +#endif // HAS_TFT_LVGL_UI && MKS_WIFI_MODULE +#endif // HAL_STM32 diff --git a/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.h b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.h new file mode 100644 index 000000000000..87de27c04439 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.h @@ -0,0 +1,63 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include +#include "Stream.h" +#include "uart.h" + +class WifiSerial { + protected: + // Has any byte been written to the UART since begin() + bool _written; + serial_t _serial; + public: + uint8_t wifiRxBuf[WIFI_RX_BUF_SIZE]; + uint8_t wifiTxBuf[WIFI_TX_BUF_SIZE]; + WifiSerial(void *peripheral); + + // Set up / tear down + void begin(uint32_t baud); + void begin(uint32_t baud,uint8_t config); + void end(); + int available(void); + int read(void); + int write(uint8_t); + + // Interrupt handlers + static int _tx_complete_irq(serial_t *obj); + static void _rx_complete_irq(serial_t *obj); + + void flush(void); + bool isHalfDuplex(void) const; + void enableHalfDuplexRx(void); + + private: + void setRx(uint32_t _rx); + void setTx(uint32_t _tx); + void setRx(PinName _rx); + void setTx(PinName _tx); + void init(PinName _rx, PinName _tx); + bool _rx_enabled; + uint8_t _config; + unsigned long _baud; +}; diff --git a/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32F1.cpp b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32F1.cpp new file mode 100644 index 000000000000..75830ce1bd4a --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32F1.cpp @@ -0,0 +1,141 @@ +/** + * 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 __STM32F1__ + +#include "../../../inc/MarlinConfigPre.h" + +#if BOTH(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) + +#include "tft_lvgl_configuration.h" + +#include "draw_ui.h" +#include "wifiSerial.h" + +#include +#include +#include +#include +#include + +#include "../../../MarlinCore.h" + +DEFINE_WFSERIAL(WifiSerial1, 1); + +WifiSerial::WifiSerial(usart_dev *usart_device, uint8 tx_pin, uint8 rx_pin) { + this->usart_device = usart_device; + this->tx_pin = tx_pin; + this->rx_pin = rx_pin; +} + +/** + * Set up / tear down + */ +#if STM32_MCU_SERIES == STM32_SERIES_F1 + /* F1 MCUs have no GPIO_AFR[HL], so turn off PWM if there's a conflict + * on this GPIO bit. */ + static void disable_timer_if_necessary(timer_dev *dev, uint8 ch) { + if (dev) timer_set_mode(dev, ch, TIMER_DISABLED); + } + static void usart_enable_no_irq(usart_dev *usart_device, bool with_irq) { + if (with_irq) usart_enable(usart_device); + else { + usart_reg_map *regs = usart_device->regs; + regs->CR1 |= (USART_CR1_TE | USART_CR1_RE); // Preserve word length, etc. Use 'or' to preserve USART_CR1_M_8N1 + regs->CR1 |= USART_CR1_UE; + } + } + +#elif STM32_MCU_SERIES == STM32_SERIES_F2 || STM32_MCU_SERIES == STM32_SERIES_F4 + #define disable_timer_if_necessary(dev, ch) NOOP + + static void usart_enable_no_irq(usart_dev *usart_device, bool with_irq) { + if (with_irq) usart_enable(usart_device); + else { + usart_reg_map *regs = usart_device->regs; + regs->CR1 |= (USART_CR1_TE | USART_CR1_RE); // Preserve word length, etc. Use 'or' to preserve USART_CR1_M_8N1 + regs->CR1 |= USART_CR1_UE; + } + } +#else + #warning "Unsupported STM32 series; timer conflicts are possible" + #define usart_enable_no_irq(X, Y) usart_enable(X) +#endif + +void WifiSerial::begin(uint32 baud) { begin(baud, SERIAL_8N1); } + +/** + * Roger Clark. + * Note. The config parameter is not currently used. This is a work in progress. + * Code needs to be written to set the config of the hardware serial control register in question. + */ + +void WifiSerial::begin(uint32 baud, uint8_t config) { + //ASSERT(baud <= this->usart_device->max_baud); // Roger Clark. Assert doesn't do anything useful, we may as well save the space in flash and ram etc + + if (baud > this->usart_device->max_baud) return; + + const stm32_pin_info *txi = &PIN_MAP[this->tx_pin], + *rxi = &PIN_MAP[this->rx_pin]; + + disable_timer_if_necessary(txi->timer_device, txi->timer_channel); + + usart_init(this->usart_device); + + // Reinitialize the receive buffer, mks_esp8266 fixed data frame length is 1k bytes + rb_init(this->usart_device->rb, WIFI_RX_BUF_SIZE, wifiRxBuf); + + usart_config_gpios_async(this->usart_device, + rxi->gpio_device, rxi->gpio_bit, + txi->gpio_device, txi->gpio_bit, + config); + usart_set_baud_rate(this->usart_device, USART_USE_PCLK, baud); + usart_enable_no_irq(this->usart_device, baud == WIFI_BAUDRATE); +} + +void WifiSerial::end() { + usart_disable(this->usart_device); +} + +int WifiSerial::available() { + return usart_data_available(this->usart_device); +} + +// +// I/O +// + +int WifiSerial::read() { + if (usart_data_available(usart_device) <= 0) return -1; + return usart_getc(usart_device); +} + +int WifiSerial::write(unsigned char ch) { + usart_putc(this->usart_device, ch); + return 1; +} + +int WifiSerial::wifi_rb_is_full() { + return rb_is_full(this->usart_device->rb); +} + +#endif // HAS_TFT_LVGL_UI && MKS_WIFI_MODULE +#endif // __STM32F1__ diff --git a/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32F1.h b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32F1.h new file mode 100644 index 000000000000..6af2f9743ba7 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32F1.h @@ -0,0 +1,77 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include +#include +#include +#include +#include +#include + +#define DEFINE_WFSERIAL(name, n) WifiSerial name(USART##n, BOARD_USART##n##_TX_PIN, BOARD_USART##n##_RX_PIN) + +class WifiSerial { + public: + uint8 wifiRxBuf[WIFI_RX_BUF_SIZE]; + + public: + WifiSerial(struct usart_dev *usart_device, uint8 tx_pin, uint8 rx_pin); + + /* Set up/tear down */ + void begin(uint32 baud); + void begin(uint32 baud,uint8_t config); + void end(); + int available(); + int read(); + int write(uint8_t); + inline void wifi_usart_irq(usart_reg_map *regs) { + /* Handling RXNEIE and TXEIE interrupts. + * RXNE signifies availability of a byte in DR. + * + * See table 198 (sec 27.4, p809) in STM document RM0008 rev 15. + * We enable RXNEIE. + */ + if ((regs->CR1 & USART_CR1_RXNEIE) && (regs->SR & USART_SR_RXNE)) { + #ifdef USART_SAFE_INSERT + /* If the buffer is full and the user defines USART_SAFE_INSERT, + * ignore new bytes. */ + rb_safe_insert(this->usart_device->rb, (uint8)regs->DR); + #else + /* By default, push bytes around in the ring buffer. */ + rb_push_insert(this->usart_device->rb, (uint8)regs->DR); + #endif + } + /* TXE signifies readiness to send a byte to DR. */ + if ((regs->CR1 & USART_CR1_TXEIE) && (regs->SR & USART_SR_TXE)) { + if (!rb_is_empty(this->usart_device->wb)) + regs->DR=rb_remove(this->usart_device->wb); + else + regs->CR1 &= ~((uint32)USART_CR1_TXEIE); // disable TXEIE + } + } + int wifi_rb_is_full(); + struct usart_dev *usart_device; + private: + uint8 tx_pin; + uint8 rx_pin; +}; diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp new file mode 100644 index 000000000000..b53586c75672 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp @@ -0,0 +1,2067 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if BOTH(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) + +#include "draw_ui.h" +#include "wifi_module.h" +#include "wifi_upload.h" +#include "SPI_TFT.h" + +#include "../../marlinui.h" + +#include "../../../MarlinCore.h" +#include "../../../module/temperature.h" +#include "../../../gcode/queue.h" +#include "../../../gcode/gcode.h" +#include "../../../sd/cardreader.h" +#include "../../../module/planner.h" +#include "../../../module/servo.h" +#include "../../../module/probe.h" + +#if DISABLED(EMERGENCY_PARSER) + #include "../../../module/motion.h" +#endif +#if ENABLED(POWER_LOSS_RECOVERY) + #include "../../../feature/powerloss.h" +#endif +#if ENABLED(PARK_HEAD_ON_PAUSE) + #include "../../../feature/pause.h" +#endif + +#define WIFI_SET() WRITE(WIFI_RESET_PIN, HIGH); +#define WIFI_RESET() WRITE(WIFI_RESET_PIN, LOW); +#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); + +extern uint8_t commands_in_queue; +extern uint8_t sel_id; +extern unsigned int getTickDiff(unsigned int curTick, unsigned int lastTick); + +volatile SZ_USART_FIFO WifiRxFifo; + +#define WAIT_ESP_TRANS_TIMEOUT_TICK 10500 + +int cfg_cloud_flag = 0; + +extern PRINT_TIME print_time; + +char wifi_firm_ver[20] = { 0 }; +WIFI_GCODE_BUFFER espGcodeFifo; +extern uint8_t pause_resum; + +uint8_t wifi_connect_flg = 0; +extern volatile uint8_t get_temp_flag; + +#define WIFI_MODE 2 +#define WIFI_AP_MODE 3 + +int upload_result = 0; + +uint32_t upload_time_sec = 0; +uint32_t upload_size = 0; + +volatile WIFI_STATE wifi_link_state; +WIFI_PARA wifiPara; +IP_PARA ipPara; +CLOUD_PARA cloud_para; + +char wifi_check_time = 0; + +extern uint8_t gCurDir[100]; + +extern uint32_t wifi_loop_cycle; + +volatile TRANSFER_STATE esp_state; + +uint8_t left_to_send = 0; +uint8_t left_to_save[96] = { 0 }; + +volatile WIFI_DMA_RCV_FIFO wifiDmaRcvFifo; + +volatile WIFI_TRANS_ERROR wifiTransError; + +static bool need_ok_later = false; + +extern volatile WIFI_STATE wifi_link_state; +extern WIFI_PARA wifiPara; +extern IP_PARA ipPara; +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(); } + +uint32_t getWifiTickDiff(int32_t lastTick, int32_t curTick) { + return (lastTick <= curTick ? curTick - lastTick : 0xFFFFFFFF - lastTick + curTick) * TICK_CYCLE; +} + +void wifi_delay(int n) { + const uint32_t start = getWifiTick(); + while (getWifiTickDiff(start, getWifiTick()) < (uint32_t)n) + watchdog_refresh(); +} + +void wifi_reset() { + uint32_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) { + } +} + +static bool longName2DosName(const char *longName, char *dosName) { + uint8_t i = FILENAME_LENGTH; + while (i) dosName[--i] = '\0'; + + while (*longName) { + uint8_t c = *longName++; + if (c == '.') { // For a dot... + if (i == 0) return false; + strcat_P(dosName, PSTR(".GCO")); + return dosName[0] != '\0'; + } + 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 + } + if (i >= 5) { + strcat_P(dosName, PSTR("~1.GCO")); + return dosName[0] != '\0'; + } + } + return dosName[0] != '\0'; // Return true if any name was set +} + +#ifdef __STM32F1__ + + #include + #include + #include + + #include + #include + + #include + #include + + #include + #include + #include + #include + + void changeFlashMode(const bool dmaMode) { + if (flash_dma_mode != dmaMode) { + flash_dma_mode = dmaMode; + if (!flash_dma_mode) { + dma_disable(DMA1, DMA_CH5); + dma_clear_isr_bits(DMA1, DMA_CH4); + } + } + } + + static int storeRcvData(volatile uint8_t *bufToCpy, int32_t len) { + unsigned char tmpW = wifiDmaRcvFifo.write_cur; + if (len > UDISKBUFLEN) return 0; + if (wifiDmaRcvFifo.state[tmpW] == udisk_buf_empty) { + memcpy((unsigned char *) wifiDmaRcvFifo.bufferAddr[tmpW], (uint8_t *)bufToCpy, len); + wifiDmaRcvFifo.state[tmpW] = udisk_buf_full; + wifiDmaRcvFifo.write_cur = (tmpW + 1) % TRANS_RCV_FIFO_BLOCK_NUM; + return 1; + } + return 0; + } + + static void esp_dma_pre() { + dma_channel_reg_map *channel_regs = dma_tube_regs(DMA1, DMA_CH5); + + CBI32(channel_regs->CCR, 0); + channel_regs->CMAR = (uint32_t)WIFISERIAL.usart_device->rb->buf; + channel_regs->CNDTR = 0x0000; + channel_regs->CNDTR = UART_RX_BUFFER_SIZE; + DMA1->regs->IFCR = 0xF0000; + SBI32(channel_regs->CCR, 0); + } + + static void dma_ch5_irq_handle() { + uint8 status_bits = dma_get_isr_bits(DMA1, DMA_CH5); + dma_clear_isr_bits(DMA1, DMA_CH5); + if (status_bits & 0x8) { + // DMA transmit Error + } + else if (status_bits & 0x2) { + // DMA transmit complete + if (esp_state == TRANSFER_IDLE) + esp_state = TRANSFERRING; + + if (storeRcvData(WIFISERIAL.usart_device->rb->buf, UART_RX_BUFFER_SIZE)) { + esp_dma_pre(); + if (wifiTransError.flag != 0x1) + WIFI_IO1_RESET(); + } + else { + WIFI_IO1_SET(); + esp_state = TRANSFER_STORE; + } + } + else if (status_bits & 0x4) { + // DMA transmit half + WIFI_IO1_SET(); + } + } + + static void wifi_usart_dma_init() { + dma_init(DMA1); + uint32_t flags = ( DMA_MINC_MODE | DMA_TRNS_CMPLT | DMA_HALF_TRNS | DMA_TRNS_ERR); + dma_xfer_size dma_bit_size = DMA_SIZE_8BITS; + dma_setup_transfer(DMA1, DMA_CH5, &USART1_BASE->DR, dma_bit_size, + (volatile void*)WIFISERIAL.usart_device->rb->buf, dma_bit_size, flags);// Transmit buffer DMA + dma_set_priority(DMA1, DMA_CH5, DMA_PRIORITY_LOW); + dma_attach_interrupt(DMA1, DMA_CH5, &dma_ch5_irq_handle); + + dma_clear_isr_bits(DMA1, DMA_CH5); + dma_set_num_transfers(DMA1, DMA_CH5, UART_RX_BUFFER_SIZE); + + bb_peri_set_bit(&USART1_BASE->CR3, USART_CR3_DMAR_BIT, 1); + dma_enable(DMA1, DMA_CH5); // enable transmit + + for (uint8_t i = 0; i < TRANS_RCV_FIFO_BLOCK_NUM; i++) { + wifiDmaRcvFifo.bufferAddr[i] = &bmp_public_buf[1024 * i]; + wifiDmaRcvFifo.state[i] = udisk_buf_empty; + } + + memset(wifiDmaRcvFifo.bufferAddr[0], 0, 1024 * TRANS_RCV_FIFO_BLOCK_NUM); + wifiDmaRcvFifo.read_cur = 0; + wifiDmaRcvFifo.write_cur = 0; + } + + void esp_port_begin(uint8_t interrupt) { + WifiRxFifo.uart_read_point = 0; + WifiRxFifo.uart_write_point = 0; + #if ENABLED(MKS_WIFI_MODULE) + if (interrupt) { + WIFISERIAL.end(); + for (uint16_t i = 0; i < 65535; i++) { /*nada*/ } + WIFISERIAL.begin(WIFI_BAUDRATE); + millis_t serial_connect_timeout = millis() + 1000UL; + while (PENDING(millis(), serial_connect_timeout)) { /*nada*/ } + } + else { + WIFISERIAL.end(); + WIFISERIAL.usart_device->regs->CR1 &= ~USART_CR1_RXNEIE; + WIFISERIAL.begin(WIFI_UPLOAD_BAUDRATE); + wifi_usart_dma_init(); + } + #endif + } + +#else // !__STM32F1__ + + DMA_HandleTypeDef wifiUsartDMArx; + + void changeFlashMode(const bool dmaMode) { + if (flash_dma_mode != dmaMode) { + flash_dma_mode = dmaMode; + if (flash_dma_mode == 1) { + } + else { + } + } + } + + #ifdef STM32F1xx + + HAL_StatusTypeDef HAL_DMA_PollForTransferCustomize(DMA_HandleTypeDef *hdma, uint32_t CompleteLevel, uint32_t Timeout) { + uint32_t temp; + uint32_t tickstart = 0U; + + if (HAL_DMA_STATE_BUSY != hdma->State) { // No transfer ongoing + hdma->ErrorCode = HAL_DMA_ERROR_NO_XFER; + __HAL_UNLOCK(hdma); + return HAL_ERROR; + } + + // Polling mode not supported in circular mode + if (RESET != (hdma->Instance->CCR & DMA_CCR_CIRC)) { + hdma->ErrorCode = HAL_DMA_ERROR_NOT_SUPPORTED; + return HAL_ERROR; + } + + // Get the level transfer complete flag + temp = (CompleteLevel == HAL_DMA_FULL_TRANSFER + ? __HAL_DMA_GET_TC_FLAG_INDEX(hdma) // Transfer Complete flag + : __HAL_DMA_GET_HT_FLAG_INDEX(hdma) // Half Transfer Complete flag + ); + + // Get tick + tickstart = HAL_GetTick(); + + while (__HAL_DMA_GET_FLAG(hdma, temp) == RESET) { + if ((__HAL_DMA_GET_FLAG(hdma, __HAL_DMA_GET_HT_FLAG_INDEX(hdma)) != RESET)) { + __HAL_DMA_CLEAR_FLAG(hdma, __HAL_DMA_GET_HT_FLAG_INDEX(hdma)); // Clear the half transfer complete flag + WIFI_IO1_SET(); + } + + if ((__HAL_DMA_GET_FLAG(hdma, __HAL_DMA_GET_TE_FLAG_INDEX(hdma)) != RESET)) { + /** + * When a DMA transfer error occurs + * A hardware clear of its EN bits is performed + * Clear all flags + */ + hdma->DmaBaseAddress->IFCR = (DMA_ISR_GIF1 << hdma->ChannelIndex); + + SET_BIT(hdma->ErrorCode, HAL_DMA_ERROR_TE); // Update error code + hdma->State= HAL_DMA_STATE_READY; // Change the DMA state + __HAL_UNLOCK(hdma); // Process Unlocked + return HAL_ERROR; + } + + // Check for the Timeout + if (Timeout != HAL_MAX_DELAY && (!Timeout || (HAL_GetTick() - tickstart) > Timeout)) { + SET_BIT(hdma->ErrorCode, HAL_DMA_ERROR_TIMEOUT); // Update error code + hdma->State = HAL_DMA_STATE_READY; // Change the DMA state + __HAL_UNLOCK(hdma); // Process Unlocked + return HAL_ERROR; + } + } + + if (CompleteLevel == HAL_DMA_FULL_TRANSFER) { + // Clear the transfer complete flag + __HAL_DMA_CLEAR_FLAG(hdma, __HAL_DMA_GET_TC_FLAG_INDEX(hdma)); + + /* The selected Channelx EN bit is cleared (DMA is disabled and + all transfers are complete) */ + hdma->State = HAL_DMA_STATE_READY; + } + else + __HAL_DMA_CLEAR_FLAG(hdma, __HAL_DMA_GET_HT_FLAG_INDEX(hdma)); // Clear the half transfer complete flag + + __HAL_UNLOCK(hdma); // Process unlocked + + return HAL_OK; + } + + #else // !STM32F1xx + + typedef struct { + __IO uint32_t ISR; //!< DMA interrupt status register + __IO uint32_t Reserved0; + __IO uint32_t IFCR; //!< DMA interrupt flag clear register + } MYDMA_Base_Registers; + + HAL_StatusTypeDef HAL_DMA_PollForTransferCustomize(DMA_HandleTypeDef *hdma, HAL_DMA_LevelCompleteTypeDef CompleteLevel, uint32_t Timeout) { + HAL_StatusTypeDef status = HAL_OK; + uint32_t mask_cpltlevel; + uint32_t tickstart = HAL_GetTick(); + uint32_t tmpisr; + + MYDMA_Base_Registers *regs; // Calculate DMA base and stream number + + if (HAL_DMA_STATE_BUSY != hdma->State) { // No transfer ongoing + hdma->ErrorCode = HAL_DMA_ERROR_NO_XFER; + __HAL_UNLOCK(hdma); + return HAL_ERROR; + } + + // Polling mode not supported in circular mode and double buffering mode + if ((hdma->Instance->CR & DMA_SxCR_CIRC) != RESET) { + hdma->ErrorCode = HAL_DMA_ERROR_NOT_SUPPORTED; + return HAL_ERROR; + } + + // Get the level transfer complete flag + mask_cpltlevel = (CompleteLevel == HAL_DMA_FULL_TRANSFER + ? DMA_FLAG_TCIF0_4 << hdma->StreamIndex // Transfer Complete flag + : DMA_FLAG_HTIF0_4 << hdma->StreamIndex // Half Transfer Complete flag + ); + + regs = (MYDMA_Base_Registers *)hdma->StreamBaseAddress; + tmpisr = regs->ISR; + + while (((tmpisr & mask_cpltlevel) == RESET) && ((hdma->ErrorCode & HAL_DMA_ERROR_TE) == RESET)) { + // Check for the Timeout (Not applicable in circular mode) + if (Timeout != HAL_MAX_DELAY) { + if (!Timeout || (HAL_GetTick() - tickstart) > Timeout) { + hdma->ErrorCode = HAL_DMA_ERROR_TIMEOUT; // Update error code + __HAL_UNLOCK(hdma); // Process Unlocked + hdma->State = HAL_DMA_STATE_READY; // Change the DMA state + return HAL_TIMEOUT; + } + } + + tmpisr = regs->ISR; // Get the ISR register value + + if ((tmpisr & (DMA_FLAG_HTIF0_4 << hdma->StreamIndex)) != RESET) { + regs->IFCR = DMA_FLAG_HTIF0_4 << hdma->StreamIndex; // Clear the Direct Mode error flag + WIFI_IO1_SET(); + } + + if ((tmpisr & (DMA_FLAG_TEIF0_4 << hdma->StreamIndex)) != RESET) { + hdma->ErrorCode |= HAL_DMA_ERROR_TE; // Update error code + regs->IFCR = DMA_FLAG_TEIF0_4 << hdma->StreamIndex; // Clear the transfer error flag + } + + if ((tmpisr & (DMA_FLAG_FEIF0_4 << hdma->StreamIndex)) != RESET) { + hdma->ErrorCode |= HAL_DMA_ERROR_FE; // Update error code + regs->IFCR = DMA_FLAG_FEIF0_4 << hdma->StreamIndex; // Clear the FIFO error flag + } + + if ((tmpisr & (DMA_FLAG_DMEIF0_4 << hdma->StreamIndex)) != RESET) { + hdma->ErrorCode |= HAL_DMA_ERROR_DME; // Update error code + regs->IFCR = DMA_FLAG_DMEIF0_4 << hdma->StreamIndex; // Clear the Direct Mode error flag + } + } + + if (hdma->ErrorCode != HAL_DMA_ERROR_NONE && (hdma->ErrorCode & HAL_DMA_ERROR_TE) != RESET) { + HAL_DMA_Abort(hdma); + regs->IFCR = (DMA_FLAG_HTIF0_4 | DMA_FLAG_TCIF0_4) << hdma->StreamIndex; // Clear the half transfer and transfer complete flags + __HAL_UNLOCK(hdma); // Process Unlocked + hdma->State= HAL_DMA_STATE_READY; // Change the DMA state + return HAL_ERROR; + } + + // Get the level transfer complete flag + if (CompleteLevel == HAL_DMA_FULL_TRANSFER) { + regs->IFCR = (DMA_FLAG_HTIF0_4 | DMA_FLAG_TCIF0_4) << hdma->StreamIndex; // Clear the half transfer and transfer complete flags + __HAL_UNLOCK(hdma); // Process Unlocked + hdma->State = HAL_DMA_STATE_READY; + } + else + regs->IFCR = (DMA_FLAG_HTIF0_4) << hdma->StreamIndex; // Clear the half transfer and transfer complete flags + + return status; + } + #endif + + static void dmaTransmitBegin() { + wifiUsartDMArx.Init.MemInc = DMA_MINC_ENABLE; + if (HAL_DMA_Init((DMA_HandleTypeDef *)&wifiUsartDMArx) != HAL_OK) + Error_Handler(); + + if (HAL_DMA_Start(&wifiUsartDMArx, (uint32_t)&(USART1->DR), (uint32_t)WIFISERIAL.wifiRxBuf, UART_RX_BUFFER_SIZE)) + Error_Handler(); + + USART1->CR1 |= USART_CR1_UE; + + SET_BIT(USART1->CR3, USART_CR3_DMAR); + WIFI_IO1_RESET(); + } + + static int storeRcvData(volatile uint8_t *bufToCpy, int32_t len) { + unsigned char tmpW = wifiDmaRcvFifo.write_cur; + + if (len > UDISKBUFLEN) return 0; + + if (wifiDmaRcvFifo.state[tmpW] == udisk_buf_empty) { + const int timeOut = 2000; //millisecond + dmaTransmitBegin(); + if (HAL_DMA_PollForTransferCustomize(&wifiUsartDMArx, HAL_DMA_FULL_TRANSFER, timeOut) == HAL_OK) { + memcpy((unsigned char *) wifiDmaRcvFifo.bufferAddr[tmpW], (uint8_t *)bufToCpy, len); + wifiDmaRcvFifo.state[tmpW] = udisk_buf_full; + wifiDmaRcvFifo.write_cur = (tmpW + 1) % TRANS_RCV_FIFO_BLOCK_NUM; + return 1; + } + } + return 0; + } + + static void wifi_usart_dma_init() { + #ifdef STM32F1xx + __HAL_RCC_DMA1_CLK_ENABLE(); + wifiUsartDMArx.Instance = DMA1_Channel5; + #else + __HAL_RCC_DMA2_CLK_ENABLE(); + wifiUsartDMArx.Instance = DMA2_Stream2; + wifiUsartDMArx.Init.Channel = DMA_CHANNEL_4; + #endif + wifiUsartDMArx.Init.Direction = DMA_PERIPH_TO_MEMORY; + wifiUsartDMArx.Init.PeriphInc = DMA_PINC_DISABLE; + wifiUsartDMArx.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE; + wifiUsartDMArx.Init.MemDataAlignment = DMA_PDATAALIGN_BYTE; + wifiUsartDMArx.Init.Mode = DMA_NORMAL; + #ifdef STM32F4xx + wifiUsartDMArx.Init.FIFOMode = DMA_FIFOMODE_DISABLE; + #endif + wifiUsartDMArx.Init.MemInc = DMA_MINC_ENABLE; + if (HAL_DMA_Init((DMA_HandleTypeDef *)&wifiUsartDMArx) != HAL_OK) + Error_Handler(); + + if (HAL_DMA_Start(&wifiUsartDMArx, (uint32_t)&(USART1->DR), (uint32_t)WIFISERIAL.wifiRxBuf, UART_RX_BUFFER_SIZE)) + Error_Handler(); + + USART1->CR1 |= USART_CR1_UE; + + SET_BIT(USART1->CR3, USART_CR3_DMAR); // Enable Rx DMA Request + + for (uint8_t i = 0; i < TRANS_RCV_FIFO_BLOCK_NUM; i++) { + wifiDmaRcvFifo.bufferAddr[i] = &bmp_public_buf[1024 * i]; + wifiDmaRcvFifo.state[i] = udisk_buf_empty; + } + + memset(wifiDmaRcvFifo.bufferAddr[0], 0, 1024 * TRANS_RCV_FIFO_BLOCK_NUM); + wifiDmaRcvFifo.read_cur = 0; + wifiDmaRcvFifo.write_cur = 0; + } + + void esp_port_begin(uint8_t interrupt) { + WifiRxFifo.uart_read_point = 0; + WifiRxFifo.uart_write_point = 0; + + #if ENABLED(MKS_WIFI_MODULE) + if (interrupt) { + WIFISERIAL.end(); + for (uint16_t i = 0; i < 65535; i++) { /*nada*/ } + WIFISERIAL.begin(WIFI_BAUDRATE); + uint32_t serial_connect_timeout = millis() + 1000UL; + while (PENDING(millis(), serial_connect_timeout)) { /*nada*/ } + } + else { + WIFISERIAL.end(); + USART1->CR1 &= ~USART_CR1_RXNEIE; + WIFISERIAL.begin(WIFI_UPLOAD_BAUDRATE); + wifi_usart_dma_init(); + } + #endif + } + +#endif // !__STM32F1__ + +#if ENABLED(MKS_WIFI_MODULE) + + int raw_send_to_wifi(uint8_t *buf, int len) { + if (buf == 0 || len <= 0) return 0; + for (int i = 0; i < len; i++) WIFISERIAL.write(*(buf + i)); + return len; + } + +#endif + +void wifi_ret_ack() {} + +uint8_t buf_to_wifi[256]; +int index_to_wifi = 0; +int package_to_wifi(WIFI_RET_TYPE type, uint8_t *buf, int len) { + uint8_t wifi_ret_head = 0xA5; + uint8_t wifi_ret_tail = 0xFC; + + if (type == WIFI_PARA_SET) { + int data_offset = 4, + apLen = strlen((const char *)uiCfg.wifi_name), + keyLen = strlen((const char *)uiCfg.wifi_key); + + ZERO(buf_to_wifi); + index_to_wifi = 0; + + buf_to_wifi[data_offset] = gCfgItems.wifi_mode_sel; + buf_to_wifi[data_offset + 1] = apLen; + memcpy(&buf_to_wifi[data_offset + 2], (const char *)uiCfg.wifi_name, apLen); + buf_to_wifi[data_offset + apLen + 2] = keyLen; + memcpy(&buf_to_wifi[data_offset + apLen + 3], (const char *)uiCfg.wifi_key, keyLen); + buf_to_wifi[data_offset + apLen + keyLen + 3] = wifi_ret_tail; + + index_to_wifi = apLen + keyLen + 3; + + buf_to_wifi[0] = wifi_ret_head; + buf_to_wifi[1] = type; + buf_to_wifi[2] = index_to_wifi & 0xFF; + buf_to_wifi[3] = (index_to_wifi >> 8) & 0xFF; + + raw_send_to_wifi(buf_to_wifi, 5 + index_to_wifi); + + ZERO(buf_to_wifi); + index_to_wifi = 0; + } + else if (type == WIFI_TRANS_INF) { + if (len > (int)(sizeof(buf_to_wifi) - index_to_wifi - 5)) { + ZERO(buf_to_wifi); + index_to_wifi = 0; + return 0; + } + + if (len > 0) { + memcpy(&buf_to_wifi[4 + index_to_wifi], buf, len); + index_to_wifi += len; + + if (index_to_wifi < 1) + return 0; + + if (buf_to_wifi[index_to_wifi + 3] == '\n') { + // mask "wait" "busy" "X:" + if ( ((buf_to_wifi[4] == 'w') && (buf_to_wifi[5] == 'a') && (buf_to_wifi[6] == 'i') && (buf_to_wifi[7] == 't')) + || ((buf_to_wifi[4] == 'b') && (buf_to_wifi[5] == 'u') && (buf_to_wifi[6] == 's') && (buf_to_wifi[7] == 'y')) + || ((buf_to_wifi[4] == 'X') && (buf_to_wifi[5] == ':')) + ) { + ZERO(buf_to_wifi); + index_to_wifi = 0; + return 0; + } + + buf_to_wifi[0] = wifi_ret_head; + buf_to_wifi[1] = type; + buf_to_wifi[2] = index_to_wifi & 0xFF; + buf_to_wifi[3] = (index_to_wifi >> 8) & 0xFF; + buf_to_wifi[4 + index_to_wifi] = wifi_ret_tail; + + raw_send_to_wifi(buf_to_wifi, 5 + index_to_wifi); + + ZERO(buf_to_wifi); + index_to_wifi = 0; + } + } + } + else if (type == WIFI_EXCEP_INF) { + ZERO(buf_to_wifi); + + buf_to_wifi[0] = wifi_ret_head; + buf_to_wifi[1] = type; + buf_to_wifi[2] = 1; + buf_to_wifi[3] = 0; + buf_to_wifi[4] = *buf; + buf_to_wifi[5] = wifi_ret_tail; + + raw_send_to_wifi(buf_to_wifi, 6); + + ZERO(buf_to_wifi); + index_to_wifi = 0; + } + else if (type == WIFI_CLOUD_CFG) { + int data_offset = 4; + int urlLen = strlen((const char *)uiCfg.cloud_hostUrl); + + ZERO(buf_to_wifi); + index_to_wifi = 0; + + buf_to_wifi[data_offset] = gCfgItems.cloud_enable ? 0x0A : 0x05; + buf_to_wifi[data_offset + 1] = urlLen; + memcpy(&buf_to_wifi[data_offset + 2], (const char *)uiCfg.cloud_hostUrl, urlLen); + buf_to_wifi[data_offset + urlLen + 2] = uiCfg.cloud_port & 0xFF; + buf_to_wifi[data_offset + urlLen + 3] = (uiCfg.cloud_port >> 8) & 0xFF; + buf_to_wifi[data_offset + urlLen + 4] = wifi_ret_tail; + + index_to_wifi = urlLen + 4; + + buf_to_wifi[0] = wifi_ret_head; + buf_to_wifi[1] = type; + buf_to_wifi[2] = index_to_wifi & 0xFF; + buf_to_wifi[3] = (index_to_wifi >> 8) & 0xFF; + + raw_send_to_wifi(buf_to_wifi, 5 + index_to_wifi); + + ZERO(buf_to_wifi); + index_to_wifi = 0; + } + else if (type == WIFI_CLOUD_UNBIND) { + ZERO(buf_to_wifi); + + buf_to_wifi[0] = wifi_ret_head; + buf_to_wifi[1] = type; + buf_to_wifi[2] = 0; + buf_to_wifi[3] = 0; + buf_to_wifi[4] = wifi_ret_tail; + + raw_send_to_wifi(buf_to_wifi, 5); + + ZERO(buf_to_wifi); + index_to_wifi = 0; + } + return 1; +} + + +#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); } + +void set_cur_file_sys(int fileType) { gCfgItems.fileSysType = fileType; } + +void get_file_list(char *path) { + if (!path) return; + + if (gCfgItems.fileSysType == FILE_SYS_SD) { + TERN_(SDSUPPORT, card.mount()); + } + else if (gCfgItems.fileSysType == FILE_SYS_USB) { + // udisk + } + Explore_Disk(path, 0); +} + +char wait_ip_back_flag = 0; + +typedef struct { + int write_index; + uint8_t saveFileName[30]; + uint8_t fileTransfer; + uint32_t fileLen; + uint32_t tick_begin; + uint32_t tick_end; +} FILE_WRITER; + +FILE_WRITER file_writer; + +int32_t lastFragment = 0; + +char saveFilePath[50]; + +static SdFile upload_file, *upload_curDir; +static filepos_t pos; + +int write_to_file(char *buf, int len) { + int i; + int res = 0; + + for (i = 0; i < len; i++) { + public_buf[file_writer.write_index++] = buf[i]; + if (file_writer.write_index >= 512) { + res = upload_file.write(public_buf, file_writer.write_index); + + if (res == -1) { + upload_file.close(); + const char * const fname = card.diveToFile(false, upload_curDir, saveFilePath); + + if (upload_file.open(upload_curDir, fname, O_WRITE)) { + upload_file.setpos(&pos); + res = upload_file.write(public_buf, file_writer.write_index); + } + } + + if (res == -1) return -1; + + upload_file.getpos(&pos); + file_writer.write_index = 0; + } + } + + if (res == -1) { + ZERO(public_buf); + file_writer.write_index = 0; + return -1; + } + + return 0; +} + +#define ESP_PROTOC_HEAD (uint8_t)0xA5 +#define ESP_PROTOC_TAIL (uint8_t)0xFC + +#define ESP_TYPE_NET (uint8_t)0x0 +#define ESP_TYPE_GCODE (uint8_t)0x1 +#define ESP_TYPE_FILE_FIRST (uint8_t)0x2 +#define ESP_TYPE_FILE_FRAGMENT (uint8_t)0x3 + +#define ESP_TYPE_WIFI_LIST (uint8_t)0x4 + +uint8_t esp_msg_buf[UART_RX_BUFFER_SIZE] = { 0 }; +uint16_t esp_msg_index = 0; + +typedef struct { + uint8_t head; + uint8_t type; + uint16_t dataLen; + uint8_t *data; + uint8_t tail; +} ESP_PROTOC_FRAME; + +static int cut_msg_head(uint8_t *msg, uint16_t msgLen, uint16_t cutLen) { + if (msgLen < cutLen) return 0; + + else if (msgLen == cutLen) { + memset(msg, 0, msgLen); + return 0; + } + + for (int i = 0; i < (msgLen - cutLen); i++) + msg[i] = msg[cutLen + i]; + + memset(&msg[msgLen - cutLen], 0, cutLen); + + return msgLen - cutLen; +} + +uint8_t Explore_Disk(char *path , uint8_t recu_level) { + char tmp[200]; + char Fstream[200]; + + if (!path) return 0; + + const uint8_t fileCnt = card.get_num_Files(); + + for (uint8_t i = 0; i < fileCnt; i++) { + card.getfilename_sorted(SD_ORDER(i, fileCnt)); + ZERO(tmp); + strcpy(tmp, card.filename); + + ZERO(Fstream); + strcpy(Fstream, tmp); + + if (card.flag.filenameIsDir && recu_level <= 10) + strcat_P(Fstream, PSTR(".DIR")); + + strcat_P(Fstream, PSTR("\r\n")); + send_to_wifi((uint8_t*)Fstream, strlen(Fstream)); + } + + return fileCnt; +} + +static void wifi_gcode_exec(uint8_t *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'; + + tmpStr = (uint8_t *)strchr((char *)cmd_line, 'M'); + if (tmpStr) { + cmd_value = atoi((char *)(tmpStr + 1)); + tmpStr = (uint8_t *)strchr((char *)tmpStr, ' '); + + switch (cmd_value) { + + case 20: // M20: Print SD / µdisk file + file_writer.fileTransfer = 0; + if (uiCfg.print_state == IDLE) { + int index = 0; + + 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:/"); + send_to_wifi((uint8_t *)(STR_END_FILE_LIST "\r\n"), strlen(STR_END_FILE_LIST "\r\n")); + SEND_OK_TO_WIFI; + break; + } + + while (tmpStr[index] == ' ') index++; + + if (gCfgItems.wifi_type == ESP_WIFI) { + char *path = (char *)tempBuf; + + 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 (strncmp((char *)&tmpStr[index], "1:", 2) == 0) + gCfgItems.fileSysType = FILE_SYS_SD; + else if (strncmp((char *)&tmpStr[index], "0:", 2) == 0) + gCfgItems.fileSysType = FILE_SYS_USB; + + 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")); + } + SEND_OK_TO_WIFI; + } + } + break; + + case 21: SEND_OK_TO_WIFI; break; // Init SD card + + case 23: + // Select the file + 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("/")); + + 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]); + } + + } + 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")); + } + 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], '/'); + + SdFile file; + SdFile *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 EXTRUDERS + planner.flow_percentage[0] = 100; + planner.e_factor[0] = planner.flow_percentage[0] * 0.01f; + #endif + #if EXTRUDERS == 2 + 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(); + } + } + SEND_OK_TO_WIFI; + break; + + case 25: + // Pause print file + if (uiCfg.print_state == WORKING) { + stop_print_time(); + + clear_cur_ui(); + + #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(); + + clear_cur_ui(); + #if ENABLED(SDSUPPORT) + uiCfg.print_state = IDLE; + card.abortFilePrintSoon(); + #endif + + lv_draw_ready_print(); + + 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; + + case 28: + // Begin to transfer file to filesys + 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"))) { + strcpy((char *)file_writer.saveFileName, (char *)&tmpStr[index]); + + 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 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; + + 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)) + ); + } + + send_to_wifi((uint8_t *)tempBuf, strlen((char *)tempBuf)); + queue.enqueue_one_P(PSTR("M105")); + 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 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: + if (uiCfg.print_state == IDLE) { + wifi_ret_ack(); + send_to_wifi((uint8_t *)"M997 IDLE\r\n", strlen("M997 IDLE\r\n")); + } + else if (uiCfg.print_state == WORKING) { + wifi_ret_ack(); + send_to_wifi((uint8_t *)"M997 PRINTING\r\n", strlen("M997 PRINTING\r\n")); + } + else if (uiCfg.print_state == PAUSED) { + wifi_ret_ack(); + send_to_wifi((uint8_t *)"M997 PAUSE\r\n", strlen("M997 PAUSE\r\n")); + } + else if (uiCfg.print_state == 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; + + 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 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; + } + } + break; + } + } + else { + 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 (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; + } + } + } + } +} + +static int32_t charAtArray(const uint8_t *_array, uint32_t _arrayLen, uint8_t _char) { + for (uint32_t i = 0; i < _arrayLen; i++) + if (*(_array + i) == _char) return i; + return -1; +} + +void get_wifi_list_command_send() { + uint8_t cmd_wifi_list[] = { 0xA5, 0x07, 0x00, 0x00, 0xFC }; + raw_send_to_wifi(cmd_wifi_list, COUNT(cmd_wifi_list)); +} + +static void net_msg_handle(uint8_t * msg, uint16_t msgLen) { + int wifiNameLen, wifiKeyLen, hostLen, id_len, ver_len; + + if (msgLen <= 0) return; + + // IP address + sprintf_P(ipPara.ip_addr, PSTR("%d.%d.%d.%d"), msg[0], msg[1], msg[2], msg[3]); + + // port connect state + switch (msg[6]) { + case 0x0A: wifi_link_state = WIFI_CONNECTED; break; + case 0x0E: wifi_link_state = WIFI_EXCEPTION; break; + default: wifi_link_state = WIFI_NOT_CONFIG; break; + } + + // mode + wifiPara.mode = msg[7]; + + // WiFi name + wifiNameLen = msg[8]; + wifiKeyLen = msg[9 + wifiNameLen]; + if (wifiNameLen < 32) { + ZERO(wifiPara.ap_name); + memcpy(wifiPara.ap_name, &msg[9], wifiNameLen); + + memset(&wifi_list.wifiConnectedName, 0, sizeof(wifi_list.wifiConnectedName)); + memcpy(&wifi_list.wifiConnectedName, &msg[9], wifiNameLen); + + // WiFi key + if (wifiKeyLen < 64) { + ZERO(wifiPara.keyCode); + memcpy(wifiPara.keyCode, &msg[10 + wifiNameLen], wifiKeyLen); + } + } + + cloud_para.state =msg[10 + wifiNameLen + wifiKeyLen]; + hostLen = msg[11 + wifiNameLen + wifiKeyLen]; + if (cloud_para.state) { + if (hostLen < 96) { + ZERO(cloud_para.hostUrl); + memcpy(cloud_para.hostUrl, &msg[12 + wifiNameLen + wifiKeyLen], hostLen); + } + cloud_para.port = msg[12 + wifiNameLen + wifiKeyLen + hostLen] + (msg[13 + wifiNameLen + wifiKeyLen + hostLen] << 8); + } + + // ID + id_len = msg[14 + wifiNameLen + wifiKeyLen + hostLen]; + if (id_len == 20) { + ZERO(cloud_para.id); + memcpy(cloud_para.id, (const char *)&msg[15 + wifiNameLen + wifiKeyLen + hostLen], id_len); + } + ver_len = msg[15 + wifiNameLen + wifiKeyLen + hostLen + id_len]; + if (ver_len < 20) { + ZERO(wifi_firm_ver); + memcpy(wifi_firm_ver, (const char *)&msg[16 + wifiNameLen + wifiKeyLen + hostLen + id_len], ver_len); + } + + if (uiCfg.configWifi) { + if ((wifiPara.mode != gCfgItems.wifi_mode_sel) + || (strncmp(wifiPara.ap_name, (const char *)uiCfg.wifi_name, 32) != 0) + || (strncmp(wifiPara.keyCode, (const char *)uiCfg.wifi_key, 64) != 0)) { + package_to_wifi(WIFI_PARA_SET, (uint8_t *)0, 0); + } + else uiCfg.configWifi = false; + } + if (cfg_cloud_flag == 1) { + if (((cloud_para.state >> 4) != (char)gCfgItems.cloud_enable) + || (strncmp(cloud_para.hostUrl, (const char *)uiCfg.cloud_hostUrl, 96) != 0) + || (cloud_para.port != uiCfg.cloud_port) + ) package_to_wifi(WIFI_CLOUD_CFG, (uint8_t *)0, 0); + else + cfg_cloud_flag = 0; + } +} + +static void wifi_list_msg_handle(uint8_t * msg, uint16_t msgLen) { + int wifiNameLen,wifiMsgIdex = 1; + int8_t wifi_name_is_same = 0; + int8_t i, j; + int8_t wifi_name_num = 0; + uint8_t *str = 0; + int8_t valid_name_num; + + if (msgLen <= 0) return; + if (disp_state == KEYBOARD_UI) return; + + wifi_list.getNameNum = msg[0]; + + if (wifi_list.getNameNum < 20) { + uiCfg.command_send = true; + ZERO(wifi_list.wifiName); + wifi_name_num = wifi_list.getNameNum; + valid_name_num = 0; + str = wifi_list.wifiName[0]; + + if (wifi_list.getNameNum > 0) wifi_list.currentWifipage = 1; + + for (i = 0; i < wifi_list.getNameNum; i++) { + wifiNameLen = msg[wifiMsgIdex++]; + if (wifiNameLen < 32) { + memset(str, 0, WIFI_NAME_BUFFER_SIZE); + memcpy(str, &msg[wifiMsgIdex], wifiNameLen); + for (j = 0; j < valid_name_num; j++) { + if (strcmp((const char *)str, (const char *)wifi_list.wifiName[j]) == 0) { + wifi_name_is_same = 1; + break; + } + } + + if (wifi_name_is_same != 1 && str[0] > 0x80) + wifi_name_is_same = 1; + + if (wifi_name_is_same == 1) { + wifi_name_is_same = 0; + wifiMsgIdex += wifiNameLen; + wifiMsgIdex += 1; + wifi_name_num--; + //i--; + continue; + } + if (i < WIFI_TOTAL_NUMBER - 1) + str = wifi_list.wifiName[++valid_name_num]; + } + wifiMsgIdex += wifiNameLen; + wifi_list.RSSI[i] = msg[wifiMsgIdex++]; + } + wifi_list.getNameNum = wifi_name_num; + wifi_list.getPage = wifi_list.getNameNum / NUMBER_OF_PAGE + ((wifi_list.getNameNum % NUMBER_OF_PAGE) != 0); + wifi_list.nameIndex = 0; + + if (disp_state == WIFI_LIST_UI) disp_wifi_list(); + } +} + +static void gcode_msg_handle(uint8_t * msg, 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'); + if (*msg == 'N') { + index_s = (char *)strchr((char *)msg, ' '); + while (*index_s == ' ') index_s++; + } + while ((index_e != 0) && ((int)index_s < (int)index_e)) { + if ((int)(index_e - index_s) < (int)sizeof(gcodeBuf)) { + ZERO(gcodeBuf); + memcpy(gcodeBuf, index_s, index_e - index_s + 1); + wifi_gcode_exec(gcodeBuf); + } + while ((*index_e == '\r') || (*index_e == '\n')) index_e++; + index_s = index_e; + index_e = (char *)strchr(index_s, '\n'); + } +} + +void utf8_2_unicode(uint8_t *source, uint8_t Len) { + uint8_t i = 0, char_i = 0, char_byte_num = 0; + uint16_t u16_h, u16_m, u16_l, u16_value; + uint8_t FileName_unicode[30]; + + ZERO(FileName_unicode); + + while (1) { + char_byte_num = source[i] & 0xF0; + if (source[i] < 0x80) { + //ASCII --1byte + FileName_unicode[char_i] = source[i]; + i += 1; + char_i += 1; + } + else if (char_byte_num == 0xC0 || char_byte_num == 0xD0) { + //--2byte + u16_h = (((uint16_t)source[i] << 8) & 0x1F00) >> 2; + u16_l = ((uint16_t)source[i + 1] & 0x003F); + u16_value = (u16_h | u16_l); + FileName_unicode[char_i] = (uint8_t)((u16_value & 0xFF00) >> 8); + FileName_unicode[char_i + 1] = (uint8_t)(u16_value & 0x00FF); + i += 2; + char_i += 2; + } + else if (char_byte_num == 0xE0) { + //--3byte + u16_h = (((uint16_t)source[i] << 8) & 0x0F00) << 4; + u16_m = (((uint16_t)source[i + 1] << 8) & 0x3F00) >> 2; + u16_l = ((uint16_t)source[i + 2] & 0x003F); + u16_value = (u16_h | u16_m | u16_l); + FileName_unicode[char_i] = (uint8_t)((u16_value & 0xFF00) >> 8); + FileName_unicode[char_i + 1] = (uint8_t)(u16_value & 0x00FF); + i += 3; + char_i += 2; + } + else if (char_byte_num == 0xF0) { + //--4byte + i += 4; + //char_i += 3; + } + else + break; + + if (i >= Len || i >= 255) break; + } + COPY(source, FileName_unicode); +} + +static void file_first_msg_handle(uint8_t * msg, uint16_t msgLen) { + uint8_t fileNameLen = *msg; + + if (msgLen != fileNameLen + 5) return; + + file_writer.fileLen = *((uint32_t *)(msg + 1)); + ZERO(file_writer.saveFileName); + + memcpy(file_writer.saveFileName, msg + 5, fileNameLen); + + utf8_2_unicode(file_writer.saveFileName,fileNameLen); + + ZERO(public_buf); + + if (strlen((const char *)file_writer.saveFileName) > sizeof(saveFilePath)) + return; + + ZERO(saveFilePath); + + if (gCfgItems.fileSysType == FILE_SYS_SD) { + TERN_(SDSUPPORT, card.mount()); + } + else if (gCfgItems.fileSysType == FILE_SYS_USB) { + + } + file_writer.write_index = 0; + lastFragment = -1; + + wifiTransError.flag = 0; + wifiTransError.start_tick = 0; + wifiTransError.now_tick = 0; + + TERN_(SDSUPPORT, card.closefile()); + + wifi_delay(1000); + + #if ENABLED(SDSUPPORT) + + char dosName[FILENAME_LENGTH]; + + if (!longName2DosName((const char *)file_writer.saveFileName, dosName)) { + clear_cur_ui(); + upload_result = 2; + wifiTransError.flag = 1; + wifiTransError.start_tick = getWifiTick(); + lv_draw_dialog(DIALOG_TYPE_UPLOAD_FILE); + return; + } + strcpy((char *)saveFilePath, dosName); + + card.cdroot(); + upload_file.close(); + const char * const fname = card.diveToFile(false, upload_curDir, saveFilePath); + + if (!upload_file.open(upload_curDir, fname, O_CREAT | O_APPEND | O_WRITE | O_TRUNC)) { + clear_cur_ui(); + upload_result = 2; + + wifiTransError.flag = 1; + wifiTransError.start_tick = getWifiTick(); + + lv_draw_dialog(DIALOG_TYPE_UPLOAD_FILE); + return; + } + + #endif // SDSUPPORT + + wifi_link_state = WIFI_TRANS_FILE; + + upload_result = 1; + + clear_cur_ui(); + lv_draw_dialog(DIALOG_TYPE_UPLOAD_FILE); + + lv_task_handler(); + + file_writer.tick_begin = getWifiTick(); + + file_writer.fileTransfer = 1; +} + +#define FRAG_MASK ~_BV32(31) + +static void file_fragment_msg_handle(uint8_t * msg, uint16_t msgLen) { + uint32_t frag = *((uint32_t *)msg); + if ((frag & FRAG_MASK) != (uint32_t)(lastFragment + 1)) { + ZERO(public_buf); + file_writer.write_index = 0; + wifi_link_state = WIFI_CONNECTED; + upload_result = 2; + } + else { + if (write_to_file((char *)msg + 4, msgLen - 4) < 0) { + ZERO(public_buf); + file_writer.write_index = 0; + wifi_link_state = WIFI_CONNECTED; + upload_result = 2; + return; + } + lastFragment = frag; + + if ((frag & (~FRAG_MASK)) != 0) { + wifiDmaRcvFifo.receiveEspData = false; + int res = upload_file.write(public_buf, file_writer.write_index); + if (res == -1) { + upload_file.close(); + const char * const fname = card.diveToFile(false, upload_curDir, saveFilePath); + if (upload_file.open(upload_curDir, fname, O_WRITE)) { + upload_file.setpos(&pos); + res = upload_file.write(public_buf, file_writer.write_index); + } + } + upload_file.close(); + SdFile file, *curDir; + const char * const fname = card.diveToFile(false, curDir, saveFilePath); + if (file.open(curDir, fname, O_RDWR)) { + gCfgItems.curFilesize = file.fileSize(); + file.close(); + } + else { + ZERO(public_buf); + file_writer.write_index = 0; + wifi_link_state = WIFI_CONNECTED; + upload_result = 2; + return; + } + ZERO(public_buf); + file_writer.write_index = 0; + file_writer.tick_end = getWifiTick(); + upload_time_sec = getWifiTickDiff(file_writer.tick_begin, file_writer.tick_end) / 1000; + upload_size = gCfgItems.curFilesize; + wifi_link_state = WIFI_CONNECTED; + upload_result = 3; + } + } +} + +void esp_data_parser(char *cmdRxBuf, int len) { + int32_t head_pos, tail_pos; + uint16_t cpyLen; + int16_t leftLen = len; + bool loop_again = false; + + ESP_PROTOC_FRAME esp_frame; + + while (leftLen > 0 || loop_again) { + loop_again = false; + + if (esp_msg_index != 0) { + head_pos = 0; + cpyLen = (leftLen < (int16_t)((sizeof(esp_msg_buf) - esp_msg_index)) ? leftLen : sizeof(esp_msg_buf) - esp_msg_index); + + memcpy(&esp_msg_buf[esp_msg_index], cmdRxBuf + len - leftLen, cpyLen); + + esp_msg_index += cpyLen; + + leftLen = leftLen - cpyLen; + tail_pos = charAtArray(esp_msg_buf, esp_msg_index, ESP_PROTOC_TAIL); + + if (tail_pos == -1) { + if (esp_msg_index >= sizeof(esp_msg_buf)) { + ZERO(esp_msg_buf); + esp_msg_index = 0; + } + return; + } + } + else { + head_pos = charAtArray((uint8_t const *)&cmdRxBuf[len - leftLen], leftLen, ESP_PROTOC_HEAD); + if (head_pos == -1) return; + + ZERO(esp_msg_buf); + memcpy(esp_msg_buf, &cmdRxBuf[len - leftLen + head_pos], leftLen - head_pos); + + esp_msg_index = leftLen - head_pos; + + leftLen = 0; + head_pos = 0; + tail_pos = charAtArray(esp_msg_buf, esp_msg_index, ESP_PROTOC_TAIL); + if (tail_pos == -1) { + if (esp_msg_index >= sizeof(esp_msg_buf)) { + ZERO(esp_msg_buf); + esp_msg_index = 0; + } + return; + } + } + + esp_frame.type = esp_msg_buf[1]; + if ( esp_frame.type != ESP_TYPE_NET + && esp_frame.type != ESP_TYPE_GCODE + && esp_frame.type != ESP_TYPE_FILE_FIRST + && esp_frame.type != ESP_TYPE_FILE_FRAGMENT + && esp_frame.type != ESP_TYPE_WIFI_LIST + ) { + ZERO(esp_msg_buf); + esp_msg_index = 0; + return; + } + + esp_frame.dataLen = esp_msg_buf[2] + (esp_msg_buf[3] << 8); + + if ((int)(4 + esp_frame.dataLen) > (int)(sizeof(esp_msg_buf))) { + ZERO(esp_msg_buf); + esp_msg_index = 0; + return; + } + + if (esp_msg_buf[4 + esp_frame.dataLen] != ESP_PROTOC_TAIL) { + if (esp_msg_index >= sizeof(esp_msg_buf)) { + ZERO(esp_msg_buf); + esp_msg_index = 0; + } + return; + } + + esp_frame.data = &esp_msg_buf[4]; + switch (esp_frame.type) { + case ESP_TYPE_NET: + net_msg_handle(esp_frame.data, esp_frame.dataLen); + break; + case ESP_TYPE_GCODE: + gcode_msg_handle(esp_frame.data, esp_frame.dataLen); + break; + case ESP_TYPE_FILE_FIRST: + file_first_msg_handle(esp_frame.data, esp_frame.dataLen); + break; + case ESP_TYPE_FILE_FRAGMENT: + file_fragment_msg_handle(esp_frame.data, esp_frame.dataLen); + break; + case ESP_TYPE_WIFI_LIST: + wifi_list_msg_handle(esp_frame.data, esp_frame.dataLen); + break; + default: break; + } + + esp_msg_index = cut_msg_head(esp_msg_buf, esp_msg_index, esp_frame.dataLen + 5); + if (esp_msg_index > 0) { + if (charAtArray(esp_msg_buf, esp_msg_index, ESP_PROTOC_HEAD) == -1) { + ZERO(esp_msg_buf); + esp_msg_index = 0; + return; + } + if ((charAtArray(esp_msg_buf, esp_msg_index, ESP_PROTOC_HEAD) != -1) && (charAtArray(esp_msg_buf, esp_msg_index, ESP_PROTOC_TAIL) != -1)) + loop_again = true; + } + } +} + +int32_t tick_net_time1, tick_net_time2; +int32_t readWifiFifo(uint8_t *retBuf, uint32_t bufLen) { + unsigned char tmpR = wifiDmaRcvFifo.read_cur; + if (bufLen >= UDISKBUFLEN && wifiDmaRcvFifo.state[tmpR] == udisk_buf_full) { + memcpy(retBuf, (unsigned char *)wifiDmaRcvFifo.bufferAddr[tmpR], UDISKBUFLEN); + wifiDmaRcvFifo.state[tmpR] = udisk_buf_empty; + wifiDmaRcvFifo.read_cur = (tmpR + 1) % TRANS_RCV_FIFO_BLOCK_NUM; + return UDISKBUFLEN; + } + return 0; +} + +void stopEspTransfer() { + if (wifi_link_state == WIFI_TRANS_FILE) + wifi_link_state = WIFI_CONNECTED; + + TERN_(SDSUPPORT, card.closefile()); + + if (upload_result != 3) { + wifiTransError.flag = 1; + wifiTransError.start_tick = getWifiTick(); + card.removeFile((const char *)saveFilePath); + } + + wifi_delay(200); + WIFI_IO1_SET(); + + // disable dma + #ifdef __STM32F1__ + dma_clear_isr_bits(DMA1, DMA_CH5); + bb_peri_set_bit(&USART1_BASE->CR3, USART_CR3_DMAR_BIT, 0); + dma_disable(DMA1, DMA_CH5); + #else + // First, abort any running dma + HAL_DMA_Abort(&wifiUsartDMArx); + // DeInit objects + HAL_DMA_DeInit(&wifiUsartDMArx); + #endif + + wifi_delay(200); + changeFlashMode(true); // Set SPI flash to use DMA mode + esp_port_begin(1); + wifi_delay(200); + + W25QXX.init(SPI_QUARTER_SPEED); + + TERN_(HAS_TFT_LVGL_UI_SPI, SPI_TFT.spi_init(SPI_FULL_SPEED)); + TERN_(HAS_SERVOS, servo_init()); + TERN_(HAS_Z_SERVO_PROBE, probe.servo_probe_init()); + + if (wifiTransError.flag != 0x1) WIFI_IO1_RESET(); +} + +void wifi_rcv_handle() { + int32_t len = 0; + uint8_t ucStr[(UART_RX_BUFFER_SIZE) + 1] = {0}; + int8_t getDataF = 0; + if (wifi_link_state == WIFI_TRANS_FILE) { + #if 0 + if (WIFISERIAL.available() == UART_RX_BUFFER_SIZE) { + for (uint16_t i=0;i 0) { + esp_data_parser((char *)ucStr, len); + if (wifi_link_state == WIFI_CONNECTED) { + clear_cur_ui(); + lv_draw_dialog(DIALOG_TYPE_UPLOAD_FILE); + stopEspTransfer(); + } + getDataF = 1; + } + #ifdef __STM32F1__ + if (esp_state == TRANSFER_STORE) { + if (storeRcvData(WIFISERIAL.wifiRxBuf, UART_RX_BUFFER_SIZE)) { + esp_state = TRANSFERRING; + esp_dma_pre(); + if (wifiTransError.flag != 0x1) WIFI_IO1_RESET(); + } + else WIFI_IO1_SET(); + } + #endif + } + else { + len = readWifiBuf((int8_t *)ucStr, UART_RX_BUFFER_SIZE); + if (len > 0) { + esp_data_parser((char *)ucStr, len); + if (wifi_link_state == WIFI_TRANS_FILE) { + changeFlashMode(false); // Set SPI flash to use non-DMA mode + wifi_delay(10); + esp_port_begin(0); + wifi_delay(10); + tick_net_time1 = 0; + #ifndef __STM32F1__ + wifiDmaRcvFifo.receiveEspData = true; + return; + #endif + } + if (wifiTransError.flag != 0x1) WIFI_IO1_RESET(); + getDataF = 1; + } + if (need_ok_later && !queue.ring_buffer.full()) { + need_ok_later = false; + send_to_wifi((uint8_t *)"ok\r\n", strlen("ok\r\n")); + } + } + + if (getDataF == 1) + tick_net_time1 = getWifiTick(); + else { + tick_net_time2 = getWifiTick(); + + if (wifi_link_state == WIFI_TRANS_FILE) { + if (tick_net_time1 && getWifiTickDiff(tick_net_time1, tick_net_time2) > 8000) { + wifi_link_state = WIFI_CONNECTED; + upload_result = 2; + clear_cur_ui(); + stopEspTransfer(); + lv_draw_dialog(DIALOG_TYPE_UPLOAD_FILE); + } + } + if (tick_net_time1 && getWifiTickDiff(tick_net_time1, tick_net_time2) > 10000) + wifi_link_state = WIFI_NOT_CONFIG; + + if (tick_net_time1 && getWifiTickDiff(tick_net_time1, tick_net_time2) > 120000) { + wifi_link_state = WIFI_NOT_CONFIG; + wifi_reset(); + tick_net_time1 = getWifiTick(); + } + } + + if (wifiTransError.flag == 0x1) { + wifiTransError.now_tick = getWifiTick(); + if (getWifiTickDiff(wifiTransError.start_tick, wifiTransError.now_tick) > WAIT_ESP_TRANS_TIMEOUT_TICK) { + wifiTransError.flag = 0; + WIFI_IO1_RESET(); + } + } +} + +void wifi_looping() { + do { + wifi_rcv_handle(); + watchdog_refresh(); + } while (wifi_link_state == WIFI_TRANS_FILE); +} + +void mks_esp_wifi_init() { + wifi_link_state = WIFI_NOT_CONFIG; + + SET_OUTPUT(WIFI_RESET_PIN); + WIFI_SET(); + SET_OUTPUT(WIFI_IO1_PIN); + SET_INPUT_PULLUP(WIFI_IO0_PIN); + WIFI_IO1_SET(); + + esp_state = TRANSFER_IDLE; + esp_port_begin(1); + watchdog_refresh(); + wifi_reset(); + + #if 0 + if (update_flag == 0) { + res = f_open(&esp_upload.uploadFile, ESP_WEB_FIRMWARE_FILE, FA_OPEN_EXISTING | FA_READ); + if (res == FR_OK) { + f_close(&esp_upload.uploadFile); + + wifi_delay(2000); + + if (usartFifoAvailable((SZ_USART_FIFO *)&WifiRxFifo) < 20) return; + + clear_cur_ui(); + + draw_dialog(DIALOG_TYPE_UPDATE_ESP_FIRMWARE); + if (wifi_upload(1) >= 0) { + f_unlink("1:/MKS_WIFI_CUR"); + f_rename(ESP_WEB_FIRMWARE_FILE,"/MKS_WIFI_CUR"); + } + draw_return_ui(); + update_flag = 1; + } + } + + if (update_flag == 0) { + res = f_open(&esp_upload.uploadFile, ESP_WEB_FILE, FA_OPEN_EXISTING | FA_READ); + if (res == FR_OK) { + f_close(&esp_upload.uploadFile); + + wifi_delay(2000); + + if (usartFifoAvailable((SZ_USART_FIFO *)&WifiRxFifo) < 20) return; + + clear_cur_ui(); + + draw_dialog(DIALOG_TYPE_UPDATE_ESP_DATA); + + if (wifi_upload(2) >= 0) { + f_unlink("1:/MKS_WEB_CONTROL_CUR"); + f_rename(ESP_WEB_FILE,"/MKS_WEB_CONTROL_CUR"); + } + draw_return_ui(); + } + } + #endif + + wifiPara.decodeType = WIFI_DECODE_TYPE; + wifiPara.baud = 115200; + wifi_link_state = WIFI_NOT_CONFIG; +} + +void mks_wifi_firmware_update() { + watchdog_refresh(); + card.openFileRead((char *)ESP_FIRMWARE_FILE); + + if (card.isFileOpen()) { + card.closefile(); + + wifi_delay(2000); + watchdog_refresh(); + if (usartFifoAvailable((SZ_USART_FIFO *)&WifiRxFifo) < 20) return; + + clear_cur_ui(); + + lv_draw_dialog(DIALOG_TYPE_UPDATE_ESP_FIRMWARE); + + lv_task_handler(); + watchdog_refresh(); + + if (wifi_upload(0) >= 0) { + card.removeFile((char *)ESP_FIRMWARE_FILE_RENAME); + SdFile file, *curDir; + const char * const fname = card.diveToFile(false, curDir, ESP_FIRMWARE_FILE); + if (file.open(curDir, fname, O_READ)) { + file.rename(curDir, (char *)ESP_FIRMWARE_FILE_RENAME); + file.close(); + } + } + clear_cur_ui(); + } +} + +void get_wifi_commands() { + static char wifi_line_buffer[MAX_CMD_SIZE]; + static bool wifi_comment_mode = false; + static int wifi_read_count = 0; + + if (espGcodeFifo.wait_tick > 5) { + while (!queue.ring_buffer.full() && (espGcodeFifo.r != espGcodeFifo.w)) { + + espGcodeFifo.wait_tick = 0; + + char wifi_char = espGcodeFifo.Buffer[espGcodeFifo.r]; + + espGcodeFifo.r = (espGcodeFifo.r + 1) % WIFI_GCODE_BUFFER_SIZE; + + /** + * If the character ends the line + */ + if (wifi_char == '\n' || wifi_char == '\r') { + + wifi_comment_mode = false; // end of line == end of comment + + if (!wifi_read_count) continue; // skip empty lines + + wifi_line_buffer[wifi_read_count] = 0; // terminate string + wifi_read_count = 0; //reset buffer + + char* command = wifi_line_buffer; + while (*command == ' ') command++; // skip any leading spaces + + // Movement commands alert when stopped + if (IsStopped()) { + char* gpos = strchr(command, 'G'); + if (gpos) { + switch (strtol(gpos + 1, nullptr, 10)) { + case 0 ... 1: + TERN_(ARC_SUPPORT, case 2 ... 3:) + TERN_(BEZIER_CURVE_SUPPORT, case 5:) + SERIAL_ECHOLNPGM(STR_ERR_STOPPED); + LCD_MESSAGEPGM(MSG_STOPPED); + break; + } + } + } + + #if DISABLED(EMERGENCY_PARSER) + // Process critical commands early + if (strcmp(command, "M108") == 0) { + wait_for_heatup = false; + TERN_(HAS_LCD_MENU, wait_for_user = false); + } + if (strcmp(command, "M112") == 0) kill(M112_KILL_STR, nullptr, true); + if (strcmp(command, "M410") == 0) quickstop_stepper(); + #endif + + // Add the command to the queue + queue.enqueue_one_P(wifi_line_buffer); + } + else if (wifi_read_count >= MAX_CMD_SIZE - 1) { + + } + else { // it's not a newline, carriage return or escape char + if (wifi_char == ';') wifi_comment_mode = true; + if (!wifi_comment_mode) wifi_line_buffer[wifi_read_count++] = wifi_char; + } + } + } // queue has space, serial has data + else + espGcodeFifo.wait_tick++; +} + +int readWifiBuf(int8_t *buf, int32_t len) { + int i = 0; + while (i < len && WIFISERIAL.available()) + buf[i++] = WIFISERIAL.read(); + return i; +} + +int usartFifoAvailable(SZ_USART_FIFO *fifo) { return WIFISERIAL.available(); } + +#endif // HAS_TFT_LVGL_UI && MKS_WIFI_MODULE diff --git a/Marlin/src/lcd/extui/lib/mks_ui/wifi_module.h b/Marlin/src/lcd/extui/mks_ui/wifi_module.h similarity index 82% rename from Marlin/src/lcd/extui/lib/mks_ui/wifi_module.h rename to Marlin/src/lcd/extui/mks_ui/wifi_module.h index 0b402a3adb10..d02716e43549 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/wifi_module.h +++ b/Marlin/src/lcd/extui/mks_ui/wifi_module.h @@ -25,7 +25,7 @@ extern "C" { /* C-declarations for C++ */ #endif -#include "../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #include #include @@ -34,11 +34,6 @@ #define UART_RX_BUFFER_SIZE 1024 #define UART_FIFO_BUFFER_SIZE 1024 -#define ESP_WIFI 0x02 - -#define AP_MODEL 0x01 -#define STA_MODEL 0x02 - #define WIFI_DECODE_TYPE 1 #define IP_DHCP_FLAG 1 @@ -66,9 +61,10 @@ typedef enum{ udisk_buf_full, } UDISK_DATA_BUFFER_STATE; -#define TRANS_RCV_FIFO_BLOCK_NUM 8 +#define TRANS_RCV_FIFO_BLOCK_NUM 14 typedef struct { + bool receiveEspData; unsigned char *bufferAddr[TRANS_RCV_FIFO_BLOCK_NUM]; unsigned char *p; UDISK_DATA_BUFFER_STATE state[TRANS_RCV_FIFO_BLOCK_NUM]; @@ -141,7 +137,7 @@ typedef enum { typedef enum { TRANSFER_IDLE, - TRANSFERING, + TRANSFERRING, TRANSFER_STORE, } TRANSFER_STATE; extern volatile TRANSFER_STATE esp_state; @@ -164,16 +160,16 @@ typedef enum { typedef struct { uint32_t uart_read_point; uint32_t uart_write_point; - uint8_t uartTxBuffer[UART_FIFO_BUFFER_SIZE]; + //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) typedef struct { - uint8_t wait_tick; - uint8_t Buffer[WIFI_GCODE_BUFFER_SIZE]; - uint32_t r; - uint32_t w; + uint8_t wait_tick; + uint8_t Buffer[WIFI_GCODE_BUFFER_SIZE]; + uint32_t r; + uint32_t w; } WIFI_GCODE_BUFFER; extern volatile WIFI_STATE wifi_link_state; @@ -183,19 +179,22 @@ extern CLOUD_PARA cloud_para; extern WIFI_GCODE_BUFFER espGcodeFifo; -extern uint32_t getWifiTick(); -extern uint32_t getWifiTickDiff(int32_t lastTick, int32_t curTick); - -extern void mks_esp_wifi_init(); -extern int cfg_cloud_flag; -extern int send_to_wifi(char *buf, int len); -extern void wifi_looping(); -extern int raw_send_to_wifi(char *buf, int len); -extern int package_to_wifi(WIFI_RET_TYPE type,char *buf, int len); -extern void get_wifi_list_command_send(); -extern void get_wifi_commands(); -extern int readWifiBuf(int8_t *buf, int32_t len); -extern int storeRcvData(int32_t len); +uint32_t getWifiTick(); +uint32_t getWifiTickDiff(int32_t lastTick, int32_t curTick); + +void mks_esp_wifi_init(); +extern int cfg_cloud_flag; +int send_to_wifi(uint8_t *buf, int len); +void wifi_looping(); +int raw_send_to_wifi(uint8_t *buf, 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(); +int readWifiBuf(int8_t *buf, int32_t len); +void mks_wifi_firmware_update(); +int usartFifoAvailable(SZ_USART_FIFO *fifo); +int readUsartFifo(SZ_USART_FIFO *fifo, int8_t *buf, int32_t len); +void esp_port_begin(uint8_t interrupt); #ifdef __cplusplus } /* C-declarations for C++ */ diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp b/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp new file mode 100644 index 000000000000..4a5f08edaaea --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp @@ -0,0 +1,683 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if BOTH(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) + +#include "draw_ui.h" +#include "wifi_module.h" +#include "wifi_upload.h" + +#include "../../../MarlinCore.h" +#include "../../../sd/cardreader.h" + +#define WIFI_SET() WRITE(WIFI_RESET_PIN, HIGH); +#define WIFI_RESET() WRITE(WIFI_RESET_PIN, LOW); +#define WIFI_IO1_SET() WRITE(WIFI_IO1_PIN, HIGH); +#define WIFI_IO1_RESET() WRITE(WIFI_IO1_PIN, LOW); + +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); + +#define ARRAY_SIZE(a) sizeof(a) / sizeof((a)[0]) + +//typedef signed char bool; + +// ESP8266 command codes +const uint8_t ESP_FLASH_BEGIN = 0x02; +const uint8_t ESP_FLASH_DATA = 0x03; +const uint8_t ESP_FLASH_END = 0x04; +const uint8_t ESP_MEM_BEGIN = 0x05; +const uint8_t ESP_MEM_END = 0x06; +const uint8_t ESP_MEM_DATA = 0x07; +const uint8_t ESP_SYNC = 0x08; +const uint8_t ESP_WRITE_REG = 0x09; +const uint8_t ESP_READ_REG = 0x0A; + +// MAC address storage locations +const uint32_t ESP_OTP_MAC0 = 0x3FF00050; +const uint32_t ESP_OTP_MAC1 = 0x3FF00054; +const uint32_t ESP_OTP_MAC2 = 0x3FF00058; +const uint32_t ESP_OTP_MAC3 = 0x3FF0005C; + +const size_t EspFlashBlockSize = 0x0400; // 1K byte blocks + +const uint8_t ESP_IMAGE_MAGIC = 0xE9; +const uint8_t ESP_CHECKSUM_MAGIC = 0xEF; + +const uint32_t ESP_ERASE_CHIP_ADDR = 0x40004984; // &SPIEraseChip +const uint32_t ESP_SEND_PACKET_ADDR = 0x40003C80; // &send_packet +const uint32_t ESP_SPI_READ_ADDR = 0x40004B1C; // &SPIRead +const uint32_t ESP_UNKNOWN_ADDR = 0x40001121; // not used +const uint32_t ESP_USER_DATA_RAM_ADDR = 0x3FFE8000; // &user data ram +const uint32_t ESP_IRAM_ADDR = 0x40100000; // instruction RAM +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 SdFile update_file, *update_curDir; + +// Messages corresponding to result codes, should make sense when followed by " error" +const char *resultMessages[] = { + "no", + "timeout", + "comm write", + "connect", + "bad reply", + "file read", + "empty file", + "response header", + "slip frame", + "slip state", + "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. +static const uint32_t uploadBaudRates[] = { 460800, 230400, 115200, 74880 }; + +signed char IsReady() { + return esp_upload.state == upload_idle; +} + +void uploadPort_write(const uint8_t *buf, const size_t len) { + for (size_t i = 0; i < len; i++) + WIFISERIAL.write(*(buf + i)); +} + +char uploadPort_read() { + uint8_t retChar; + retChar = WIFISERIAL.read(); + return _MAX(retChar, 0); +} + +int uploadPort_available() { + return usartFifoAvailable(&WifiRxFifo); +} + +void uploadPort_begin() { + esp_port_begin(1); +} + +void uploadPort_close() { + //WIFI_COM.end(); + //WIFI_COM.begin(115200, true); + esp_port_begin(0); +} + +void flushInput() { + while (uploadPort_available() != 0) { + (void)uploadPort_read(); + //IWDG_ReloadCounter(); + } +} + +// Extract 1-4 bytes of a value in little-endian order from a buffer beginning at a specified offset +uint32_t getData(unsigned byteCnt, const uint8_t *buf, int ofst) { + uint32_t val = 0; + if (buf && byteCnt) { + unsigned int shiftCnt = 0; + NOMORE(byteCnt, 4U); + do { + val |= (uint32_t)buf[ofst++] << shiftCnt; + shiftCnt += 8; + } while (--byteCnt); + } + return val; +} + +// Put 1-4 bytes of a value in little-endian order into a buffer beginning at a specified offset. +void putData(uint32_t val, unsigned byteCnt, uint8_t *buf, int ofst) { + if (buf && byteCnt) { + NOMORE(byteCnt, 4U); + do { + buf[ofst++] = (uint8_t)(val & 0xFF); + val >>= 8; + } while (--byteCnt); + } +} + +// 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 + *data = uploadPort_read(); + + if (!slipDecode) return 1; + + if (*data == 0xC0) return -1; // This shouldn't happen + if (*data != 0xDB) return 1; // If not the SLIP escape, we're done + + // SLIP escape, check availability of subsequent byte + if (uploadPort_available() == 0) return -2; + + // process the escaped byte + *data = uploadPort_read(); + if (*data == 0xDC) { *data = 0xC0; return 2; } + if (*data == 0xDD) { *data = 0xDB; return 2; } + + return -3; // invalid +} +// When we write a sync packet, there must be no gaps between most of the characters. +// So use this function, which does a block write to the UART buffer in the latest CoreNG. +void _writePacketRaw(const uint8_t *buf, size_t len) { + uploadPort_write(buf, len); +} + +// Write a byte to the serial port optionally SLIP encoding. Return the number of bytes actually written. +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) { + if (b == 0xC0) { + WriteByteRaw(0xDB); + WriteByteRaw(0xDC); + } + else if (b == 0xDB) { + 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) { + typedef enum { + begin = 0, + header, + body, + end, + done + } PacketState; + + uint8_t resp, opRet; + + const size_t headerLength = 8; + + uint32_t startTime = getWifiTick(); + uint8_t hdr[headerLength]; + uint16_t hdrIdx = 0; + + uint16_t bodyIdx = 0; + uint8_t respBuf[2]; + + // wait for the response + uint16_t needBytes = 1; + + PacketState state = begin; + + *bodyLen = 0; + + while (state != done) { + uint8_t c; + EspUploadResult stat; + + //IWDG_ReloadCounter(); + watchdog_refresh(); + + if (getWifiTickDiff(startTime, getWifiTick()) > msTimeout) + return timeout; + + if (uploadPort_available() < needBytes) { + // insufficient data available + // preferably, return to Spin() here + continue; + } + + // sufficient bytes have been received for the current state, process them + switch (state) { + case begin: // expecting frame start + c = uploadPort_read(); + if (c != (uint8_t)0xC0) break; + state = header; + needBytes = 2; + break; + case end: // expecting frame end + c = uploadPort_read(); + if (c != (uint8_t)0xC0) return slipFrame; + state = done; + break; + + case header: // reading an 8-byte header + case body: { // reading the response body + int rslt; + // retrieve a byte with SLIP decoding + rslt = ReadByte(&c, 1); + if (rslt != 1 && rslt != 2) { + // some error occurred + stat = (rslt == 0 || rslt == -2) ? slipData : slipFrame; + return stat; + } + else if (state == header) { + //store the header byte + hdr[hdrIdx++] = c; + if (hdrIdx >= headerLength) { + // get the body length, prepare a buffer for it + *bodyLen = (uint16_t)getData(2, hdr, 2); + + // extract the value, if requested + if (valp) + *valp = getData(4, hdr, 4); + + if (*bodyLen != 0) + state = body; + else { + needBytes = 1; + state = end; + } + } + } + else { + // Store the response body byte, check for completion + if (bodyIdx < ARRAY_SIZE(respBuf)) + respBuf[bodyIdx] = c; + + if (++bodyIdx >= *bodyLen) { + needBytes = 1; + state = end; + } + } + } break; + + default: return slipState; // this shouldn't happen + } + } + + // Extract elements from the header + resp = (uint8_t)getData(1, hdr, 0); + opRet = (uint8_t)getData(1, hdr, 1); + + // Sync packets often provoke a response with a zero opcode instead of ESP_SYNC + if (resp != 0x01 || opRet != op) return respHeader; + + return success; +} + +// 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; + while (len != 0) { + if (*data == 0xC0) { + outBuf[outIndex++] = 0xDB; + outBuf[outIndex++] = 0xDC; + } + else if (*data == 0xDB) { + outBuf[outIndex++] = 0xDB; + outBuf[outIndex++] = 0xDD; + } + else { + outBuf[outIndex++] = *data; + } + data++; + --len; + } + uploadPort_write((const uint8_t *)outBuf, outIndex); +} + +// Send a packet to the serial port while performing SLIP framing. The packet data comprises a header and an optional data block. +// A SLIP packet begins and ends with 0xC0. The data encapsulated has the bytes +// 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 + _writePacket(hdr, hdrLen); // send the header + _writePacket(data, dataLen); // send the data block + 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 + _writePacketRaw(hdr, hdrLen); // send the header + _writePacketRaw(data, dataLen); // send the data block in raw mode + WriteByteRaw(0xC0); // send the packet end character +} + +// Send a command to the attached device together with the supplied data, if any. +// The data is supplied via a list of one or more segments. +void sendCommand(uint8_t op, uint32_t checkVal, const uint8_t *data, size_t dataLen) { + // populate the header + uint8_t hdr[8]; + putData(0, 1, hdr, 0); + putData(op, 1, hdr, 1); + putData(dataLen, 2, hdr, 2); + putData(checkVal, 4, hdr, 4); + + // send the packet + if (op == ESP_SYNC) + writePacketRaw(hdr, sizeof(hdr), data, dataLen); + else + writePacket(hdr, sizeof(hdr), data, dataLen); +} + +// 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) { + size_t bodyLen; + EspUploadResult stat; + + sendCommand(op, checkVal, data, dataLen); + + stat = readPacket(op, valp, &bodyLen, msTimeout); + if (stat == success && bodyLen != 2) + stat = badReply; + + return stat; +} + +// 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) { + uint8_t buf[36]; + EspUploadResult stat; + int i ; + + // compose the data for the sync attempt + memset(buf, 0x55, sizeof(buf)); + buf[0] = 0x07; + buf[1] = 0x07; + buf[2] = 0x12; + buf[3] = 0x20; + + stat = doCommand(ESP_SYNC, buf, sizeof(buf), 0, 0, timeout); + + // If we got a response other than sync, discard it and wait for a sync response. This happens at higher baud rates. + for (i = 0; i < 10 && stat == respHeader; ++i) { + size_t bodyLen; + stat = readPacket(ESP_SYNC, 0, &bodyLen, timeout); + } + + if (stat == success) { + // Read and discard additional replies + for (;;) { + size_t bodyLen; + EspUploadResult rc = readPacket(ESP_SYNC, 0, &bodyLen, defaultTimeout); + watchdog_refresh(); + if (rc != success || bodyLen != 2) break; + } + } + //DEBUG + //else debug//printf("stat=%d\n", (int)stat); + return stat; +} + +// Send a command to the device to begin the Flash process. +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; + + blkCnt = (size + EspFlashBlockSize - 1) / EspFlashBlockSize; + + // ensure that the address is on a block boundary + addr &= ~(EspFlashBlockSize - 1); + + // begin the Flash process + putData(size, 4, buf, 0); + putData(blkCnt, 4, buf, 4); + putData(EspFlashBlockSize, 4, buf, 8); + putData(addr, 4, buf, 12); + + timeout = (size != 0) ? eraseTimeout : defaultTimeout; + return doCommand(ESP_FLASH_BEGIN, buf, sizeof(buf), 0, 0, timeout); +} + +// Send a command to the device to terminate the Flash process +EspUploadResult flashFinish(signed char reboot) { + uint8_t buf[4]; + putData(reboot ? 0 : 1, 4, buf, 0); + return doCommand(ESP_FLASH_END, buf, sizeof(buf), 0, 0, defaultTimeout); +} + +// Compute the checksum of a block of data +uint16_t checksum(const uint8_t *data, uint16_t dataLen, uint16_t cksum) { + if (data) while (dataLen--) cksum ^= (uint16_t)*data++; + return cksum; +} + +EspUploadResult flashWriteBlock(uint16_t flashParmVal, uint16_t flashParmMask) { + const uint32_t blkSize = EspFlashBlockSize; + int i; + + // Allocate a data buffer for the combined header and block data + const uint16_t hdrOfst = 0; + const uint16_t dataOfst = 16; + const uint16_t blkBufSize = dataOfst + blkSize; + uint32_t blkBuf32[blkBufSize/4]; + uint8_t * const blkBuf = (uint8_t*)(blkBuf32); + uint32_t cnt; + uint16_t cksum; + EspUploadResult stat; + + // Prepare the header for the block + putData(blkSize, 4, blkBuf, hdrOfst + 0); + putData(esp_upload.uploadBlockNumber, 4, blkBuf, hdrOfst + 4); + putData(0, 4, blkBuf, hdrOfst + 8); + putData(0, 4, blkBuf, hdrOfst + 12); + + // Get the data for the block + cnt = update_file.read(blkBuf + dataOfst, blkSize); //->Read(reinterpret_cast(blkBuf + dataOfst), blkSize); + if (cnt != blkSize) { + if (update_file.curPosition() == esp_upload.fileSize) { + // partial last block, fill the remainder + memset(blkBuf + dataOfst + cnt, 0xFF, blkSize - cnt); + } + else + return fileRead; + } + + // Patch the flash parameters into the first block if it is loaded at address 0 + if (esp_upload.uploadBlockNumber == 0 && esp_upload.uploadAddress == 0 && blkBuf[dataOfst] == ESP_IMAGE_MAGIC && flashParmMask != 0) { + // update the Flash parameters + uint32_t flashParm = getData(2, blkBuf + dataOfst + 2, 0) & ~(uint32_t)flashParmMask; + putData(flashParm | flashParmVal, 2, blkBuf + dataOfst + 2, 0); + } + + // Calculate the block checksum + cksum = checksum(blkBuf + dataOfst, blkSize, ESP_CHECKSUM_MAGIC); + + for (i = 0; i < 3; i++) + if ((stat = doCommand(ESP_FLASH_DATA, blkBuf, blkBufSize, cksum, 0, blockWriteTimeout)) == success) + break; + return stat; +} + +void upload_spin() { + + switch (esp_upload.state) { + case resetting: + if (esp_upload.connectAttemptNumber == 9) { + esp_upload.uploadResult = connected; + esp_upload.state = done; + } + else { + uploadPort_begin(); + wifi_delay(2000); + flushInput(); + esp_upload.lastAttemptTime = esp_upload.lastResetTime = getWifiTick(); + esp_upload.state = connecting; + } + break; + + case connecting: + if ((getWifiTickDiff(esp_upload.lastAttemptTime, getWifiTick()) >= connectAttemptInterval) && (getWifiTickDiff(esp_upload.lastResetTime, getWifiTick()) >= 500)) { + EspUploadResult res = Sync(5000); + esp_upload.lastAttemptTime = getWifiTick(); + if (res == success) + esp_upload.state = erasing; + else { + esp_upload.connectAttemptNumber++; + if (esp_upload.connectAttemptNumber % retriesPerReset == 0) + esp_upload.state = resetting; + } + } + break; + + case erasing: + if (getWifiTickDiff(esp_upload.lastAttemptTime, getWifiTick()) >= blockWriteInterval) { + uint32_t eraseSize; + const uint32_t sectorsPerBlock = 16; + const uint32_t sectorSize = 4096; + const uint32_t numSectors = (esp_upload.fileSize + sectorSize - 1)/sectorSize; + const uint32_t startSector = esp_upload.uploadAddress/sectorSize; + + uint32_t headSectors = sectorsPerBlock - (startSector % sectorsPerBlock); + NOMORE(headSectors, numSectors); + + eraseSize = (numSectors < 2 * headSectors) + ? (numSectors + 1) / 2 * sectorSize + : (numSectors - headSectors) * sectorSize; + + esp_upload.uploadResult = flashBegin(esp_upload.uploadAddress, eraseSize); + if (esp_upload.uploadResult == success) { + esp_upload.uploadBlockNumber = 0; + esp_upload.uploadNextPercentToReport = percentToReportIncrement; + esp_upload.lastAttemptTime = getWifiTick(); + esp_upload.state = uploading; + } + else + esp_upload.state = done; + } + break; + + 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; + const uint32_t blkCnt = (esp_upload.fileSize + EspFlashBlockSize - 1) / EspFlashBlockSize; + if (esp_upload.uploadBlockNumber < blkCnt) { + esp_upload.uploadResult = flashWriteBlock(0, 0); + esp_upload.lastAttemptTime = getWifiTick(); + if (esp_upload.uploadResult != success) + esp_upload.state = done; + percentComplete = (100 * esp_upload.uploadBlockNumber)/blkCnt; + ++esp_upload.uploadBlockNumber; + if (percentComplete >= esp_upload.uploadNextPercentToReport) + esp_upload.uploadNextPercentToReport += percentToReportIncrement; + } + else + esp_upload.state = done; + } + break; + + case done: + update_file.close(); + esp_upload.state = upload_idle; + break; + + default: break; + } +} + +// Try to upload the given file at the given 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; + + esp_upload.fileSize = update_file.fileSize(); + + if (esp_upload.fileSize == 0) { + update_file.close(); + return; + } + + esp_upload.uploadAddress = address; + esp_upload.connectAttemptNumber = 0; + esp_upload.state = resetting; +} + +static const uint32_t FirmwareAddress = 0x00000000, WebFilesAddress = 0x00100000; + +void ResetWiFiForUpload(int begin_or_end) { + //#if 0 + uint32_t start = getWifiTick(); + + if (begin_or_end == 0) { + SET_OUTPUT(WIFI_IO0_PIN); + WRITE(WIFI_IO0_PIN, LOW); + } + else + SET_INPUT_PULLUP(WIFI_IO0_PIN); + + WIFI_RESET(); + while (getWifiTickDiff(start, getWifiTick()) < 500) { /* nada */ } + WIFI_SET(); + //#endif +} + +int32_t wifi_upload(int type) { + esp_upload.retriesPerBaudRate = 9; + + 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; + default: return -1; + } + + while (esp_upload.state != upload_idle) { + upload_spin(); + watchdog_refresh(); + } + + ResetWiFiForUpload(1); + + return esp_upload.uploadResult == success ? 0 : -1; +} + +#endif // HAS_TFT_LVGL_UI && MKS_WIFI_MODULE diff --git a/Marlin/src/lcd/extui/lib/mks_ui/wifi_upload.h b/Marlin/src/lcd/extui/mks_ui/wifi_upload.h similarity index 88% rename from Marlin/src/lcd/extui/lib/mks_ui/wifi_upload.h rename to Marlin/src/lcd/extui/mks_ui/wifi_upload.h index d942a2c84f80..ff98173b9555 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/wifi_upload.h +++ b/Marlin/src/lcd/extui/mks_ui/wifi_upload.h @@ -25,9 +25,10 @@ extern "C" { /* C-declarations for C++ */ #endif -#define ESP_FIRMWARE_FILE "1:/MksWifi.bin" -#define ESP_WEB_FIRMWARE_FILE "1:/MksWifi_Web.bin" -#define ESP_WEB_FILE "1:/MksWifi_WebView.bin" +#define ESP_FIRMWARE_FILE "MksWifi.bin" +#define ESP_FIRMWARE_FILE_RENAME "MKSWIFI.CUR" +#define ESP_WEB_FIRMWARE_FILE "1:/MksWifi_Web.bin" +#define ESP_WEB_FILE "1:/MksWifi_WebView.bin" typedef enum { upload_idle, @@ -52,7 +53,6 @@ typedef enum { } EspUploadResult; typedef struct { - //FIL uploadFile; uint32_t fileSize; uint32_t uploadAddress; diff --git a/Marlin/src/lcd/extui/nextion/FileNavigator.cpp b/Marlin/src/lcd/extui/nextion/FileNavigator.cpp new file mode 100644 index 000000000000..650bbd6645d6 --- /dev/null +++ b/Marlin/src/lcd/extui/nextion/FileNavigator.cpp @@ -0,0 +1,174 @@ +/** + * 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 . + * + */ + +/* **************************************** + * lcd/extui/nextion/FileNavigator.cpp + * **************************************** + * Extensible_UI implementation for Nextion + * https://github.com/Skorpi08 + * ***************************************/ + +#include "../../../inc/MarlinConfigPre.h" + +#if ENABLED(NEXTION_TFT) + +#include "FileNavigator.h" +#include "nextion_tft.h" + +using namespace ExtUI; + +#define DEBUG_OUT NEXDEBUGLEVEL +#include "../../../core/debug_out.h" + +FileList FileNavigator::filelist; // Instance of the Marlin file API +char FileNavigator::currentfoldername[MAX_PATH_LEN]; // Current folder path +uint16_t FileNavigator::lastindex; +uint8_t FileNavigator::folderdepth; +uint16_t FileNavigator::currentindex; // override the panel request + +FileNavigator filenavigator; + +FileNavigator::FileNavigator() { reset(); } + +void FileNavigator::reset() { + currentfoldername[0] = '\0'; + folderdepth = 0; + currentindex = 0; + lastindex = 0; + // Start at root folder + while (!filelist.isAtRootDir()) filelist.upDir(); + refresh(); +} + +void FileNavigator::refresh() { filelist.refresh(); } + +void FileNavigator::getFiles(uint16_t index) { + uint16_t files = 7, fseek = 0, fcnt = 0; + if (index == 0) + currentindex = 0; + else { + // Each time we change folder we reset the file index to 0 and keep track + // of the current position as the TFT panel isn't aware of folder trees. + --currentindex; // go back a file to take account of the .. added to the root. + if (index > lastindex) + currentindex += files + 1; + else if (currentindex >= files) + currentindex -= files - 1; + else + currentindex = 0; + } + lastindex = index; + + #if NEXDEBUG(AC_FILE) + DEBUG_ECHOLNPAIR("index=", index, " currentindex=", currentindex); + #endif + + if (currentindex == 0 && folderdepth > 0) { // Add a link to go up a folder + nextion.SendtoTFT(PSTR("vis p0,1")); + nextion.SendtoTFT(PSTR("\xFF\xFF\xFF")); + SEND_VAL("tmpUP", "0"); + files--; + } + else { + nextion.SendtoTFT(PSTR("vis p0,0")); + nextion.SendtoTFT(PSTR("\xFF\xFF\xFF")); + } + + for (uint16_t seek = currentindex; seek < currentindex + files; seek++) { + if (filelist.seek(seek)) { + nextion.SendtoTFT(PSTR("s")); + LCD_SERIAL.print(fcnt); + nextion.SendtoTFT(PSTR(".txt=\"")); + if (filelist.isDir()) { + LCD_SERIAL.print(filelist.shortFilename()); + nextion.SendtoTFT(PSTR("/\"")); + nextion.SendtoTFT(PSTR("\xFF\xFF\xFF")); + + nextion.SendtoTFT(PSTR("l")); + LCD_SERIAL.print(fcnt); + nextion.SendtoTFT(PSTR(".txt=\"")); + LCD_SERIAL.print(filelist.filename()); + nextion.SendtoTFT(PSTR("\"")); + nextion.SendtoTFT(PSTR("\xFF\xFF\xFF")); + SEND_PCO2("l", fcnt, "1055"); + } + else { + LCD_SERIAL.print(currentfoldername); + LCD_SERIAL.print(filelist.shortFilename()); + nextion.SendtoTFT(PSTR("\"")); + nextion.SendtoTFT(PSTR("\xFF\xFF\xFF")); + + nextion.SendtoTFT(PSTR("l")); + LCD_SERIAL.print(fcnt); + nextion.SendtoTFT(PSTR(".txt=\"")); + LCD_SERIAL.print(filelist.longFilename()); + nextion.SendtoTFT(PSTR("\"")); + nextion.SendtoTFT(PSTR("\xFF\xFF\xFF")); + } + fcnt++; + fseek = seek; + #if NEXDEBUG(AC_FILE) + DEBUG_ECHOLNPAIR("-", seek, " '", filelist.longFilename(), "' '", currentfoldername, "", filelist.shortFilename(), "'\n"); + #endif + } + } + SEND_VAL("n0", filelist.count()); + SEND_VAL("n1", fseek + 1); +} + +void FileNavigator::changeDIR(char *folder) { + #if NEXDEBUG(AC_FILE) + DEBUG_ECHOLNPAIR("currentfolder: ", currentfoldername, " New: ", folder); + #endif + if (folderdepth >= MAX_FOLDER_DEPTH) return; // limit the folder depth + strcat(currentfoldername, folder); + strcat(currentfoldername, "/"); + filelist.changeDir(folder); + refresh(); + folderdepth++; + currentindex = 0; +} + +void FileNavigator::upDIR() { + filelist.upDir(); + refresh(); + folderdepth--; + currentindex = 0; + // Remove the last child folder from the stored path + if (folderdepth == 0) { + currentfoldername[0] = '\0'; + reset(); + } + else { + char *pos = nullptr; + for (uint8_t f = 0; f < folderdepth; f++) + pos = strchr(currentfoldername, '/'); + pos[1] = '\0'; + } + #if NEXDEBUG(AC_FILE) + DEBUG_ECHOLNPAIR("depth: ", folderdepth, " currentfoldername: ", currentfoldername); + #endif +} + +char* FileNavigator::getCurrentFolderName() { return currentfoldername; } + +#endif // NEXTION_TFT diff --git a/Marlin/src/lcd/extui/nextion/FileNavigator.h b/Marlin/src/lcd/extui/nextion/FileNavigator.h new file mode 100644 index 000000000000..fd29bceadea7 --- /dev/null +++ b/Marlin/src/lcd/extui/nextion/FileNavigator.h @@ -0,0 +1,53 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/* **************************************** + * lcd/extui/nextion/FileNavigator.cpp + * **************************************** + * Extensible_UI implementation for Nextion + * https://github.com/Skorpi08 + * ***************************************/ + +#include "nextion_tft_defs.h" // for MAX_PATH_LEN +#include "../ui_api.h" + +using namespace ExtUI; + +class FileNavigator { + public: + FileNavigator(); + static void reset(); + static void getFiles(uint16_t); + static void upDIR(); + static void changeDIR(char *); + static void refresh(); + static char* getCurrentFolderName(); + private: + static FileList filelist; + static char currentfoldername[MAX_PATH_LEN]; + static uint16_t lastindex; + static uint8_t folderdepth; + static uint16_t currentindex; +}; + +extern FileNavigator filenavigator; diff --git a/Marlin/src/lcd/extui/nextion/nextion_extui.cpp b/Marlin/src/lcd/extui/nextion/nextion_extui.cpp new file mode 100644 index 000000000000..a825bd502f1d --- /dev/null +++ b/Marlin/src/lcd/extui/nextion/nextion_extui.cpp @@ -0,0 +1,121 @@ +/** + * 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 . + * + */ + +/** + * lcd/extui/nextion_lcd.cpp + * + * Nextion TFT support for Marlin + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if ENABLED(NEXTION_TFT) + +#include "../ui_api.h" +#include "nextion_tft.h" + +namespace ExtUI { + + void onStartup() { nextion.Startup(); } + void onIdle() { nextion.IdleLoop(); } + void onPrinterKilled(PGM_P const error, PGM_P const component) { nextion.PrinterKilled(error,component); } + void onMediaInserted() {} + void onMediaError() {} + void onMediaRemoved() {} + void onPlayTone(const uint16_t frequency, const uint16_t duration) {} + void onPrintTimerStarted() {} + void onPrintTimerPaused() {} + void onPrintTimerStopped() {} + void onFilamentRunout(const extruder_t) {} + void onUserConfirmRequired(const char * const msg) { nextion.ConfirmationRequest(msg); } + void onStatusChanged(const char * const msg) { nextion.StatusChange(msg); } + + void onHomingStart() {} + void onHomingComplete() {} + void onPrintFinished() { nextion.PrintFinished(); } + + void onFactoryReset() {} + + void onStoreSettings(char *buff) { + // Called when saving to EEPROM (i.e. M500). If the ExtUI needs + // permanent data to be stored, it can write up to eeprom_data_size bytes + // into buff. + + // Example: + // static_assert(sizeof(myDataStruct) <= ExtUI::eeprom_data_size); + // memcpy(buff, &myDataStruct, sizeof(myDataStruct)); + } + + void onLoadSettings(const char *buff) { + // Called while loading settings from EEPROM. If the ExtUI + // needs to retrieve data, it should copy up to eeprom_data_size bytes + // from buff + + // Example: + // static_assert(sizeof(myDataStruct) <= ExtUI::eeprom_data_size); + // memcpy(&myDataStruct, buff, sizeof(myDataStruct)); + } + + void onPostprocessSettings() { + // Called after loading or resetting stored settings + } + + void onConfigurationStoreWritten(bool success) { + // Called after the entire EEPROM has been written, + // whether successful or not. + } + + void onConfigurationStoreRead(bool success) { + // Called after the entire EEPROM has been read, + // whether successful or not. + } + + #if HAS_MESH + void onMeshLevelingStart() {} + + void onMeshUpdate(const int8_t xpos, const int8_t ypos, const float zval) { + // Called when any mesh points are updated + } + + void onMeshUpdate(const int8_t xpos, const int8_t ypos, const ExtUI::probe_state_t state) { + // Called to indicate a special condition + } + #endif + + #if ENABLED(POWER_LOSS_RECOVERY) + void onPowerLossResume() { + // Called on resume from power-loss + } + #endif + + #if HAS_PID_HEATING + void onPidTuning(const result_t rst) { + // Called for temperature PID tuning result + nextion.PanelInfo(37); + } + #endif + + void onSteppersDisabled() {} + void onSteppersEnabled() {} +} + +#endif // NEXTION_TFT diff --git a/Marlin/src/lcd/extui/nextion/nextion_tft.cpp b/Marlin/src/lcd/extui/nextion/nextion_tft.cpp new file mode 100644 index 000000000000..903544268167 --- /dev/null +++ b/Marlin/src/lcd/extui/nextion/nextion_tft.cpp @@ -0,0 +1,736 @@ +/** + * 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 . + * + */ + +/* **************************************** + * lcd/extui/nextion/nextion_tft.h + * **************************************** + * Extensible_UI implementation for Nextion + * https://github.com/Skorpi08 + * ***************************************/ + +#include "../../../inc/MarlinConfigPre.h" + +#if ENABLED(NEXTION_TFT) + +#include "../../../MarlinCore.h" +#include "../../../feature/pause.h" +#include "../../../gcode/queue.h" +#include "../../../libs/numtostr.h" +#include "../../../sd/cardreader.h" +#include "FileNavigator.h" +#include "nextion_tft.h" + +#define DEBUG_OUT NEXDEBUGLEVEL +#include "../../../core/debug_out.h" + +char NextionTFT::selectedfile[MAX_PATH_LEN]; +char NextionTFT::nextion_command[MAX_CMND_LEN]; +uint8_t NextionTFT::command_len; + +uint32_t layer = 0; + +NextionTFT nextion; + +NextionTFT::NextionTFT() {} + +void NextionTFT::Startup() { + selectedfile[0] = '\0'; + nextion_command[0] = '\0'; + command_len = 0; + LCD_SERIAL.begin(115200); + + SEND_VAL("tmppage.connected", 0); + delay_ms(100); + SEND_VAL("tmppage.connected", 1); + + SEND_VALasTXT("tmppage.marlin", SHORT_BUILD_VERSION); + SEND_VALasTXT("tmppage.compiled", __DATE__ " / " __TIME__); + SEND_VALasTXT("tmppage.extruder", EXTRUDERS); + SEND_VALasTXT("tmppage.printer", MACHINE_NAME); + SEND_VALasTXT("tmppage.author", STRING_CONFIG_H_AUTHOR); + SEND_VALasTXT("tmppage.released", STRING_DISTRIBUTION_DATE); + SEND_VALasTXT("tmppage.bedx", X_BED_SIZE); + SEND_VALasTXT("tmppage.bedy", Y_BED_SIZE); + SEND_VALasTXT("tmppage.bedz", Z_MAX_POS); + + DEBUG_ECHOLNPAIR("Nextion Debug Level ", NEXDEBUGLEVEL); +} + +void NextionTFT::IdleLoop() { + if (ReadTFTCommand()) { + ProcessPanelRequest(); + command_len = 0; + } + UpdateOnChange(); +} + +void NextionTFT::PrinterKilled(PGM_P error, PGM_P component) { + SEND_TXT_END("page error"); + SEND_TXT("t3", "Error"); + SEND_TXT_P("t4", component); + SEND_TXT_P("t5", error); + SEND_TXT("t6", "Need reset"); +} + +void NextionTFT::PrintFinished() { + SEND_TXT_END("page printfinished"); +} + +void NextionTFT::ConfirmationRequest(const char * const msg) { + SEND_VALasTXT("tmppage.M117", msg); + #if NEXDEBUG(N_MARLIN) + DEBUG_ECHOLNPAIR("ConfirmationRequest() ", msg, " printer_state:", printer_state); + #endif +} + +void NextionTFT::StatusChange(const char * const msg) { + #if NEXDEBUG(N_MARLIN) + DEBUG_ECHOLNPAIR("StatusChange() ", msg, "\nprinter_state:", printer_state); + #endif + SEND_VALasTXT("tmppage.M117", msg); +} + +void NextionTFT::SendtoTFT(PGM_P str) { // A helper to print PROGMEM string to the panel + #if NEXDEBUG(N_SOME) + DEBUG_ECHOPGM_P(str); + #endif + while (const char c = pgm_read_byte(str++)) + LCD_SERIAL.write(c); +} + +bool NextionTFT::ReadTFTCommand() { + bool command_ready = false; + while ((LCD_SERIAL.available() > 0) && (command_len < MAX_CMND_LEN)) { + nextion_command[command_len] = LCD_SERIAL.read(); + if (nextion_command[command_len] == 10) { + command_ready = true; + break; + } + command_len++; + } + + if (command_ready) { + nextion_command[command_len] = 0x00; + if (nextion_command[0] == 'G' || nextion_command[0] == 'M' || nextion_command[0] == 'T') + injectCommands(nextion_command); + #if NEXDEBUG(N_ALL) + DEBUG_ECHOLNPAIR("< ", nextion_command); + #endif + #if NEXDEBUG(N_SOME) + uint8_t req = atoi(&nextion_command[1]); + if (req > 7 && req != 20) + DEBUG_ECHOLNPAIR( "> ", AS_CHAR(nextion_command[0]), + "\n> ", AS_CHAR(nextion_command[1]), + "\n> ", AS_CHAR(nextion_command[2]), + "\n> ", AS_CHAR(nextion_command[3]), + "\nprinter_state:", printer_state); + #endif + } + return command_ready; +} + +void NextionTFT::SendFileList(int8_t startindex) { + // respond to panel request for 7 files starting at index + #if NEXDEBUG(N_INFO) + DEBUG_ECHOLNPAIR("## SendFileList ## ", startindex); + #endif + filenavigator.getFiles(startindex); +} + +void NextionTFT::SelectFile() { + strncpy(selectedfile, nextion_command + 4, command_len - 4); + selectedfile[command_len - 5] = '\0'; + #if NEXDEBUG(N_FILE) + DEBUG_ECHOLNPAIR_F(" Selected File: ", selectedfile); + #endif + switch (selectedfile[0]) { + case '/': // Valid file selected + //SEND_TXT("tmppage.M117", msg_sd_file_open_success); + break; + case '<': // .. (go up folder level) + filenavigator.upDIR(); + SendFileList(0); + break; + default: // enter sub folder + filenavigator.changeDIR(selectedfile); + SendFileList(0); + break; + } +} + +void NextionTFT::_format_time(char *outstr, uint32_t time) { + const uint8_t hrs = time / 3600, + min = (time / 60) % 60, + sec = time % 60; + if (hrs) + sprintf_P(outstr, PSTR("%02d:%02dm"), hrs, min); + else + sprintf_P(outstr, PSTR("%02d:%02ds"), min, sec); +} + +void NextionTFT::ProcessPanelRequest() { + // Break these up into logical blocks as its easier to navigate than one huge switch case! + if (nextion_command[0] == 'X') { + int8_t req = atoi(&nextion_command[1]); + + // Information requests + if (req <= 49) + PanelInfo(req); + + // Simple Actions + else if (req >= 50) + PanelAction(req); + } +} + +#define SEND_NA(A) SEND_TXT(A, "n/a") + +void NextionTFT::PanelInfo(uint8_t req) { + switch (req) { + case 0: break; + + case 1: // Get SD Card list + if (!isPrinting()) { + if (!isMediaInserted()) safe_delay(500); + if (!isMediaInserted()) { // Make sure the card is removed + //SEND_TXT("tmppage.M117", msg_no_sd_card); + } + else if (nextion_command[3] == 'S') + SendFileList(atoi(&nextion_command[4])); + } + break; + + case 2: // Printer Info + if (!isPrinting()) { + SEND_VAL("tmppage.connected", 1); + SEND_VALasTXT("tmppage.marlin", SHORT_BUILD_VERSION); + SEND_VALasTXT("tmppage.compiled", __DATE__ " / " __TIME__); + SEND_VALasTXT("tmppage.extruder", EXTRUDERS); + SEND_VALasTXT("tmppage.printer", MACHINE_NAME); + SEND_VALasTXT("tmppage.author", STRING_CONFIG_H_AUTHOR); + SEND_VALasTXT("tmppage.released", STRING_DISTRIBUTION_DATE); + SEND_VALasTXT("tmppage.bedx", X_BED_SIZE); + SEND_VALasTXT("tmppage.bedy", Y_BED_SIZE); + SEND_VALasTXT("tmppage.bedz", Z_MAX_POS); + SEND_TEMP("tmppage.t0", ui8tostr3rj(getActualTemp_celsius(E0)), " / ", ui8tostr3rj(getTargetTemp_celsius(E0))); + SEND_TEMP("tmppage.t1", ui8tostr3rj(getActualTemp_celsius(E1)), " / ", ui8tostr3rj(getTargetTemp_celsius(E1))); + SEND_TEMP("tmppage.t2", ui8tostr3rj(getActualTemp_celsius(BED)), " / ", ui8tostr3rj(getTargetTemp_celsius(BED))); + SEND_VALasTXT("tmppage.tool", getActiveTool()); + SEND_VALasTXT("tmppage.fan", ui8tostr3rj(getActualFan_percent(FAN0))); + SEND_VALasTXT("tmppage.speed", getFeedrate_percent()); + SEND_VALasTXT("tmppage.flow", getFlow_percent(getActiveTool())); + SEND_VALasTXT("tmppage.progress", ui8tostr3rj(getProgress_percent())); + SEND_VALasTXT("tmppage.layer", layer); + SEND_VALasTXT("tmppage.x", getAxisPosition_mm(X)); + SEND_VALasTXT("tmppage.y", getAxisPosition_mm(Y)); + SEND_VALasTXT("tmppage.z", getAxisPosition_mm(Z)); + SEND_VAL("tmppage.homed", isPositionKnown()); + SEND_VAL("tmppage.homedx", isAxisPositionKnown(X)); + SEND_VAL("tmppage.homedy", isAxisPositionKnown(Y)); + SEND_VAL("tmppage.homedz", isAxisPositionKnown(Z)); + #if ENABLED(DUAL_X_CARRIAGE) + SEND_VAL("tmppage.idexmode", getIDEX_Mode()); + #endif + SEND_TXT("tmppage.M117", msg_welcome); + } + break; + + case 23: // Linear Advance + #if ENABLED(LIN_ADVANCE) + SEND_VALasTXT("linadvance", getLinearAdvance_mm_mm_s(getActiveTool())); + #else + SEND_NA("linadvance"); + #endif + break; + + case 24: // TMC Motor Current + #if HAS_TRINAMIC_CONFIG + #define SEND_TRINAMIC_CURR(A, B) SEND_VALasTXT(A, getAxisCurrent_mA(B)) + #else + #define SEND_TRINAMIC_CURR(A, B) SEND_NA(A) + #endif + SEND_TRINAMIC_CURR("x", X); + SEND_TRINAMIC_CURR("x2", X2); + SEND_TRINAMIC_CURR("y", Y); + SEND_TRINAMIC_CURR("y2", Y2); + SEND_TRINAMIC_CURR("z", Z); + SEND_TRINAMIC_CURR("z2", Z2); + SEND_TRINAMIC_CURR("e", E0); + SEND_TRINAMIC_CURR("e1", E1); + break; + + case 25: // TMC Bump Sensitivity + #if HAS_TRINAMIC_CONFIG + #define SEND_TRINAMIC_BUMP(A, B) SEND_VALasTXT(A, getTMCBumpSensitivity(B)) + #else + #define SEND_TRINAMIC_BUMP(A, B) SEND_NA(A) + #endif + SEND_TRINAMIC_BUMP("x", X); + SEND_TRINAMIC_BUMP("x2", X2); + SEND_TRINAMIC_BUMP("y", Y); + SEND_TRINAMIC_BUMP("y2", Y2); + SEND_TRINAMIC_BUMP("z", Z); + SEND_TRINAMIC_BUMP("z2", Z2); + break; + + case 26: // TMC Hybrid Threshold Speed + #if 0 && BOTH(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) + #endif + SEND_TRINAMIC_THRS("x", X); + SEND_TRINAMIC_THRS("x2", X2); + SEND_TRINAMIC_THRS("y", Y); + SEND_TRINAMIC_THRS("y2", Y2); + SEND_TRINAMIC_THRS("z", Z); + SEND_TRINAMIC_THRS("z2", Z2); + SEND_TRINAMIC_THRS("e", E0); + SEND_TRINAMIC_THRS("e1", E1); + break; + + case 27: // Printcounter + #if ENABLED(PRINTCOUNTER) + char buffer[21]; + #define SEND_PRINT_INFO(A, B) SEND_VALasTXT(A, B(buffer)) + #else + #define SEND_PRINT_INFO(A, B) SEND_NA(A) + #endif + SEND_PRINT_INFO("t5", getTotalPrints_str); + SEND_PRINT_INFO("t3", getFinishedPrints_str); + SEND_PRINT_INFO("t4", getFailedPrints_str); + SEND_PRINT_INFO("t6", getTotalPrintTime_str); + SEND_PRINT_INFO("t7", getLongestPrint_str); + SEND_PRINT_INFO("t8", getFilamentUsed_str); + break; + + case 28: // Filament laod/unload + #if ENABLED(ADVANCED_PAUSE_FEATURE) + #define SEND_PAUSE_INFO(A, B) SEND_VALasTXT(A, fc_settings[getActiveTool()].B) + #else + #define SEND_PAUSE_INFO(A, B) SEND_NA(A) + #endif + SEND_PAUSE_INFO("filamentin", load_length); + SEND_PAUSE_INFO("filamentout", unload_length); + break; + + case 29: // Preheat + #if PREHEAT_COUNT + if (!isPrinting()) { + // Preheat PLA + if (nextion_command[4] == 'P') { + SEND_VALasTXT("pe", getMaterial_preset_E(0)); + #if HAS_HEATED_BED + SEND_VALasTXT("pb", getMaterial_preset_B(0)); + #endif + } + + // Preheat ABS + if (nextion_command[4] == 'A') { + SEND_VALasTXT("ae", getMaterial_preset_E(1)); + #if HAS_HEATED_BED + SEND_VALasTXT("ab", getMaterial_preset_B(1)); + #endif + } + + // Preheat PETG + if (nextion_command[4] == 'G') { + #ifdef PREHEAT_3_TEMP_HOTEND + SEND_VALasTXT("ge", getMaterial_preset_E(2)); + #if HAS_HEATED_BED + SEND_VALasTXT("gb", getMaterial_preset_B(2)); + #endif + #endif + } + } + #endif + break; + + case 30: // Velocity + SEND_VALasTXT("x", getAxisMaxFeedrate_mm_s(X)); + SEND_VALasTXT("y", getAxisMaxFeedrate_mm_s(Y)); + SEND_VALasTXT("z", getAxisMaxFeedrate_mm_s(Z)); + SEND_VALasTXT("e", getAxisMaxFeedrate_mm_s(getActiveTool())); + SEND_VALasTXT("min", getMinFeedrate_mm_s()); + SEND_VALasTXT("tmin", getMinTravelFeedrate_mm_s()); + break; + + case 31: // Jerk + #if ENABLED(CLASSIC_JERK) + #define SEND_JERK_INFO(A, B) SEND_VALasTXT(A, getAxisMaxJerk_mm_s(B)) + #else + #define SEND_JERK_INFO(A, B) SEND_NA(A) + //SEND_VALasTXT("x", getJunctionDeviation_mm()); + SEND_TXT("tmppage.M117", "classic Jerk not enabled"); + #endif + SEND_JERK_INFO("x", X); + SEND_JERK_INFO("y", Y); + SEND_JERK_INFO("z", Z); + SEND_JERK_INFO("e", getActiveTool()); + break; + + case 32: // Steps-per-mm + SEND_VALasTXT("x", getAxisSteps_per_mm(X)); + SEND_VALasTXT("y", getAxisSteps_per_mm(Y)); + SEND_VALasTXT("z", getAxisSteps_per_mm(Z)); + SEND_VALasTXT("e0", getAxisSteps_per_mm(E0)); + SEND_VALasTXT("e1", getAxisSteps_per_mm(E1)); + break; + + case 33: // Acceleration + SEND_VALasTXT("x", ui16tostr5rj(getAxisMaxAcceleration_mm_s2(X))); + SEND_VALasTXT("y", ui16tostr5rj(getAxisMaxAcceleration_mm_s2(Y))); + SEND_VALasTXT("z", ui16tostr5rj(getAxisMaxAcceleration_mm_s2(Z))); + SEND_VALasTXT("e", ui16tostr5rj(getAxisMaxAcceleration_mm_s2(getActiveTool()))); + SEND_VALasTXT("print", ui16tostr5rj(getPrintingAcceleration_mm_s2())); + SEND_VALasTXT("retract", ui16tostr5rj(getRetractAcceleration_mm_s2())); + SEND_VALasTXT("travel", ui16tostr5rj(getTravelAcceleration_mm_s2())); + break; + + case 34: // Dual X carriage offset + #if ENABLED(DUAL_X_CARRIAGE) + #define SEND_IDEX_INFO(A, B) SEND_VALasTXT(A, getNozzleOffset_mm(B, getActiveTool())) + #else + #define SEND_IDEX_INFO(A, B) SEND_NA(A) + #endif + SEND_IDEX_INFO("x", X); + SEND_IDEX_INFO("y", Y); + SEND_IDEX_INFO("z", Z); + break; + + case 35: // Probe offset + #if HAS_PROBE_XY_OFFSET + #define SEND_PROBE_INFO(A, B) SEND_VALasTXT(A, getProbeOffset_mm(B)) + #else + #define SEND_PROBE_INFO(A, B) SEND_NA(A) + #endif + SEND_PROBE_INFO("x", X); + SEND_PROBE_INFO("y", Y); + SEND_VALasTXT("z", getZOffset_mm()); + break; + + case 36: // Endstop Info + #if HAS_X_MIN + SEND_VALasTXT("x1", READ(X_MIN_PIN) != X_MIN_ENDSTOP_INVERTING ? "triggered" : "open"); + #endif + #if HAS_X_MAX + SEND_VALasTXT("x2", READ(X_MAX_PIN) != X_MAX_ENDSTOP_INVERTING ? "triggered" : "open"); + #endif + #if HAS_Y_MIN + SEND_VALasTXT("y1", READ(Y_MIN_PIN) != Y_MIN_ENDSTOP_INVERTING ? "triggered" : "open"); + #endif + #if HAS_Z_MIN + SEND_VALasTXT("z1", READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING ? "triggered" : "open"); + #endif + #if HAS_Z_MAX + SEND_VALasTXT("z2", READ(Z_MAX_PIN) != Z_MAX_ENDSTOP_INVERTING ? "triggered" : "open"); + #endif + #if HAS_Z2_MIN + SEND_VALasTXT("z2", READ(Z2_MIN_PIN) != Z2_MIN_ENDSTOP_INVERTING ? "triggered" : "open"); + #endif + #if HAS_Z2_MAX + SEND_VALasTXT("z2", READ(Z2_MAX_PIN) != Z2_MAX_ENDSTOP_INVERTING ? "triggered" : "open"); + #endif + #if HAS_BED_PROBE + //SEND_VALasTXT("bltouch", READ(Z_MIN_PROBE_PIN) != Z_MIN_PROBE_ENDSTOP_INVERTING ? "triggered" : "open"); + #else + SEND_NA("bltouch"); + #endif + break; + + case 37: // PID + #if ENABLED(PIDTEMP) + #define SEND_PID_INFO_0(A, B) SEND_VALasTXT(A, getPIDValues_K##B(E0)) + #else + #define SEND_PID_INFO_0(A, B) SEND_NA(A) + #endif + #if BOTH(PIDTEMP, HAS_MULTI_EXTRUDER) + #define SEND_PID_INFO_1(A, B) SEND_VALasTXT(A, getPIDValues_K##B(E1)) + #else + #define SEND_PID_INFO_1(A, B) SEND_NA(A) + #endif + #if ENABLED(PIDTEMPBED) + #define SEND_PID_INFO_BED(A, B) SEND_VALasTXT(A, getBedPIDValues_K##B()) + #else + #define SEND_PID_INFO_BED(A, B) SEND_NA(A) + #endif + SEND_PID_INFO_0("p0", p); + SEND_PID_INFO_0("i0", i); + SEND_PID_INFO_0("d0", d); + + SEND_PID_INFO_1("p1", p); + SEND_PID_INFO_1("i1", i); + SEND_PID_INFO_1("d1", d); + + SEND_PID_INFO_BED("hbp", p); + SEND_PID_INFO_BED("hbi", i); + SEND_PID_INFO_BED("hbd", d); + break; + } +} + +void NextionTFT::PanelAction(uint8_t req) { + switch (req) { + + case 50: // Pause SD print + //if (isPrintingFromMedia()) { + //SEND_TXT("tmppage.M117", "Paused"); + pausePrint(); + SEND_TXT_END("qpause.picc=29"); + //} + break; + + case 51: // Resume SD Print + resumePrint(); + SEND_TXT_END("qpause.picc=28"); + break; + + case 52: // Stop SD print + //if (isPrintingFromMedia()) { + stopPrint(); + SEND_TXT_END("page prepare"); + //} + break; + + case 54: // A13 Select file + SelectFile(); + break; + + case 65: // Cool Down + if (!isPrinting()) coolDown(); + break; + + case 66: // Refresh SD + if (!isPrinting()) { + injectCommands_P(PSTR("M21")); + filenavigator.reset(); + } + break; + + case 56: // Set Fan, Flow, Print Speed + switch (nextion_command[4]) { + case 'S': setTargetFan_percent(atof(&nextion_command[5]), FAN0); break; + case 'P': setFeedrate_percent(atoi(&nextion_command[5])); break; + case 'F': setFlow_percent(atoi(&nextion_command[5]), getActiveTool()); break; + } + break; + + case 57: // Disable Motors + if (!isPrinting()) { + disable_all_steppers(); // from marlincore.h + SEND_TXT("tmppage.M117", "Motors disabled"); + } + break; + + case 58: // Load/Unload Filament + #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) + if (canMove(getActiveTool())) { + switch (nextion_command[4]) { + case 'L': injectCommands_P(PSTR("M701")); break; + case 'U': injectCommands_P(PSTR("M702")); break; + } + } + else { + SEND_TXT("tmppage.M117", "Preheat first"); + SEND_TXT_END("page preheat"); + } + #else + SEND_TXT("tmppage.M117", "Filament loading disabled"); + #endif + break; + + case 63: // Preheat // Temps defined in configuration.h + #if PREHEAT_COUNT + if (!isPrinting()) switch (nextion_command[4]) { + // Preheat PLA + case 'P': + #if HAS_HEATED_BED + setTargetTemp_celsius(getMaterial_preset_B(0), BED); + #endif + setTargetTemp_celsius(getMaterial_preset_E(0), getActiveTool()); + break; + + // Preheat ABS + case 'A': + #if HAS_HEATED_BED + setTargetTemp_celsius(getMaterial_preset_B(1), BED); + #endif + setTargetTemp_celsius(getMaterial_preset_E(1), getActiveTool()); + break; + + // Preheat PETG + case 'G': + #if HAS_HEATED_BED + setTargetTemp_celsius(getMaterial_preset_B(2), BED); + #endif + setTargetTemp_celsius(getMaterial_preset_E(2), getActiveTool()); + break; + } + #else + SEND_TXT("tmppage.M117", "Preheat disabled"); + #endif + break; + } +} + +void NextionTFT::UpdateOnChange() { + const millis_t ms = millis(); + static millis_t next_event_ms = 0; + static celsius_float_t last_degBed = 999, last_degHotend0 = 999, last_degHotend1 = 999, + last_degTargetBed = 999, last_degTargetHotend0 = 999, last_degTargetHotend1 = 999; + + // tmppage Temperature + if (!WITHIN(last_degHotend0 - getActualTemp_celsius(E0), -0.2, 0.2) || !WITHIN(last_degTargetHotend0 - getTargetTemp_celsius(E0), -0.5, 0.5)) { + SEND_TEMP("tmppage.t0", ui8tostr3rj(getActualTemp_celsius(E0)), " / ", ui8tostr3rj(getTargetTemp_celsius(E0))); + last_degHotend0 = getActualTemp_celsius(E0); + last_degTargetHotend0 = getTargetTemp_celsius(E0); + } + + if (!WITHIN(last_degHotend1 - getActualTemp_celsius(E1), -0.2, 0.2) || !WITHIN(last_degTargetHotend1 - getTargetTemp_celsius(E1), -0.5, 0.5)) { + SEND_TEMP("tmppage.t1", ui8tostr3rj(getActualTemp_celsius(E1)), " / ", ui8tostr3rj(getTargetTemp_celsius(E1))); + last_degHotend1 = getActualTemp_celsius(E1); + last_degTargetHotend1 = getTargetTemp_celsius(E1); + } + + if (!WITHIN(last_degBed - getActualTemp_celsius(BED), -0.2, 0.2) || !WITHIN(last_degTargetBed - getTargetTemp_celsius(BED), -0.5, 0.5)) { + SEND_TEMP("tmppage.t2", ui8tostr3rj(getActualTemp_celsius(BED)), " / ", ui8tostr3rj(getTargetTemp_celsius(BED))); + last_degBed = getActualTemp_celsius(BED); + last_degTargetBed = getTargetTemp_celsius(BED); + } + + // tmppage Tool + static uint8_t last_active_extruder = 99; + if (last_active_extruder != getActiveTool()) { + SEND_VALasTXT("tmppage.tool", getActiveTool()); + last_active_extruder = getActiveTool(); + } + + // tmppage Fan Speed + static uint8_t last_fan_speed = 99; + if (last_fan_speed != getActualFan_percent(FAN0)) { + SEND_VALasTXT("tmppage.fan", ui8tostr3rj(getActualFan_percent(FAN0))); + last_fan_speed = getActualFan_percent(FAN0); + } + + // tmppage Print Speed + static uint8_t last_print_speed = 99; + if (last_print_speed != getFeedrate_percent()) { + SEND_VALasTXT("tmppage.speed", ui8tostr3rj(getFeedrate_percent())); + last_print_speed = getFeedrate_percent(); + } + + // tmppage Flow + static uint8_t last_flow_speed = 99; + if (last_flow_speed != getFlow_percent(getActiveTool())) { + SEND_VALasTXT("tmppage.flow", getFlow_percent(getActiveTool())); + last_flow_speed = getFlow_percent(getActiveTool()); + } + + // tmppage Axis + static float last_get_axis_position_mmX = 999, last_get_axis_position_mmY = 999, last_get_axis_position_mmZ = 999; + + // tmppage Progress + Layer + Time + if (isPrinting()) { + + if (ELAPSED(ms, next_event_ms)) { + next_event_ms = ms + 1000; + #if ENABLED(SHOW_REMAINING_TIME) + const uint32_t remaining = getProgress_seconds_remaining(); + char remaining_str[10]; + _format_time(remaining_str, remaining); + SEND_VALasTXT("tmppage.remaining", remaining_str); + #endif + const uint32_t elapsed = getProgress_seconds_elapsed(); + char elapsed_str[10]; + _format_time(elapsed_str, elapsed); + SEND_VALasTXT("tmppage.elapsed", elapsed_str); + } + + static uint8_t last_progress = 99; + if (last_progress != getProgress_percent()) { + SEND_VALasTXT("tmppage.progress", ui8tostr3rj(getProgress_percent())); + last_progress = getProgress_percent(); + } + + if (last_get_axis_position_mmZ < getAxisPosition_mm(Z)) { + layer++; + SEND_VALasTXT("tmppage.layer", layer); + } + + if (last_get_axis_position_mmZ > getAxisPosition_mm(Z)) { + layer--; + SEND_VALasTXT("tmppage.layer", layer); + } + } + + if (!WITHIN(last_get_axis_position_mmX - getAxisPosition_mm(X), -0.1, 0.1)) { + if (ELAPSED(ms, next_event_ms)) { + next_event_ms = ms + 30; + SEND_VALasTXT("tmppage.x", getAxisPosition_mm(X)); + last_get_axis_position_mmX = getAxisPosition_mm(X); + } + } + + if (!WITHIN(last_get_axis_position_mmY - getAxisPosition_mm(Y), -0.1, 0.1)) { + if (ELAPSED(ms, next_event_ms)) { + next_event_ms = ms + 30; + SEND_VALasTXT("tmppage.y", getAxisPosition_mm(Y)); + last_get_axis_position_mmY = getAxisPosition_mm(Y); + } + } + + if (!WITHIN(last_get_axis_position_mmZ - getAxisPosition_mm(Z), -0.1, 0.1)) { + SEND_VALasTXT("tmppage.z", getAxisPosition_mm(Z)); + last_get_axis_position_mmZ = getAxisPosition_mm(Z); + } + + // tmppage homed + static bool last_homed = false, last_homedX = false, last_homedY = false, last_homedZ = false; + + if (last_homed != isPositionKnown()) { + SEND_VAL("tmppage.homed", isPositionKnown()); + last_homed = isPositionKnown(); + } + if (last_homedX != isAxisPositionKnown(X)) { + SEND_VAL("tmppage.homedx", isAxisPositionKnown(X)); + last_homedX = isAxisPositionKnown(X); + } + if (last_homedY != isAxisPositionKnown(Y)) { + SEND_VAL("tmppage.homedy", isAxisPositionKnown(Y)); + last_homedY = isAxisPositionKnown(Y); + } + if (last_homedZ != isAxisPositionKnown(Z)) { + SEND_VAL("tmppage.homedz", isAxisPositionKnown(Z)); + last_homedZ = isAxisPositionKnown(Z); + } + + #if ENABLED(DUAL_X_CARRIAGE) + // tmppage IDEX Mode + static uint8_t last_IDEX_Mode = 99; + if (last_IDEX_Mode != getIDEX_Mode()) { + SEND_VAL("tmppage.idexmode", getIDEX_Mode()); + last_IDEX_Mode = getIDEX_Mode(); + } + #endif +} + +#endif // NEXTION_TFT diff --git a/Marlin/src/lcd/extui/nextion/nextion_tft.h b/Marlin/src/lcd/extui/nextion/nextion_tft.h new file mode 100644 index 000000000000..4eb5fbe0b7fb --- /dev/null +++ b/Marlin/src/lcd/extui/nextion/nextion_tft.h @@ -0,0 +1,62 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/* **************************************** + * lcd/extui/nextion/nextion_tft.h + * **************************************** + * Extensible_UI implementation for Nextion + * https://github.com/Skorpi08 + * ***************************************/ + +#include "nextion_tft_defs.h" +#include "../../../inc/MarlinConfigPre.h" +#include "../ui_api.h" + +class NextionTFT { + private: + static uint8_t command_len; + static char nextion_command[MAX_CMND_LEN]; + static char selectedfile[MAX_PATH_LEN]; + + public: + NextionTFT(); + static void Startup(); + static void IdleLoop(); + static void PrinterKilled(PGM_P, PGM_P); + static void ConfirmationRequest(const char * const ); + static void StatusChange(const char * const ); + static void SendtoTFT(PGM_P); + static void UpdateOnChange(); + static void PrintFinished(); + static void PanelInfo(uint8_t); + + private: + static bool ReadTFTCommand(); + static void SendFileList(int8_t); + static void SelectFile(); + static void ProcessPanelRequest(); + static void PanelAction(uint8_t); + static void _format_time(char *, uint32_t); +}; + +extern NextionTFT nextion; diff --git a/Marlin/src/lcd/extui/nextion/nextion_tft_defs.h b/Marlin/src/lcd/extui/nextion/nextion_tft_defs.h new file mode 100644 index 000000000000..32d3ea329552 --- /dev/null +++ b/Marlin/src/lcd/extui/nextion/nextion_tft_defs.h @@ -0,0 +1,63 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/* **************************************** + * lcd/extui/nextion/nextion_tft_defs.h + * **************************************** + * Extensible_UI implementation for Nextion + * https://github.com/Skorpi08 + * ***************************************/ + +#include "../../../inc/MarlinConfigPre.h" + +//#define NEXDEBUGLEVEL 255 +#if NEXDEBUGLEVEL + // Bit-masks for selective debug: + enum NexDebugMask : uint8_t { + N_INFO = _BV(0), + N_ACTION = _BV(1), + N_FILE = _BV(2), + N_PANEL = _BV(3), + N_MARLIN = _BV(4), + N_SOME = _BV(5), + N_ALL = _BV(6) + }; + #define NEXDEBUG(M) (((M) & NEXDEBUGLEVEL) == M) // Debug flag macro +#else + #define NEXDEBUG(M) false +#endif + +#define MAX_FOLDER_DEPTH 4 // Limit folder depth TFT has a limit for the file path +#define MAX_CMND_LEN 16 * MAX_FOLDER_DEPTH // Maximum Length for a Panel command +#define MAX_PATH_LEN 16 * MAX_FOLDER_DEPTH // Maximum number of characters in a SD file path + + // TFT panel commands +#define msg_welcome MACHINE_NAME " Ready." + +#define SEND_TEMP(x,y,t,z) (nextion.SendtoTFT(PSTR(x)), nextion.SendtoTFT(PSTR(".txt=\"")), LCD_SERIAL.print(y), nextion.SendtoTFT(PSTR(t)), LCD_SERIAL.print(z), nextion.SendtoTFT(PSTR("\"\xFF\xFF\xFF"))) +#define SEND_VAL(x,y) (nextion.SendtoTFT(PSTR(x)), nextion.SendtoTFT(PSTR(".val=")), LCD_SERIAL.print(y), nextion.SendtoTFT(PSTR("\xFF\xFF\xFF"))) +#define SEND_TXT(x,y) (nextion.SendtoTFT(PSTR(x)), nextion.SendtoTFT(PSTR(".txt=\"")), nextion.SendtoTFT(PSTR(y)), nextion.SendtoTFT(PSTR("\"\xFF\xFF\xFF"))) +#define SEND_TXT_P(x,y) (nextion.SendtoTFT(PSTR(x)), nextion.SendtoTFT(PSTR(".txt=\"")), nextion.SendtoTFT(y), nextion.SendtoTFT(PSTR("\"\xFF\xFF\xFF"))) +#define SEND_VALasTXT(x,y) (nextion.SendtoTFT(PSTR(x)), nextion.SendtoTFT(PSTR(".txt=\"")), LCD_SERIAL.print(y), nextion.SendtoTFT(PSTR("\"\xFF\xFF\xFF"))) +#define SEND_TXT_END(x) (nextion.SendtoTFT(PSTR(x)), nextion.SendtoTFT(PSTR("\xFF\xFF\xFF"))) +#define SEND_PCO2(x,y,z) (nextion.SendtoTFT(PSTR(x)), LCD_SERIAL.print(y), nextion.SendtoTFT(PSTR(".pco=")), nextion.SendtoTFT(PSTR(z)), nextion.SendtoTFT(PSTR("\xFF\xFF\xFF"))) diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index 30cf696f3ed7..4ef96251bcb2 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -38,15 +38,16 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../../inc/MarlinConfigPre.h" #if ENABLED(EXTENSIBLE_UI) -#include "../ultralcd.h" +#include "../marlinui.h" #include "../../gcode/queue.h" +#include "../../gcode/gcode.h" #include "../../module/motion.h" #include "../../module/planner.h" #include "../../module/probe.h" @@ -54,6 +55,7 @@ #include "../../module/printcounter.h" #include "../../libs/duration_t.h" #include "../../HAL/shared/Delay.h" +#include "../../MarlinCore.h" #include "../../sd/cardreader.h" #if ENABLED(PRINTCOUNTER) @@ -100,11 +102,16 @@ #include "../../feature/host_actions.h" #endif +#if M600_PURGE_MORE_RESUMABLE + #include "../../feature/pause.h" +#endif + namespace ExtUI { static struct { uint8_t printer_killed : 1; - TERN_(JOYSTICK, uint8_t jogging : 1); - TERN_(SDSUPPORT, uint8_t was_sd_printing : 1); + #if ENABLED(JOYSTICK) + uint8_t jogging : 1; + #endif } flags; #ifdef __SAM3X8E__ @@ -123,7 +130,7 @@ namespace ExtUI { // Machine was killed, reinit SysTick so we are able to compute time without ISRs if (currTimeHI == 0) { // Get the last time the Arduino time computed (from CMSIS) and convert it to SysTick - currTimeHI = (uint32_t)((GetTickCount() * (uint64_t)(F_CPU / 8000)) >> 24); + currTimeHI = uint32_t((GetTickCount() * uint64_t(F_CPU / 8000)) >> 24); // Reinit the SysTick timer to maximize its period SysTick->LOAD = SysTick_LOAD_RELOAD_Msk; // get the full range for the systick timer @@ -148,9 +155,9 @@ namespace ExtUI { } #endif // __SAM3X8E__ - void delay_us(unsigned long us) { DELAY_US(us); } + void delay_us(uint32_t us) { DELAY_US(us); } - void delay_ms(unsigned long ms) { + void delay_ms(uint32_t ms) { if (flags.printer_killed) DELAY_US(ms * 1000); else @@ -175,7 +182,12 @@ namespace ExtUI { #if HAS_HEATED_BED case BED: thermalManager.reset_bed_idle_timer(); return; #endif - TERN_(HAS_HEATED_CHAMBER, case CHAMBER: return); // Chamber has no idle timer + #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; @@ -233,8 +245,12 @@ namespace ExtUI { bool isHeaterIdle(const heater_t heater) { #if HEATER_IDLE_HANDLER switch (heater) { - TERN_(HAS_HEATED_BED, case BED: return thermalManager.heater_idle[thermalManager.IDLE_INDEX_BED].timed_out); - TERN_(HAS_HEATED_CHAMBER, case CHAMBER: return false); // Chamber has no idle timer + #if HAS_HEATED_BED + case BED: return thermalManager.heater_idle[thermalManager.IDLE_INDEX_BED].timed_out; + #endif + #if HAS_HEATED_CHAMBER + case CHAMBER: return false; // Chamber has no idle timer + #endif default: return TERN0(HAS_HOTEND, thermalManager.heater_idle[heater - H0].timed_out); } @@ -245,66 +261,66 @@ namespace ExtUI { } #ifdef TOUCH_UI_LCD_TEMP_SCALING - #define GET_TEMP_ADJUSTMENT(A) float(A)/TOUCH_UI_LCD_TEMP_SCALING + #define GET_TEMP_ADJUSTMENT(A) (float(A) / (TOUCH_UI_LCD_TEMP_SCALING)) #else #define GET_TEMP_ADJUSTMENT(A) A #endif - float getActualTemp_celsius(const heater_t heater) { + celsius_float_t getActualTemp_celsius(const heater_t heater) { switch (heater) { - TERN_(HAS_HEATED_BED, case BED: return GET_TEMP_ADJUSTMENT(thermalManager.degBed())); - TERN_(HAS_HEATED_CHAMBER, case CHAMBER: return GET_TEMP_ADJUSTMENT(thermalManager.degChamber())); + #if HAS_HEATED_BED + case BED: return GET_TEMP_ADJUSTMENT(thermalManager.degBed()); + #endif + #if HAS_HEATED_CHAMBER + case CHAMBER: return GET_TEMP_ADJUSTMENT(thermalManager.degChamber()); + #endif default: return GET_TEMP_ADJUSTMENT(thermalManager.degHotend(heater - H0)); } } - float getActualTemp_celsius(const extruder_t extruder) { + celsius_float_t getActualTemp_celsius(const extruder_t extruder) { return GET_TEMP_ADJUSTMENT(thermalManager.degHotend(extruder - E0)); } - float getTargetTemp_celsius(const heater_t heater) { + celsius_float_t getTargetTemp_celsius(const heater_t heater) { switch (heater) { - TERN_(HAS_HEATED_BED, case BED: return GET_TEMP_ADJUSTMENT(thermalManager.degTargetBed())); - TERN_(HAS_HEATED_CHAMBER, case CHAMBER: return GET_TEMP_ADJUSTMENT(thermalManager.degTargetChamber())); + #if HAS_HEATED_BED + case BED: return GET_TEMP_ADJUSTMENT(thermalManager.degTargetBed()); + #endif + #if HAS_HEATED_CHAMBER + case CHAMBER: return GET_TEMP_ADJUSTMENT(thermalManager.degTargetChamber()); + #endif default: return GET_TEMP_ADJUSTMENT(thermalManager.degTargetHotend(heater - H0)); } } - float getTargetTemp_celsius(const extruder_t extruder) { + celsius_float_t getTargetTemp_celsius(const extruder_t extruder) { return GET_TEMP_ADJUSTMENT(thermalManager.degTargetHotend(extruder - E0)); } float getTargetFan_percent(const fan_t fan) { - #if HAS_FAN - return thermalManager.fanPercent(thermalManager.fan_speed[fan - FAN0]); - #else - UNUSED(fan); - return 0; - #endif + UNUSED(fan); + return TERN0(HAS_FAN, thermalManager.fanSpeedPercent(fan - FAN0)); } float getActualFan_percent(const fan_t fan) { - #if HAS_FAN - return thermalManager.fanPercent(thermalManager.scaledFanSpeed(fan - FAN0)); - #else - UNUSED(fan); - return 0; - #endif + UNUSED(fan); + return TERN0(HAS_FAN, thermalManager.scaledFanSpeedPercent(fan - FAN0)); } float getAxisPosition_mm(const axis_t axis) { - return TERN_(JOYSTICK, flags.jogging ? destination[axis] :) current_position[axis]; + return current_position[axis]; } float getAxisPosition_mm(const extruder_t extruder) { const extruder_t old_tool = getActiveTool(); setActiveTool(extruder, true); - const float epos = TERN_(JOYSTICK, flags.jogging ? destination.e :) current_position.e; + const float epos = TERN0(JOYSTICK, flags.jogging) ? destination.e : current_position.e; setActiveTool(old_tool, true); return epos; } - void setAxisPosition_mm(const float position, const axis_t axis, const feedRate_t feedrate/*=0*/) { + void setAxisPosition_mm(const_float_t position, const axis_t axis, const feedRate_t feedrate/*=0*/) { // Get motion limit from software endstops, if any float min, max; soft_endstop.get_manual_axis_limits((AxisEnum)axis, min, max); @@ -322,7 +338,7 @@ namespace ExtUI { line_to_current_position(feedrate ?: manual_feedrate_mm_s[axis]); } - void setAxisPosition_mm(const float position, const extruder_t extruder, const feedRate_t feedrate/*=0*/) { + void setAxisPosition_mm(const_float_t position, const extruder_t extruder, const feedRate_t feedrate/*=0*/) { setActiveTool(extruder, true); current_position.e = position; @@ -340,25 +356,24 @@ namespace ExtUI { #endif } - extruder_t getActiveTool() { - switch (active_extruder) { - case 5: return E5; - case 4: return E4; - case 3: return E3; - case 2: return E2; - case 1: return E1; - default: return E0; + extruder_t getTool(const uint8_t extruder) { + switch (extruder) { + default: + case 0: return E0; case 1: return E1; case 2: return E2; case 3: return E3; + case 4: return E4; case 5: return E5; case 6: return E6; case 7: return E7; } } + extruder_t getActiveTool() { return getTool(active_extruder); } + bool isMoving() { return planner.has_blocks_queued(); } bool canMove(const axis_t axis) { switch (axis) { #if IS_KINEMATIC || ENABLED(NO_MOTION_BEFORE_HOMING) - case X: return TEST(axis_homed, X_AXIS); - case Y: return TEST(axis_homed, Y_AXIS); - case Z: return TEST(axis_homed, Z_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 case X: case Y: case Z: return true; #endif @@ -370,6 +385,9 @@ namespace ExtUI { return !thermalManager.tooColdToExtrude(extruder - E0); } + GcodeSuite::MarlinBusyState getHostKeepaliveState() { return TERN0(HOST_KEEPALIVE_FEATURE, gcode.busy_state); } + bool getHostKeepaliveIsPaused() { return TERN0(HOST_KEEPALIVE_FEATURE, gcode.host_keepalive_is_paused()); } + #if HAS_SOFTWARE_ENDSTOPS bool getSoftEndstopState() { return soft_endstop._enabled; } void setSoftEndstopState(const bool value) { soft_endstop._enabled = value; } @@ -381,18 +399,27 @@ namespace ExtUI { #if AXIS_IS_TMC(X) case X: return stepperX.getMilliamps(); #endif - #if AXIS_IS_TMC(X2) - case X2: return stepperX2.getMilliamps(); - #endif #if AXIS_IS_TMC(Y) case Y: return stepperY.getMilliamps(); #endif - #if AXIS_IS_TMC(Y2) - case Y2: return stepperY2.getMilliamps(); - #endif #if AXIS_IS_TMC(Z) case Z: return stepperZ.getMilliamps(); #endif + #if AXIS_IS_TMC(I) + case I: return stepperI.getMilliamps(); + #endif + #if AXIS_IS_TMC(J) + case J: return stepperJ.getMilliamps(); + #endif + #if AXIS_IS_TMC(K) + case K: return stepperK.getMilliamps(); + #endif + #if AXIS_IS_TMC(X2) + case X2: return stepperX2.getMilliamps(); + #endif + #if AXIS_IS_TMC(Y2) + case Y2: return stepperY2.getMilliamps(); + #endif #if AXIS_IS_TMC(Z2) case Z2: return stepperZ2.getMilliamps(); #endif @@ -430,23 +457,32 @@ namespace ExtUI { }; } - void setAxisCurrent_mA(const float mA, const axis_t axis) { + void setAxisCurrent_mA(const_float_t mA, const axis_t axis) { switch (axis) { #if AXIS_IS_TMC(X) case X: stepperX.rms_current(constrain(mA, 400, 1500)); break; #endif - #if AXIS_IS_TMC(X2) - case X2: stepperX2.rms_current(constrain(mA, 400, 1500)); break; - #endif #if AXIS_IS_TMC(Y) case Y: stepperY.rms_current(constrain(mA, 400, 1500)); break; #endif - #if AXIS_IS_TMC(Y2) - case Y2: stepperY2.rms_current(constrain(mA, 400, 1500)); break; - #endif #if AXIS_IS_TMC(Z) case Z: stepperZ.rms_current(constrain(mA, 400, 1500)); break; #endif + #if AXIS_IS_TMC(I) + case I: stepperI.rms_current(constrain(mA, 400, 1500)); break; + #endif + #if AXIS_IS_TMC(J) + case J: stepperJ.rms_current(constrain(mA, 400, 1500)); break; + #endif + #if AXIS_IS_TMC(K) + case K: stepperK.rms_current(constrain(mA, 400, 1500)); break; + #endif + #if AXIS_IS_TMC(X2) + case X2: stepperX2.rms_current(constrain(mA, 400, 1500)); break; + #endif + #if AXIS_IS_TMC(Y2) + case Y2: stepperY2.rms_current(constrain(mA, 400, 1500)); break; + #endif #if AXIS_IS_TMC(Z2) case Z2: stepperZ2.rms_current(constrain(mA, 400, 1500)); break; #endif @@ -454,7 +490,7 @@ namespace ExtUI { }; } - void setAxisCurrent_mA(const float mA, const extruder_t extruder) { + void setAxisCurrent_mA(const_float_t mA, const extruder_t extruder) { switch (extruder) { #if AXIS_IS_TMC(E0) case E0: stepperE0.rms_current(constrain(mA, 400, 1500)); break; @@ -486,50 +522,59 @@ namespace ExtUI { int getTMCBumpSensitivity(const axis_t axis) { switch (axis) { - TERN_(X_SENSORLESS, case X: return stepperX.homing_threshold()); - TERN_(X2_SENSORLESS, case X2: return stepperX2.homing_threshold()); - TERN_(Y_SENSORLESS, case Y: return stepperY.homing_threshold()); - TERN_(Y2_SENSORLESS, case Y2: return stepperY2.homing_threshold()); - TERN_(Z_SENSORLESS, case Z: return stepperZ.homing_threshold()); - TERN_(Z2_SENSORLESS, case Z2: return stepperZ2.homing_threshold()); - TERN_(Z3_SENSORLESS, case Z3: return stepperZ3.homing_threshold()); - TERN_(Z4_SENSORLESS, case Z4: return stepperZ4.homing_threshold()); + OPTCODE(X_SENSORLESS, case X: return stepperX.homing_threshold()) + OPTCODE(Y_SENSORLESS, case Y: return stepperY.homing_threshold()) + OPTCODE(Z_SENSORLESS, case Z: return stepperZ.homing_threshold()) + OPTCODE(I_SENSORLESS, case I: return stepperI.homing_threshold()) + OPTCODE(J_SENSORLESS, case J: return stepperJ.homing_threshold()) + OPTCODE(K_SENSORLESS, case K: return stepperK.homing_threshold()) + OPTCODE(X2_SENSORLESS, case X2: return stepperX2.homing_threshold()) + OPTCODE(Y2_SENSORLESS, case Y2: return stepperY2.homing_threshold()) + OPTCODE(Z2_SENSORLESS, case Z2: return stepperZ2.homing_threshold()) + OPTCODE(Z3_SENSORLESS, case Z3: return stepperZ3.homing_threshold()) + OPTCODE(Z4_SENSORLESS, case Z4: return stepperZ4.homing_threshold()) default: return 0; } } - void setTMCBumpSensitivity(const float value, const axis_t axis) { + void setTMCBumpSensitivity(const_float_t value, const axis_t axis) { switch (axis) { - #if X_SENSORLESS || Y_SENSORLESS || Z_SENSORLESS - #if X_SENSORLESS - case X: stepperX.homing_threshold(value); break; - #endif - #if X2_SENSORLESS - case X2: stepperX2.homing_threshold(value); break; - #endif - #if Y_SENSORLESS - case Y: stepperY.homing_threshold(value); break; - #endif - #if Y2_SENSORLESS - case Y2: stepperY2.homing_threshold(value); break; - #endif - #if Z_SENSORLESS - case Z: stepperZ.homing_threshold(value); break; - #endif - #if Z2_SENSORLESS - case Z2: stepperZ2.homing_threshold(value); break; - #endif - #if Z3_SENSORLESS - case Z3: stepperZ3.homing_threshold(value); break; - #endif - #if Z4_SENSORLESS - case Z4: stepperZ4.homing_threshold(value); break; - #endif - #else - UNUSED(value); + #if X_SENSORLESS + case X: stepperX.homing_threshold(value); break; + #endif + #if Y_SENSORLESS + case Y: stepperY.homing_threshold(value); break; + #endif + #if Z_SENSORLESS + case Z: stepperZ.homing_threshold(value); break; + #endif + #if I_SENSORLESS + case I: stepperI.homing_threshold(value); break; + #endif + #if J_SENSORLESS + case J: stepperJ.homing_threshold(value); break; + #endif + #if K_SENSORLESS + case K: stepperK.homing_threshold(value); break; + #endif + #if X2_SENSORLESS + case X2: stepperX2.homing_threshold(value); break; + #endif + #if Y2_SENSORLESS + case Y2: stepperY2.homing_threshold(value); break; + #endif + #if Z2_SENSORLESS + case Z2: stepperZ2.homing_threshold(value); break; + #endif + #if Z3_SENSORLESS + case Z3: stepperZ3.homing_threshold(value); break; + #endif + #if Z4_SENSORLESS + case Z4: stepperZ4.homing_threshold(value); break; #endif default: break; } + UNUSED(value); } #endif @@ -538,17 +583,17 @@ namespace ExtUI { } float getAxisSteps_per_mm(const extruder_t extruder) { - UNUSED_E(extruder); + UNUSED(extruder); return planner.settings.axis_steps_per_mm[E_AXIS_N(extruder - E0)]; } - void setAxisSteps_per_mm(const float value, const axis_t axis) { + void setAxisSteps_per_mm(const_float_t value, const axis_t axis) { planner.settings.axis_steps_per_mm[axis] = value; planner.refresh_positioning(); } - void setAxisSteps_per_mm(const float value, const extruder_t extruder) { - UNUSED_E(extruder); + void setAxisSteps_per_mm(const_float_t value, const extruder_t extruder) { + UNUSED(extruder); planner.settings.axis_steps_per_mm[E_AXIS_N(extruder - E0)] = value; planner.refresh_positioning(); } @@ -558,7 +603,7 @@ namespace ExtUI { } feedRate_t getAxisMaxFeedrate_mm_s(const extruder_t extruder) { - UNUSED_E(extruder); + UNUSED(extruder); return planner.settings.max_feedrate_mm_s[E_AXIS_N(extruder - E0)]; } @@ -567,7 +612,7 @@ namespace ExtUI { } void setAxisMaxFeedrate_mm_s(const feedRate_t value, const extruder_t extruder) { - UNUSED_E(extruder); + UNUSED(extruder); planner.set_max_feedrate(E_AXIS_N(extruder - E0), value); } @@ -576,19 +621,17 @@ namespace ExtUI { } float getAxisMaxAcceleration_mm_s2(const extruder_t extruder) { - UNUSED_E(extruder); + UNUSED(extruder); return planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(extruder - E0)]; } - void setAxisMaxAcceleration_mm_s2(const float value, const axis_t axis) { + void setAxisMaxAcceleration_mm_s2(const_float_t value, const axis_t axis) { planner.set_max_acceleration(axis, value); - planner.reset_acceleration_rates(); } - void setAxisMaxAcceleration_mm_s2(const float value, const extruder_t extruder) { - UNUSED_E(extruder); + void setAxisMaxAcceleration_mm_s2(const_float_t value, const extruder_t extruder) { + UNUSED(extruder); planner.set_max_acceleration(E_AXIS_N(extruder - E0), value); - planner.reset_acceleration_rates(); } #if HAS_FILAMENT_SENSOR @@ -599,7 +642,7 @@ namespace ExtUI { #if HAS_FILAMENT_RUNOUT_DISTANCE float getFilamentRunoutDistance_mm() { return runout.runout_distance(); } - void setFilamentRunoutDistance_mm(const float value) { runout.set_runout_distance(constrain(value, 0, 999)); } + void setFilamentRunoutDistance_mm(const_float_t value) { runout.set_runout_distance(constrain(value, 0, 999)); } #endif #endif @@ -610,9 +653,9 @@ namespace ExtUI { caselight.update_enabled(); } - #if DISABLED(CASE_LIGHT_NO_BRIGHTNESS) + #if CASELIGHT_USES_BRIGHTNESS float getCaseLightBrightness_percent() { return ui8_to_percent(caselight.brightness); } - void setCaseLightBrightness_percent(const float value) { + void setCaseLightBrightness_percent(const_float_t value) { caselight.brightness = map(constrain(value, 0, 100), 0, 100, 0, 255); caselight.update_brightness(); } @@ -624,44 +667,41 @@ namespace ExtUI { return (extruder < EXTRUDERS) ? planner.extruder_advance_K[extruder - E0] : 0; } - void setLinearAdvance_mm_mm_s(const float value, const extruder_t extruder) { + void setLinearAdvance_mm_mm_s(const_float_t value, const extruder_t extruder) { if (extruder < EXTRUDERS) - planner.extruder_advance_K[extruder - E0] = constrain(value, 0, 999); + planner.extruder_advance_K[extruder - E0] = constrain(value, 0, 10); } #endif #if HAS_JUNCTION_DEVIATION - float getJunctionDeviation_mm() { - return planner.junction_deviation_mm; - } + float getJunctionDeviation_mm() { return planner.junction_deviation_mm; } - void setJunctionDeviation_mm(const float value) { + void setJunctionDeviation_mm(const_float_t value) { planner.junction_deviation_mm = constrain(value, 0.001, 0.3); TERN_(LIN_ADVANCE, planner.recalculate_max_e_jerk()); } #else + float getAxisMaxJerk_mm_s(const axis_t axis) { return planner.max_jerk[axis]; } + float getAxisMaxJerk_mm_s(const extruder_t) { return planner.max_jerk.e; } + void setAxisMaxJerk_mm_s(const_float_t value, const axis_t axis) { planner.set_max_jerk((AxisEnum)axis, value); } + void setAxisMaxJerk_mm_s(const_float_t value, const extruder_t) { planner.set_max_jerk(E_AXIS, value); } + #endif - float getAxisMaxJerk_mm_s(const axis_t axis) { - return planner.max_jerk[axis]; - } - - float getAxisMaxJerk_mm_s(const extruder_t) { - return planner.max_jerk.e; - } - - void setAxisMaxJerk_mm_s(const float value, const axis_t axis) { - planner.set_max_jerk((AxisEnum)axis, value); - } + #if ENABLED(DUAL_X_CARRIAGE) + uint8_t getIDEX_Mode() { return dual_x_carriage_mode; } + #endif - void setAxisMaxJerk_mm_s(const float value, const extruder_t) { - planner.set_max_jerk(E_AXIS, value); - } + #if PREHEAT_COUNT + uint16_t getMaterial_preset_E(const uint16_t index) { return ui.material_preset[index].hotend_temp; } + #if HAS_HEATED_BED + uint16_t getMaterial_preset_B(const uint16_t index) { return ui.material_preset[index].bed_temp; } + #endif #endif feedRate_t getFeedrate_mm_s() { return feedrate_mm_s; } - int16_t getFlowPercentage(const extruder_t extr) { return planner.flow_percentage[extr]; } + int16_t getFlow_percent(const extruder_t extr) { return planner.flow_percentage[extr]; } feedRate_t getMinFeedrate_mm_s() { return planner.settings.min_feedrate_mm_s; } feedRate_t getMinTravelFeedrate_mm_s() { return planner.settings.min_travel_feedrate_mm_s; } float getPrintingAcceleration_mm_s2() { return planner.settings.acceleration; } @@ -671,18 +711,23 @@ namespace ExtUI { void setFlow_percent(const int16_t flow, const extruder_t extr) { planner.set_flow(extr, flow); } void setMinFeedrate_mm_s(const feedRate_t fr) { planner.settings.min_feedrate_mm_s = fr; } void setMinTravelFeedrate_mm_s(const feedRate_t fr) { planner.settings.min_travel_feedrate_mm_s = fr; } - void setPrintingAcceleration_mm_s2(const float acc) { planner.settings.acceleration = acc; } - void setRetractAcceleration_mm_s2(const float acc) { planner.settings.retract_acceleration = acc; } - void setTravelAcceleration_mm_s2(const float acc) { planner.settings.travel_acceleration = acc; } + void setPrintingAcceleration_mm_s2(const_float_t acc) { planner.settings.acceleration = acc; } + void setRetractAcceleration_mm_s2(const_float_t acc) { planner.settings.retract_acceleration = acc; } + void setTravelAcceleration_mm_s2(const_float_t acc) { planner.settings.travel_acceleration = acc; } #if ENABLED(BABYSTEPPING) + 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; - case Y: babystep.add_steps(Y_AXIS, steps); break; + #if HAS_Y_AXIS + case Y: babystep.add_steps(Y_AXIS, steps); break; + #endif + #endif + #if HAS_Z_AXIS + case Z: babystep.add_steps(Z_AXIS, steps); break; #endif - case Z: babystep.add_steps(Z_AXIS, steps); break; default: return false; }; return true; @@ -721,8 +766,8 @@ namespace ExtUI { hotend_offset[e][axis] += mm; normalizeNozzleOffset(X); - normalizeNozzleOffset(Y); - normalizeNozzleOffset(Z); + TERN_(HAS_Y_AXIS, normalizeNozzleOffset(Y)); + TERN_(HAS_Z_AXIS, normalizeNozzleOffset(Z)); } #else UNUSED(linked_nozzles); @@ -733,11 +778,16 @@ namespace ExtUI { * Converts a mm displacement to a number of whole number of * steps that is at least mm long. */ - int16_t mmToWholeSteps(const float mm, const axis_t axis) { + int16_t mmToWholeSteps(const_float_t mm, const axis_t axis) { const float steps = mm / planner.steps_to_mm[axis]; return steps > 0 ? CEIL(steps) : FLOOR(steps); } - #endif + + float mmFromWholeSteps(int16_t steps, const axis_t axis) { + return steps * planner.steps_to_mm[axis]; + } + + #endif // BABYSTEPPING float getZOffset_mm() { return (0.0f @@ -749,7 +799,7 @@ namespace ExtUI { ); } - void setZOffset_mm(const float value) { + void setZOffset_mm(const_float_t value) { #if HAS_BED_PROBE if (WITHIN(value, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX)) probe.offset.z = value; @@ -767,7 +817,7 @@ namespace ExtUI { return hotend_offset[extruder - E0][axis]; } - void setNozzleOffset_mm(const float value, const axis_t axis, const extruder_t extruder) { + void setNozzleOffset_mm(const_float_t value, const axis_t axis, const extruder_t extruder) { if (extruder - E0 >= HOTENDS) return; hotend_offset[extruder - E0][axis] = value; } @@ -785,58 +835,82 @@ namespace ExtUI { #endif // HAS_HOTEND_OFFSET #if HAS_BED_PROBE - float getProbeOffset_mm(const axis_t axis) { - return probe.offset.pos[axis]; - } - void setProbeOffset_mm(const float val, const axis_t axis) { - probe.offset.pos[axis] = val; - } + float getProbeOffset_mm(const axis_t axis) { return probe.offset.pos[axis]; } + void setProbeOffset_mm(const_float_t val, const axis_t axis) { probe.offset.pos[axis] = val; } #endif #if ENABLED(BACKLASH_GCODE) float getAxisBacklash_mm(const axis_t axis) { return backlash.distance_mm[axis]; } - void setAxisBacklash_mm(const float value, const axis_t axis) + void setAxisBacklash_mm(const_float_t value, const axis_t axis) { backlash.distance_mm[axis] = constrain(value,0,5); } float getBacklashCorrection_percent() { return ui8_to_percent(backlash.correction); } - void setBacklashCorrection_percent(const float value) { backlash.correction = map(constrain(value, 0, 100), 0, 100, 0, 255); } + void setBacklashCorrection_percent(const_float_t value) { backlash.correction = map(constrain(value, 0, 100), 0, 100, 0, 255); } #ifdef BACKLASH_SMOOTHING_MM float getBacklashSmoothing_mm() { return backlash.smoothing_mm; } - void setBacklashSmoothing_mm(const float value) { backlash.smoothing_mm = constrain(value, 0, 999); } + void setBacklashSmoothing_mm(const_float_t value) { backlash.smoothing_mm = constrain(value, 0, 999); } #endif #endif - uint8_t getProgress_percent() { - return ui.get_progress_percent(); - } - uint32_t getProgress_seconds_elapsed() { const duration_t elapsed = print_job_timer.duration(); return elapsed.value; } #if HAS_LEVELING + bool getLevelingActive() { return planner.leveling_active; } void setLevelingActive(const bool state) { set_bed_leveling_enabled(state); } bool getMeshValid() { return leveling_is_valid(); } + #if HAS_MESH + bed_mesh_t& getMeshArray() { return Z_VALUES_ARR; } float getMeshPoint(const xy_uint8_t &pos) { return Z_VALUES(pos.x, pos.y); } - void setMeshPoint(const xy_uint8_t &pos, const float zoff) { - if (WITHIN(pos.x, 0, GRID_MAX_POINTS_X) && WITHIN(pos.y, 0, GRID_MAX_POINTS_Y)) { + 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)) { Z_VALUES(pos.x, pos.y) = zoff; TERN_(ABL_BILINEAR_SUBDIVISION, bed_level_virt_interpolate()); } } - #endif - #endif + + 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; + 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; + destination = current_position; + destination.z = Z_CLEARANCE_BETWEEN_PROBES; + prepare_line_to_destination(); + feedrate_mm_s = XY_PROBE_FEEDRATE; + destination.x = x_target; + destination.y = y_target; + prepare_line_to_destination(); + } + feedrate_mm_s = Z_PROBE_FEEDRATE_FAST; + destination.z = z; + prepare_line_to_destination(); + feedrate_mm_s = old_feedrate; + #else + UNUSED(pos); + UNUSED(z); + #endif + } + + #endif // HAS_MESH + + #endif // HAS_LEVELING #if ENABLED(HOST_PROMPT_SUPPORT) void setHostResponse(const uint8_t response) { host_response_handler(response); } #endif #if ENABLED(PRINTCOUNTER) + char* getFailedPrints_str(char buffer[21]) { strcpy(buffer,i16tostr3left(print_job_timer.getStats().totalPrints - print_job_timer.getStats().finishedPrints)); return buffer; } char* getTotalPrints_str(char buffer[21]) { strcpy(buffer,i16tostr3left(print_job_timer.getStats().totalPrints)); return buffer; } char* getFinishedPrints_str(char buffer[21]) { strcpy(buffer,i16tostr3left(print_job_timer.getStats().finishedPrints)); return buffer; } char* getTotalPrintTime_str(char buffer[21]) { return duration_t(print_job_timer.getStats().printTime).toString(buffer); } @@ -855,14 +929,14 @@ namespace ExtUI { float getPIDValues_Ki(const extruder_t tool) { return unscalePID_i(PID_PARAM(Ki, tool)); } float getPIDValues_Kd(const extruder_t tool) { return unscalePID_d(PID_PARAM(Kd, tool)); } - void setPIDValues(const float p, const float i, const float d, extruder_t tool) { + void setPIDValues(const_float_t p, const_float_t i, const_float_t d, extruder_t tool) { thermalManager.temp_hotend[tool].pid.Kp = p; thermalManager.temp_hotend[tool].pid.Ki = scalePID_i(i); thermalManager.temp_hotend[tool].pid.Kd = scalePID_d(d); thermalManager.updatePID(); } - void startPIDTune(const float temp, extruder_t tool) { + void startPIDTune(const celsius_t temp, extruder_t tool) { thermalManager.PID_autotune(temp, (heater_id_t)tool, 8, true); } #endif @@ -872,14 +946,14 @@ namespace ExtUI { float getBedPIDValues_Ki() { return unscalePID_i(thermalManager.temp_bed.pid.Ki); } float getBedPIDValues_Kd() { return unscalePID_d(thermalManager.temp_bed.pid.Kd); } - void setBedPIDValues(const float p, const float i, const float d) { + void setBedPIDValues(const_float_t p, const_float_t i, const_float_t d) { thermalManager.temp_bed.pid.Kp = p; thermalManager.temp_bed.pid.Ki = scalePID_i(i); thermalManager.temp_bed.pid.Kd = scalePID_d(d); thermalManager.updatePID(); } - void startBedPIDTune(const float temp) { + void startBedPIDTune(const celsius_t temp) { thermalManager.PID_autotune(temp, H_BED, 4, true); } #endif @@ -889,9 +963,9 @@ namespace ExtUI { bool commandsInQueue() { return (planner.movesplanned() || queue.has_commands_queued()); } - bool isAxisPositionKnown(const axis_t axis) { return TEST(axis_known_position, axis); } - bool isAxisPositionKnown(const extruder_t) { return TEST(axis_known_position, E_AXIS); } - bool isPositionKnown() { return all_axes_known(); } + bool isAxisPositionKnown(const axis_t axis) { return axis_is_trusted((AxisEnum)axis); } + bool isAxisPositionKnown(const extruder_t) { return axis_is_trusted(E_AXIS); } + bool isPositionKnown() { return all_axes_trusted(); } bool isMachineHomed() { return all_axes_homed(); } PGM_P getFirmwareName_str() { @@ -899,41 +973,44 @@ namespace ExtUI { return firmware_name; } - void setTargetTemp_celsius(float value, const heater_t heater) { + void setTargetTemp_celsius(const_float_t inval, const heater_t heater) { + float value = inval; #ifdef TOUCH_UI_LCD_TEMP_SCALING value *= TOUCH_UI_LCD_TEMP_SCALING; #endif enableHeater(heater); - #if HAS_HEATED_CHAMBER - if (heater == CHAMBER) - thermalManager.setTargetChamber(LROUND(constrain(value, 0, CHAMBER_MAXTEMP - 10))); - else - #endif - #if HAS_HEATED_BED - if (heater == BED) - thermalManager.setTargetBed(LROUND(constrain(value, 0, BED_MAX_TARGET))); - else - #endif - { + switch (heater) { + #if HAS_HEATED_CHAMBER + case CHAMBER: thermalManager.setTargetChamber(LROUND(constrain(value, 0, CHAMBER_MAX_TARGET))); break; + #endif + #if HAS_COOLER + case COOLER: thermalManager.setTargetCooler(LROUND(constrain(value, 0, COOLER_MAXTEMP))); break; + #endif + #if HAS_HEATED_BED + case BED: thermalManager.setTargetBed(LROUND(constrain(value, 0, BED_MAX_TARGET))); break; + #endif + default: { #if HAS_HOTEND const int16_t e = heater - H0; - thermalManager.setTargetHotend(LROUND(constrain(value, 0, thermalManager.heater_maxtemp[e] - HOTEND_OVERSHOOT)), e); + thermalManager.setTargetHotend(LROUND(constrain(value, 0, thermalManager.hotend_max_target(e))), e); #endif - } + } break; + } } - void setTargetTemp_celsius(float value, const extruder_t extruder) { + void setTargetTemp_celsius(const_float_t inval, const extruder_t extruder) { + float value = inval; #ifdef TOUCH_UI_LCD_TEMP_SCALING value *= TOUCH_UI_LCD_TEMP_SCALING; #endif #if HAS_HOTEND const int16_t e = extruder - E0; enableHeater(extruder); - thermalManager.setTargetHotend(LROUND(constrain(value, 0, thermalManager.heater_maxtemp[e] - HOTEND_OVERSHOOT)), e); + thermalManager.setTargetHotend(LROUND(constrain(value, 0, thermalManager.hotend_max_target(e))), e); #endif } - void setTargetFan_percent(const float value, const fan_t fan) { + void setTargetFan_percent(const_float_t value, const fan_t fan) { #if HAS_FAN if (fan < FAN_COUNT) thermalManager.set_fan_speed(fan - FAN0, map(constrain(value, 0, 100), 0, 100, 0, 255)); @@ -943,45 +1020,48 @@ namespace ExtUI { #endif } - void setFeedrate_percent(const float value) { - feedrate_percentage = constrain(value, 10, 500); + void setFeedrate_percent(const_float_t value) { feedrate_percentage = constrain(value, 10, 500); } + + void coolDown() { + #if HAS_HOTEND + HOTEND_LOOP() thermalManager.setTargetHotend(0, e); + #endif + TERN_(HAS_HEATED_BED, thermalManager.setTargetBed(0)); + TERN_(HAS_FAN, thermalManager.zero_fan_speeds()); } - void setUserConfirmed() { - TERN_(HAS_RESUME_CONTINUE, wait_for_user = false); + bool awaitingUserConfirm() { + return TERN0(HAS_RESUME_CONTINUE, wait_for_user) || getHostKeepaliveIsPaused(); } + void setUserConfirmed() { TERN_(HAS_RESUME_CONTINUE, wait_for_user = false); } + + #if M600_PURGE_MORE_RESUMABLE + void setPauseMenuResponse(PauseMenuResponse response) { pause_menu_response = response; } + #endif void printFile(const char *filename) { - UNUSED(filename); - IFSD(card.openAndPrintFile(filename), NOOP); + TERN(SDSUPPORT, card.openAndPrintFile(filename), UNUSED(filename)); } bool isPrintingFromMediaPaused() { - return IFSD(isPrintingFromMedia() && !IS_SD_PRINTING(), false); + return TERN0(SDSUPPORT, IS_SD_PAUSED()); } - bool isPrintingFromMedia() { - #if ENABLED(SDSUPPORT) - // Account for when IS_SD_PRINTING() reports the end of the - // print when there is still SD card data in the planner. - flags.was_sd_printing = card.isFileOpen() || (flags.was_sd_printing && commandsInQueue()); - return flags.was_sd_printing; - #else - return false; - #endif - } + bool isPrintingFromMedia() { return TERN0(SDSUPPORT, IS_SD_PRINTING() || IS_SD_PAUSED()); } bool isPrinting() { - return (commandsInQueue() || isPrintingFromMedia() || IFSD(IS_SD_PRINTING(), false)); + return commandsInQueue() || isPrintingFromMedia() || printJobOngoing() || printingIsPaused(); } - bool isMediaInserted() { - return IFSD(IS_SD_INSERTED() && card.isMounted(), false); + bool isPrintingPaused() { + return isPrinting() && (isPrintingFromMediaPaused() || print_job_timer.isPaused()); } - void pausePrint() { ui.pause_print(); } + bool isMediaInserted() { return TERN0(SDSUPPORT, IS_SD_INSERTED()); } + + void pausePrint() { ui.pause_print(); } void resumePrint() { ui.resume_print(); } - void stopPrint() { ui.abort_print(); } + void stopPrint() { ui.abort_print(); } void onUserConfirmRequired_P(PGM_P const pstr) { char msg[strlen_P(pstr) + 1]; @@ -1012,27 +1092,27 @@ namespace ExtUI { } const char* FileList::filename() { - return IFSD(card.longFilename[0] ? card.longFilename : card.filename, ""); + return TERN(SDSUPPORT, card.longest_filename(), ""); } const char* FileList::shortFilename() { - return IFSD(card.filename, ""); + return TERN(SDSUPPORT, card.filename, ""); } const char* FileList::longFilename() { - return IFSD(card.longFilename, ""); + return TERN(SDSUPPORT, card.longFilename, ""); } bool FileList::isDir() { - return IFSD(card.flag.filenameIsDir, false); + return TERN0(SDSUPPORT, card.flag.filenameIsDir); } uint16_t FileList::count() { - return IFSD((num_files = (num_files == 0xFFFF ? card.get_num_Files() : num_files)), 0); + return TERN0(SDSUPPORT, (num_files = (num_files == 0xFFFF ? card.get_num_Files() : num_files))); } bool FileList::isAtRootDir() { - return IFSD(card.flag.workDirIsRoot, true); + return TERN1(SDSUPPORT, card.flag.workDirIsRoot); } void FileList::upDir() { @@ -1053,11 +1133,9 @@ namespace ExtUI { } // namespace ExtUI -// At the moment, we piggy-back off the ultralcd calls, but this could be cleaned up in the future +// At the moment we hook into MarlinUI methods, but this could be cleaned up in the future -void MarlinUI::init() { - ExtUI::onStartup(); -} +void MarlinUI::init() { ExtUI::onStartup(); } void MarlinUI::update() { ExtUI::onIdle(); } diff --git a/Marlin/src/lcd/extui/ui_api.h b/Marlin/src/lcd/extui/ui_api.h index 15122ec69e15..faa6c8f41a85 100644 --- a/Marlin/src/lcd/extui/ui_api.h +++ b/Marlin/src/lcd/extui/ui_api.h @@ -39,10 +39,15 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #include "../../inc/MarlinConfig.h" +#include "../marlinui.h" +#include "../../gcode/gcode.h" +#if M600_PURGE_MORE_RESUMABLE + #include "../../feature/pause.h" +#endif namespace ExtUI { @@ -52,11 +57,11 @@ namespace ExtUI { static constexpr size_t eeprom_data_size = 48; - enum axis_t : uint8_t { X, Y, Z, X2, Y2, Z2, Z3, Z4 }; + enum axis_t : uint8_t { X, Y, Z, I, J, K, X2, Y2, Z2, Z3, Z4 }; enum extruder_t : uint8_t { E0, E1, E2, E3, E4, E5, E6, E7 }; - enum heater_t : uint8_t { H0, H1, H2, H3, H4, H5, BED, CHAMBER }; + enum heater_t : uint8_t { H0, H1, H2, H3, H4, H5, BED, CHAMBER, COOLER }; enum fan_t : uint8_t { FAN0, FAN1, FAN2, FAN3, FAN4, FAN5, FAN6, FAN7 }; - enum result_t : uint8_t { PID_BAD_EXTRUDER_NUM, PID_TEMP_TOO_HIGH, PID_TUNING_TIMEOUT, PID_DONE }; + enum result_t : uint8_t { PID_STARTED, PID_BAD_EXTRUDER_NUM, PID_TEMP_TOO_HIGH, PID_TUNING_TIMEOUT, PID_DONE }; constexpr uint8_t extruderCount = EXTRUDERS; constexpr uint8_t hotendCount = HOTENDS; @@ -77,6 +82,9 @@ namespace ExtUI { void injectCommands(char * const); bool commandsInQueue(); + GcodeSuite::MarlinBusyState getHostKeepaliveState(); + bool getHostKeepaliveIsPaused(); + bool isHeaterIdle(const heater_t); bool isHeaterIdle(const extruder_t); void enableHeater(const heater_t); @@ -101,17 +109,17 @@ namespace ExtUI { #if HAS_TRINAMIC_CONFIG float getAxisCurrent_mA(const axis_t); float getAxisCurrent_mA(const extruder_t); - void setAxisCurrent_mA(const float, const axis_t); - void setAxisCurrent_mA(const float, const extruder_t); + void setAxisCurrent_mA(const_float_t, const axis_t); + void setAxisCurrent_mA(const_float_t, const extruder_t); int getTMCBumpSensitivity(const axis_t); - void setTMCBumpSensitivity(const float, const axis_t); + void setTMCBumpSensitivity(const_float_t, const axis_t); #endif - float getActualTemp_celsius(const heater_t); - float getActualTemp_celsius(const extruder_t); - float getTargetTemp_celsius(const heater_t); - float getTargetTemp_celsius(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 getAxisPosition_mm(const axis_t); @@ -124,14 +132,36 @@ namespace ExtUI { float getAxisMaxAcceleration_mm_s2(const extruder_t); feedRate_t getMinFeedrate_mm_s(); feedRate_t getMinTravelFeedrate_mm_s(); + feedRate_t getFeedrate_mm_s(); float getPrintingAcceleration_mm_s2(); float getRetractAcceleration_mm_s2(); float getTravelAcceleration_mm_s2(); float getFeedrate_percent(); - int16_t getFlowPercentage(const extruder_t); - uint8_t getProgress_percent(); + int16_t getFlow_percent(const extruder_t); + + 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(); + #if PREHEAT_COUNT + uint16_t getMaterial_preset_E(const uint16_t); + #if HAS_HEATED_BED + uint16_t getMaterial_preset_B(const uint16_t); + #endif + #endif + + #if ENABLED(DUAL_X_CARRIAGE) + uint8_t getIDEX_Mode(); + #endif + + #if ENABLED(SHOW_REMAINING_TIME) + inline uint32_t getProgress_seconds_remaining() { return ui.get_remaining_time(); } + #endif + #if HAS_LEVELING bool getLevelingActive(); void setLevelingActive(const bool); @@ -139,15 +169,21 @@ namespace ExtUI { #if HAS_MESH bed_mesh_t& getMeshArray(); float getMeshPoint(const xy_uint8_t &pos); - void setMeshPoint(const xy_uint8_t &pos, const float zval); - void onMeshUpdate(const int8_t xpos, const int8_t ypos, const float zval); - inline void onMeshUpdate(const xy_int8_t &pos, const float zval) { onMeshUpdate(pos.x, pos.y, zval); } - - typedef enum : unsigned char { - MESH_START, // Prior to start of probe - MESH_FINISH, // Following probe of all points - PROBE_START, // Beginning probe of grid location - PROBE_FINISH // Finished probe of grid location + void setMeshPoint(const xy_uint8_t &pos, const_float_t zval); + void moveToMeshPoint(const xy_uint8_t &pos, const_float_t z); + void onMeshLevelingStart(); + void 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); } + + typedef enum : uint8_t { + G29_START, // Prior to start of probe + G29_FINISH, // Following probe of all points + G29_POINT_START, // Beginning probe of grid location + G29_POINT_FINISH, // Finished probe of grid location + G26_START, + G26_FINISH, + G26_POINT_START, + G26_POINT_FINISH } probe_state_t; void onMeshUpdate(const int8_t xpos, const int8_t ypos, probe_state_t state); inline void onMeshUpdate(const xy_int8_t &pos, probe_state_t state) { onMeshUpdate(pos.x, pos.y, state); } @@ -158,7 +194,14 @@ namespace ExtUI { void setHostResponse(const uint8_t); #endif + inline void simulateUserClick() { + #if EITHER(HAS_LCD_MENU, EXTENSIBLE_UI) + ui.lcd_clicked = true; + #endif + } + #if ENABLED(PRINTCOUNTER) + char* getFailedPrints_str(char buffer[21]); char* getTotalPrints_str(char buffer[21]); char* getFinishedPrints_str(char buffer[21]); char* getTotalPrintTime_str(char buffer[21]); @@ -166,47 +209,55 @@ namespace ExtUI { char* getFilamentUsed_str(char buffer[21]); #endif - void setTargetTemp_celsius(const float, const heater_t); - void setTargetTemp_celsius(const float, const extruder_t); - void setTargetFan_percent(const float, const fan_t); - void setAxisPosition_mm(const float, const axis_t, const feedRate_t=0); - void setAxisPosition_mm(const float, const extruder_t, const feedRate_t=0); - void setAxisSteps_per_mm(const float, const axis_t); - void setAxisSteps_per_mm(const float, const extruder_t); + 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(); + 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); + 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); void setAxisMaxFeedrate_mm_s(const feedRate_t, const extruder_t); - void setAxisMaxAcceleration_mm_s2(const float, const axis_t); - void setAxisMaxAcceleration_mm_s2(const float, const extruder_t); + void setAxisMaxAcceleration_mm_s2(const_float_t, const axis_t); + void setAxisMaxAcceleration_mm_s2(const_float_t, const extruder_t); void setFeedrate_mm_s(const feedRate_t); void setMinFeedrate_mm_s(const feedRate_t); void setMinTravelFeedrate_mm_s(const feedRate_t); - void setPrintingAcceleration_mm_s2(const float); - void setRetractAcceleration_mm_s2(const float); - void setTravelAcceleration_mm_s2(const float); - void setFeedrate_percent(const float); + void setPrintingAcceleration_mm_s2(const_float_t); + void setRetractAcceleration_mm_s2(const_float_t); + void setTravelAcceleration_mm_s2(const_float_t); + void setFeedrate_percent(const_float_t); void setFlow_percent(const int16_t, const extruder_t); + bool awaitingUserConfirm(); void setUserConfirmed(); + #if M600_PURGE_MORE_RESUMABLE + void setPauseMenuResponse(PauseMenuResponse); + #endif + #if ENABLED(LIN_ADVANCE) float getLinearAdvance_mm_mm_s(const extruder_t); - void setLinearAdvance_mm_mm_s(const float, const extruder_t); + void setLinearAdvance_mm_mm_s(const_float_t, const extruder_t); #endif #if HAS_JUNCTION_DEVIATION float getJunctionDeviation_mm(); - void setJunctionDeviation_mm(const float); + void setJunctionDeviation_mm(const_float_t); #else float getAxisMaxJerk_mm_s(const axis_t); float getAxisMaxJerk_mm_s(const extruder_t); - void setAxisMaxJerk_mm_s(const float, const axis_t); - void setAxisMaxJerk_mm_s(const float, const extruder_t); + void setAxisMaxJerk_mm_s(const_float_t, const axis_t); + void setAxisMaxJerk_mm_s(const_float_t, const extruder_t); #endif + extruder_t getTool(const uint8_t extruder); extruder_t getActiveTool(); void setActiveTool(const extruder_t, bool no_move); #if ENABLED(BABYSTEPPING) - int16_t mmToWholeSteps(const float mm, const axis_t axis); + int16_t mmToWholeSteps(const_float_t mm, const axis_t axis); + float mmFromWholeSteps(int16_t steps, const axis_t axis); bool babystepAxis_steps(const int16_t steps, const axis_t axis); void smartAdjustAxis_steps(const int16_t steps, const axis_t axis, bool linked_nozzles); @@ -214,28 +265,28 @@ namespace ExtUI { #if HAS_HOTEND_OFFSET float getNozzleOffset_mm(const axis_t, const extruder_t); - void setNozzleOffset_mm(const float, 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 float getZOffset_mm(); - void setZOffset_mm(const float); + void setZOffset_mm(const_float_t); #if HAS_BED_PROBE float getProbeOffset_mm(const axis_t); - void setProbeOffset_mm(const float, const axis_t); + void setProbeOffset_mm(const_float_t, const axis_t); #endif #if ENABLED(BACKLASH_GCODE) float getAxisBacklash_mm(const axis_t); - void setAxisBacklash_mm(const float, const axis_t); + void setAxisBacklash_mm(const_float_t, const axis_t); float getBacklashCorrection_percent(); - void setBacklashCorrection_percent(const float); + void setBacklashCorrection_percent(const_float_t); #ifdef BACKLASH_SMOOTHING_MM float getBacklashSmoothing_mm(); - void setBacklashSmoothing_mm(const float); + void setBacklashSmoothing_mm(const_float_t); #endif #endif @@ -247,7 +298,7 @@ namespace ExtUI { #if HAS_FILAMENT_RUNOUT_DISTANCE float getFilamentRunoutDistance_mm(); - void setFilamentRunoutDistance_mm(const float); + void setFilamentRunoutDistance_mm(const_float_t); #endif #endif @@ -257,7 +308,7 @@ namespace ExtUI { #if DISABLED(CASE_LIGHT_NO_BRIGHTNESS) float getCaseLightBrightness_percent(); - void setCaseLightBrightness_percent(const float); + void setCaseLightBrightness_percent(const_float_t); #endif #endif @@ -265,16 +316,16 @@ namespace ExtUI { float getPIDValues_Kp(const extruder_t); float getPIDValues_Ki(const extruder_t); float getPIDValues_Kd(const extruder_t); - void setPIDValues(const float, const float, const float, extruder_t); - void startPIDTune(const float, extruder_t); + void setPIDValues(const_float_t, const_float_t , const_float_t , extruder_t); + void startPIDTune(const celsius_t, extruder_t); #endif #if ENABLED(PIDTEMPBED) float getBedPIDValues_Kp(); float getBedPIDValues_Ki(); float getBedPIDValues_Kd(); - void setBedPIDValues(const float, const float, const float); - void startBedPIDTune(const float); + void setBedPIDValues(const_float_t, const_float_t , const_float_t); + void startBedPIDTune(const celsius_t); #endif /** @@ -289,8 +340,8 @@ namespace ExtUI { FORCE_INLINE uint32_t safe_millis() { return millis(); } // TODO: Implement for AVR #endif - void delay_us(unsigned long us); - void delay_ms(unsigned long ms); + void delay_us(uint32_t us); + void delay_ms(uint32_t ms); void yield(); /** @@ -302,6 +353,7 @@ namespace ExtUI { bool isPrintingFromMediaPaused(); bool isPrintingFromMedia(); bool isPrinting(); + bool isPrintingPaused(); void printFile(const char *filename); void stopPrint(); @@ -343,14 +395,20 @@ namespace ExtUI { void onPrintTimerStarted(); void onPrintTimerPaused(); void onPrintTimerStopped(); + void onPrintFinished(); void onFilamentRunout(const extruder_t extruder); void onUserConfirmRequired(const char * const msg); void onUserConfirmRequired_P(PGM_P const pstr); void onStatusChanged(const char * const msg); void onStatusChanged_P(PGM_P const pstr); + void onHomingStart(); + void onHomingComplete(); + void onSteppersDisabled(); + void onSteppersEnabled(); void onFactoryReset(); void onStoreSettings(char *); void onLoadSettings(const char *); + void onPostprocessSettings(); void onConfigurationStoreWritten(bool success); void onConfigurationStoreRead(bool success); #if ENABLED(POWER_LOSS_RECOVERY) diff --git a/Marlin/src/lcd/fontutils.cpp b/Marlin/src/lcd/fontutils.cpp index 5bf07e1bd458..90fcb2ae7c47 100644 --- a/Marlin/src/lcd/fontutils.cpp +++ b/Marlin/src/lcd/fontutils.cpp @@ -9,8 +9,10 @@ #include "../inc/MarlinConfig.h" +#define MAX_UTF8_CHAR_SIZE 4 + #if HAS_WIRED_LCD - #include "ultralcd.h" + #include "marlinui.h" #include "../MarlinCore.h" #endif @@ -73,12 +75,19 @@ 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 */ +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 */ uint8_t* get_utf8_value_cb(uint8_t *pstart, read_byte_cb_t cb_read_byte, wchar_t *pval) { uint32_t val = 0; uint8_t *p = pstart; + #define NEXT_6_BITS() do{ val <<= 6; p++; valcur = cb_read_byte(p); val |= (valcur & 0x3F); }while(0) + uint8_t valcur = cb_read_byte(p); if (0 == (0x80 & valcur)) { val = valcur; @@ -86,74 +95,51 @@ uint8_t* get_utf8_value_cb(uint8_t *pstart, read_byte_cb_t cb_read_byte, wchar_t } else if (0xC0 == (0xE0 & valcur)) { val = valcur & 0x1F; - val <<= 6; - p++; - valcur = cb_read_byte(p); - val |= (valcur & 0x3F); - p++; - } - else if (0xE0 == (0xF0 & valcur)) { - val = valcur & 0x0F; - val <<= 6; p++; - valcur = cb_read_byte(p); - val |= (valcur & 0x3F); - val <<= 6; p++; - valcur = cb_read_byte(p); - val |= (valcur & 0x3F); + NEXT_6_BITS(); p++; } - else if (0xF0 == (0xF8 & valcur)) { - val = valcur & 0x07; - val <<= 6; p++; - valcur = cb_read_byte(p); - val |= (valcur & 0x3F); - val <<= 6; p++; - valcur = cb_read_byte(p); - val |= (valcur & 0x3F); - val <<= 6; p++; - valcur = cb_read_byte(p); - val |= (valcur & 0x3F); - p++; - } - else if (0xF8 == (0xFC & valcur)) { - val = valcur & 0x03; - val <<= 6; p++; - valcur = cb_read_byte(p); - val |= (valcur & 0x3F); - val <<= 6; p++; - valcur = cb_read_byte(p); - val |= (valcur & 0x3F); - val <<= 6; p++; - valcur = cb_read_byte(p); - val |= (valcur & 0x3F); - val <<= 6; p++; - valcur = cb_read_byte(p); - val |= (valcur & 0x3F); - p++; - } - else if (0xFC == (0xFE & valcur)) { - val = valcur & 0x01; - val <<= 6; p++; - valcur = cb_read_byte(p); - val |= (valcur & 0x3F); - val <<= 6; p++; - valcur = cb_read_byte(p); - val |= (valcur & 0x3F); - val <<= 6; p++; - valcur = cb_read_byte(p); - val |= (valcur & 0x3F); - val <<= 6; p++; - valcur = cb_read_byte(p); - val |= (valcur & 0x3F); - val <<= 6; p++; - valcur = cb_read_byte(p); - val |= (valcur & 0x3F); - p++; - } - else if (0x80 == (0xC0 & valcur)) - for (; 0x80 == (0xC0 & valcur); ) { p++; valcur = cb_read_byte(p); } + #if MAX_UTF8_CHAR_SIZE >= 3 + else if (0xE0 == (0xF0 & valcur)) { + val = valcur & 0x0F; + NEXT_6_BITS(); + NEXT_6_BITS(); + p++; + } + #endif + #if MAX_UTF8_CHAR_SIZE >= 4 + else if (0xF0 == (0xF8 & valcur)) { + val = valcur & 0x07; + NEXT_6_BITS(); + NEXT_6_BITS(); + NEXT_6_BITS(); + p++; + } + #endif + #if MAX_UTF8_CHAR_SIZE >= 5 + else if (0xF8 == (0xFC & valcur)) { + val = valcur & 0x03; + NEXT_6_BITS(); + NEXT_6_BITS(); + NEXT_6_BITS(); + NEXT_6_BITS(); + p++; + } + #endif + #if MAX_UTF8_CHAR_SIZE >= 6 + else if (0xFC == (0xFE & valcur)) { + val = valcur & 0x01; + NEXT_6_BITS(); + NEXT_6_BITS(); + NEXT_6_BITS(); + NEXT_6_BITS(); + NEXT_6_BITS(); + p++; + } + #endif + else if (!utf8_is_start_byte_of_char(valcur)) + for (; !utf8_is_start_byte_of_char(valcur); ) { p++; valcur = cb_read_byte(p); } else - for (; ((0xFE & valcur) > 0xFC); ) { p++; valcur = cb_read_byte(p); } + for (; 0xFC < (0xFE & valcur); ) { p++; valcur = cb_read_byte(p); } if (pval) *pval = val; @@ -162,12 +148,12 @@ uint8_t* get_utf8_value_cb(uint8_t *pstart, read_byte_cb_t cb_read_byte, wchar_t static inline uint8_t utf8_strlen_cb(const char *pstart, read_byte_cb_t cb_read_byte) { uint8_t cnt = 0; - uint8_t *pnext = (uint8_t *)pstart; - for (;;) { - wchar_t ch; - pnext = get_utf8_value_cb(pnext, cb_read_byte, &ch); - if (!ch) break; - cnt++; + uint8_t *p = (uint8_t *)pstart; + if (p) for (;;) { + const uint8_t b = cb_read_byte(p); + if (!b) break; + if (utf8_is_start_byte_of_char(b)) cnt++; + p++; } return cnt; } @@ -179,3 +165,26 @@ uint8_t utf8_strlen(const char *pstart) { 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; + uint8_t char_idx = 0; + uint8_t byte_idx = 0; + for (;;) { + const uint8_t b = cb_read_byte(p + byte_idx); + if (!b) return byte_idx; // Termination byte of string + if (utf8_is_start_byte_of_char(b)) { + char_idx++; + if (char_idx == charnum + 1) return byte_idx; + } + byte_idx++; + } +} + +uint8_t utf8_byte_pos_by_char_num(const char *pstart, const uint8_t charnum) { + return utf8_byte_pos_by_char_num_cb(pstart, read_byte_ram, charnum); +} + +uint8_t utf8_byte_pos_by_char_num_P(PGM_P pstart, const uint8_t charnum) { + return utf8_byte_pos_by_char_num_cb(pstart, read_byte_rom, charnum); +} diff --git a/Marlin/src/lcd/fontutils.h b/Marlin/src/lcd/fontutils.h index 74c4a87fb9d3..04ff81148f96 100644 --- a/Marlin/src/lcd/fontutils.h +++ b/Marlin/src/lcd/fontutils.h @@ -41,3 +41,7 @@ uint8_t* get_utf8_value_cb(uint8_t *pstart, read_byte_cb_t cb_read_byte, wchar_t /* Returns length of string in CHARACTERS, NOT BYTES */ uint8_t utf8_strlen(const char *pstart); uint8_t utf8_strlen_P(PGM_P pstart); + +/* Returns start byte position of desired char number */ +uint8_t utf8_byte_pos_by_char_num(const char *pstart, const uint8_t charnum); +uint8_t utf8_byte_pos_by_char_num_P(PGM_P pstart, const uint8_t charnum); diff --git a/Marlin/src/lcd/language/language_an.h b/Marlin/src/lcd/language/language_an.h index a5030fcd5636..787096994f7d 100644 --- a/Marlin/src/lcd/language/language_an.h +++ b/Marlin/src/lcd/language/language_an.h @@ -42,7 +42,7 @@ namespace Language_an { PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Tarcheta sacada"); PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Endstops"); // Max length 8 characters PROGMEM Language_Str MSG_MAIN = _UxGT("Menu prencipal"); - PROGMEM Language_Str MSG_AUTOSTART = _UxGT("Inicio automatico"); + PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Inicio automatico"); PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Amortar motors"); PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Levar a l'orichen"); PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Orichen X"); @@ -85,10 +85,11 @@ namespace Language_an { PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Mover Z"); PROGMEM Language_Str MSG_MOVE_E = _UxGT("Extrusor"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Extrusor *"); - PROGMEM Language_Str MSG_MOVE_Z_DIST = _UxGT("Mover %smm"); + PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Mover %smm"); PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mover 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mover 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Mover 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Mover 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Velocidat"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Base Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Boquilla"); @@ -121,7 +122,7 @@ namespace Language_an { PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatura"); PROGMEM Language_Str MSG_MOTION = _UxGT("Movimiento"); PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filamento"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm³"); + PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm") SUPERSCRIPT_THREE; PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Fil. Dia."); PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Fil. Dia. *"); PROGMEM Language_Str MSG_CONTRAST = _UxGT("Contraste"); diff --git a/Marlin/src/lcd/language/language_bg.h b/Marlin/src/lcd/language/language_bg.h index dcb06e31e703..0d4291b8355d 100644 --- a/Marlin/src/lcd/language/language_bg.h +++ b/Marlin/src/lcd/language/language_bg.h @@ -40,7 +40,7 @@ namespace Language_bg { PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Картата е поставена"); PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Картата е извадена"); PROGMEM Language_Str MSG_MAIN = _UxGT("Меню"); - PROGMEM Language_Str MSG_AUTOSTART = _UxGT("Автостарт"); + PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Автостарт"); PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Изкл. двигатели"); PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Паркиране"); PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Задай Начало"); @@ -75,10 +75,11 @@ namespace Language_bg { PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Движение по Z"); PROGMEM Language_Str MSG_MOVE_E = _UxGT("Екструдер"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Екструдер *"); - PROGMEM Language_Str MSG_MOVE_Z_DIST = _UxGT("Премести с %smm"); + PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Премести с %smm"); PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Премести с 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Премести с 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Премести с 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Премести с 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Скорост"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Bed Z"); PROGMEM Language_Str MSG_NOZZLE = " " LCD_STR_THERMOMETER _UxGT(" Дюза"); @@ -106,7 +107,7 @@ namespace Language_bg { PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Температура"); PROGMEM Language_Str MSG_MOTION = _UxGT("Движение"); PROGMEM Language_Str MSG_FILAMENT = _UxGT("Нишка"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm³"); + PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm") SUPERSCRIPT_THREE; PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Диам. нишка"); PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Диам. нишка *"); PROGMEM Language_Str MSG_CONTRAST = _UxGT("LCD контраст"); diff --git a/Marlin/src/lcd/language/language_ca.h b/Marlin/src/lcd/language/language_ca.h index 0657c4a75959..f97a783d0183 100644 --- a/Marlin/src/lcd/language/language_ca.h +++ b/Marlin/src/lcd/language/language_ca.h @@ -38,7 +38,7 @@ namespace Language_ca { PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Targeta extreta."); PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Endstops"); PROGMEM Language_Str MSG_MAIN = _UxGT("Menú principal"); - PROGMEM Language_Str MSG_AUTOSTART = _UxGT("Inici automatic"); + PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Inici automatic"); PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Desactiva motors"); PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Menu de depuracio"); PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Test barra progres"); @@ -85,10 +85,11 @@ namespace Language_ca { PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Mou Z"); PROGMEM Language_Str MSG_MOVE_E = _UxGT("Extrusor"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Extrusor *"); - PROGMEM Language_Str MSG_MOVE_Z_DIST = _UxGT("Mou %smm"); + PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Mou %smm"); PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mou 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mou 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Mou 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Mou 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Velocitat"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Llit Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Nozzle"); @@ -111,7 +112,7 @@ namespace Language_ca { PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatura"); PROGMEM Language_Str MSG_MOTION = _UxGT("Moviment"); PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filament"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E en mm³"); + PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E en mm") SUPERSCRIPT_THREE; PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Diam. Fil."); PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Diam. Fil. *"); PROGMEM Language_Str MSG_CONTRAST = _UxGT("Contrast de LCD"); diff --git a/Marlin/src/lcd/language/language_cz.h b/Marlin/src/lcd/language/language_cz.h index 9cbd7042d613..fa6a8e21a3ac 100644 --- a/Marlin/src/lcd/language/language_cz.h +++ b/Marlin/src/lcd/language/language_cz.h @@ -57,7 +57,7 @@ namespace Language_cz { PROGMEM Language_Str MSG_MAIN = _UxGT("Hlavní nabídka"); PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Další nastavení"); PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Konfigurace"); - PROGMEM Language_Str MSG_AUTOSTART = _UxGT("Autostart"); + PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Autostart"); PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Uvolnit motory"); PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Nabídka ladění"); #if LCD_WIDTH >= 20 @@ -98,12 +98,8 @@ namespace Language_cz { PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Zahřát vlastní"); PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Zchladit"); PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Ovládání laseru"); - PROGMEM Language_Str MSG_LASER_OFF = _UxGT("Vypnout laser"); - PROGMEM Language_Str MSG_LASER_ON = _UxGT("Zapnout laser"); PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Výkon laseru"); PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Vřeteno ovládání"); - PROGMEM Language_Str MSG_SPINDLE_OFF = _UxGT("Vřeteno vyp"); - PROGMEM Language_Str MSG_SPINDLE_ON = _UxGT("Vřeteno zap"); PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Vřeteno výkon"); PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Vřeteno opačně"); PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Zapnout napájení"); @@ -113,7 +109,7 @@ namespace Language_cz { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Posunout osy"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Vyrovnat podložku"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Vyrovnat podložku"); - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Vyrovnat rohy"); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Vyrovnat rohy"); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Další roh"); PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Editor sítě"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Upravit síť bodů"); @@ -123,7 +119,7 @@ namespace Language_cz { PROGMEM Language_Str MSG_MESH_Y = _UxGT("Index Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Hodnota Z"); - PROGMEM Language_Str MSG_USER_MENU = _UxGT("Vlastní příkazy"); + PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Vlastní příkazy"); PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 test sondy"); PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 bod"); PROGMEM Language_Str MSG_M48_DEVIATION = _UxGT("Odchylka"); @@ -241,10 +237,11 @@ namespace Language_cz { PROGMEM Language_Str MSG_MOVE_E = _UxGT("Extrudér"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Extrudér *"); PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Hotend je studený"); - PROGMEM Language_Str MSG_MOVE_Z_DIST = _UxGT("Posunout o %smm"); + PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Posunout o %smm"); PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Posunout o 0,1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Posunout o 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Posunout o 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Posunout o 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Rychlost"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Výška podl."); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Tryska"); @@ -301,7 +298,7 @@ namespace Language_cz { PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Teplota"); PROGMEM Language_Str MSG_MOTION = _UxGT("Pohyb"); PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filament"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E na mm³"); + PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E na mm") SUPERSCRIPT_THREE; PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Fil. Prum."); PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Fil. Prum. *"); PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Vysunout mm"); diff --git a/Marlin/src/lcd/language/language_da.h b/Marlin/src/lcd/language/language_da.h index be9ad758ce92..95c2573ae144 100644 --- a/Marlin/src/lcd/language/language_da.h +++ b/Marlin/src/lcd/language/language_da.h @@ -75,10 +75,11 @@ namespace Language_da { PROGMEM Language_Str MSG_MOVE_X = _UxGT("Flyt X"); PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Flyt Y"); PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Flyt Z"); - PROGMEM Language_Str MSG_MOVE_Z_DIST = _UxGT("Flyt %smm"); + PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Flyt %smm"); PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Flyt 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Flyt 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Flyt 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Flyt 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Hastighed"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Plade Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Dyse"); @@ -101,7 +102,7 @@ namespace Language_da { PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatur"); PROGMEM Language_Str MSG_MOTION = _UxGT("Bevægelse"); PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filament"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E i mm³"); + PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E i mm") SUPERSCRIPT_THREE; PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Fil. Dia."); PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Fil. Dia. *"); PROGMEM Language_Str MSG_CONTRAST = _UxGT("LCD kontrast"); diff --git a/Marlin/src/lcd/language/language_de.h b/Marlin/src/lcd/language/language_de.h index 74e185680cc7..f06370078a4b 100644 --- a/Marlin/src/lcd/language/language_de.h +++ b/Marlin/src/lcd/language/language_de.h @@ -53,7 +53,7 @@ namespace Language_de { PROGMEM Language_Str MSG_MAIN = _UxGT("Hauptmenü"); PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Erw. Einstellungen"); PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Konfiguration"); - PROGMEM Language_Str MSG_AUTOSTART = _UxGT("Autostart"); + PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Autostart"); PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Motoren deaktivieren"); // M84 :: Max length 19 characters PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Debug-Menü"); PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Statusbalken-Test"); @@ -62,7 +62,6 @@ namespace Language_de { PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Home Y"); PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Home Z"); PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Z-Achsen ausgleichen"); - PROGMEM Language_Str MSG_ASSISTED_TRAMMING = _UxGT("Bett ausrichten"); // Bettausrichtung PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("XYZ homen"); PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Klick zum Starten"); PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Nächste Koordinate"); @@ -70,7 +69,7 @@ namespace Language_de { PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Ausblendhöhe"); PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Setze Homeversatz"); PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Homeversatz aktiv"); - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Setze Nullpunkte"); //"G92 X0 Y0 Z0" commented out in ultralcd.cpp + PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Setze Nullpunkte"); //"G92 X0 Y0 Z0" commented out in marlinui.cpp #if PREHEAT_COUNT PROGMEM Language_Str MSG_PREHEAT_1 = PREHEAT_1_LABEL _UxGT(" Vorwärmen"); PROGMEM Language_Str MSG_PREHEAT_1_H = PREHEAT_1_LABEL _UxGT(" Vorwärmen ~"); @@ -92,12 +91,8 @@ namespace Language_de { PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Abkühlen"); PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Frequenz"); PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Laser"); - PROGMEM Language_Str MSG_LASER_OFF = _UxGT("Laser aus"); - PROGMEM Language_Str MSG_LASER_ON = _UxGT("Laser an"); PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Laserleistung"); PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Spindel-Steuerung"); - PROGMEM Language_Str MSG_SPINDLE_OFF = _UxGT("Spindel aus"); - PROGMEM Language_Str MSG_SPINDLE_ON = _UxGT("Spindel an"); PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Spindelleistung"); PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Spindelrichtung"); PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Netzteil ein"); @@ -107,7 +102,7 @@ namespace Language_de { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Achsen bewegen"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Bett-Nivellierung"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Bett nivellieren"); - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Ecken nivellieren"); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Bett ausrichten"); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Nächste Ecke"); PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Netz Editor"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Netz bearbeiten"); @@ -116,7 +111,7 @@ namespace Language_de { PROGMEM Language_Str MSG_MESH_X = _UxGT("Index X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("Index Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Z-Wert"); - PROGMEM Language_Str MSG_USER_MENU = _UxGT("Benutzer-Menü"); + PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Benutzer-Menü"); PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 Sondentest"); PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 Punkt"); PROGMEM Language_Str MSG_M48_OUT_OF_BOUNDS = _UxGT("Zu weit draußen"); @@ -234,10 +229,11 @@ namespace Language_de { PROGMEM Language_Str MSG_MOVE_E = _UxGT("Bewege Extruder"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Bewege Extruder *"); PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Hotend zu kalt"); - PROGMEM Language_Str MSG_MOVE_Z_DIST = _UxGT(" %s mm"); - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT(" 0,1 mm"); - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT(" 1,0 mm"); - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("10,0 mm"); + PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT(" %s mm"); + PROGMEM Language_Str MSG_MOVE_01MM = _UxGT(" 0,1 mm"); + PROGMEM Language_Str MSG_MOVE_1MM = _UxGT(" 1,0 mm"); + PROGMEM Language_Str MSG_MOVE_10MM = _UxGT(" 10,0 mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("100,0 mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Geschw."); PROGMEM Language_Str MSG_BED_Z = _UxGT("Bett Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Düse"); @@ -271,16 +267,6 @@ namespace Language_de { PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Autotune fehlge. Falscher Extruder"); PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Autotune fehlge. Temperatur zu hoch."); PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("Autotune fehlge.! Timeout."); - PROGMEM Language_Str MSG_PID_P = _UxGT("PID-P"); - PROGMEM Language_Str MSG_PID_P_E = _UxGT("PID-P *"); - PROGMEM Language_Str MSG_PID_I = _UxGT("PID-I"); - PROGMEM Language_Str MSG_PID_I_E = _UxGT("PID-I *"); - PROGMEM Language_Str MSG_PID_D = _UxGT("PID-D"); - PROGMEM Language_Str MSG_PID_D_E = _UxGT("PID-D *"); - PROGMEM Language_Str MSG_PID_C = _UxGT("PID-C"); - PROGMEM Language_Str MSG_PID_C_E = _UxGT("PID-C *"); - PROGMEM Language_Str MSG_PID_F = _UxGT("PID-F"); - PROGMEM Language_Str MSG_PID_F_E = _UxGT("PID-F *"); PROGMEM Language_Str MSG_SELECT = _UxGT("Auswählen"); PROGMEM Language_Str MSG_SELECT_E = _UxGT("Auswählen *"); PROGMEM Language_Str MSG_ACC = _UxGT("Beschleunigung"); @@ -318,8 +304,8 @@ namespace Language_de { PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatur"); PROGMEM Language_Str MSG_MOTION = _UxGT("Bewegung"); PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filament"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm³"); - PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("E Limit in mm³"); + PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm") SUPERSCRIPT_THREE; + PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("E Limit in mm") SUPERSCRIPT_THREE; PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT_E = _UxGT("E Limit *"); PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Filamentdurchmesser"); PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Filamentdurchmesser *"); diff --git a/Marlin/src/lcd/language/language_el.h b/Marlin/src/lcd/language/language_el.h index 125119d5ccfa..b69b4695d3be 100644 --- a/Marlin/src/lcd/language/language_el.h +++ b/Marlin/src/lcd/language/language_el.h @@ -40,7 +40,7 @@ namespace Language_el { PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Εισαγωγή κάρτας"); PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Αφαίρεση κάρτας"); PROGMEM Language_Str MSG_MAIN = _UxGT("Βασική Οθόνη"); - PROGMEM Language_Str MSG_AUTOSTART = _UxGT("Αυτόματη εκκίνηση"); + PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Αυτόματη εκκίνηση"); PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Απενεργοποίηση Μοτέρ"); PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Αυτομ. επαναφορά στο αρχικό σημείο"); //SHORTEN PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Αρχικό σημείο X"); @@ -83,10 +83,11 @@ namespace Language_el { PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Μετακίνηση Z"); PROGMEM Language_Str MSG_MOVE_E = _UxGT("Εξωθητήρας"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Εξωθητήρας *"); - PROGMEM Language_Str MSG_MOVE_Z_DIST = _UxGT("Μετακίνηση %s μμ"); + PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Μετακίνηση %s μμ"); PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Μετακίνηση 0,1 μμ"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Μετακίνηση 1 μμ"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Μετακίνηση 10 μμ"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Μετακίνηση 100 μμ"); PROGMEM Language_Str MSG_SPEED = _UxGT("Ταχύτητα"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Επ. Εκτύπωσης Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Ακροφύσιο"); @@ -132,7 +133,7 @@ namespace Language_el { PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Θερμοκρασία"); PROGMEM Language_Str MSG_MOTION = _UxGT("Κίνηση"); PROGMEM Language_Str MSG_FILAMENT = _UxGT("Νήμα"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("Ε σε μμ³"); + PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("Ε σε μμ") SUPERSCRIPT_THREE; PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Διάμετρος νήματος"); PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Διάμετρος νήματος *"); PROGMEM Language_Str MSG_CONTRAST = _UxGT("Κοντράστ LCD"); diff --git a/Marlin/src/lcd/language/language_el_gr.h b/Marlin/src/lcd/language/language_el_gr.h index 3db6fccdf07f..208d7c2363be 100644 --- a/Marlin/src/lcd/language/language_el_gr.h +++ b/Marlin/src/lcd/language/language_el_gr.h @@ -41,7 +41,7 @@ namespace Language_el_gr { PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Αφαίρεση κάρτας"); PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Endstops"); // Max length 8 characters PROGMEM Language_Str MSG_MAIN = _UxGT("Βασική Οθόνη"); - PROGMEM Language_Str MSG_AUTOSTART = _UxGT("Αυτόματη εκκίνηση"); + PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Αυτόματη εκκίνηση"); PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Απενεργοποίηση βηματιστή"); PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Αυτομ. επαναφορά στο αρχικό σημείο"); PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Αρχικό σημείο X"); @@ -84,10 +84,11 @@ namespace Language_el_gr { PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Μετακίνηση Z"); PROGMEM Language_Str MSG_MOVE_E = _UxGT("Εξωθητήρας"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Εξωθητήρας *"); - PROGMEM Language_Str MSG_MOVE_Z_DIST = _UxGT("Μετακίνηση %s μμ"); + PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Μετακίνηση %s μμ"); PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Μετακίνηση 0,1 μμ"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Μετακίνηση 1 μμ"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Μετακίνηση 10 μμ"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Μετακίνηση 100 μμ"); PROGMEM Language_Str MSG_SPEED = _UxGT("Ταχύτητα"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Κλίνη Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Ακροφύσιο"); @@ -134,7 +135,7 @@ namespace Language_el_gr { PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Θερμοκρασία"); PROGMEM Language_Str MSG_MOTION = _UxGT("Κίνηση"); PROGMEM Language_Str MSG_FILAMENT = _UxGT("Νήμα"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("Ε σε μμ³"); + PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("Ε σε μμ") SUPERSCRIPT_THREE; PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Διάμετρος νήματος"); PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Διάμετρος νήματος *"); PROGMEM Language_Str MSG_CONTRAST = _UxGT("Κοντράστ LCD"); diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index e8b4769cc216..cd204eef5915 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -26,6 +26,13 @@ * * 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 that call lcd_put_u8str_ind_P with an index: + * + * = 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) */ #define en 1234 @@ -57,7 +64,7 @@ namespace Language_en { PROGMEM Language_Str MSG_MAIN = _UxGT("Main"); PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Advanced Settings"); PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Configuration"); - PROGMEM Language_Str MSG_AUTOSTART = _UxGT("Autostart"); + PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Run Auto Files"); PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Disable Steppers"); PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Debug Menu"); PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Progress Bar Test"); @@ -65,8 +72,10 @@ namespace Language_en { PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Home X"); PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Home Y"); PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Home Z"); + PROGMEM Language_Str MSG_AUTO_HOME_I = _UxGT("Home ") LCD_STR_I; + PROGMEM Language_Str MSG_AUTO_HOME_J = _UxGT("Home ") LCD_STR_J; + PROGMEM Language_Str MSG_AUTO_HOME_K = _UxGT("Home ") LCD_STR_K; PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Auto Z-Align"); - PROGMEM Language_Str MSG_ASSISTED_TRAMMING = _UxGT("Assisted Tramming"); PROGMEM Language_Str MSG_ITERATION = _UxGT("G34 Iteration: %i"); PROGMEM Language_Str MSG_DECREASING_ACCURACY = _UxGT("Accuracy Decreasing!"); PROGMEM Language_Str MSG_ACCURACY_ACHIEVED = _UxGT("Accuracy Achieved"); @@ -76,8 +85,17 @@ namespace Language_en { PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Leveling Done!"); PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Fade Height"); PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Set Home Offsets"); + PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("Home Offset X"); + PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Home Offset Y"); + PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Home Offset Z"); + PROGMEM Language_Str MSG_HOME_OFFSET_I = _UxGT("Home Offset ") LCD_STR_I; + PROGMEM Language_Str MSG_HOME_OFFSET_J = _UxGT("Home Offset ") LCD_STR_J; + PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Home Offset ") LCD_STR_K; PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Offsets Applied"); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Set Origin"); + PROGMEM Language_Str MSG_TRAMMING_WIZARD = _UxGT("Tramming Wizard"); + PROGMEM Language_Str MSG_SELECT_ORIGIN = _UxGT("Select Origin"); + PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Last value "); #if PREHEAT_COUNT PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Preheat ") PREHEAT_1_LABEL; PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Preheat ") PREHEAT_1_LABEL " ~"; @@ -97,15 +115,21 @@ namespace Language_en { #endif PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Preheat Custom"); PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Cooldown"); + PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Frequency"); PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Laser Control"); - PROGMEM Language_Str MSG_LASER_OFF = _UxGT("Laser Off"); - PROGMEM Language_Str MSG_LASER_ON = _UxGT("Laser On"); - PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Laser Power"); PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Spindle Control"); - PROGMEM Language_Str MSG_SPINDLE_OFF = _UxGT("Spindle Off"); - PROGMEM Language_Str MSG_SPINDLE_ON = _UxGT("Spindle On"); - PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Spindle Power"); + PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Laser Power"); + PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Spindle Pwr"); + PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Toggle Laser"); + PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Toggle Blower"); + PROGMEM Language_Str MSG_LASER_ASSIST_TOGGLE = _UxGT("Air Assist"); + PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Test Pulse ms"); + PROGMEM Language_Str MSG_LASER_FIRE_PULSE = _UxGT("Fire Pulse"); + PROGMEM Language_Str MSG_FLOWMETER_FAULT = _UxGT("Coolant Flow Fault"); + PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Toggle Spindle"); + PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Toggle Vacuum"); + PROGMEM Language_Str MSG_SPINDLE_FORWARD = _UxGT("Spindle Forward"); PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Spindle Reverse"); PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Switch Power On"); PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Switch Power Off"); @@ -114,7 +138,11 @@ namespace Language_en { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Move Axis"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Bed Leveling"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Level Bed"); - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Level Corners"); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Bed Tramming"); + PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Raise Bed Until Probe Triggered"); + PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("All Corners Within Tolerance. Level Bed"); + PROGMEM Language_Str MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Good Points: "); + PROGMEM Language_Str MSG_BED_TRAMMING_LAST_Z = _UxGT("Last Z: "); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Next Corner"); PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Mesh Editor"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Edit Mesh"); @@ -123,7 +151,7 @@ namespace Language_en { PROGMEM Language_Str MSG_MESH_X = _UxGT("Index X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("Index Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Z Value"); - PROGMEM Language_Str MSG_USER_MENU = _UxGT("Custom Commands"); + PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Custom Commands"); PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 Probe Test"); PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 Point"); PROGMEM Language_Str MSG_M48_OUT_OF_BOUNDS = _UxGT("Probe out of bounds"); @@ -134,6 +162,7 @@ namespace Language_en { PROGMEM Language_Str MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplication"); PROGMEM Language_Str MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Mirrored Copy"); PROGMEM Language_Str MSG_IDEX_MODE_FULL_CTRL = _UxGT("Full Control"); + PROGMEM Language_Str MSG_IDEX_DUPE_GAP = _UxGT("Duplicate X-Gap"); PROGMEM Language_Str MSG_HOTEND_OFFSET_X = _UxGT("2nd Nozzle X"); PROGMEM Language_Str MSG_HOTEND_OFFSET_Y = _UxGT("2nd Nozzle Y"); PROGMEM Language_Str MSG_HOTEND_OFFSET_Z = _UxGT("2nd Nozzle Z"); @@ -142,6 +171,7 @@ namespace Language_en { PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Unified Bed Leveling"); PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Tilting Point"); PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Manually Build Mesh"); + PROGMEM Language_Str MSG_UBL_MESH_WIZARD = _UxGT("UBL Mesh Wizard"); PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Place Shim & Measure"); PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Measure"); PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Remove & Measure Bed"); @@ -240,13 +270,21 @@ namespace Language_en { PROGMEM Language_Str MSG_MOVE_X = _UxGT("Move X"); PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Move Y"); PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Move Z"); + PROGMEM Language_Str MSG_MOVE_I = _UxGT("Move ") LCD_STR_I; + PROGMEM Language_Str MSG_MOVE_J = _UxGT("Move ") LCD_STR_J; + PROGMEM Language_Str MSG_MOVE_K = _UxGT("Move ") LCD_STR_K; PROGMEM Language_Str MSG_MOVE_E = _UxGT("Extruder"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Extruder *"); PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Hotend too cold"); - PROGMEM Language_Str MSG_MOVE_Z_DIST = _UxGT("Move %smm"); + PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Move %smm"); PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Move 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Move 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Move 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Move 100mm"); + PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Move 0.001in"); + PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Move 0.01in"); + PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Move 0.1in"); + PROGMEM Language_Str MSG_MOVE_1IN = _UxGT("Move 1.0in"); PROGMEM Language_Str MSG_SPEED = _UxGT("Speed"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Bed Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Nozzle"); @@ -255,6 +293,10 @@ namespace Language_en { PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Nozzle Standby"); PROGMEM Language_Str MSG_BED = _UxGT("Bed"); PROGMEM Language_Str MSG_CHAMBER = _UxGT("Enclosure"); + PROGMEM Language_Str MSG_COOLER = _UxGT("Laser Coolant"); + PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Toggle Cooler"); + PROGMEM Language_Str MSG_FLOWMETER_SAFETY = _UxGT("Flow Safety"); + PROGMEM Language_Str MSG_LASER = _UxGT("Laser"); PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Fan Speed"); PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Fan Speed ~"); PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Stored Fan ~"); @@ -297,12 +339,18 @@ namespace Language_en { PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-Jerk"); PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-Jerk"); PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-Jerk"); + PROGMEM Language_Str MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-Jerk"); + PROGMEM Language_Str MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-Jerk"); + PROGMEM Language_Str MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-Jerk"); PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-Jerk"); PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev"); PROGMEM Language_Str MSG_VELOCITY = _UxGT("Velocity"); PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; + PROGMEM Language_Str MSG_VMAX_I = _UxGT("Vmax ") LCD_STR_I; + PROGMEM Language_Str MSG_VMAX_J = _UxGT("Vmax ") LCD_STR_J; + PROGMEM Language_Str MSG_VMAX_K = _UxGT("Vmax ") LCD_STR_K; PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vmax *"); PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin"); @@ -311,6 +359,9 @@ namespace Language_en { PROGMEM Language_Str MSG_AMAX_A = _UxGT("Amax ") LCD_STR_A; PROGMEM Language_Str MSG_AMAX_B = _UxGT("Amax ") LCD_STR_B; PROGMEM Language_Str MSG_AMAX_C = _UxGT("Amax ") LCD_STR_C; + PROGMEM Language_Str MSG_AMAX_I = _UxGT("Amax ") LCD_STR_I; + PROGMEM Language_Str MSG_AMAX_J = _UxGT("Amax ") LCD_STR_J; + PROGMEM Language_Str MSG_AMAX_K = _UxGT("Amax ") LCD_STR_K; PROGMEM Language_Str MSG_AMAX_E = _UxGT("Amax ") LCD_STR_E; PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Amax *"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-Retract"); @@ -321,13 +372,16 @@ namespace Language_en { PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" Steps/mm"); PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" Steps/mm"); PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" Steps/mm"); + PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" Steps/mm"); + PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" Steps/mm"); + PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" Steps/mm"); PROGMEM Language_Str MSG_E_STEPS = _UxGT("E steps/mm"); PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* Steps/mm"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperature"); PROGMEM Language_Str MSG_MOTION = _UxGT("Motion"); PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filament"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm³"); - PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("E Limit in mm³"); + PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm") SUPERSCRIPT_THREE; + PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("E Limit in mm") SUPERSCRIPT_THREE; PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT_E = _UxGT("E Limit *"); PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Fil. Dia."); PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Fil. Dia. *"); @@ -365,11 +419,13 @@ namespace Language_en { PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Done"); PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Back"); PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Proceed"); + PROGMEM Language_Str MSG_BUTTON_SKIP = _UxGT("Skip"); PROGMEM Language_Str MSG_PAUSING = _UxGT("Pausing..."); PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Pause Print"); PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Resume Print"); PROGMEM Language_Str MSG_HOST_START_PRINT = _UxGT("Host Start"); PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Stop Print"); + PROGMEM Language_Str MSG_END_LOOPS = _UxGT("End Repeat Loops"); PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("Printing Object"); PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("Cancel Object"); PROGMEM Language_Str MSG_CANCEL_OBJECT_N = _UxGT("Cancel Object ="); @@ -414,9 +470,9 @@ namespace Language_en { PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Change Filament"); PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Change Filament *"); PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Load Filament"); - PROGMEM Language_Str MSG_FILAMENTLOAD_E = _UxGT("Load Filament *"); + PROGMEM Language_Str MSG_FILAMENTLOAD_E = _UxGT("Load *"); PROGMEM Language_Str MSG_FILAMENTUNLOAD = _UxGT("Unload Filament"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_E = _UxGT("Unload Filament *"); + PROGMEM Language_Str MSG_FILAMENTUNLOAD_E = _UxGT("Unload *"); PROGMEM Language_Str MSG_FILAMENTUNLOAD_ALL = _UxGT("Unload All"); PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Attach Media"); PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Change Media"); @@ -452,6 +508,9 @@ namespace Language_en { PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Babystep X"); PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Babystep Y"); PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Babystep Z"); + PROGMEM Language_Str MSG_BABYSTEP_I = _UxGT("Babystep ") LCD_STR_I; + PROGMEM Language_Str MSG_BABYSTEP_J = _UxGT("Babystep ") LCD_STR_J; + PROGMEM Language_Str MSG_BABYSTEP_K = _UxGT("Babystep ") LCD_STR_K; PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Total"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Endstop Abort"); PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Heating Failed"); @@ -459,6 +518,8 @@ namespace Language_en { PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("THERMAL RUNAWAY"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("BED THERMAL RUNAWAY"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("CHAMBER T. RUNAWAY"); + PROGMEM Language_Str MSG_THERMAL_RUNAWAY_COOLER = _UxGT("Cooler Runaway"); + PROGMEM Language_Str MSG_COOLING_FAILED = _UxGT("Cooling Failed"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Err: MAXTEMP"); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Err: MINTEMP"); PROGMEM Language_Str MSG_HALTED = _UxGT("PRINTER HALTED"); @@ -474,6 +535,7 @@ namespace Language_en { PROGMEM Language_Str MSG_PROBE_COOLING = _UxGT("Probe Cooling..."); PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Chamber Heating..."); PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Chamber Cooling..."); + PROGMEM Language_Str MSG_LASER_COOLING = _UxGT("Laser Cooling..."); PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Delta Calibration"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Calibrate X"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Calibrate Y"); @@ -493,6 +555,7 @@ namespace Language_en { PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Bilinear Leveling"); PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Unified Bed Leveling"); PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Mesh Leveling"); + PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Mesh probing done"); PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Printer Stats"); PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Board Info"); PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Thermistors"); @@ -528,6 +591,9 @@ namespace Language_en { PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Driver %"); PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Driver %"); PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = AXIS4_STR _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = AXIS5_STR _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = AXIS6_STR _UxGT(" Driver %"); PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Driver %"); PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("TMC CONNECTION ERROR"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM Write"); @@ -645,6 +711,9 @@ namespace Language_en { PROGMEM Language_Str MSG_BACKLASH_A = LCD_STR_A; PROGMEM Language_Str MSG_BACKLASH_B = LCD_STR_B; PROGMEM Language_Str MSG_BACKLASH_C = LCD_STR_C; + PROGMEM Language_Str MSG_BACKLASH_I = LCD_STR_I; + PROGMEM Language_Str MSG_BACKLASH_J = LCD_STR_J; + PROGMEM Language_Str MSG_BACKLASH_K = LCD_STR_K; PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Correction"); PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Smoothing"); @@ -657,8 +726,25 @@ namespace Language_en { #endif PROGMEM Language_Str MSG_REHEAT = _UxGT("Reheat"); PROGMEM Language_Str MSG_REHEATING = _UxGT("Reheating..."); + PROGMEM Language_Str MSG_REHEATDONE = _UxGT("Reheat Done"); PROGMEM Language_Str MSG_PROBE_WIZARD = _UxGT("Z Probe Wizard"); + PROGMEM Language_Str MSG_PROBE_WIZARD_PROBING = _UxGT("Probing Z Reference"); + PROGMEM Language_Str MSG_PROBE_WIZARD_MOVING = _UxGT("Moving to Probing Pos"); + + PROGMEM Language_Str MSG_SOUND = _UxGT("Sound"); + + PROGMEM Language_Str MSG_TOP_LEFT = _UxGT("Top Left"); + PROGMEM Language_Str MSG_BOTTOM_LEFT = _UxGT("Bottom Left"); + PROGMEM Language_Str MSG_TOP_RIGHT = _UxGT("Top Right"); + PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Bottom Right"); + PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Calibration Completed"); + PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Calibration Failed"); + + PROGMEM Language_Str MSG_DRIVER_BACKWARD = _UxGT(" driver backward"); + + PROGMEM Language_Str MSG_SD_CARD = _UxGT("SD Card"); + PROGMEM Language_Str MSG_USB_DISK = _UxGT("USB Disk"); } #if FAN_COUNT == 1 diff --git a/Marlin/src/lcd/language/language_es.h b/Marlin/src/lcd/language/language_es.h index c77b12ee7749..8fdf0bd47ed2 100644 --- a/Marlin/src/lcd/language/language_es.h +++ b/Marlin/src/lcd/language/language_es.h @@ -43,15 +43,17 @@ namespace Language_es { PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("SD/USB insertado"); PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("SD/USB retirado"); PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Esperando al SD/USB"); + PROGMEM Language_Str MSG_SD_INIT_FAIL = _UxGT("Fallo al iniciar SD"); PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Error lectura SD/USB"); PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("Disp. USB retirado"); PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("Inicio USB fallido"); + PROGMEM Language_Str MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Desbordamiento de subllamada"); PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Endstops"); // Max length 8 characters PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft Endstops"); PROGMEM Language_Str MSG_MAIN = _UxGT("Menú principal"); PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Ajustes avanzados"); PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Configuración"); - PROGMEM Language_Str MSG_AUTOSTART = _UxGT("Inicio automático"); + PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Inicio automático"); PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Apagar motores"); PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Menú depuración"); PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Prob. barra progreso"); @@ -60,6 +62,9 @@ namespace Language_es { PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Origen Y"); PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Origen Z"); PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Auto alineado Z"); + PROGMEM Language_Str MSG_ITERATION = _UxGT("G34 Iteración: %i"); + PROGMEM Language_Str MSG_DECREASING_ACCURACY = _UxGT("¡Precisión disminuyendo!"); + PROGMEM Language_Str MSG_ACCURACY_ACHIEVED = _UxGT("Precisión conseguida"); PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Origen XYZ"); PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Pulsar para comenzar"); PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Siguiente punto"); @@ -89,12 +94,8 @@ namespace Language_es { PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Enfriar"); PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Frecuencia"); PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Control Láser"); - PROGMEM Language_Str MSG_LASER_OFF = _UxGT("Apagar Láser"); - PROGMEM Language_Str MSG_LASER_ON = _UxGT("Encender Láser"); PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Potencia Láser"); PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Control Mandrino"); - PROGMEM Language_Str MSG_SPINDLE_OFF = _UxGT("Apagar Mandrino"); - PROGMEM Language_Str MSG_SPINDLE_ON = _UxGT("Encender Mandrino"); PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Potencia Mandrino"); PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Invertir giro"); PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Encender Fuente"); @@ -104,7 +105,7 @@ namespace Language_es { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Mover ejes"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Nivelando Cama"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Nivelar Cama"); - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Nivelar Esquinas"); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Recorrido asistido"); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Siguente Esquina"); PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Editor Mallado"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Editar Mallado"); @@ -113,7 +114,7 @@ namespace Language_es { PROGMEM Language_Str MSG_MESH_X = _UxGT("Índice X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("Índice Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Valor Z"); - PROGMEM Language_Str MSG_USER_MENU = _UxGT("Com. Personalizados"); + PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Com. Personalizados"); PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 Probar Sonda"); PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 Punto"); PROGMEM Language_Str MSG_M48_DEVIATION = _UxGT("Desviación"); @@ -230,10 +231,11 @@ namespace Language_es { PROGMEM Language_Str MSG_MOVE_E = _UxGT("Extrusor"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Extrusor *"); PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Hotend muy frio"); - PROGMEM Language_Str MSG_MOVE_Z_DIST = _UxGT("Mover %smm"); + PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Mover %smm"); PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mover 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mover 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Mover 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Mover 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Velocidad"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Cama Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Boquilla"); @@ -263,16 +265,6 @@ namespace Language_es { PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Apg"); PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("PID Auto-ajuste"); PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("PID Auto-ajuste *"); - PROGMEM Language_Str MSG_PID_P = _UxGT("PID-P"); - PROGMEM Language_Str MSG_PID_P_E = _UxGT("PID-P *"); - PROGMEM Language_Str MSG_PID_I = _UxGT("PID-I"); - PROGMEM Language_Str MSG_PID_I_E = _UxGT("PID-I *"); - PROGMEM Language_Str MSG_PID_D = _UxGT("PID-D"); - PROGMEM Language_Str MSG_PID_D_E = _UxGT("PID-D *"); - PROGMEM Language_Str MSG_PID_C = _UxGT("PID-C"); - PROGMEM Language_Str MSG_PID_C_E = _UxGT("PID-C *"); - PROGMEM Language_Str MSG_PID_F = _UxGT("PID-F"); - PROGMEM Language_Str MSG_PID_F_E = _UxGT("PID-F *"); PROGMEM Language_Str MSG_SELECT = _UxGT("Seleccionar"); PROGMEM Language_Str MSG_SELECT_E = _UxGT("Seleccionar *"); PROGMEM Language_Str MSG_ACC = _UxGT("Aceleración"); @@ -307,7 +299,7 @@ namespace Language_es { PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatura"); PROGMEM Language_Str MSG_MOTION = _UxGT("Movimiento"); PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filamento"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E en mm³"); + PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E en mm") SUPERSCRIPT_THREE; PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Diámetro Fil."); PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Diámetro Fil. *"); PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Descarga mm"); diff --git a/Marlin/src/lcd/language/language_eu.h b/Marlin/src/lcd/language/language_eu.h index 7e35c6ee41ec..530742d6d3a2 100644 --- a/Marlin/src/lcd/language/language_eu.h +++ b/Marlin/src/lcd/language/language_eu.h @@ -42,7 +42,7 @@ namespace Language_eu { PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Txartela sartuta"); PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Txartela kenduta"); PROGMEM Language_Str MSG_MAIN = _UxGT("Menu nagusia"); - PROGMEM Language_Str MSG_AUTOSTART = _UxGT("Auto hasiera"); + PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Auto hasiera"); PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Itzali motoreak"); PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Arazketa Menua"); PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Prog. Barra Proba"); @@ -82,7 +82,7 @@ namespace Language_eu { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Ardatzak mugitu"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Ohe berdinketa"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Ohea berdindu"); - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Ertzak berdindu"); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Ertzak berdindu"); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Hurrengo ertza"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Sarea editatu"); @@ -139,10 +139,11 @@ namespace Language_eu { PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Mugitu Z"); PROGMEM Language_Str MSG_MOVE_E = _UxGT("Estrusorea"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Estrusorea *"); - PROGMEM Language_Str MSG_MOVE_Z_DIST = _UxGT("Mugitu %smm"); + PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Mugitu %smm"); PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mugitu 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mugitu 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Mugitu 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Mugitu 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Abiadura"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Z Ohea"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Pita"); diff --git a/Marlin/src/lcd/language/language_fi.h b/Marlin/src/lcd/language/language_fi.h index e8621377d966..0d3b97cc44af 100644 --- a/Marlin/src/lcd/language/language_fi.h +++ b/Marlin/src/lcd/language/language_fi.h @@ -40,7 +40,7 @@ namespace Language_fi { PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Kortti asetettu"); PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Kortti poistettu"); PROGMEM Language_Str MSG_MAIN = _UxGT("Palaa"); - PROGMEM Language_Str MSG_AUTOSTART = _UxGT("Automaatti"); + PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Automaatti"); PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Vapauta moottorit"); PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Aja referenssiin"); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Aseta origo"); @@ -72,10 +72,11 @@ namespace Language_fi { PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Liikuta Z"); PROGMEM Language_Str MSG_MOVE_E = _UxGT("Extruder"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Extruder *"); - PROGMEM Language_Str MSG_MOVE_Z_DIST = _UxGT("Liikuta %smm"); + PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Liikuta %smm"); PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Liikuta 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Liikuta 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Liikuta 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Liikuta 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Nopeus"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Suutin"); PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Suutin ~"); @@ -95,7 +96,7 @@ namespace Language_fi { PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Lämpötila"); PROGMEM Language_Str MSG_MOTION = _UxGT("Liike"); PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filament"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm³"); + PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm") SUPERSCRIPT_THREE; PROGMEM Language_Str MSG_CONTRAST = _UxGT("LCD kontrasti"); PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Tallenna muistiin"); PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Lataa muistista"); diff --git a/Marlin/src/lcd/language/language_fr.h b/Marlin/src/lcd/language/language_fr.h index 714feeee9976..6032937e0f18 100644 --- a/Marlin/src/lcd/language/language_fr.h +++ b/Marlin/src/lcd/language/language_fr.h @@ -52,7 +52,7 @@ namespace Language_fr { PROGMEM Language_Str MSG_MAIN = _UxGT("Menu principal"); PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Config. avancée"); PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Configuration"); - PROGMEM Language_Str MSG_AUTOSTART = _UxGT("Exéc. auto.gcode"); + PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Exéc. auto.gcode"); PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Arrêter moteurs"); PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Menu debug"); PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Test barre progress."); @@ -60,6 +60,9 @@ namespace Language_fr { PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Origine X auto"); PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Origine Y auto"); PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Origine Z auto"); + PROGMEM Language_Str MSG_AUTO_HOME_I = _UxGT("Origine ") LCD_STR_I _UxGT(" auto"); + PROGMEM Language_Str MSG_AUTO_HOME_J = _UxGT("Origine ") LCD_STR_J _UxGT(" auto"); + PROGMEM Language_Str MSG_AUTO_HOME_K = _UxGT("Origine ") LCD_STR_K _UxGT(" auto"); PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Align. Z auto"); PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Origine XYZ..."); PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Clic pour commencer"); @@ -67,8 +70,17 @@ namespace Language_fr { PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Mise à niveau OK!"); PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Hauteur lissée"); PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Régl. décal origine"); + PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("Décal. origine X"); + PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Décal. origine Y"); + PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Décal. origine Z"); + PROGMEM Language_Str MSG_HOME_OFFSET_I = _UxGT("Décal. origine ") LCD_STR_I; + PROGMEM Language_Str MSG_HOME_OFFSET_J = _UxGT("Décal. origine ") LCD_STR_J; + PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Décal. origine ") LCD_STR_K; PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Décalages appliqués"); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Régler origine"); + PROGMEM Language_Str MSG_TRAMMING_WIZARD = _UxGT("Assistant Molettes"); + PROGMEM Language_Str MSG_SELECT_ORIGIN = _UxGT("Molette du lit"); // Not a selection of the origin + PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Ecart origine "); #if PREHEAT_COUNT PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Préchauffage ") PREHEAT_1_LABEL; PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Préchauffage ") PREHEAT_1_LABEL " ~"; @@ -98,7 +110,9 @@ namespace Language_fr { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Déplacer un axe"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Régler Niv. lit"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Niveau du lit"); - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Niveau des coins"); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Assistant Molettes"); + PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Relever le coin jusqu'à la sonde"); + PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("Coins dans la tolérance. Niveau lit "); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Coin suivant"); PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Modif. maille"); // 13 car. max PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Modifier grille"); @@ -107,7 +121,7 @@ namespace Language_fr { PROGMEM Language_Str MSG_MESH_X = _UxGT("Index X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("Index Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Valeur Z"); - PROGMEM Language_Str MSG_USER_MENU = _UxGT("Commandes perso"); + PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Commandes perso"); PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Mesure point"); PROGMEM Language_Str MSG_M48_TEST = _UxGT("Ecart sonde Z M48"); @@ -222,13 +236,21 @@ namespace Language_fr { PROGMEM Language_Str MSG_MOVE_X = _UxGT("Déplacer X"); PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Déplacer Y"); PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Déplacer Z"); - PROGMEM Language_Str MSG_MOVE_E = _UxGT("Extrudeur"); - PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Extrudeur *"); + PROGMEM Language_Str MSG_MOVE_I = _UxGT("Déplacer ") LCD_STR_I; + PROGMEM Language_Str MSG_MOVE_J = _UxGT("Déplacer ") LCD_STR_J; + PROGMEM Language_Str MSG_MOVE_K = _UxGT("Déplacer ") LCD_STR_K; + PROGMEM Language_Str MSG_MOVE_E = _UxGT("Extruder"); + PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Extruder *"); PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Buse trop froide"); - PROGMEM Language_Str MSG_MOVE_Z_DIST = _UxGT("Déplacer %smm"); + PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Déplacer %smm"); PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Déplacer 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Déplacer 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Déplacer 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Déplacer 100mm"); + PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Déplacer 0.001\""); + PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Déplacer 0.01\""); + PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Déplacer 0.1\""); + PROGMEM Language_Str MSG_MOVE_1IN = _UxGT("Déplacer 1\""); PROGMEM Language_Str MSG_SPEED = _UxGT("Vitesse"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Lit Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Buse"); @@ -263,11 +285,31 @@ namespace Language_fr { PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT(" jerk"); PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT(" jerk"); PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT(" jerk"); + PROGMEM Language_Str MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT(" jerk"); + PROGMEM Language_Str MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT(" jerk"); + PROGMEM Language_Str MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT(" jerk"); PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve jerk"); PROGMEM Language_Str MSG_VELOCITY = _UxGT("Vélocité"); + PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vit. Max ") LCD_STR_A; + PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vit. Max ") LCD_STR_B; + PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vit. Max ") LCD_STR_C; + PROGMEM Language_Str MSG_VMAX_I = _UxGT("Vit. Max ") LCD_STR_I; + PROGMEM Language_Str MSG_VMAX_J = _UxGT("Vit. Max ") LCD_STR_J; + PROGMEM Language_Str MSG_VMAX_K = _UxGT("Vit. Max ") LCD_STR_K; + PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vit. Max ") LCD_STR_E; + PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vit. Max *"); PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Déviat. jonct."); + PROGMEM Language_Str MSG_VMIN = _UxGT("Vit. Min"); PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Vmin course"); PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Accélération"); + PROGMEM Language_Str MSG_AMAX_A = _UxGT("Max Accél. ") LCD_STR_A; + PROGMEM Language_Str MSG_AMAX_B = _UxGT("Max Accél. ") LCD_STR_B; + PROGMEM Language_Str MSG_AMAX_C = _UxGT("Max Accél. ") LCD_STR_C; + PROGMEM Language_Str MSG_AMAX_I = _UxGT("Max Accél. ") LCD_STR_I; + PROGMEM Language_Str MSG_AMAX_J = _UxGT("Max Accél. ") LCD_STR_J; + PROGMEM Language_Str MSG_AMAX_K = _UxGT("Max Accél. ") LCD_STR_K; + PROGMEM Language_Str MSG_AMAX_E = _UxGT("Max Accél. ") LCD_STR_E; + PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Max Accél. *"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Acc.rétraction"); PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("Acc.course"); PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("Fréquence max"); @@ -276,13 +318,16 @@ namespace Language_fr { PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" pas/mm"); PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" pas/mm"); PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" pas/mm"); + PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" pas/mm"); + PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" pas/mm"); + PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" pas/mm"); PROGMEM Language_Str MSG_E_STEPS = _UxGT("E pas/mm"); PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* pas/mm"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Température"); PROGMEM Language_Str MSG_MOTION = _UxGT("Mouvement"); PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filament"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E en mm³"); - PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("Limite en mm³"); + PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E en mm") SUPERSCRIPT_THREE; + PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("Limite en mm") SUPERSCRIPT_THREE; PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT_E = _UxGT("Limite *"); PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Diamètre fil."); PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Diamètre fil. *"); @@ -313,6 +358,7 @@ namespace Language_fr { PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Terminé"); PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Retour"); PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Procéder"); + PROGMEM Language_Str MSG_BUTTON_SKIP = _UxGT("Passer"); PROGMEM Language_Str MSG_PAUSING = _UxGT("Mise en pause..."); PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Pause impression"); PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Reprendre impr."); @@ -394,6 +440,12 @@ namespace Language_fr { PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("Décalage X"); PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Décalage Y"); PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Décalage Z"); + PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Babystep X"); + PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Babystep Y"); + PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Babystep Z"); + PROGMEM Language_Str MSG_BABYSTEP_I = _UxGT("Babystep ") LCD_STR_I; + PROGMEM Language_Str MSG_BABYSTEP_J = _UxGT("Babystep ") LCD_STR_J; + PROGMEM Language_Str MSG_BABYSTEP_K = _UxGT("Babystep ") LCD_STR_K; PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Total"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Butée abandon"); PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Err de chauffe"); @@ -436,6 +488,7 @@ namespace Language_fr { PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Niveau bilinéaire"); PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Niveau lit unifié"); PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Niveau par grille"); + PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Niveau terminé"); PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Stats. imprimante"); PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Infos carte"); PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Thermistances"); @@ -468,10 +521,13 @@ namespace Language_fr { PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Temp Max"); PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Alim."); PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Puiss. moteur "); - PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("Driver X %"); + PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Driver Y %"); + PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Driver Z %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = _UxGT("Driver " AXIS4_STR " %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = _UxGT("Driver " AXIS5_STR " %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = _UxGT("Driver " AXIS6_STR " %"); + PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("Driver E %"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM sauv."); PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("ERREUR CONNEXION TMC"); @@ -568,6 +624,38 @@ namespace Language_fr { PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop activé"); PROGMEM Language_Str MSG_SERVICE_RESET = _UxGT("Réinit."); PROGMEM Language_Str MSG_SERVICE_IN = _UxGT(" dans:"); + PROGMEM Language_Str MSG_BACKLASH_A = LCD_STR_A; + PROGMEM Language_Str MSG_BACKLASH_B = LCD_STR_B; + PROGMEM Language_Str MSG_BACKLASH_C = LCD_STR_C; + PROGMEM Language_Str MSG_BACKLASH_I = LCD_STR_I; + PROGMEM Language_Str MSG_BACKLASH_J = LCD_STR_J; + PROGMEM Language_Str MSG_BACKLASH_K = LCD_STR_K; PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Correction"); PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Lissage"); + + PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("Niveau axe X"); + PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Etalon. auto."); + #if ENABLED(TOUCH_UI_FTDI_EVE) + PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("En protection, temp. réduite. Ok pour rechauffer et continuer."); + #else + PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("En protection"); + #endif + PROGMEM Language_Str MSG_REHEAT = _UxGT("Chauffer"); + PROGMEM Language_Str MSG_REHEATING = _UxGT("Réchauffe..."); + + PROGMEM Language_Str MSG_PROBE_WIZARD = _UxGT("Assistant Sonde Z"); + PROGMEM Language_Str MSG_PROBE_WIZARD_PROBING = _UxGT("Mesure référence"); + PROGMEM Language_Str MSG_PROBE_WIZARD_MOVING = _UxGT("Dépl. vers pos"); + + PROGMEM Language_Str MSG_SOUND = _UxGT("Sons"); + + PROGMEM Language_Str MSG_TOP_LEFT = _UxGT("Coin haut gauche"); + PROGMEM Language_Str MSG_BOTTOM_LEFT = _UxGT("Coin bas gauche"); + PROGMEM Language_Str MSG_TOP_RIGHT = _UxGT("Coin haut droit"); + PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Coin bas droit"); + PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Calibration terminée"); + PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Échec de l'étalonnage"); + + PROGMEM Language_Str MSG_SD_CARD = _UxGT("Carte SD"); + PROGMEM Language_Str MSG_USB_DISK = _UxGT("Clé USB"); } diff --git a/Marlin/src/lcd/language/language_gl.h b/Marlin/src/lcd/language/language_gl.h index 2fd4bf69758a..8defd2b01f37 100644 --- a/Marlin/src/lcd/language/language_gl.h +++ b/Marlin/src/lcd/language/language_gl.h @@ -54,7 +54,7 @@ namespace Language_gl { PROGMEM Language_Str MSG_MAIN = _UxGT("Menú principal"); PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Axustes avanzados"); PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Configuración"); - PROGMEM Language_Str MSG_AUTOSTART = _UxGT("Autoarranque"); + PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Autoarranque"); PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Apagar motores"); PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Menú depuración"); PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Test barra progreso"); @@ -92,12 +92,8 @@ namespace Language_gl { PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Arrefriar"); PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Frecuencia"); PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Control Láser"); - PROGMEM Language_Str MSG_LASER_OFF = _UxGT("Láser Apagado"); - PROGMEM Language_Str MSG_LASER_ON = _UxGT("Láser Aceso"); PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Potencia Láser"); PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Control Fuso"); - PROGMEM Language_Str MSG_SPINDLE_OFF = _UxGT("Fuso Apagado"); - PROGMEM Language_Str MSG_SPINDLE_ON = _UxGT("Fuso Aceso"); PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Potencia Fuso"); PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Inverter xiro"); PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Acender"); @@ -107,7 +103,7 @@ namespace Language_gl { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Mover eixe"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Nivelando Cama"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Nivelar Cama"); - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Nivelar Cantos"); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Nivelar Cantos"); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Seguinte Canto"); PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Editor Mallado"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Editar Mallado"); @@ -116,7 +112,7 @@ namespace Language_gl { PROGMEM Language_Str MSG_MESH_X = _UxGT("Índice X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("Índice Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Valor Z"); - PROGMEM Language_Str MSG_USER_MENU = _UxGT("Comandos Personaliz."); + PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Comandos Personaliz."); PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 Probar Sonda"); PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 Punto"); PROGMEM Language_Str MSG_M48_DEVIATION = _UxGT("Desviación"); @@ -233,10 +229,11 @@ namespace Language_gl { PROGMEM Language_Str MSG_MOVE_E = _UxGT("Extrusor"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Extrusor *"); PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Bico moi frío"); - PROGMEM Language_Str MSG_MOVE_Z_DIST = _UxGT("Mover %smm"); + PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Mover %smm"); PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mover 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mover 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Mover 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Mover 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Velocidade"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Cama Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Bico"); @@ -270,16 +267,6 @@ namespace Language_gl { PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Auto-Sint. fallida. Extrusor danado."); PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Auto-Sint. fallida. Temperatura moi alta."); PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("Auto-Sint. fallida. Tempo excedido."); - PROGMEM Language_Str MSG_PID_P = _UxGT("PID-P"); - PROGMEM Language_Str MSG_PID_P_E = _UxGT("PID-P *"); - PROGMEM Language_Str MSG_PID_I = _UxGT("PID-I"); - PROGMEM Language_Str MSG_PID_I_E = _UxGT("PID-I *"); - PROGMEM Language_Str MSG_PID_D = _UxGT("PID-D"); - PROGMEM Language_Str MSG_PID_D_E = _UxGT("PID-D *"); - PROGMEM Language_Str MSG_PID_C = _UxGT("PID-C"); - PROGMEM Language_Str MSG_PID_C_E = _UxGT("PID-C *"); - PROGMEM Language_Str MSG_PID_F = _UxGT("PID-F"); - PROGMEM Language_Str MSG_PID_F_E = _UxGT("PID-F *"); PROGMEM Language_Str MSG_SELECT = _UxGT("Escolla"); PROGMEM Language_Str MSG_SELECT_E = _UxGT("Escolla *"); PROGMEM Language_Str MSG_ACC = _UxGT("Acel"); @@ -316,7 +303,7 @@ namespace Language_gl { PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatura"); PROGMEM Language_Str MSG_MOTION = _UxGT("Movemento"); PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filamento"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E en mm³"); + PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E en mm") SUPERSCRIPT_THREE; PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Diam. fil."); PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Diam. fil. *"); PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Descarga mm"); diff --git a/Marlin/src/lcd/language/language_hr.h b/Marlin/src/lcd/language/language_hr.h index 1b2ae41fcedb..e4cbdaed6c61 100644 --- a/Marlin/src/lcd/language/language_hr.h +++ b/Marlin/src/lcd/language/language_hr.h @@ -41,7 +41,7 @@ namespace Language_hr { PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("SD kartica uklonjena"); PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Endstops"); // Max length 8 characters PROGMEM Language_Str MSG_MAIN = _UxGT("Main"); - PROGMEM Language_Str MSG_AUTOSTART = _UxGT("Auto pokretanje"); + PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Auto pokretanje"); PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Ugasi steppere"); PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Automatski homing"); PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Home-aj X"); @@ -79,10 +79,11 @@ namespace Language_hr { PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Niveliraj bed"); PROGMEM Language_Str MSG_MOVE_X = _UxGT("Miči X"); PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Miči Y"); - PROGMEM Language_Str MSG_MOVE_Z_DIST = _UxGT("Miči %smm"); + PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Miči %smm"); PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Miči 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Miči 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Miči 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Miči 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Brzina"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Bed Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Dizna"); @@ -94,7 +95,7 @@ namespace Language_hr { PROGMEM Language_Str MSG_SELECT_E = _UxGT("Odaberi *"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperature"); PROGMEM Language_Str MSG_MOTION = _UxGT("Gibanje"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm³"); + PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm") SUPERSCRIPT_THREE; PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Fil. Dia."); PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Fil. Dia. *"); PROGMEM Language_Str MSG_CONTRAST = _UxGT("Kontrast LCD-a"); diff --git a/Marlin/src/lcd/language/language_hu.h b/Marlin/src/lcd/language/language_hu.h index 6e1b30c18096..6fb41f90ff2d 100644 --- a/Marlin/src/lcd/language/language_hu.h +++ b/Marlin/src/lcd/language/language_hu.h @@ -22,19 +22,20 @@ #pragma once /** - * Magyar - * - * LCD Menü Üzenetek. Lásd még https://marlinfw.org/docs/development/lcd_language.html - * Marlin 2.0.x bugfix Magyar fordítása. A fordítást folyamatosan javítom és frissítem. - * A Magyar fordítást készítette: AntoszHUN + * Hungarian / Magyar * + * LCD Menu Messages. See also https://marlinfw.org/docs/development/lcd_language.html + * Hungarian translation by AntoszHUN. I am constantly improving and updating the translation. + * Translation last updated: 07/07/2021 - 11:20 * + * LCD Menü Üzenetek. Lásd még https://marlinfw.org/docs/development/lcd_language.html + * A Magyar fordítást készítette: AntoszHUN. A fordítást folyamatosan javítom és frissítem. + * A Fordítás utolsó frissítése: 2021.07.07. - 11:20 */ namespace Language_hu { using namespace Language_en; // A fordítás az örökölt Amerikai Angol (English) karakterláncokat használja. - constexpr uint8_t CHARSIZE = 2; PROGMEM Language_Str LANGUAGE = _UxGT("Magyar"); @@ -44,35 +45,51 @@ namespace Language_hu { PROGMEM Language_Str MSG_NO = _UxGT("NEM"); PROGMEM Language_Str MSG_BACK = _UxGT("Vissza"); PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("Megszakítás..."); - PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Tároló Behelyezve"); - PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Tároló Eltávolítva"); + PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Tároló behelyezve"); + PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Tároló eltávolítva"); PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Várakozás a tárolóra"); + PROGMEM Language_Str MSG_SD_INIT_FAIL = _UxGT("SD-kártya hiba"); PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Tároló olvasási hiba"); PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("USB eltávolítva"); PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("USB eszköz hiba"); PROGMEM Language_Str MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Túlfolyás"); PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Végállás"); // Maximum 8 karakter - PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("Szoft. Végállás"); + PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("Szoft. végállás"); PROGMEM Language_Str MSG_MAIN = _UxGT(""); - PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("További Beállítások"); + PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("További beállítások"); PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Konfiguráció"); - PROGMEM Language_Str MSG_AUTOSTART = _UxGT("Autoinditás"); + PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Fájl auto. futtatás"); PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Motorok kikapcsolása"); PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Hiba Menü"); PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Haladás sáv teszt"); - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("XYZ Auto kezdöpont"); - PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("X Kezdöpont"); - PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Y Kezdöpont"); - PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Z Kezdöpont"); - PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Auto Z-Igazítás"); - PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("XYZ Kezdöpont"); + PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("X-Y-Z auto kezdöpont"); + PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("X kezdöpont"); + PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Y kezdöpont"); + PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Z kezdöpont"); + PROGMEM Language_Str MSG_AUTO_HOME_I = _UxGT("Kezdö ") LCD_STR_I; + PROGMEM Language_Str MSG_AUTO_HOME_J = _UxGT("Kezdö ") LCD_STR_J; + PROGMEM Language_Str MSG_AUTO_HOME_K = _UxGT("Kezdö ") LCD_STR_K; + PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Auto Z-igazítás"); + PROGMEM Language_Str MSG_ITERATION = _UxGT("G34 Ismétlés: %i"); + PROGMEM Language_Str MSG_DECREASING_ACCURACY = _UxGT("Pontosság csökken!"); + PROGMEM Language_Str MSG_ACCURACY_ACHIEVED = _UxGT("Pontosság elérve"); + PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("X-Y-Z kezdöpont"); PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Kattints a kezdéshez."); - PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Következö Pont"); - PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Szintezés Kész!"); - PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Szint Csökkentés"); + PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Következö pont"); + PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Szintezés kész!"); + PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Szint csökkentés"); PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Kezdöpont eltolás"); + PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("X Kezdö eltol."); + PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Y Kezdö eltol."); + PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Z Kezdö eltol."); + PROGMEM Language_Str MSG_HOME_OFFSET_I = _UxGT("Kezdö eltol. ") LCD_STR_I; + PROGMEM Language_Str MSG_HOME_OFFSET_J = _UxGT("Kezdö eltol. ") LCD_STR_J; + PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Kezdö eltol. ") LCD_STR_K; PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Eltolás beállítva."); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Eredeti Be"); + PROGMEM Language_Str MSG_TRAMMING_WIZARD = _UxGT("Elektromos varázsló"); + PROGMEM Language_Str MSG_SELECT_ORIGIN = _UxGT("Eredeti választása"); + PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Utolsó érték "); #if PREHEAT_COUNT PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Fütés ") PREHEAT_1_LABEL; PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Fütés ") PREHEAT_1_LABEL " ~"; @@ -90,127 +107,138 @@ namespace Language_hu { PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("Fütés $ Ágy"); PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("Fütés $ Beáll"); #endif - PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Egyedi Elömelegítés"); + PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Egyedi elömelegítés"); PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Visszahütés"); + PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Frekvencia"); - PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Lézer Vezérlés"); - PROGMEM Language_Str MSG_LASER_OFF = _UxGT("Lézer Ki"); - PROGMEM Language_Str MSG_LASER_ON = _UxGT("Lézer Be"); - PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Lézer Teljesítmény"); - PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Orsó Vezérlés"); - PROGMEM Language_Str MSG_SPINDLE_OFF = _UxGT("Orsó Ki"); - PROGMEM Language_Str MSG_SPINDLE_ON = _UxGT("Orsó Be"); - PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Orsó Teljesítmény"); - PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Orsó Hátra"); + PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Lézer vezérlés"); + PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Orsó vezérlés"); + PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Lézer telj."); + PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Orsó telj."); + PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Lézer váltás"); + PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Hütés váltás"); + PROGMEM Language_Str MSG_LASER_ASSIST_TOGGLE = _UxGT("Levegö segéd"); + PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Impulzus teszt ms"); + PROGMEM Language_Str MSG_LASER_FIRE_PULSE = _UxGT("Tüz impulzus"); + PROGMEM Language_Str MSG_FLOWMETER_FAULT = _UxGT("Áramlási hiba"); + PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Orsóváltás"); + PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Vákuum váltás"); + PROGMEM Language_Str MSG_SPINDLE_FORWARD = _UxGT("Orsó elöre"); + PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Orsó hátra"); PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Bekapcsolás"); PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Kikapcsolás"); - PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Extrudál"); + PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Adagol"); PROGMEM Language_Str MSG_RETRACT = _UxGT("Visszahúz"); - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Tengelyek Mozgatása"); - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Ágy Szintezés"); + PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Tengelyek mozgatása"); + PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Ágy szintezés"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Ágy szintezése"); - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Sarok szint"); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Elektromos segéd"); + PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Ágy emelése a szonda váltásig"); + PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("Minden sarok tolerancián belül. Szint jó."); + PROGMEM Language_Str MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Jó pontok: "); + PROGMEM Language_Str MSG_BED_TRAMMING_LAST_Z = _UxGT("Utolsó Z: "); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Következö sarok"); - PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Háló Szerkesztö"); - PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Háló Szerkesztése"); - PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Háló Szerk. Állj"); + PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Háló szerkesztö"); + PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Háló szerkesztése"); + PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Háló szerk. állj"); PROGMEM Language_Str MSG_PROBING_MESH = _UxGT("Próbapont"); PROGMEM Language_Str MSG_MESH_X = _UxGT("Index X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("Index Y"); - PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Z Érték"); - PROGMEM Language_Str MSG_USER_MENU = _UxGT("Egyéni Parancs"); - PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 Probe Teszt"); + PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Z érték"); + PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Egyéni parancs"); + PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 Szonda teszt"); PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 Pont"); + PROGMEM Language_Str MSG_M48_OUT_OF_BOUNDS = _UxGT("Szonda határon kívül"); PROGMEM Language_Str MSG_M48_DEVIATION = _UxGT("Eltérés"); - PROGMEM Language_Str MSG_IDEX_MENU = _UxGT("IDEX Mód"); - PROGMEM Language_Str MSG_OFFSETS_MENU = _UxGT("Eszköz Eltolás"); - PROGMEM Language_Str MSG_IDEX_MODE_AUTOPARK = _UxGT("Auto-Parkolás"); + PROGMEM Language_Str MSG_IDEX_MENU = _UxGT("IDEX mód"); + PROGMEM Language_Str MSG_OFFSETS_MENU = _UxGT("Eszköz eltolás"); + PROGMEM Language_Str MSG_IDEX_MODE_AUTOPARK = _UxGT("Automata parkolás"); PROGMEM Language_Str MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplikálás"); PROGMEM Language_Str MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Tükrözött másolás"); PROGMEM Language_Str MSG_IDEX_MODE_FULL_CTRL = _UxGT("Teljes felügyelet"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_X = _UxGT("2. fúvóka X"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_Y = _UxGT("2. fúvóka Y"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_Z = _UxGT("2. fúvóka Z"); + PROGMEM Language_Str MSG_IDEX_DUPE_GAP = _UxGT("X-hézag másolása"); + PROGMEM Language_Str MSG_HOTEND_OFFSET_X = _UxGT("2. fej X"); + PROGMEM Language_Str MSG_HOTEND_OFFSET_Y = _UxGT("2. fej Y"); + PROGMEM Language_Str MSG_HOTEND_OFFSET_Z = _UxGT("2. fej Z"); PROGMEM Language_Str MSG_UBL_DOING_G29 = _UxGT("Szintezz! G29"); - PROGMEM Language_Str MSG_UBL_TOOLS = _UxGT("UBL Eszköz"); - PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Egységes Ágy Szint"); - PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Döntési Pont"); - PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Kézi Háló Építés"); + PROGMEM Language_Str MSG_UBL_TOOLS = _UxGT("UBL eszköz"); + PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Egységes ágy szint"); + PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Döntési pont"); + PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Kézi háló építés"); + PROGMEM Language_Str MSG_UBL_MESH_WIZARD = _UxGT("UBL Háló varázsló"); PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Tégy alátétet és mérj"); PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Mérés"); PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Üres ágyat mérj"); PROGMEM Language_Str MSG_UBL_MOVING_TO_NEXT = _UxGT("Továbblépés"); - PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("UBL Aktivál"); - PROGMEM Language_Str MSG_UBL_DEACTIVATE_MESH = _UxGT("UBL Deaktivál"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = _UxGT("Ágy Höfok"); - PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Ágy Höfok"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = _UxGT("Fúvóka Höfok"); - PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Fúvóka Höfok"); - PROGMEM Language_Str MSG_UBL_MESH_EDIT = _UxGT("Háló Szerkesztés"); - PROGMEM Language_Str MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Egyéni Háló Szerkesztés"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("Finomított Háló"); - PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Háló Kész"); - PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Egyéni Háló Építés"); - PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("Háló Építés"); - #if PREHEAT_COUNT - PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Háló Építés ($)"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Háló Elfogadás ($)"); - #endif - PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Hideg Háló Építés"); - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("AHáló Magasság Állítása"); - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Összmagasság"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Háló Elfogadás"); - PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Valódi Háló Elfogadása"); - PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26 Ágy Fűtés"); - PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("G26 Fúvóka Fűtés"); + PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("UBL aktívál"); + PROGMEM Language_Str MSG_UBL_DEACTIVATE_MESH = _UxGT("UBL deaktívál"); + PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = _UxGT("Ágy höfok"); + PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Egyéni ágy höfok"); + PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = _UxGT("Fejhöfok"); + PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Egyéni fejhöfok"); + PROGMEM Language_Str MSG_UBL_MESH_EDIT = _UxGT("Háló szerkesztés"); + PROGMEM Language_Str MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Egyéni háló szerkesztés"); + PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("Finomított háló"); + PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Háló kész"); + PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Egyéni háló építés"); + PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("Háló építés"); + PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Háló építés ($)"); + PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Hideg háló építés"); + PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Háló magasság állítás"); + PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Magasság összege"); + PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Háló elfogadás"); + PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Háló elfogadás ($)"); + PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Valódi háló elfogadása"); + PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26 Ágy fütés"); + PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("G26 Fej fütés"); PROGMEM Language_Str MSG_G26_MANUAL_PRIME = _UxGT("Kézi alapozás..."); PROGMEM Language_Str MSG_G26_FIXED_LENGTH = _UxGT("Fix hosszúságú alap"); - PROGMEM Language_Str MSG_G26_PRIME_DONE = _UxGT("Alapozás Kész"); + PROGMEM Language_Str MSG_G26_PRIME_DONE = _UxGT("Alapozás kész"); PROGMEM Language_Str MSG_G26_CANCELED = _UxGT("G26 Törölve"); PROGMEM Language_Str MSG_G26_LEAVING = _UxGT("Kilépö G26"); - PROGMEM Language_Str MSG_UBL_CONTINUE_MESH = _UxGT("Ágy Háló Folyt."); - PROGMEM Language_Str MSG_UBL_MESH_LEVELING = _UxGT("Háló Szintezés"); - PROGMEM Language_Str MSG_UBL_3POINT_MESH_LEVELING = _UxGT("3-Pontos Szintezés"); - PROGMEM Language_Str MSG_UBL_GRID_MESH_LEVELING = _UxGT("Rács Szintezés"); - PROGMEM Language_Str MSG_UBL_MESH_LEVEL = _UxGT("Háló Szint"); + PROGMEM Language_Str MSG_UBL_CONTINUE_MESH = _UxGT("Ágy háló folyt."); + PROGMEM Language_Str MSG_UBL_MESH_LEVELING = _UxGT("Háló szintezés"); + PROGMEM Language_Str MSG_UBL_3POINT_MESH_LEVELING = _UxGT("3-Pontos szintezés"); + PROGMEM Language_Str MSG_UBL_GRID_MESH_LEVELING = _UxGT("Rács szintezés"); + PROGMEM Language_Str MSG_UBL_MESH_LEVEL = _UxGT("Háló szint"); PROGMEM Language_Str MSG_UBL_SIDE_POINTS = _UxGT("Oldal pontok"); - PROGMEM Language_Str MSG_UBL_MAP_TYPE = _UxGT("Térkép Típus"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP = _UxGT("Háló Térkép Kimenet"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Host Kimenet"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_CSV = _UxGT("CSV Kimenet"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Nyomtató Backup Ki"); - PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("UBL Infó Kimenet"); - PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Kitöltési Költség"); - PROGMEM Language_Str MSG_UBL_MANUAL_FILLIN = _UxGT("Kézi Kitöltés"); - PROGMEM Language_Str MSG_UBL_SMART_FILLIN = _UxGT("Okos Kitöltés"); - PROGMEM Language_Str MSG_UBL_FILLIN_MESH = _UxGT("Háló Kitöltés"); - PROGMEM Language_Str MSG_UBL_INVALIDATE_ALL = _UxGT("Minden Érvénytelen"); - PROGMEM Language_Str MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Közelebbi Érvénytelen"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("Mindet Finomhangolja"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Közelebbi Finomhangolása"); - PROGMEM Language_Str MSG_UBL_STORAGE_MESH_MENU = _UxGT("Háló Tárolás"); - PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Memória Foglalat"); - PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Ágy háló Betöltés"); - PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Ágy háló Mentés"); - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("M117 Háló %i Betöltve"); - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("M117 Háló %i Mentve"); + PROGMEM Language_Str MSG_UBL_MAP_TYPE = _UxGT("Térkép típus"); + PROGMEM Language_Str MSG_UBL_OUTPUT_MAP = _UxGT("Háló térkép kimenet"); + PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Host kimenet"); + PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_CSV = _UxGT("CSV kimenet"); + PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Nyomtató bizt.mentés"); + PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("UBL infó kimenet"); + PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Kitöltési költség"); + PROGMEM Language_Str MSG_UBL_MANUAL_FILLIN = _UxGT("Kézi kitöltés"); + PROGMEM Language_Str MSG_UBL_SMART_FILLIN = _UxGT("Okos kitöltés"); + PROGMEM Language_Str MSG_UBL_FILLIN_MESH = _UxGT("Háló kitöltés"); + PROGMEM Language_Str MSG_UBL_INVALIDATE_ALL = _UxGT("Minden érvénytelen"); + PROGMEM Language_Str MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Közelebbi érvénytelen"); + PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("Mindet finomhangolja"); + PROGMEM Language_Str MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Közelebbi finomhangolása"); + PROGMEM Language_Str MSG_UBL_STORAGE_MESH_MENU = _UxGT("Háló tárolás"); + PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Memória foglalat"); + PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Ágy háló betöltés"); + PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Ágy háló mentés"); + PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("M117 Háló %i betöltve"); + PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("M117 Háló %i mentve"); PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("Nincs tároló"); - PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Hiba: UBL Mentés"); - PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Hiba: UBL Visszaáll"); - PROGMEM Language_Str MSG_UBL_Z_OFFSET = _UxGT("Z-Eltolás: "); - PROGMEM Language_Str MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Z-Eltolás Leállítva"); - PROGMEM Language_Str MSG_UBL_STEP_BY_STEP_MENU = _UxGT("Lépésröl Lépésre UBL"); - PROGMEM Language_Str MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1. Hideg Háló Készítés"); - PROGMEM Language_Str MSG_UBL_2_SMART_FILLIN = _UxGT("2. Inteligens Kitöltés"); - PROGMEM Language_Str MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3. Háló Érvényesítés"); - PROGMEM Language_Str MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4. Minden Finomítása"); - PROGMEM Language_Str MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5. Háló Érvényesítés"); - PROGMEM Language_Str MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6. Minden Finomítása"); - PROGMEM Language_Str MSG_UBL_7_SAVE_MESH = _UxGT("7. Ágy Háló Mentése"); + PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Hiba: UBL mentés"); + PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Hiba: UBL visszaáll."); + PROGMEM Language_Str MSG_UBL_Z_OFFSET = _UxGT("Z-eltolás: "); + PROGMEM Language_Str MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Z-eltolás leállítva"); + PROGMEM Language_Str MSG_UBL_STEP_BY_STEP_MENU = _UxGT("Lépésröl lépésre UBL"); + PROGMEM Language_Str MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1. Hideg háló készítés"); + PROGMEM Language_Str MSG_UBL_2_SMART_FILLIN = _UxGT("2. Inteligens kitöltés"); + PROGMEM Language_Str MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3. Háló érvényesítés"); + PROGMEM Language_Str MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4. Minden finomítása"); + PROGMEM Language_Str MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5. Háló érvényesítés"); + PROGMEM Language_Str MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6. Minden finomítása"); + PROGMEM Language_Str MSG_UBL_7_SAVE_MESH = _UxGT("7. Ágy háló mentése"); - PROGMEM Language_Str MSG_LED_CONTROL = _UxGT("LED Vezérlés"); + PROGMEM Language_Str MSG_LED_CONTROL = _UxGT("LED vezérlés"); PROGMEM Language_Str MSG_LEDS = _UxGT("Világítás"); - PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("Beállított Színek"); + PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("Beállított színek"); PROGMEM Language_Str MSG_SET_LEDS_RED = _UxGT("Piros"); PROGMEM Language_Str MSG_SET_LEDS_ORANGE = _UxGT("Narancs"); PROGMEM Language_Str MSG_SET_LEDS_YELLOW = _UxGT("Sárga"); @@ -220,42 +248,58 @@ namespace Language_hu { PROGMEM Language_Str MSG_SET_LEDS_VIOLET = _UxGT("Viola"); PROGMEM Language_Str MSG_SET_LEDS_WHITE = _UxGT("Fehér"); PROGMEM Language_Str MSG_SET_LEDS_DEFAULT = _UxGT("Alapérték"); - PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Egyéni Szín"); - PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Piros Intenzitás"); - PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Zöld Intenzitás"); - PROGMEM Language_Str MSG_INTENSITY_B = _UxGT("Kék Intenzitás"); - PROGMEM Language_Str MSG_INTENSITY_W = _UxGT("Fehér Intenzitás"); + PROGMEM Language_Str MSG_LED_CHANNEL_N = _UxGT("Csatorna ="); + PROGMEM Language_Str MSG_LEDS2 = _UxGT("LED-ek #2"); + PROGMEM Language_Str MSG_NEO2_PRESETS = _UxGT("Fény #2 megadott"); + PROGMEM Language_Str MSG_NEO2_BRIGHTNESS = _UxGT("Fényerö"); + PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Egyéni szín"); + PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Piros intenzitás"); + PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Zöld intenzitás"); + PROGMEM Language_Str MSG_INTENSITY_B = _UxGT("Kék intenzitás"); + PROGMEM Language_Str MSG_INTENSITY_W = _UxGT("Fehér intenzitás"); PROGMEM Language_Str MSG_LED_BRIGHTNESS = _UxGT("Fényerö"); PROGMEM Language_Str MSG_MOVING = _UxGT("Mozgás..."); - PROGMEM Language_Str MSG_FREE_XY = _UxGT("XY Szabad"); - PROGMEM Language_Str MSG_MOVE_X = _UxGT("X Mozgás"); - PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Y Mozgás"); - PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Z Mozgás"); + PROGMEM Language_Str MSG_FREE_XY = _UxGT("XY szabad"); + PROGMEM Language_Str MSG_MOVE_X = _UxGT("X mozgás"); + PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Y mozgás"); + PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Z mozgás"); + PROGMEM Language_Str MSG_MOVE_I = _UxGT("Mozgás ") LCD_STR_I; + PROGMEM Language_Str MSG_MOVE_J = _UxGT("Mozgás ") LCD_STR_J; + PROGMEM Language_Str MSG_MOVE_K = _UxGT("Mozgás ") LCD_STR_K; PROGMEM Language_Str MSG_MOVE_E = _UxGT("Adagoló"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Adagoló *"); - PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("A fúvóka túl hideg"); - PROGMEM Language_Str MSG_MOVE_Z_DIST = _UxGT("Mozgás %smm"); + PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("A fej túl hideg"); + PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Mozgás %smm"); PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mozgás 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mozgás 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Mozgás 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Mozgás 100mm"); + PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Mozgás 0.025mm"); + PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Mozgás 0.254mm"); + PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Mozgás 2.54mm"); + PROGMEM Language_Str MSG_MOVE_1IN = _UxGT("Mozgáá 25.4mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Sebesség"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Z ágy"); - PROGMEM Language_Str MSG_NOZZLE = _UxGT("Fúvóka"); - PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Fúvóka ~"); - PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Fej Parkolva"); - PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Fej Készenlétbe"); + PROGMEM Language_Str MSG_NOZZLE = _UxGT("Fej"); + PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Fej ~"); + PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Fej parkolva"); + PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Fej készenlétbe"); PROGMEM Language_Str MSG_BED = _UxGT("Ágy"); PROGMEM Language_Str MSG_CHAMBER = _UxGT("Burkolat"); + PROGMEM Language_Str MSG_COOLER = _UxGT("Lézer hütövíz"); + PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Hütö kapcsoló"); + PROGMEM Language_Str MSG_FLOWMETER_SAFETY = _UxGT("Áramlásbiztonság"); + PROGMEM Language_Str MSG_LASER = _UxGT("Lézer"); PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Hütés sebesség"); PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Hütés sebesség ="); - PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Tárolt Hütés ="); + PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Tárolt hütés ="); PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Extra hütés sebesség"); PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Extra hütés sebesség ="); - PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Hűtésvezérlés"); + PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Hütésvezérlés"); PROGMEM Language_Str MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Alapjárat"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Automatikus Mód"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("Aktív Sebesség"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Automatikus mód"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("Aktív sebesség"); PROGMEM Language_Str MSG_CONTROLLER_FAN_DURATION = _UxGT("Készenlét"); PROGMEM Language_Str MSG_FLOW = _UxGT("Folyás"); PROGMEM Language_Str MSG_FLOW_N = _UxGT("Folyás ~"); @@ -263,13 +307,13 @@ namespace Language_hu { PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Minimum"); PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Maximum"); PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Tényezö"); - PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Automata Höfok"); + PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Automata höfok"); PROGMEM Language_Str MSG_LCD_ON = _UxGT("Be"); PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Ki"); - PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("PID Hangolás"); - PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("PID Hangolás *"); + PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("PID hangolás"); + PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("PID hangolás *"); PROGMEM Language_Str MSG_PID_AUTOTUNE_DONE = _UxGT("PID hangolás kész"); - PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Hangolási hiba. Rossz Adagoló."); + PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Hangolási hiba. Rossz adagoló."); PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Hangolási hiba. Magas hömérséklet."); PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("Hangolási hiba! Idötúllépés."); PROGMEM Language_Str MSG_PID_P = _UxGT("PID-P"); @@ -286,41 +330,55 @@ namespace Language_hu { PROGMEM Language_Str MSG_SELECT_E = _UxGT("Kiválaszt *"); PROGMEM Language_Str MSG_ACC = _UxGT("Gyorsítás"); PROGMEM Language_Str MSG_JERK = _UxGT("Rántás"); - PROGMEM Language_Str MSG_VA_JERK = LCD_STR_A _UxGT(" Ránt. Seb."); - PROGMEM Language_Str MSG_VB_JERK = LCD_STR_B _UxGT(" Ránt. Seb."); - PROGMEM Language_Str MSG_VC_JERK = LCD_STR_C _UxGT(" Ránt. Seb."); - PROGMEM Language_Str MSG_VE_JERK = _UxGT("E Ránt. Seb."); - PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Csomopont Eltérés"); + PROGMEM Language_Str MSG_VA_JERK = _UxGT("Seb.") LCD_STR_A _UxGT("-Rántás"); + PROGMEM Language_Str MSG_VB_JERK = _UxGT("Seb.") LCD_STR_B _UxGT("-Rántás"); + PROGMEM Language_Str MSG_VC_JERK = _UxGT("Seb.") LCD_STR_C _UxGT("-Rántás"); + PROGMEM Language_Str MSG_VI_JERK = _UxGT("Seb.") LCD_STR_I _UxGT("-Rántás"); + PROGMEM Language_Str MSG_VJ_JERK = _UxGT("Seb.") LCD_STR_J _UxGT("-Rántás"); + PROGMEM Language_Str MSG_VK_JERK = _UxGT("Seb.") LCD_STR_K _UxGT("-Rántás"); + PROGMEM Language_Str MSG_VE_JERK = _UxGT("E ránt. seb."); + PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Csomopont eltérés"); PROGMEM Language_Str MSG_VELOCITY = _UxGT("Sebesség"); - PROGMEM Language_Str MSG_VMAX_A = _UxGT("Max Sebesség ") LCD_STR_A; - PROGMEM Language_Str MSG_VMAX_B = _UxGT("Max Sebesség ") LCD_STR_B; - PROGMEM Language_Str MSG_VMAX_C = _UxGT("Max Sebesség ") LCD_STR_C; - PROGMEM Language_Str MSG_VMAX_E = _UxGT("Max Sebesség ") LCD_STR_E; - PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Max Sebesség *"); - PROGMEM Language_Str MSG_VMIN = _UxGT("Min Sebesség"); - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Min Utazó.seb."); + PROGMEM Language_Str MSG_VMAX_A = _UxGT("Max Seb. ") LCD_STR_A; + PROGMEM Language_Str MSG_VMAX_B = _UxGT("Max Seb. ") LCD_STR_B; + PROGMEM Language_Str MSG_VMAX_C = _UxGT("Max Seb. ") LCD_STR_C; + PROGMEM Language_Str MSG_VMAX_I = _UxGT("Max Seb. ") LCD_STR_I; + PROGMEM Language_Str MSG_VMAX_J = _UxGT("Max Seb. ") LCD_STR_J; + PROGMEM Language_Str MSG_VMAX_K = _UxGT("Max Seb. ") LCD_STR_K; + PROGMEM Language_Str MSG_VMAX_E = _UxGT("Max Seb. ") LCD_STR_E; + PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Max sebesség *"); + PROGMEM Language_Str MSG_VMIN = _UxGT("Min sebesség"); + PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Min utazó.seb."); PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Gyorsulás"); - PROGMEM Language_Str MSG_AMAX_A = _UxGT("Max Gyors. ") LCD_STR_A; - PROGMEM Language_Str MSG_AMAX_B = _UxGT("Max Gyors. ") LCD_STR_B; - PROGMEM Language_Str MSG_AMAX_C = _UxGT("Max Gyors. ") LCD_STR_C; - PROGMEM Language_Str MSG_AMAX_E = _UxGT("Max Gyors. ") LCD_STR_E; - PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Max Gyorsulás *"); + PROGMEM Language_Str MSG_AMAX_A = _UxGT("Max gyors. ") LCD_STR_A; + PROGMEM Language_Str MSG_AMAX_B = _UxGT("Max gyors. ") LCD_STR_B; + PROGMEM Language_Str MSG_AMAX_C = _UxGT("Max gyors. ") LCD_STR_C; + PROGMEM Language_Str MSG_AMAX_I = _UxGT("Max gyors. ") LCD_STR_I; + PROGMEM Language_Str MSG_AMAX_J = _UxGT("Max gyors. ") LCD_STR_J; + PROGMEM Language_Str MSG_AMAX_K = _UxGT("Max gyors. ") LCD_STR_K; + PROGMEM Language_Str MSG_AMAX_E = _UxGT("Max gyors. ") LCD_STR_E; + PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Max gyorsulás *"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Visszahúzás"); PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("Utazás"); - PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("Max Frekvencia"); - PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Min Elötolás"); + PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("Max frekvencia"); + PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Min elötolás"); PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Lépés/mm"); - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" lépés/mm"); - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" lépés/mm"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" lépés/mm"); + PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" Lépés/mm"); + PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" Lépés/mm"); + PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" Lépés/mm"); + PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" Lépés/mm"); + PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" Lépés/mm"); + PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" Lépés/mm"); PROGMEM Language_Str MSG_E_STEPS = _UxGT("E lépés/mm"); - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("*lépés/mm"); + PROGMEM Language_Str MSG_EN_STEPS = _UxGT("*Lépés/mm"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Höfok"); PROGMEM Language_Str MSG_MOTION = _UxGT("Mozgatások"); PROGMEM Language_Str MSG_FILAMENT = _UxGT("Nyomtatószál"); PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E mm³-ben"); - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Szál. Átm."); - PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Szál. Átm. *"); + PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("E Limit mm³-ben"); + PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT_E = _UxGT("E Limit *"); + PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Szál. átm."); + PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Szál. átm. *"); PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Kiadás mm"); PROGMEM Language_Str MSG_FILAMENT_LOAD = _UxGT("Betöltés mm"); PROGMEM Language_Str MSG_ADVANCE_K = _UxGT("Haladó K"); @@ -329,84 +387,92 @@ namespace Language_hu { PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Mentés EEPROM"); PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Betöltés EEPROM"); PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Alapértelmezett"); - PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("EEPROM Inicializálás"); + PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("EEPROM inicializálás"); PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("Hiba: EEPROM CRC"); - PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("Hiba: EEPROM Index"); - PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("Hiba: EEPROM Verzió"); - PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Beállítások Mentve"); - PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Tároló Frissítés"); - PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Nyomtató Újraindítása"); + PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("Hiba: EEPROM index"); + PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("Hiba: EEPROM verzió"); + PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Beállítások mentve"); + PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Tároló frissítés"); + PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Nyomtató újraindítása"); PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Frissítés"); - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT(""); + PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT(""); PROGMEM Language_Str MSG_PREPARE = _UxGT("Vezérlés"); PROGMEM Language_Str MSG_TUNE = _UxGT("Hangolás"); - PROGMEM Language_Str MSG_START_PRINT = _UxGT("Nyomtatás Indítása"); + PROGMEM Language_Str MSG_POWER_MONITOR = _UxGT("Teljesítménymonitor"); + PROGMEM Language_Str MSG_CURRENT = _UxGT("Jelenlegi"); + PROGMEM Language_Str MSG_VOLTAGE = _UxGT("Feszültség"); + PROGMEM Language_Str MSG_POWER = _UxGT("Energia"); + PROGMEM Language_Str MSG_START_PRINT = _UxGT("Nyomtatás indítása"); PROGMEM Language_Str MSG_BUTTON_NEXT = _UxGT("Tovább"); PROGMEM Language_Str MSG_BUTTON_INIT = _UxGT("Kezdet"); PROGMEM Language_Str MSG_BUTTON_STOP = _UxGT("Állj"); PROGMEM Language_Str MSG_BUTTON_PRINT = _UxGT("Nyomtatás"); PROGMEM Language_Str MSG_BUTTON_RESET = _UxGT("Újraindítás"); + PROGMEM Language_Str MSG_BUTTON_IGNORE = _UxGT("Mellöz"); PROGMEM Language_Str MSG_BUTTON_CANCEL = _UxGT("Mégse"); PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Kész"); PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Vissza"); PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Folytatás"); + PROGMEM Language_Str MSG_BUTTON_SKIP = _UxGT("Kihagy"); PROGMEM Language_Str MSG_PAUSING = _UxGT("Szüneteltetve..."); - PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Nyomtatás Szünetelés"); + PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Nyomtatás szünetelés"); PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Nyomtatás folytatása"); + PROGMEM Language_Str MSG_HOST_START_PRINT = _UxGT("Hoszt indítás"); PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Nyomtatás leállítása"); - PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("Objektum Nyomtatása"); - PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("Objektum Törlése"); - PROGMEM Language_Str MSG_CANCEL_OBJECT_N = _UxGT("Objektum Törlése ="); - PROGMEM Language_Str MSG_OUTAGE_RECOVERY = _UxGT("Kiesés Helyreáll."); - PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Nyomtatás Tárolóról"); - PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("Nincs Tároló"); + PROGMEM Language_Str MSG_END_LOOPS = _UxGT("Hurok ismétlés vége"); + PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("Objektum nyomtatása"); + PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("Objektum törlése"); + PROGMEM Language_Str MSG_CANCEL_OBJECT_N = _UxGT("Objektum törlése ="); + PROGMEM Language_Str MSG_OUTAGE_RECOVERY = _UxGT("Kiesés helyreáll."); + PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Nyomtatás tárolóról"); + PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("Nincs tároló"); PROGMEM Language_Str MSG_DWELL = _UxGT("Alvás..."); PROGMEM Language_Str MSG_USERWAIT = _UxGT("Katt a folytatáshoz..."); PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("Nyomtatás szünetelve"); PROGMEM Language_Str MSG_PRINTING = _UxGT("Nyomtatás..."); PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Nyomtatás leállítva"); - PROGMEM Language_Str MSG_PRINT_DONE = _UxGT("Nyomtatás Kész"); + PROGMEM Language_Str MSG_PRINT_DONE = _UxGT("Nyomtatás kész"); PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Nincs mozgás."); PROGMEM Language_Str MSG_KILLED = _UxGT("HALOTT! "); PROGMEM Language_Str MSG_STOPPED = _UxGT("MEGÁLLT! "); PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Visszahúzás mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Visszahúzás Cs. mm"); + PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Visszahúzás cs. mm"); PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Viszahúzás"); PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Ugrás mm"); PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("Visszah.helyre mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Csere.Visszah.helyre mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Unretract V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("S UnRet V"); - PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("AutoVisszah."); - PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Visszahúzás Távolság"); - PROGMEM Language_Str MSG_FILAMENT_SWAP_EXTRA = _UxGT("Extra Csere"); - PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Tisztítási Távolság"); + PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Csere.visszah.helyre mm"); + PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Visszahúzás V"); + PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("S Vissza.h V"); + PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Auto visszah."); + PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Visszahúzás távolság"); + PROGMEM Language_Str MSG_FILAMENT_SWAP_EXTRA = _UxGT("Extra csere"); + PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Tisztítási távolság"); PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Szerszámcsere"); - PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Z Emelés"); + PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Z emelés"); PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Fösebesség"); - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Visszah. Sebesség"); - PROGMEM Language_Str MSG_FILAMENT_PARK_ENABLED = _UxGT("Fej Parkolás"); - PROGMEM Language_Str MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Visszahúzás Sebesség"); - PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("FAN Sebesség"); + PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Visszah. sebesség"); + PROGMEM Language_Str MSG_FILAMENT_PARK_ENABLED = _UxGT("Fej parkolás"); + PROGMEM Language_Str MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Visszav.visszah. sebesség"); + PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("FAN sebesség"); PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_TIME = _UxGT("FAN idö"); PROGMEM Language_Str MSG_TOOL_MIGRATION_ON = _UxGT("Auto BE"); PROGMEM Language_Str MSG_TOOL_MIGRATION_OFF = _UxGT("Auto KI"); PROGMEM Language_Str MSG_TOOL_MIGRATION = _UxGT("Szerszámcsere"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_AUTO = _UxGT("Automata Csere"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_END = _UxGT("Utolsó Adagoló"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_AUTO = _UxGT("Automata csere"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_END = _UxGT("Utolsó adagoló"); PROGMEM Language_Str MSG_TOOL_MIGRATION_SWAP = _UxGT("Csere *"); - PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Szál csere"); - PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Szál csere *"); + PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Szálcsere"); + PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Szálcsere *"); PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Szál betöltés"); PROGMEM Language_Str MSG_FILAMENTLOAD_E = _UxGT("Szál betöltés *"); PROGMEM Language_Str MSG_FILAMENTUNLOAD = _UxGT("Szál eltávolítás"); PROGMEM Language_Str MSG_FILAMENTUNLOAD_E = _UxGT("Szál eltávolítás *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_ALL = _UxGT("Mindet Eltávolít"); + PROGMEM Language_Str MSG_FILAMENTUNLOAD_ALL = _UxGT("Mindet eltávolít"); PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Tároló"); PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Tároló csere"); PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("Tároló Kiadása"); PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Z szonda tálcán kivül"); - PROGMEM Language_Str MSG_SKEW_FACTOR = _UxGT("Ferdeség Faktor"); + PROGMEM Language_Str MSG_SKEW_FACTOR = _UxGT("Ferdeség faktor"); PROGMEM Language_Str MSG_BLTOUCH = _UxGT("BLTouch"); PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("Önteszt"); PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Visszaállítás"); @@ -416,25 +482,29 @@ namespace Language_hu { PROGMEM Language_Str MSG_BLTOUCH_5V_MODE = _UxGT("5V-Mód"); PROGMEM Language_Str MSG_BLTOUCH_OD_MODE = _UxGT("OD-Mód"); PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE = _UxGT("Módok"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_5V = _UxGT("BLTouch 5V Mód"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_OD = _UxGT("BLTouch OD Mód"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_5V = _UxGT("BLTouch 5V mód"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_OD = _UxGT("BLTouch OD mód"); PROGMEM Language_Str MSG_BLTOUCH_MODE_ECHO = _UxGT("Jelentés"); PROGMEM Language_Str MSG_BLTOUCH_MODE_CHANGE = _UxGT("VESZÉLY: A rossz beállítások kárt okozhatnak! Biztos továbblép?"); PROGMEM Language_Str MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); PROGMEM Language_Str MSG_TOUCHMI_INIT = _UxGT("Kezd TouchMI"); - PROGMEM Language_Str MSG_TOUCHMI_ZTEST = _UxGT("Z Offset Teszt"); + PROGMEM Language_Str MSG_TOUCHMI_ZTEST = _UxGT("Z eltolás teszt"); PROGMEM Language_Str MSG_TOUCHMI_SAVE = _UxGT("Mentés"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("TouchMI Használ"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("Z-Probe Használ"); - PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("Z-Probe Elhelyezés"); - PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Elsö %s%s%s Kell"); - PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("Szonda Eltolások"); - PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("Szonda X Eltolás"); - PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Szonda Y Eltolás"); - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Szonda Z Eltolás"); + PROGMEM Language_Str MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("TouchMI használ"); + PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("Z-Szonda telepítés"); + PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("Z-Szonda elhelyezés"); + PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Elsö %s%s%s kell"); + PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("Szonda eltolások"); + PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("X szonda eltolás"); + PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Y szonda eltolás"); + PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Z szonda eltolás"); + PROGMEM Language_Str MSG_MOVE_NOZZLE_TO_BED = _UxGT("Fej az ágyhoz"); PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Mikrolépés X"); PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Mikrolépés Y"); PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Mikrolépés Z"); + PROGMEM Language_Str MSG_BABYSTEP_I = _UxGT("Mikrolépés ") LCD_STR_I; + PROGMEM Language_Str MSG_BABYSTEP_J = _UxGT("Mikrolépés ") LCD_STR_J; + PROGMEM Language_Str MSG_BABYSTEP_K = _UxGT("Mikrolépés ") LCD_STR_K; PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Teljes"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Végállás megszakítva!"); PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Fütés hiba!"); @@ -442,9 +512,11 @@ namespace Language_hu { PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("FÜTÉS KIMARADÁS"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("ÁGY FÜTÉS KIMARADÁS"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("KAMRA FÜTÉS KIMARADÁS"); - PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Hiba: MAX Höfok"); - PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Hiba: MIN Höfok"); - PROGMEM Language_Str MSG_HALTED = _UxGT("A NYOMTATÓ LEFAGYOTT"); + PROGMEM Language_Str MSG_THERMAL_RUNAWAY_COOLER = _UxGT("Hütés kimaradás"); + PROGMEM Language_Str MSG_COOLING_FAILED = _UxGT("Hütés sikertelen"); + PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Hiba: MAX höfok"); + PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Hiba: MIN höfok"); + PROGMEM Language_Str MSG_HALTED = _UxGT("A NYOMTATÓ LEÁLLT"); PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Indítsd újra!"); PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("n"); // Csak egy karakter PROGMEM Language_Str MSG_SHORT_HOUR = _UxGT("ó"); // Csak egy karakter @@ -453,42 +525,47 @@ namespace Language_hu { PROGMEM Language_Str MSG_COOLING = _UxGT("Hütés..."); PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Ágy fütés..."); PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Ágy hütés..."); + PROGMEM Language_Str MSG_PROBE_HEATING = _UxGT("Szonda fütése..."); + PROGMEM Language_Str MSG_PROBE_COOLING = _UxGT("Szonda hütése..."); PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Kamra fütés..."); PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Kamra hütés..."); - PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Delta Kalibráció"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("X Kalibrálás"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Y Kalibrálás"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Z Kalibrálás"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Központ Kalibrálás"); - PROGMEM Language_Str MSG_DELTA_SETTINGS = _UxGT("Delta Beállítások"); - PROGMEM Language_Str MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto Kalibráció"); - PROGMEM Language_Str MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Delta Magasság Kalib."); - PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Z Szonda Eltolás"); - PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Diag Rúd"); + PROGMEM Language_Str MSG_LASER_COOLING = _UxGT("Lézer hütés..."); + PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Delta kalibráció"); + PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("X kalibrálás"); + PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Y kalibrálás"); + PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Z kalibrálás"); + PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Központ kalibrálás"); + PROGMEM Language_Str MSG_DELTA_SETTINGS = _UxGT("Delta beállítások"); + PROGMEM Language_Str MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto kalibráció"); + PROGMEM Language_Str MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Delta magasság kalib."); + PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Z eltolás"); + PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Diag rúd"); PROGMEM Language_Str MSG_DELTA_HEIGHT = _UxGT("Magasság"); PROGMEM Language_Str MSG_DELTA_RADIUS = _UxGT("Sugár"); PROGMEM Language_Str MSG_INFO_MENU = _UxGT("A Nyomtatóról"); - PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("Nyomtató Infó"); - PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("3-Pontos Szintezés"); - PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Lineáris Szintezés"); - PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Bilineáris Szintezés"); - PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Egységes Ágy Szintezés"); - PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Háló Szintezés"); + PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("Nyomtató infó"); + PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("3-Pontos szintezés"); + PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Lineáris szintezés"); + PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Bilineáris szintezés"); + PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Egységes ágy szintezés"); + PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Háló szintezés"); + PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Háló szintezés kész"); PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Statisztikák"); - PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Alaplap Infó"); + PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Alaplap infó"); PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Termisztorok"); PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT("Adagolók"); PROGMEM Language_Str MSG_INFO_BAUDRATE = _UxGT("Átviteli sebesség"); - PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protokoll"); + PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protokol"); PROGMEM Language_Str MSG_INFO_RUNAWAY_OFF = _UxGT("Futáselemzés: KI"); PROGMEM Language_Str MSG_INFO_RUNAWAY_ON = _UxGT("Futáselemzés: BE"); + PROGMEM Language_Str MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Fej üresjárati idök."); PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Munkalámpa"); PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Fényerösség"); PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("HELYTELEN NYOMTATÓ"); #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Nyomtatás Számláló"); + PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Nyomtatás számláló"); PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Befejezett"); PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Összes nyomtatási idö"); PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Leghosszabb munkaidö"); @@ -501,16 +578,19 @@ namespace Language_hu { PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Kiadott"); #endif - PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Min Höfok"); - PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Max Höfok"); + PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Min höfok"); + PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Max höfok"); PROGMEM Language_Str MSG_INFO_PSU = _UxGT("PSU"); - PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Meghajtási Erö"); - PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Meghajtó %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Meghajtó %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z Meghajtó %"); - PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Meghajtó %"); + PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Meghajtási erö"); + PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X meghajtó %"); + PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y meghajtó %"); + PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z meghajtó %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = AXIS4_STR _UxGT(" Meghajtó %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = AXIS5_STR _UxGT(" Meghajtó %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = AXIS6_STR _UxGT(" Meghajtó %"); + PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E meghajtó %"); PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("TMC CSATLAKOZÁSI HIBA"); - PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM Írása"); + PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM írása"); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER = _UxGT("NYOMTATÓSZÁL CSERE"); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("NYOMTATÁS SZÜNETEL"); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("SZÁL BETÖLTÉS"); @@ -518,42 +598,42 @@ namespace Language_hu { PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("FOLYTATÁSI OPCIÓ:"); PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Tisztítsd meg"); PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Folytatás"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Fúvóka: "); - PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Túlfutás Szenzor"); - PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Túlfutás Táv. mm"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Fej: "); + PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Túlfutás szenzor"); + PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Túlfutás táv. mm"); PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Tájolási hiba"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Szondázás hiba"); PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("SZÁLVÁLASZTÁS"); PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); - PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("MMU Szoftver Feltöltése!"); - PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU Figyelmeztetés."); - PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Nyomtatás Folytatása"); + PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("MMU szoftver feltöltése!"); + PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU figyelmeztetés."); + PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Nyomtatás folytatása"); PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("Folytatás..."); - PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("Szál Betöltése"); - PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("Összes Betöltése"); - PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Fúvóka Betöltése"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("Szál Kiadása"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Szál Kiadása ~"); + PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("Szál betöltése"); + PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("Összes betöltése"); + PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Fej betöltése"); + PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("Szál kidobás"); + PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Szál kidobás ~"); PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Kiadja a szálat"); PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("Szál betölt. %i..."); - PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Szál kiadás...."); + PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Szál kidobás. ..."); PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Szál kiadása...."); PROGMEM Language_Str MSG_MMU2_ALL = _UxGT("Mind"); PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("Nyomtatószál ~"); - PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("MMU Újraindítás"); - PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("MMU Újraindul..."); - PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Eltávolít, kattint"); + PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("MMU újraindítás"); + PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("MMU újraindul..."); + PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Kidob, kattint"); PROGMEM Language_Str MSG_MIX = _UxGT("Kever"); PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Összetevö ="); PROGMEM Language_Str MSG_MIXER = _UxGT("Keverö"); PROGMEM Language_Str MSG_GRADIENT = _UxGT("Színátm."); - PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("Teljes Színátm."); - PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Váltás Keverésre"); - PROGMEM Language_Str MSG_CYCLE_MIX = _UxGT("Ciklikus Keverés"); - PROGMEM Language_Str MSG_GRADIENT_MIX = _UxGT("Színátm. Keverés"); - PROGMEM Language_Str MSG_REVERSE_GRADIENT = _UxGT("Fordított Színátm."); + PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("Teljes színátm."); + PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Váltás keverésre"); + PROGMEM Language_Str MSG_CYCLE_MIX = _UxGT("Ciklikus keverés"); + PROGMEM Language_Str MSG_GRADIENT_MIX = _UxGT("Színátm. keverés"); + PROGMEM Language_Str MSG_REVERSE_GRADIENT = _UxGT("Fordított színátm."); PROGMEM Language_Str MSG_ACTIVE_VTOOL = _UxGT("Aktív V-szerszám"); PROGMEM Language_Str MSG_START_VTOOL = _UxGT("Kezdés V-szerszám"); PROGMEM Language_Str MSG_END_VTOOL = _UxGT(" Vége V-szerszám"); @@ -570,6 +650,20 @@ namespace Language_hu { PROGMEM Language_Str MSG_SNAKE = _UxGT("Sn4k3"); PROGMEM Language_Str MSG_MAZE = _UxGT("Maze"); + PROGMEM Language_Str MSG_BAD_PAGE = _UxGT("Rossz oldalindex"); + PROGMEM Language_Str MSG_BAD_PAGE_SPEED = _UxGT("Rossz oldalsebesség"); + + PROGMEM Language_Str MSG_EDIT_PASSWORD = _UxGT("Jelszó szerkesztése"); + PROGMEM Language_Str MSG_LOGIN_REQUIRED = _UxGT("Belépés szükséges"); + PROGMEM Language_Str MSG_PASSWORD_SETTINGS = _UxGT("Jelszóbeállítások"); + PROGMEM Language_Str MSG_ENTER_DIGIT = _UxGT("Írja be a számokat"); + PROGMEM Language_Str MSG_CHANGE_PASSWORD = _UxGT("Jelszó Beáll/Szerk"); + PROGMEM Language_Str MSG_REMOVE_PASSWORD = _UxGT("Jelszó törlése"); + PROGMEM Language_Str MSG_PASSWORD_SET = _UxGT("A jelszó "); + PROGMEM Language_Str MSG_START_OVER = _UxGT("Újrakezdés"); + PROGMEM Language_Str MSG_REMINDER_SAVE_SETTINGS = _UxGT("Mentsd el!"); + PROGMEM Language_Str MSG_PASSWORD_REMOVED = _UxGT("Jelszó törölve"); + // // Filament Change screens show up to 3 lines on a 4-line display // ...or up to 2 lines on a 3-line display @@ -577,48 +671,73 @@ namespace Language_hu { #if LCD_HEIGHT >= 4 PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Nyomj gombot", "nyomtatás folytatáshoz")); PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parkolás...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Várj míg", "szál csere", "indítás")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Várj míg", "szálcsere", "indítás")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Szál behelyezés", "majd nyomj gombot", "a folytatáshoz")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Nyomj gombot", "a fúvóka fűtéséhez")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Fúvóka fűtése", "Kérlek várj...")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Nyomj gombot", "a fej fütéséhez")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Fej fütése", "Kérlek várj...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Várj a", "szál kiadására")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Várj a", "szál betöltésére")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("Várj a", "szál tisztításra")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("Kattints a készre", "szál tiszta")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Várj a nyomtatóra", "majd foltyat...")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Várj a nyomtatóra", "majd folytat...")); #else PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Katt a folytatáshoz")); PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parkolás...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Kérlek Várj...")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Kérlek várj...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Behelyez majd katt")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Katt a fűtéshez")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Fűtés...")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Katt a fütéshez")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Fütés...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Kiadás...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Betöltés...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Tisztítás...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Katt ha kész")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Folytatás...")); #endif - PROGMEM Language_Str MSG_TMC_DRIVERS = _UxGT("TMC Meghajtók"); + PROGMEM Language_Str MSG_TMC_DRIVERS = _UxGT("TMC meghajtók"); PROGMEM Language_Str MSG_TMC_CURRENT = _UxGT("Meghajtó áram"); - PROGMEM Language_Str MSG_TMC_HYBRID_THRS = _UxGT("Hibrid Küszöbérték"); - PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Motoros Kezdöpont"); - PROGMEM Language_Str MSG_TMC_STEPPING_MODE = _UxGT("Léptetö Mód"); - PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop Mód"); + PROGMEM Language_Str MSG_TMC_HYBRID_THRS = _UxGT("Hibrid küszöbérték"); + PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Motoros kezdöpont"); + PROGMEM Language_Str MSG_TMC_STEPPING_MODE = _UxGT("Léptetö mód"); + PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop mód"); PROGMEM Language_Str MSG_SERVICE_RESET = _UxGT("Újraindítás"); PROGMEM Language_Str MSG_SERVICE_IN = _UxGT(" be:"); PROGMEM Language_Str MSG_BACKLASH = _UxGT("Holtjáték"); PROGMEM Language_Str MSG_BACKLASH_A = LCD_STR_A; PROGMEM Language_Str MSG_BACKLASH_B = LCD_STR_B; PROGMEM Language_Str MSG_BACKLASH_C = LCD_STR_C; + PROGMEM Language_Str MSG_BACKLASH_I = LCD_STR_I; + PROGMEM Language_Str MSG_BACKLASH_J = LCD_STR_J; + PROGMEM Language_Str MSG_BACKLASH_K = LCD_STR_K; PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Korrekció"); PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Simítás"); - PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("X Tengely Szint"); + PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("X tengely szint"); PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Önkalibrálás"); - PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Fűtéskimaradás"); - PROGMEM Language_Str MSG_REHEAT = _UxGT("Újrafűt"); - PROGMEM Language_Str MSG_REHEATING = _UxGT("Újrafűtés..."); + #if ENABLED(TOUCH_UI_FTDI_EVE) + PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Tétlenségi idökorlát, a hömérséklet csökkent. Nyomd meg az OK gombot az ismételt felfütéshez, és újra a folytatáshoz."); + #else + PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Fütés idökorlátja"); + #endif + PROGMEM Language_Str MSG_REHEAT = _UxGT("Újrafüt"); + PROGMEM Language_Str MSG_REHEATING = _UxGT("Újrafütés..."); + + PROGMEM Language_Str MSG_PROBE_WIZARD = _UxGT("Z szonda varázsló"); + PROGMEM Language_Str MSG_PROBE_WIZARD_PROBING = _UxGT("Z referencia mérés"); + PROGMEM Language_Str MSG_PROBE_WIZARD_MOVING = _UxGT("Menj a próba pontra"); + + PROGMEM Language_Str MSG_SOUND = _UxGT("Hang"); + + PROGMEM Language_Str MSG_TOP_LEFT = _UxGT("Bal felsö"); + PROGMEM Language_Str MSG_BOTTOM_LEFT = _UxGT("Bal alsó"); + PROGMEM Language_Str MSG_TOP_RIGHT = _UxGT("Jobb felsö"); + PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Jobb alsó"); + PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Kalibrálás befejezve"); + PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Kalibrálási hiba"); + + PROGMEM Language_Str MSG_DRIVER_BACKWARD = _UxGT(" meghajtók hátra"); + + PROGMEM Language_Str MSG_SD_CARD = _UxGT("SD Kártya"); + PROGMEM Language_Str MSG_USB_DISK = _UxGT("USB Lemez"); } #if FAN_COUNT == 1 diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index 38fffcb73b8c..32bc7ff7c708 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -26,6 +26,13 @@ * * 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 that call lcd_put_u8str_ind_P with an index: + * + * = 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) */ #define DISPLAY_CHARSET_ISO10646_1 @@ -34,12 +41,12 @@ namespace Language_it { using namespace Language_en; // Inherit undefined strings from English constexpr uint8_t CHARSIZE = 1; - PROGMEM Language_Str LANGUAGE = _UxGT("Italian"); + PROGMEM Language_Str LANGUAGE = _UxGT("Italiano"); - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" pronto."); + PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" pronta."); PROGMEM Language_Str MSG_MARLIN = _UxGT("Marlin"); - PROGMEM Language_Str MSG_YES = _UxGT("SI"); - PROGMEM Language_Str MSG_NO = _UxGT("NO"); + PROGMEM Language_Str MSG_YES = _UxGT("Si"); + PROGMEM Language_Str MSG_NO = _UxGT("No"); PROGMEM Language_Str MSG_BACK = _UxGT("Indietro"); PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("Annullando..."); PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Media inserito"); @@ -55,24 +62,38 @@ namespace Language_it { PROGMEM Language_Str MSG_MAIN = _UxGT("Menu principale"); PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Impostaz. avanzate"); PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Configurazione"); - PROGMEM Language_Str MSG_AUTOSTART = _UxGT("Autostart"); + PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Autostart"); PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Disabilita Motori"); PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Menu di debug"); PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Test barra avanzam."); PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Auto Home"); - PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Home asse X"); - PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Home asse Y"); - PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Home asse Z"); + PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Home X"); + PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Home Y"); + PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Home Z"); + PROGMEM Language_Str MSG_AUTO_HOME_I = _UxGT("Home ") LCD_STR_I; + PROGMEM Language_Str MSG_AUTO_HOME_J = _UxGT("Home ") LCD_STR_J; + PROGMEM Language_Str MSG_AUTO_HOME_K = _UxGT("Home ") LCD_STR_K; PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Allineam.automat. Z"); - PROGMEM Language_Str MSG_ASSISTED_TRAMMING = _UxGT("Tramming assistito"); + PROGMEM Language_Str MSG_ITERATION = _UxGT("Iterazione G34: %i"); + PROGMEM Language_Str MSG_DECREASING_ACCURACY = _UxGT("Precisione in calo!"); + PROGMEM Language_Str MSG_ACCURACY_ACHIEVED = _UxGT("Precisione raggiunta"); PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Home assi XYZ"); PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Premi per iniziare"); PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Punto successivo"); PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Livel. terminato!"); PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Fade Height"); PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Imp. offset home"); + PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("Offset home X"); + PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Offset home Y"); + PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Offset home Z"); + PROGMEM Language_Str MSG_HOME_OFFSET_I = _UxGT("Offset home ") LCD_STR_I; + PROGMEM Language_Str MSG_HOME_OFFSET_J = _UxGT("Offset home ") LCD_STR_J; + PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Offset home ") LCD_STR_K; PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Offset applicato"); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Imposta Origine"); + PROGMEM Language_Str MSG_TRAMMING_WIZARD = _UxGT("Wizard Tramming"); + PROGMEM Language_Str MSG_SELECT_ORIGIN = _UxGT("Selez. origine"); + PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Ultimo valore "); #if PREHEAT_COUNT PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Preriscalda ") PREHEAT_1_LABEL; PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Preriscalda ") PREHEAT_1_LABEL " ~"; @@ -92,15 +113,21 @@ namespace Language_it { #endif PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Prerisc.personal."); PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Raffredda"); + PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Frequenza"); PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Controllo laser"); - PROGMEM Language_Str MSG_LASER_OFF = _UxGT("Laser Off"); - PROGMEM Language_Str MSG_LASER_ON = _UxGT("Laser On"); - PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Potenza laser"); PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Controllo mandrino"); - PROGMEM Language_Str MSG_SPINDLE_OFF = _UxGT("Mandrino Off"); - PROGMEM Language_Str MSG_SPINDLE_ON = _UxGT("Mandrino On"); + PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Potenza laser"); PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Potenza mandrino"); + PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Alterna Laser"); + PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Alterna soffiatore"); + PROGMEM Language_Str MSG_LASER_ASSIST_TOGGLE = _UxGT("Alterna aria supp."); + PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("ms impulso di test"); + PROGMEM Language_Str MSG_LASER_FIRE_PULSE = _UxGT("Spara impulso"); + PROGMEM Language_Str MSG_FLOWMETER_FAULT = _UxGT("Err.flusso refrig."); + PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Alterna mandrino"); + PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Alterna vuoto"); + PROGMEM Language_Str MSG_SPINDLE_FORWARD = _UxGT("Mandrino in avanti"); PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Inverti mandrino"); PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Accendi aliment."); PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Spegni aliment."); @@ -109,8 +136,12 @@ namespace Language_it { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Muovi Asse"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Livella piano"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Livella piano"); - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Livella spigoli"); - PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Prossimo spigolo"); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Tramming piano"); + PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Regola la vite finche' la sonda non rileva il piano."); + PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("Tolleranza raggiunta su tutti gli angoli. Piano livellato!"); + PROGMEM Language_Str MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Punti buoni: "); + PROGMEM Language_Str MSG_BED_TRAMMING_LAST_Z = _UxGT("Ultimo Z: "); + PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Prossimo punto"); PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Editor Mesh"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Modifica Mesh"); PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Modif. Mesh Fermata"); @@ -118,8 +149,7 @@ namespace Language_it { PROGMEM Language_Str MSG_MESH_X = _UxGT("Indice X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("Indice Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Valore di Z"); - PROGMEM Language_Str MSG_USER_MENU = _UxGT("Comandi personaliz."); - PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Punto inclinaz."); + PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Comandi personaliz."); PROGMEM Language_Str MSG_M48_TEST = _UxGT("Test sonda M48"); PROGMEM Language_Str MSG_M48_POINT = _UxGT("Punto M48"); PROGMEM Language_Str MSG_M48_OUT_OF_BOUNDS = _UxGT("Sonda oltre i limiti"); @@ -130,13 +160,16 @@ namespace Language_it { PROGMEM Language_Str MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplicazione"); PROGMEM Language_Str MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Copia speculare"); PROGMEM Language_Str MSG_IDEX_MODE_FULL_CTRL = _UxGT("Pieno controllo"); + PROGMEM Language_Str MSG_IDEX_DUPE_GAP = _UxGT("X-Gap-X duplicato"); PROGMEM Language_Str MSG_HOTEND_OFFSET_X = _UxGT("2° ugello X"); PROGMEM Language_Str MSG_HOTEND_OFFSET_Y = _UxGT("2° ugello Y"); PROGMEM Language_Str MSG_HOTEND_OFFSET_Z = _UxGT("2° ugello Z"); PROGMEM Language_Str MSG_UBL_DOING_G29 = _UxGT("G29 in corso"); PROGMEM Language_Str MSG_UBL_TOOLS = _UxGT("Strumenti UBL"); - PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Unified Bed Leveling"); + PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Livel.letto unificato"); + PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Punto inclinaz."); PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Mesh Manuale"); + PROGMEM Language_Str MSG_UBL_MESH_WIZARD = _UxGT("Creaz.guid.mesh UBL"); PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Metti spes. e misura"); PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Misura"); PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Rimuovi e mis.piatto"); @@ -237,13 +270,21 @@ namespace Language_it { PROGMEM Language_Str MSG_MOVE_X = _UxGT("Muovi X"); PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Muovi Y"); PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Muovi Z"); + PROGMEM Language_Str MSG_MOVE_I = _UxGT("Muovi ") LCD_STR_I; + PROGMEM Language_Str MSG_MOVE_J = _UxGT("Muovi ") LCD_STR_J; + PROGMEM Language_Str MSG_MOVE_K = _UxGT("Muovi ") LCD_STR_K; PROGMEM Language_Str MSG_MOVE_E = _UxGT("Estrusore"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Estrusore *"); PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Ugello freddo"); - PROGMEM Language_Str MSG_MOVE_Z_DIST = _UxGT("Muovi di %smm"); + PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Muovi di %smm"); PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Muovi di 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Muovi di 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Muovi di 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Muovi di 100mm"); + PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Muovi di 0.001\""); + PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Muovi di 0.01\""); + PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Muovi di 0.1\""); + PROGMEM Language_Str MSG_MOVE_1IN = _UxGT("Muovi di 1\""); PROGMEM Language_Str MSG_SPEED = _UxGT("Velocità"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Piatto Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Ugello"); @@ -252,6 +293,10 @@ namespace Language_it { PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Ugello in pausa"); PROGMEM Language_Str MSG_BED = _UxGT("Piatto"); PROGMEM Language_Str MSG_CHAMBER = _UxGT("Camera"); + PROGMEM Language_Str MSG_COOLER = _UxGT("Raffreddam. laser"); + PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Alterna raffreddam."); + PROGMEM Language_Str MSG_FLOWMETER_SAFETY = _UxGT("Sicurezza flusso"); + PROGMEM Language_Str MSG_LASER = _UxGT("Laser"); PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Vel. ventola"); // Max 15 characters PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Vel. ventola ~"); // Max 15 characters PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Ventola mem. ~"); // Max 15 characters @@ -277,16 +322,6 @@ namespace Language_it { PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Calibrazione fallita. Estrusore errato."); PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Calibrazione fallita. Temperatura troppo alta."); PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("Calibrazione fallita! Tempo scaduto."); - PROGMEM Language_Str MSG_PID_P = _UxGT("PID-P"); - PROGMEM Language_Str MSG_PID_P_E = _UxGT("PID-P *"); - PROGMEM Language_Str MSG_PID_I = _UxGT("PID-I"); - PROGMEM Language_Str MSG_PID_I_E = _UxGT("PID-I *"); - PROGMEM Language_Str MSG_PID_D = _UxGT("PID-D"); - PROGMEM Language_Str MSG_PID_D_E = _UxGT("PID-D *"); - PROGMEM Language_Str MSG_PID_C = _UxGT("PID-C"); - PROGMEM Language_Str MSG_PID_C_E = _UxGT("PID-C *"); - PROGMEM Language_Str MSG_PID_F = _UxGT("PID-F"); - PROGMEM Language_Str MSG_PID_F_E = _UxGT("PID-F *"); PROGMEM Language_Str MSG_SELECT = _UxGT("Seleziona"); PROGMEM Language_Str MSG_SELECT_E = _UxGT("Seleziona *"); PROGMEM Language_Str MSG_ACC = _UxGT("Accel"); @@ -294,12 +329,18 @@ namespace Language_it { PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-jerk"); PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-jerk"); PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-jerk"); + PROGMEM Language_Str MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-jerk"); + PROGMEM Language_Str MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-jerk"); + PROGMEM Language_Str MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-jerk"); PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-jerk"); PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Deviaz. giunzioni"); PROGMEM Language_Str MSG_VELOCITY = _UxGT("Velocità"); PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; + PROGMEM Language_Str MSG_VMAX_I = _UxGT("Vmax ") LCD_STR_I; + PROGMEM Language_Str MSG_VMAX_J = _UxGT("Vmax ") LCD_STR_J; + PROGMEM Language_Str MSG_VMAX_K = _UxGT("Vmax ") LCD_STR_K; PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vmax *"); PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin"); @@ -308,6 +349,9 @@ namespace Language_it { PROGMEM Language_Str MSG_AMAX_A = _UxGT("Amax ") LCD_STR_A; PROGMEM Language_Str MSG_AMAX_B = _UxGT("Amax ") LCD_STR_B; PROGMEM Language_Str MSG_AMAX_C = _UxGT("Amax ") LCD_STR_C; + PROGMEM Language_Str MSG_AMAX_I = _UxGT("Amax ") LCD_STR_I; + PROGMEM Language_Str MSG_AMAX_J = _UxGT("Amax ") LCD_STR_J; + PROGMEM Language_Str MSG_AMAX_K = _UxGT("Amax ") LCD_STR_K; PROGMEM Language_Str MSG_AMAX_E = _UxGT("Amax ") LCD_STR_E; PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Amax *"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-Ritrazione"); @@ -315,16 +359,19 @@ namespace Language_it { PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("Frequenza max"); PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Feed min"); PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Passi/mm"); - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT("passi/mm"); - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT("passi/mm"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT("passi/mm"); - PROGMEM Language_Str MSG_E_STEPS = _UxGT("Epassi/mm"); - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("*passi/mm"); + PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" passi/mm"); + PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" passi/mm"); + PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" passi/mm"); + PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" passi/mm"); + PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" passi/mm"); + PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" passi/mm"); + PROGMEM Language_Str MSG_E_STEPS = _UxGT("E passi/mm"); + PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* passi/mm"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatura"); PROGMEM Language_Str MSG_MOTION = _UxGT("Movimento"); PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filamento"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm³"); - PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("Limite E in mm³"); + PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm") SUPERSCRIPT_THREE; + PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("Limite E in mm") SUPERSCRIPT_THREE; PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT_E = _UxGT("Limite E *"); PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Diam. filo"); PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Diam. filo *"); @@ -362,11 +409,13 @@ namespace Language_it { PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Fatto"); PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Indietro"); PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Procedi"); + PROGMEM Language_Str MSG_BUTTON_SKIP = _UxGT("Salta"); PROGMEM Language_Str MSG_PAUSING = _UxGT("Messa in pausa..."); PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Pausa stampa"); PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Riprendi stampa"); PROGMEM Language_Str MSG_HOST_START_PRINT = _UxGT("Host Avvio"); PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Arresta stampa"); + PROGMEM Language_Str MSG_END_LOOPS = _UxGT("Fine cicli di rip."); PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("Stampa Oggetto"); PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("Cancella Oggetto"); PROGMEM Language_Str MSG_CANCEL_OBJECT_N = _UxGT("Canc. Oggetto ="); @@ -431,7 +480,7 @@ namespace Language_it { PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Metti BLTouch a 5V"); PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Metti BLTouch a OD"); PROGMEM Language_Str MSG_BLTOUCH_MODE_ECHO = _UxGT("Segnala modo"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_CHANGE = _UxGT("PERICOLO: Impostazioni errate possono cause danni! Procedo comunque?"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_CHANGE = _UxGT("PERICOLO: impostazioni errate possono cause danni! Procedo comunque?"); PROGMEM Language_Str MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); PROGMEM Language_Str MSG_TOUCHMI_INIT = _UxGT("Inizializ.TouchMI"); PROGMEM Language_Str MSG_TOUCHMI_ZTEST = _UxGT("Test Z offset"); @@ -449,6 +498,9 @@ namespace Language_it { PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Babystep X"); PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Babystep Y"); PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Babystep Z"); + PROGMEM Language_Str MSG_BABYSTEP_I = _UxGT("Babystep ") LCD_STR_I; + PROGMEM Language_Str MSG_BABYSTEP_J = _UxGT("Babystep ") LCD_STR_J; + PROGMEM Language_Str MSG_BABYSTEP_K = _UxGT("Babystep ") LCD_STR_K; PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Totali"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Finecorsa annullati"); PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Risc.Fallito"); // Max 12 caratteri @@ -456,6 +508,8 @@ namespace Language_it { PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("TEMP FUORI CONTROLLO"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("TEMP PIAT.FUORI CTRL"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("T.CAMERA FUORI CTRL"); + PROGMEM Language_Str MSG_THERMAL_RUNAWAY_COOLER = _UxGT("RAFFREDAM.FUORI CTRL"); + PROGMEM Language_Str MSG_COOLING_FAILED = _UxGT("Raffreddam. fallito"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Err: TEMP MASSIMA"); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Err: TEMP MINIMA"); PROGMEM Language_Str MSG_HALTED = _UxGT("STAMPANTE FERMATA"); @@ -471,6 +525,7 @@ namespace Language_it { PROGMEM Language_Str MSG_PROBE_COOLING = _UxGT("Raffr. sonda..."); PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Risc. camera..."); PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Raffr. camera..."); + PROGMEM Language_Str MSG_LASER_COOLING = _UxGT("Raffr. laser..."); PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Calibraz. Delta"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Calibra X"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Calibra Y"); @@ -490,6 +545,7 @@ namespace Language_it { PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Livel. Bilineare"); PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Livel.piatto unific."); PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Livel. Mesh"); + PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Sond.mesh eseguito"); PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Statistiche"); PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Info. scheda"); PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Termistori"); @@ -521,10 +577,13 @@ namespace Language_it { PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Temp max"); PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Alimentatore"); PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Potenza Drive"); - PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("Driver X %"); + PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Driver Y %"); + PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Driver Z %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = _UxGT("Driver ") AXIS4_STR _UxGT(" %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = _UxGT("Driver ") AXIS5_STR _UxGT(" %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = _UxGT("Driver ") AXIS6_STR _UxGT(" %"); + PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("Driver E %"); PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("ERR.CONNESSIONE TMC"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Scrivi DAC EEPROM"); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER = _UxGT("CAMBIO FILAMENTO"); @@ -544,14 +603,14 @@ namespace Language_it { PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("Agg.firmware MMU!"); PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU chiede attenz."); - PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Riprendi stampa"); - PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("Ripresa..."); - PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("Carica filamento"); - PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("Carica tutto"); + PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("MMU riprendi"); + PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("MMU ripresa..."); + PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("MMU carica"); + PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("MMU carica tutto"); PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Carica fino ugello"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("Espelli filamento"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Espelli filam.~"); - PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Scarica filamento"); + PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("MMU espelli"); + PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("MMU espelli ~"); + PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("MMU scarica"); PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("Caric.fil. %i..."); PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Esplus.filam. ..."); PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Scaric.filam. ..."); @@ -628,12 +687,12 @@ namespace Language_it { PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Ripresa...")); #endif // LCD_HEIGHT < 4 - PROGMEM Language_Str MSG_TMC_DRIVERS = _UxGT("Drivers TMC"); - PROGMEM Language_Str MSG_TMC_CURRENT = _UxGT("Driver in uso"); + PROGMEM Language_Str MSG_TMC_DRIVERS = _UxGT("Driver TMC"); + PROGMEM Language_Str MSG_TMC_CURRENT = _UxGT("Correnti driver"); PROGMEM Language_Str MSG_TMC_HYBRID_THRS = _UxGT("Soglia modo ibrido"); - PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Azzer. senza sens."); - PROGMEM Language_Str MSG_TMC_STEPPING_MODE = _UxGT("Modo stepping"); - PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop abil."); + PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Sensorless homing"); + PROGMEM Language_Str MSG_TMC_STEPPING_MODE = _UxGT("Stealthchop"); + PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("Stealthchop"); PROGMEM Language_Str MSG_SERVICE_RESET = _UxGT("Resetta"); PROGMEM Language_Str MSG_SERVICE_IN = _UxGT(" tra:"); @@ -651,5 +710,21 @@ namespace Language_it { PROGMEM Language_Str MSG_REHEAT = _UxGT("Riscalda"); PROGMEM Language_Str MSG_REHEATING = _UxGT("Riscaldando..."); - PROGMEM Language_Str MSG_PROBE_WIZARD = _UxGT("Proc.guid.sonda Z"); + PROGMEM Language_Str MSG_PROBE_WIZARD = _UxGT("Wizard Z offset"); + PROGMEM Language_Str MSG_PROBE_WIZARD_PROBING = _UxGT("Altezza di riferimento sonda"); + PROGMEM Language_Str MSG_PROBE_WIZARD_MOVING = _UxGT("Spostati in posizione di rilevazione"); + + PROGMEM Language_Str MSG_SOUND = _UxGT("Suoni"); + + PROGMEM Language_Str MSG_TOP_LEFT = _UxGT("Alto sinistra"); + PROGMEM Language_Str MSG_BOTTOM_LEFT = _UxGT("Basso sinistra"); + PROGMEM Language_Str MSG_TOP_RIGHT = _UxGT("Alto destra"); + PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Basso destra"); + PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Calibrazione completata"); + PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Calibrazione fallita"); + + PROGMEM Language_Str MSG_DRIVER_BACKWARD = _UxGT(" driver invertito"); + + PROGMEM Language_Str MSG_SD_CARD = _UxGT("Scheda SD"); + PROGMEM Language_Str MSG_USB_DISK = _UxGT("Disco USB"); } diff --git a/Marlin/src/lcd/language/language_jp_kana.h b/Marlin/src/lcd/language/language_jp_kana.h index 32b12f50cb8b..61740e3b40eb 100644 --- a/Marlin/src/lcd/language/language_jp_kana.h +++ b/Marlin/src/lcd/language/language_jp_kana.h @@ -47,7 +47,7 @@ namespace Language_jp_kana { PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("メディアノトリダシ"); PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("エンドストップ"); // "Endstops" // Max length 8 characters PROGMEM Language_Str MSG_MAIN = _UxGT("メイン"); // "Main" - PROGMEM Language_Str MSG_AUTOSTART = _UxGT("ジドウカイシ"); // "Autostart" + PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("ジドウカイシ"); // "Autostart" PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("モーターデンゲン オフ"); // "Disable steppers" PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("デバッグメニュー"); // "Debug Menu" PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("プログレスバー テスト"); // "Progress Bar Test" @@ -94,10 +94,11 @@ namespace Language_jp_kana { PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Yジク イドウ"); // "Move Y" PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Zジク イドウ"); // "Move Z" PROGMEM Language_Str MSG_MOVE_E = _UxGT("エクストルーダー"); // "Extruder" - PROGMEM Language_Str MSG_MOVE_Z_DIST = _UxGT("%smm イドウ"); // "Move 0.025mm" + PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("%smm イドウ"); // "Move 0.025mm" PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("0.1mm イドウ"); // "Move 0.1mm" PROGMEM Language_Str MSG_MOVE_1MM = _UxGT(" 1mm イドウ"); // "Move 1mm" PROGMEM Language_Str MSG_MOVE_10MM = _UxGT(" 10mm イドウ"); // "Move 10mm" + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT(" 100mm イドウ"); // "Move 100mm" PROGMEM Language_Str MSG_SPEED = _UxGT("ソクド"); // "Speed" PROGMEM Language_Str MSG_BED_Z = _UxGT("Zオフセット"); // "Bed Z" PROGMEM Language_Str MSG_NOZZLE = _UxGT("ノズル"); // "Nozzle" @@ -113,7 +114,7 @@ namespace Language_jp_kana { PROGMEM Language_Str MSG_LCD_OFF = _UxGT("オフ"); // "Off" PROGMEM Language_Str MSG_SELECT = _UxGT("センタク"); // "Select" PROGMEM Language_Str MSG_SELECT_E = _UxGT("センタク *"); - PROGMEM Language_Str MSG_ACC = _UxGT("カソクド mm/s²"); // "Accel" + PROGMEM Language_Str MSG_ACC = _UxGT("カソクド mm/s") SUPERSCRIPT_TWO; // "Accel" PROGMEM Language_Str MSG_JERK = _UxGT("ヤクドウ mm/s"); // "Jerk" PROGMEM Language_Str MSG_VA_JERK = _UxGT("ジク ヤクドウ mm/s") LCD_STR_A; // "Va-jerk" PROGMEM Language_Str MSG_VB_JERK = _UxGT("ジク ヤクドウ mm/s") LCD_STR_B; // "Vb-jerk" @@ -129,14 +130,14 @@ namespace Language_jp_kana { PROGMEM Language_Str MSG_VMAX_EN = _UxGT("サイダイオクリソクド *"); // "Vmax E1" PROGMEM Language_Str MSG_VMIN = _UxGT("サイショウオクリソクド"); // "Vmin" PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("サイショウイドウソクド"); // "VTrav min" - PROGMEM Language_Str MSG_ACCELERATION = _UxGT("カソクド mm/s²"); // "Accel" + PROGMEM Language_Str MSG_ACCELERATION = _UxGT("カソクド mm/s") SUPERSCRIPT_TWO; // "Accel" PROGMEM Language_Str MSG_AMAX = _UxGT("サイダイカソクド "); // "Amax " PROGMEM Language_Str MSG_A_RETRACT = _UxGT("ヒキコミカソクド"); // "A-retract" PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("イドウカソクド"); // "A-travel" PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("オンド"); // "Temperature" PROGMEM Language_Str MSG_MOTION = _UxGT("ウゴキセッテイ"); // "Motion" PROGMEM Language_Str MSG_FILAMENT = _UxGT("フィラメント"); // "Filament" - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm³"); + PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm") SUPERSCRIPT_THREE; PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("フィラメントチョッケイ"); // "Fil. Dia." PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("フィラメントチョッケイ *"); PROGMEM Language_Str MSG_CONTRAST = _UxGT("LCDコントラスト"); // "LCD contrast" @@ -246,7 +247,7 @@ namespace Language_jp_kana { PROGMEM Language_Str MSG_BACK = _UxGT("モドリ"); PROGMEM Language_Str MSG_VELOCITY = _UxGT("ソクド"); PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("ステップ/mm"); - PROGMEM Language_Str MSG_USER_MENU = _UxGT("ユーザーコマンド"); + PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("ユーザーコマンド"); PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("プリントガイチジテイシサレマシタ"); PROGMEM Language_Str MSG_PRINTING = _UxGT("プリントチュウ..."); } diff --git a/Marlin/src/lcd/language/language_ko_KR.h b/Marlin/src/lcd/language/language_ko_KR.h index 1ab03dcf57df..20700896c1c1 100644 --- a/Marlin/src/lcd/language/language_ko_KR.h +++ b/Marlin/src/lcd/language/language_ko_KR.h @@ -42,7 +42,7 @@ namespace Language_ko_KR { PROGMEM Language_Str MSG_MAIN = _UxGT("뒤로"); PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("고급 설정"); PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("설정"); - PROGMEM Language_Str MSG_AUTOSTART = _UxGT("자동 시작"); + PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("자동 시작"); PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("모터 정지"); PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("디버깅 메뉴"); PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("프로그레스바 테스트"); diff --git a/Marlin/src/lcd/language/language_nl.h b/Marlin/src/lcd/language/language_nl.h index c142c5c9bfd6..1eef4ca42472 100644 --- a/Marlin/src/lcd/language/language_nl.h +++ b/Marlin/src/lcd/language/language_nl.h @@ -43,7 +43,7 @@ namespace Language_nl { PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Kaart verwijderd"); PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Endstops"); // Max length 8 characters PROGMEM Language_Str MSG_MAIN = _UxGT("Hoofdmenu"); - PROGMEM Language_Str MSG_AUTOSTART = _UxGT("Autostart"); + PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Autostart"); PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Motoren uit"); PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Debug Menu"); // accepted English terms PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Vooruitgang Test"); @@ -87,10 +87,11 @@ namespace Language_nl { PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Verplaats Z"); PROGMEM Language_Str MSG_MOVE_E = _UxGT("Extruder"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Extruder *"); - PROGMEM Language_Str MSG_MOVE_Z_DIST = _UxGT("Verplaats %smm"); + PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Verplaats %smm"); PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Verplaats 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Verplaats 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Verplaats 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Verplaats 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Snelheid"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Bed Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Nozzle"); @@ -115,7 +116,7 @@ namespace Language_nl { PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filament"); PROGMEM Language_Str MSG_ADVANCE_K = _UxGT("Advance K"); // accepted english dutch PROGMEM Language_Str MSG_ADVANCE_K_E = _UxGT("Advance K *"); // accepted english dutch - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm³"); + PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm") SUPERSCRIPT_THREE; PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Fil. Dia."); PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Fil. Dia. *"); PROGMEM Language_Str MSG_CONTRAST = _UxGT("LCD contrast"); diff --git a/Marlin/src/lcd/language/language_pl.h b/Marlin/src/lcd/language/language_pl.h index 770c872a4099..e467178f6a98 100644 --- a/Marlin/src/lcd/language/language_pl.h +++ b/Marlin/src/lcd/language/language_pl.h @@ -26,6 +26,13 @@ * * 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 that call lcd_put_u8str_ind_P with an index: + * + * = 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) */ #define DISPLAY_CHARSET_ISO10646_PL @@ -34,9 +41,10 @@ namespace Language_pl { using namespace Language_en; // Inherit undefined strings from English constexpr uint8_t CHARSIZE = 2; - PROGMEM Language_Str LANGUAGE = _UxGT("Polish"); + PROGMEM Language_Str LANGUAGE = _UxGT("Polski"); PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" gotowy."); + //PROGMEM Language_Str MSG_MARLIN = _UxGT("Marlin"); PROGMEM Language_Str MSG_YES = _UxGT("TAK"); PROGMEM Language_Str MSG_NO = _UxGT("NIE"); PROGMEM Language_Str MSG_BACK = _UxGT("Wstecz"); @@ -44,15 +52,17 @@ namespace Language_pl { PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Karta włożona"); PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Karta usunięta"); PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Oczekiwanie na kartę"); + PROGMEM Language_Str MSG_SD_INIT_FAIL = _UxGT("Błąd inicializacji karty"); PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Bład odczytu karty"); PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("Urządzenie USB usunięte"); PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("Błąd uruchomienia USB"); + //PROGMEM Language_Str MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Subcall Overflow"); PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Krańców."); // Max length 8 characters PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("Progr. Krańcówki"); PROGMEM Language_Str MSG_MAIN = _UxGT("Menu główne"); PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Ustawienie zaawansowane"); PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Konfiguracja"); - PROGMEM Language_Str MSG_AUTOSTART = _UxGT("Autostart"); + PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Autostart"); PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Wyłącz silniki"); PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Menu Debugowania"); PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Testowy pasek postępu"); @@ -61,14 +71,23 @@ namespace Language_pl { PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Zeruj Y"); PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Zeruj Z"); PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Autowyrównanie Z"); + //PROGMEM Language_Str MSG_ITERATION = _UxGT("G34 Iteration: %i"); + PROGMEM Language_Str MSG_DECREASING_ACCURACY = _UxGT("Spadek dokładności!"); + PROGMEM Language_Str MSG_ACCURACY_ACHIEVED = _UxGT("Osiągnięto dokładność"); PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Pozycja zerowa"); PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Kliknij by rozp."); PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Następny punkt"); PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Wypoziomowano!"); PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Wys. zanikania"); PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Ust. poz. zer."); + //PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("Home Offset X"); + //PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Home Offset Y"); + //PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Home Offset Z"); PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Poz. zerowa ust."); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Ustaw punkt zero"); + //PROGMEM Language_Str MSG_TRAMMING_WIZARD = _UxGT("Tramming Wizard"); + PROGMEM Language_Str MSG_SELECT_ORIGIN = _UxGT("Wybierz punkt zero"); + PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Poprzednia wartość "); #if PREHEAT_COUNT PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Rozgrzej ") PREHEAT_1_LABEL; PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Rozgrzej ") PREHEAT_1_LABEL " ~"; @@ -88,14 +107,21 @@ namespace Language_pl { #endif PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Rozgrzej własne ust."); PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Chłodzenie"); + + PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Częstotliwość"); PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Sterowanie Lasera"); - PROGMEM Language_Str MSG_LASER_OFF = _UxGT("Wyłącz Laser"); - PROGMEM Language_Str MSG_LASER_ON = _UxGT("Włącz Laser"); - PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Zasilanie Lasera"); PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Sterowanie wrzeciona"); - PROGMEM Language_Str MSG_SPINDLE_OFF = _UxGT("Wyłącz wrzeciono"); - PROGMEM Language_Str MSG_SPINDLE_ON = _UxGT("Włącz wrzeciono"); + PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Zasilanie Lasera"); PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Zasilanie wrzeciona"); + //PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Toggle Laser"); + //PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Toggle Blower"); + //PROGMEM Language_Str MSG_LASER_ASSIST_TOGGLE = _UxGT("Air Assist"); + //PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Test Pulse ms"); + //PROGMEM Language_Str MSG_LASER_FIRE_PULSE = _UxGT("Fire Pulse"); + //PROGMEM Language_Str MSG_FLOWMETER_FAULT = _UxGT("Coolant Flow Fault"); + //PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Toggle Spindle"); + //PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Toggle Vacuum"); + //PROGMEM Language_Str MSG_SPINDLE_FORWARD = _UxGT("Spindle Forward"); PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Rewers wrzeciona"); PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Włącz zasilacz"); PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Wyłącz zasilacz"); @@ -104,7 +130,11 @@ namespace Language_pl { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Ruch osi"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Poziomowanie stołu"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Wypoziomuj stół"); - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Narożniki poziomowania"); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Narożniki poziomowania"); + //PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Raise Bed Until Probe Triggered"); + //PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("All Corners Within Tolerance. Level Bed"); + //PROGMEM Language_Str MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Good Points: "); + //PROGMEM Language_Str MSG_BED_TRAMMING_LAST_Z = _UxGT("Last Z: "); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Nastepny narożnik"); PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Edytor siatki"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Edycja siatki"); @@ -113,9 +143,10 @@ namespace Language_pl { PROGMEM Language_Str MSG_MESH_X = _UxGT("Indeks X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("Indeks Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Wartość Z"); - PROGMEM Language_Str MSG_USER_MENU = _UxGT("Własne Polecenia"); + PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Własne Polecenia"); PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 Test sondy"); PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 Punky"); + //PROGMEM Language_Str MSG_M48_OUT_OF_BOUNDS = _UxGT("Probe out of bounds"); PROGMEM Language_Str MSG_M48_DEVIATION = _UxGT("Odchylenie"); PROGMEM Language_Str MSG_IDEX_MENU = _UxGT("Tryb IDEX"); PROGMEM Language_Str MSG_OFFSETS_MENU = _UxGT("Przesunięcie narzędzia"); @@ -123,14 +154,16 @@ namespace Language_pl { PROGMEM Language_Str MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplikowanie"); PROGMEM Language_Str MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Kopia lustrzana"); PROGMEM Language_Str MSG_IDEX_MODE_FULL_CTRL = _UxGT("Pełne sterowanie"); + //PROGMEM Language_Str MSG_IDEX_DUPE_GAP = _UxGT("Duplicate X-Gap"); PROGMEM Language_Str MSG_HOTEND_OFFSET_X = _UxGT("2ga dysza X"); PROGMEM Language_Str MSG_HOTEND_OFFSET_Y = _UxGT("2ga dysza Y"); PROGMEM Language_Str MSG_HOTEND_OFFSET_Z = _UxGT("2ga dysza Z"); PROGMEM Language_Str MSG_UBL_DOING_G29 = _UxGT("Wykonywanie G29"); PROGMEM Language_Str MSG_UBL_TOOLS = _UxGT("Narzędzia UBL"); - PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Unified Bed Leveling"); + //PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Unified Bed Leveling"); PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Punkt pochylenia"); PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Ręczne Budowanie Siatki"); + //PROGMEM Language_Str MSG_UBL_MESH_WIZARD = _UxGT("UBL Mesh Wizard"); PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Umieść podkładkę i zmierz"); PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Zmierz"); PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Usuń & Zmierz Stół"); @@ -147,14 +180,12 @@ namespace Language_pl { PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Koniec edycji siati"); PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Buduj własna siatkę"); PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("Buduj siatkę"); - #if PREHEAT_COUNT - PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Buduj siatkę ($)"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Sprawdzenie siatki ($)"); - #endif + PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Buduj siatkę ($)"); PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Buduj siatkę na zimno"); PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Dostrojenie wysokości siatki"); PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Wartość wysokości"); PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Sprawdzenie siatki"); + PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Sprawdzenie siatki ($)"); PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Sprawdzenie własnej siatki"); PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26 Nagrzewanie stołu"); PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("G26 Nagrzewanie dyszy"); @@ -215,6 +246,10 @@ namespace Language_pl { PROGMEM Language_Str MSG_SET_LEDS_VIOLET = _UxGT("Fioletowy"); PROGMEM Language_Str MSG_SET_LEDS_WHITE = _UxGT("Biały"); PROGMEM Language_Str MSG_SET_LEDS_DEFAULT = _UxGT("Domyślny"); + PROGMEM Language_Str MSG_LED_CHANNEL_N = _UxGT("Kanał ="); + //PROGMEM Language_Str MSG_LEDS2 = _UxGT("Lights #2"); + //PROGMEM Language_Str MSG_NEO2_PRESETS = _UxGT("Light #2 Presets"); + PROGMEM Language_Str MSG_NEO2_BRIGHTNESS = _UxGT("Jasność"); PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Własne światła"); PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Czerwony"); PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Zielony"); @@ -230,31 +265,61 @@ namespace Language_pl { PROGMEM Language_Str MSG_MOVE_E = _UxGT("Ekstruzja (os E)"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Ekstruzja (os E) *"); PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Dysza za zimna"); - PROGMEM Language_Str MSG_MOVE_Z_DIST = _UxGT("Przesuń co %smm"); - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Przesuń co .1mm"); - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Przesuń co 1mm"); - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Przesuń co 10mm"); + PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Przesuń co %s mm"); + PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Przesuń co .1 mm"); + PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Przesuń co 1 mm"); + PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Przesuń co 10 mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Przesuń co 100 mm"); + PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Przesuń co 0.001 cala"); + PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Przesuń co 0.01 cala"); + PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Przesuń co 0.1 cala"); PROGMEM Language_Str MSG_SPEED = _UxGT("Predkość"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Stół Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Dysza"); PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Dysza ~"); + //PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Nozzle Parked"); + PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Dysza w oczekiwaniu"); PROGMEM Language_Str MSG_BED = _UxGT("Stół"); PROGMEM Language_Str MSG_CHAMBER = _UxGT("Obudowa"); - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Obroty wiatraka"); - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Obroty wiatraka ~"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Obroty dodatkowego wiatraka"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Obroty dodatkowego wiatraka ~"); + //PROGMEM Language_Str MSG_COOLER = _UxGT("Laser Coolant"); + //PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Toggle Cooler"); + //PROGMEM Language_Str MSG_FLOWMETER_SAFETY = _UxGT("Flow Safety"); + //PROGMEM Language_Str MSG_LASER = _UxGT("Laser"); + PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Obroty wentylatora"); + PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Obroty wentylatora ~"); + //PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Stored Fan ~"); + PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Obroty dodatkowego wentylatora"); + PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Obroty dodatkowego wentylatora ~"); + PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Wentylator kontrolera"); + //PROGMEM Language_Str MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Idle Speed"); + //PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Auto Mode"); + //PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("Active Speed"); + //PROGMEM Language_Str MSG_CONTROLLER_FAN_DURATION = _UxGT("Idle Period"); PROGMEM Language_Str MSG_FLOW = _UxGT("Przepływ"); PROGMEM Language_Str MSG_FLOW_N = _UxGT("Przepływ ~"); PROGMEM Language_Str MSG_CONTROL = _UxGT("Ustawienia"); - PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); - PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); + //PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); + //PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Mnożnik"); PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Auto. temperatura"); PROGMEM Language_Str MSG_LCD_ON = _UxGT("Wł."); PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Wył."); PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("PID Autostrojenie"); PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("PID Autostrojenie *"); + PROGMEM Language_Str MSG_PID_AUTOTUNE_DONE = _UxGT("Strojenie PID zakończone"); + //PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Autotune failed. Bad extruder."); + //PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Autotune failed. Temperature too high."); + //PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("Autotune failed! Timeout."); + //PROGMEM Language_Str MSG_PID_P = _UxGT("PID-P"); + //PROGMEM Language_Str MSG_PID_P_E = _UxGT("PID-P *"); + //PROGMEM Language_Str MSG_PID_I = _UxGT("PID-I"); + //PROGMEM Language_Str MSG_PID_I_E = _UxGT("PID-I *"); + //PROGMEM Language_Str MSG_PID_D = _UxGT("PID-D"); + //PROGMEM Language_Str MSG_PID_D_E = _UxGT("PID-D *"); + //PROGMEM Language_Str MSG_PID_C = _UxGT("PID-C"); + //PROGMEM Language_Str MSG_PID_C_E = _UxGT("PID-C *"); + //PROGMEM Language_Str MSG_PID_F = _UxGT("PID-F"); + //PROGMEM Language_Str MSG_PID_F_E = _UxGT("PID-F *"); PROGMEM Language_Str MSG_SELECT = _UxGT("Wybierz"); PROGMEM Language_Str MSG_SELECT_E = _UxGT("Wybierz *"); PROGMEM Language_Str MSG_ACC = _UxGT("Przyspieszenie"); @@ -263,61 +328,83 @@ namespace Language_pl { PROGMEM Language_Str MSG_VB_JERK = _UxGT("Zryw V") LCD_STR_B; PROGMEM Language_Str MSG_VC_JERK = _UxGT("Zryw V") LCD_STR_C; PROGMEM Language_Str MSG_VE_JERK = _UxGT("Zryw Ve"); - PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev"); + //PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev"); PROGMEM Language_Str MSG_VELOCITY = _UxGT("Prędkość (V)"); - PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; - PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; - PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; - PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; - PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vmax *"); - PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin"); + //PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; + //PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; + //PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; + //PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; + //PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vmax *"); + //PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin"); PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Vskok min"); PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Przyspieszenie (A)"); - PROGMEM Language_Str MSG_AMAX_A = _UxGT("Amax ") LCD_STR_A; - PROGMEM Language_Str MSG_AMAX_B = _UxGT("Amax ") LCD_STR_B; - PROGMEM Language_Str MSG_AMAX_C = _UxGT("Amax ") LCD_STR_C; - PROGMEM Language_Str MSG_AMAX_E = _UxGT("Amax ") LCD_STR_E; - PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Amax *"); + //PROGMEM Language_Str MSG_AMAX_A = _UxGT("Amax ") LCD_STR_A; + //PROGMEM Language_Str MSG_AMAX_B = _UxGT("Amax ") LCD_STR_B; + //PROGMEM Language_Str MSG_AMAX_C = _UxGT("Amax ") LCD_STR_C; + //PROGMEM Language_Str MSG_AMAX_E = _UxGT("Amax ") LCD_STR_E; + //PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Amax *"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-wycofanie"); PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("A-przesuń."); + PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("Częstotliwość max"); + //PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Feed min"); PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("kroki/mm"); - PROGMEM Language_Str MSG_A_STEPS = _UxGT("kroki") LCD_STR_A _UxGT("/mm"); - PROGMEM Language_Str MSG_B_STEPS = _UxGT("kroki") LCD_STR_B _UxGT("/mm"); - PROGMEM Language_Str MSG_C_STEPS = _UxGT("kroki") LCD_STR_C _UxGT("/mm"); - PROGMEM Language_Str MSG_E_STEPS = _UxGT("krokiE/mm"); - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("kroki */mm"); + PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" kroki/mm"); + PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" kroki/mm"); + PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" kroki/mm"); + PROGMEM Language_Str MSG_E_STEPS = _UxGT("E kroki/mm"); + PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* kroki/mm"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatura"); PROGMEM Language_Str MSG_MOTION = _UxGT("Ruch"); - PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filament"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E w mm³"); + //PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filament"); + PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E w mm") SUPERSCRIPT_THREE; + //PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("E Limit in mm") SUPERSCRIPT_THREE; + //PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT_E = _UxGT("E Limit *"); PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Śr. fil."); PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Śr. fil. *"); PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Wysuń mm"); PROGMEM Language_Str MSG_FILAMENT_LOAD = _UxGT("Wsuń mm"); - PROGMEM Language_Str MSG_ADVANCE_K = _UxGT("Advance K"); - PROGMEM Language_Str MSG_ADVANCE_K_E = _UxGT("Advance K *"); + //PROGMEM Language_Str MSG_ADVANCE_K = _UxGT("Advance K"); + //PROGMEM Language_Str MSG_ADVANCE_K_E = _UxGT("Advance K *"); PROGMEM Language_Str MSG_CONTRAST = _UxGT("Kontrast LCD"); PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Zapisz w pamięci"); PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Wczytaj z pamięci"); PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Ustaw. fabryczne"); PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Initializuj EEPROM"); + //PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("EEPROM CRC Error"); + //PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("EEPROM Index Error"); + //PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("EEPROM Version Error"); + //PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Settings Stored"); PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Uaktualnij kartę"); PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Resetuj drukarkę"); PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Odswież"); PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Ekran główny"); PROGMEM Language_Str MSG_PREPARE = _UxGT("Przygotuj"); PROGMEM Language_Str MSG_TUNE = _UxGT("Strojenie"); + //PROGMEM Language_Str MSG_POWER_MONITOR = _UxGT("Power monitor"); + PROGMEM Language_Str MSG_CURRENT = _UxGT("Natężenie"); + PROGMEM Language_Str MSG_VOLTAGE = _UxGT("Napięcie"); + PROGMEM Language_Str MSG_POWER = _UxGT("Moc"); PROGMEM Language_Str MSG_START_PRINT = _UxGT("Start wydruku"); PROGMEM Language_Str MSG_BUTTON_NEXT = _UxGT("Następny"); PROGMEM Language_Str MSG_BUTTON_INIT = _UxGT("Inic."); - PROGMEM Language_Str MSG_BUTTON_STOP = _UxGT("Stop"); + //PROGMEM Language_Str MSG_BUTTON_STOP = _UxGT("Stop"); PROGMEM Language_Str MSG_BUTTON_PRINT = _UxGT("Drukuj"); PROGMEM Language_Str MSG_BUTTON_RESET = _UxGT("Resetuj"); + PROGMEM Language_Str MSG_BUTTON_IGNORE = _UxGT("Ignoruj"); PROGMEM Language_Str MSG_BUTTON_CANCEL = _UxGT("Przerwij"); PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Gotowe"); + PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Wstecz"); + PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Kontynuuj"); + PROGMEM Language_Str MSG_BUTTON_SKIP = _UxGT("Pomiń"); + PROGMEM Language_Str MSG_PAUSING = _UxGT("Wstrzymywanie..."); PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Wstrzymaj druk"); PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Wznowienie"); + //PROGMEM Language_Str MSG_HOST_START_PRINT = _UxGT("Host Start"); PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Stop"); + //PROGMEM Language_Str MSG_END_LOOPS = _UxGT("End Repeat Loops"); + PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("Drukowanie obiektu"); + PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("Anunuj obiekt"); + PROGMEM Language_Str MSG_CANCEL_OBJECT_N = _UxGT("Anunuj obiekt ="); PROGMEM Language_Str MSG_OUTAGE_RECOVERY = _UxGT("Odzyskiwanie po awarii"); PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Karta SD"); PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("Brak karty"); @@ -326,6 +413,7 @@ namespace Language_pl { PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("Druk wstrzymany"); PROGMEM Language_Str MSG_PRINTING = _UxGT("Drukowanie..."); PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Druk przerwany"); + PROGMEM Language_Str MSG_PRINT_DONE = _UxGT("Druk zakończony"); PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Brak ruchu"); PROGMEM Language_Str MSG_KILLED = _UxGT("Ubity. "); PROGMEM Language_Str MSG_STOPPED = _UxGT("Zatrzymany. "); @@ -335,15 +423,26 @@ namespace Language_pl { PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Skok Z mm"); PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("Cof. wycof. mm"); PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Z Cof. wyc. mm"); + //PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Unretract V"); PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Cof. wycof. V"); PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Auto. wycofanie"); PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Długość zmiany"); + //PROGMEM Language_Str MSG_FILAMENT_SWAP_EXTRA = _UxGT("Swap Extra"); PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Długość oczyszczania"); PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Zmiana narzędzia"); PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Podniesienie Z"); PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Prędkość napełniania"); PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Prędkość wycofania"); - PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Dysza w oczekiwaniu"); + //PROGMEM Language_Str MSG_FILAMENT_PARK_ENABLED = _UxGT("Park Head"); + //PROGMEM Language_Str MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Recover Speed"); + //PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Fan Speed"); + //PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Fan Time"); + //PROGMEM Language_Str MSG_TOOL_MIGRATION_ON = _UxGT("Auto ON"); + //PROGMEM Language_Str MSG_TOOL_MIGRATION_OFF = _UxGT("Auto OFF"); + //PROGMEM Language_Str MSG_TOOL_MIGRATION = _UxGT("Tool Migration"); + //PROGMEM Language_Str MSG_TOOL_MIGRATION_AUTO = _UxGT("Auto-migration"); + //PROGMEM Language_Str MSG_TOOL_MIGRATION_END = _UxGT("Last Extruder"); + //PROGMEM Language_Str MSG_TOOL_MIGRATION_SWAP = _UxGT("Migrate to *"); PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Zmień filament"); PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Zmień filament *"); PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Wsuń Filament"); @@ -356,31 +455,35 @@ namespace Language_pl { PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("Zwolnienie karty"); PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Sonda Z za stołem"); PROGMEM Language_Str MSG_SKEW_FACTOR = _UxGT("Współczynik skrzywienia"); - PROGMEM Language_Str MSG_BLTOUCH = _UxGT("BLTouch"); + //PROGMEM Language_Str MSG_BLTOUCH = _UxGT("BLTouch"); PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("BLTouch Self-Test"); PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Reset BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("Stow"); - PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("Deploy"); - PROGMEM Language_Str MSG_BLTOUCH_SW_MODE = _UxGT("SW-Mode"); - PROGMEM Language_Str MSG_BLTOUCH_5V_MODE = _UxGT("5V-Mode"); - PROGMEM Language_Str MSG_BLTOUCH_OD_MODE = _UxGT("OD-Mode"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE = _UxGT("Mode-Store"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Set BLTouch to 5V"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Set BLTouch to OD"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_ECHO = _UxGT("Report Drain"); + //PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("Stow"); + //PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("Deploy"); + //PROGMEM Language_Str MSG_BLTOUCH_SW_MODE = _UxGT("SW-Mode"); + //PROGMEM Language_Str MSG_BLTOUCH_5V_MODE = _UxGT("5V-Mode"); + //PROGMEM Language_Str MSG_BLTOUCH_OD_MODE = _UxGT("OD-Mode"); + //PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE = _UxGT("Mode-Store"); + //PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Set BLTouch to 5V"); + //PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Set BLTouch to OD"); + //PROGMEM Language_Str MSG_BLTOUCH_MODE_ECHO = _UxGT("Report Drain"); PROGMEM Language_Str MSG_BLTOUCH_MODE_CHANGE = _UxGT("UWAGA: Złe ustawienia mogą uszkodzić drukarkę. Kontynuować?"); - PROGMEM Language_Str MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); - PROGMEM Language_Str MSG_TOUCHMI_INIT = _UxGT("Init TouchMI"); - PROGMEM Language_Str MSG_TOUCHMI_ZTEST = _UxGT("Z Offset Test"); - PROGMEM Language_Str MSG_TOUCHMI_SAVE = _UxGT("Save"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("Deploy TouchMI"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("Deploy Z-Probe"); - PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("Stow Z-Probe"); + //PROGMEM Language_Str MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); + //PROGMEM Language_Str MSG_TOUCHMI_INIT = _UxGT("Init TouchMI"); + //PROGMEM Language_Str MSG_TOUCHMI_ZTEST = _UxGT("Z Offset Test"); + //PROGMEM Language_Str MSG_TOUCHMI_SAVE = _UxGT("Save"); + //PROGMEM Language_Str MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("Deploy TouchMI"); + //PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("Deploy Z-Probe"); + //PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("Stow Z-Probe"); PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Najpierw Home %s%s%s"); + //PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("Probe Offsets"); + //PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("Probe X Offset"); + //PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Probe Y Offset"); PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Offset Z"); - PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Babystep X"); - PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Babystep Y"); - PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Babystep Z"); + PROGMEM Language_Str MSG_MOVE_NOZZLE_TO_BED = _UxGT("Przesuń dyszę do stołu"); + //PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Babystep X"); + //PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Babystep Y"); + //PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Babystep Z"); PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Łącznie"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Błąd krańcówki"); PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Rozgrz. nieudane"); @@ -388,19 +491,24 @@ namespace Language_pl { PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("ZANIK TEMPERATURY"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("ZANIK TEMP. STOŁU"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("ZANIK TEMP.KOMORY"); + //PROGMEM Language_Str MSG_THERMAL_RUNAWAY_COOLER = _UxGT("Cooler Runaway"); + //PROGMEM Language_Str MSG_COOLING_FAILED = _UxGT("Cooling Failed"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Błąd: MAXTEMP"); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Błąd: MINTEMP"); PROGMEM Language_Str MSG_HALTED = _UxGT("Drukarka zatrzym."); PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Proszę zresetować"); - PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); // One character only + //PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); // One character only PROGMEM Language_Str MSG_SHORT_HOUR = _UxGT("g"); // One character only - PROGMEM Language_Str MSG_SHORT_MINUTE = _UxGT("m"); // One character only + //PROGMEM Language_Str MSG_SHORT_MINUTE = _UxGT("m"); // One character only PROGMEM Language_Str MSG_HEATING = _UxGT("Rozgrzewanie..."); PROGMEM Language_Str MSG_COOLING = _UxGT("Chłodzenie..."); PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Rozgrzewanie stołu..."); PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Chłodzenie stołu..."); + //PROGMEM Language_Str MSG_PROBE_HEATING = _UxGT("Probe Heating..."); + //PROGMEM Language_Str MSG_PROBE_COOLING = _UxGT("Probe Cooling..."); PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Rozgrzewanie komory..."); PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Chłodzenie komory..."); + //PROGMEM Language_Str MSG_LASER_COOLING = _UxGT("Laser Cooling..."); PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Kalibrowanie Delty"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Kalibruj X"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Kalibruj Y"); @@ -418,8 +526,9 @@ namespace Language_pl { PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("Poziomowanie 3-punktowe"); PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Poziomowanie liniowe"); PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Poziomowanie biliniowe"); - PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Unified Bed Leveling"); + //PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Unified Bed Leveling"); PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Poziomowanie siatką"); + //PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Mesh probing done"); PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Statystyki"); PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Info płyty"); PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Termistory"); @@ -428,6 +537,7 @@ namespace Language_pl { PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protokół"); PROGMEM Language_Str MSG_INFO_RUNAWAY_OFF = _UxGT("Zegar pracy: OFF"); PROGMEM Language_Str MSG_INFO_RUNAWAY_ON = _UxGT("Zegar pracy: ON"); + //PROGMEM Language_Str MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Hotend Idle Timeout"); PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Oświetlenie obudowy"); PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Jasność oświetlenia"); @@ -447,8 +557,8 @@ namespace Language_pl { PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Użyty fil."); #endif - PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Min Temp"); - PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Max Temp"); + //PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Min Temp"); + //PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Max Temp"); PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Zasilacz"); PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Siła silnika"); PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Siła %"); @@ -471,7 +581,7 @@ namespace Language_pl { PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Sondowanie nieudane"); PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("WYBIERZ FILAMENT"); - PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); + //PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("Uaktualnij firmware MMU!"); PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU wymaga uwagi."); PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Wznów wydruk"); @@ -486,7 +596,7 @@ namespace Language_pl { PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Wysuwanie fil. ..."); PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Wysuwanie fil...."); PROGMEM Language_Str MSG_MMU2_ALL = _UxGT("Wszystko"); - PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("Filament ~"); + //PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("Filament ~"); PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("Resetuj MMU"); PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("Resetowanie MMU..."); PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Usuń, kliknij"); @@ -494,12 +604,41 @@ namespace Language_pl { PROGMEM Language_Str MSG_MIX = _UxGT("Miks"); PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Komponent ="); PROGMEM Language_Str MSG_MIXER = _UxGT("Mikser"); - PROGMEM Language_Str MSG_GRADIENT = _UxGT("Gradient"); + //PROGMEM Language_Str MSG_GRADIENT = _UxGT("Gradient"); PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("Pełny gradient"); PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Przełacz miks"); - PROGMEM Language_Str MSG_CYCLE_MIX = _UxGT("Cycle Mix"); - PROGMEM Language_Str MSG_GRADIENT_MIX = _UxGT("Gradient Mix"); + //PROGMEM Language_Str MSG_CYCLE_MIX = _UxGT("Cycle Mix"); + //PROGMEM Language_Str MSG_GRADIENT_MIX = _UxGT("Gradient Mix"); PROGMEM Language_Str MSG_REVERSE_GRADIENT = _UxGT("Odwrotny gradient"); + //PROGMEM Language_Str MSG_ACTIVE_VTOOL = _UxGT("Active V-tool"); + //PROGMEM Language_Str MSG_START_VTOOL = _UxGT("Start V-tool"); + //PROGMEM Language_Str MSG_END_VTOOL = _UxGT(" End V-tool"); + //PROGMEM Language_Str MSG_GRADIENT_ALIAS = _UxGT("Alias V-tool"); + //PROGMEM Language_Str MSG_RESET_VTOOLS = _UxGT("Reset V-tools"); + //PROGMEM Language_Str MSG_COMMIT_VTOOL = _UxGT("Commit V-tool Mix"); + //PROGMEM Language_Str MSG_VTOOLS_RESET = _UxGT("V-tools Were Reset"); + //PROGMEM Language_Str MSG_START_Z = _UxGT("Start Z:"); + //PROGMEM Language_Str MSG_END_Z = _UxGT(" End Z:"); + + PROGMEM Language_Str MSG_GAMES = _UxGT("Gry"); + //PROGMEM Language_Str MSG_BRICKOUT = _UxGT("Brickout"); + //PROGMEM Language_Str MSG_INVADERS = _UxGT("Invaders"); + //PROGMEM Language_Str MSG_SNAKE = _UxGT("Sn4k3"); + //PROGMEM Language_Str MSG_MAZE = _UxGT("Maze"); + + //PROGMEM Language_Str MSG_BAD_PAGE = _UxGT("Bad page index"); + //PROGMEM Language_Str MSG_BAD_PAGE_SPEED = _UxGT("Bad page speed"); + + PROGMEM Language_Str MSG_EDIT_PASSWORD = _UxGT("Zmień hasło"); + PROGMEM Language_Str MSG_LOGIN_REQUIRED = _UxGT("Wymagane zalogowanie"); + PROGMEM Language_Str MSG_PASSWORD_SETTINGS = _UxGT("Ustawienia hasła"); + PROGMEM Language_Str MSG_ENTER_DIGIT = _UxGT("Wprowadź cyfrę"); + PROGMEM Language_Str MSG_CHANGE_PASSWORD = _UxGT("Ustaw/zmień hasło"); + PROGMEM Language_Str MSG_REMOVE_PASSWORD = _UxGT("Usuń hasło"); + PROGMEM Language_Str MSG_PASSWORD_SET = _UxGT("Hasło to "); + PROGMEM Language_Str MSG_START_OVER = _UxGT("Od nowa"); + PROGMEM Language_Str MSG_REMINDER_SAVE_SETTINGS = _UxGT("Pamiętaj by zapisać!"); + PROGMEM Language_Str MSG_PASSWORD_REMOVED = _UxGT("Hasło usunięte"); // // Filament Change screens show up to 3 lines on a 4-line display @@ -530,4 +669,51 @@ namespace Language_pl { PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Kliknij by zakończyć")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Wznawianie...")); #endif + PROGMEM Language_Str MSG_TMC_DRIVERS = _UxGT("Sterowniki TMC"); + PROGMEM Language_Str MSG_TMC_CURRENT = _UxGT("Prąd sterownika"); + //PROGMEM Language_Str MSG_TMC_HYBRID_THRS = _UxGT("Hybrid Threshold"); + PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Zerowanie bezczujnikowe"); + //PROGMEM Language_Str MSG_TMC_STEPPING_MODE = _UxGT("Stepping Mode"); + //PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop Enabled"); + //PROGMEM Language_Str MSG_SERVICE_RESET = _UxGT("Reset"); + //PROGMEM Language_Str MSG_SERVICE_IN = _UxGT(" in:"); + //PROGMEM Language_Str MSG_BACKLASH = _UxGT("Backlash"); + //PROGMEM Language_Str MSG_BACKLASH_A = LCD_STR_A; + //PROGMEM Language_Str MSG_BACKLASH_B = LCD_STR_B; + //PROGMEM Language_Str MSG_BACKLASH_C = LCD_STR_C; + PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Korekcja"); + PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Wygładzanie"); + + PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("Wypoziomuj oś X"); + PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Autokalibracja"); + #if ENABLED(TOUCH_UI_FTDI_EVE) + //PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Idle timeout, temperature decreased. Press Okay to reheat and again to resume."); + #else + //PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Heater Timeout"); + #endif + //PROGMEM Language_Str MSG_REHEAT = _UxGT("Reheat"); + //PROGMEM Language_Str MSG_REHEATING = _UxGT("Reheating..."); + + //PROGMEM Language_Str MSG_PROBE_WIZARD = _UxGT("Z Probe Wizard"); + //PROGMEM Language_Str MSG_PROBE_WIZARD_PROBING = _UxGT("Probing Z Reference"); + //PROGMEM Language_Str MSG_PROBE_WIZARD_MOVING = _UxGT("Moving to Probing Pos"); + + PROGMEM Language_Str MSG_SOUND = _UxGT("Dźwięk"); + + //PROGMEM Language_Str MSG_TOP_LEFT = _UxGT("Top Left"); + //PROGMEM Language_Str MSG_BOTTOM_LEFT = _UxGT("Bottom Left"); + //PROGMEM Language_Str MSG_TOP_RIGHT = _UxGT("Top Right"); + //PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Bottom Right"); + PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Kalibracja zakończona"); + PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Kalibracja nie powiodła się"); + + //PROGMEM Language_Str MSG_DRIVER_BACKWARD = _UxGT(" driver backward"); } + +#if FAN_COUNT == 1 + #define MSG_FIRST_FAN_SPEED MSG_FAN_SPEED + #define MSG_EXTRA_FIRST_FAN_SPEED MSG_EXTRA_FAN_SPEED +#else + #define MSG_FIRST_FAN_SPEED MSG_FAN_SPEED_N + #define MSG_EXTRA_FIRST_FAN_SPEED MSG_EXTRA_FAN_SPEED_N +#endif diff --git a/Marlin/src/lcd/language/language_pt.h b/Marlin/src/lcd/language/language_pt.h index 37da6216240c..4bec74558e80 100644 --- a/Marlin/src/lcd/language/language_pt.h +++ b/Marlin/src/lcd/language/language_pt.h @@ -81,10 +81,11 @@ namespace Language_pt { PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Mover Z"); PROGMEM Language_Str MSG_MOVE_E = _UxGT("Mover Extrusor"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Mover Extrusor *"); - PROGMEM Language_Str MSG_MOVE_Z_DIST = _UxGT("Mover %smm"); + PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Mover %smm"); PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mover 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mover 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Mover 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Mover 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Velocidade"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Base Z"); PROGMEM Language_Str MSG_NOZZLE = " " LCD_STR_THERMOMETER _UxGT(" Bico"); @@ -109,7 +110,7 @@ namespace Language_pt { PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatura"); PROGMEM Language_Str MSG_MOTION = _UxGT("Movimento"); PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filamento"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E em mm³"); + PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E em mm") SUPERSCRIPT_THREE; PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Fil. Diam."); PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Fil. Diam. *"); PROGMEM Language_Str MSG_CONTRAST = _UxGT("Contraste"); @@ -160,4 +161,11 @@ namespace Language_pt { PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Fim de curso"); PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Impressora Incorreta"); + + PROGMEM Language_Str MSG_TOP_LEFT = _UxGT("Superior Esquerdo"); + PROGMEM Language_Str MSG_BOTTOM_LEFT = _UxGT("Inferior Esquerdo"); + PROGMEM Language_Str MSG_TOP_RIGHT = _UxGT("Superior Direto"); + PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Inferior Direto"); + PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Calibração Completa"); + PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Calibração Falhou"); } diff --git a/Marlin/src/lcd/language/language_pt_br.h b/Marlin/src/lcd/language/language_pt_br.h index cf2f7a0ccef1..12904aa7ea79 100644 --- a/Marlin/src/lcd/language/language_pt_br.h +++ b/Marlin/src/lcd/language/language_pt_br.h @@ -51,7 +51,7 @@ namespace Language_pt_br { PROGMEM Language_Str MSG_MAIN = _UxGT("Menu principal"); PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Config. Avançada"); PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Configuração"); - PROGMEM Language_Str MSG_AUTOSTART = _UxGT("Início automático"); + PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Início automático"); PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Desabilit. motores"); PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Menu Debug"); PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Testar Barra Progres"); @@ -94,7 +94,7 @@ namespace Language_pt_br { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Mover eixo"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Nivelação Mesa"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Nivelar Mesa"); - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Nivelar Cantos"); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Nivelar Cantos"); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Próximo Canto"); PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Editor de Malha"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Editar Malha"); @@ -103,7 +103,7 @@ namespace Language_pt_br { PROGMEM Language_Str MSG_MESH_X = _UxGT("Índice X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("Índice Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Valor Z"); - PROGMEM Language_Str MSG_USER_MENU = _UxGT("Comando customizado"); + PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Comando customizado"); PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 Teste de sonda"); PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 Ponto"); PROGMEM Language_Str MSG_IDEX_MENU = _UxGT("Modo IDEX"); @@ -214,10 +214,11 @@ namespace Language_pt_br { PROGMEM Language_Str MSG_MOVE_E = _UxGT("Mover Extrusor"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Mover Extrusor *"); PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Extrus. mto fria"); - PROGMEM Language_Str MSG_MOVE_Z_DIST = _UxGT("Mover %smm"); + PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Mover %smm"); PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mover 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mover 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Mover 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Mover 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Velocidade"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Base Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Bocal"); @@ -259,7 +260,7 @@ namespace Language_pt_br { PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatura"); PROGMEM Language_Str MSG_MOTION = _UxGT("Movimento"); PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filamento"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("Extrusão em mm³"); + PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("Extrusão em mm") SUPERSCRIPT_THREE; PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Diâmetro Fil."); PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Diâmetro Fil. *"); PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Descarr. mm"); @@ -478,4 +479,11 @@ namespace Language_pt_br { PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Clique p. finalizar")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Continuando...")); #endif + + PROGMEM Language_Str MSG_TOP_LEFT = _UxGT("Superior Esquerdo"); + PROGMEM Language_Str MSG_BOTTOM_LEFT = _UxGT("Inferior Esquerdo"); + PROGMEM Language_Str MSG_TOP_RIGHT = _UxGT("Superior Direto"); + PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Inferior Direto"); + PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Calibração Completa"); + PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Calibração Falhou"); } diff --git a/Marlin/src/lcd/language/language_ro.h b/Marlin/src/lcd/language/language_ro.h index 7b54f24abf7d..3d21e1a58d7a 100644 --- a/Marlin/src/lcd/language/language_ro.h +++ b/Marlin/src/lcd/language/language_ro.h @@ -53,7 +53,7 @@ namespace Language_ro { PROGMEM Language_Str MSG_MAIN = _UxGT("Principal"); PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Setari Avansate"); PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Configurare"); - PROGMEM Language_Str MSG_AUTOSTART = _UxGT("Autostart"); + PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Autostart"); PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Dezactivare Motoare"); PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Meniu Debug"); PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Test Bara Progres"); @@ -91,12 +91,8 @@ namespace Language_ro { PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Racire"); PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Frecventa"); PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Control Laser"); - PROGMEM Language_Str MSG_LASER_OFF = _UxGT("Laser Oprit"); - PROGMEM Language_Str MSG_LASER_ON = _UxGT("Laser Pornit"); PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Puterea Laserului"); PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Controlul Spindle"); - PROGMEM Language_Str MSG_SPINDLE_OFF = _UxGT("Spindle Oprit"); - PROGMEM Language_Str MSG_SPINDLE_ON = _UxGT("Spindle Pornit"); PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Puterea Spindle"); PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Spindle Invers"); PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Porneste"); @@ -106,7 +102,7 @@ namespace Language_ro { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Muta Axa"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Nivelarea Patului"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Niveleaza Patul"); - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Niveleaza Colturile"); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Niveleaza Colturile"); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Urmatorul Colt"); PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Editor Mesh"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Editeaza Mesh"); @@ -115,7 +111,7 @@ namespace Language_ro { PROGMEM Language_Str MSG_MESH_X = _UxGT("Index X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("Index Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Valoare Z"); - PROGMEM Language_Str MSG_USER_MENU = _UxGT("Comenzi Personalizate"); + PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Comenzi Personalizate"); PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 Probe Test"); PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 Point"); PROGMEM Language_Str MSG_M48_DEVIATION = _UxGT("Deviation"); @@ -232,10 +228,11 @@ namespace Language_ro { PROGMEM Language_Str MSG_MOVE_E = _UxGT("Extruder"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Extruder *"); PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Capat Prea Rece"); - PROGMEM Language_Str MSG_MOVE_Z_DIST = _UxGT("Move %smm"); + PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Move %smm"); PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Move 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Move 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Move 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Move 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Speed"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Bed Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Nozzle"); @@ -269,16 +266,6 @@ namespace Language_ro { PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Autotune failed. Bad extruder."); PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Autotune failed. Temperature too high."); PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("Autotune failed! Timeout."); - PROGMEM Language_Str MSG_PID_P = _UxGT("PID-P"); - PROGMEM Language_Str MSG_PID_P_E = _UxGT("PID-P *"); - PROGMEM Language_Str MSG_PID_I = _UxGT("PID-I"); - PROGMEM Language_Str MSG_PID_I_E = _UxGT("PID-I *"); - PROGMEM Language_Str MSG_PID_D = _UxGT("PID-D"); - PROGMEM Language_Str MSG_PID_D_E = _UxGT("PID-D *"); - PROGMEM Language_Str MSG_PID_C = _UxGT("PID-C"); - PROGMEM Language_Str MSG_PID_C_E = _UxGT("PID-C *"); - PROGMEM Language_Str MSG_PID_F = _UxGT("PID-F"); - PROGMEM Language_Str MSG_PID_F_E = _UxGT("PID-F *"); PROGMEM Language_Str MSG_SELECT = _UxGT("Select"); PROGMEM Language_Str MSG_SELECT_E = _UxGT("Select *"); PROGMEM Language_Str MSG_ACC = _UxGT("Accel"); @@ -315,8 +302,8 @@ namespace Language_ro { PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperature"); PROGMEM Language_Str MSG_MOTION = _UxGT("Motion"); PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filament"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm³"); - PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("E Limit in mm³"); + PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm") SUPERSCRIPT_THREE; + PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("E Limit in mm") SUPERSCRIPT_THREE; PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT_E = _UxGT("E Limit *"); PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Fil. Dia."); PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Fil. Dia. *"); diff --git a/Marlin/src/lcd/language/language_ru.h b/Marlin/src/lcd/language/language_ru.h index 2a2f56857303..6ccfe5f47a12 100644 --- a/Marlin/src/lcd/language/language_ru.h +++ b/Marlin/src/lcd/language/language_ru.h @@ -43,6 +43,11 @@ namespace Language_ru { PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("SD-карта вставлена"); PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("SD-карта извлечена"); PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Вставьте SD-карту"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_SD_INIT_FAIL = _UxGT("Сбой инициализации SD"); + #else + PROGMEM Language_Str MSG_SD_INIT_FAIL = _UxGT("Сбой инициализ. SD"); + #endif PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Ошибка считывания"); PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("USB диск удалён"); PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("Ошибка USB диска"); @@ -56,7 +61,7 @@ namespace Language_ru { PROGMEM Language_Str MSG_MAIN = _UxGT("Основное меню"); PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Другие настройки"); PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Конфигурация"); - PROGMEM Language_Str MSG_AUTOSTART = _UxGT("Автостарт"); + PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Автостарт"); PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Выключить двигатели"); PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Меню отладки"); PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Тест индикатора"); @@ -64,7 +69,13 @@ namespace Language_ru { PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Парковка X"); PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Парковка Y"); PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Парковка Z"); + PROGMEM Language_Str MSG_AUTO_HOME_I = _UxGT("Парковка ") LCD_STR_I; + PROGMEM Language_Str MSG_AUTO_HOME_J = _UxGT("Парковка ") LCD_STR_J; + PROGMEM Language_Str MSG_AUTO_HOME_K = _UxGT("Парковка ") LCD_STR_K; PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Авто Z-выравнивание"); + PROGMEM Language_Str MSG_ITERATION = _UxGT("G34 Итерация: %i"); + PROGMEM Language_Str MSG_DECREASING_ACCURACY = _UxGT("Уменьшение точности!"); + PROGMEM Language_Str MSG_ACCURACY_ACHIEVED = _UxGT("Точность достигнута"); PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Нулевое положение"); PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Нажмите чтобы начать"); PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Следующая точка"); @@ -72,11 +83,29 @@ namespace Language_ru { PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Высота спада"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Установ. смещения дома"); + PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("Смещение дома X"); + PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Смещение дома Y"); + PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Смещение дома Z"); + PROGMEM Language_Str MSG_HOME_OFFSET_I = _UxGT("Смещение дома ") LCD_STR_I; + PROGMEM Language_Str MSG_HOME_OFFSET_J = _UxGT("Смещение дома ") LCD_STR_J; + PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Смещение дома ") LCD_STR_K; #else PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Установ.смещ.дома"); + PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("Смещ. дома X"); + PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Смещ. дома Y"); + PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Смещ. дома Z"); + PROGMEM Language_Str MSG_HOME_OFFSET_I = _UxGT("Смещ. дома ") LCD_STR_I; + PROGMEM Language_Str MSG_HOME_OFFSET_J = _UxGT("Смещ. дома ") LCD_STR_J; + PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Смещ. дома ") LCD_STR_K; #endif PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Смещения применены"); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Установить ноль"); + PROGMEM Language_Str MSG_SELECT_ORIGIN = _UxGT("Выберите ноль"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Последнее знач. "); + #else + PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Послед. знач. "); + #endif #if PREHEAT_COUNT PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Преднагрев ") PREHEAT_1_LABEL; PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Нагрев ") PREHEAT_1_LABEL " ~"; @@ -98,18 +127,31 @@ namespace Language_ru { PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Охлаждение"); PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Частота"); PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Управление лазером"); - PROGMEM Language_Str MSG_LASER_OFF = _UxGT("Выключить лазер"); - PROGMEM Language_Str MSG_LASER_ON = _UxGT("Включить лазер"); - PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Мощность лазера"); - PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Управление шпинделем"); - PROGMEM Language_Str MSG_SPINDLE_OFF = _UxGT("Выключить шпиндель"); - PROGMEM Language_Str MSG_SPINDLE_ON = _UxGT("Включить шпиндель"); #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Управление шпинделем"); + PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Переключить лазер"); + PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Переключ.шпиндель"); PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Мощность шпинделя"); + PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Мощность лазера"); + PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Тестовый импульс мс"); + PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Переключить обдув"); + PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Переключить вакуум"); #else + PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Управление шпинд."); + PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Переключ.лазер"); + PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Переключ.шпинд"); PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Мощн.шпинделя"); + PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Мощн. лазера"); + PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Тест. имп. мс"); + PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Переключ. обдув"); + PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Переключ. вакуум"); #endif + PROGMEM Language_Str MSG_LASER_ASSIST_TOGGLE = _UxGT("Управление обдувом"); + PROGMEM Language_Str MSG_FLOWMETER_FAULT = _UxGT("Ошибка обдува"); + PROGMEM Language_Str MSG_LASER_FIRE_PULSE = _UxGT("Импульс лазера"); + PROGMEM Language_Str MSG_SPINDLE_FORWARD = _UxGT("Шпиндель вперёд"); PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Инверсия шпинделя"); + PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Включить питание"); PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Выключить питание"); PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Экструзия"); @@ -117,8 +159,17 @@ namespace Language_ru { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Движение по осям"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Выравнивание стола"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Выровнять стол"); - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Выровнять углы"); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Выровнять углы"); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Следующий угол"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Вверх до срабатыв. зонда"); + PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("Углы в норме. Вырав.стола"); + #else + PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Вверх до сраб. зонда"); + PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("Углы в норме. Вырав."); + #endif + PROGMEM Language_Str MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Хорошие точки: "); + PROGMEM Language_Str MSG_BED_TRAMMING_LAST_Z = _UxGT("Последняя Z: "); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Смещение по Z"); PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Правка сетки окончена"); @@ -131,19 +182,20 @@ namespace Language_ru { PROGMEM Language_Str MSG_MESH_X = _UxGT("Индекс X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("Индекс Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Значение Z"); - PROGMEM Language_Str MSG_USER_MENU = _UxGT("Свои команды"); + PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Свои команды"); PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 тест Z-зонда"); PROGMEM Language_Str MSG_M48_DEVIATION = _UxGT("Отклонение"); PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 точка"); + PROGMEM Language_Str MSG_M48_OUT_OF_BOUNDS = _UxGT("Зонд за пределами"); PROGMEM Language_Str MSG_IDEX_MENU = _UxGT("Меню IDEX"); + PROGMEM Language_Str MSG_OFFSETS_MENU = _UxGT("Размещение сопел"); PROGMEM Language_Str MSG_IDEX_MODE_AUTOPARK = _UxGT("Авто парковка"); PROGMEM Language_Str MSG_IDEX_MODE_DUPLICATE = _UxGT("Размножение"); PROGMEM Language_Str MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Зеркальная копия"); PROGMEM Language_Str MSG_IDEX_MODE_FULL_CTRL = _UxGT("Полный контроль"); - - PROGMEM Language_Str MSG_OFFSETS_MENU = _UxGT("Размещение сопел"); + PROGMEM Language_Str MSG_IDEX_DUPE_GAP = _UxGT("Дублировать X-зазор"); PROGMEM Language_Str MSG_HOTEND_OFFSET_X = _UxGT("2-е сопло X"); PROGMEM Language_Str MSG_HOTEND_OFFSET_Y = _UxGT("2-е сопло Y"); @@ -155,20 +207,19 @@ namespace Language_ru { PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Точка разворота"); PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Ручной ввод сетки"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Разместить шайбу и измерить"); + PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Разместить шайбу,измерить"); PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Убрать и замерить стол"); #else - PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Разм.шайбу,измерить"); + PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Разм.шайбу, измерить"); PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Убрать, измер. стол"); #endif + PROGMEM Language_Str MSG_UBL_MESH_WIZARD = _UxGT("Мастер сеток UBL"); PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Измерение"); PROGMEM Language_Str MSG_UBL_MOVING_TO_NEXT = _UxGT("Двигаемся дальше"); PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("Активировать UBL"); PROGMEM Language_Str MSG_UBL_DEACTIVATE_MESH = _UxGT("Деактивировать UBL"); - PROGMEM Language_Str MSG_UBL_MESH_EDIT = _UxGT("Редактор сеток"); PROGMEM Language_Str MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Править свою сетку"); - #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = _UxGT("Температура стола"); PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Температура стола"); @@ -178,17 +229,15 @@ namespace Language_ru { PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Правка сетки завершена"); #else PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = LCD_STR_THERMOMETER _UxGT(" стола, ") LCD_STR_DEGREE "C"; - PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = LCD_STR_THERMOMETER _UxGT(" стола, ") LCD_STR_DEGREE "C"; + PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Своя ") LCD_STR_THERMOMETER _UxGT(" стола,") LCD_STR_DEGREE "C"; PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = LCD_STR_THERMOMETER _UxGT(" сопла, ") LCD_STR_DEGREE "C"; - PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = LCD_STR_THERMOMETER _UxGT(" сопла, ") LCD_STR_DEGREE "C"; + PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Своя ") LCD_STR_THERMOMETER _UxGT(" сопла,") LCD_STR_DEGREE "C"; PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Построить свою"); PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Правка завершена"); #endif PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("Точная правка сетки"); PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("Построить сетку"); - #if PREHEAT_COUNT - PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Построить сетку $"); - #endif + PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Построить сетку $"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Построить холодную сетку"); #else @@ -198,14 +247,10 @@ namespace Language_ru { PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Высота"); PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Проверить сетку"); #if LCD_WIDTH > 21 - #if PREHEAT_COUNT - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Проверить сетку $"); - #endif + PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Проверить сетку $"); PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Проверить свою сетку"); #else - #if PREHEAT_COUNT - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Провер. сетку $"); - #endif + PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Провер. сетку $"); PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Провер. свою сетку"); #endif PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26 нагрев стола"); @@ -232,11 +277,12 @@ namespace Language_ru { #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Сохранить сетку снаружи"); PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("Вывод информации UBL"); + PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Кол-во заполнителя"); #else PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Сохранить снаружи"); PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("Информация UBL"); + PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Кол-во заполн."); #endif - PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Кол-во заполнителя"); PROGMEM Language_Str MSG_UBL_MANUAL_FILLIN = _UxGT("Ручное заполнение"); PROGMEM Language_Str MSG_UBL_SMART_FILLIN = _UxGT("Умное заполнение"); PROGMEM Language_Str MSG_UBL_FILLIN_MESH = _UxGT("Заполнить сетку"); @@ -253,6 +299,7 @@ namespace Language_ru { PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("Нет хранилища"); PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Ошибка: Сохран. UBL"); PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Ошибка: Восстан.UBL"); + PROGMEM Language_Str MSG_UBL_Z_OFFSET = _UxGT("Смещение Z: "); PROGMEM Language_Str MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Смещение Z останов."); PROGMEM Language_Str MSG_UBL_STEP_BY_STEP_MENU = _UxGT("UBL пошагово"); PROGMEM Language_Str MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1.Строить холодную"); @@ -275,6 +322,14 @@ namespace Language_ru { PROGMEM Language_Str MSG_SET_LEDS_VIOLET = _UxGT("Фиолетовый"); PROGMEM Language_Str MSG_SET_LEDS_WHITE = _UxGT("Белый"); PROGMEM Language_Str MSG_SET_LEDS_DEFAULT = _UxGT("Свет по умолчанию"); + PROGMEM Language_Str MSG_LED_CHANNEL_N = _UxGT("Канал ="); + PROGMEM Language_Str MSG_LEDS2 = _UxGT("Свет #2"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_NEO2_PRESETS = _UxGT("Свет #2 предустановки"); + #else + PROGMEM Language_Str MSG_NEO2_PRESETS = _UxGT("Свет #2 предустан."); + #endif + PROGMEM Language_Str MSG_NEO2_BRIGHTNESS = _UxGT("Яркость"); PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Свой цвет подсветки"); PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Уровень красного"); PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Уровень зелёного"); @@ -287,13 +342,17 @@ namespace Language_ru { PROGMEM Language_Str MSG_MOVE_X = _UxGT("Движение по X"); PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Движение по Y"); PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Движение по Z"); + PROGMEM Language_Str MSG_MOVE_I = _UxGT("Движение по ") LCD_STR_I; + PROGMEM Language_Str MSG_MOVE_J = _UxGT("Движение по ") LCD_STR_J; + PROGMEM Language_Str MSG_MOVE_K = _UxGT("Движение по ") LCD_STR_K; PROGMEM Language_Str MSG_MOVE_E = _UxGT("Экструдер"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Экструдер *"); PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Сопло не нагрето"); - PROGMEM Language_Str MSG_MOVE_Z_DIST = _UxGT("Движение %sмм"); + PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Движение %sмм"); PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Движение 0.1мм"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Движение 1мм"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Движение 10мм"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Движение 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Скорость"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Z стола"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Сопло, ") LCD_STR_DEGREE "C"; @@ -302,6 +361,16 @@ namespace Language_ru { PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Сопло ожидает"); PROGMEM Language_Str MSG_BED = _UxGT("Стол, ") LCD_STR_DEGREE "C"; PROGMEM Language_Str MSG_CHAMBER = _UxGT("Камера,") LCD_STR_DEGREE "C"; + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_COOLER = _UxGT("Охлаждение лазера"); + PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Переключ. охлажд."); + PROGMEM Language_Str MSG_FLOWMETER_SAFETY = _UxGT("Безопасн. потока"); + #else + PROGMEM Language_Str MSG_COOLER = _UxGT("Охлажд. лазера"); + PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Переключ. охл."); + PROGMEM Language_Str MSG_FLOWMETER_SAFETY = _UxGT("Безопас.потока"); + #endif + PROGMEM Language_Str MSG_LASER = _UxGT("Лазер"); PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Кулер"); PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Кулер ~"); PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Сохранённый кулер ~"); @@ -336,6 +405,9 @@ namespace Language_ru { PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-рывок"); PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-рывок"); PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-рывок"); + PROGMEM Language_Str MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-рывок"); + PROGMEM Language_Str MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-рывок"); + PROGMEM Language_Str MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-рывок"); PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-рывок"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Отклонение узла"); @@ -346,6 +418,9 @@ namespace Language_ru { PROGMEM Language_Str MSG_VMAX_A = _UxGT("Скор.макс ") LCD_STR_A; PROGMEM Language_Str MSG_VMAX_B = _UxGT("Скор.макс ") LCD_STR_B; PROGMEM Language_Str MSG_VMAX_C = _UxGT("Скор.макс ") LCD_STR_C; + PROGMEM Language_Str MSG_VMAX_I = _UxGT("Скор.макс ") LCD_STR_I; + PROGMEM Language_Str MSG_VMAX_J = _UxGT("Скор.макс ") LCD_STR_J; + PROGMEM Language_Str MSG_VMAX_K = _UxGT("Скор.макс ") LCD_STR_K; PROGMEM Language_Str MSG_VMAX_E = _UxGT("Скор.макс ") LCD_STR_E; PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Скор.макс *"); PROGMEM Language_Str MSG_VMIN = _UxGT("Скор.мин"); @@ -354,6 +429,9 @@ namespace Language_ru { PROGMEM Language_Str MSG_AMAX_A = _UxGT("Ускор.макс ") LCD_STR_A; PROGMEM Language_Str MSG_AMAX_B = _UxGT("Ускор.макс ") LCD_STR_B; PROGMEM Language_Str MSG_AMAX_C = _UxGT("Ускор.макс ") LCD_STR_C; + PROGMEM Language_Str MSG_AMAX_I = _UxGT("Ускор.макс ") LCD_STR_I; + PROGMEM Language_Str MSG_AMAX_J = _UxGT("Ускор.макс ") LCD_STR_J; + PROGMEM Language_Str MSG_AMAX_K = _UxGT("Ускор.макс ") LCD_STR_K; PROGMEM Language_Str MSG_AMAX_E = _UxGT("Ускор.макс ") LCD_STR_E; PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Ускор.макс *"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Ускор.втягив."); @@ -364,13 +442,16 @@ namespace Language_ru { PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" шаг/мм"); PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" шаг/мм"); PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" шаг/мм"); + PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" шаг/мм"); + PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" шаг/мм"); + PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" шаг/мм"); PROGMEM Language_Str MSG_E_STEPS = _UxGT("E шаг/мм"); PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* шаг/мм"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Температура"); PROGMEM Language_Str MSG_MOTION = _UxGT("Движение"); PROGMEM Language_Str MSG_FILAMENT = _UxGT("Филамент"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E в мм³"); - PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("E огран.,мм³"); + PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E в мм") SUPERSCRIPT_THREE; + PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("E огран.,мм") SUPERSCRIPT_THREE; PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT_E = _UxGT("E огран. *"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Диам. филамента"); @@ -386,10 +467,11 @@ namespace Language_ru { PROGMEM Language_Str MSG_CONTRAST = _UxGT("Контраст экрана"); PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Сохранить настройки"); PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Загрузить настройки"); - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("На базовые параметры"); #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("На базовые параметры"); PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Инициализация EEPROM"); #else + PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("На базовые парам."); PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Инициализ. EEPROM"); #endif PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("Сбой EEPROM: CRC"); @@ -398,7 +480,7 @@ namespace Language_ru { PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Параметры сохранены"); PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Обновление прошивки"); PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Сброс принтера"); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT(" Обновить"); + PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT(" Обновить"); PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Главный экран"); PROGMEM Language_Str MSG_PREPARE = _UxGT("Подготовить"); PROGMEM Language_Str MSG_TUNE = _UxGT("Настроить"); @@ -418,9 +500,11 @@ namespace Language_ru { PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Готово"); PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Назад"); PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Продолжить"); + PROGMEM Language_Str MSG_BUTTON_SKIP = _UxGT("Пропустить"); PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Пауза печати"); PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Продолжить печать"); + PROGMEM Language_Str MSG_HOST_START_PRINT = _UxGT("Старт с хоста"); PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Остановить печать"); PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("Печать объекта"); PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("Завершить объект"); @@ -523,9 +607,17 @@ namespace Language_ru { PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("Смещение X"); PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Смещение Y"); PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Смещение Z"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_MOVE_NOZZLE_TO_BED = _UxGT("Двигать сопло к столу"); + #else + PROGMEM Language_Str MSG_MOVE_NOZZLE_TO_BED = _UxGT("Двиг. сопло к столу"); + #endif PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Микрошаг X"); PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Микрошаг Y"); PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Микрошаг Z"); + PROGMEM Language_Str MSG_BABYSTEP_I = _UxGT("Микрошаг ") LCD_STR_I; + PROGMEM Language_Str MSG_BABYSTEP_J = _UxGT("Микрошаг ") LCD_STR_J; + PROGMEM Language_Str MSG_BABYSTEP_K = _UxGT("Микрошаг ") LCD_STR_K; PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Сумарно"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Сработал концевик"); PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Разогрев не удался"); @@ -533,6 +625,8 @@ namespace Language_ru { PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("УТЕЧКА ТЕПЛА"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("УТЕЧКА ТЕПЛА СТОЛА"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("УТЕЧКА ТЕПЛА КАМЕРЫ"); + PROGMEM Language_Str MSG_THERMAL_RUNAWAY_COOLER = _UxGT("УТЕЧКА ОХЛАЖДЕНИЯ"); + PROGMEM Language_Str MSG_COOLING_FAILED = _UxGT("ОХЛАДИТЬ НЕ УДАЛОСЬ"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Ошибка: Т макс."); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Ошибка: Т мин."); PROGMEM Language_Str MSG_HALTED = _UxGT("ПРИНТЕР ОСТАНОВЛЕН"); @@ -543,9 +637,12 @@ namespace Language_ru { PROGMEM Language_Str MSG_HEATING = _UxGT("Нагрев..."); PROGMEM Language_Str MSG_COOLING = _UxGT("Охлаждение..."); PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Нагрев стола..."); - PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Нагрев камеры..."); PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Охлаждение стола..."); + PROGMEM Language_Str MSG_PROBE_HEATING = _UxGT("Нагрев зонда..."); + PROGMEM Language_Str MSG_PROBE_COOLING = _UxGT("Охлаждение зонда..."); + PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Нагрев камеры..."); PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Охладжение камеры..."); + PROGMEM Language_Str MSG_LASER_COOLING = _UxGT("Охлаждение лазера..."); PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Калибровка Delta"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Калибровать X"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Калибровать Y"); @@ -554,13 +651,12 @@ namespace Language_ru { PROGMEM Language_Str MSG_DELTA_SETTINGS = _UxGT("Настройки Delta"); PROGMEM Language_Str MSG_DELTA_AUTO_CALIBRATE = _UxGT("Авто калибровка"); PROGMEM Language_Str MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Высота Delta"); - #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Зондировать Z-смещение"); - PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Стержень диагонали"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Зондировать Z-смещения"); #else PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Зондир. Z-смещения"); - PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Стержень диаг."); #endif + PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Стержень диаг."); PROGMEM Language_Str MSG_DELTA_HEIGHT = _UxGT("Высота"); PROGMEM Language_Str MSG_DELTA_RADIUS = _UxGT("Радиус"); PROGMEM Language_Str MSG_INFO_MENU = _UxGT("О принтере"); @@ -576,6 +672,11 @@ namespace Language_ru { #endif PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Управление UBL"); PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Выравнивание сетки"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Зондирование выполнено"); + #else + PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Зондиров. выполнено"); + #endif PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Статистика принтера"); PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Данные платы"); @@ -596,14 +697,14 @@ namespace Language_ru { PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Яркость подсветки"); PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Неверный принтер"); - #if LCD_WIDTH >= 20 + #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Счётчик печати"); PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Общее время печати"); PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Наидольшее задание"); PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Длина филамента"); #else - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Отпечатков"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Всего"); + PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Напечатано"); + PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Общее время"); PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Наидольшее"); PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Выдавлено"); #endif @@ -616,6 +717,9 @@ namespace Language_ru { PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Привод, %"); PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Привод, %"); PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z Привод, %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Привод, %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Привод, %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Привод, %"); PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Привод, %"); PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("СБОЙ СВЯЗИ С TMC"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Запись DAC в EEPROM"); @@ -664,6 +768,7 @@ namespace Language_ru { PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("Перезапуск MMU"); PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("Перезапуск MMU..."); PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Удалите и нажмите"); + #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_MIX = _UxGT("Смешивание"); #else @@ -672,7 +777,7 @@ namespace Language_ru { PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Компонент ="); PROGMEM Language_Str MSG_MIXER = _UxGT("Смеситель"); PROGMEM Language_Str MSG_GRADIENT = _UxGT("Градиент"); - PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("Полний градиент"); + PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("Полный градиент"); PROGMEM Language_Str MSG_CYCLE_MIX = _UxGT("Цикличное смешивание"); PROGMEM Language_Str MSG_GRADIENT_MIX = _UxGT("Градиент смешивания"); PROGMEM Language_Str MSG_REVERSE_GRADIENT = _UxGT("Сменить градиент"); @@ -683,8 +788,8 @@ namespace Language_ru { PROGMEM Language_Str MSG_END_VTOOL = _UxGT("Конец В-инструмента"); PROGMEM Language_Str MSG_GRADIENT_ALIAS = _UxGT("Псевдоним В-инструмента"); PROGMEM Language_Str MSG_RESET_VTOOLS = _UxGT("Сброс В-инструментов"); - PROGMEM Language_Str MSG_VTOOLS_RESET = _UxGT("В-инструменти сброшены"); - PROGMEM Language_Str MSG_COMMIT_VTOOL = _UxGT("Смешать В-инструменти"); + PROGMEM Language_Str MSG_COMMIT_VTOOL = _UxGT("Смешать В-инструменты"); + PROGMEM Language_Str MSG_VTOOLS_RESET = _UxGT("В-инструменты сброшены"); #else PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Перекл. смешивание"); PROGMEM Language_Str MSG_ACTIVE_VTOOL = _UxGT("Актив.В-инструм."); @@ -692,8 +797,8 @@ namespace Language_ru { PROGMEM Language_Str MSG_END_VTOOL = _UxGT("В-инструм.кон."); PROGMEM Language_Str MSG_GRADIENT_ALIAS = _UxGT("Псевдоним В-инстр."); PROGMEM Language_Str MSG_RESET_VTOOLS = _UxGT("Сброс В-инструм."); - PROGMEM Language_Str MSG_VTOOLS_RESET = _UxGT("В-инструм. сброшены"); PROGMEM Language_Str MSG_COMMIT_VTOOL = _UxGT("Смешать В-инструм."); + PROGMEM Language_Str MSG_VTOOLS_RESET = _UxGT("В-инструм. сброшены"); #endif PROGMEM Language_Str MSG_START_Z = _UxGT("Начало Z"); PROGMEM Language_Str MSG_END_Z = _UxGT(" Конец Z"); @@ -706,17 +811,32 @@ namespace Language_ru { #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_BAD_PAGE = _UxGT("Плохой индекс страницы"); - PROGMEM Language_Str MSG_BAD_PAGE_SPEED = _UxGT("Полохая скорость страницы"); + PROGMEM Language_Str MSG_BAD_PAGE_SPEED = _UxGT("Плохая скорость страницы"); #else - PROGMEM Language_Str MSG_BAD_PAGE = _UxGT("Полохая страница"); - PROGMEM Language_Str MSG_BAD_PAGE_SPEED = _UxGT("Полохая скор.стран."); + PROGMEM Language_Str MSG_BAD_PAGE = _UxGT("Плохая страница"); + PROGMEM Language_Str MSG_BAD_PAGE_SPEED = _UxGT("Плохая скор.стран."); #endif - PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Парковка...")); + PROGMEM Language_Str MSG_EDIT_PASSWORD = _UxGT("Редактировать пароль"); + PROGMEM Language_Str MSG_LOGIN_REQUIRED = _UxGT("Нужен логин"); + PROGMEM Language_Str MSG_PASSWORD_SETTINGS = _UxGT("Настройки пароля"); + PROGMEM Language_Str MSG_ENTER_DIGIT = _UxGT("Введите цифру"); + PROGMEM Language_Str MSG_CHANGE_PASSWORD = _UxGT("Смените пароль"); + PROGMEM Language_Str MSG_REMOVE_PASSWORD = _UxGT("Удалить пароль"); + PROGMEM Language_Str MSG_PASSWORD_SET = _UxGT("Пароль это "); + PROGMEM Language_Str MSG_START_OVER = _UxGT("Старт через"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_REMINDER_SAVE_SETTINGS = _UxGT("Запомни для сохранения!"); + #else + PROGMEM Language_Str MSG_REMINDER_SAVE_SETTINGS = _UxGT("Запомни, сохрани!"); + #endif + PROGMEM Language_Str 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 // + PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Парковка...")); #if LCD_HEIGHT >= 4 PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_3_LINE("Нажмите кнопку", "для продолжения", "печати")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_2_LINE("Ожидайте начала", "смены филамента")); @@ -742,10 +862,10 @@ namespace Language_ru { #endif PROGMEM Language_Str MSG_TMC_DRIVERS = _UxGT("Драйвера TMC"); - PROGMEM Language_Str MSG_TMC_CURRENT = _UxGT("Текущие настройки"); + PROGMEM Language_Str MSG_TMC_CURRENT = _UxGT("Ток двигателей"); PROGMEM Language_Str MSG_TMC_HYBRID_THRS = _UxGT("Гибридный режим"); PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Режим без эндстопов"); - PROGMEM Language_Str MSG_TMC_STEPPING_MODE = _UxGT("Режим шага"); + PROGMEM Language_Str MSG_TMC_STEPPING_MODE = _UxGT("Режим драйвера"); PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("Тихий режим вкл"); PROGMEM Language_Str MSG_SERVICE_RESET = _UxGT("Сброс"); @@ -763,6 +883,29 @@ namespace Language_ru { #endif PROGMEM Language_Str MSG_REHEAT = _UxGT("Возобновить нагрев"); PROGMEM Language_Str MSG_REHEATING = _UxGT("Нагрев..."); + + PROGMEM Language_Str MSG_PROBE_WIZARD = _UxGT("Мастер Z-зонда"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_PROBE_WIZARD_PROBING = _UxGT("Зондиров. контр. точки Z"); + PROGMEM Language_Str MSG_PROBE_WIZARD_MOVING = _UxGT("Движение к точке зондиров."); + #else + PROGMEM Language_Str MSG_PROBE_WIZARD_PROBING = _UxGT("Зондир.контр.точки Z"); + PROGMEM Language_Str MSG_PROBE_WIZARD_MOVING = _UxGT("Движ. к точке зондир."); + #endif + + PROGMEM Language_Str MSG_SOUND = _UxGT("Звук"); + + PROGMEM Language_Str MSG_TOP_LEFT = _UxGT("Верхний левый"); + PROGMEM Language_Str MSG_BOTTOM_LEFT = _UxGT("Нижний левый"); + PROGMEM Language_Str MSG_TOP_RIGHT = _UxGT("Верхний правый"); + PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Нижний правый"); + PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Калибровка успешна"); + PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Ошибка калибровки"); + + PROGMEM Language_Str MSG_DRIVER_BACKWARD = _UxGT(" драйвер назад"); + + PROGMEM Language_Str MSG_SD_CARD = _UxGT("SD Карта"); + PROGMEM Language_Str MSG_USB_DISK = _UxGT("USB Диск"); } #if FAN_COUNT == 1 diff --git a/Marlin/src/lcd/language/language_sk.h b/Marlin/src/lcd/language/language_sk.h index d0fdf5749cf2..717fa49b3375 100644 --- a/Marlin/src/lcd/language/language_sk.h +++ b/Marlin/src/lcd/language/language_sk.h @@ -30,6 +30,13 @@ * * Translated by Michal Holeš, Farma MaM * https://www.facebook.com/farmamam + * + * Substitutions are applied for the following characters when used + * in menu items that call lcd_put_u8str_ind_P with an index: + * + * = 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) */ #define DISPLAY_CHARSET_ISO10646_SK @@ -37,7 +44,7 @@ namespace Language_sk { using namespace Language_en; // Inherit undefined strings from English constexpr uint8_t CHARSIZE = 2; - PROGMEM Language_Str LANGUAGE = _UxGT("Slovak"); + PROGMEM Language_Str LANGUAGE = _UxGT("Slovenčina"); PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" pripravená."); PROGMEM Language_Str MSG_YES = _UxGT("ÁNO"); @@ -57,7 +64,7 @@ namespace Language_sk { PROGMEM Language_Str MSG_MAIN = _UxGT("Hlavná ponuka"); PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Pokročilé nastav."); PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Konfigurácia"); - PROGMEM Language_Str MSG_AUTOSTART = _UxGT("Auto-štart"); + PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Auto-štart"); PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Uvolniť motory"); PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Ponuka ladenia"); PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Test uk. priebehu"); @@ -66,15 +73,23 @@ namespace Language_sk { PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Domov os Y"); PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Domov os Z"); PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Auto-zarovn. Z"); - PROGMEM Language_Str MSG_ASSISTED_TRAMMING = _UxGT("Asist. vyrovnanie"); + PROGMEM Language_Str MSG_ITERATION = _UxGT("Iterácia G34: %i"); + PROGMEM Language_Str MSG_DECREASING_ACCURACY = _UxGT("Klesajúca presnosť!"); + PROGMEM Language_Str MSG_ACCURACY_ACHIEVED = _UxGT("Dosiahnutá presnosť"); PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Parkovanie XYZ"); PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Kliknutím začnete"); PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Ďalší bod"); PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Vyrovnanie hotové!"); PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Výška rovnania"); - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Nastaviť ofsety"); + PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Nastav. dom. ofsety"); + PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("X Ofset"); + PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Y Ofset"); + PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Z Ofset"); PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Ofsety nastavené"); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Nastaviť začiatok"); + PROGMEM Language_Str MSG_TRAMMING_WIZARD = _UxGT("Spriev. vyrovn."); + PROGMEM Language_Str MSG_SELECT_ORIGIN = _UxGT("Vyberte začiatok"); + PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Posl. hodnota "); #if PREHEAT_COUNT PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Zahriať ") PREHEAT_1_LABEL; PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Zahriať ") PREHEAT_1_LABEL " ~"; @@ -94,15 +109,21 @@ namespace Language_sk { #endif PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Vlastná teplota"); PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Schladiť"); + PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Frekvencia"); PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Nastavenie lasera"); - PROGMEM Language_Str MSG_LASER_OFF = _UxGT("Vypnúť laser"); - PROGMEM Language_Str MSG_LASER_ON = _UxGT("Zapnúť laser"); - PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Výkon lasera"); PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Nastavenie vretena"); - PROGMEM Language_Str MSG_SPINDLE_OFF = _UxGT("Vypnúť vreteno"); - PROGMEM Language_Str MSG_SPINDLE_ON = _UxGT("Zapnúť vreteno"); + PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Výkon lasera"); PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Výkon vretena"); + PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Prepnúť laser"); + PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Prepnúť odsávanie"); + PROGMEM Language_Str MSG_LASER_ASSIST_TOGGLE = _UxGT("Prepnúť ofuk"); + PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Test. impulz ms"); + PROGMEM Language_Str MSG_LASER_FIRE_PULSE = _UxGT("Vystreliť impulz"); + PROGMEM Language_Str MSG_FLOWMETER_FAULT = _UxGT("Chyba chladenia"); + PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Prepnúť vreteno"); + PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Prepnúť odsávanie"); + PROGMEM Language_Str MSG_SPINDLE_FORWARD = _UxGT("Dopredný chod"); PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Spätný chod"); PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Zapnúť napájanie"); PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Vypnúť napájanie"); @@ -111,7 +132,11 @@ namespace Language_sk { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Posunúť osy"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Vyrovnanie podložky"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Vyrovnať podložku"); - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Vyrovnať rohy"); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Asist. vyrovnanie"); + PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Zdvyhnite podl., kým sa nezopne sonda"); + PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("Rohy sú vrámci odchyl. Vyrovnajte podl."); + PROGMEM Language_Str MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Dobré body: "); + PROGMEM Language_Str MSG_BED_TRAMMING_LAST_Z = _UxGT("Posl. Z: "); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Ďalší roh"); PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Editor sieťe bodov"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Upraviť sieť bodov"); @@ -120,7 +145,7 @@ namespace Language_sk { PROGMEM Language_Str MSG_MESH_X = _UxGT("Index X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("Index Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Hodnota Z"); - PROGMEM Language_Str MSG_USER_MENU = _UxGT("Vlastné príkazy"); + PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Vlastné príkazy"); PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 Test sondy"); PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 Bod"); PROGMEM Language_Str MSG_M48_OUT_OF_BOUNDS = _UxGT("Sonda mimo hraníc"); @@ -131,6 +156,7 @@ namespace Language_sk { PROGMEM Language_Str MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplikácia"); PROGMEM Language_Str MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Zrkadlená kópia"); PROGMEM Language_Str MSG_IDEX_MODE_FULL_CTRL = _UxGT("Plná kontrola"); + PROGMEM Language_Str MSG_IDEX_DUPE_GAP = _UxGT("Duplik. medz.-X"); PROGMEM Language_Str MSG_HOTEND_OFFSET_X = _UxGT("2. tryska X"); PROGMEM Language_Str MSG_HOTEND_OFFSET_Y = _UxGT("2. tryska Y"); PROGMEM Language_Str MSG_HOTEND_OFFSET_Z = _UxGT("2. tryska Z"); @@ -139,6 +165,7 @@ namespace Language_sk { PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("UBL rovnanie"); PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Vyrovnávam bod"); PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Manuálna sieť bodov"); + PROGMEM Language_Str MSG_UBL_MESH_WIZARD = _UxGT("Spriev. UBL rovnan."); PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Položte a zmerajte"); PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Zmerajte"); PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Odstráňte a zmerajte"); @@ -240,18 +267,26 @@ namespace Language_sk { PROGMEM Language_Str MSG_MOVE_E = _UxGT("Extrudér"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Extrudér *"); PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Hotend je studený"); - PROGMEM Language_Str MSG_MOVE_Z_DIST = _UxGT("Posunúť o %smm"); + PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Posunúť o %smm"); PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Posunúť o 0,1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Posunúť o 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Posunúť o 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Posunúť o 100mm"); + PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Posunúť o 0,001in"); + PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Posunúť o 0,01in"); + PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Posunúť o 0,1in"); PROGMEM Language_Str MSG_SPEED = _UxGT("Rýchlosť"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Výška podl."); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Tryska"); PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Tryska ~"); - PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Tryska zaparkovná"); + PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Tryska zaparkovaná"); PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Záložná tryska"); PROGMEM Language_Str MSG_BED = _UxGT("Podložka"); PROGMEM Language_Str MSG_CHAMBER = _UxGT("Komora"); + PROGMEM Language_Str MSG_COOLER = _UxGT("Chladen. lasera"); + PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Prepnúť chladenie"); + PROGMEM Language_Str MSG_FLOWMETER_SAFETY = _UxGT("Bezpeč. prietok"); + PROGMEM Language_Str MSG_LASER = _UxGT("Laser"); PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Rýchlosť vent."); PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Rýchlosť vent. ~"); PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Ulož. vent. ~"); @@ -259,7 +294,7 @@ namespace Language_sk { PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Rýchlosť ex. vent. ~"); PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Vent. riad. jedn."); PROGMEM Language_Str MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Voľno. rýchl."); - PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Auto-režím"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Auto-režim"); PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("Aktív. rýchl."); PROGMEM Language_Str MSG_CONTROLLER_FAN_DURATION = _UxGT("Doba nečinnosti"); PROGMEM Language_Str MSG_FLOW = _UxGT("Prietok"); @@ -313,8 +348,8 @@ namespace Language_sk { PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Teplota"); PROGMEM Language_Str MSG_MOTION = _UxGT("Pohyb"); PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filament"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E v mm³"); - PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("E Limit v mm³"); + PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E v mm") SUPERSCRIPT_THREE; + PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("E Limit v mm") SUPERSCRIPT_THREE; PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT_E = _UxGT("E Limit *"); PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Priem. fil."); PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Priem. fil. *"); @@ -352,11 +387,13 @@ namespace Language_sk { PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Hotovo"); PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Naspäť"); PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Pokračovať"); + PROGMEM Language_Str MSG_BUTTON_SKIP = _UxGT("Preskočiť"); PROGMEM Language_Str MSG_PAUSING = _UxGT("Pozastavujem..."); PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Pozastaviť tlač"); PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Obnoviť tlač"); PROGMEM Language_Str MSG_HOST_START_PRINT = _UxGT("Spustiť z hosta"); PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Zastaviť tlač"); + PROGMEM Language_Str MSG_END_LOOPS = _UxGT("Koniec opak. sluč."); PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("Tlačím objekt"); PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("Zrušiť objekt"); PROGMEM Language_Str MSG_CANCEL_OBJECT_N = _UxGT("Zrušiť objekt ="); @@ -435,6 +472,7 @@ namespace Language_sk { PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("X ofset"); PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Y ofset"); PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Z ofset"); + PROGMEM Language_Str MSG_MOVE_NOZZLE_TO_BED = _UxGT("Pos. trysku k podl."); PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Babystep X"); PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Babystep Y"); PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Babystep Z"); @@ -445,6 +483,8 @@ namespace Language_sk { PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("TEPLOTNÝ SKOK"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("TEPLOTNÝ SKOK PODL."); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("TEPLOTNÝ SKOK KOMO."); + PROGMEM Language_Str MSG_THERMAL_RUNAWAY_COOLER = _UxGT("TEPLOTNÝ SKOK CHLAD."); + PROGMEM Language_Str MSG_COOLING_FAILED = _UxGT("Ochladz. zlyhalo"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Chyba: MAXTEMP"); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Chyba: MINTEMP"); PROGMEM Language_Str MSG_HALTED = _UxGT("TLAČIAREŇ ZASTAVENÁ"); @@ -460,6 +500,7 @@ namespace Language_sk { PROGMEM Language_Str MSG_PROBE_COOLING = _UxGT("Ochladz. sondy..."); PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Ohrev komory..."); PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Ochladz. komory..."); + PROGMEM Language_Str MSG_LASER_COOLING = _UxGT("Ochladz. lasera..."); PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Delta kalibrácia"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Kalibrovať X"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Kalibrovať Y"); @@ -479,6 +520,7 @@ namespace Language_sk { PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Bilineárne rovnanie"); PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("UBL rovnanie"); PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Mriežkové rovnanie"); + PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Mriežka dokončená"); PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Štatistika"); PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Info. o doske"); PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Termistory"); @@ -588,7 +630,7 @@ namespace Language_sk { PROGMEM Language_Str MSG_PASSWORD_SET = _UxGT("Heslo je "); PROGMEM Language_Str MSG_START_OVER = _UxGT("Začať odznova"); PROGMEM Language_Str MSG_REMINDER_SAVE_SETTINGS = _UxGT("Nezabudnite uložiť!"); - PROGMEM Language_Str MSG_PASSWORD_REMOVED = _UxGT("Heslo odstránene"); + PROGMEM Language_Str MSG_PASSWORD_REMOVED = _UxGT("Heslo odstránené"); // // Filament Change screens show up to 3 lines on a 4-line display @@ -643,4 +685,19 @@ namespace Language_sk { #endif PROGMEM Language_Str MSG_REHEAT = _UxGT("Zohriať"); PROGMEM Language_Str MSG_REHEATING = _UxGT("Zohrievanie..."); + + PROGMEM Language_Str MSG_PROBE_WIZARD = _UxGT("Sprievodca sondy Z"); + PROGMEM Language_Str MSG_PROBE_WIZARD_PROBING = _UxGT("Referencia Z"); + PROGMEM Language_Str MSG_PROBE_WIZARD_MOVING = _UxGT("Presúvam na pozíciu"); + + PROGMEM Language_Str MSG_SOUND = _UxGT("Zvuk"); + + PROGMEM Language_Str MSG_TOP_LEFT = _UxGT("Ľavý horný"); + PROGMEM Language_Str MSG_BOTTOM_LEFT = _UxGT("Ľavý dolný"); + PROGMEM Language_Str MSG_TOP_RIGHT = _UxGT("Pravý horný"); + PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Pravý dolný"); + PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Kalibrácia dokončená"); + PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Kalibrácia zlyhala"); + + PROGMEM Language_Str MSG_DRIVER_BACKWARD = _UxGT(" spätný chod ovl."); } diff --git a/Marlin/src/lcd/language/language_sv.h b/Marlin/src/lcd/language/language_sv.h new file mode 100644 index 000000000000..baa0f645062c --- /dev/null +++ b/Marlin/src/lcd/language/language_sv.h @@ -0,0 +1,681 @@ +/** + * 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 för more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * Swedish + * + * LCD Menu Messages + * See also https://marlinfw.org/docs/development/lcd_language.html + */ + +#define DISPLAY_CHARSET_ISO10646_1 + +namespace Language_sv { + using namespace Language_en; // Inherit undefined strings from English + + constexpr uint8_t CHARSIZE = 2; + PROGMEM Language_Str LANGUAGE = _UxGT("Swedish"); + + PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" Redo."); + PROGMEM Language_Str MSG_MARLIN = _UxGT("Marlin"); + PROGMEM Language_Str MSG_YES = _UxGT("JA"); + PROGMEM Language_Str MSG_NO = _UxGT("NEJ"); + PROGMEM Language_Str MSG_BACK = _UxGT("Bakåt"); + PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("Avbryter..."); + PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Media Instatt"); + PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Media Borttaget"); + PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Väntar på media"); + PROGMEM Language_Str MSG_SD_INIT_FAIL = _UxGT("SD init misslyckades"); + PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Media läsningsfel"); + PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("USB enhet borttagen"); + PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("USB start misslyckad"); + PROGMEM Language_Str MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Underanrop överskriden"); + PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Slutstop"); // Max length 8 characters + PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("Mjuk slutstopp"); + PROGMEM Language_Str MSG_MAIN = _UxGT("Huvud"); + PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Advancerade inställningar"); + PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Konfiguration"); + PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Autostarta Filer"); + PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Inaktivera Stegare"); + PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Debug Meny"); + PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Framstegsindikator Test"); + PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Auto Hem"); + PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Hem X"); + PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Hem Y"); + PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Hem Z"); + PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Auto Z-Justering"); + PROGMEM Language_Str MSG_ITERATION = _UxGT("G34 Iteration: %i"); + PROGMEM Language_Str MSG_DECREASING_ACCURACY = _UxGT("Noggrannhet Minskar!"); + PROGMEM Language_Str MSG_ACCURACY_ACHIEVED = _UxGT("Noggrannhet uppnådd"); + PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Hemning XYZ"); + PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Klicka för att börja"); + PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Nästa Punkt"); + PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Nivellering Färdig!"); + PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Falna Höjd"); + PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Sätt Hem Offset"); + PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Offset Tillämpad"); + PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Sätt Origo"); + PROGMEM Language_Str MSG_TRAMMING_WIZARD = _UxGT("Justerings Wizard"); + PROGMEM Language_Str MSG_SELECT_ORIGIN = _UxGT("Välj Origo"); + PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Senaste värde "); + + #if PREHEAT_COUNT + PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Förvärmning ") PREHEAT_1_LABEL; + PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Förvärmning ") PREHEAT_1_LABEL " ~"; + PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Förvärmning ") PREHEAT_1_LABEL _UxGT(" Stoppa"); + PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Förvärmning ") PREHEAT_1_LABEL _UxGT(" Stoppa ~"); + PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Förvärmning ") PREHEAT_1_LABEL _UxGT(" Alla"); + PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Förvärmning ") PREHEAT_1_LABEL _UxGT(" Bädd"); + PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Förvärmning ") PREHEAT_1_LABEL _UxGT(" Konf"); + + PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("Förvärmning $"); + PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("Förvärmning $ ~"); + PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("Förvärmning $ Stoppa"); + PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("Förvärmning $ Stoppa ~"); + PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("Förvärmning $ Alla"); + PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("Förvärmning $ Bädd"); + PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("Förvärmning $ Donf"); + #endif + + PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Förvärmning Anpassad"); + PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Nedkylning"); + PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Frekvens"); + PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Laser kontroll"); + PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Spindel Kontroll"); + PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Laser Styrka"); + PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Spindel Styrka"); + PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Växla Laser"); + PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Test Puls ms"); + PROGMEM Language_Str MSG_LASER_FIRE_PULSE = _UxGT("Avfyra Puls"); + PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Växla Spindel"); + PROGMEM Language_Str MSG_SPINDLE_FORWARD = _UxGT("Spindel Framåt"); + PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Spindel Bakåt"); + PROGMEM Language_Str MSG_LASER_OFF = _UxGT("Laser Av"); + PROGMEM Language_Str MSG_LASER_ON = _UxGT("Laser På"); + PROGMEM Language_Str MSG_SPINDLE_OFF = _UxGT("Spindel Av"); + PROGMEM Language_Str MSG_SPINDLE_ON = _UxGT("Spindel På"); + PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Sätt på ström"); + PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Stäng av ström"); + PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Extrudera"); + PROGMEM Language_Str MSG_RETRACT = _UxGT("Dra tillbaka"); + PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Flytta Axel"); + PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Bädd Nivellering"); + PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Nivellera Bädd"); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Bädd Justering"); + PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Höj Bädd tills nästa Sond Triggad"); + PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("Alla Hörn inom Tolerans. Nivellering Bädd"); + PROGMEM Language_Str MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Bra Punkter: "); + PROGMEM Language_Str MSG_BED_TRAMMING_LAST_Z = _UxGT("Senaste Z: "); + PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Nästa Hörn"); + PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Nät Redigerare"); + PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Redigera Nät"); + PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Nätredigering Stoppad"); + PROGMEM Language_Str MSG_PROBING_MESH = _UxGT("Sonderingspunkt"); + PROGMEM Language_Str MSG_MESH_X = _UxGT("Index X"); + PROGMEM Language_Str MSG_MESH_Y = _UxGT("Index Y"); + PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Z Värde"); + PROGMEM Language_Str MSG_USER_MENU = _UxGT("Anpassade Kommandon"); + PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 Sond Test"); + PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 Punkt"); + PROGMEM Language_Str MSG_M48_OUT_OF_BOUNDS = _UxGT("Sond utan för gränser"); + PROGMEM Language_Str MSG_M48_DEVIATION = _UxGT("Avvikelse"); + PROGMEM Language_Str MSG_IDEX_MENU = _UxGT("IDEX Läge"); + PROGMEM Language_Str MSG_OFFSETS_MENU = _UxGT("Verktygsoffset"); + PROGMEM Language_Str MSG_IDEX_MODE_AUTOPARK = _UxGT("Auto-Parkera"); + PROGMEM Language_Str MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplicering"); + PROGMEM Language_Str MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Speglad Kopia"); + PROGMEM Language_Str MSG_IDEX_MODE_FULL_CTRL = _UxGT("Full Kontroll"); + PROGMEM Language_Str MSG_IDEX_DUPE_GAP = _UxGT("Duplicera X-Avstånd"); + PROGMEM Language_Str MSG_HOTEND_OFFSET_X = _UxGT("2:a Munstycke X"); + PROGMEM Language_Str MSG_HOTEND_OFFSET_Y = _UxGT("2:a Munstycke Y"); + PROGMEM Language_Str MSG_HOTEND_OFFSET_Z = _UxGT("2:a Munstycke Z"); + PROGMEM Language_Str MSG_UBL_DOING_G29 = _UxGT("Utför G29"); + PROGMEM Language_Str MSG_UBL_TOOLS = _UxGT("UBL Verktyg"); + PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Enad Bädd Nivellering (UBL)"); + PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Lutningspunkt"); + PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Manuellt skapa nät"); + PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Placera Shim & Mät"); + PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Mät"); + PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Ta bort & Mät bädd"); + PROGMEM Language_Str MSG_UBL_MOVING_TO_NEXT = _UxGT("Flyttar till nästa"); + PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("Aktivera UBL"); + PROGMEM Language_Str MSG_UBL_DEACTIVATE_MESH = _UxGT("Avaktivera UBL"); + PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = _UxGT("Bädd Temp"); + PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Bädd Temp"); + PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = _UxGT("Hetände Temp"); + PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Hetände Temp"); + PROGMEM Language_Str MSG_UBL_MESH_EDIT = _UxGT("Nät Redigera"); + PROGMEM Language_Str MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Redigera Anpassat Nät"); + PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("Finjustera Nät"); + PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Färdig Redigera Nät"); + PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Bygg Anpassat Nät"); + PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("Bygg Nät"); + PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Bygg Nät ($)"); + PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Bygg Kallt Nät"); + PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Justera Nät Höjd"); + PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Höjd Antal"); + PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Validera Nät"); + PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Validera Nät ($)"); + PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Validera Anpassat Nät"); + PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26 Värma Bädd"); + PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("G26 Värma Munstycke"); + PROGMEM Language_Str MSG_G26_MANUAL_PRIME = _UxGT("Manuel grundning..."); + PROGMEM Language_Str MSG_G26_FIXED_LENGTH = _UxGT("Fastlängd Grundning"); + PROGMEM Language_Str MSG_G26_PRIME_DONE = _UxGT("Färdig Grundning"); + PROGMEM Language_Str MSG_G26_CANCELED = _UxGT("G26 Avbruten"); + PROGMEM Language_Str MSG_G26_LEAVING = _UxGT("Nivellera G26"); + PROGMEM Language_Str MSG_UBL_CONTINUE_MESH = _UxGT("Fortsätt Bädd Nät"); + PROGMEM Language_Str MSG_UBL_MESH_LEVELING = _UxGT("Nät Nivellering"); + PROGMEM Language_Str MSG_UBL_3POINT_MESH_LEVELING = _UxGT("3-Punkts Nivellering"); + PROGMEM Language_Str MSG_UBL_GRID_MESH_LEVELING = _UxGT("Rutnät Nivellering"); + PROGMEM Language_Str MSG_UBL_MESH_LEVEL = _UxGT("Nivellera Nät"); + PROGMEM Language_Str MSG_UBL_SIDE_POINTS = _UxGT("Sidopunkter"); + PROGMEM Language_Str MSG_UBL_MAP_TYPE = _UxGT("Kart Typ"); + PROGMEM Language_Str MSG_UBL_OUTPUT_MAP = _UxGT("Utmatning Nät Map"); + PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Utmatning för Värd"); + PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Utmatning för CSV"); + PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Utanför skrivare Backup"); + PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("Utmatning UBL Info"); + PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Ifyllnad Mängd"); + PROGMEM Language_Str MSG_UBL_MANUAL_FILLIN = _UxGT("Manuell Ifyllnad"); + PROGMEM Language_Str MSG_UBL_SMART_FILLIN = _UxGT("Smart Ifyllnad"); + PROGMEM Language_Str MSG_UBL_FILLIN_MESH = _UxGT("Ifyllnad Nät"); + PROGMEM Language_Str MSG_UBL_INVALIDATE_ALL = _UxGT("Ogiltigförklara Alla"); + PROGMEM Language_Str MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Ogiltigförklara Närmast"); + PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("Finjustera Alla"); + PROGMEM Language_Str MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Finjustera Närmast"); + PROGMEM Language_Str MSG_UBL_STORAGE_MESH_MENU = _UxGT("Nät Lagra"); + PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Minnesöppning"); + PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Ladda Bädd Nät"); + PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Spara Bädd Nät"); + PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("Nät %i Ladda"); + PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("Nät %i Sparad"); + PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("Ingen Lagring"); + PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Fel: UBL Sparad"); + PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Fel: UBL Återställd"); + PROGMEM Language_Str MSG_UBL_Z_OFFSET = _UxGT("Z-Offset: "); + PROGMEM Language_Str MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Z-Offset Stoppad"); + PROGMEM Language_Str MSG_UBL_STEP_BY_STEP_MENU = _UxGT("Steg-för-Steg UBL"); + PROGMEM Language_Str MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1. Bygg Kallt Nät"); + PROGMEM Language_Str MSG_UBL_2_SMART_FILLIN = _UxGT("2. Smart Ifyllnad"); + PROGMEM Language_Str MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3. Validera Nät"); + PROGMEM Language_Str MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4. Finjustera Alla"); + PROGMEM Language_Str MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5. Validera Nät"); + PROGMEM Language_Str MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6. Finjustera Alla"); + PROGMEM Language_Str MSG_UBL_7_SAVE_MESH = _UxGT("7. Spara Bädd Nät"); + + PROGMEM Language_Str MSG_LED_CONTROL = _UxGT("LED Kontroll"); + PROGMEM Language_Str MSG_LEDS = _UxGT("Ljus"); + PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("Ljus Förinställd"); + PROGMEM Language_Str MSG_SET_LEDS_RED = _UxGT("Röd"); + PROGMEM Language_Str MSG_SET_LEDS_ORANGE = _UxGT("Orange"); + PROGMEM Language_Str MSG_SET_LEDS_YELLOW = _UxGT("Gul"); + PROGMEM Language_Str MSG_SET_LEDS_GREEN = _UxGT("Grön"); + PROGMEM Language_Str MSG_SET_LEDS_BLUE = _UxGT("Blå"); + PROGMEM Language_Str MSG_SET_LEDS_INDIGO = _UxGT("Indigo"); + PROGMEM Language_Str MSG_SET_LEDS_VIOLET = _UxGT("Violet"); + PROGMEM Language_Str MSG_SET_LEDS_WHITE = _UxGT("Vitt"); + PROGMEM Language_Str MSG_SET_LEDS_DEFAULT = _UxGT("Standard"); + PROGMEM Language_Str MSG_LED_CHANNEL_N = _UxGT("Kanal ="); + PROGMEM Language_Str MSG_LEDS2 = _UxGT("Ljus #2"); + PROGMEM Language_Str MSG_NEO2_PRESETS = _UxGT("Ljus #2 Förinställd"); + PROGMEM Language_Str MSG_NEO2_BRIGHTNESS = _UxGT("Ljusstyrka"); + PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Anpassat Ljus"); + PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Rör Intensitet"); + PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Grön Intensitet"); + PROGMEM Language_Str MSG_INTENSITY_B = _UxGT("Blå Intensitet"); + PROGMEM Language_Str MSG_INTENSITY_W = _UxGT("Vit Intensitet"); + PROGMEM Language_Str MSG_LED_BRIGHTNESS = _UxGT("Brightness"); + + PROGMEM Language_Str MSG_MOVING = _UxGT("Flyttar..."); + PROGMEM Language_Str MSG_FREE_XY = _UxGT("Fri XY"); + PROGMEM Language_Str MSG_MOVE_X = _UxGT("Flytta X"); + PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Flytta Y"); + PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Flytta Z"); + PROGMEM Language_Str MSG_MOVE_E = _UxGT("Extruder"); + PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Extruder *"); + PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Hetände för kall"); + PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Flytta %smm"); + PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Flytta 0.1mm"); + PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Flytta 1mm"); + PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Flytta 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Flytta 100mm"); + PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Flytta 0.001tum"); + PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Flytta 0.01tum"); + PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Flytta 0.1tum"); + PROGMEM Language_Str MSG_SPEED = _UxGT("Hastighet"); + PROGMEM Language_Str MSG_BED_Z = _UxGT("Bädd Z"); + PROGMEM Language_Str MSG_NOZZLE = _UxGT("Munstycke"); + PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Munstycke ~"); + PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Munstycke Parkerad"); + PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Munstycke Standby"); + PROGMEM Language_Str MSG_BED = _UxGT("Bädd"); + PROGMEM Language_Str MSG_CHAMBER = _UxGT("Inkapsling"); + PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Fläkt Hastighet"); + PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Fläkt Hastighet ~"); + PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Lagrad Fläkt ~"); + PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Extra Fläkt Hastighet"); + PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Extra Fläkt Hastighet ~"); + PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Kontroller Fläkt"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Overksam Hastighet"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Auto läga"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("Aktive Hastighet"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_DURATION = _UxGT("Overksam Period"); + PROGMEM Language_Str MSG_FLOW = _UxGT("Flöde"); + PROGMEM Language_Str MSG_FLOW_N = _UxGT("Flöde ~"); + PROGMEM Language_Str MSG_CONTROL = _UxGT("Kontroll"); + PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); + PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); + PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Fakt"); + PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Autotemp"); + PROGMEM Language_Str MSG_LCD_ON = _UxGT("På"); + PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Av"); + PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("PID Autojustera"); + PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("PID Autojustera *"); + PROGMEM Language_Str MSG_PID_AUTOTUNE_DONE = _UxGT("PID tuning done"); + PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Autojustera misslyckad. Dålig extruder."); + PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Autojustera misslyckad. Temperatur för hög."); + PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("Autojustera misslyckad! Tidsgräns."); + PROGMEM Language_Str MSG_SELECT = _UxGT("Välj"); + PROGMEM Language_Str MSG_SELECT_E = _UxGT("Välj *"); + PROGMEM Language_Str MSG_ACC = _UxGT("Accel"); + PROGMEM Language_Str MSG_JERK = _UxGT("Ryck"); + PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-Ryck"); + PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-Ryck"); + PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-Ryck"); + PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-Ryck"); + PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Knutpunkt Avv"); + PROGMEM Language_Str MSG_VELOCITY = _UxGT("Hastighet"); + PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; + PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; + PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; + PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; + PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vmax *"); + PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin"); + PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("VTrav Min"); + PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Acceleration"); + PROGMEM Language_Str MSG_AMAX_A = _UxGT("Amax ") LCD_STR_A; + PROGMEM Language_Str MSG_AMAX_B = _UxGT("Amax ") LCD_STR_B; + PROGMEM Language_Str MSG_AMAX_C = _UxGT("Amax ") LCD_STR_C; + PROGMEM Language_Str MSG_AMAX_E = _UxGT("Amax ") LCD_STR_E; + PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Amax *"); + PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-Dra tillbaka"); + PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("A-Färdas"); + PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("Frekvens max"); + PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Flöde min"); + PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Steg/mm"); + PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" Steg/mm"); + PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" Steg/mm"); + PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" Steg/mm"); + PROGMEM Language_Str MSG_E_STEPS = _UxGT("E Steg/mm"); + PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* Steg/mm"); + PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatur"); + PROGMEM Language_Str MSG_MOTION = _UxGT("Rörelse"); + PROGMEM Language_Str MSG_FILAMENT = _UxGT("Tråd"); + PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E i mm³"); + PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("E Gräns i mm³"); + PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT_E = _UxGT("E Gräns *"); + PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Tråd Dia."); + PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Tråd Dia. *"); + PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Lossa mm"); + PROGMEM Language_Str MSG_FILAMENT_LOAD = _UxGT("Ladda mm"); + PROGMEM Language_Str MSG_ADVANCE_K = _UxGT("Advancera K"); + PROGMEM Language_Str MSG_ADVANCE_K_E = _UxGT("Advancera K *"); + PROGMEM Language_Str MSG_CONTRAST = _UxGT("LCD Kontrast"); + PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Spara Inställningar"); + PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Ladda Inställningar"); + PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Återställ Standard"); + PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Initiera EEPROM"); + PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("EEPROM CRC Fel"); + PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("EEPROM Index Fel"); + PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("EEPROM Version Fel"); + PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Inställningar Lagrad"); + PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Media Uppdatera"); + PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Återställ Skrivare"); + PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Uppdatera"); + PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Info Skärm"); + PROGMEM Language_Str MSG_PREPARE = _UxGT("Förbered"); + PROGMEM Language_Str MSG_TUNE = _UxGT("Justera"); + PROGMEM Language_Str MSG_POWER_MONITOR = _UxGT("Ström övervakning"); + PROGMEM Language_Str MSG_CURRENT = _UxGT("Ström"); + PROGMEM Language_Str MSG_VOLTAGE = _UxGT("Spänning"); + PROGMEM Language_Str MSG_POWER = _UxGT("Ström"); + PROGMEM Language_Str MSG_START_PRINT = _UxGT("Start Utskrift"); + PROGMEM Language_Str MSG_BUTTON_NEXT = _UxGT("Nästa"); + PROGMEM Language_Str MSG_BUTTON_INIT = _UxGT("Initiera"); + PROGMEM Language_Str MSG_BUTTON_STOP = _UxGT("Stoppa"); + PROGMEM Language_Str MSG_BUTTON_PRINT = _UxGT("Skriv"); + PROGMEM Language_Str MSG_BUTTON_RESET = _UxGT("Återställa"); + PROGMEM Language_Str MSG_BUTTON_IGNORE = _UxGT("Ignorera"); + PROGMEM Language_Str MSG_BUTTON_CANCEL = _UxGT("Avbryt"); + PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Färdig"); + PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Bakåt"); + PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Fortsätt"); + PROGMEM Language_Str MSG_BUTTON_SKIP = _UxGT("Hoppa över"); + PROGMEM Language_Str MSG_PAUSING = _UxGT("Paus.."); + PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Pausera Utskrift"); + PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Återuppta Utskrift"); + PROGMEM Language_Str MSG_HOST_START_PRINT = _UxGT("Värd Start"); + PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Stoppa Utskrift"); + PROGMEM Language_Str MSG_END_LOOPS = _UxGT("Slut Upprepningsloop"); + PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("Skriver Objekt"); + PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("Avbryt Objekt"); + PROGMEM Language_Str MSG_CANCEL_OBJECT_N = _UxGT("Avbryt Objekt ="); + PROGMEM Language_Str MSG_OUTAGE_RECOVERY = _UxGT("Ström Avbrott"); + PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Skriv fråm Media"); + PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("Inget Media"); + PROGMEM Language_Str MSG_DWELL = _UxGT("Sov..."); + PROGMEM Language_Str MSG_USERWAIT = _UxGT("Klick för att återuppta..."); + PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("Utskrift Pausad"); + PROGMEM Language_Str MSG_PRINTING = _UxGT("Skriver..."); + PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Utskrift Avbruten"); + PROGMEM Language_Str MSG_PRINT_DONE = _UxGT("Utskrift Färdig"); + PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Ingen Flytt."); + PROGMEM Language_Str MSG_KILLED = _UxGT("DÖDAD. "); + PROGMEM Language_Str MSG_STOPPED = _UxGT("STOPPAD. "); + PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Dra tillbaka mm"); + PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Byt Dra.mm"); + PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Dra tillbaka V"); + PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Hoppa mm"); + PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("Åter dra tillbaka. mm"); + PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Byt åter dra t. mm"); + PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Återdrat. V"); + PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("Byt åter dra. V"); + PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Auto-Dra-tillbka"); + PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Byt Längd"); + PROGMEM Language_Str MSG_FILAMENT_SWAP_EXTRA = _UxGT("Byt Extra"); + PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Rensa Längd"); + PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Byt verktyg"); + PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Z Höj"); + PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Grund Hastighet"); + PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Återgå Hastighet"); + PROGMEM Language_Str MSG_FILAMENT_PARK_ENABLED = _UxGT("Parkera Huvud"); + PROGMEM Language_Str MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Återgår Hastighet"); + PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Fläkt Hastighet"); + PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Fläkt Tid"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_ON = _UxGT("Auto PÅ"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_OFF = _UxGT("Auto AV"); + PROGMEM Language_Str MSG_TOOL_MIGRATION = _UxGT("Verktyg Migration"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_AUTO = _UxGT("Auto-migration"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_END = _UxGT("Senast Extruder"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_SWAP = _UxGT("Migrera till *"); + PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Byt Tråd"); + PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Byt Tråd *"); + PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Ladda Tråd"); + PROGMEM Language_Str MSG_FILAMENTLOAD_E = _UxGT("Ladda *"); + PROGMEM Language_Str MSG_FILAMENTUNLOAD = _UxGT("Lossa Tråd"); + PROGMEM Language_Str MSG_FILAMENTUNLOAD_E = _UxGT("Lossa *"); + PROGMEM Language_Str MSG_FILAMENTUNLOAD_ALL = _UxGT("Lossa All"); + PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Bifoga Media"); + PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Byt Media"); + PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("Släpp Media"); + PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Z Sond Utanför Bädd"); + PROGMEM Language_Str MSG_SKEW_FACTOR = _UxGT("Skev Faktor"); + PROGMEM Language_Str MSG_BLTOUCH = _UxGT("BLTouch"); + PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("Själv-Test"); + PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Återställ"); + PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("Stuva undan"); + PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("Fällut"); + PROGMEM Language_Str MSG_BLTOUCH_SW_MODE = _UxGT("SW-Läge"); + PROGMEM Language_Str MSG_BLTOUCH_5V_MODE = _UxGT("5V-Läge"); + PROGMEM Language_Str MSG_BLTOUCH_OD_MODE = _UxGT("OD-Läge"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE = _UxGT("Läge-Lägring"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Sätt BLTouch to 5V"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Sätt BLTouch to OD"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_ECHO = _UxGT("Reportera Dränering"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_CHANGE = _UxGT("FARA: Dålig inställningar kan orsaka skada! Fortsätt ändå?"); + PROGMEM Language_Str MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); + PROGMEM Language_Str MSG_TOUCHMI_INIT = _UxGT("Initiera TouchMI"); + PROGMEM Language_Str MSG_TOUCHMI_ZTEST = _UxGT("Z Offset Test"); + PROGMEM Language_Str MSG_TOUCHMI_SAVE = _UxGT("Spara"); + PROGMEM Language_Str MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("Fällut TouchMI"); + PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("Fällut Z-Sond"); + PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("Stuva undan Z-Sond"); + PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Hem %s%s%s Först"); + PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("Sond Offsets"); + PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("Sond X Offset"); + PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Sond Y Offset"); + PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Sond Z Offset"); + PROGMEM Language_Str MSG_MOVE_NOZZLE_TO_BED = _UxGT("Flytta Munstycke till Bädd"); + PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Småsteg X"); + PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Småsteg Y"); + PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Småsteg Z"); + PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Total"); + PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Slutstopp Avbrott"); + PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Värma Misslyckad"); + PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Fel: REDUNDANT TEMP"); + PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("TERMISK ÖVERDRIFT"); + PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("BÄDD TERMISK ÖVERDRIFT"); + PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("KAMMARE T. ÖVERDRIFT"); + PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Fel: MAXTEMP"); + PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Fel: MINTEMP"); + PROGMEM Language_Str MSG_HALTED = _UxGT("Utskrift stoppad"); + PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Snälla Återställ"); + PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); // One character only + PROGMEM Language_Str MSG_SHORT_HOUR = _UxGT("t"); // One character only + PROGMEM Language_Str MSG_SHORT_MINUTE = _UxGT("m"); // One character only + PROGMEM Language_Str MSG_HEATING = _UxGT("Värmer..."); + PROGMEM Language_Str MSG_COOLING = _UxGT("Kyler..."); + PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Bädd Värmer..."); + PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Bädd Kyler..."); + PROGMEM Language_Str MSG_PROBE_HEATING = _UxGT("Sond Värmer..."); + PROGMEM Language_Str MSG_PROBE_COOLING = _UxGT("Sond Kyler..."); + PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Kammare Värmer..."); + PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Kammare Kyler..."); + PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Delta Kalibrering"); + PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Kalibrera X"); + PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Kalibrera Y"); + PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Kalibrera Z"); + PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibrera Center"); + PROGMEM Language_Str MSG_DELTA_SETTINGS = _UxGT("Delta Inställningar"); + PROGMEM Language_Str MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto Kalibrering"); + PROGMEM Language_Str MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Sätt Delta Höjd"); + PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Sond Z-offset"); + PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Diag Rod"); + PROGMEM Language_Str MSG_DELTA_HEIGHT = _UxGT("Höjd"); + PROGMEM Language_Str MSG_DELTA_RADIUS = _UxGT("Radius"); + PROGMEM Language_Str MSG_INFO_MENU = _UxGT("Om Skrivaren"); + PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("Skrivare Info"); + PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("3-Punkt Nivellering"); + PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Linjär Nivellering"); + PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Bilinjär Nivellering"); + PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Enhetlig Bädd Nivellering (UBL)"); + PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Nät Nivellering"); + PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Skrivar Stats"); + PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Kort Info"); + PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Termistor"); + PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT("Extruderare"); + PROGMEM Language_Str MSG_INFO_BAUDRATE = _UxGT("Baud"); + PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protokoll"); + PROGMEM Language_Str MSG_INFO_RUNAWAY_OFF = _UxGT("Överdrift Övervakning: AV"); + PROGMEM Language_Str MSG_INFO_RUNAWAY_ON = _UxGT("Överdrift Övervakning: PÅ"); + PROGMEM Language_Str MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Hetände Overksam Tidsgräns"); + + PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Lådljus"); + PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Ljus ljusstyrka"); + PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("INKORREKT SKRIVARE"); + + #if LCD_WIDTH >= 20 + PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Utskriftsantal"); + PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Färdiga"); + PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Total Utskriftstid"); + PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Längsta Jobbtid"); + PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Extruderade Totalt"); + #else + PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Utskrift"); + PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Färdig"); + PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Total"); + PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Längsta"); + PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Extruderad"); + #endif + + PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Min Temp"); + PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Max Temp"); + PROGMEM Language_Str MSG_INFO_PSU = _UxGT("PSU"); + PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Driv Styrka"); + PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Driver %"); + PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("TMC KOPPLNINGSFEL"); + PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM Skriv"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER = _UxGT("TRÅDBYTE"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("UTSKRIFTSPAUSERAD"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("LADDA TRÅD"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("LOSSA TRÅD"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("ÅTERGÅ VAÖ:"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Rensa mer"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Fortsätt"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Munstycke: "); + PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Utskjut Sensor"); + PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Utskjut Dist mm"); + PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Hemning Misslyckad"); + PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Sondering Misslyckad"); + + PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("VÄLJ TRÅD"); + PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); + PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("Uppdatera MMU Firmware!"); + PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU Behöver uppmärksamhet."); + PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("MMU Återuppta"); + PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("MMU Återupptas..."); + PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("MMU Ladda"); + PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("MMU Ladda Alla"); + PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("MMU Ladda till Munstycke"); + PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("MMU Mata ut"); + PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("MMU Mata ut ~"); + PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("MMU Lossa"); + PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("Ladda Tråd %i..."); + PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Mata ut Tråd ..."); + PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Lossa Tråd..."); + PROGMEM Language_Str MSG_MMU2_ALL = _UxGT("Alla"); + PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("Tråd ~"); + PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("Återställ MMU"); + PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("MMU Återställer..."); + PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Ta bort, Klicka"); + + PROGMEM Language_Str MSG_MIX = _UxGT("Mixa"); + PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Komponent ="); + PROGMEM Language_Str MSG_MIXER = _UxGT("Mixer"); + PROGMEM Language_Str MSG_GRADIENT = _UxGT("Gradient"); + PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("Full Gradient"); + PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Växla Mix"); + PROGMEM Language_Str MSG_CYCLE_MIX = _UxGT("Totera Mix"); + PROGMEM Language_Str MSG_GRADIENT_MIX = _UxGT("Gradient Mix"); + PROGMEM Language_Str MSG_REVERSE_GRADIENT = _UxGT("Omvänd Gradient"); + PROGMEM Language_Str MSG_ACTIVE_VTOOL = _UxGT("Aktive V-verktyg"); + PROGMEM Language_Str MSG_START_VTOOL = _UxGT("Start V-verktyg"); + PROGMEM Language_Str MSG_END_VTOOL = _UxGT(" Slut V-verktyg"); + PROGMEM Language_Str MSG_GRADIENT_ALIAS = _UxGT("Alias V-verktyg"); + PROGMEM Language_Str MSG_RESET_VTOOLS = _UxGT("Återställ V-verktyg"); + PROGMEM Language_Str MSG_COMMIT_VTOOL = _UxGT("Kommitta V-verktyg Mix"); + PROGMEM Language_Str MSG_VTOOLS_RESET = _UxGT("V-verktyg blev Återställda"); + PROGMEM Language_Str MSG_START_Z = _UxGT("Start Z:"); + PROGMEM Language_Str MSG_END_Z = _UxGT(" Slut Z:"); + + PROGMEM Language_Str MSG_GAMES = _UxGT("Spel"); + PROGMEM Language_Str MSG_BRICKOUT = _UxGT("Brickout"); + PROGMEM Language_Str MSG_INVADERS = _UxGT("Invaders"); + PROGMEM Language_Str MSG_SNAKE = _UxGT("Sn4k3"); + PROGMEM Language_Str MSG_MAZE = _UxGT("Labyrint"); + + PROGMEM Language_Str MSG_BAD_PAGE = _UxGT("Dålig sida index"); + PROGMEM Language_Str MSG_BAD_PAGE_SPEED = _UxGT("Dålig sida hastighet"); + + PROGMEM Language_Str MSG_EDIT_PASSWORD = _UxGT("Redigera Lösenord"); + PROGMEM Language_Str MSG_LOGIN_REQUIRED = _UxGT("Login Krävs"); + PROGMEM Language_Str MSG_PASSWORD_SETTINGS = _UxGT("Lösenordsinställningar"); + PROGMEM Language_Str MSG_ENTER_DIGIT = _UxGT("Ange Siffra"); + PROGMEM Language_Str MSG_CHANGE_PASSWORD = _UxGT("Sätt/Redigera Lösenord"); + PROGMEM Language_Str MSG_REMOVE_PASSWORD = _UxGT("Ta bort Lösenord"); + PROGMEM Language_Str MSG_PASSWORD_SET = _UxGT("Lösenord är "); + PROGMEM Language_Str MSG_START_OVER = _UxGT("Börja om"); + PROGMEM Language_Str MSG_REMINDER_SAVE_SETTINGS = _UxGT("Kom ihåg att Spara!"); + PROGMEM Language_Str MSG_PASSWORD_REMOVED = _UxGT("Lösenord Bort taget"); + + // + // Filament Change screens show up to 3 lines on a 4-line display + // ...or up to 2 lines on a 3-line display + // + #if LCD_HEIGHT >= 4 + PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Tryck på knappen", "för att fortsätta utskrift")); + PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parkera...")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Vänta på", "trådbyte", "att börja")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Sätt in tråd", "och tryck på knappen", "för att fortsätta")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Tryck på knappen", "för att värma munstycke")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Munstycke värms", "Var snäll och vänta...")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Väntar på", "trådlossning")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Väntar på", "trådladdning")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("Väntar på", "tråd utrensning")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("Klicka för att slutföra", "tråd utrensning")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Väntar på utskrift", "att återstarta...")); + #else + PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Klick för att fortsätta")); + PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parkera...")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Vänta...")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Sätt in och klicka")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Klicka för att värma")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Värmer...")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Lossar...")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Laddar...")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Rensar...")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Klicka för att slutföra")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Återgår...")); + #endif + PROGMEM Language_Str MSG_TMC_DRIVERS = _UxGT("TMC Drivers"); + PROGMEM Language_Str MSG_TMC_CURRENT = _UxGT("Driver Ström"); + PROGMEM Language_Str MSG_TMC_HYBRID_THRS = _UxGT("Hybrid Tröskelvärde"); + PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Sensorlös Hemning"); + PROGMEM Language_Str MSG_TMC_STEPPING_MODE = _UxGT("Stegningsläge"); + PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("Smyghack Aktiverad"); + PROGMEM Language_Str MSG_SERVICE_RESET = _UxGT("Återställ"); + PROGMEM Language_Str MSG_SERVICE_IN = _UxGT(" in:"); + PROGMEM Language_Str MSG_BACKLASH = _UxGT("Backlash"); + PROGMEM Language_Str MSG_BACKLASH_A = LCD_STR_A; + PROGMEM Language_Str MSG_BACKLASH_B = LCD_STR_B; + PROGMEM Language_Str MSG_BACKLASH_C = LCD_STR_C; + PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Korrigering"); + PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Glättning"); + + PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("Nivå X Axel"); + PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Auto Kalibrera"); + #if ENABLED(TOUCH_UI_FTDI_EVE) + PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Overksam tidsgräns, temperatur minskning. Tryck ok för att återvärma och igen för att fortsätta."); + #else + PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Värmare Tidsgräns"); + #endif + PROGMEM Language_Str MSG_REHEAT = _UxGT("Återvärm"); + PROGMEM Language_Str MSG_REHEATING = _UxGT("Återvärmning..."); + + PROGMEM Language_Str MSG_PROBE_WIZARD = _UxGT("Z Sond Wizard"); + PROGMEM Language_Str MSG_PROBE_WIZARD_PROBING = _UxGT("Sondering Z Referens"); + PROGMEM Language_Str MSG_PROBE_WIZARD_MOVING = _UxGT("Flyttar till Sonderings Pos"); + + PROGMEM Language_Str MSG_SOUND = _UxGT("Ljud"); + + PROGMEM Language_Str MSG_TOP_LEFT = _UxGT("Uppe Vänster"); + PROGMEM Language_Str MSG_BOTTOM_LEFT = _UxGT("Nere Vänster"); + PROGMEM Language_Str MSG_TOP_RIGHT = _UxGT("Uppe Höger"); + PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Nere Höger"); + PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Kalibrering Färdig"); + PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Kalibrering Misslyckad"); +} diff --git a/Marlin/src/lcd/language/language_tr.h b/Marlin/src/lcd/language/language_tr.h index f81f153789ae..bf218f136fac 100644 --- a/Marlin/src/lcd/language/language_tr.h +++ b/Marlin/src/lcd/language/language_tr.h @@ -57,7 +57,7 @@ namespace Language_tr { PROGMEM Language_Str MSG_MAIN = _UxGT("Ana"); PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Gelişmiş Ayarlar"); PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Yapılandırma"); - PROGMEM Language_Str MSG_AUTOSTART = _UxGT("Oto. Başlat"); + PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Oto. Başlat"); PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Motorları Durdur"); PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Hata Ayıklama"); PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Durum Çubuğu Testi"); @@ -94,12 +94,8 @@ namespace Language_tr { PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Özel Ön Isınma"); PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Soğut/(Durdur)"); PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Lazer Kontrolü"); - PROGMEM Language_Str MSG_LASER_OFF = _UxGT("Lazeri Kapat"); - PROGMEM Language_Str MSG_LASER_ON = _UxGT("Lazeri Aç"); PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Lazer Gücü"); PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Spindle Kontrolü"); - PROGMEM Language_Str MSG_SPINDLE_OFF = _UxGT("Spindle Kapat"); - PROGMEM Language_Str MSG_SPINDLE_ON = _UxGT("Spindle Aç"); PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Spindle Gücü"); PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Spindle Ters Yön"); PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Gücü Aç"); @@ -109,7 +105,7 @@ namespace Language_tr { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Eksen Hareketleri"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Tabla Hizalama"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Tabla Hizası"); - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Hizalama Köşeleri"); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Hizalama Köşeleri"); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Sonraki Köşe"); PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Mesh Editörü"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Mesh Düzenle"); @@ -118,7 +114,7 @@ namespace Language_tr { PROGMEM Language_Str MSG_MESH_X = _UxGT("İndeks X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("İndeks Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Z Değeri"); - PROGMEM Language_Str MSG_USER_MENU = _UxGT("Özel Komutlar"); + PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Özel Komutlar"); PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 Prob Testi"); PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 Nokta"); PROGMEM Language_Str MSG_M48_DEVIATION = _UxGT("Sapma"); @@ -235,10 +231,11 @@ namespace Language_tr { PROGMEM Language_Str MSG_MOVE_E = _UxGT("Ekstruder"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Ekstruder *"); PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Nozul Çok Soğuk"); - PROGMEM Language_Str MSG_MOVE_Z_DIST = _UxGT("%smm"); + PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("%smm"); PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Hız"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Z Mesafesi"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Nozul"); @@ -261,16 +258,6 @@ namespace Language_tr { PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Kapalı"); PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("PID Kalibrasyon"); PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("PID Kalibrasyon *"); - PROGMEM Language_Str MSG_PID_P = _UxGT("PID-P"); - PROGMEM Language_Str MSG_PID_P_E = _UxGT("PID-P *"); - PROGMEM Language_Str MSG_PID_I = _UxGT("PID-I"); - PROGMEM Language_Str MSG_PID_I_E = _UxGT("PID-I *"); - PROGMEM Language_Str MSG_PID_D = _UxGT("PID-D"); - PROGMEM Language_Str MSG_PID_D_E = _UxGT("PID-D *"); - PROGMEM Language_Str MSG_PID_C = _UxGT("PID-C"); - PROGMEM Language_Str MSG_PID_C_E = _UxGT("PID-C *"); - PROGMEM Language_Str MSG_PID_F = _UxGT("PID-F"); - PROGMEM Language_Str MSG_PID_F_E = _UxGT("PID-F *"); PROGMEM Language_Str MSG_SELECT = _UxGT("Seç"); PROGMEM Language_Str MSG_SELECT_E = _UxGT("Seç *"); PROGMEM Language_Str MSG_ACC = _UxGT("İvme"); @@ -306,7 +293,7 @@ namespace Language_tr { PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Sıcaklık"); PROGMEM Language_Str MSG_MOTION = _UxGT("Hareket"); PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filaman"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("Ekstrüzyon/mm³"); + PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("Ekstrüzyon/mm") SUPERSCRIPT_THREE; PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Filaman Çapı"); PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Filaman Çapı *"); PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Çıkart mm"); diff --git a/Marlin/src/lcd/language/language_uk.h b/Marlin/src/lcd/language/language_uk.h index 9cc1002964f8..2e4a1b068caf 100644 --- a/Marlin/src/lcd/language/language_uk.h +++ b/Marlin/src/lcd/language/language_uk.h @@ -34,7 +34,7 @@ namespace Language_uk { using namespace Language_en; // Inherit undefined strings from English constexpr uint8_t CHARSIZE = 2; - PROGMEM Language_Str LANGUAGE = _UxGT("Ukranian"); + PROGMEM Language_Str LANGUAGE = _UxGT("Ukrainian"); PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" Готовий."); PROGMEM Language_Str MSG_YES = _UxGT("ТАК"); @@ -44,6 +44,11 @@ namespace Language_uk { PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("SD-картка вставлена"); PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("SD-картка видалена"); PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Вставте SD-картку"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_SD_INIT_FAIL = _UxGT("Збій ініціалізації SD"); + #else + PROGMEM Language_Str MSG_SD_INIT_FAIL = _UxGT("Збій ініціаліз. SD"); + #endif PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Помилка зчитування"); PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("USB диск видалений"); PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("Помилка USB диску"); @@ -58,15 +63,21 @@ namespace Language_uk { PROGMEM Language_Str MSG_MAIN = _UxGT("Основне меню"); PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Інші налаштування"); PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Конфігурація"); - PROGMEM Language_Str MSG_AUTOSTART = _UxGT("Автостарт"); + PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Автостарт"); PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Вимкнути двигуни"); PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Меню Debug"); - PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Тест Progress Bar"); + PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Тест лінії прогр."); PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Авто паркування"); PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Паркування X"); PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Паркування Y"); PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Паркування Z"); + PROGMEM Language_Str MSG_AUTO_HOME_I = _UxGT("Паркування ") LCD_STR_I; + PROGMEM Language_Str MSG_AUTO_HOME_J = _UxGT("Паркування ") LCD_STR_J; + PROGMEM Language_Str MSG_AUTO_HOME_K = _UxGT("Паркування ") LCD_STR_K; PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Авто Z-вирівнювання"); + PROGMEM Language_Str MSG_ITERATION = _UxGT("G34 Ітерація: %i"); + PROGMEM Language_Str MSG_DECREASING_ACCURACY = _UxGT("Зменьшення точності!"); + PROGMEM Language_Str MSG_ACCURACY_ACHIEVED = _UxGT("Точність досягнута"); PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Паркування XYZ"); PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Почати"); PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Наступна точка"); @@ -74,11 +85,29 @@ namespace Language_uk { PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Висота спаду"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Встанов. зміщення дому"); + PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("Зміщення дому X"); + PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Зміщення дому Y"); + PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Зміщення дому Z"); + PROGMEM Language_Str MSG_HOME_OFFSET_I = _UxGT("Зміщення дому ") LCD_STR_I; + PROGMEM Language_Str MSG_HOME_OFFSET_J = _UxGT("Зміщення дому ") LCD_STR_J; + PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Зміщення дому ") LCD_STR_K; #else - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Встанов.зміщ.дому"); + PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Встан. зміщ. дому"); + PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("Зміщ. дому X"); + PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Зміщ. дому Y"); + PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Зміщ. дому Z"); + PROGMEM Language_Str MSG_HOME_OFFSET_I = _UxGT("Зміщ. дому ") LCD_STR_I; + PROGMEM Language_Str MSG_HOME_OFFSET_J = _UxGT("Зміщ. дому ") LCD_STR_J; + PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Зміщ. дому ") LCD_STR_K; #endif PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Зміщення прийняті"); - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Встановити ноль"); + PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Встановити нуль"); + PROGMEM Language_Str MSG_SELECT_ORIGIN = _UxGT("Оберіть нуль"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Останнє значення "); + #else + PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Останнє знач. "); + #endif #if PREHEAT_COUNT PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Нагрів ") PREHEAT_1_LABEL; PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Нагрів ") PREHEAT_1_LABEL " ~"; @@ -96,27 +125,35 @@ namespace Language_uk { PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("Нагрів $ стіл"); PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("Нагрів $ налашт"); #endif - PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Нагрів Свій"); + PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Нагрів свого"); PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Вимкнути нагрів"); + PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Частота"); PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Керування лазером"); - PROGMEM Language_Str MSG_LASER_OFF = _UxGT("Вимкнути лазер"); - PROGMEM Language_Str MSG_LASER_ON = _UxGT("Увімкнути лазер"); + PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Керування шпінделем"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Потужність лазера"); - PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Керування шпінделем"); + PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Перемкн. шпіндель"); + PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Перемкнути вакуум"); + PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Перемкнути лазер"); + PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Потужн. шпінделя"); + PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Тестовий імпульс мс"); + PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Перемкнути обдув"); #else - PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Потуж.лазера"); - PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Керув. шпінделем"); + PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Потужн. лазера"); + PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Перемк. шпінд."); + PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Перемк. вакуум"); + PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Перемкн. лазер"); + PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Потужн. шпінд."); + PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Тест. імп., мс"); + PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Перемкн. обдув"); #endif - PROGMEM Language_Str MSG_SPINDLE_OFF = _UxGT("Вимкнути шпіндель"); - PROGMEM Language_Str MSG_SPINDLE_ON = _UxGT("Увімкнути шпіндель"); - #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Потуж. шпінделя"); - #else - PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Потуж. шпінд."); - #endif - PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Напрямок шпінделя"); + PROGMEM Language_Str MSG_LASER_ASSIST_TOGGLE = _UxGT("Керування обдувом"); + PROGMEM Language_Str MSG_FLOWMETER_FAULT = _UxGT("Помилка обдуву"); + PROGMEM Language_Str MSG_LASER_FIRE_PULSE = _UxGT("Імпульс лазеру"); + PROGMEM Language_Str MSG_SPINDLE_FORWARD = _UxGT("Шпіндель вперед"); + PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Шпіндель назад"); + PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Увімкнути живлення"); PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Вимкнути живлення"); PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Екструзія"); @@ -124,7 +161,16 @@ namespace Language_uk { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Рух по осям"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Вирівнювання столу"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Вирівняти стіл"); - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Вирівняти кути"); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Вирівняти кути"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Вгору до спрацюв. зонду"); + PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("Кути в межах. Вирів.столу"); + #else + PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Вгору до спрац.зонду"); + PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("Кути в межах. Вирівн"); + #endif + PROGMEM Language_Str MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Хороші точки: "); + PROGMEM Language_Str MSG_BED_TRAMMING_LAST_Z = _UxGT("Остання Z: "); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Наступний кут"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Зміщення по Z"); @@ -137,16 +183,21 @@ namespace Language_uk { PROGMEM Language_Str MSG_MESH_X = _UxGT("Індекс X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("Індекс Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Значення Z"); - PROGMEM Language_Str MSG_USER_MENU = _UxGT("Власні команди"); + PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Власні команди"); + PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 тест зонду"); PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 точка"); + PROGMEM Language_Str MSG_M48_OUT_OF_BOUNDS = _UxGT("Зонд за межами"); PROGMEM Language_Str MSG_M48_DEVIATION = _UxGT("Відхилення"); - PROGMEM Language_Str MSG_IDEX_MENU = _UxGT("Меню IDEX"); + + PROGMEM Language_Str MSG_IDEX_MENU = _UxGT("Режим IDEX"); PROGMEM Language_Str MSG_OFFSETS_MENU = _UxGT("Зміщення сопел"); PROGMEM Language_Str MSG_IDEX_MODE_AUTOPARK = _UxGT("Авто паркування"); - PROGMEM Language_Str MSG_IDEX_MODE_DUPLICATE = _UxGT("Розмноження"); + PROGMEM Language_Str MSG_IDEX_MODE_DUPLICATE = _UxGT("Дуплікація"); PROGMEM Language_Str MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Дзеркальна копія"); - PROGMEM Language_Str MSG_IDEX_MODE_FU1L_CTRL = _UxGT("Повний контроль"); + PROGMEM Language_Str MSG_IDEX_MODE_FULL_CTRL = _UxGT("Повний контроль"); + PROGMEM Language_Str MSG_IDEX_DUPE_GAP = _UxGT("Дублюв. X-проміжок"); + PROGMEM Language_Str MSG_HOTEND_OFFSET_X = _UxGT("Друге сопло X"); PROGMEM Language_Str MSG_HOTEND_OFFSET_Y = _UxGT("Друге сопло Y"); PROGMEM Language_Str MSG_HOTEND_OFFSET_Z = _UxGT("Друге сопло Z"); @@ -154,7 +205,7 @@ namespace Language_uk { PROGMEM Language_Str MSG_UBL_DOING_G29 = _UxGT("Виконується G29"); PROGMEM Language_Str MSG_UBL_TOOLS = _UxGT("Інструменти UBL"); PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Налаштування UBL"); - PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Точка розвороту"); + PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Точка нахилу"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Ручне введення сітки"); PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Розмістити шайбу і вимір."); @@ -162,24 +213,25 @@ namespace Language_uk { PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Ручне введ. сітки"); PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Розм. шайбу і вимір."); #endif + PROGMEM Language_Str MSG_UBL_MESH_WIZARD = _UxGT("Майстер сіток UBL"); PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Вимірювання"); - PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Видалити і виміряти"); - PROGMEM Language_Str MSG_UBL_MOVING_TO_NEXT = _UxGT("До наступної точки"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Видалити і виміряти стіл"); + #else + PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Видали і вимір. стіл"); + #endif + PROGMEM Language_Str MSG_UBL_MOVING_TO_NEXT = _UxGT("Рух до наступної"); PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("Активувати UBL"); PROGMEM Language_Str MSG_UBL_DEACTIVATE_MESH = _UxGT("Деактивувати UBL"); + PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = LCD_STR_THERMOMETER _UxGT(" столу, ") LCD_STR_DEGREE "C"; + PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Своя ") LCD_STR_THERMOMETER _UxGT(" столу,") LCD_STR_DEGREE "C"; + PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = LCD_STR_THERMOMETER _UxGT(" сопла, ") LCD_STR_DEGREE "C"; + PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Своя ") LCD_STR_THERMOMETER _UxGT(" сопла,") LCD_STR_DEGREE "C"; #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = _UxGT("Температура столу"); - PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Температура столу"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = _UxGT("Температура сопла"); - PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Температура сопла"); PROGMEM Language_Str MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Редагувати свою сітку"); PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("Точне редагування сітки"); PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Будувати свою сітку"); #else - PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = LCD_STR_THERMOMETER _UxGT(" столу, ") LCD_STR_DEGREE "C"; - PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = LCD_STR_THERMOMETER _UxGT(" столу, ") LCD_STR_DEGREE "C"; - PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = LCD_STR_THERMOMETER _UxGT(" сопла, ") LCD_STR_DEGREE "C"; - PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = LCD_STR_THERMOMETER _UxGT(" сопла, ") LCD_STR_DEGREE "C"; PROGMEM Language_Str MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Редагувати свою"); PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("Точне редаг. сітки"); PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Будувати свою"); @@ -187,21 +239,20 @@ namespace Language_uk { PROGMEM Language_Str MSG_UBL_MESH_EDIT = _UxGT("Редагування сітки"); PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Сітка побудована"); PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("Будувати сітку"); - #if PREHEAT_COUNT - PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Будувати сітку $"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Підтвердити $"); - #endif + PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Будувати сітку ($)"); + PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Підтвердити ($)"); PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Буд. холодну сітку"); PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Встан.висоту сітки"); PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Висота"); PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Підтвердити сітку"); PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Підтвердити свою"); + PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26 нагрів столу"); PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("G26 нагрів сопла"); PROGMEM Language_Str MSG_G26_MANUAL_PRIME = _UxGT("Ручне грунтування"); - PROGMEM Language_Str MSG_G26_FIXED_LENGTH = _UxGT("Грунт фікс. довж."); + PROGMEM Language_Str MSG_G26_FIXED_LENGTH = _UxGT("Фікс. довж. грунт."); PROGMEM Language_Str MSG_G26_PRIME_DONE = _UxGT("Грунтув. виконане"); - PROGMEM Language_Str MSG_G26_CANCELED = _UxGT("G26 завершена"); + PROGMEM Language_Str MSG_G26_CANCELED = _UxGT("G26 скасовано"); PROGMEM Language_Str MSG_G26_LEAVING = _UxGT("Вийти з G26"); PROGMEM Language_Str MSG_UBL_CONTINUE_MESH = _UxGT("Продовжити сітку"); PROGMEM Language_Str MSG_UBL_MESH_LEVELING = _UxGT("Вирівнювання сітки"); @@ -220,7 +271,7 @@ namespace Language_uk { PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Зберегти зовні"); PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("Інформація по UBL"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Обсяг заповнювача"); + PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Обсяг заповнюв."); #else PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Обсяг заповн."); #endif @@ -229,10 +280,11 @@ namespace Language_uk { PROGMEM Language_Str MSG_UBL_FILLIN_MESH = _UxGT("Заповнити сітку"); PROGMEM Language_Str MSG_UBL_INVALIDATE_ALL = _UxGT("Анулювати все"); PROGMEM Language_Str MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Анулювати найближчу"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("Точно налашт. все"); #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("Точно налаштувати все"); PROGMEM Language_Str MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Точно налашт.найближчу"); #else + PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("Точно налашт. все"); PROGMEM Language_Str MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Точно найближчу"); #endif PROGMEM Language_Str MSG_UBL_STORAGE_MESH_MENU = _UxGT("Збереження сітки"); @@ -247,7 +299,7 @@ namespace Language_uk { PROGMEM Language_Str MSG_UBL_Z_OFFSET = _UxGT("Зміщення Z: "); PROGMEM Language_Str MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Зміщення Z зупинено"); PROGMEM Language_Str MSG_UBL_STEP_BY_STEP_MENU = _UxGT("UBL покроково"); - PROGMEM Language_Str MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1.Будувати холодну"); + PROGMEM Language_Str MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1.Збудувати холодну"); PROGMEM Language_Str MSG_UBL_2_SMART_FILLIN = _UxGT("2.Розумне заповн-я"); PROGMEM Language_Str MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3.Затвердити сітку"); PROGMEM Language_Str MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4.Точно налашт.все"); @@ -263,7 +315,7 @@ namespace Language_uk { PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("Передустан. світла"); #endif PROGMEM Language_Str MSG_SET_LEDS_RED = _UxGT("Червоний"); - PROGMEM Language_Str MSG_SET_LEDS_ORANGE = _UxGT("Оранжевий"); + PROGMEM Language_Str MSG_SET_LEDS_ORANGE = _UxGT("Помаранчевий"); PROGMEM Language_Str MSG_SET_LEDS_YELLOW = _UxGT("Жовтий"); PROGMEM Language_Str MSG_SET_LEDS_GREEN = _UxGT("Зелений"); PROGMEM Language_Str MSG_SET_LEDS_BLUE = _UxGT("Синій"); @@ -271,49 +323,68 @@ namespace Language_uk { PROGMEM Language_Str MSG_SET_LEDS_VIOLET = _UxGT("Фіолетовий"); PROGMEM Language_Str MSG_SET_LEDS_WHITE = _UxGT("Білий"); PROGMEM Language_Str MSG_SET_LEDS_DEFAULT = _UxGT("За умовчанням"); - PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Свої кольори"); + PROGMEM Language_Str MSG_LED_CHANNEL_N = _UxGT("Канал ="); + PROGMEM Language_Str MSG_LEDS2 = _UxGT("Світло #2"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_NEO2_PRESETS = _UxGT("Передустановка світла #2"); + #else + PROGMEM Language_Str MSG_NEO2_PRESETS = _UxGT("Передуст. світла #2"); + #endif + PROGMEM Language_Str MSG_NEO2_BRIGHTNESS = _UxGT("Яскравість"); + PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Своє світло"); PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Рівень червоного"); PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Рівень зеленого"); PROGMEM Language_Str MSG_INTENSITY_B = _UxGT("Рівень синього"); PROGMEM Language_Str MSG_INTENSITY_W = _UxGT("Рівень білого"); PROGMEM Language_Str MSG_LED_BRIGHTNESS = _UxGT("Яскравість"); - PROGMEM Language_Str MSG_MOVING = _UxGT("Переміщення..."); + PROGMEM Language_Str MSG_MOVING = _UxGT("Рух..."); PROGMEM Language_Str MSG_FREE_XY = _UxGT("Звільнити XY"); PROGMEM Language_Str MSG_MOVE_X = _UxGT("Рух по X"); PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Рух по Y"); PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Рух по Z"); + PROGMEM Language_Str MSG_MOVE_I = _UxGT("Рух по ") LCD_STR_I; + PROGMEM Language_Str MSG_MOVE_J = _UxGT("Рух по ") LCD_STR_J; + PROGMEM Language_Str MSG_MOVE_K = _UxGT("Рух по ") LCD_STR_K; PROGMEM Language_Str MSG_MOVE_E = _UxGT("Екструдер"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Екструдер *"); PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Сопло дуже холодне"); - PROGMEM Language_Str MSG_MOVE_Z_DIST = _UxGT("Рух по %sмм"); - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Рух по 0.1мм"); - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Рух по 1мм"); - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Рух по 10мм"); + PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Рух %sмм"); + PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Рух 0.1мм"); + PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Рух 1мм"); + PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Рух 10мм"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Рух 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Швидкість"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Z Столу"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Сопло, ") LCD_STR_DEGREE "C"; PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Сопло ~"); PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Сопло запарковане"); - PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Сопло очикує"); + PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Сопло очікує"); PROGMEM Language_Str MSG_BED = _UxGT("Стіл, ") LCD_STR_DEGREE "C"; PROGMEM Language_Str MSG_CHAMBER = _UxGT("Камера,") LCD_STR_DEGREE "C"; - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Охолодження"); - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Охолодження ~"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Збережене охолодж. ~"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Додаткове охолодж."); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Додаткове охолодж. ~"); - PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Контролер охолодження"); + PROGMEM Language_Str MSG_COOLER = _UxGT("Охолодження лазеру"); + PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Перемк. охолодж."); + #else + PROGMEM Language_Str MSG_COOLER = _UxGT("Охолодж. лазеру"); + PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Перемк.охолод"); + #endif + PROGMEM Language_Str MSG_FLOWMETER_SAFETY = _UxGT("Безпека потоку"); + PROGMEM Language_Str MSG_LASER = _UxGT("Лазер"); + PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Швидк. вент."); + PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Швидк. вент. ~"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Збереж.швидк.вент. ~"); + PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Дод. швидк. вент. ~"); #else - PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Збереж.охолодж. ~"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Додат. охолодж."); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Додат.охолодж ~"); - PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Контролер охолодж."); + PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Збереж. вент. ~"); + PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Додат.вент. ~"); #endif + PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Дод. швидк. вент."); + PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Вент. контролера"); PROGMEM Language_Str MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Холості оберти"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("Робочі оберти"); PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Авто-режим"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("Робочі оберти"); PROGMEM Language_Str MSG_CONTROLLER_FAN_DURATION = _UxGT("Період простою"); PROGMEM Language_Str MSG_FLOW = _UxGT("Потік"); PROGMEM Language_Str MSG_FLOW_N = _UxGT("Потік ~"); @@ -322,15 +393,15 @@ namespace Language_uk { PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER ", " LCD_STR_DEGREE _UxGT("С макс"); PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Фактор"); PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Автотемпер."); - PROGMEM Language_Str MSG_LCD_ON = _UxGT("Увімк"); - PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Вимк."); + PROGMEM Language_Str MSG_LCD_ON = _UxGT("Увім"); + PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Вимк"); PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("Автопідбір PID"); PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("Автопідбір PID *"); PROGMEM Language_Str MSG_PID_AUTOTUNE_DONE = _UxGT("Підбір PID виконано"); PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Збій автопідбору. Поганий екструдер."); PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Збій автопідбору. Температура завищена."); - PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("Збій автопідбору! Завершення часу."); + PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("Збій автопідбору! Вичерпан час."); PROGMEM Language_Str MSG_SELECT = _UxGT("Вибрати"); PROGMEM Language_Str MSG_SELECT_E = _UxGT("Вибрати *"); @@ -339,6 +410,9 @@ namespace Language_uk { PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-ривок"); PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-ривок"); PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-ривок"); + PROGMEM Language_Str MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-ривок"); + PROGMEM Language_Str MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-ривок"); + PROGMEM Language_Str MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-ривок"); PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-ривок"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Відхилення вузла"); @@ -349,14 +423,24 @@ namespace Language_uk { PROGMEM Language_Str MSG_VMAX_A = _UxGT("Швидк.макс ") LCD_STR_A; PROGMEM Language_Str MSG_VMAX_B = _UxGT("Швидк.макс ") LCD_STR_B; PROGMEM Language_Str MSG_VMAX_C = _UxGT("Швидк.макс ") LCD_STR_C; + PROGMEM Language_Str MSG_VMAX_I = _UxGT("Швидк.макс ") LCD_STR_I; + PROGMEM Language_Str MSG_VMAX_J = _UxGT("Швидк.макс ") LCD_STR_J; + PROGMEM Language_Str MSG_VMAX_K = _UxGT("Швидк.макс ") LCD_STR_K; PROGMEM Language_Str MSG_VMAX_E = _UxGT("Швидк.макс ") LCD_STR_E; PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Швидк.макс *"); - PROGMEM Language_Str MSG_VMIN = _UxGT("Швидк.мін"); - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Переміщення мін"); + PROGMEM Language_Str MSG_VMIN = _UxGT("Швидк. мін"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Переміщення мін"); + #else + PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Переміщ. мін"); + #endif PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Прискорення, мм/с2"); PROGMEM Language_Str MSG_AMAX_A = _UxGT("Приск.макс ") LCD_STR_A; PROGMEM Language_Str MSG_AMAX_B = _UxGT("Приск.макс ") LCD_STR_B; PROGMEM Language_Str MSG_AMAX_C = _UxGT("Приск.макс ") LCD_STR_C; + PROGMEM Language_Str MSG_AMAX_I = _UxGT("Приск.макс ") LCD_STR_I; + PROGMEM Language_Str MSG_AMAX_J = _UxGT("Приск.макс ") LCD_STR_J; + PROGMEM Language_Str MSG_AMAX_K = _UxGT("Приск.макс ") LCD_STR_K; PROGMEM Language_Str MSG_AMAX_E = _UxGT("Приск.макс ") LCD_STR_E; PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Приск.макс *"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Приск.втягув."); @@ -367,13 +451,16 @@ namespace Language_uk { PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" кроків/мм"); PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" кроків/мм"); PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" кроків/мм"); + PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" кроків/мм"); + PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" кроків/мм"); + PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" кроків/мм"); PROGMEM Language_Str MSG_E_STEPS = _UxGT("E кроків/мм"); PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* кроків/мм"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Температура"); PROGMEM Language_Str MSG_MOTION = _UxGT("Рух"); PROGMEM Language_Str MSG_FILAMENT = _UxGT("Пруток"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E в мм³"); - PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("E обмеж.,мм³"); + PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E, мм") SUPERSCRIPT_THREE; + PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("E обмеж.,мм") SUPERSCRIPT_THREE; PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT_E = _UxGT("E обмеж. *"); PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Діам. прутка"); PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Діам. прутка *"); @@ -396,7 +483,7 @@ namespace Language_uk { PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Параметри збережені"); PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Оновити SD-картку"); PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Зкинути принтер"); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT(" Поновити"); + PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT(" Поновити"); PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Головний екран"); PROGMEM Language_Str MSG_PREPARE = _UxGT("Підготувати"); PROGMEM Language_Str MSG_TUNE = _UxGT("Підлаштування"); @@ -416,18 +503,21 @@ namespace Language_uk { PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Готово"); PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Назад"); PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Продовжити"); + PROGMEM Language_Str MSG_BUTTON_SKIP = _UxGT("Пропустити"); PROGMEM Language_Str MSG_PAUSING = _UxGT("Призупинення..."); PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Призупинити друк"); PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Відновити друк"); + PROGMEM Language_Str MSG_HOST_START_PRINT = _UxGT("Старт з хосту"); PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Скасувати друк"); + PROGMEM Language_Str MSG_END_LOOPS = _UxGT("End Repeat Loops"); // needs translation PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("Друк об'єкта"); PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("Завершити об'єкт"); PROGMEM Language_Str MSG_CANCEL_OBJECT_N = _UxGT("Завершити об'єкт ="); PROGMEM Language_Str MSG_OUTAGE_RECOVERY = _UxGT("Віднов. після збою"); PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Друкувати з SD"); PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("SD-картки немає"); - PROGMEM Language_Str MSG_DWELL = _UxGT("Сплячка..."); + PROGMEM Language_Str MSG_DWELL = _UxGT("Сон..."); PROGMEM Language_Str MSG_USERWAIT = _UxGT("Продовжити..."); PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("Друк призупинено"); PROGMEM Language_Str MSG_PRINTING = _UxGT("Друк..."); @@ -453,8 +543,8 @@ namespace Language_uk { PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Підскок, мм"); PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Повернення V"); PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("Поверн.зміни V"); - PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Поміняти довжини"); - PROGMEM Language_Str MSG_FILAMENT_SWAP_EXTRA = _UxGT("Поміняти додатково"); + PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Змінити довжини"); + PROGMEM Language_Str MSG_FILAMENT_SWAP_EXTRA = _UxGT("Змінити додатково"); PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Очистити довжину"); PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Зміна сопла"); PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Підняти по Z"); @@ -468,11 +558,11 @@ namespace Language_uk { PROGMEM Language_Str MSG_FILAMENT_PARK_ENABLED = _UxGT("Паркувати голову"); PROGMEM Language_Str MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Відновити швидкість"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Оберти охолодження"); - PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Час охолодження"); + PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Оберти вентилятора"); + PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Час вентилятора"); #else - PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Оберти охолодж."); - PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Час охолодж."); + PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Оберти вент."); + PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Час вент."); #endif PROGMEM Language_Str MSG_TOOL_MIGRATION_ON = _UxGT("Авто Увімк."); PROGMEM Language_Str MSG_TOOL_MIGRATION_OFF = _UxGT("Авто Вимкн."); @@ -489,37 +579,41 @@ namespace Language_uk { PROGMEM Language_Str MSG_FILAMENTUNLOAD_ALL = _UxGT("Видалити все"); PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Вставити SD-картку"); PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Заміна SD-картки"); - PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("Звільніть SD-картку"); + PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("Видаліть SD-картку"); PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Z-Зонд поза столом"); PROGMEM Language_Str MSG_SKEW_FACTOR = _UxGT("Фактор нахилу"); - PROGMEM Language_Str MSG_BLTOUCH = _UxGT("Z-зонд BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("BLTouch Само-Тест"); - PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Зкинути BLTouch"); + PROGMEM Language_Str MSG_BLTOUCH = _UxGT("BLTouch"); + PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("Само-тест"); + PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Зкинути зонд"); PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("Підняти зонд"); PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("Опустити зонд"); PROGMEM Language_Str MSG_BLTOUCH_SW_MODE = _UxGT("Режим SW"); PROGMEM Language_Str MSG_BLTOUCH_5V_MODE = _UxGT("Режим 5V"); PROGMEM Language_Str MSG_BLTOUCH_OD_MODE = _UxGT("Режим OD"); PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE = _UxGT("Режим збереження"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Встановити на 5V"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Встановити на OD"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_ECHO = _UxGT("Злив звіту"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_CHANGE = _UxGT("НЕБЕЗПЕКА: Неправильні параметри приводять до пошкоджень! Продовжувати?"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Встановити BLT на 5V"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Встановити BLT на OD"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_ECHO = _UxGT("Звітувати злив"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_CHANGE = _UxGT("НЕБЕЗПЕКА: Неправильні параметри приводять до пошкоджень! Продовжити?"); PROGMEM Language_Str MSG_TOUCHMI_PROBE = _UxGT("Z-Зонд TouchMI"); - PROGMEM Language_Str MSG_TOUCHMI_INIT = _UxGT("Ініціалізація"); + PROGMEM Language_Str MSG_TOUCHMI_INIT = _UxGT("Ініц. TouchMI"); PROGMEM Language_Str MSG_TOUCHMI_ZTEST = _UxGT("Тест Z-зміщення"); PROGMEM Language_Str MSG_TOUCHMI_SAVE = _UxGT("Зберегти"); PROGMEM Language_Str MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("Установити TouchMI"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("Установити зонд"); - PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("Завантажити зонд"); - PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Дім %s%s%s перший"); + PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("Установити Z-зонд"); + PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("Завантажити Z-зонд"); + PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Спочатку дім %s%s%s"); PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("Зміщення зонду"); - PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("Тест зміщення X"); - PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Тест зміщення Y"); - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Тест зміщення Z"); + PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("Зміщення по X"); + PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Зміщення по Y"); + PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Зміщення по Z"); + PROGMEM Language_Str MSG_MOVE_NOZZLE_TO_BED = _UxGT("Рухати сопло до столу"); PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Мікрокрок X"); PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Мікрокрок Y"); PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Мікрокрок Z"); + PROGMEM Language_Str MSG_BABYSTEP_I = _UxGT("Мікрокрок ") LCD_STR_I; + PROGMEM Language_Str MSG_BABYSTEP_J = _UxGT("Мікрокрок ") LCD_STR_J; + PROGMEM Language_Str MSG_BABYSTEP_K = _UxGT("Мікрокрок ") LCD_STR_K; PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Сумарно"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Кінцевик спрацював"); PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Збій нагріву"); @@ -527,7 +621,13 @@ namespace Language_uk { PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("ВИТІК ТЕПЛА"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("ВИТІК ТЕПЛА СТОЛУ"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("ВИТІК ТЕПЛА КАМЕРИ"); - PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("ПЕРЕГРІВ"); + PROGMEM Language_Str MSG_THERMAL_RUNAWAY_COOLER = _UxGT("ВИТІК ОХОЛОДЖЕННЯ"); + #if LCD_WIDTH >= 20 + PROGMEM Language_Str MSG_COOLING_FAILED = _UxGT("ОХОЛОДЖЕННЯ НЕ ВДАЛОСЬ"); + #else + PROGMEM Language_Str MSG_COOLING_FAILED = _UxGT("ОХОЛОДЖ. НЕ ВДАЛОСЬ"); + #endif + PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("МАКСИМАЛЬНА Т") LCD_STR_DEGREE; PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("МІНІМАЛЬНА Т") LCD_STR_DEGREE; PROGMEM Language_Str MSG_HALTED = _UxGT("ПРИНТЕР ЗУПИНЕНО"); PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Перезавантажте"); @@ -537,57 +637,57 @@ namespace Language_uk { PROGMEM Language_Str MSG_HEATING = _UxGT("Нагрівання..."); PROGMEM Language_Str MSG_COOLING = _UxGT("Охолодження..."); PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Нагрів столу..."); + PROGMEM Language_Str MSG_PROBE_HEATING = _UxGT("Нагрів зонду..."); PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Нагрів камери..."); #if LCD_WIDTH >= 20 PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Охолодження столу..."); + PROGMEM Language_Str MSG_PROBE_COOLING = _UxGT("Охолодження зонду..."); PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Охолодження камери..."); - PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Калібрування Delta"); + PROGMEM Language_Str MSG_LASER_COOLING = _UxGT("Охолодження лазеру..."); #else - PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Охол. столу..."); - PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Охол. камери..."); - PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Калібрув. Delta"); + PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Охолодж. столу..."); + PROGMEM Language_Str MSG_PROBE_COOLING = _UxGT("Охолодж. зонду..."); + PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Охолодж. камери..."); + PROGMEM Language_Str MSG_LASER_COOLING = _UxGT("Охолодж. лазеру..."); #endif + PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Калібрування Delta"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Калібрувати X"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Калібрувати Y"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Калібрувати Z"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Калібр. центр"); PROGMEM Language_Str MSG_DELTA_SETTINGS = _UxGT("Параметри Delta"); PROGMEM Language_Str MSG_DELTA_AUTO_CALIBRATE = _UxGT("Автокалібрування"); - PROGMEM Language_Str MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Висота Delta"); - #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Зондування Z-зміщ."); - PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Стрижень діагоналі"); - #else - PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Зондув. Z-зміщ."); - PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Стрижень діаг."); - #endif + PROGMEM Language_Str MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Встан. Висоту Delta"); + PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Z-зміщення зонду"); + PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Діагональ стрижня"); PROGMEM Language_Str MSG_DELTA_HEIGHT = _UxGT("Висота"); PROGMEM Language_Str MSG_DELTA_RADIUS = _UxGT("Радіус"); PROGMEM Language_Str MSG_INFO_MENU = _UxGT("Про принтер"); - PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("Данні принтера"); + PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("Дані принтера"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("3-точкове вирівнювання"); PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Лінійне вирівнювання"); PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Білінійне вирівнювання"); - #elif LCD_WIDTH == 20 - PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("3-точкове вирівнюв."); - PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Лінійне вирівнюван."); - PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Білінійне вирівнюв."); #else - PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("3-точк. вирівн."); + PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("3-точкове вирівн."); PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Лінійне вирівн."); - PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Білін. вирівнюв."); + PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Білінійне вирівн."); #endif - PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Керування UBL"); + PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("UBL"); PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Вирівнювання сітки"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Зондування сітки виконано"); + #else + PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Зондування виконано"); + #endif PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Статистика принтера"); PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Про плату"); PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Термістори"); PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT("Екструдери"); - PROGMEM Language_Str MSG_INFO_BAUDRATE = _UxGT("Біт/секунду"); + PROGMEM Language_Str MSG_INFO_BAUDRATE = _UxGT("Бод"); PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Протокол"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_INFO_RUNAWAY_OFF = _UxGT("Контроль витіку ") LCD_STR_THERMOMETER _UxGT(" Вимк"); @@ -602,6 +702,7 @@ namespace Language_uk { PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Підсвітка"); PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Яскравість світла"); PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("НЕ ТОЙ ПРИНТЕР"); + PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Завершено"); PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Екструдовано"); #if LCD_WIDTH >= 20 @@ -621,6 +722,9 @@ namespace Language_uk { PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("Драйвер X, %"); PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Драйвер Y, %"); PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Драйвер Z, %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = _UxGT("Драйвер ") AXIS4_STR _UxGT(", %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = _UxGT("Драйвер ") AXIS5_STR _UxGT(", %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = _UxGT("Драйвер ") AXIS6_STR _UxGT(", %"); PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("Драйвер E, %"); PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("ЗБІЙ ЗВ'ЯЗКУ З TMC"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Запис ЦАП у EEPROM"); @@ -647,25 +751,30 @@ namespace Language_uk { PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Помилка зондування"); PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("ОБЕРІТЬ ПРУТОК"); - PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("Налаштування MMU"); - PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("Понови прошивку MMU!"); + PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); + PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("Онови прошивку MMU!"); PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU потребує уваги"); - PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Продовжити друк"); - PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("Продовження..."); - PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("Завантажити пруток"); - PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("Завантажити все"); - PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Завантажити в сопло"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("Звільнити пруток"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Звільнити пруток ~"); - PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Вивантажити пруток"); - PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("Завантаження %i..."); - PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Звільнення прутка..."); - PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Вивантаження ...."); + PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("MMU Продовжити"); + PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("MMU Продовження..."); + PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("MMU Завантажити"); + PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("MMU Завантажити все"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("MMU Завантажити в сопло"); + #else + PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("MMU Завант. в сопло"); + #endif + PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("MMU Звільнити"); + PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("MMU Звільнити ~"); + PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("MMU Вивантажити"); + PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("Завантаж. %i..."); + PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Викидання прутка..."); + PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Вивантаження..."); PROGMEM Language_Str MSG_MMU2_ALL = _UxGT("Все"); PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("Пруток ~"); PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("Перезапуск MMU"); - PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("Перезапуск MMU..."); + PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("MMU Перезапуск..."); PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Видаліть, натисніть"); + #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_MIX = _UxGT("Змішування"); #else @@ -675,51 +784,66 @@ namespace Language_uk { PROGMEM Language_Str MSG_MIXER = _UxGT("Змішувач"); PROGMEM Language_Str MSG_GRADIENT = _UxGT("Градієнт"); PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("Повний градієнт"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Переключити змішування"); + #else + PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Переключ.змішування"); + #endif PROGMEM Language_Str MSG_CYCLE_MIX = _UxGT("Циклічне змішування"); PROGMEM Language_Str MSG_GRADIENT_MIX = _UxGT("Градієнт змішування"); PROGMEM Language_Str MSG_REVERSE_GRADIENT = _UxGT("Змінити градієнт"); + #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Перемкнути змішування"); PROGMEM Language_Str MSG_ACTIVE_VTOOL = _UxGT("Активація В-інструменту"); - PROGMEM Language_Str MSG_START_VTOOL = _UxGT("Початок В-інструменту"); - PROGMEM Language_Str MSG_END_VTOOL = _UxGT("Кінець В-інструменту"); PROGMEM Language_Str MSG_GRADIENT_ALIAS = _UxGT("Псевдонім В-інструменту"); PROGMEM Language_Str MSG_RESET_VTOOLS = _UxGT("Зкидання В-інструментів"); - PROGMEM Language_Str MSG_VTOOLS_RESET = _UxGT("В-інструменти зкинуті"); - PROGMEM Language_Str MSG_COMMIT_VTOOL = _UxGT("Змішати В-інструменти"); #else - PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Перемкнути змішув."); - PROGMEM Language_Str MSG_ACTIVE_VTOOL = _UxGT("Актив.В-інструм."); - PROGMEM Language_Str MSG_START_VTOOL = _UxGT("В-інструм. поч."); - PROGMEM Language_Str MSG_END_VTOOL = _UxGT("В-інструм. кін."); - PROGMEM Language_Str MSG_GRADIENT_ALIAS = _UxGT("Псевдонім В-інстр."); - PROGMEM Language_Str MSG_RESET_VTOOLS = _UxGT("Зкидання В-інструм"); - PROGMEM Language_Str MSG_VTOOLS_RESET = _UxGT("В-інструм. зкинуті"); - PROGMEM Language_Str MSG_COMMIT_VTOOL = _UxGT("Змішати В-інструм."); + PROGMEM Language_Str MSG_ACTIVE_VTOOL = _UxGT("Актив. В-інструм."); + PROGMEM Language_Str MSG_GRADIENT_ALIAS = _UxGT("Псевдонім В-інструм"); + PROGMEM Language_Str MSG_RESET_VTOOLS = _UxGT("Зкидання В-інструм."); #endif - PROGMEM Language_Str MSG_START_Z = _UxGT("Початок Z"); - PROGMEM Language_Str MSG_END_Z = _UxGT(" Кінець Z"); + PROGMEM Language_Str MSG_START_VTOOL = _UxGT("Початок В-інструменту"); + PROGMEM Language_Str MSG_END_VTOOL = _UxGT("Кінець В-інструменту"); + PROGMEM Language_Str MSG_COMMIT_VTOOL = _UxGT("Змішати В-інструменти"); + PROGMEM Language_Str MSG_VTOOLS_RESET = _UxGT("В-інструменти зкинуті"); + PROGMEM Language_Str MSG_START_Z = _UxGT("Початок Z:"); + PROGMEM Language_Str MSG_END_Z = _UxGT(" Кінець Z:"); PROGMEM Language_Str MSG_GAMES = _UxGT("Ігри"); PROGMEM Language_Str MSG_BRICKOUT = _UxGT("Цеглини"); PROGMEM Language_Str MSG_INVADERS = _UxGT("Вторгнення"); - PROGMEM Language_Str MSG_SNAKE = _UxGT("Змійка"); + PROGMEM Language_Str MSG_SNAKE = _UxGT("Zм!йк@"); PROGMEM Language_Str MSG_MAZE = _UxGT("Лабіринт"); + PROGMEM Language_Str MSG_BAD_PAGE = _UxGT("Погана сторінка"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_BAD_PAGE = _UxGT("Поганий індекс сторінки"); - PROGMEM Language_Str MSG_BAD_PAGE_SPEED = _UxGT("Погана швидкість сторінки"); + PROGMEM Language_Str MSG_BAD_PAGE_SPEED = _UxGT("Погана швидкість стор."); #else - PROGMEM Language_Str MSG_BAD_PAGE = _UxGT("Погана сторінка"); - PROGMEM Language_Str MSG_BAD_PAGE_SPEED = _UxGT("Погана швидк.стор"); + PROGMEM Language_Str MSG_BAD_PAGE_SPEED = _UxGT("Погана швидк. стор."); #endif + PROGMEM Language_Str MSG_EDIT_PASSWORD = _UxGT("Редагувати пароль"); + PROGMEM Language_Str MSG_LOGIN_REQUIRED = _UxGT("Потрібен логін"); + PROGMEM Language_Str MSG_PASSWORD_SETTINGS = _UxGT("Параметри паролю"); + PROGMEM Language_Str MSG_ENTER_DIGIT = _UxGT("Введіть цифру"); + PROGMEM Language_Str MSG_CHANGE_PASSWORD = _UxGT("Змінити пароль"); + PROGMEM Language_Str MSG_REMOVE_PASSWORD = _UxGT("Видалити пароль"); + PROGMEM Language_Str MSG_PASSWORD_SET = _UxGT("Пароль: "); + PROGMEM Language_Str MSG_START_OVER = _UxGT("Старт через"); + PROGMEM Language_Str MSG_REMINDER_SAVE_SETTINGS = _UxGT("Не забудь зберегти!"); + PROGMEM Language_Str 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 + // PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Паркування...")); #if LCD_HEIGHT >= 4 // Up to 3 lines allowed PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_3_LINE("Натисніть кнопку", "для продовження", "друку")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Зачекайте", "на початок", "заміни прутка")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Вставте пруток", "та натисніть", "для продовження...")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Вставте пруток", "та натисніть", "для продовження")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Натисніть кнопку", "для нагріву сопла")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Сопло нагрівається", "зачекайте...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Зачекайте", "на вивід прутка")); @@ -755,9 +879,37 @@ namespace Language_uk { PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("Рівень вісі X"); PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Авто калібрування"); - PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Час нагрівача збіг"); + + #if ENABLED(TOUCH_UI_FTDI_EVE) + PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Час простою збіг, температура впала. Натисніть ОК, щоби знову нагріти та продовжити"); + #else + PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Час нагрівача збіг"); + #endif PROGMEM Language_Str MSG_REHEAT = _UxGT("Поновити нагрів"); PROGMEM Language_Str MSG_REHEATING = _UxGT("Нагрівання..."); + + PROGMEM Language_Str MSG_PROBE_WIZARD = _UxGT("Майстер Z-зонда"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_PROBE_WIZARD_PROBING = _UxGT("Зондув. контрольної точки Z"); + PROGMEM Language_Str MSG_PROBE_WIZARD_MOVING = _UxGT("Рух до точки зондування"); + #else + PROGMEM Language_Str MSG_PROBE_WIZARD_PROBING = _UxGT("Зондув.контр.точки Z"); + PROGMEM Language_Str MSG_PROBE_WIZARD_MOVING = _UxGT("Рух до точки зондув."); + #endif + + PROGMEM Language_Str MSG_SOUND = _UxGT("Звук"); + + PROGMEM Language_Str MSG_TOP_LEFT = _UxGT("Верхній лівий"); + PROGMEM Language_Str MSG_BOTTOM_LEFT = _UxGT("Нижній лівий"); + PROGMEM Language_Str MSG_TOP_RIGHT = _UxGT("Верхній правий"); + PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Нижній правий"); + PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Калібрування успішне"); + PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Збій калібрування"); + + PROGMEM Language_Str MSG_DRIVER_BACKWARD = _UxGT(" драйвер назад"); + + PROGMEM Language_Str MSG_SD_CARD = _UxGT("SD Картка"); + PROGMEM Language_Str MSG_USB_DISK = _UxGT("USB Диск"); } #if FAN_COUNT == 1 diff --git a/Marlin/src/lcd/language/language_vi.h b/Marlin/src/lcd/language/language_vi.h index f7cf60657535..013a9159214a 100644 --- a/Marlin/src/lcd/language/language_vi.h +++ b/Marlin/src/lcd/language/language_vi.h @@ -47,7 +47,7 @@ namespace Language_vi { PROGMEM Language_Str MSG_MAIN = _UxGT("Chính"); // Main PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Thiết lập cấp cao"); // Advanced Settings PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Cấu hình"); // Configuration - PROGMEM Language_Str MSG_AUTOSTART = _UxGT("Khởi chạy tự động"); // Autostart + PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Khởi chạy tự động"); // Autostart PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Tắt động cơ bước"); // Disable steppers PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Menu gỡ lỗi"); // Debug Menu PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Kiểm tra tiến độ"); // Progress bar test @@ -90,13 +90,13 @@ namespace Language_vi { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Di chuyển trục"); // Move axis PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("San Lấp Bàn"); // Bed Leveling PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Làm bằng mặt bàn"); // Level bed - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Làm bằng góc bàn"); // Level corners + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Làm bằng góc bàn"); // Level corners PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Góc tiếp theo"); // Next corner PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Chỉnh lưới đã dừng"); // Mesh Editing Stopped PROGMEM Language_Str MSG_MESH_X = _UxGT("Mục lục X"); // Index X PROGMEM Language_Str MSG_MESH_Y = _UxGT("Mục lục Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Giá trị Z"); // Z Value - PROGMEM Language_Str MSG_USER_MENU = _UxGT("Các lệnh tự chọn"); // Custom Commands + PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Các lệnh tự chọn"); // Custom Commands PROGMEM Language_Str MSG_UBL_DOING_G29 = _UxGT("Đang chạy G29"); // Doing G29 PROGMEM Language_Str MSG_UBL_TOOLS = _UxGT("Công cụ UBL"); // UBL tools PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("San Lấp Bàn Thống Nhất (UBL)"); // Unified Bed Leveling @@ -205,6 +205,7 @@ namespace Language_vi { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Di chuyển 0.1mm"); // Move 0.1mm PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Di chuyển 1mm"); // Move 1mm PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Di chuyển 10mm"); // Move 10mm + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Di chuyển 100mm"); // Move 100mm PROGMEM Language_Str MSG_SPEED = _UxGT("Tốc độ"); // Speed PROGMEM Language_Str MSG_BED_Z = _UxGT("Z Bàn"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Đầu phun"); // Nozzle @@ -257,7 +258,7 @@ namespace Language_vi { PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Nhiệt độ"); // Temperature PROGMEM Language_Str MSG_MOTION = _UxGT("Chuyển động"); // Motion PROGMEM Language_Str MSG_FILAMENT = _UxGT("Vật liệu in"); // dây nhựa - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E bằng mm³"); // E in mm + PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E bằng mm") SUPERSCRIPT_THREE; // E in mm PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Đường kính nhựa"); // Fil. Dai. PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Đường kính nhựa *"); PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Dỡ mm"); // unload mm diff --git a/Marlin/src/lcd/language/language_zh_CN.h b/Marlin/src/lcd/language/language_zh_CN.h index 3bebe12fda8d..31d262360489 100644 --- a/Marlin/src/lcd/language/language_zh_CN.h +++ b/Marlin/src/lcd/language/language_zh_CN.h @@ -31,7 +31,7 @@ namespace Language_zh_CN { using namespace Language_en; // Inherit undefined strings from English constexpr uint8_t CHARSIZE = 3; - PROGMEM Language_Str LANGUAGE = _UxGT("简体中文"); + PROGMEM Language_Str LANGUAGE = _UxGT("Simplified Chinese"); PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT("已就绪."); //" ready." PROGMEM Language_Str MSG_MARLIN = _UxGT("马林"); @@ -51,7 +51,7 @@ namespace Language_zh_CN { PROGMEM Language_Str MSG_MAIN = _UxGT("主菜单"); //"Main" PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("高级设置"); PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("配置"); - PROGMEM Language_Str MSG_AUTOSTART = _UxGT("自动开始"); //"Autostart" + PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("自动开始"); //"Autostart" PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("关闭步进电机"); //"Disable steppers" PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("调试菜单"); // "Debug Menu" PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("进度条测试"); // "Progress Bar Test" @@ -89,12 +89,8 @@ namespace Language_zh_CN { PROGMEM Language_Str MSG_COOLDOWN = _UxGT("降温"); //"Cooldown" PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("切割频率"); PROGMEM Language_Str MSG_LASER_MENU = _UxGT("激光控制"); - PROGMEM Language_Str MSG_LASER_OFF = _UxGT("激光关"); - PROGMEM Language_Str MSG_LASER_ON = _UxGT("激光开"); PROGMEM Language_Str MSG_LASER_POWER = _UxGT("激光电源"); PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("主轴控制"); - PROGMEM Language_Str MSG_SPINDLE_OFF = _UxGT("主轴关"); - PROGMEM Language_Str MSG_SPINDLE_ON = _UxGT("主轴开"); PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("主轴电源"); PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("主轴反转"); PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("电源打开"); //"Switch power on" @@ -104,7 +100,7 @@ namespace Language_zh_CN { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("移动轴"); //"Move axis" PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("调平热床"); //"Bed leveling" PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("调平热床"); //"Level bed" - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("调平边角"); // "Level corners" + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("调平边角"); // "Bed Tramming" PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("下个边角"); // "Next corner" PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("网格编辑器"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("编辑网格"); // "Edit Mesh" @@ -113,7 +109,7 @@ namespace Language_zh_CN { PROGMEM Language_Str MSG_MESH_X = _UxGT("索引X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("索引Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Z 值"); - PROGMEM Language_Str MSG_USER_MENU = _UxGT("定制命令"); // "Custom Commands" + PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("定制命令"); // "Custom Commands" PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48探测"); PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48点"); PROGMEM Language_Str MSG_M48_DEVIATION = _UxGT("M48偏差"); @@ -230,10 +226,11 @@ namespace Language_zh_CN { PROGMEM Language_Str MSG_MOVE_E = _UxGT("挤出机"); //"Extruder" PROGMEM Language_Str MSG_MOVE_EN = _UxGT("挤出机 *"); //"Extruder" PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("热端太冷"); - PROGMEM Language_Str MSG_MOVE_Z_DIST = _UxGT("移动 %s mm"); //"Move 0.025mm" + PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("移动 %s mm"); //"Move 0.025mm" PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("移动 0.1 mm"); //"Move 0.1mm" PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("移动 1 mm"); //"Move 1mm" PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("移动 10 mm"); //"Move 10mm" + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("移动 100 mm"); //"Move 100mm" PROGMEM Language_Str MSG_SPEED = _UxGT("速率"); //"Speed" PROGMEM Language_Str MSG_BED_Z = _UxGT("热床Z"); //"Bed Z" PROGMEM Language_Str MSG_NOZZLE = _UxGT("喷嘴"); //"Nozzle" 噴嘴 @@ -267,16 +264,6 @@ namespace Language_zh_CN { PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("自动调失败. 坏的挤出机"); PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("自动调失败. 温度太高"); PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("自动调失败! 超时"); - PROGMEM Language_Str MSG_PID_P = _UxGT("PID-P"); - PROGMEM Language_Str MSG_PID_P_E = _UxGT("PID-P *"); - PROGMEM Language_Str MSG_PID_I = _UxGT("PID-I"); - PROGMEM Language_Str MSG_PID_I_E = _UxGT("PID-I *"); - PROGMEM Language_Str MSG_PID_D = _UxGT("PID-D"); - PROGMEM Language_Str MSG_PID_D_E = _UxGT("PID-D *"); - PROGMEM Language_Str MSG_PID_C = _UxGT("PID-C"); - PROGMEM Language_Str MSG_PID_C_E = _UxGT("PID-C *"); - PROGMEM Language_Str MSG_PID_F = _UxGT("PID-F"); - PROGMEM Language_Str MSG_PID_F_E = _UxGT("PID-F *"); PROGMEM Language_Str MSG_SELECT = _UxGT("选择"); //"Select" PROGMEM Language_Str MSG_SELECT_E = _UxGT("选择 *"); PROGMEM Language_Str MSG_ACC = _UxGT("加速度"); //"Accel" acceleration @@ -313,8 +300,8 @@ namespace Language_zh_CN { PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("温度"); //"Temperature" PROGMEM Language_Str MSG_MOTION = _UxGT("运动"); //"Motion" PROGMEM Language_Str MSG_FILAMENT = _UxGT("料丝"); //"Filament" menu_advanced_filament - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E 在 mm³"); //"E in mm3" volumetric_enabled - PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("E 限制 在 mm³"); + PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E 在 mm") SUPERSCRIPT_THREE; //"E in mm3" volumetric_enabled + PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("E 限制 在 mm") SUPERSCRIPT_THREE; PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT_E = _UxGT("E 限制 *"); PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("丝料直径"); //"Fil. Dia." PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("丝料直径 *"); diff --git a/Marlin/src/lcd/language/language_zh_TW.h b/Marlin/src/lcd/language/language_zh_TW.h index 7abf895d5457..f162536132bd 100644 --- a/Marlin/src/lcd/language/language_zh_TW.h +++ b/Marlin/src/lcd/language/language_zh_TW.h @@ -50,7 +50,7 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_MAIN = _UxGT("主選單"); //"Main" PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("進階設置"); //"Advanced Settings" PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("設置"); //Configuration - PROGMEM Language_Str MSG_AUTOSTART = _UxGT("自動開始"); //"Autostart" + PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("自動開始"); //"Autostart" PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("關閉步進馬達"); //"Disable steppers" PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("除錯選單"); // "Debug Menu" PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("進度條測試"); // "Progress Bar Test" @@ -87,12 +87,8 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("自定預熱"); //"Preheat Custom" PROGMEM Language_Str MSG_COOLDOWN = _UxGT("降溫"); //"Cooldown" PROGMEM Language_Str MSG_LASER_MENU = _UxGT("激光控制"); //"Laser Control" - PROGMEM Language_Str MSG_LASER_OFF = _UxGT("激光 關"); //"Laser Off" - PROGMEM Language_Str MSG_LASER_ON = _UxGT("激光 開"); //"Laser On" PROGMEM Language_Str MSG_LASER_POWER = _UxGT("激光電源"); //"Laser Power" PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("主軸控告制"); //"Spindle Control" - PROGMEM Language_Str MSG_SPINDLE_OFF = _UxGT("主軸 關"); //"Spindle Off" - PROGMEM Language_Str MSG_SPINDLE_ON = _UxGT("主軸 開"); //"Spindle On" PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("主軸電源"); //"Spindle Power" PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("主軸反轉"); //"Spindle Reverse" PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("電源打開"); //"Switch power on" @@ -102,7 +98,7 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("移動軸"); //"Move axis" PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("調平熱床"); //"Bed leveling" PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("調平熱床"); //"Level bed" - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("調平邊角"); // "Level corners" + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("調平邊角"); // "Bed Tramming" PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("下個邊角"); // "Next corner" PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("網格編輯器"); //"Mesh Editor" PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("編輯網格"); // "Edit Mesh" @@ -111,7 +107,7 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_MESH_X = _UxGT("索引 X"); //"Index X" PROGMEM Language_Str MSG_MESH_Y = _UxGT("索引 Y"); //"Index Y" PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Z 值"); //"Z Value" - PROGMEM Language_Str MSG_USER_MENU = _UxGT("自定命令"); // "Custom Commands" + PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("自定命令"); // "Custom Commands" PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 探測測試"); //"M48 Probe Test" PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 探測點"); //"M48 Point" PROGMEM Language_Str MSG_M48_DEVIATION = _UxGT("偏差"); //"Deviation" @@ -227,11 +223,12 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_MOVE_Z = _UxGT("移動Z"); //"Move Z" PROGMEM Language_Str MSG_MOVE_E = _UxGT("擠出機"); //"Extruder" PROGMEM Language_Str MSG_MOVE_EN = _UxGT("擠出機 *"); //"Extruder *" - PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("噴嘴溫度不夠"); //"Hotend too cold" - PROGMEM Language_Str MSG_MOVE_Z_DIST = _UxGT("移動 %s mm"); //"Move 0.025mm" - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("移動 0.1 mm"); //"Move 0.1mm" - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("移動 1 mm"); //"Move 1mm" + PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("噴嘴溫度不夠"); //"Hotend too cold" + PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("移動 %s mm"); //"Move 0.025mm" + PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("移動 0.1 mm"); //"Move 0.1mm" + PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("移動 1 mm"); //"Move 1mm" PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("移動 10 mm"); //"Move 10mm" + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("移動 100 mm"); //"Move 100mm" PROGMEM Language_Str MSG_SPEED = _UxGT("速率"); //"Speed" PROGMEM Language_Str MSG_BED_Z = _UxGT("熱床Z"); //"Bed Z" PROGMEM Language_Str MSG_NOZZLE = " " LCD_STR_THERMOMETER _UxGT(" 噴嘴"); //"Nozzle" 噴嘴 @@ -287,7 +284,7 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("溫度"); //"Temperature" PROGMEM Language_Str MSG_MOTION = _UxGT("運作"); //"Motion" PROGMEM Language_Str MSG_FILAMENT = _UxGT("絲料測容"); //"Filament" menu_control_volumetric - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("測容積mm³"); //"E in mm3" volumetric_enabled + PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("測容積mm") SUPERSCRIPT_THREE; //"E in mm3" volumetric_enabled PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("絲料直徑"); //"Fil. Dia." PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("絲料直徑 *"); PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("卸載 mm"); // "Unload mm" diff --git a/Marlin/src/lcd/lcdprint.cpp b/Marlin/src/lcd/lcdprint.cpp index e381c590f578..eef27dbdb4bc 100644 --- a/Marlin/src/lcd/lcdprint.cpp +++ b/Marlin/src/lcd/lcdprint.cpp @@ -26,15 +26,22 @@ #include "../inc/MarlinConfigPre.h" -#if HAS_WIRED_LCD +#if HAS_WIRED_LCD && !HAS_GRAPHICAL_TFT +#include "marlinui.h" #include "lcdprint.h" /** * lcd_put_u8str_ind_P - * Print a string with an index substituted within it + * + * Print a string with an index substituted within it: + * + * = 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) */ lcd_uint_t lcd_put_u8str_ind_P(PGM_P const pstr, const int8_t ind, PGM_P const inStr/*=nullptr*/, const lcd_uint_t maxlen/*=LCD_WIDTH*/) { + const uint8_t prop = USE_WIDE_GLYPH ? 2 : 1; uint8_t *p = (uint8_t*)pstr; int8_t n = maxlen; while (n > 0) { @@ -67,10 +74,27 @@ lcd_uint_t lcd_put_u8str_ind_P(PGM_P const pstr, const int8_t ind, PGM_P const i } else { lcd_put_wchar(ch); - n--; + n -= ch > 255 ? prop : 1; } } return n; } +// Calculate UTF8 width with a simple check +int calculateWidth(PGM_P const pstr) { + if (!USE_WIDE_GLYPH) return utf8_strlen_P(pstr) * MENU_FONT_WIDTH; + const uint8_t prop = 2; + uint8_t *p = (uint8_t*)pstr; + int n = 0; + + do { + wchar_t ch; + p = get_utf8_value_cb(p, read_byte_rom, &ch); + if (!ch) break; + n += (ch > 255) ? prop : 1; + } while (1); + + return n * MENU_FONT_WIDTH; +} + #endif // HAS_WIRED_LCD diff --git a/Marlin/src/lcd/lcdprint.h b/Marlin/src/lcd/lcdprint.h index cf34a7ade92e..32d958bf7f33 100644 --- a/Marlin/src/lcd/lcdprint.h +++ b/Marlin/src/lcd/lcdprint.h @@ -76,8 +76,9 @@ #define INFO_FONT_HEIGHT (INFO_FONT_ASCENT + INFO_FONT_DESCENT) #define INFO_FONT_WIDTH 6 - #define SETCURSOR(col, row) lcd_moveto((col) * (MENU_FONT_WIDTH), ((row) + 1) * (MENU_FONT_HEIGHT)) - #define SETCURSOR_RJ(len, row) lcd_moveto(LCD_PIXEL_WIDTH - (len) * (MENU_FONT_WIDTH), ((row) + 1) * (MENU_FONT_HEIGHT)) + // Graphical LCD uses the menu font size for cursor positioning + #define LCD_COL_X(col) (( (col)) * (MENU_FONT_WIDTH)) + #define LCD_ROW_Y(row) ((1 + (row)) * (MENU_LINE_HEIGHT)) #else @@ -94,14 +95,21 @@ #define LCD_PIXEL_WIDTH LCD_WIDTH #define LCD_PIXEL_HEIGHT LCD_HEIGHT - #define SETCURSOR(col, row) lcd_moveto(col, row) - #define SETCURSOR_RJ(len, row) SETCURSOR(LCD_WIDTH - (len), row) + // Character LCD uses direct cursor positioning + #define LCD_COL_X(col) (col) + #define LCD_ROW_Y(row) (row) #endif -#define SETCURSOR_X(col) SETCURSOR(col, _lcdLineNr) -#define SETCURSOR_X_RJ(len) SETCURSOR_RJ(len, _lcdLineNr) -#define START_OF_UTF8_CHAR(C) (((C) & 0xC0u) != 0x80U) +#ifndef MENU_LINE_HEIGHT + #define MENU_LINE_HEIGHT MENU_FONT_HEIGHT +#endif + +#define LCD_COL_X_RJ(len) (LCD_PIXEL_WIDTH - LCD_COL_X(len)) +#define SETCURSOR(col, row) lcd_moveto(LCD_COL_X(col), LCD_ROW_Y(row)) +#define SETCURSOR_RJ(len, row) lcd_moveto(LCD_COL_X_RJ(len), LCD_ROW_Y(row)) +#define SETCURSOR_X(col) SETCURSOR(col, _lcdLineNr) +#define SETCURSOR_X_RJ(len) SETCURSOR_RJ(len, _lcdLineNr) int lcd_glyph_height(); @@ -158,7 +166,7 @@ inline lcd_uint_t lcd_put_u8str_ind_P(const lcd_uint_t col, const lcd_uint_t row return lcd_put_u8str_ind_P(pstr, ind, inStr, maxlen); } -inline int lcd_put_u8str(const char* str) { return lcd_put_u8str_max(str, PIXEL_LEN_NOLIMIT); } +inline int lcd_put_u8str(const char *str) { return lcd_put_u8str_max(str, PIXEL_LEN_NOLIMIT); } inline int lcd_put_u8str(const lcd_uint_t col, const lcd_uint_t row, PGM_P const str) { lcd_moveto(col, row); return lcd_put_u8str(str); @@ -169,3 +177,5 @@ inline int lcd_put_wchar(const lcd_uint_t col, const lcd_uint_t row, const wchar lcd_moveto(col, row); return lcd_put_wchar(c); } + +int calculateWidth(PGM_P const pstr); diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp new file mode 100644 index 000000000000..438a7eeaa105 --- /dev/null +++ b/Marlin/src/lcd/marlinui.cpp @@ -0,0 +1,1752 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../inc/MarlinConfig.h" + +#include "../MarlinCore.h" // for printingIsPaused + +#ifdef LED_BACKLIGHT_TIMEOUT + #include "../feature/leds/leds.h" +#endif + +#if ENABLED(HOST_ACTION_COMMANDS) + #include "../feature/host_actions.h" +#endif + +#if ENABLED(BROWSE_MEDIA_ON_INSERT, PASSWORD_ON_SD_PRINT_MENU) + #include "../feature/password/password.h" +#endif + +// All displays share the MarlinUI class +#include "marlinui.h" +MarlinUI ui; + +#if HAS_DISPLAY + #include "../gcode/queue.h" + #include "fontutils.h" + #include "../sd/cardreader.h" +#endif + +#if ENABLED(DWIN_CREALITY_LCD) + #include "e3v2/creality/dwin.h" +#endif + +#if ENABLED(LCD_PROGRESS_BAR) && !IS_TFTGLCD_PANEL + #define BASIC_PROGRESS_BAR 1 +#endif + +#if ANY(HAS_DISPLAY, HAS_STATUS_MESSAGE, BASIC_PROGRESS_BAR) + #include "../module/printcounter.h" +#endif + +#if LCD_HAS_WAIT_FOR_MOVE + bool MarlinUI::wait_for_move; // = false +#endif + +constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; + +#if HAS_STATUS_MESSAGE + #if BOTH(HAS_WIRED_LCD, STATUS_MESSAGE_SCROLLING) + uint8_t MarlinUI::status_scroll_offset; // = 0 + #endif + char MarlinUI::status_message[MAX_MESSAGE_LENGTH + 1]; + uint8_t MarlinUI::alert_level; // = 0 +#endif + +#if ENABLED(LCD_SET_PROGRESS_MANUALLY) + MarlinUI::progress_t MarlinUI::progress_override; // = 0 + #if ENABLED(USE_M73_REMAINING_TIME) + uint32_t MarlinUI::remaining_time; + #endif +#endif + +#if HAS_MULTI_LANGUAGE + uint8_t MarlinUI::language; // Initialized by settings.load() + void MarlinUI::set_language(const uint8_t lang) { + if (lang < NUM_LANGUAGES) { + language = lang; + TERN_(HAS_MARLINUI_U8GLIB, update_language_font()); + return_to_status(); + refresh(); + } + } +#endif + +#if HAS_LCD_BRIGHTNESS + uint8_t MarlinUI::brightness = DEFAULT_LCD_BRIGHTNESS; + bool MarlinUI::backlight = true; + + void MarlinUI::set_brightness(const uint8_t value) { + backlight = !!value; + if (backlight) brightness = constrain(value, MIN_LCD_BRIGHTNESS, MAX_LCD_BRIGHTNESS); + // Set brightness on enabled LCD here + } +#endif + +#if ENABLED(SOUND_MENU_ITEM) + bool MarlinUI::buzzer_enabled = true; +#endif + +#if EITHER(PCA9632_BUZZER, USE_BEEPER) + #include "../libs/buzzer.h" // for BUZZ() macro + #if ENABLED(PCA9632_BUZZER) + #include "../feature/leds/pca9632.h" + #endif + void MarlinUI::buzz(const long duration, const uint16_t freq) { + if (!buzzer_enabled) return; + #if ENABLED(PCA9632_BUZZER) + PCA9632_buzz(duration, freq); + #elif USE_BEEPER + buzzer.tone(duration, freq); + #endif + } +#endif + +#if PREHEAT_COUNT + preheat_t MarlinUI::material_preset[PREHEAT_COUNT]; // Initialized by settings.load() + PGM_P MarlinUI::get_preheat_label(const uint8_t m) { + #define _PDEF(N) static PGMSTR(preheat_##N##_label, PREHEAT_##N##_LABEL); + #define _PLBL(N) preheat_##N##_label, + REPEAT_1(PREHEAT_COUNT, _PDEF); + static PGM_P const preheat_labels[PREHEAT_COUNT] PROGMEM = { REPEAT_1(PREHEAT_COUNT, _PLBL) }; + return (PGM_P)pgm_read_ptr(&preheat_labels[m]); + } +#endif + +#if EITHER(HAS_LCD_MENU, EXTENSIBLE_UI) + bool MarlinUI::lcd_clicked; +#endif + +#if HAS_WIRED_LCD + + #if HAS_MARLINUI_U8GLIB + #include "dogm/marlinui_DOGM.h" + #endif + + #include "lcdprint.h" + + #include "../sd/cardreader.h" + + #include "../module/temperature.h" + #include "../module/planner.h" + #include "../module/motion.h" + + #if HAS_LCD_MENU + #include "../module/settings.h" + #endif + + #if ENABLED(AUTO_BED_LEVELING_UBL) + #include "../feature/bedlevel/bedlevel.h" + #endif + + #if HAS_TRINAMIC_CONFIG + #include "../feature/tmc_util.h" + #endif + + #if HAS_ADC_BUTTONS + #include "../module/thermistor/thermistors.h" + #endif + + #if HAS_POWER_MONITOR + #include "../feature/power_monitor.h" + #endif + + #if HAS_ENCODER_ACTION + volatile uint8_t MarlinUI::buttons; + #if HAS_SLOW_BUTTONS + volatile uint8_t MarlinUI::slow_buttons; + #endif + #if HAS_TOUCH_BUTTONS + #include "touch/touch_buttons.h" + bool MarlinUI::on_edit_screen = false; + #endif + #endif + + #if SCREENS_CAN_TIME_OUT + bool MarlinUI::defer_return_to_status; + millis_t MarlinUI::return_to_status_ms = 0; + #endif + + uint8_t MarlinUI::lcd_status_update_delay = 1; // First update one loop delayed + + #if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) + millis_t MarlinUI::next_filament_display; // = 0 + #endif + + millis_t MarlinUI::next_button_update_ms; // = 0 + + #if HAS_MARLINUI_U8GLIB + bool MarlinUI::drawing_screen, MarlinUI::first_page; // = false + #endif + + // Encoder Handling + #if HAS_ENCODER_ACTION + uint32_t MarlinUI::encoderPosition; + volatile int8_t encoderDiff; // Updated in update_buttons, added to encoderPosition every LCD update + #endif + + #if ENABLED(SDSUPPORT) + + #include "../sd/cardreader.h" + + #if MARLINUI_SCROLL_NAME + uint8_t MarlinUI::filename_scroll_pos, MarlinUI::filename_scroll_max; + #endif + + const char * MarlinUI::scrolled_filename(CardReader &theCard, const uint8_t maxlen, uint8_t hash, const bool doScroll) { + const char *outstr = theCard.longest_filename(); + if (theCard.longFilename[0]) { + #if MARLINUI_SCROLL_NAME + if (doScroll) { + for (uint8_t l = FILENAME_LENGTH; l--;) + hash = ((hash << 1) | (hash >> 7)) ^ theCard.filename[l]; // rotate, xor + static uint8_t filename_scroll_hash; + if (filename_scroll_hash != hash) { // If the hash changed... + filename_scroll_hash = hash; // Save the new hash + filename_scroll_max = _MAX(0, utf8_strlen(theCard.longFilename) - maxlen); // Update the scroll limit + filename_scroll_pos = 0; // Reset scroll to the start + lcd_status_update_delay = 8; // Don't scroll right away + } + // Advance byte position corresponding to filename_scroll_pos char position + outstr += TERN(UTF_FILENAME_SUPPORT, utf8_byte_pos_by_char_num(outstr, filename_scroll_pos), filename_scroll_pos); + } + #else + theCard.longFilename[ + TERN(UTF_FILENAME_SUPPORT, utf8_byte_pos_by_char_num(theCard.longFilename, maxlen), maxlen) + ] = '\0'; // cutoff at screen edge + #endif + } + return outstr; + } + + #endif + + #if HAS_LCD_MENU + #include "menu/menu.h" + + screenFunc_t MarlinUI::currentScreen; // Initialized in CTOR + bool MarlinUI::screen_changed; + + #if ENABLED(ENCODER_RATE_MULTIPLIER) + bool MarlinUI::encoderRateMultiplierEnabled; + millis_t MarlinUI::lastEncoderMovementMillis = 0; + void MarlinUI::enable_encoder_multiplier(const bool onoff) { + encoderRateMultiplierEnabled = onoff; + lastEncoderMovementMillis = 0; + } + #endif + + #if EITHER(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; + #endif + + #if EITHER(AUTO_BED_LEVELING_UBL, G26_MESH_VALIDATION) + + bool MarlinUI::external_control; // = false + + void MarlinUI::wait_for_release() { + while (button_pressed()) safe_delay(50); + safe_delay(50); + } + + #endif + + #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*/) { + SETCURSOR(col, row); + if (!string) return; + + auto _newline = [&col, &row]{ + col = 0; row++; // Move col to string len (plus space) + SETCURSOR(0, row); // Simulate carriage return + }; + + uint8_t *p = (uint8_t*)string; + wchar_t ch; + if (wordwrap) { + uint8_t *wrd = nullptr, c = 0; + // find the end of the part + for (;;) { + if (!wrd) wrd = p; // Get word start /before/ advancing + p = get_utf8_value_cb(p, cb_read_byte, &ch); + const bool eol = !ch; // zero ends the string + // End or a break between phrases? + if (eol || ch == ' ' || ch == '-' || ch == '+' || ch == '.') { + if (!c && ch == ' ') { 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 + col += c; // advance col to new position + while (c) { // character countdown + --c; // count down to zero + wrd = get_utf8_value_cb(wrd, cb_read_byte, &ch); // get characters again + lcd_put_wchar(ch); // character to the LCD + } + if (eol) break; // all done! + wrd = nullptr; // set up for next word + } + else c++; // count word characters + } + } + else { + for (;;) { + p = get_utf8_value_cb(p, cb_read_byte, &ch); + if (!ch) break; + lcd_put_wchar(ch); + col++; + if (col >= LCD_WIDTH) _newline(); + } + } + } + + void MarlinUI::draw_select_screen_prompt(PGM_P const pref, const char * const string/*=nullptr*/, PGM_P const suff/*=nullptr*/) { + const uint8_t plen = utf8_strlen_P(pref), slen = suff ? utf8_strlen_P(suff) : 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; + } + wrap_string_P(col, row, pref, 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, suff); + } + + #endif // !HAS_GRAPHICAL_TFT + + #endif // HAS_LCD_MENU + + void MarlinUI::init() { + + init_lcd(); + + #if HAS_DIGITAL_BUTTONS + #if BUTTON_EXISTS(EN1) + SET_INPUT_PULLUP(BTN_EN1); + #endif + #if BUTTON_EXISTS(EN2) + SET_INPUT_PULLUP(BTN_EN2); + #endif + #if BUTTON_EXISTS(ENC) + SET_INPUT_PULLUP(BTN_ENC); + #endif + #if BUTTON_EXISTS(ENC_EN) + SET_INPUT_PULLUP(BTN_ENC_EN); + #endif + #if BUTTON_EXISTS(BACK) + SET_INPUT_PULLUP(BTN_BACK); + #endif + #if BUTTON_EXISTS(UP) + SET_INPUT(BTN_UP); + #endif + #if BUTTON_EXISTS(DWN) + SET_INPUT(BTN_DWN); + #endif + #if BUTTON_EXISTS(LFT) + SET_INPUT(BTN_LFT); + #endif + #if BUTTON_EXISTS(RT) + SET_INPUT(BTN_RT); + #endif + #endif + + #if HAS_SHIFT_ENCODER + + #if ENABLED(SR_LCD_2W_NL) // Non latching 2 wire shift register + + SET_OUTPUT(SR_DATA_PIN); + SET_OUTPUT(SR_CLK_PIN); + + #elif PIN_EXISTS(SHIFT_CLK) + + SET_OUTPUT(SHIFT_CLK_PIN); + OUT_WRITE(SHIFT_LD_PIN, HIGH); + #if PIN_EXISTS(SHIFT_EN) + OUT_WRITE(SHIFT_EN_PIN, LOW); + #endif + SET_INPUT_PULLUP(SHIFT_OUT_PIN); + + #endif + + #endif // HAS_SHIFT_ENCODER + + #if BOTH(HAS_ENCODER_ACTION, HAS_SLOW_BUTTONS) + slow_buttons = 0; + #endif + + update_buttons(); + + TERN_(HAS_ENCODER_ACTION, encoderDiff = 0); + } + + bool MarlinUI::get_blink() { + static uint8_t blink = 0; + static millis_t next_blink_ms = 0; + millis_t ms = millis(); + if (ELAPSED(ms, next_blink_ms)) { + blink ^= 0xFF; + next_blink_ms = ms + 1000 - (LCD_UPDATE_INTERVAL) / 2; + } + return blink != 0; + } + + //////////////////////////////////////////// + ///////////// Keypad Handling ////////////// + //////////////////////////////////////////// + + #if IS_RRW_KEYPAD && HAS_ENCODER_ACTION + + volatile uint8_t MarlinUI::keypad_buttons; + + #if HAS_LCD_MENU && !HAS_ADC_BUTTONS + + void lcd_move_x(); + void lcd_move_y(); + void lcd_move_z(); + + void _reprapworld_keypad_move(const AxisEnum axis, const int16_t dir) { + ui.manual_move.menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP; + ui.encoderPosition = dir; + switch (axis) { + case X_AXIS: lcd_move_x(); break; + case Y_AXIS: lcd_move_y(); break; + case Z_AXIS: lcd_move_z(); + default: break; + } + } + + #endif + + bool MarlinUI::handle_keypad() { + + #if HAS_ADC_BUTTONS + + #define ADC_MIN_KEY_DELAY 100 + if (keypad_buttons) { + #if HAS_ENCODER_ACTION + refresh(LCDVIEW_REDRAW_NOW); + #if HAS_LCD_MENU + if (encoderDirection == -(ENCODERBASE)) { // HAS_ADC_BUTTONS forces REVERSE_MENU_DIRECTION, so this indicates menu navigation + if (RRK(EN_KEYPAD_UP)) encoderPosition += ENCODER_STEPS_PER_MENU_ITEM; + else if (RRK(EN_KEYPAD_DOWN)) encoderPosition -= ENCODER_STEPS_PER_MENU_ITEM; + else if (RRK(EN_KEYPAD_LEFT)) { MenuItem_back::action(); quick_feedback(); } + else if (RRK(EN_KEYPAD_RIGHT)) { return_to_status(); quick_feedback(); } + } + else + #endif + { + #if HAS_LCD_MENU + if (RRK(EN_KEYPAD_UP)) encoderPosition -= epps; + else if (RRK(EN_KEYPAD_DOWN)) encoderPosition += epps; + else if (RRK(EN_KEYPAD_LEFT)) { MenuItem_back::action(); quick_feedback(); } + else if (RRK(EN_KEYPAD_RIGHT)) encoderPosition = 0; + #else + if (RRK(EN_KEYPAD_UP) || RRK(EN_KEYPAD_LEFT)) encoderPosition -= epps; + else if (RRK(EN_KEYPAD_DOWN) || RRK(EN_KEYPAD_RIGHT)) encoderPosition += epps; + #endif + } + #endif + next_button_update_ms = millis() + ADC_MIN_KEY_DELAY; + return true; + } + + #else // !HAS_ADC_BUTTONS + + static uint8_t keypad_debounce = 0; + + if (!RRK( EN_KEYPAD_F1 | EN_KEYPAD_F2 + | EN_KEYPAD_F3 | EN_KEYPAD_DOWN + | EN_KEYPAD_RIGHT | EN_KEYPAD_MIDDLE + | EN_KEYPAD_UP | EN_KEYPAD_LEFT ) + ) { + if (keypad_debounce > 0) keypad_debounce--; + } + else if (!keypad_debounce) { + keypad_debounce = 2; + + const bool homed = all_axes_homed(); + + #if HAS_LCD_MENU + + if (RRK(EN_KEYPAD_MIDDLE)) goto_screen(menu_move); + + #if NONE(DELTA, Z_HOME_TO_MAX) + if (RRK(EN_KEYPAD_F2)) _reprapworld_keypad_move(Z_AXIS, 1); + #endif + + if (homed) { + #if EITHER(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); + if (RRK(EN_KEYPAD_LEFT)) _reprapworld_keypad_move(X_AXIS, -1); + if (RRK(EN_KEYPAD_RIGHT)) _reprapworld_keypad_move(X_AXIS, 1); + if (RRK(EN_KEYPAD_DOWN)) _reprapworld_keypad_move(Y_AXIS, 1); + if (RRK(EN_KEYPAD_UP)) _reprapworld_keypad_move(Y_AXIS, -1); + } + + #endif // HAS_LCD_MENU + + if (!homed && RRK(EN_KEYPAD_F1)) queue.inject_P(G28_STR); + return true; + } + + #endif // !HAS_ADC_BUTTONS + + return false; + } + + #endif // IS_RRW_KEYPAD && HAS_ENCODER_ACTION + + /** + * Status Screen + * + * This is very display-dependent, so the lcd implementation draws this. + */ + + #if BASIC_PROGRESS_BAR + millis_t MarlinUI::progress_bar_ms; // = 0 + #if PROGRESS_MSG_EXPIRE > 0 + millis_t MarlinUI::expire_status_ms; // = 0 + #endif + #endif + + void MarlinUI::status_screen() { + + TERN_(HAS_LCD_MENU, ENCODER_RATE_MULTIPLY(false)); + + #if BASIC_PROGRESS_BAR + + // + // HD44780 implements the following message blinking and + // message expiration because Status Line and Progress Bar + // share the same line on the display. + // + + #if DISABLED(PROGRESS_MSG_ONCE) || (PROGRESS_MSG_EXPIRE > 0) + #define GOT_MS + const millis_t ms = millis(); + #endif + + // If the message will blink rather than expire... + #if DISABLED(PROGRESS_MSG_ONCE) + if (ELAPSED(ms, progress_bar_ms + PROGRESS_BAR_MSG_TIME + PROGRESS_BAR_BAR_TIME)) + progress_bar_ms = ms; + #endif + + #if PROGRESS_MSG_EXPIRE > 0 + + // Handle message expire + if (expire_status_ms) { + + // Expire the message if a job is active and the bar has ticks + if (get_progress_percent() > 2 && !print_job_timer.isPaused()) { + if (ELAPSED(ms, expire_status_ms)) { + status_message[0] = '\0'; + expire_status_ms = 0; + } + } + else { + // Defer message expiration before bar appears + // and during any pause (not just SD) + expire_status_ms += LCD_UPDATE_INTERVAL; + } + } + + #endif // PROGRESS_MSG_EXPIRE + + #endif // BASIC_PROGRESS_BAR + + #if HAS_LCD_MENU + if (use_click()) { + #if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) + next_filament_display = millis() + 5000UL; // Show status message for 5s + #endif + goto_screen(menu_main); + #if DISABLED(NO_LCD_REINIT) + init_lcd(); // May revive the LCD if static electricity killed it + #endif + return; + } + + #endif + + #if ENABLED(ULTIPANEL_FEEDMULTIPLY) + + const int16_t old_frm = feedrate_percentage; + int16_t new_frm = old_frm + int16_t(encoderPosition); + + // Dead zone at 100% feedrate + if (old_frm == 100) { + if (int16_t(encoderPosition) > ENCODER_FEEDRATE_DEADZONE) + new_frm -= ENCODER_FEEDRATE_DEADZONE; + else if (int16_t(encoderPosition) < -(ENCODER_FEEDRATE_DEADZONE)) + new_frm += ENCODER_FEEDRATE_DEADZONE; + else + new_frm = old_frm; + } + else if ((old_frm < 100 && new_frm > 100) || (old_frm > 100 && new_frm < 100)) + new_frm = 100; + + LIMIT(new_frm, 10, 999); + + if (old_frm != new_frm) { + feedrate_percentage = new_frm; + encoderPosition = 0; + #if BOTH(HAS_BUZZER, BEEP_ON_FEEDRATE_CHANGE) + static millis_t next_beep; + #ifndef GOT_MS + const millis_t ms = millis(); + #endif + if (ELAPSED(ms, next_beep)) { + buzz(FEEDRATE_CHANGE_BEEP_DURATION, FEEDRATE_CHANGE_BEEP_FREQUENCY); + next_beep = ms + 500UL; + } + #endif + } + + #endif // ULTIPANEL_FEEDMULTIPLY + + draw_status_screen(); + } + + void MarlinUI::kill_screen(PGM_P lcd_error, PGM_P lcd_component) { + init(); + status_printf_P(1, PSTR(S_FMT ": " S_FMT), lcd_error, lcd_component); + TERN_(HAS_LCD_MENU, return_to_status()); + + // RED ALERT. RED ALERT. + #ifdef LED_BACKLIGHT_TIMEOUT + leds.set_color(LEDColorRed()); + #ifdef NEOPIXEL_BKGD_INDEX_FIRST + neo.set_background_color(255, 0, 0, 0); + neo.show(); + #endif + #endif + + draw_kill_screen(); + } + + void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { + + TERN_(HAS_LCD_MENU, refresh()); + + #if HAS_ENCODER_ACTION + if (clear_buttons) buttons = 0; + next_button_update_ms = millis() + 500; + #else + UNUSED(clear_buttons); + #endif + + #if HAS_CHIRP + chirp(); // Buzz and wait. Is the delay needed for buttons to settle? + #if BOTH(HAS_LCD_MENU, USE_BEEPER) + for (int8_t i = 5; i--;) { buzzer.tick(); delay(2); } + #elif HAS_LCD_MENU + delay(10); + #endif + #endif + } + + //////////////////////////////////////////// + /////////////// Manual Move //////////////// + //////////////////////////////////////////// + + #if HAS_LCD_MENU + + ManualMove MarlinUI::manual_move{}; + + millis_t ManualMove::start_time = 0; + float ManualMove::menu_scale = 1; + #if IS_KINEMATIC + float ManualMove::offset = 0; + xyze_pos_t ManualMove::all_axes_destination = { 0 }; + bool ManualMove::processing = false; + #endif + #if MULTI_E_MANUAL + int8_t ManualMove::e_index = 0; + #endif + AxisEnum ManualMove::axis = NO_AXIS_ENUM; + + /** + * If a manual move has been posted and its time has arrived, and if the planner + * has a space for it, then add a linear move to current_position the planner. + * + * If any manual move needs to be interrupted, make sure to force a manual move + * by setting manual_move.start_time to millis() after updating current_position. + * + * To post a manual move: + * - Update current_position to the new place you want to go. + * - Set manual_move.axis to an axis like X_AXIS. Use ALL_AXES_ENUM for diagonal moves. + * - Set manual_move.start_time to a point in the future (in ms) when the move should be done. + * + * For kinematic machines: + * - Set manual_move.offset to modify one axis and post the move. + * This is used to achieve more rapid stepping on kinematic machines. + * + * Currently used by the _lcd_move_xyz function in menu_motion.cpp + * and the ubl_map_move_to_xy function in menu_ubl.cpp. + */ + void ManualMove::task() { + + if (processing) return; // Prevent re-entry from idle() calls + + // Add a manual move to the queue? + if (axis != NO_AXIS_ENUM && ELAPSED(millis(), start_time) && !planner.is_full()) { + + const feedRate_t fr_mm_s = (axis <= LOGICAL_AXES) ? manual_feedrate_mm_s[axis] : XY_PROBE_FEEDRATE_MM_S; + + #if IS_KINEMATIC + + #if HAS_MULTI_EXTRUDER + REMEMBER(ae, active_extruder); + #if MULTI_E_MANUAL + if (axis == E_AXIS) active_extruder = e_index; + #endif + #endif + + // Apply a linear offset to a single axis + if (axis == ALL_AXES_ENUM) + destination = all_axes_destination; + else if (axis <= XYZE) { + destination = current_position; + destination[axis] += offset; + } + + // Reset for the next move + offset = 0; + axis = NO_AXIS_ENUM; + + // DELTA and SCARA machines use segmented moves, which could fill the planner during the call to + // move_to_destination. This will cause idle() to be called, which can then call this function while the + // previous invocation is being blocked. Modifications to offset shouldn't be made while + // processing is true or the planner will get out of sync. + processing = true; + prepare_internal_move_to_destination(fr_mm_s); // will set current_position from destination + processing = false; + + #else + + // For Cartesian / Core motion simply move to the current_position + planner.buffer_line(current_position, fr_mm_s, + TERN_(MULTI_E_MANUAL, axis == E_AXIS ? e_index :) active_extruder + ); + + //SERIAL_ECHOLNPAIR("Add planner.move with Axis ", AS_CHAR(axis_codes[axis]), " at FR ", fr_mm_s); + + axis = NO_AXIS_ENUM; + + #endif + } + } + + // + // Tell ui.update() to start a move to current_position after a short delay. + // + void ManualMove::soon(const AxisEnum move_axis + OPTARG(MULTI_E_MANUAL, const int8_t eindex/*=active_extruder*/) + ) { + 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_ECHOLNPAIR("Post Move with Axis ", AS_CHAR(axis_codes[axis]), " soon."); + } + + #if ENABLED(AUTO_BED_LEVELING_UBL) + + void MarlinUI::external_encoder() { + if (external_control && encoderDiff) { + ubl.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. + } + } + + #endif + + #endif // HAS_LCD_MENU + + /** + * Update the LCD, read encoder buttons, etc. + * - Read button states + * - Check the SD Card slot state + * - Act on RepRap World keypad input + * - Update the encoder position + * - Apply acceleration to the encoder position + * - Do refresh(LCDVIEW_CALL_REDRAW_NOW) on controller events + * - Reset the Info Screen timeout if there's any input + * - Update status indicators, if any + * + * Run the current LCD menu handler callback function: + * - Call the handler only if lcdDrawUpdate != LCDVIEW_NONE + * - Before calling the handler, LCDVIEW_CALL_NO_REDRAW => LCDVIEW_NONE + * - Call the menu handler. Menu handlers should do the following: + * - If a value changes, set lcdDrawUpdate to LCDVIEW_REDRAW_NOW and draw the value + * (Encoder events automatically set lcdDrawUpdate for you.) + * - if (should_draw()) { redraw } + * - Before exiting the handler set lcdDrawUpdate to: + * - LCDVIEW_CLEAR_CALL_REDRAW to clear screen and set LCDVIEW_CALL_REDRAW_NEXT. + * - LCDVIEW_REDRAW_NOW to draw now (including remaining stripes). + * - LCDVIEW_CALL_REDRAW_NEXT to draw now and get LCDVIEW_REDRAW_NOW on the next loop. + * - LCDVIEW_CALL_NO_REDRAW to draw now and get LCDVIEW_NONE on the next loop. + * - NOTE: For graphical displays menu handlers may be called 2 or more times per loop, + * so don't change lcdDrawUpdate without considering this. + * + * After the menu handler callback runs (or not): + * - Clear the LCD if lcdDrawUpdate == LCDVIEW_CLEAR_CALL_REDRAW + * - Update lcdDrawUpdate for the next loop (i.e., move one state down, usually) + * + * This function is only called from the main thread. + */ + + LCDViewAction MarlinUI::lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; + millis_t next_lcd_update_ms; + + inline bool can_encode() { + return !BUTTON_PRESSED(ENC_EN); // Update encoder only when ENC_EN is not LOW (pressed) + } + + void MarlinUI::update() { + + static uint16_t max_display_update_time = 0; + millis_t ms = millis(); + + #ifdef LED_BACKLIGHT_TIMEOUT + leds.update_timeout(powersupply_on); + #endif + + #if HAS_LCD_MENU + + // Handle any queued Move Axis motion + manual_move.task(); + + // Update button states for button_pressed(), etc. + // If the state changes the next update may be delayed 300-500ms. + update_buttons(); + + // If the action button is pressed... + static bool wait_for_unclick; // = false + + auto do_click = [&]{ + wait_for_unclick = true; // - Set debounce flag to ignore continuous clicks + lcd_clicked = !wait_for_user; // - Keep the click if not waiting for a user-click + wait_for_user = false; // - Any click clears wait for user + quick_feedback(); // - Always make a click sound + }; + + #if HAS_TOUCH_BUTTONS + if (touch_buttons) { + reset_status_timeout(ms); + if (touch_buttons & (EN_A | EN_B)) { // Menu arrows, in priority + if (ELAPSED(ms, next_button_update_ms)) { + encoderDiff = (ENCODER_STEPS_PER_MENU_ITEM) * epps * encoderDirection; + if (touch_buttons & EN_A) encoderDiff *= -1; + TERN_(AUTO_BED_LEVELING_UBL, external_encoder()); + next_button_update_ms = ms + repeat_delay; // Assume the repeat delay + if (!wait_for_unclick) { + next_button_update_ms += 250; // Longer delay on first press + wait_for_unclick = true; // Avoid Back/Select click while repeating + chirp(); + } + } + } + else if (!wait_for_unclick && (buttons & EN_C)) // OK button, if not waiting for a debounce release: + do_click(); + } + // keep wait_for_unclick value + #endif + + if (!touch_buttons) { + // Integrated LCD click handling via button_pressed + if (!external_control && button_pressed()) { + if (!wait_for_unclick) do_click(); // Handle the click + } + else + wait_for_unclick = false; + } + + if (LCD_BACK_CLICKED()) { + quick_feedback(); + goto_previous_screen(); + } + + #endif // HAS_LCD_MENU + + if (ELAPSED(ms, next_lcd_update_ms) || TERN0(HAS_MARLINUI_U8GLIB, drawing_screen)) { + + next_lcd_update_ms = ms + LCD_UPDATE_INTERVAL; + + #if HAS_TOUCH_BUTTONS + + if (on_status_screen()) next_lcd_update_ms += (LCD_UPDATE_INTERVAL) * 2; + + TERN_(HAS_ENCODER_ACTION, touch_buttons = touch.read_buttons()); + + #endif + + TERN_(LCD_HAS_STATUS_INDICATORS, update_indicators()); + + #if HAS_ENCODER_ACTION + + TERN_(HAS_SLOW_BUTTONS, slow_buttons = read_slow_buttons()); // Buttons that take too long to read in interrupt context + + if (TERN0(IS_RRW_KEYPAD, handle_keypad())) + reset_status_timeout(ms); + + uint8_t abs_diff = ABS(encoderDiff); + + #if ENCODER_PULSES_PER_STEP > 1 + // When reversing the encoder direction, a movement step can be missed because + // encoderDiff has a non-zero residual value, making the controller unresponsive. + // The fix clears the residual value when the encoder is idle. + // Also check if past half the threshold to compensate for missed single steps. + static int8_t lastEncoderDiff; + + // Timeout? No decoder change since last check. 10 or 20 times per second. + if (encoderDiff == lastEncoderDiff && abs_diff <= epps / 2) // Same direction & size but not over a half-step? + encoderDiff = 0; // Clear residual pulses. + else if (WITHIN(abs_diff, epps / 2 + 1, epps - 1)) { // Past half of threshold? + abs_diff = epps; // Treat as a full step size + encoderDiff = (encoderDiff < 0 ? -1 : 1) * abs_diff; // ...in the spin direction. + } + lastEncoderDiff = encoderDiff; + #endif + + const bool encoderPastThreshold = (abs_diff >= epps); + if (encoderPastThreshold || lcd_clicked) { + if (encoderPastThreshold && TERN1(IS_TFTGLCD_PANEL, !external_control)) { + + #if BOTH(HAS_LCD_MENU, ENCODER_RATE_MULTIPLIER) + + int32_t encoderMultiplier = 1; + + if (encoderRateMultiplierEnabled) { + const float encoderMovementSteps = float(abs_diff) / epps; + + if (lastEncoderMovementMillis) { + // Note that the rate is always calculated between two passes through the + // loop and that the abs of the encoderDiff value is tracked. + const float encoderStepRate = encoderMovementSteps / float(ms - lastEncoderMovementMillis) * 1000; + + if (encoderStepRate >= ENCODER_100X_STEPS_PER_SEC) encoderMultiplier = 100; + else if (encoderStepRate >= ENCODER_10X_STEPS_PER_SEC) encoderMultiplier = 10; + + // Enable to output the encoder steps per second value + //#define ENCODER_RATE_MULTIPLIER_DEBUG + #if ENABLED(ENCODER_RATE_MULTIPLIER_DEBUG) + SERIAL_ECHO_START(); + SERIAL_ECHOPAIR("Enc Step Rate: ", encoderStepRate); + SERIAL_ECHOPAIR(" Multiplier: ", encoderMultiplier); + SERIAL_ECHOPAIR(" ENCODER_10X_STEPS_PER_SEC: ", ENCODER_10X_STEPS_PER_SEC); + SERIAL_ECHOPAIR(" ENCODER_100X_STEPS_PER_SEC: ", ENCODER_100X_STEPS_PER_SEC); + SERIAL_EOL(); + #endif + } + + lastEncoderMovementMillis = ms; + } // encoderRateMultiplierEnabled + + #else + + constexpr int32_t encoderMultiplier = 1; + + #endif // ENCODER_RATE_MULTIPLIER + + if (can_encode()) encoderPosition += (encoderDiff * encoderMultiplier) / epps; + + encoderDiff = 0; + } + + reset_status_timeout(ms); + + refresh(LCDVIEW_REDRAW_NOW); + + #ifdef LED_BACKLIGHT_TIMEOUT + if (!powersupply_on) leds.reset_timeout(ms); + #endif + } + + #endif + + // This runs every ~100ms when idling often enough. + // Instead of tracking changes just redraw the Status Screen once per second. + if (on_status_screen() && !lcd_status_update_delay--) { + lcd_status_update_delay = TERN(HAS_MARLINUI_U8GLIB, 12, 9); + if (max_display_update_time) max_display_update_time--; // Be sure never go to a very big number + refresh(LCDVIEW_REDRAW_NOW); + } + + #if BOTH(HAS_LCD_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--) { + lcd_status_update_delay = ++filename_scroll_pos >= filename_scroll_max ? 12 : 4; // Long delay at end and start + if (filename_scroll_pos > filename_scroll_max) filename_scroll_pos = 0; + refresh(LCDVIEW_REDRAW_NOW); + reset_status_timeout(ms); + } + #endif + + // Then we want to use only 50% of the time + const uint16_t bbr2 = planner.block_buffer_runtime() >> 1; + + if ((should_draw() || drawing_screen) && (!bbr2 || bbr2 > max_display_update_time)) { + + // Change state of drawing flag between screen updates + if (!drawing_screen) switch (lcdDrawUpdate) { + case LCDVIEW_CALL_NO_REDRAW: + refresh(LCDVIEW_NONE); + break; + case LCDVIEW_CLEAR_CALL_REDRAW: + case LCDVIEW_CALL_REDRAW_NEXT: + refresh(LCDVIEW_REDRAW_NOW); + case LCDVIEW_REDRAW_NOW: // set above, or by a handler through LCDVIEW_CALL_REDRAW_NEXT + case LCDVIEW_NONE: + break; + } // switch + + TERN_(HAS_ADC_BUTTONS, keypad_buttons = 0); + + #if HAS_MARLINUI_U8GLIB + + #if ENABLED(LIGHTWEIGHT_UI) + const bool in_status = on_status_screen(), + do_u8g_loop = !in_status; + lcd_in_status(in_status); + if (in_status) status_screen(); + #else + constexpr bool do_u8g_loop = true; + #endif + + if (do_u8g_loop) { + if (!drawing_screen) { // If not already drawing pages + u8g.firstPage(); // Start the first page + drawing_screen = first_page = true; // Flag as drawing pages + } + set_font(FONT_MENU); // Setup font for every page draw + u8g.setColorIndex(1); // And reset the color + run_current_screen(); // Draw and process the current screen + first_page = false; + + // The screen handler can clear drawing_screen for an action that changes the screen. + // If still drawing and there's another page, update max-time and return now. + // The nextPage will already be set up on the next call. + if (drawing_screen && (drawing_screen = u8g.nextPage())) { + if (on_status_screen()) + NOLESS(max_display_update_time, millis() - ms); + return; + } + } + + #else + + run_current_screen(); + + #endif + + TERN_(HAS_LCD_MENU, lcd_clicked = false); + + // Keeping track of the longest time for an individual LCD update. + // Used to do screen throttling when the planner starts to fill up. + if (on_status_screen()) + NOLESS(max_display_update_time, millis() - ms); + } + + #if SCREENS_CAN_TIME_OUT + // Return to Status Screen after a timeout + if (on_status_screen() || defer_return_to_status) + reset_status_timeout(ms); + else if (ELAPSED(ms, return_to_status_ms)) + return_to_status(); + #endif + + // Change state of drawing flag between screen updates + if (!drawing_screen) switch (lcdDrawUpdate) { + case LCDVIEW_CLEAR_CALL_REDRAW: + clear_lcd(); break; + case LCDVIEW_REDRAW_NOW: + refresh(LCDVIEW_NONE); + case LCDVIEW_NONE: + case LCDVIEW_CALL_REDRAW_NEXT: + case LCDVIEW_CALL_NO_REDRAW: + default: break; + } // switch + + } // ELAPSED(ms, next_lcd_update_ms) + + TERN_(HAS_GRAPHICAL_TFT, tft_idle()); + } + + #if HAS_ADC_BUTTONS + + typedef struct { + uint16_t ADCKeyValueMin, ADCKeyValueMax; + uint8_t ADCKeyNo; + } _stADCKeypadTable_; + + #ifndef ADC_BUTTONS_VALUE_SCALE + #define ADC_BUTTONS_VALUE_SCALE 1.0 // for the power voltage equal to the reference voltage + #endif + #ifndef ADC_BUTTONS_R_PULLUP + #define ADC_BUTTONS_R_PULLUP 4.7 // common pull-up resistor in the voltage divider + #endif + #ifndef ADC_BUTTONS_LEFT_R_PULLDOWN + #define ADC_BUTTONS_LEFT_R_PULLDOWN 0.47 // pull-down resistor for LEFT button voltage divider + #endif + #ifndef ADC_BUTTONS_RIGHT_R_PULLDOWN + #define ADC_BUTTONS_RIGHT_R_PULLDOWN 4.7 // pull-down resistor for RIGHT button voltage divider + #endif + #ifndef ADC_BUTTONS_UP_R_PULLDOWN + #define ADC_BUTTONS_UP_R_PULLDOWN 1.0 // pull-down resistor for UP button voltage divider + #endif + #ifndef ADC_BUTTONS_DOWN_R_PULLDOWN + #define ADC_BUTTONS_DOWN_R_PULLDOWN 10.0 // pull-down resistor for DOWN button voltage divider + #endif + #ifndef ADC_BUTTONS_MIDDLE_R_PULLDOWN + #define ADC_BUTTONS_MIDDLE_R_PULLDOWN 2.2 // pull-down resistor for MIDDLE button voltage divider + #endif + + // Calculate the ADC value for the voltage divider with specified pull-down resistor value + #define ADC_BUTTON_VALUE(r) int(HAL_ADC_RANGE * (ADC_BUTTONS_VALUE_SCALE) * r / (r + ADC_BUTTONS_R_PULLUP)) + + static constexpr uint16_t adc_button_tolerance = HAL_ADC_RANGE * 25 / 1024, + adc_other_button = HAL_ADC_RANGE * 1000 / 1024; + static const _stADCKeypadTable_ stADCKeyTable[] PROGMEM = { + // VALUE_MIN, VALUE_MAX, KEY + { adc_other_button, HAL_ADC_RANGE, 1 + BLEN_KEYPAD_F1 }, // F1 + { adc_other_button, HAL_ADC_RANGE, 1 + BLEN_KEYPAD_F2 }, // F2 + { adc_other_button, HAL_ADC_RANGE, 1 + BLEN_KEYPAD_F3 }, // F3 + { ADC_BUTTON_VALUE(ADC_BUTTONS_LEFT_R_PULLDOWN) - adc_button_tolerance, + ADC_BUTTON_VALUE(ADC_BUTTONS_LEFT_R_PULLDOWN) + adc_button_tolerance, 1 + BLEN_KEYPAD_LEFT }, // LEFT ( 272 ... 472) + { ADC_BUTTON_VALUE(ADC_BUTTONS_RIGHT_R_PULLDOWN) - adc_button_tolerance, + ADC_BUTTON_VALUE(ADC_BUTTONS_RIGHT_R_PULLDOWN) + adc_button_tolerance, 1 + BLEN_KEYPAD_RIGHT }, // RIGHT (1948 ... 2148) + { ADC_BUTTON_VALUE(ADC_BUTTONS_UP_R_PULLDOWN) - adc_button_tolerance, + ADC_BUTTON_VALUE(ADC_BUTTONS_UP_R_PULLDOWN) + adc_button_tolerance, 1 + BLEN_KEYPAD_UP }, // UP ( 618 ... 818) + { ADC_BUTTON_VALUE(ADC_BUTTONS_DOWN_R_PULLDOWN) - adc_button_tolerance, + ADC_BUTTON_VALUE(ADC_BUTTONS_DOWN_R_PULLDOWN) + adc_button_tolerance, 1 + BLEN_KEYPAD_DOWN }, // DOWN (2686 ... 2886) + { ADC_BUTTON_VALUE(ADC_BUTTONS_MIDDLE_R_PULLDOWN) - adc_button_tolerance, + ADC_BUTTON_VALUE(ADC_BUTTONS_MIDDLE_R_PULLDOWN) + adc_button_tolerance, 1 + BLEN_KEYPAD_MIDDLE }, // ENTER (1205 ... 1405) + }; + + uint8_t get_ADC_keyValue() { + if (thermalManager.ADCKey_count >= 16) { + const uint16_t currentkpADCValue = thermalManager.current_ADCKey_raw; + thermalManager.current_ADCKey_raw = HAL_ADC_RANGE; + thermalManager.ADCKey_count = 0; + if (currentkpADCValue < adc_other_button) + LOOP_L_N(i, ADC_KEY_NUM) { + const uint16_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); + } + } + return 0; + } + + #endif // HAS_ADC_BUTTONS + + #if HAS_ENCODER_ACTION + + /** + * Read encoder buttons from the hardware registers + * Warning: This function is called from interrupt context! + */ + void MarlinUI::update_buttons() { + const millis_t now = millis(); + if (ELAPSED(now, next_button_update_ms)) { + + #if HAS_DIGITAL_BUTTONS + + #if ANY_BUTTON(EN1, EN2, ENC, BACK) + + uint8_t newbutton = 0; + if (BUTTON_PRESSED(EN1)) newbutton |= EN_A; + if (BUTTON_PRESSED(EN2)) newbutton |= EN_B; + if (can_encode() && BUTTON_PRESSED(ENC)) newbutton |= EN_C; + if (BUTTON_PRESSED(BACK)) newbutton |= EN_D; + + #else + + constexpr uint8_t newbutton = 0; + + #endif + + // + // Directional buttons + // + #if ANY_BUTTON(UP, DWN, LFT, RT) + + const int8_t pulses = epps * encoderDirection; + + if (BUTTON_PRESSED(UP)) { + encoderDiff = (ENCODER_STEPS_PER_MENU_ITEM) * pulses; + next_button_update_ms = now + 300; + } + else if (BUTTON_PRESSED(DWN)) { + encoderDiff = -(ENCODER_STEPS_PER_MENU_ITEM) * pulses; + next_button_update_ms = now + 300; + } + else if (BUTTON_PRESSED(LFT)) { + encoderDiff = -pulses; + next_button_update_ms = now + 300; + } + else if (BUTTON_PRESSED(RT)) { + encoderDiff = pulses; + next_button_update_ms = now + 300; + } + + #endif // UP || DWN || LFT || RT + + buttons = (newbutton | TERN0(HAS_SLOW_BUTTONS, slow_buttons) + #if BOTH(HAS_TOUCH_BUTTONS, HAS_ENCODER_ACTION) + | (touch_buttons & TERN(HAS_ENCODER_WHEEL, ~(EN_A | EN_B), 0xFF)) + #endif + ); + + #elif HAS_ADC_BUTTONS + + buttons = 0; + + #endif + + #if HAS_ADC_BUTTONS + if (keypad_buttons == 0) { + const uint8_t b = get_ADC_keyValue(); + if (WITHIN(b, 1, 8)) keypad_buttons = _BV(b - 1); + } + #endif + + #if HAS_SHIFT_ENCODER + /** + * Set up Rotary Encoder bit values (for two pin encoders to indicate movement). + * These values are independent of which pins are used for EN_A / EN_B indications. + * The rotary encoder part is also independent of the LCD chipset. + */ + uint8_t val = 0; + WRITE(SHIFT_LD_PIN, LOW); + WRITE(SHIFT_LD_PIN, HIGH); + LOOP_L_N(i, 8) { + val >>= 1; + if (READ(SHIFT_OUT_PIN)) SBI(val, 7); + WRITE(SHIFT_CLK_PIN, HIGH); + WRITE(SHIFT_CLK_PIN, LOW); + } + TERN(REPRAPWORLD_KEYPAD, keypad_buttons, buttons) = ~val; + #endif + + #if IS_TFTGLCD_PANEL + next_button_update_ms = now + (LCD_UPDATE_INTERVAL / 2); + buttons = slow_buttons; + TERN_(AUTO_BED_LEVELING_UBL, external_encoder()); + #endif + + } // next_button_update_ms + + #if HAS_ENCODER_WHEEL + static uint8_t lastEncoderBits; + + // Manage encoder rotation + #define ENCODER_SPIN(_E1, _E2) switch (lastEncoderBits) { case _E1: encoderDiff += encoderDirection; break; case _E2: encoderDiff -= encoderDirection; } + + uint8_t enc = 0; + if (buttons & EN_A) enc |= B01; + if (buttons & EN_B) enc |= B10; + if (enc != lastEncoderBits) { + switch (enc) { + case ENCODER_PHASE_0: ENCODER_SPIN(ENCODER_PHASE_3, ENCODER_PHASE_1); break; + case ENCODER_PHASE_1: ENCODER_SPIN(ENCODER_PHASE_0, ENCODER_PHASE_2); break; + case ENCODER_PHASE_2: ENCODER_SPIN(ENCODER_PHASE_1, ENCODER_PHASE_3); break; + case ENCODER_PHASE_3: ENCODER_SPIN(ENCODER_PHASE_2, ENCODER_PHASE_0); break; + } + #if BOTH(HAS_LCD_MENU, AUTO_BED_LEVELING_UBL) + external_encoder(); + #endif + lastEncoderBits = enc; + } + + #endif // HAS_ENCODER_WHEEL + } + + #endif // HAS_ENCODER_ACTION + +#endif // HAS_WIRED_LCD + +#if HAS_STATUS_MESSAGE + + //////////////////////////////////////////// + ////////////// Status Message ////////////// + //////////////////////////////////////////// + + #if ENABLED(EXTENSIBLE_UI) + #include "extui/ui_api.h" + #endif + + bool MarlinUI::has_status() { return (status_message[0] != '\0'); } + + void MarlinUI::set_status(const char * const message, const bool persist) { + if (alert_level) return; + + TERN_(HOST_PROMPT_SUPPORT, host_action_notify(message)); + + // Here we have a problem. The message is encoded in UTF8, so + // arbitrarily cutting it will be a problem. We MUST be sure + // that there is no cutting in the middle of a multibyte character! + + // Get a pointer to the null terminator + const char* pend = message + strlen(message); + + // If length of supplied UTF8 string is greater than + // our buffer size, start cutting whole UTF8 chars + while ((pend - message) > MAX_MESSAGE_LENGTH) { + --pend; + while (!START_OF_UTF8_CHAR(*pend)) --pend; + }; + + // At this point, we have the proper cut point. Use it + uint8_t maxLen = pend - message; + strncpy(status_message, message, maxLen); + status_message[maxLen] = '\0'; + + finish_status(persist); + } + + /** + * Reset the status message + */ + + void MarlinUI::reset_status(const bool no_welcome) { + #if SERVICE_INTERVAL_1 > 0 + static PGMSTR(service1, "> " SERVICE_NAME_1 "!"); + #endif + #if SERVICE_INTERVAL_2 > 0 + static PGMSTR(service2, "> " SERVICE_NAME_2 "!"); + #endif + #if SERVICE_INTERVAL_3 > 0 + static PGMSTR(service3, "> " SERVICE_NAME_3 "!"); + #endif + PGM_P msg; + if (printingIsPaused()) + msg = GET_TEXT(MSG_PRINT_PAUSED); + #if ENABLED(SDSUPPORT) + else if (IS_SD_PRINTING()) + return set_status(card.longest_filename(), true); + #endif + else if (print_job_timer.isRunning()) + msg = GET_TEXT(MSG_PRINTING); + + #if SERVICE_INTERVAL_1 > 0 + else if (print_job_timer.needsService(1)) msg = service1; + #endif + #if SERVICE_INTERVAL_2 > 0 + else if (print_job_timer.needsService(2)) msg = service2; + #endif + #if SERVICE_INTERVAL_3 > 0 + else if (print_job_timer.needsService(3)) msg = service3; + #endif + + else if (!no_welcome) + msg = GET_TEXT(WELCOME_MSG); + else + return; + + set_status_P(msg, -1); + } + + void MarlinUI::set_status_P(PGM_P const message, int8_t level) { + if (level < 0) level = alert_level = 0; + if (level < alert_level) return; + alert_level = level; + + TERN_(HOST_PROMPT_SUPPORT, host_action_notify_P(message)); + + // Since the message is encoded in UTF8 it must + // only be cut on a character boundary. + + // Get a pointer to the null terminator + PGM_P pend = message + strlen_P(message); + + // If length of supplied UTF8 string is greater than + // the buffer size, start cutting whole UTF8 chars + while ((pend - message) > MAX_MESSAGE_LENGTH) { + --pend; + while (!START_OF_UTF8_CHAR(pgm_read_byte(pend))) --pend; + }; + + // At this point, we have the proper cut point. Use it + uint8_t maxLen = pend - message; + strncpy_P(status_message, message, maxLen); + status_message[maxLen] = '\0'; + + finish_status(level > 0); + } + + void MarlinUI::set_alert_status_P(PGM_P const message) { + set_status_P(message, 1); + TERN_(HAS_LCD_MENU, return_to_status()); + } + + #include + + void MarlinUI::status_printf_P(const uint8_t level, PGM_P const fmt, ...) { + if (level < alert_level) return; + alert_level = level; + va_list args; + va_start(args, fmt); + vsnprintf_P(status_message, MAX_MESSAGE_LENGTH, fmt, args); + va_end(args); + finish_status(level > 0); + } + + void MarlinUI::finish_status(const bool persist) { + + #if HAS_WIRED_LCD + + #if !(BASIC_PROGRESS_BAR && (PROGRESS_MSG_EXPIRE) > 0) + UNUSED(persist); + #endif + + #if ENABLED(LCD_PROGRESS_BAR) || BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) + const millis_t ms = millis(); + #endif + + #if BASIC_PROGRESS_BAR + progress_bar_ms = ms; + #if PROGRESS_MSG_EXPIRE > 0 + expire_status_ms = persist ? 0 : ms + PROGRESS_MSG_EXPIRE; + #endif + #endif + + #if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) + next_filament_display = ms + 5000UL; // Show status message for 5s + #endif + + #if ENABLED(STATUS_MESSAGE_SCROLLING) + status_scroll_offset = 0; + #endif + #else // HAS_WIRED_LCD + UNUSED(persist); + #endif + + TERN_(EXTENSIBLE_UI, ExtUI::onStatusChanged(status_message)); + TERN_(DWIN_CREALITY_LCD, DWIN_StatusChanged(status_message)); + } + + #if ENABLED(STATUS_MESSAGE_SCROLLING) + + void MarlinUI::advance_status_scroll() { + // Advance by one UTF8 code-word + if (status_scroll_offset < utf8_strlen(status_message)) + while (!START_OF_UTF8_CHAR(status_message[++status_scroll_offset])); + else + status_scroll_offset = 0; + } + + char* MarlinUI::status_and_len(uint8_t &len) { + char *out = status_message + status_scroll_offset; + len = utf8_strlen(out); + return out; + } + + #endif + +#endif + +#if HAS_DISPLAY + + #if ENABLED(SDSUPPORT) + extern bool wait_for_user, wait_for_heatup; + #endif + + void MarlinUI::abort_print() { + #if ENABLED(SDSUPPORT) + wait_for_heatup = wait_for_user = false; + card.abortFilePrintSoon(); + #endif + #ifdef ACTION_ON_CANCEL + host_action_cancel(); + #endif + IF_DISABLED(SDSUPPORT, print_job_timer.stop()); + TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_INFO, PSTR("UI Aborted"), DISMISS_STR)); + LCD_MESSAGEPGM(MSG_PRINT_ABORTED); + TERN_(HAS_LCD_MENU, return_to_status()); + } + + void MarlinUI::flow_fault() { + LCD_ALERTMESSAGEPGM(MSG_FLOWMETER_FAULT); + TERN_(HAS_BUZZER, buzz(1000, 440)); + TERN_(HAS_LCD_MENU, return_to_status()); + } + + #if ANY(PARK_HEAD_ON_PAUSE, SDSUPPORT) + #include "../gcode/queue.h" + #endif + + void MarlinUI::pause_print() { + #if HAS_LCD_MENU + synchronize(GET_TEXT(MSG_PAUSING)); + defer_status_screen(); + #endif + + TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_PAUSE_RESUME, PSTR("UI Pause"), PSTR("Resume"))); + + LCD_MESSAGEPGM(MSG_PRINT_PAUSED); + + #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_P(PSTR("M25 P\nM24")); + #elif ENABLED(SDSUPPORT) + queue.inject_P(PSTR("M25")); + #elif defined(ACTION_ON_PAUSE) + host_action_pause(); + #endif + } + + 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)); + #ifdef ACTION_ON_RESUME + host_action_resume(); + #endif + print_job_timer.start(); // Also called by M24 + } + + #if HAS_PRINT_PROGRESS + + MarlinUI::progress_t MarlinUI::_get_progress() { + return ( + TERN0(LCD_SET_PROGRESS_MANUALLY, (progress_override & PROGRESS_MASK)) + #if ENABLED(SDSUPPORT) + ?: TERN(HAS_PRINT_PROGRESS_PERMYRIAD, card.permyriadDone(), card.percentDone()) + #endif + ); + } + + #endif + + #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 + + // + 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; + next_button_update_ms = now + repeat_delay; // Assume the repeat delay + const int8_t xdir = col < (LCD_WIDTH ) / 2 ? -1 : 1, + ydir = row < (LCD_HEIGHT) / 2 ? -1 : 1; + if (on_edit_screen) + encoderDiff = epps * ydir; + else if (screen_items > 0) { + // Last 5 cols act as a scroll :-) + if (col > (LCD_WIDTH) - 5) + // 2 * LCD_HEIGHT to scroll to bottom of next page. (LCD_HEIGHT would only go 1 item down.) + encoderDiff = epps * (encoderLine - encoderTopLine + 2 * (LCD_HEIGHT)) * ydir; + else + encoderDiff = epps * (row - encoderPosition + encoderTopLine); + } + else if (!on_status_screen()) + encoderDiff = epps * xdir; + } + + #endif + +#elif !HAS_STATUS_MESSAGE // && !HAS_DISPLAY + + // + // Send the status line as a host notification + // + void MarlinUI::set_status(const char * const message, const bool) { + TERN(HOST_PROMPT_SUPPORT, host_action_notify(message), UNUSED(message)); + } + void MarlinUI::set_status_P(PGM_P message, const int8_t) { + TERN(HOST_PROMPT_SUPPORT, host_action_notify_P(message), UNUSED(message)); + } + void MarlinUI::status_printf_P(const uint8_t, PGM_P const message, ...) { + TERN(HOST_PROMPT_SUPPORT, host_action_notify_P(message), UNUSED(message)); + } + +#endif // !HAS_DISPLAY && !HAS_STATUS_MESSAGE + +#if ENABLED(SDSUPPORT) + + #if ENABLED(EXTENSIBLE_UI) + #include "extui/ui_api.h" + #endif + + void MarlinUI::media_changed(const uint8_t old_status, const uint8_t status) { + if (old_status == status) { + TERN_(EXTENSIBLE_UI, ExtUI::onMediaError()); // Failed to mount/unmount + return; + } + + if (status) { + if (old_status < 2) { + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onMediaInserted(); + #elif ENABLED(BROWSE_MEDIA_ON_INSERT) + clear_menu_history(); + quick_feedback(); + goto_screen(MEDIA_MENU_GATEWAY); + #else + LCD_MESSAGEPGM(MSG_MEDIA_INSERTED); + #endif + } + } + else { + if (old_status < 2) { + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onMediaRemoved(); + #elif PIN_EXISTS(SD_DETECT) + LCD_MESSAGEPGM(MSG_MEDIA_REMOVED); + #if HAS_LCD_MENU + if (!defer_return_to_status) return_to_status(); + #endif + #endif + } + } + + #if PIN_EXISTS(SD_DETECT) && DISABLED(NO_LCD_REINIT) + init_lcd(); // Revive a noisy shared SPI LCD + #endif + + refresh(); + + #if HAS_WIRED_LCD || defined(LED_BACKLIGHT_TIMEOUT) + const millis_t ms = millis(); + #endif + + TERN_(HAS_WIRED_LCD, next_lcd_update_ms = ms + LCD_UPDATE_INTERVAL); // Delay LCD update for SD activity + + #ifdef LED_BACKLIGHT_TIMEOUT + leds.reset_timeout(ms); + #endif + } + +#endif // SDSUPPORT + +#if HAS_LCD_MENU + void MarlinUI::reset_settings() { + settings.reset(); + completion_feedback(); + #if ENABLED(TOUCH_SCREEN_CALIBRATION) + if (touch_calibration.need_calibration()) ui.goto_screen(touch_screen_calibration); + #endif + } +#endif + +#if BOTH(EXTENSIBLE_UI, ADVANCED_PAUSE_FEATURE) + + void MarlinUI::pause_show_message( + const PauseMessage message, + const PauseMode mode/*=PAUSE_MODE_SAME*/, + const uint8_t extruder/*=active_extruder*/ + ) { + if (mode == PAUSE_MODE_SAME) + return; + pause_mode = mode; + switch (message) { + case PAUSE_MESSAGE_PARKING: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_PAUSE_PRINT_PARKING)); + case PAUSE_MESSAGE_CHANGING: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_INIT)); + case PAUSE_MESSAGE_UNLOAD: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_UNLOAD)); + case PAUSE_MESSAGE_WAITING: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_ADVANCED_PAUSE_WAITING)); + case PAUSE_MESSAGE_INSERT: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_INSERT)); + case PAUSE_MESSAGE_LOAD: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_LOAD)); + case PAUSE_MESSAGE_PURGE: + #if ENABLED(ADVANCED_PAUSE_CONTINUOUS_PURGE) + ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_CONT_PURGE)); + #else + ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_PURGE)); + #endif + case PAUSE_MESSAGE_RESUME: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_RESUME)); + case PAUSE_MESSAGE_HEAT: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_HEAT)); + case PAUSE_MESSAGE_HEATING: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_HEATING)); + case PAUSE_MESSAGE_OPTION: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_OPTION_HEADER)); + case PAUSE_MESSAGE_STATUS: + default: break; + } + } + +#endif + +#if ENABLED(EEPROM_SETTINGS) + + #if HAS_LCD_MENU + void MarlinUI::init_eeprom() { + const bool good = settings.init_eeprom(); + completion_feedback(good); + return_to_status(); + } + void MarlinUI::load_settings() { + const bool good = settings.load(); + completion_feedback(good); + } + void MarlinUI::store_settings() { + const bool good = settings.save(); + completion_feedback(good); + } + #endif + + #if DISABLED(EEPROM_AUTO_INIT) + + static inline PGM_P eeprom_err(const uint8_t msgid) { + switch (msgid) { + default: + case 0: return GET_TEXT(MSG_ERR_EEPROM_CRC); + case 1: return GET_TEXT(MSG_ERR_EEPROM_INDEX); + case 2: return GET_TEXT(MSG_ERR_EEPROM_VERSION); + } + } + + void MarlinUI::eeprom_alert(const uint8_t msgid) { + #if HAS_LCD_MENU + editable.uint8 = msgid; + goto_screen([]{ + PGM_P const restore_msg = GET_TEXT(MSG_INIT_EEPROM); + char msg[utf8_strlen_P(restore_msg) + 1]; + strcpy_P(msg, restore_msg); + MenuItem_confirm::select_screen( + GET_TEXT(MSG_BUTTON_RESET), GET_TEXT(MSG_BUTTON_IGNORE), + init_eeprom, return_to_status, + eeprom_err(editable.uint8), msg, PSTR("?") + ); + }); + #else + set_status_P(eeprom_err(msgid)); + #endif + } + + #endif // EEPROM_AUTO_INIT + +#endif // EEPROM_SETTINGS diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h new file mode 100644 index 000000000000..e01f7d74c47f --- /dev/null +++ b/Marlin/src/lcd/marlinui.h @@ -0,0 +1,713 @@ +/** + * 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 + +#include "../inc/MarlinConfig.h" + +#include "../module/motion.h" + +#include "buttons.h" + +#if HAS_BUZZER + #include "../libs/buzzer.h" +#endif + +#if ENABLED(SDSUPPORT) + #include "../sd/cardreader.h" +#endif + +#if ENABLED(TOUCH_SCREEN_CALIBRATION) + #include "tft_io/touch_calibration.h" +#endif + +#if ANY(HAS_LCD_MENU, ULTIPANEL_FEEDMULTIPLY, SOFT_RESET_ON_KILL) + #define HAS_ENCODER_ACTION 1 +#endif + +#if HAS_STATUS_MESSAGE + #define START_OF_UTF8_CHAR(C) (((C) & 0xC0u) != 0x80U) +#endif + +#if E_MANUAL > 1 + #define MULTI_E_MANUAL 1 +#endif + +#if HAS_DISPLAY + #include "../module/printcounter.h" +#endif + +#if ENABLED(ADVANCED_PAUSE_FEATURE) && EITHER(HAS_LCD_MENU, EXTENSIBLE_UI) + #include "../feature/pause.h" + #include "../module/motion.h" // for active_extruder +#endif + +#define START_OF_UTF8_CHAR(C) (((C) & 0xC0u) != 0x80U) + +#if HAS_WIRED_LCD + + enum LCDViewAction : uint8_t { + LCDVIEW_NONE, + LCDVIEW_REDRAW_NOW, + LCDVIEW_CALL_REDRAW_NEXT, + LCDVIEW_CLEAR_CALL_REDRAW, + LCDVIEW_CALL_NO_REDRAW + }; + + #if HAS_ADC_BUTTONS + uint8_t get_ADC_keyValue(); + #endif + + #define LCD_UPDATE_INTERVAL TERN(HAS_TOUCH_BUTTONS, 50, 100) + + #if HAS_LCD_MENU + + #include "lcdprint.h" + + #if !HAS_GRAPHICAL_TFT + void _wrap_string(uint8_t &col, uint8_t &row, const char * const string, read_byte_cb_t cb_read_byte, const bool wordwrap=false); + inline void wrap_string_P(uint8_t &col, uint8_t &row, PGM_P const pstr, const bool wordwrap=false) { _wrap_string(col, row, pstr, read_byte_rom, wordwrap); } + inline void wrap_string(uint8_t &col, uint8_t &row, const char * const string, const bool wordwrap=false) { _wrap_string(col, row, string, read_byte_ram, wordwrap); } + #endif + + typedef void (*screenFunc_t)(); + typedef void (*menuAction_t)(); + + #endif // HAS_LCD_MENU + +#endif // HAS_WIRED_LCD + +#if HAS_MARLINUI_U8GLIB + enum MarlinFont : uint8_t { + FONT_STATUSMENU = 1, + FONT_EDIT, + FONT_MENU + }; +#else + enum HD44780CharSet : uint8_t { + CHARSET_MENU, + CHARSET_INFO, + CHARSET_BOOT + }; +#endif + +#if PREHEAT_COUNT + typedef struct { + #if HAS_HOTEND + celsius_t hotend_temp; + #endif + #if HAS_HEATED_BED + celsius_t bed_temp; + #endif + #if HAS_FAN + uint16_t fan_speed; + #endif + } preheat_t; +#endif + +#if HAS_LCD_MENU + + // Manual Movement class + class ManualMove { + private: + static AxisEnum axis; + #if MULTI_E_MANUAL + static int8_t e_index; + #else + static int8_t constexpr e_index = 0; + #endif + static millis_t start_time; + #if IS_KINEMATIC + static xyze_pos_t all_axes_destination; + #endif + public: + static float menu_scale; + #if IS_KINEMATIC + static float offset; + #endif + template + void set_destination(const T& dest) { + #if IS_KINEMATIC + // Moves are segmented, so the entire move is not submitted at once. + // Using a separate variable prevents corrupting the in-progress move. + all_axes_destination = current_position; + all_axes_destination.set(dest); + #else + // Moves are submitted as single line to the planner using buffer_line. + current_position.set(dest); + #endif + } + float axis_value(const AxisEnum axis) { + return NATIVE_TO_LOGICAL(processing ? destination[axis] : SUM_TERN(IS_KINEMATIC, current_position[axis], offset), axis); + } + bool apply_diff(const AxisEnum axis, const_float_t diff, const_float_t min, const_float_t max) { + #if IS_KINEMATIC + float &valref = offset; + const float rmin = min - current_position[axis], rmax = max - current_position[axis]; + #else + float &valref = current_position[axis]; + const float rmin = min, rmax = max; + #endif + valref += diff; + const float pre = valref; + if (min != max) { + if (diff < 0) + NOLESS(valref, rmin); + else + NOMORE(valref, rmax); + } + return pre != valref; + } + #if IS_KINEMATIC + static bool processing; + #else + static bool constexpr processing = false; + #endif + static void task(); + static void soon(const AxisEnum axis OPTARG(MULTI_E_MANUAL, const int8_t eindex=active_extruder)); + }; + +#endif + +//////////////////////////////////////////// +//////////// MarlinUI Singleton //////////// +//////////////////////////////////////////// + +class MarlinUI { +public: + + MarlinUI() { + TERN_(HAS_LCD_MENU, currentScreen = status_screen); + } + + #if HAS_MULTI_LANGUAGE + static uint8_t language; + static void set_language(const uint8_t lang); + #endif + + #if HAS_MARLINUI_U8GLIB + static void update_language_font(); + #endif + + #if ENABLED(SOUND_MENU_ITEM) + static bool buzzer_enabled; // Initialized by settings.load() + #else + static constexpr bool buzzer_enabled = true; + #endif + + #if HAS_BUZZER + static void buzz(const long duration, const uint16_t freq); + #endif + + FORCE_INLINE static void chirp() { + TERN_(HAS_CHIRP, buzz(LCD_FEEDBACK_FREQUENCY_DURATION_MS, LCD_FEEDBACK_FREQUENCY_HZ)); + } + + #if ENABLED(LCD_HAS_STATUS_INDICATORS) + static void update_indicators(); + #endif + + // LCD implementations + static void clear_lcd(); + + #if BOTH(HAS_LCD_MENU, TOUCH_SCREEN_CALIBRATION) + static void check_touch_calibration() { + if (touch_calibration.need_calibration()) currentScreen = touch_calibration_screen; + } + #endif + + #if ENABLED(SDSUPPORT) + #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 + + #if HAS_LCD_BRIGHTNESS + #ifndef MIN_LCD_BRIGHTNESS + #define MIN_LCD_BRIGHTNESS 1 + #endif + #ifndef MAX_LCD_BRIGHTNESS + #define MAX_LCD_BRIGHTNESS 255 + #endif + #ifndef DEFAULT_LCD_BRIGHTNESS + #define DEFAULT_LCD_BRIGHTNESS MAX_LCD_BRIGHTNESS + #endif + static uint8_t brightness; + static bool backlight; + static void set_brightness(const uint8_t value); + FORCE_INLINE static void refresh_brightness() { set_brightness(brightness); } + #endif + + #if ENABLED(DWIN_CREALITY_LCD) + static void refresh(); + #else + FORCE_INLINE static void refresh() { + TERN_(HAS_WIRED_LCD, refresh(LCDVIEW_CLEAR_CALL_REDRAW)); + } + #endif + + #if HAS_WIRED_LCD + static bool detected(); + static void init_lcd(); + #else + static inline bool detected() { return true; } + static inline void init_lcd() {} + #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(LCD_SET_PROGRESS_MANUALLY) + 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); } + #if ENABLED(SHOW_REMAINING_TIME) + static inline uint32_t _calculated_remaining_time() { + const duration_t elapsed = print_job_timer.duration(); + const progress_t progress = _get_progress(); + return progress ? elapsed.value * (100 * (PROGRESS_SCALE) - progress) / progress : 0; + } + #if ENABLED(USE_M73_REMAINING_TIME) + static uint32_t remaining_time; + FORCE_INLINE static void set_remaining_time(const uint32_t r) { remaining_time = r; } + FORCE_INLINE static uint32_t get_remaining_time() { return remaining_time ?: _calculated_remaining_time(); } + FORCE_INLINE static void reset_remaining_time() { set_remaining_time(0); } + #else + FORCE_INLINE static uint32_t get_remaining_time() { return _calculated_remaining_time(); } + #endif + #endif + #endif + static progress_t _get_progress(); + #if HAS_PRINT_PROGRESS_PERMYRIAD + FORCE_INLINE static uint16_t get_progress_permyriad() { return _get_progress(); } + #endif + static uint8_t get_progress_percent() { return uint8_t(_get_progress() / (PROGRESS_SCALE)); } + #else + static constexpr uint8_t get_progress_percent() { return 0; } + #endif + + #if HAS_STATUS_MESSAGE + + #if HAS_WIRED_LCD + #if ENABLED(STATUS_MESSAGE_SCROLLING) + #define MAX_MESSAGE_LENGTH _MAX(LONG_FILENAME_LENGTH, MAX_LANG_CHARSIZE * 2 * (LCD_WIDTH)) + #else + #define MAX_MESSAGE_LENGTH (MAX_LANG_CHARSIZE * (LCD_WIDTH)) + #endif + #else + #define MAX_MESSAGE_LENGTH 63 + #endif + + static char status_message[]; + static uint8_t alert_level; // Higher levels block lower levels + + #if ENABLED(STATUS_MESSAGE_SCROLLING) + static uint8_t status_scroll_offset; + static void advance_status_scroll(); + static char* status_and_len(uint8_t &len); + #endif + + static bool has_status(); + static void reset_status(const bool no_welcome=false); + static void set_status(const char * const message, const bool persist=false); + static void set_status_P(PGM_P const message, const int8_t level=0); + static void status_printf_P(const uint8_t level, PGM_P const fmt, ...); + static void set_alert_status_P(PGM_P const message); + static inline void reset_alert_level() { alert_level = 0; } + #else + static constexpr bool has_status() { return false; } + static inline void reset_status(const bool=false) {} + static void set_status(const char *message, const bool=false); + static void set_status_P(PGM_P message, const int8_t=0); + static void status_printf_P(const uint8_t, PGM_P message, ...); + static inline void set_alert_status_P(PGM_P const) {} + static inline void reset_alert_level() {} + #endif + + #if HAS_DISPLAY + + static void init(); + static void update(); + + static void abort_print(); + static void pause_print(); + static void resume_print(); + static void flow_fault(); + + #if HAS_WIRED_LCD + + static millis_t next_button_update_ms; + + static LCDViewAction lcdDrawUpdate; + FORCE_INLINE static bool should_draw() { return bool(lcdDrawUpdate); } + FORCE_INLINE static void refresh(const LCDViewAction type) { lcdDrawUpdate = type; } + + #if ENABLED(SHOW_CUSTOM_BOOTSCREEN) + static void draw_custom_bootscreen(const uint8_t frame=0); + static void show_custom_bootscreen(); + #endif + + #if ENABLED(SHOW_BOOTSCREEN) + #ifndef BOOTSCREEN_TIMEOUT + #define BOOTSCREEN_TIMEOUT 2500 + #endif + static void draw_marlin_bootscreen(const bool line2=false); + static void show_marlin_bootscreen(); + static void show_bootscreen(); + static void bootscreen_completion(const millis_t sofar); + #endif + + #if HAS_MARLINUI_U8GLIB + + static void set_font(const MarlinFont font_nr); + + #else + + static void set_custom_characters(const HD44780CharSet screen_charset=CHARSET_INFO); + + #if ENABLED(LCD_PROGRESS_BAR) + static millis_t progress_bar_ms; // Start time for the current progress bar cycle + static void draw_progress_bar(const uint8_t percent); + #if PROGRESS_MSG_EXPIRE > 0 + static millis_t expire_status_ms; // = 0 + FORCE_INLINE static void reset_progress_bar_timeout() { expire_status_ms = 0; } + #endif + #endif + + #endif + + static uint8_t lcd_status_update_delay; + + #if HAS_LCD_CONTRAST + static int16_t contrast; + static void set_contrast(const int16_t value); + FORCE_INLINE static void refresh_contrast() { set_contrast(contrast); } + #endif + + #if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) + static millis_t next_filament_display; + #endif + + static void quick_feedback(const bool clear_buttons=true); + #if HAS_BUZZER + static void completion_feedback(const bool good=true); + #else + static inline void completion_feedback(const bool=true) {} + #endif + + #if DISABLED(LIGHTWEIGHT_UI) + static void draw_status_message(const bool blink); + #endif + + #if ENABLED(ADVANCED_PAUSE_FEATURE) + static void draw_hotend_status(const uint8_t row, const uint8_t extruder); + #endif + + #if HAS_TOUCH_BUTTONS + static bool on_edit_screen; + static void screen_click(const uint8_t row, const uint8_t col, const uint8_t x, const uint8_t y); + #endif + + static void status_screen(); + + #endif + + #if HAS_MARLINUI_U8GLIB + static bool drawing_screen, first_page; + #else + static constexpr bool drawing_screen = false, first_page = true; + #endif + + static bool get_blink(); + static void kill_screen(PGM_P const lcd_error, PGM_P const lcd_component); + static void draw_kill_screen(); + + #else // No LCD + + static inline void init() {} + static inline void update() {} + static inline void return_to_status() {} + + #endif + + #if ENABLED(SDSUPPORT) + #if BOTH(SCROLL_LONG_FILENAMES, HAS_LCD_MENU) + #define MARLINUI_SCROLL_NAME 1 + #endif + #if MARLINUI_SCROLL_NAME + static uint8_t filename_scroll_pos, filename_scroll_max; + #endif + static const char * scrolled_filename(CardReader &theCard, const uint8_t maxlen, uint8_t hash, const bool doScroll); + #endif + + #if PREHEAT_COUNT + static preheat_t material_preset[PREHEAT_COUNT]; + static PGM_P get_preheat_label(const uint8_t m); + #endif + + #if SCREENS_CAN_TIME_OUT + static inline void reset_status_timeout(const millis_t ms) { return_to_status_ms = ms + LCD_TIMEOUT_TO_STATUS; } + #else + static inline void reset_status_timeout(const millis_t) {} + #endif + + #if HAS_LCD_MENU + + #if HAS_TOUCH_BUTTONS + static uint8_t touch_buttons; + static uint8_t repeat_delay; + #else + static constexpr uint8_t touch_buttons = 0; + #endif + + #if ENABLED(ENCODER_RATE_MULTIPLIER) + static bool encoderRateMultiplierEnabled; + static millis_t lastEncoderMovementMillis; + static void enable_encoder_multiplier(const bool onoff); + #define ENCODER_RATE_MULTIPLY(F) (ui.encoderRateMultiplierEnabled = F) + #else + #define ENCODER_RATE_MULTIPLY(F) NOOP + #endif + + // Manual Movement + static ManualMove manual_move; + + // Select Screen (modal NO/YES style dialog) + static bool selection; + static void set_selection(const bool sel) { selection = sel; } + static bool update_selection(); + + static void synchronize(PGM_P const msg=nullptr); + + static screenFunc_t currentScreen; + static bool screen_changed; + static void goto_screen(const screenFunc_t screen, const uint16_t encoder=0, const uint8_t top=0, const uint8_t items=0); + static void push_current_screen(); + + // goto_previous_screen and go_back may also be used as menu item callbacks + static void _goto_previous_screen(TERN_(TURBO_BACK_MENU_ITEM, const bool is_back)); + static inline void goto_previous_screen() { _goto_previous_screen(TERN_(TURBO_BACK_MENU_ITEM, false)); } + static inline void go_back() { _goto_previous_screen(TERN_(TURBO_BACK_MENU_ITEM, true)); } + + static void return_to_status(); + static inline bool on_status_screen() { return currentScreen == status_screen; } + FORCE_INLINE static void run_current_screen() { (*currentScreen)(); } + + #if ENABLED(LIGHTWEIGHT_UI) + static void lcd_in_status(const bool inStatus); + #endif + + FORCE_INLINE static bool screen_is_sticky() { + return TERN1(SCREENS_CAN_TIME_OUT, defer_return_to_status); + } + + FORCE_INLINE static void defer_status_screen(const bool defer=true) { + TERN(SCREENS_CAN_TIME_OUT, defer_return_to_status = defer, UNUSED(defer)); + } + + static inline void goto_previous_screen_no_defer() { + defer_status_screen(false); + goto_previous_screen(); + } + + #if ENABLED(SD_REPRINT_LAST_SELECTED_FILE) + static void reselect_last_file(); + #endif + + #if ENABLED(AUTO_BED_LEVELING_UBL) + static void ubl_plot(const uint8_t x_plot, const uint8_t y_plot); + #endif + + #if ENABLED(AUTO_BED_LEVELING_UBL) + static void ubl_mesh_edit_start(const_float_t initial); + static float ubl_mesh_value(); + #endif + + static void draw_select_screen_prompt(PGM_P const pref, const char * const string=nullptr, PGM_P const suff=nullptr); + + #else + + static constexpr bool on_status_screen() { return true; } + + #if HAS_WIRED_LCD + FORCE_INLINE static void run_current_screen() { status_screen(); } + #endif + + #endif + + #if EITHER(HAS_LCD_MENU, EXTENSIBLE_UI) + static bool lcd_clicked; + static inline bool use_click() { + const bool click = lcd_clicked; + lcd_clicked = false; + return click; + } + #else + static constexpr bool lcd_clicked = false; + static inline bool use_click() { return false; } + #endif + + #if ENABLED(ADVANCED_PAUSE_FEATURE) && EITHER(HAS_LCD_MENU, EXTENSIBLE_UI) + static void pause_show_message(const PauseMessage message, const PauseMode mode=PAUSE_MODE_SAME, const uint8_t extruder=active_extruder); + #else + static inline void _pause_show_message() {} + #define pause_show_message(...) _pause_show_message() + #endif + + // + // EEPROM: Reset / Init / Load / Store + // + #if HAS_LCD_MENU + static void reset_settings(); + #endif + + #if ENABLED(EEPROM_SETTINGS) + #if HAS_LCD_MENU + static void init_eeprom(); + static void load_settings(); + static void store_settings(); + #endif + #if DISABLED(EEPROM_AUTO_INIT) + static void eeprom_alert(const uint8_t msgid); + static inline void eeprom_alert_crc() { eeprom_alert(0); } + static inline void eeprom_alert_index() { eeprom_alert(1); } + static inline void eeprom_alert_version() { eeprom_alert(2); } + #endif + #endif + + // + // Special handling if a move is underway + // + #if ANY(DELTA_CALIBRATION_MENU, DELTA_AUTO_CALIBRATION, PROBE_OFFSET_WIZARD) || (ENABLED(LCD_BED_LEVELING) && EITHER(PROBE_MANUALLY, MESH_BED_LEVELING)) + #define LCD_HAS_WAIT_FOR_MOVE 1 + static bool wait_for_move; + #else + static constexpr bool wait_for_move = false; + #endif + + // + // Block interaction while under external control + // + #if HAS_LCD_MENU && EITHER(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; } + #if ENABLED(AUTO_BED_LEVELING_UBL) + static void external_encoder(); + #endif + #else + static constexpr bool external_control = false; + #endif + + #if HAS_ENCODER_ACTION + + static volatile uint8_t buttons; + #if IS_RRW_KEYPAD + static volatile uint8_t keypad_buttons; + static bool handle_keypad(); + #endif + #if HAS_SLOW_BUTTONS + static volatile uint8_t slow_buttons; + static uint8_t read_slow_buttons(); + #endif + + static void update_buttons(); + static inline bool button_pressed() { return BUTTON_CLICK() || TERN(TOUCH_SCREEN, touch_pressed(), false); } + #if EITHER(AUTO_BED_LEVELING_UBL, G26_MESH_VALIDATION) + static void wait_for_release(); + #endif + + static uint32_t encoderPosition; + + #define ENCODERBASE (TERN(REVERSE_ENCODER_DIRECTION, -1, +1)) + + #if EITHER(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) + encoderDirection = ENCODERBASE; + #endif + } + + FORCE_INLINE static void encoder_direction_menus() { + TERN_(REVERSE_MENU_DIRECTION, encoderDirection = -(ENCODERBASE)); + } + + FORCE_INLINE static void encoder_direction_select() { + TERN_(REVERSE_SELECT_DIRECTION, encoderDirection = -(ENCODERBASE)); + } + + #else + + static inline void update_buttons() {} + + #endif + + #if ENABLED(TOUCH_SCREEN_CALIBRATION) + static void touch_calibration_screen(); + #endif + + #if HAS_GRAPHICAL_TFT + static void move_axis_screen(); + #endif + +private: + + #if SCREENS_CAN_TIME_OUT + static millis_t return_to_status_ms; + static bool defer_return_to_status; + #else + static constexpr bool defer_return_to_status = false; + #endif + + #if HAS_STATUS_MESSAGE + static void finish_status(const bool persist); + #endif + + #if HAS_WIRED_LCD + static void draw_status_screen(); + #if HAS_GRAPHICAL_TFT + static void tft_idle(); + #if ENABLED(TOUCH_SCREEN) + static bool touch_pressed(); + #endif + #endif + #endif +}; + +extern MarlinUI ui; + +#define LCD_MESSAGEPGM_P(x) ui.set_status_P(x) +#define LCD_ALERTMESSAGEPGM_P(x) ui.set_alert_status_P(x) + +#define LCD_MESSAGEPGM(x) LCD_MESSAGEPGM_P(GET_TEXT(x)) +#define LCD_ALERTMESSAGEPGM(x) LCD_ALERTMESSAGEPGM_P(GET_TEXT(x)) diff --git a/Marlin/src/lcd/menu/game/game.h b/Marlin/src/lcd/menu/game/game.h index e788f2980512..999aa781008d 100644 --- a/Marlin/src/lcd/menu/game/game.h +++ b/Marlin/src/lcd/menu/game/game.h @@ -22,9 +22,9 @@ #pragma once #include "../../../inc/MarlinConfigPre.h" -#include "../../dogm/ultralcd_DOGM.h" +#include "../../dogm/marlinui_DOGM.h" #include "../../lcdprint.h" -#include "../../ultralcd.h" +#include "../../marlinui.h" //#define MUTE_GAMES @@ -53,10 +53,18 @@ // Pool game data to save SRAM union MarlinGameData { - TERN_(MARLIN_BRICKOUT, brickout_data_t brickout); - TERN_(MARLIN_INVADERS, invaders_data_t invaders); - TERN_(MARLIN_SNAKE, snake_data_t snake); - TERN_(MARLIN_MAZE, maze_data_t maze); + #if ENABLED(MARLIN_BRICKOUT) + brickout_data_t brickout; + #endif + #if ENABLED(MARLIN_INVADERS) + invaders_data_t invaders; + #endif + #if ENABLED(MARLIN_SNAKE) + snake_data_t snake; + #endif + #if ENABLED(MARLIN_MAZE) + maze_data_t maze; + #endif }; extern MarlinGameData marlin_game_data; diff --git a/Marlin/src/lcd/menu/menu.cpp b/Marlin/src/lcd/menu/menu.cpp index 5d67410351f6..01c8bb80c0ef 100644 --- a/Marlin/src/lcd/menu/menu.cpp +++ b/Marlin/src/lcd/menu/menu.cpp @@ -50,9 +50,12 @@ int8_t encoderTopLine, encoderLine, screen_items; typedef struct { - screenFunc_t menu_function; - uint32_t encoder_position; - int8_t top_line, items; + screenFunc_t menu_function; // The screen's function + uint32_t encoder_position; // The position of the encoder + int8_t top_line, items; // The amount of scroll, and the number of items + #if SCREENS_CAN_TIME_OUT + bool sticky; // The screen is sticky + #endif } menuPosition; menuPosition screen_history[6]; uint8_t screen_history_depth = 0; @@ -75,14 +78,14 @@ bool MenuEditItemBase::liveEdit; void MarlinUI::return_to_status() { goto_screen(status_screen); } -void MarlinUI::save_previous_screen() { +void MarlinUI::push_current_screen() { if (screen_history_depth < COUNT(screen_history)) - screen_history[screen_history_depth++] = { currentScreen, encoderPosition, encoderTopLine, screen_items }; + screen_history[screen_history_depth++] = { currentScreen, encoderPosition, encoderTopLine, screen_items OPTARG(SCREENS_CAN_TIME_OUT, screen_is_sticky()) }; } void MarlinUI::_goto_previous_screen(TERN_(TURBO_BACK_MENU_ITEM, const bool is_back/*=false*/)) { - TERN(TURBO_BACK_MENU_ITEM,,constexpr bool is_back = false); - TERN_(HAS_TOUCH_XPT2046, on_edit_screen = false); + IF_DISABLED(TURBO_BACK_MENU_ITEM, constexpr bool is_back = false); + TERN_(HAS_TOUCH_BUTTONS, on_edit_screen = false); if (screen_history_depth > 0) { menuPosition &sh = screen_history[--screen_history_depth]; goto_screen(sh.menu_function, @@ -90,6 +93,7 @@ void MarlinUI::_goto_previous_screen(TERN_(TURBO_BACK_MENU_ITEM, const bool is_b is_back ? 0 : sh.top_line, sh.items ); + defer_status_screen(TERN_(SCREENS_CAN_TIME_OUT, sh.sticky)); } else return_to_status(); @@ -123,13 +127,13 @@ void MarlinUI::_goto_previous_screen(TERN_(TURBO_BACK_MENU_ITEM, const bool is_b * MenuItem_int3::draw(encoderLine == _thisItemNr, _lcdLineNr, plabel, &feedrate_percentage, 10, 999) */ void MenuEditItemBase::edit_screen(strfunc_t strfunc, loadfunc_t loadfunc) { - TERN_(HAS_TOUCH_XPT2046, ui.repeat_delay = BUTTON_DELAY_EDIT); + TERN_(HAS_TOUCH_BUTTONS, ui.repeat_delay = BUTTON_DELAY_EDIT); if (int32_t(ui.encoderPosition) < 0) ui.encoderPosition = 0; if (int32_t(ui.encoderPosition) > maxEditValue) ui.encoderPosition = maxEditValue; if (ui.should_draw()) draw_edit_screen(strfunc(ui.encoderPosition + minEditValue)); if (ui.lcd_clicked || (liveEdit && ui.should_draw())) { - if (editValue != nullptr) loadfunc(editValue, ui.encoderPosition + minEditValue); + if (editValue) loadfunc(editValue, ui.encoderPosition + minEditValue); if (callbackFunc && (liveEdit || ui.lcd_clicked)) (*callbackFunc)(); if (ui.use_click()) ui.goto_previous_screen(); } @@ -145,9 +149,9 @@ void MenuEditItemBase::goto_edit_screen( const screenFunc_t cb, // Callback after edit const bool le // Flag to call cb() during editing ) { - TERN_(HAS_TOUCH_XPT2046, ui.on_edit_screen = true); + TERN_(HAS_TOUCH_BUTTONS, ui.on_edit_screen = true); ui.screen_changed = true; - ui.save_previous_screen(); + ui.push_current_screen(); ui.refresh(); editLabel = el; editValue = ev; @@ -175,7 +179,7 @@ bool printer_busy() { void MarlinUI::goto_screen(screenFunc_t screen, const uint16_t encoder/*=0*/, const uint8_t top/*=0*/, const uint8_t items/*=0*/) { if (currentScreen != screen) { - TERN_(HAS_TOUCH_XPT2046, repeat_delay = BUTTON_DELAY_MENU); + TERN_(HAS_TOUCH_BUTTONS, repeat_delay = BUTTON_DELAY_MENU); TERN_(LCD_SET_PROGRESS_MANUALLY, progress_reset()); @@ -188,8 +192,7 @@ void MarlinUI::goto_screen(screenFunc_t screen, const uint16_t encoder/*=0*/, co doubleclick_expire_ms = millis() + DOUBLECLICK_MAX_INTERVAL; } else if (screen == status_screen && currentScreen == menu_main && PENDING(millis(), doubleclick_expire_ms)) { - if ( (ENABLED(BABYSTEP_WITHOUT_HOMING) || all_axes_known()) - && (ENABLED(BABYSTEP_ALWAYS_AVAILABLE) || printer_busy()) ) + if (BABYSTEP_ALLOWED()) screen = TERN(BABYSTEP_ZPROBE_OFFSET, lcd_babystep_zoffset, lcd_babystep_z); else { #if ENABLED(MOVE_Z_WHEN_IDLE) @@ -206,8 +209,8 @@ void MarlinUI::goto_screen(screenFunc_t screen, const uint16_t encoder/*=0*/, co screen_items = items; if (on_status_screen()) { defer_status_screen(false); + clear_menu_history(); TERN_(AUTO_BED_LEVELING_UBL, ubl.lcd_map_control = false); - screen_history_depth = 0; } clear_lcd(); @@ -238,7 +241,7 @@ void MarlinUI::goto_screen(screenFunc_t screen, const uint16_t encoder/*=0*/, co // void MarlinUI::synchronize(PGM_P const msg/*=nullptr*/) { static PGM_P sync_message = msg ?: GET_TEXT(MSG_MOVING); - save_previous_screen(); + push_current_screen(); goto_screen([]{ if (should_draw()) MenuItem_static::draw(LCD_HEIGHT >= 4, sync_message); }); @@ -290,7 +293,7 @@ void scroll_screen(const uint8_t limit, const bool is_menu) { #if HAS_LINE_TO_Z - void line_to_z(const float &z) { + void line_to_z(const_float_t z) { current_position.z = z; line_to_current_position(manual_feedrate_mm_s.z); } @@ -372,6 +375,7 @@ void MenuItem_confirm::select_screen( selectFunc_t yesFunc, selectFunc_t noFunc, PGM_P const pref, const char * const string/*=nullptr*/, PGM_P const suff/*=nullptr*/ ) { + ui.defer_status_screen(); const bool ui_selection = ui.update_selection(), got_click = ui.use_click(); if (got_click || ui.should_draw()) { draw_select_screen(yes, no, ui_selection, pref, string, suff); @@ -379,7 +383,6 @@ void MenuItem_confirm::select_screen( selectFunc_t callFunc = ui_selection ? yesFunc : noFunc; if (callFunc) callFunc(); else ui.goto_previous_screen(); } - ui.defer_status_screen(); } } diff --git a/Marlin/src/lcd/menu/menu.h b/Marlin/src/lcd/menu/menu.h index 89970225adbe..28d377da0cf2 100644 --- a/Marlin/src/lcd/menu/menu.h +++ b/Marlin/src/lcd/menu/menu.h @@ -21,7 +21,7 @@ */ #pragma once -#include "../ultralcd.h" +#include "../marlinui.h" #include "../../libs/numtostr.h" #include "../../inc/MarlinConfig.h" @@ -40,7 +40,7 @@ typedef void (*selectFunc_t)(); #define SS_DEFAULT SS_CENTER #if HAS_MARLINUI_U8GLIB && EITHER(BABYSTEP_ZPROBE_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY) - void _lcd_zoffset_overlay_gfx(const float zvalue); + void _lcd_zoffset_overlay_gfx(const_float_t zvalue); #endif #if ENABLED(BABYSTEP_ZPROBE_OFFSET) && Z_PROBE_OFFSET_RANGE_MIN >= -9 && Z_PROBE_OFFSET_RANGE_MAX <= 9 @@ -132,14 +132,15 @@ class MenuItem_confirm : public MenuItemBase { // The Menu Edit shadow value typedef union { - bool state; - float decimal; - int8_t int8; - int16_t int16; - int32_t int32; - uint8_t uint8; - uint16_t uint16; - uint32_t uint32; + bool state; + float decimal; + int8_t int8; + int16_t int16; + int32_t int32; + uint8_t uint8; + uint16_t uint16; + uint32_t uint32; + celsius_t celsius; } chimera_t; extern chimera_t editable; @@ -172,14 +173,14 @@ class MenuEditItemBase : public MenuItemBase { public: // Implemented for HD44780 and DOGM // Draw the current item at specified row with edit data - static void draw(const bool sel, const uint8_t row, PGM_P const pstr, const char* const inStr, const bool pgm=false); + static void draw(const bool sel, const uint8_t row, PGM_P const pstr, const char * const inStr, const bool pgm=false); // Implemented for HD44780 and DOGM // This low-level method is good to draw from anywhere - static void draw_edit_screen(PGM_P const pstr, const char* const value); + static void draw_edit_screen(PGM_P const pstr, const char * const value); // This method is for the current menu item - static inline void draw_edit_screen(const char* const value) { draw_edit_screen(editLabel, value); } + static inline void draw_edit_screen(const char * const value) { draw_edit_screen(editLabel, value); } }; #if ENABLED(SDSUPPORT) @@ -212,11 +213,7 @@ void _lcd_draw_homing(); #define HAS_LINE_TO_Z ANY(DELTA, PROBE_MANUALLY, MESH_BED_LEVELING, LEVEL_BED_CORNERS) #if HAS_LINE_TO_Z - void line_to_z(const float &z); -#endif - -#if HAS_MARLINUI_U8GLIB && EITHER(BABYSTEP_ZPROBE_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY) - void _lcd_zoffset_overlay_gfx(const float zvalue); + void line_to_z(const_float_t z); #endif #if ENABLED(PROBE_OFFSET_WIZARD) @@ -249,3 +246,8 @@ void _lcd_draw_homing(); #if ENABLED(TOUCH_SCREEN_CALIBRATION) void touch_screen_calibration(); #endif + +extern uint8_t screen_history_depth; +inline void clear_menu_history() { screen_history_depth = 0; } + +#define STICKY_SCREEN(S) []{ ui.defer_status_screen(); ui.goto_screen(S); } diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index 642d9d84d94f..4ae38edf24ce 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -58,21 +58,18 @@ void menu_tmc(); void menu_backlash(); -#if ENABLED(HAS_MOTOR_CURRENT_DAC) +#if HAS_MOTOR_CURRENT_DAC #include "../../feature/dac/stepper_dac.h" void menu_dac() { static xyze_uint8_t driverPercent; - LOOP_XYZE(i) driverPercent[i] = stepper_dac.get_current_percent((AxisEnum)i); + LOOP_LOGICAL_AXES(i) driverPercent[i] = stepper_dac.get_current_percent((AxisEnum)i); START_MENU(); BACK_ITEM(MSG_ADVANCED_SETTINGS); #define EDIT_DAC_PERCENT(A) EDIT_ITEM(uint8, MSG_DAC_PERCENT_##A, &driverPercent[_AXIS(A)], 0, 100, []{ stepper_dac.set_current_percents(driverPercent); }) - EDIT_DAC_PERCENT(X); - EDIT_DAC_PERCENT(Y); - EDIT_DAC_PERCENT(Z); - EDIT_DAC_PERCENT(E); - ACTION_ITEM(MSG_DAC_EEPROM_WRITE, dac_commit_eeprom); + LOGICAL_AXIS_CODE(EDIT_DAC_PERCENT(E), EDIT_DAC_PERCENT(X), EDIT_DAC_PERCENT(Y), EDIT_DAC_PERCENT(Z), EDIT_DAC_PERCENT(I), EDIT_DAC_PERCENT(J), EDIT_DAC_PERCENT(K)); + ACTION_ITEM(MSG_DAC_EEPROM_WRITE, stepper_dac.commit_eeprom); END_MENU(); } @@ -110,10 +107,10 @@ void menu_backlash(); #if ENABLED(LIN_ADVANCE) #if EXTRUDERS == 1 - EDIT_ITEM(float42_52, MSG_ADVANCE_K, &planner.extruder_advance_K[0], 0, 999); + EDIT_ITEM(float42_52, MSG_ADVANCE_K, &planner.extruder_advance_K[0], 0, 10); #elif HAS_MULTI_EXTRUDER LOOP_L_N(n, EXTRUDERS) - EDIT_ITEM_N(float42_52, n, MSG_ADVANCE_K_E, &planner.extruder_advance_K[n], 0, 999); + EDIT_ITEM_N(float42_52, n, MSG_ADVANCE_K_E, &planner.extruder_advance_K[n], 0, 10); #endif #endif @@ -140,22 +137,22 @@ void menu_backlash(); #if ENABLED(ADVANCED_PAUSE_FEATURE) constexpr float extrude_maxlength = TERN(PREVENT_LENGTHY_EXTRUDE, EXTRUDE_MAXLENGTH, 999); - EDIT_ITEM_FAST(float3, MSG_FILAMENT_UNLOAD, &fc_settings[active_extruder].unload_length, 0, extrude_maxlength); + EDIT_ITEM_FAST(float4, MSG_FILAMENT_UNLOAD, &fc_settings[active_extruder].unload_length, 0, extrude_maxlength); #if HAS_MULTI_EXTRUDER LOOP_L_N(n, EXTRUDERS) - EDIT_ITEM_FAST_N(float3, n, MSG_FILAMENTUNLOAD_E, &fc_settings[n].unload_length, 0, extrude_maxlength); + EDIT_ITEM_FAST_N(float4, n, MSG_FILAMENTUNLOAD_E, &fc_settings[n].unload_length, 0, extrude_maxlength); #endif - EDIT_ITEM_FAST(float3, MSG_FILAMENT_LOAD, &fc_settings[active_extruder].load_length, 0, extrude_maxlength); + EDIT_ITEM_FAST(float4, MSG_FILAMENT_LOAD, &fc_settings[active_extruder].load_length, 0, extrude_maxlength); #if HAS_MULTI_EXTRUDER LOOP_L_N(n, EXTRUDERS) - EDIT_ITEM_FAST_N(float3, n, MSG_FILAMENTLOAD_E, &fc_settings[n].load_length, 0, extrude_maxlength); + EDIT_ITEM_FAST_N(float4, n, MSG_FILAMENTLOAD_E, &fc_settings[n].load_length, 0, extrude_maxlength); #endif #endif #if HAS_FILAMENT_RUNOUT_DISTANCE editable.decimal = runout.runout_distance(); - EDIT_ITEM(float3, MSG_RUNOUT_DISTANCE_MM, &editable.decimal, 1, float(FILAMENT_RUNOUT_DISTANCE_MM) * 1.5f, + EDIT_ITEM_FAST(float3, MSG_RUNOUT_DISTANCE_MM, &editable.decimal, 1, 999, []{ runout.set_runout_distance(editable.decimal); }, true ); #endif @@ -177,18 +174,25 @@ void menu_backlash(); #if ENABLED(PIDTEMPBED) int16_t autotune_temp_bed = PREHEAT_1_TEMP_BED; #endif + #if ENABLED(PIDTEMPCHAMBER) + int16_t autotune_temp_chamber = PREHEAT_1_TEMP_CHAMBER; + #endif #include "../../gcode/queue.h" - void _lcd_autotune(const int16_t e) { + void _lcd_autotune(const heater_id_t hid) { char cmd[30]; - sprintf_P(cmd, PSTR("M303 U1 E%i S%i"), e, - #if HAS_PID_FOR_BOTH - e < 0 ? autotune_temp_bed : autotune_temp[e] - #else - TERN(PIDTEMPBED, autotune_temp_bed, autotune_temp[e]) + int16_t tune_temp; + switch (hid) { + #if ENABLED(PIDTEMPBED) + case H_BED: tune_temp = autotune_temp_bed; break; #endif - ); + #if ENABLED(PIDTEMPCHAMBER) + case H_CHAMBER: tune_temp = autotune_temp_chamber; break; + #endif + default: tune_temp = autotune_temp[hid]; break; + } + sprintf_P(cmd, PSTR("M303 U1 E%i S%i"), hid, tune_temp); queue.inject(cmd); ui.return_to_status(); } @@ -202,12 +206,12 @@ void menu_backlash(); // Helpers for editing PID Ki & Kd values // grab the PID value out of the temp variable; scale it; then update the PID driver void copy_and_scalePID_i(int16_t e) { - TERN(PID_PARAMS_PER_HOTEND,,UNUSED(e)); + UNUSED(e); PID_PARAM(Ki, e) = scalePID_i(raw_Ki); thermalManager.updatePID(); } void copy_and_scalePID_d(int16_t e) { - TERN(PID_PARAMS_PER_HOTEND,,UNUSED(e)); + UNUSED(e); PID_PARAM(Kd, e) = scalePID_d(raw_Kd); thermalManager.updatePID(); } @@ -225,7 +229,7 @@ void menu_backlash(); #if ENABLED(PID_AUTOTUNE_MENU) #define DEFINE_PIDTEMP_FUNCS(N) \ _DEFINE_PIDTEMP_BASE_FUNCS(N); \ - void lcd_autotune_callback_E##N() { _lcd_autotune(N); } + void lcd_autotune_callback_E##N() { _lcd_autotune(heater_id_t(N)); } #else #define DEFINE_PIDTEMP_FUNCS(N) _DEFINE_PIDTEMP_BASE_FUNCS(N); #endif @@ -254,8 +258,8 @@ void menu_backlash(); // #if BOTH(AUTOTEMP, HAS_TEMP_HOTEND) EDIT_ITEM(bool, MSG_AUTOTEMP, &planner.autotemp_enabled); - EDIT_ITEM(float3, MSG_MIN, &planner.autotemp_min, 0, float(HEATER_0_MAXTEMP) - HOTEND_OVERSHOOT); - EDIT_ITEM(float3, MSG_MAX, &planner.autotemp_max, 0, float(HEATER_0_MAXTEMP) - HOTEND_OVERSHOOT); + EDIT_ITEM(int3, MSG_MIN, &planner.autotemp_min, 0, thermalManager.hotend_max_target(0)); + EDIT_ITEM(int3, MSG_MAX, &planner.autotemp_max, 0, thermalManager.hotend_max_target(0)); EDIT_ITEM(float42_52, MSG_FACTOR, &planner.autotemp_factor, 0, 10); #endif @@ -269,56 +273,70 @@ void menu_backlash(); // #if ENABLED(PID_EDIT_MENU) - #define __PID_BASE_MENU_ITEMS(N) \ - raw_Ki = unscalePID_i(TERN(PID_BED_MENU_SECTION, thermalManager.temp_bed.pid.Ki, PID_PARAM(Ki, N))); \ - raw_Kd = unscalePID_d(TERN(PID_BED_MENU_SECTION, thermalManager.temp_bed.pid.Kd, PID_PARAM(Kd, N))); \ - EDIT_ITEM_FAST_N(float41sign, N, MSG_PID_P_E, &TERN(PID_BED_MENU_SECTION, thermalManager.temp_bed.pid.Kp, PID_PARAM(Kp, N)), 1, 9990); \ + #define _PID_EDIT_ITEMS_TMPL(N,T) \ + raw_Ki = unscalePID_i(T.pid.Ki); \ + raw_Kd = unscalePID_d(T.pid.Kd); \ + EDIT_ITEM_FAST_N(float41sign, N, MSG_PID_P_E, &T.pid.Kp, 1, 9990); \ + EDIT_ITEM_FAST_N(float52sign, N, MSG_PID_I_E, &raw_Ki, 0.01f, 9990, []{ copy_and_scalePID_i(N); }); \ + EDIT_ITEM_FAST_N(float41sign, N, MSG_PID_D_E, &raw_Kd, 1, 9990, []{ copy_and_scalePID_d(N); }) + + #define __PID_HOTEND_MENU_ITEMS(N) \ + raw_Ki = unscalePID_i(PID_PARAM(Ki, N)); \ + raw_Kd = unscalePID_d(PID_PARAM(Kd, N)); \ + EDIT_ITEM_FAST_N(float41sign, N, MSG_PID_P_E, &PID_PARAM(Kp, N), 1, 9990); \ EDIT_ITEM_FAST_N(float52sign, N, MSG_PID_I_E, &raw_Ki, 0.01f, 9990, []{ copy_and_scalePID_i(N); }); \ EDIT_ITEM_FAST_N(float41sign, N, MSG_PID_D_E, &raw_Kd, 1, 9990, []{ copy_and_scalePID_d(N); }) #if ENABLED(PID_EXTRUSION_SCALING) - #define _PID_BASE_MENU_ITEMS(N) \ - __PID_BASE_MENU_ITEMS(N); \ - EDIT_ITEM_N(float3, N, MSG_PID_C_E, &PID_PARAM(Kc, N), 1, 9990) + #define _PID_HOTEND_MENU_ITEMS(N) \ + __PID_HOTEND_MENU_ITEMS(N); \ + EDIT_ITEM_N(float4, N, MSG_PID_C_E, &PID_PARAM(Kc, N), 1, 9990) #else - #define _PID_BASE_MENU_ITEMS(N) __PID_BASE_MENU_ITEMS(N) + #define _PID_HOTEND_MENU_ITEMS(N) __PID_HOTEND_MENU_ITEMS(N) #endif #if ENABLED(PID_FAN_SCALING) - #define _PID_EDIT_MENU_ITEMS(N) \ - _PID_BASE_MENU_ITEMS(N); \ - EDIT_ITEM_N(float3, N, MSG_PID_F_E, &PID_PARAM(Kf, N), 1, 9990) + #define _HOTEND_PID_EDIT_MENU_ITEMS(N) \ + _PID_HOTEND_MENU_ITEMS(N); \ + EDIT_ITEM_N(float4, N, MSG_PID_F_E, &PID_PARAM(Kf, N), 1, 9990) #else - #define _PID_EDIT_MENU_ITEMS(N) _PID_BASE_MENU_ITEMS(N) + #define _HOTEND_PID_EDIT_MENU_ITEMS(N) _PID_HOTEND_MENU_ITEMS(N) #endif #else - #define _PID_EDIT_MENU_ITEMS(N) NOOP + #define _HOTEND_PID_EDIT_MENU_ITEMS(N) NOOP #endif #if ENABLED(PID_AUTOTUNE_MENU) - #define PID_EDIT_MENU_ITEMS(N) \ - _PID_EDIT_MENU_ITEMS(N); \ - EDIT_ITEM_FAST_N(int3, N, MSG_PID_AUTOTUNE_E, &autotune_temp[N], 150, thermalManager.heater_maxtemp[N] - HOTEND_OVERSHOOT, []{ _lcd_autotune(MenuItemBase::itemIndex); }); + #define HOTEND_PID_EDIT_MENU_ITEMS(N) \ + _HOTEND_PID_EDIT_MENU_ITEMS(N); \ + EDIT_ITEM_FAST_N(int3, N, MSG_PID_AUTOTUNE_E, &autotune_temp[N], 150, thermalManager.hotend_max_target(N), []{ _lcd_autotune(heater_id_t(MenuItemBase::itemIndex)); }); #else - #define PID_EDIT_MENU_ITEMS(N) _PID_EDIT_MENU_ITEMS(N); + #define HOTEND_PID_EDIT_MENU_ITEMS(N) _HOTEND_PID_EDIT_MENU_ITEMS(N); #endif - PID_EDIT_MENU_ITEMS(0); + HOTEND_PID_EDIT_MENU_ITEMS(0); #if ENABLED(PID_PARAMS_PER_HOTEND) - REPEAT_S(1, HOTENDS, PID_EDIT_MENU_ITEMS) + REPEAT_S(1, HOTENDS, HOTEND_PID_EDIT_MENU_ITEMS) #endif #if ENABLED(PIDTEMPBED) #if ENABLED(PID_EDIT_MENU) - #define PID_BED_MENU_SECTION - __PID_BASE_MENU_ITEMS(-1); - #undef PID_BED_MENU_SECTION + _PID_EDIT_ITEMS_TMPL(H_BED, thermalManager.temp_bed); + #endif + #if ENABLED(PID_AUTOTUNE_MENU) + EDIT_ITEM_FAST_N(int3, H_BED, MSG_PID_AUTOTUNE_E, &autotune_temp_bed, PREHEAT_1_TEMP_BED, BED_MAX_TARGET, []{ _lcd_autotune(H_BED); }); + #endif + #endif + + #if ENABLED(PIDTEMPCHAMBER) + #if ENABLED(PID_EDIT_MENU) + _PID_EDIT_ITEMS_TMPL(H_CHAMBER, thermalManager.temp_chamber); #endif #if ENABLED(PID_AUTOTUNE_MENU) - EDIT_ITEM_FAST_N(int3, -1, MSG_PID_AUTOTUNE_E, &autotune_temp_bed, PREHEAT_1_TEMP_BED, BED_MAX_TARGET, []{ _lcd_autotune(-1); }); + EDIT_ITEM_FAST_N(int3, H_CHAMBER, MSG_PID_AUTOTUNE_E, &autotune_temp_chamber, PREHEAT_1_TEMP_CHAMBER, CHAMBER_MAX_TARGET, []{ _lcd_autotune(H_CHAMBER); }); #endif #endif @@ -329,16 +347,6 @@ void menu_backlash(); #if DISABLED(SLIM_LCD_MENUS) - #if ENABLED(DISTINCT_E_FACTORS) - inline void _reset_e_acceleration_rate(const uint8_t e) { if (e == active_extruder) planner.reset_acceleration_rates(); } - inline void _planner_refresh_e_positioning(const uint8_t e) { - if (e == active_extruder) - planner.refresh_positioning(); - else - planner.steps_to_mm[E_AXIS_N(e)] = 1.0f / planner.settings.axis_steps_per_mm[E_AXIS_N(e)]; - } - #endif - // M203 / M205 Velocity options void menu_advanced_velocity() { // M203 Max Feedrate @@ -348,7 +356,7 @@ void menu_backlash(); #elif ENABLED(LIMITED_MAX_FR_EDITING) DEFAULT_MAX_FEEDRATE #else - { 999, 999, 999, 999 } + LOGICAL_AXIS_ARRAY(9999, 9999, 9999, 9999, 9999, 9999, 9999) #endif ; #if ENABLED(LIMITED_MAX_FR_EDITING) && !defined(MAX_FEEDRATE_EDIT_VALUES) @@ -360,24 +368,22 @@ void menu_backlash(); START_MENU(); BACK_ITEM(MSG_ADVANCED_SETTINGS); - #define EDIT_VMAX(N) EDIT_ITEM_FAST(float3, MSG_VMAX_##N, &planner.settings.max_feedrate_mm_s[_AXIS(N)], 1, max_fr_edit_scaled[_AXIS(N)]) - EDIT_VMAX(A); - EDIT_VMAX(B); - EDIT_VMAX(C); + #define EDIT_VMAX(N) EDIT_ITEM_FAST(float5, MSG_VMAX_##N, &planner.settings.max_feedrate_mm_s[_AXIS(N)], 1, max_fr_edit_scaled[_AXIS(N)]) + LINEAR_AXIS_CODE(EDIT_VMAX(A), EDIT_VMAX(B), EDIT_VMAX(C), EDIT_VMAX(I), EDIT_VMAX(J), EDIT_VMAX(K)); #if E_STEPPERS - EDIT_ITEM_FAST(float3, MSG_VMAX_E, &planner.settings.max_feedrate_mm_s[E_AXIS_N(active_extruder)], 1, max_fr_edit_scaled.e); + EDIT_ITEM_FAST(float5, MSG_VMAX_E, &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) - EDIT_ITEM_FAST_N(float3, n, MSG_VMAX_EN, &planner.settings.max_feedrate_mm_s[E_AXIS_N(n)], 1, max_fr_edit_scaled.e); + 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 // M205 S Min Feedrate - EDIT_ITEM_FAST(float3, MSG_VMIN, &planner.settings.min_feedrate_mm_s, 0, 999); + EDIT_ITEM_FAST(float5, MSG_VMIN, &planner.settings.min_feedrate_mm_s, 0, 9999); // M205 T Min Travel Feedrate - EDIT_ITEM_FAST(float3, MSG_VTRAV_MIN, &planner.settings.min_travel_feedrate_mm_s, 0, 999); + EDIT_ITEM_FAST(float5, MSG_VTRAV_MIN, &planner.settings.min_travel_feedrate_mm_s, 0, 9999); END_MENU(); } @@ -393,7 +399,7 @@ void menu_backlash(); #elif ENABLED(LIMITED_MAX_ACCEL_EDITING) DEFAULT_MAX_ACCELERATION #else - { 99000, 99000, 99000, 99000 } + LOGICAL_AXIS_ARRAY(99000, 99000, 99000, 99000, 99000, 99000, 99000) #endif ; #if ENABLED(LIMITED_MAX_ACCEL_EDITING) && !defined(MAX_ACCEL_EDIT_VALUES) @@ -408,21 +414,27 @@ void menu_backlash(); // M204 P Acceleration EDIT_ITEM_FAST(float5_25, MSG_ACC, &planner.settings.acceleration, 25, max_accel); - // M204 R Retract Acceleration - EDIT_ITEM_FAST(float5, MSG_A_RETRACT, &planner.settings.retract_acceleration, 100, planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(active_extruder)]); + #if HAS_EXTRUDERS + // M204 R Retract Acceleration + EDIT_ITEM_FAST(float5, MSG_A_RETRACT, &planner.settings.retract_acceleration, 100, planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(active_extruder)]); + #endif // M204 T Travel Acceleration EDIT_ITEM_FAST(float5_25, MSG_A_TRAVEL, &planner.settings.travel_acceleration, 25, max_accel); #define EDIT_AMAX(Q,L) EDIT_ITEM_FAST(long5_25, MSG_AMAX_##Q, &planner.settings.max_acceleration_mm_per_s2[_AXIS(Q)], L, max_accel_edit_scaled[_AXIS(Q)], []{ planner.reset_acceleration_rates(); }) - EDIT_AMAX(A, 100); - EDIT_AMAX(B, 100); - EDIT_AMAX(C, 10); + LINEAR_AXIS_CODE( + EDIT_AMAX(A, 100), EDIT_AMAX(B, 100), EDIT_AMAX(C, 10), + EDIT_AMAX(I, 10), EDIT_AMAX(J, 10), EDIT_AMAX(K, 10) + ); #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.reset_acceleration_rates(); }); LOOP_L_N(n, E_STEPPERS) - 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, []{ _reset_e_acceleration_rate(MenuItemBase::itemIndex); }); + 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.reset_acceleration_rates(); + }); #elif E_STEPPERS EDIT_ITEM_FAST(long5_25, MSG_AMAX_E, &planner.settings.max_acceleration_mm_per_s2[E_AXIS], 100, max_accel_edit_scaled.e, []{ planner.reset_acceleration_rates(); }); #endif @@ -460,14 +472,17 @@ void menu_backlash(); #endif ; #define EDIT_JERK(N) EDIT_ITEM_FAST(float3, MSG_V##N##_JERK, &planner.max_jerk[_AXIS(N)], 1, max_jerk_edit[_AXIS(N)]) - EDIT_JERK(A); - EDIT_JERK(B); #if ENABLED(DELTA) - EDIT_JERK(C); + #define EDIT_JERK_C() EDIT_JERK(C) #else - EDIT_ITEM_FAST(float52sign, MSG_VC_JERK, &planner.max_jerk.c, 0.1f, max_jerk_edit.c); + #define EDIT_JERK_C() EDIT_ITEM_FAST(float52sign, MSG_VC_JERK, &planner.max_jerk.c, 0.1f, max_jerk_edit.c) #endif - #if HAS_CLASSIC_E_JERK + LINEAR_AXIS_CODE( + EDIT_JERK(A), EDIT_JERK(B), EDIT_JERK_C(), + EDIT_JERK(I), EDIT_JERK(J), EDIT_JERK(K) + ); + + #if HAS_EXTRUDERS EDIT_ITEM_FAST(float52sign, MSG_VE_JERK, &planner.max_jerk.e, 0.1f, max_jerk_edit.e); #endif @@ -503,13 +518,20 @@ void menu_advanced_steps_per_mm() { BACK_ITEM(MSG_ADVANCED_SETTINGS); #define EDIT_QSTEPS(Q) EDIT_ITEM_FAST(float51, MSG_##Q##_STEPS, &planner.settings.axis_steps_per_mm[_AXIS(Q)], 5, 9999, []{ planner.refresh_positioning(); }) - EDIT_QSTEPS(A); - EDIT_QSTEPS(B); - EDIT_QSTEPS(C); + LINEAR_AXIS_CODE( + EDIT_QSTEPS(A), EDIT_QSTEPS(B), EDIT_QSTEPS(C), + EDIT_QSTEPS(I), EDIT_QSTEPS(J), EDIT_QSTEPS(K) + ); #if ENABLED(DISTINCT_E_FACTORS) LOOP_L_N(n, E_STEPPERS) - EDIT_ITEM_FAST_N(float51, n, MSG_EN_STEPS, &planner.settings.axis_steps_per_mm[E_AXIS_N(n)], 5, 9999, []{ _planner_refresh_e_positioning(MenuItemBase::itemIndex); }); + EDIT_ITEM_FAST_N(float51, n, MSG_EN_STEPS, &planner.settings.axis_steps_per_mm[E_AXIS_N(n)], 5, 9999, []{ + const uint8_t e = MenuItemBase::itemIndex; + if (e == active_extruder) + planner.refresh_positioning(); + else + planner.steps_to_mm[E_AXIS_N(e)] = 1.0f / planner.settings.axis_steps_per_mm[E_AXIS_N(e)]; + }); #elif E_STEPPERS EDIT_ITEM_FAST(float51, MSG_E_STEPS, &planner.settings.axis_steps_per_mm[E_AXIS], 5, 9999, []{ planner.refresh_positioning(); }); #endif @@ -568,7 +590,7 @@ void menu_advanced_settings() { SUBMENU(MSG_BACKLASH, menu_backlash); #endif - #if ENABLED(HAS_MOTOR_CURRENT_DAC) + #if HAS_MOTOR_CURRENT_DAC SUBMENU(MSG_DRIVE_STRENGTH, menu_dac); #endif #if HAS_MOTOR_CURRENT_PWM @@ -587,10 +609,10 @@ void menu_advanced_settings() { SUBMENU(MSG_FILAMENT, menu_advanced_filament); #elif ENABLED(LIN_ADVANCE) #if EXTRUDERS == 1 - EDIT_ITEM(float42_52, MSG_ADVANCE_K, &planner.extruder_advance_K[0], 0, 999); + EDIT_ITEM(float42_52, MSG_ADVANCE_K, &planner.extruder_advance_K[0], 0, 10); #elif HAS_MULTI_EXTRUDER LOOP_L_N(n, E_STEPPERS) - EDIT_ITEM_N(float42_52, n, MSG_ADVANCE_K_E, &planner.extruder_advance_K[n], 0, 999); + EDIT_ITEM_N(float42_52, n, MSG_ADVANCE_K_E, &planner.extruder_advance_K[n], 0, 10); #endif #endif diff --git a/Marlin/src/lcd/menu/menu_backlash.cpp b/Marlin/src/lcd/menu/menu_backlash.cpp index 9d0b970ae1d3..b9adacc5021d 100644 --- a/Marlin/src/lcd/menu/menu_backlash.cpp +++ b/Marlin/src/lcd/menu/menu_backlash.cpp @@ -38,10 +38,28 @@ void menu_backlash() { EDIT_ITEM_FAST(percent, MSG_BACKLASH_CORRECTION, &backlash.correction, all_off, all_on); + #if DISABLED(CORE_BACKLASH) || ENABLED(MARKFORGED_XY) + #define _CAN_CALI AXIS_CAN_CALIBRATE + #else + #define _CAN_CALI(A) true + #endif #define EDIT_BACKLASH_DISTANCE(N) EDIT_ITEM_FAST(float43, MSG_BACKLASH_##N, &backlash.distance_mm[_AXIS(N)], 0.0f, 9.9f); - if (AXIS_CAN_CALIBRATE(A)) EDIT_BACKLASH_DISTANCE(A); - if (AXIS_CAN_CALIBRATE(B)) EDIT_BACKLASH_DISTANCE(B); - if (AXIS_CAN_CALIBRATE(C)) EDIT_BACKLASH_DISTANCE(C); + if (_CAN_CALI(A)) EDIT_BACKLASH_DISTANCE(A); + #if HAS_Y_AXIS && _CAN_CALI(B) + EDIT_BACKLASH_DISTANCE(B); + #endif + #if HAS_Z_AXIS && _CAN_CALI(C) + EDIT_BACKLASH_DISTANCE(C); + #endif + #if LINEAR_AXES >= 4 && _CAN_CALI(I) + EDIT_BACKLASH_DISTANCE(I); + #endif + #if LINEAR_AXES >= 5 && _CAN_CALI(J) + EDIT_BACKLASH_DISTANCE(J); + #endif + #if LINEAR_AXES >= 6 && _CAN_CALI(K) + EDIT_BACKLASH_DISTANCE(K); + #endif #ifdef BACKLASH_SMOOTHING_MM EDIT_ITEM_FAST(float43, MSG_BACKLASH_SMOOTHING, &backlash.smoothing_mm, 0.0f, 9.9f); diff --git a/Marlin/src/lcd/menu/menu_bed_corners.cpp b/Marlin/src/lcd/menu/menu_bed_corners.cpp index 16f9992c1852..82f25ea6f359 100644 --- a/Marlin/src/lcd/menu/menu_bed_corners.cpp +++ b/Marlin/src/lcd/menu/menu_bed_corners.cpp @@ -39,49 +39,302 @@ #ifndef LEVEL_CORNERS_Z_HOP #define LEVEL_CORNERS_Z_HOP 4.0 #endif - #ifndef LEVEL_CORNERS_HEIGHT #define LEVEL_CORNERS_HEIGHT 0.0 #endif +#if ENABLED(LEVEL_CORNERS_USE_PROBE) + #include "../../module/probe.h" + #include "../../module/endstops.h" + #if ENABLED(BLTOUCH) + #include "../../feature/bltouch.h" + #endif + #ifndef LEVEL_CORNERS_PROBE_TOLERANCE + #define LEVEL_CORNERS_PROBE_TOLERANCE 0.2 + #endif + float last_z; + int good_points; + bool corner_probing_done, wait_for_probe; + + #if HAS_MARLINUI_U8GLIB + #include "../dogm/marlinui_DOGM.h" + #endif + #define GOOD_POINTS_TO_STR(N) ui8tostr2(N) + #define LAST_Z_TO_STR(N) ftostr53_63(N) //ftostr42_52(N) + +#endif + static_assert(LEVEL_CORNERS_Z_HOP >= 0, "LEVEL_CORNERS_Z_HOP must be >= 0. Please update your configuration."); #if HAS_LEVELING static bool leveling_was_active = false; #endif +#ifndef LEVEL_CORNERS_LEVELING_ORDER + #define LEVEL_CORNERS_LEVELING_ORDER { LF, RF, LB, RB } // Default + //#define LEVEL_CORNERS_LEVELING_ORDER { LF, LB, RF } // 3 hard-coded points + //#define LEVEL_CORNERS_LEVELING_ORDER { LF, RF } // 3-Point tramming - Rear + //#define LEVEL_CORNERS_LEVELING_ORDER { LF, LB } // 3-Point tramming - Right + //#define LEVEL_CORNERS_LEVELING_ORDER { RF, RB } // 3-Point tramming - Left + //#define LEVEL_CORNERS_LEVELING_ORDER { LB, RB } // 3-Point tramming - Front +#endif + +#define LF 1 +#define RF 2 +#define RB 3 +#define LB 4 +constexpr int lco[] = LEVEL_CORNERS_LEVELING_ORDER; +constexpr bool level_corners_3_points = COUNT(lco) == 2; +static_assert(level_corners_3_points || COUNT(lco) == 4, "LEVEL_CORNERS_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 LEVEL_CORNERS_LEVELING_ORDER corners must be on the same edge."); + +constexpr int nr_edge_points = level_corners_3_points ? 3 : 4; +constexpr int available_points = nr_edge_points + ENABLED(LEVEL_CENTER_TOO); +constexpr int center_index = TERN(LEVEL_CENTER_TOO, available_points - 1, -1); +constexpr float inset_lfrb[4] = LEVEL_CORNERS_INSET_LFRB; +constexpr xy_pos_t lf { (X_MIN_BED) + inset_lfrb[0], (Y_MIN_BED) + inset_lfrb[1] }, + rb { (X_MAX_BED) - inset_lfrb[2], (Y_MAX_BED) - inset_lfrb[3] }; + +static int8_t bed_corner; + +/** + * Select next corner coordinates + */ +static void _lcd_level_bed_corners_get_next_position() { + + if (level_corners_3_points) { + if (bed_corner >= available_points) bed_corner = 0; // Above max position -> move back to first corner + switch (bed_corner) { + case 0 ... 1: + // First two corners set explicitly by the configuration + 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 Back + case LB: current_position.y = rb.y; break; // Left Back + } + break; + + case 2: + // Determine which edge to probe for 3rd point + current_position.set(lf.x + (rb.x - lf.x) / 2, lf.y + (rb.y - lf.y) / 2); + if ((lco[0] == LB && lco[1] == RB) || (lco[0] == RB && lco[1] == LB)) current_position.y = lf.y; // Front Center + if ((lco[0] == LF && lco[1] == LB) || (lco[0] == LB && lco[1] == LF)) current_position.x = rb.x; // Center Right + if ((lco[0] == RF && lco[1] == RB) || (lco[0] == RB && lco[1] == RF)) current_position.x = lf.x; // Left Center + if ((lco[0] == LF && lco[1] == RF) || (lco[0] == RF && lco[1] == LF)) current_position.y = rb.y; // Center Back + #if DISABLED(LEVEL_CENTER_TOO) && ENABLED(LEVEL_CORNERS_USE_PROBE) + bed_corner++; // Must increment the count to ensure it resets the loop if the 3rd point is out of tolerance + #endif + break; + + #if ENABLED(LEVEL_CENTER_TOO) + case 3: + current_position.set(X_CENTER, Y_CENTER); + break; + #endif + } + } + else { + // Four-Corner Bed Tramming with optional center + if (TERN0(LEVEL_CENTER_TOO, bed_corner == center_index)) { + current_position.set(X_CENTER, Y_CENTER); + TERN_(LEVEL_CORNERS_USE_PROBE, good_points--); // Decrement to allow one additional probe point + } + 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 + } + } + } +} + /** * Level corners, starting in the front-left corner. */ -static int8_t bed_corner; -static inline void _lcd_goto_next_corner() { - constexpr float lfrb[4] = LEVEL_CORNERS_INSET_LFRB; - constexpr xy_pos_t lf { (X_MIN_BED) + lfrb[0], (Y_MIN_BED) + lfrb[1] }, - rb { (X_MAX_BED) - lfrb[2], (Y_MAX_BED) - lfrb[3] }; - line_to_z(LEVEL_CORNERS_Z_HOP); - switch (bed_corner) { - case 0: current_position = lf; break; // copy xy - case 1: current_position.x = rb.x; break; - case 2: current_position.y = rb.y; break; - case 3: current_position.x = lf.x; break; - #if ENABLED(LEVEL_CENTER_TOO) - case 4: current_position.set(X_CENTER, Y_CENTER); break; +#if ENABLED(LEVEL_CORNERS_USE_PROBE) + + #define VALIDATE_POINT(X, Y, STR) static_assert(Probe::build_time::can_reach((X), (Y)), \ + "LEVEL_CORNERS_INSET_LFRB " STR " inset is not reachable with the default NOZZLE_TO_PROBE offset and PROBING_MARGIN.") + VALIDATE_POINT(lf.x, Y_CENTER, "left"); VALIDATE_POINT(X_CENTER, lf.y, "front"); + VALIDATE_POINT(rb.x, Y_CENTER, "right"); VALIDATE_POINT(X_CENTER, rb.y, "back"); + + #ifndef PAGE_CONTAINS + #define PAGE_CONTAINS(...) true + #endif + + void _lcd_draw_probing() { + if (!ui.should_draw()) return; + + TERN_(HAS_MARLINUI_U8GLIB, ui.set_font(FONT_MENU)); // Set up the font for extra info + + MenuItem_static::draw(0, GET_TEXT(MSG_PROBING_MESH), SS_INVERT); // "Probing Mesh" heading + + uint8_t cy = TERN(TFT_COLOR_UI, 3, LCD_HEIGHT - 1), y = LCD_ROW_Y(cy); + + // Display # of good points found vs total needed + if (PAGE_CONTAINS(y - (MENU_FONT_HEIGHT), y)) { + SETCURSOR(TERN(TFT_COLOR_UI, 2, 0), cy); + lcd_put_u8str_P(GET_TEXT(MSG_BED_TRAMMING_GOOD_POINTS)); + IF_ENABLED(TFT_COLOR_UI, lcd_moveto(12, cy)); + lcd_put_u8str(GOOD_POINTS_TO_STR(good_points)); + lcd_put_wchar('/'); + lcd_put_u8str(GOOD_POINTS_TO_STR(nr_edge_points)); + } + + --cy; + y -= MENU_LINE_HEIGHT; + + // Display the Last Z value + if (PAGE_CONTAINS(y - (MENU_FONT_HEIGHT), y)) { + SETCURSOR(TERN(TFT_COLOR_UI, 2, 0), cy); + lcd_put_u8str_P(GET_TEXT(MSG_BED_TRAMMING_LAST_Z)); + IF_ENABLED(TFT_COLOR_UI, lcd_moveto(12, 2)); + lcd_put_u8str(LAST_Z_TO_STR(last_z)); + } + } + + void _lcd_draw_raise() { + if (!ui.should_draw()) return; + MenuItem_confirm::select_screen( + GET_TEXT(MSG_BUTTON_DONE), GET_TEXT(MSG_BUTTON_SKIP) + , []{ corner_probing_done = true; wait_for_probe = false; } + , []{ wait_for_probe = false; } + , GET_TEXT(MSG_BED_TRAMMING_RAISE) + , (const char*)nullptr, NUL_STR + ); + } + + void _lcd_draw_level_prompt() { + if (!ui.should_draw()) return; + MenuItem_confirm::confirm_screen( + []{ queue.inject_P(TERN(HAS_LEVELING, PSTR("G29N"), G28_STR)); ui.return_to_status(); } + , []{ ui.goto_previous_screen_no_defer(); } + , GET_TEXT(MSG_BED_TRAMMING_IN_RANGE) + , (const char*)nullptr, PSTR("?") + ); + } + + bool _lcd_level_bed_corners_probe(bool verify=false) { + if (verify) do_blocking_move_to_z(current_position.z + LEVEL_CORNERS_Z_HOP); // do clearance if needed + TERN_(BLTOUCH_SLOW_MODE, bltouch.deploy()); // Deploy in LOW SPEED MODE on every probe action + do_blocking_move_to_z(last_z - LEVEL_CORNERS_PROBE_TOLERANCE, MMM_TO_MMS(Z_PROBE_FEEDRATE_SLOW)); // Move down to lower tolerance + if (TEST(endstops.trigger_state(), Z_MIN_PROBE)) { // check if probe triggered + endstops.hit_on_purpose(); + set_current_from_steppers_for_axis(Z_AXIS); + sync_plan_position(); + TERN_(BLTOUCH_SLOW_MODE, bltouch.stow()); // Stow in LOW SPEED MODE on every trigger + // Triggered outside tolerance range? + if (ABS(current_position.z - last_z) > LEVEL_CORNERS_PROBE_TOLERANCE) { + last_z = current_position.z; // Above tolerance. Set a new Z for subsequent corners. + good_points = 0; // ...and start over + } + return true; // probe triggered + } + do_blocking_move_to_z(last_z); // go back to tolerance middle point before raise + return false; // probe not triggered + } + + bool _lcd_level_bed_corners_raise() { + bool probe_triggered = false; + corner_probing_done = false; + wait_for_probe = true; + ui.goto_screen(_lcd_draw_raise); // show raise screen + ui.set_selection(true); + while (wait_for_probe && !probe_triggered) { // loop while waiting to bed raise and probe trigger + probe_triggered = PROBE_TRIGGERED(); + if (probe_triggered) { + endstops.hit_on_purpose(); + TERN_(LEVEL_CORNERS_AUDIO_FEEDBACK, ui.buzz(200, 600)); + } + idle(); + } + TERN_(BLTOUCH_SLOW_MODE, bltouch.stow()); + ui.goto_screen(_lcd_draw_probing); + return (probe_triggered); + } + + void _lcd_test_corners() { + bed_corner = TERN(LEVEL_CENTER_TOO, center_index, 0); + last_z = LEVEL_CORNERS_HEIGHT; + endstops.enable_z_probe(true); + good_points = 0; + ui.goto_screen(_lcd_draw_probing); + do { + ui.refresh(LCDVIEW_REDRAW_NOW); + _lcd_draw_probing(); // update screen with # of good points + do_blocking_move_to_z(SUM_TERN(BLTOUCH_HS_MODE, current_position.z + LEVEL_CORNERS_Z_HOP, 7)); // clearance + + _lcd_level_bed_corners_get_next_position(); // Select next corner coordinates + current_position -= probe.offset_xy; // Account for probe offsets + do_blocking_move_to_xy(current_position); // Goto corner + + TERN_(BLTOUCH_HS_MODE, bltouch.deploy()); // Deploy in HIGH SPEED MODE + if (!_lcd_level_bed_corners_probe()) { // Probe down to tolerance + if (_lcd_level_bed_corners_raise()) { // Prompt user to raise bed if needed + #if ENABLED(LEVEL_CORNERS_VERIFY_RAISED) // Verify + 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 + break; // Skip was selected + } + } + #endif + } + else if (corner_probing_done) // Done was selected + return; + } + + if (bed_corner != center_index) good_points++; // ignore center + if (++bed_corner > 3) bed_corner = 0; + + } while (good_points < nr_edge_points); // loop until all points within tolerance + + #if ENABLED(BLTOUCH_HS_MODE) + // In HIGH SPEED MODE do clearance and stow at the very end + do_blocking_move_to_z(current_position.z + LEVEL_CORNERS_Z_HOP); + bltouch.stow(); #endif + + ui.goto_screen(_lcd_draw_level_prompt); // prompt for bed leveling + ui.set_selection(true); } - line_to_current_position(manual_feedrate_mm_s.x); - line_to_z(LEVEL_CORNERS_HEIGHT); - if (++bed_corner > 3 + ENABLED(LEVEL_CENTER_TOO)) bed_corner = 0; -} -static inline void _lcd_level_bed_corners_homing() { +#else // !LEVEL_CORNERS_USE_PROBE + + static void _lcd_goto_next_corner() { + line_to_z(LEVEL_CORNERS_Z_HOP); + + // Select next corner coordinates + _lcd_level_bed_corners_get_next_position(); + + line_to_current_position(manual_feedrate_mm_s.x); + line_to_z(LEVEL_CORNERS_HEIGHT); + if (++bed_corner >= available_points) bed_corner = 0; + } + +#endif // !LEVEL_CORNERS_USE_PROBE + +static void _lcd_level_bed_corners_homing() { _lcd_draw_homing(); - if (all_axes_homed()) { + if (!all_axes_homed()) return; + #if ENABLED(LEVEL_CORNERS_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)); + endstops.enable_z_probe(false); + #else bed_corner = 0; ui.goto_screen([]{ MenuItem_confirm::select_screen( GET_TEXT(MSG_BUTTON_NEXT), GET_TEXT(MSG_BUTTON_DONE) , _lcd_goto_next_corner , []{ + line_to_z(LEVEL_CORNERS_Z_HOP); // Raise Z off the bed when done TERN_(HAS_LEVELING, set_bed_leveling_enabled(leveling_was_active)); ui.goto_previous_screen_no_defer(); } @@ -91,12 +344,12 @@ static inline void _lcd_level_bed_corners_homing() { }); ui.set_selection(true); _lcd_goto_next_corner(); - } + #endif } void _lcd_level_bed_corners() { ui.defer_status_screen(); - if (!all_axes_known()) { + if (!all_axes_trusted()) { set_all_unhomed(); queue.inject_P(G28_STR); } diff --git a/Marlin/src/lcd/menu/menu_bed_leveling.cpp b/Marlin/src/lcd/menu/menu_bed_leveling.cpp index e19b04ccb517..f01c7899fbe3 100644 --- a/Marlin/src/lcd/menu/menu_bed_leveling.cpp +++ b/Marlin/src/lcd/menu/menu_bed_leveling.cpp @@ -37,8 +37,10 @@ #endif #if HAS_GRAPHICAL_TFT - #include "../tft/touch.h" #include "../tft/tft.h" + #if ENABLED(TOUCH_SCREEN) + #include "../tft/touch.h" + #endif #endif #if EITHER(PROBE_MANUALLY, MESH_BED_LEVELING) @@ -61,16 +63,16 @@ // and allow the command queue to be processed. // // When G29 finishes the last move: - // - Raise Z to the "manual probe height" + // - Raise Z to the "Z after probing" height // - Don't return until done. // // ** This blocks the command queue! ** // void _lcd_level_bed_done() { if (!ui.wait_for_move) { - #if MANUAL_PROBE_HEIGHT > 0 && DISABLED(MESH_BED_LEVELING) + #if Z_AFTER_PROBING > 0 && DISABLED(MESH_BED_LEVELING) // Display "Done" screen and wait for moves to complete - line_to_z(MANUAL_PROBE_HEIGHT); + line_to_z(Z_AFTER_PROBING); ui.synchronize(GET_TEXT(MSG_LEVEL_BED_DONE)); #endif ui.goto_previous_screen_no_defer(); @@ -101,9 +103,9 @@ ui.wait_for_move = true; ui.goto_screen(_lcd_level_bed_done); #if ENABLED(MESH_BED_LEVELING) - queue.inject_P(PSTR("G29 S2")); + queue.inject_P(PSTR("G29S2")); #elif ENABLED(PROBE_MANUALLY) - queue.inject_P(PSTR("G29 V1")); + queue.inject_P(PSTR("G29V1")); #endif } else @@ -153,9 +155,9 @@ // G29 Records Z, moves, and signals when it pauses ui.wait_for_move = true; #if ENABLED(MESH_BED_LEVELING) - queue.inject_P(manual_probe_index ? PSTR("G29 S2") : PSTR("G29 S1")); + queue.inject_P(manual_probe_index ? PSTR("G29S2") : PSTR("G29S1")); #elif ENABLED(PROBE_MANUALLY) - queue.inject_P(PSTR("G29 V1")); + queue.inject_P(PSTR("G29V1")); #endif } @@ -167,7 +169,9 @@ if (ui.should_draw()) { MenuItem_static::draw(1, GET_TEXT(MSG_LEVEL_BED_WAITING)); // Color UI needs a control to detect a touch - TERN_(HAS_GRAPHICAL_TFT, touch.add_control(CLICK, 0, 0, TFT_WIDTH, TFT_HEIGHT)); + #if BOTH(TOUCH_SCREEN, HAS_GRAPHICAL_TFT) + touch.add_control(CLICK, 0, 0, TFT_WIDTH, TFT_HEIGHT); + #endif } if (ui.use_click()) { manual_probe_index = 0; @@ -202,7 +206,7 @@ #if ENABLED(MESH_EDIT_MENU) inline void refresh_planner() { - set_current_from_steppers_for_axis(ALL_AXES); + set_current_from_steppers_for_axis(ALL_AXES_ENUM); sync_plan_position(); } @@ -210,8 +214,8 @@ static uint8_t xind, yind; // =0 START_MENU(); BACK_ITEM(MSG_BED_LEVELING); - EDIT_ITEM(uint8, MSG_MESH_X, &xind, 0, GRID_MAX_POINTS_X - 1); - EDIT_ITEM(uint8, MSG_MESH_Y, &yind, 0, GRID_MAX_POINTS_Y - 1); + EDIT_ITEM(uint8, MSG_MESH_X, &xind, 0, (GRID_MAX_POINTS_X) - 1); + EDIT_ITEM(uint8, MSG_MESH_Y, &yind, 0, (GRID_MAX_POINTS_Y) - 1); EDIT_ITEM_FAST(float43, MSG_MESH_EDIT_Z, &Z_VALUES(xind, yind), -(LCD_PROBE_Z_RANGE) * 0.5, (LCD_PROBE_Z_RANGE) * 0.5, refresh_planner); END_MENU(); } @@ -233,7 +237,7 @@ * Save Settings (Req: EEPROM_SETTINGS) */ void menu_bed_leveling() { - const bool is_homed = all_axes_known(), + const bool is_homed = all_axes_trusted(), is_valid = leveling_is_valid(); START_MENU(); @@ -250,7 +254,7 @@ void menu_bed_leveling() { SUBMENU(MSG_LEVEL_BED, _lcd_level_bed_continue); #else // Automatic leveling can just run the G-code - GCODES_ITEM(MSG_LEVEL_BED, is_homed ? PSTR("G29") : PSTR("G28\nG29")); + GCODES_ITEM(MSG_LEVEL_BED, is_homed ? PSTR("G29") : PSTR("G29N")); #endif #if ENABLED(MESH_EDIT_MENU) @@ -274,7 +278,12 @@ void menu_bed_leveling() { // Mesh Bed Leveling Z-Offset // #if ENABLED(MESH_BED_LEVELING) - EDIT_ITEM(float43, MSG_BED_Z, &mbl.z_offset, -1, 1); + #if WITHIN(Z_PROBE_OFFSET_RANGE_MIN, -9, 9) + #define LCD_Z_OFFSET_TYPE float43 // Values from -9.000 to +9.000 + #else + #define LCD_Z_OFFSET_TYPE float42_52 // Values from -99.99 to 99.99 + #endif + EDIT_ITEM(LCD_Z_OFFSET_TYPE, MSG_BED_Z, &mbl.z_offset, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX); #endif #if ENABLED(BABYSTEP_ZPROBE_OFFSET) @@ -284,7 +293,7 @@ void menu_bed_leveling() { #endif #if ENABLED(LEVEL_BED_CORNERS) - SUBMENU(MSG_LEVEL_CORNERS, _lcd_level_bed_corners); + SUBMENU(MSG_BED_TRAMMING, _lcd_level_bed_corners); #endif #if ENABLED(EEPROM_SETTINGS) diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp index 22947ee5149a..7ea355b795b8 100644 --- a/Marlin/src/lcd/menu/menu_configuration.cpp +++ b/Marlin/src/lcd/menu/menu_configuration.cpp @@ -45,6 +45,10 @@ #endif #endif +#if ENABLED(SOUND_MENU_ITEM) + #include "../../libs/buzzer.h" +#endif + #define HAS_DEBUG_MENU ENABLED(LCD_PROGRESS_BAR_TEST) void menu_advanced_settings(); @@ -126,6 +130,7 @@ void menu_advanced_settings(); #if ENABLED(TOOLCHANGE_MIGRATION_FEATURE) #include "../../module/motion.h" // for active_extruder + #include "../../gcode/queue.h" void menu_toolchange_migration() { PGM_P const msg_migrate = GET_TEXT(MSG_TOOL_MIGRATION_SWAP); @@ -160,7 +165,7 @@ void menu_advanced_settings(); void menu_tool_offsets() { auto _recalc_offsets = []{ - if (active_extruder && all_axes_known()) { // For the 2nd extruder re-home so the next tool-change gets the new offsets. + if (active_extruder && all_axes_trusted()) { // For the 2nd extruder re-home so the next tool-change gets the new offsets. queue.inject_P(G28_STR); // In future, we can babystep the 2nd extruder (if active), making homing unnecessary. active_extruder = 0; } @@ -190,16 +195,19 @@ void menu_advanced_settings(); START_MENU(); BACK_ITEM(MSG_CONFIGURATION); - GCODES_ITEM(MSG_IDEX_MODE_AUTOPARK, PSTR("M605 S1\nG28 X\nG1 X100")); + GCODES_ITEM(MSG_IDEX_MODE_AUTOPARK, PSTR("M605S1\nG28X\nG1X0")); GCODES_ITEM(MSG_IDEX_MODE_DUPLICATE, need_g28 - ? PSTR("M605 S1\nT0\nG28\nM605 S2 X200\nG28 X\nG1 X100") // If Y or Z is not homed, do a full G28 first - : PSTR("M605 S1\nT0\nM605 S2 X200\nG28 X\nG1 X100") + ? PSTR("M605S1\nT0\nG28\nM605S2\nG28X\nG1X0") // If Y or Z is not homed, do a full G28 first + : PSTR("M605S1\nT0\nM605S2\nG28X\nG1X0") ); GCODES_ITEM(MSG_IDEX_MODE_MIRRORED_COPY, need_g28 - ? PSTR("M605 S1\nT0\nG28\nM605 S2 X200\nG28 X\nG1 X100\nM605 S3 X200") // If Y or Z is not homed, do a full G28 first - : PSTR("M605 S1\nT0\nM605 S2 X200\nG28 X\nG1 X100\nM605 S3 X200") + ? PSTR("M605S1\nT0\nG28\nM605S2\nG28X\nG1X0\nM605S3") // If Y or Z is not homed, do a full G28 first + : PSTR("M605S1\nT0\nM605S2\nG28 X\nG1X0\nM605S3") ); - GCODES_ITEM(MSG_IDEX_MODE_FULL_CTRL, PSTR("M605 S0\nG28 X")); + GCODES_ITEM(MSG_IDEX_MODE_FULL_CTRL, PSTR("M605S0\nG28X")); + + EDIT_ITEM(float42_52, MSG_IDEX_DUPE_GAP, &duplicate_extruder_x_offset, (X2_MIN_POS) - (X1_MIN_POS), (X_BED_SIZE) - 20); + END_MENU(); } @@ -209,7 +217,7 @@ void menu_advanced_settings(); #if ENABLED(BLTOUCH_LCD_VOLTAGE_MENU) void bltouch_report() { - SERIAL_ECHOLNPAIR("EEPROM Last BLTouch Mode - ", (int)bltouch.last_written_mode); + SERIAL_ECHOLNPAIR("EEPROM Last BLTouch Mode - ", bltouch.last_written_mode); SERIAL_ECHOLNPGM("Configuration BLTouch Mode - " TERN(BLTOUCH_SET_5V_MODE, "5V", "OD")); char mess[21]; strcpy_P(mess, PSTR("BLTouch Mode - ")); @@ -318,10 +326,10 @@ void menu_advanced_settings(); EDIT_ITEM_N(percent, m, MSG_FAN_SPEED, &editable.uint8, 0, 255, []{ ui.material_preset[MenuItemBase::itemIndex].fan_speed = editable.uint8; }); #endif #if HAS_TEMP_HOTEND - EDIT_ITEM(uint16_3, MSG_NOZZLE, &ui.material_preset[m].hotend_temp, MINTEMP_ALL, MAXTEMP_ALL - HOTEND_OVERSHOOT); + EDIT_ITEM(int3, MSG_NOZZLE, &ui.material_preset[m].hotend_temp, MINTEMP_ALL, MAXTEMP_ALL - (HOTEND_OVERSHOOT)); #endif #if HAS_HEATED_BED - EDIT_ITEM(uint16_3, MSG_BED, &ui.material_preset[m].bed_temp, BED_MINTEMP, BED_MAX_TARGET); + EDIT_ITEM(int3, MSG_BED, &ui.material_preset[m].bed_temp, BED_MINTEMP, BED_MAX_TARGET); #endif #if ENABLED(EEPROM_SETTINGS) ACTION_ITEM(MSG_STORE_EEPROM, ui.store_settings); @@ -331,6 +339,148 @@ void menu_advanced_settings(); #endif +#if ENABLED(CUSTOM_MENU_CONFIG) + + void _lcd_custom_menus_configuration_gcode(PGM_P const cmd) { + queue.inject_P(cmd); + TERN_(CUSTOM_MENU_CONFIG_SCRIPT_AUDIBLE_FEEDBACK, ui.completion_feedback()); + TERN_(CUSTOM_MENU_CONFIG_SCRIPT_RETURN, ui.return_to_status()); + } + + void custom_menus_configuration() { + START_MENU(); + BACK_ITEM(MSG_MAIN); + + #define HAS_CUSTOM_ITEM_CONF(N) (defined(CONFIG_MENU_ITEM_##N##_DESC) && defined(CONFIG_MENU_ITEM_##N##_GCODE)) + + #define CUSTOM_TEST_CONF(N) do{ \ + constexpr char c = CONFIG_MENU_ITEM_##N##_GCODE[strlen(CONFIG_MENU_ITEM_##N##_GCODE) - 1]; \ + static_assert(c != '\n' && c != '\r', "CONFIG_MENU_ITEM_" STRINGIFY(N) "_GCODE cannot have a newline at the end. Please remove it."); \ + }while(0) + + #ifdef CUSTOM_MENU_CONFIG_SCRIPT_DONE + #define _DONE_SCRIPT "\n" CUSTOM_MENU_CONFIG_SCRIPT_DONE + #else + #define _DONE_SCRIPT "" + #endif + #define GCODE_LAMBDA_CONF(N) []{ _lcd_custom_menus_configuration_gcode(PSTR(CONFIG_MENU_ITEM_##N##_GCODE _DONE_SCRIPT)); } + #define _CUSTOM_ITEM_CONF(N) ACTION_ITEM_P(PSTR(CONFIG_MENU_ITEM_##N##_DESC), GCODE_LAMBDA_CONF(N)); + #define _CUSTOM_ITEM_CONF_CONFIRM(N) \ + SUBMENU_P(PSTR(CONFIG_MENU_ITEM_##N##_DESC), []{ \ + MenuItem_confirm::confirm_screen( \ + GCODE_LAMBDA_CONF(N), \ + ui.goto_previous_screen, \ + PSTR(CONFIG_MENU_ITEM_##N##_DESC "?") \ + ); \ + }) + + #define CUSTOM_ITEM_CONF(N) do{ if (ENABLED(CONFIG_MENU_ITEM_##N##_CONFIRM)) _CUSTOM_ITEM_CONF_CONFIRM(N); else _CUSTOM_ITEM_CONF(N); }while(0) + + #if HAS_CUSTOM_ITEM_CONF(1) + CUSTOM_TEST_CONF(1); + CUSTOM_ITEM_CONF(1); + #endif + #if HAS_CUSTOM_ITEM_CONF(2) + CUSTOM_TEST_CONF(2); + CUSTOM_ITEM_CONF(2); + #endif + #if HAS_CUSTOM_ITEM_CONF(3) + CUSTOM_TEST_CONF(3); + CUSTOM_ITEM_CONF(3); + #endif + #if HAS_CUSTOM_ITEM_CONF(4) + CUSTOM_TEST_CONF(4); + CUSTOM_ITEM_CONF(4); + #endif + #if HAS_CUSTOM_ITEM_CONF(5) + CUSTOM_TEST_CONF(5); + CUSTOM_ITEM_CONF(5); + #endif + #if HAS_CUSTOM_ITEM_CONF(6) + CUSTOM_TEST_CONF(6); + CUSTOM_ITEM_CONF(6); + #endif + #if HAS_CUSTOM_ITEM_CONF(7) + CUSTOM_TEST_CONF(7); + CUSTOM_ITEM_CONF(7); + #endif + #if HAS_CUSTOM_ITEM_CONF(8) + CUSTOM_TEST_CONF(8); + CUSTOM_ITEM_CONF(8); + #endif + #if HAS_CUSTOM_ITEM_CONF(9) + CUSTOM_TEST_CONF(9); + CUSTOM_ITEM_CONF(9); + #endif + #if HAS_CUSTOM_ITEM_CONF(10) + CUSTOM_TEST_CONF(10); + CUSTOM_ITEM_CONF(10); + #endif + #if HAS_CUSTOM_ITEM_CONF(11) + CUSTOM_TEST_CONF(11); + CUSTOM_ITEM_CONF(11); + #endif + #if HAS_CUSTOM_ITEM_CONF(12) + CUSTOM_TEST_CONF(12); + CUSTOM_ITEM_CONF(12); + #endif + #if HAS_CUSTOM_ITEM_CONF(13) + CUSTOM_TEST_CONF(13); + CUSTOM_ITEM_CONF(13); + #endif + #if HAS_CUSTOM_ITEM_CONF(14) + CUSTOM_TEST_CONF(14); + CUSTOM_ITEM_CONF(14); + #endif + #if HAS_CUSTOM_ITEM_CONF(15) + CUSTOM_TEST_CONF(15); + CUSTOM_ITEM_CONF(15); + #endif + #if HAS_CUSTOM_ITEM_CONF(16) + CUSTOM_TEST_CONF(16); + CUSTOM_ITEM_CONF(16); + #endif + #if HAS_CUSTOM_ITEM_CONF(17) + CUSTOM_TEST_CONF(17); + CUSTOM_ITEM_CONF(17); + #endif + #if HAS_CUSTOM_ITEM_CONF(18) + CUSTOM_TEST_CONF(18); + CUSTOM_ITEM_CONF(18); + #endif + #if HAS_CUSTOM_ITEM_CONF(19) + CUSTOM_TEST_CONF(19); + CUSTOM_ITEM_CONF(19); + #endif + #if HAS_CUSTOM_ITEM_CONF(20) + CUSTOM_TEST_CONF(20); + CUSTOM_ITEM_CONF(20); + #endif + #if HAS_CUSTOM_ITEM_CONF(21) + CUSTOM_TEST_CONF(21); + CUSTOM_ITEM_CONF(21); + #endif + #if HAS_CUSTOM_ITEM_CONF(22) + CUSTOM_TEST_CONF(22); + CUSTOM_ITEM_CONF(22); + #endif + #if HAS_CUSTOM_ITEM_CONF(23) + CUSTOM_TEST_CONF(23); + CUSTOM_ITEM_CONF(23); + #endif + #if HAS_CUSTOM_ITEM_CONF(24) + CUSTOM_TEST_CONF(24); + CUSTOM_ITEM_CONF(24); + #endif + #if HAS_CUSTOM_ITEM_CONF(25) + CUSTOM_TEST_CONF(25); + CUSTOM_ITEM_CONF(25); + #endif + END_MENU(); + } + +#endif // CUSTOM_MENU_CONFIG + void menu_configuration() { const bool busy = printer_busy(); @@ -344,6 +494,16 @@ void menu_configuration() { SUBMENU(MSG_DEBUG_MENU, menu_debug); #endif + #if ENABLED(CUSTOM_MENU_CONFIG) + if (TERN1(CUSTOM_MENU_CONFIG_ONLY_IDLE, !busy)) { + #ifdef CUSTOM_MENU_CONFIG_TITLE + SUBMENU_P(PSTR(CUSTOM_MENU_CONFIG_TITLE), custom_menus_configuration); + #else + SUBMENU(MSG_CUSTOM_COMMANDS, custom_menus_configuration); + #endif + } + #endif + SUBMENU(MSG_ADVANCED_SETTINGS, menu_advanced_settings); #if ENABLED(BABYSTEP_ZPROBE_OFFSET) @@ -412,6 +572,10 @@ void menu_configuration() { SUBMENU_N_S(m, ui.get_preheat_label(m), MSG_PREHEAT_M_SETTINGS, _menu_configuration_preheat_settings); #endif + #if ENABLED(SOUND_MENU_ITEM) + EDIT_ITEM(bool, MSG_SOUND, &ui.buzzer_enabled, []{ ui.chirp(); }); + #endif + #if ENABLED(EEPROM_SETTINGS) ACTION_ITEM(MSG_STORE_EEPROM, ui.store_settings); if (!busy) ACTION_ITEM(MSG_LOAD_EEPROM, ui.load_settings); diff --git a/Marlin/src/lcd/menu/menu_custom.cpp b/Marlin/src/lcd/menu/menu_custom.cpp deleted file mode 100644 index 7c54ec6e2616..000000000000 --- a/Marlin/src/lcd/menu/menu_custom.cpp +++ /dev/null @@ -1,129 +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 . - * - */ - -// -// Custom User Menu -// - -#include "../../inc/MarlinConfigPre.h" - -#if BOTH(HAS_LCD_MENU, CUSTOM_USER_MENUS) - -#include "menu_item.h" -#include "../../gcode/queue.h" - -#ifdef USER_SCRIPT_DONE - #define _DONE_SCRIPT "\n" USER_SCRIPT_DONE -#else - #define _DONE_SCRIPT "" -#endif - -void _lcd_user_gcode(PGM_P const cmd) { - queue.inject_P(cmd); - TERN_(USER_SCRIPT_AUDIBLE_FEEDBACK, ui.completion_feedback()); - TERN_(USER_SCRIPT_RETURN, ui.return_to_status()); -} - -void menu_user() { - START_MENU(); - BACK_ITEM(MSG_MAIN); - #define HAS_USER_ITEM(N) (defined(USER_DESC_##N) && defined(USER_GCODE_##N)) - #define USER_ITEM(N) ACTION_ITEM_P(PSTR(USER_DESC_##N), []{ _lcd_user_gcode(PSTR(USER_GCODE_##N _DONE_SCRIPT)); }); - #if HAS_USER_ITEM(1) - USER_ITEM(1); - #endif - #if HAS_USER_ITEM(2) - USER_ITEM(2); - #endif - #if HAS_USER_ITEM(3) - USER_ITEM(3); - #endif - #if HAS_USER_ITEM(4) - USER_ITEM(4); - #endif - #if HAS_USER_ITEM(5) - USER_ITEM(5); - #endif - #if HAS_USER_ITEM(6) - USER_ITEM(6); - #endif - #if HAS_USER_ITEM(7) - USER_ITEM(7); - #endif - #if HAS_USER_ITEM(8) - USER_ITEM(8); - #endif - #if HAS_USER_ITEM(9) - USER_ITEM(9); - #endif - #if HAS_USER_ITEM(10) - USER_ITEM(10); - #endif - #if HAS_USER_ITEM(11) - USER_ITEM(11); - #endif - #if HAS_USER_ITEM(12) - USER_ITEM(12); - #endif - #if HAS_USER_ITEM(13) - USER_ITEM(13); - #endif - #if HAS_USER_ITEM(14) - USER_ITEM(14); - #endif - #if HAS_USER_ITEM(15) - USER_ITEM(15); - #endif - #if HAS_USER_ITEM(16) - USER_ITEM(16); - #endif - #if HAS_USER_ITEM(17) - USER_ITEM(17); - #endif - #if HAS_USER_ITEM(18) - USER_ITEM(18); - #endif - #if HAS_USER_ITEM(19) - USER_ITEM(19); - #endif - #if HAS_USER_ITEM(20) - USER_ITEM(20); - #endif - #if HAS_USER_ITEM(21) - USER_ITEM(21); - #endif - #if HAS_USER_ITEM(22) - USER_ITEM(22); - #endif - #if HAS_USER_ITEM(23) - USER_ITEM(23); - #endif - #if HAS_USER_ITEM(24) - USER_ITEM(24); - #endif - #if HAS_USER_ITEM(25) - USER_ITEM(25); - #endif - END_MENU(); -} - -#endif // HAS_LCD_MENU && CUSTOM_USER_MENUS diff --git a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp index 4efcb7c8eded..810f376f827b 100644 --- a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp +++ b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp @@ -31,13 +31,14 @@ #include "menu_item.h" #include "../../module/delta.h" #include "../../module/motion.h" +#include "../../module/planner.h" #if HAS_LEVELING #include "../../feature/bedlevel/bedlevel.h" #endif #if ENABLED(EXTENSIBLE_UI) - #include "../../lcd/extui/ui_api.h" + #include "../extui/ui_api.h" #endif void _man_probe_pt(const xy_pos_t &xy) { @@ -46,13 +47,14 @@ void _man_probe_pt(const xy_pos_t &xy) { do_blocking_move_to_xy_z(xy, Z_CLEARANCE_BETWEEN_PROBES); ui.wait_for_move = false; ui.synchronize(); - ui.manual_move.menu_scale = _MAX(PROBE_MANUALLY_STEP, MIN_STEPS_PER_SEGMENT / float(DEFAULT_XYZ_STEPS_PER_UNIT)); + ui.manual_move.menu_scale = _MAX(PROBE_MANUALLY_STEP, MIN_STEPS_PER_SEGMENT / planner.settings.axis_steps_per_mm[0]); // Use first axis as for delta XYZ should always match ui.goto_screen(lcd_move_z); } } #if ENABLED(DELTA_AUTO_CALIBRATION) + #include "../../MarlinCore.h" // for wait_for_user_response() #include "../../gcode/gcode.h" #if ENABLED(HOST_PROMPT_SUPPORT) @@ -85,7 +87,7 @@ void _man_probe_pt(const xy_pos_t &xy) { ui.goto_screen(_lcd_calibrate_homing); } - void _goto_tower_a(const float &a) { + void _goto_tower_a(const_float_t a) { xy_pos_t tower_vec = { cos(RADIANS(a)), sin(RADIANS(a)) }; _man_probe_pt(tower_vec * delta_calibration_radius()); } @@ -104,7 +106,7 @@ void lcd_delta_settings() { START_MENU(); BACK_ITEM(MSG_DELTA_CALIBRATE); EDIT_ITEM(float52sign, MSG_DELTA_HEIGHT, &delta_height, delta_height - 10, delta_height + 10, _recalc_delta_settings); - #define EDIT_ENDSTOP_ADJ(LABEL,N) EDIT_ITEM_P(float43, PSTR(LABEL), &delta_endstop_adj.N, -5, 5, _recalc_delta_settings) + #define EDIT_ENDSTOP_ADJ(LABEL,N) EDIT_ITEM_P(float43, PSTR(LABEL), &delta_endstop_adj.N, -5, 0, _recalc_delta_settings) EDIT_ENDSTOP_ADJ("Ex", a); EDIT_ENDSTOP_ADJ("Ey", b); EDIT_ENDSTOP_ADJ("Ez", c); @@ -118,7 +120,9 @@ void lcd_delta_settings() { } void menu_delta_calibrate() { - TERN_(DELTA_CALIBRATION_MENU, const bool all_homed = all_axes_homed()); // Acquire ahead of loop + #if ENABLED(DELTA_CALIBRATION_MENU) + const bool all_homed = all_axes_homed(); // Acquire ahead of loop + #endif START_MENU(); BACK_ITEM(MSG_MAIN); diff --git a/Marlin/src/lcd/menu/menu_filament.cpp b/Marlin/src/lcd/menu/menu_filament.cpp index d116a6a398c0..53fd67dbb258 100644 --- a/Marlin/src/lcd/menu/menu_filament.cpp +++ b/Marlin/src/lcd/menu/menu_filament.cpp @@ -67,7 +67,7 @@ static void _change_filament_with_preset() { } static void _change_filament_with_custom() { - _change_filament_with_temp(thermalManager.temp_hotend[MenuItemBase::itemIndex].target); + _change_filament_with_temp(thermalManager.degTargetHotend(MenuItemBase::itemIndex)); } // @@ -86,6 +86,7 @@ inline PGM_P change_filament_header(const PauseMode mode) { void _menu_temp_filament_op(const PauseMode mode, const int8_t extruder) { _change_filament_mode = mode; _change_filament_extruder = extruder; + const int8_t old_index = MenuItemBase::itemIndex; START_MENU(); if (LCD_HEIGHT >= 4) STATIC_ITEM_P(change_filament_header(mode), SS_DEFAULT|SS_INVERT); BACK_ITEM(MSG_BACK); @@ -94,18 +95,22 @@ void _menu_temp_filament_op(const PauseMode mode, const int8_t extruder) { ACTION_ITEM_N_S(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, - EXTRUDE_MINTEMP, thermalManager.heater_maxtemp[extruder] - HOTEND_OVERSHOOT, + EXTRUDE_MINTEMP, thermalManager.hotend_max_target(extruder), _change_filament_with_custom ); END_MENU(); + MenuItemBase::itemIndex = old_index; } /** * "Change Filament" submenu */ #if E_STEPPERS > 1 || ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) + bool printingIsPaused(); +#endif - void menu_change_filament() { +void menu_change_filament() { + #if E_STEPPERS > 1 || ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) // Say "filament change" when no print is active editable.int8 = printingIsPaused() ? PAUSE_MODE_PAUSE_PRINT : PAUSE_MODE_CHANGE_FILAMENT; @@ -200,8 +205,16 @@ void _menu_temp_filament_op(const PauseMode mode, const int8_t extruder) { #endif END_MENU(); - } -#endif + + #else + + if (thermalManager.targetHotEnoughToExtrude(active_extruder)) + queue.inject_P(PSTR("M600B0")); + else + ui.goto_screen([]{ _menu_temp_filament_op(PAUSE_MODE_CHANGE_FILAMENT, 0); }); + + #endif +} static uint8_t hotend_status_extruder = 0; @@ -219,7 +232,7 @@ static PGM_P pause_header() { #define HOTEND_STATUS_ITEM() do { \ if (_menuLineNr == _thisItemNr) { \ if (ui.should_draw()) { \ - TERN(HAS_GRAPHICAL_TFT,, MenuItem_static::draw(_lcdLineNr, GET_TEXT(MSG_FILAMENT_CHANGE_NOZZLE), SS_INVERT)); \ + IF_DISABLED(HAS_GRAPHICAL_TFT, MenuItem_static::draw(_lcdLineNr, GET_TEXT(MSG_FILAMENT_CHANGE_NOZZLE), SS_INVERT)); \ ui.draw_hotend_status(_lcdLineNr, hotend_status_extruder); \ } \ if (_skipStatic && encoderLine <= _thisItemNr) { \ @@ -313,7 +326,7 @@ FORCE_INLINE screenFunc_t ap_message_screen(const PauseMessage message) { return nullptr; } -void lcd_pause_show_message( +void MarlinUI::pause_show_message( const PauseMessage message, const PauseMode mode/*=PAUSE_MODE_SAME*/, const uint8_t extruder/*=active_extruder*/ diff --git a/Marlin/src/lcd/menu/menu_info.cpp b/Marlin/src/lcd/menu/menu_info.cpp index a4cbc31d8b6b..cecccd115d4d 100644 --- a/Marlin/src/lcd/menu/menu_info.cpp +++ b/Marlin/src/lcd/menu/menu_info.cpp @@ -100,7 +100,7 @@ void menu_info_thermistors() { START_SCREEN(); - #if EXTRUDERS + #if HAS_EXTRUDERS #define THERMISTOR_ID TEMP_SENSOR_0 #include "../thermistornames.h" STATIC_ITEM_P(PSTR(LCD_STR_E0 ": " THERMISTOR_NAME), SS_INVERT); @@ -171,7 +171,7 @@ void menu_info_thermistors() { PSTRING_ITEM(MSG_INFO_MAX_TEMP, STRINGIFY(HEATER_7_MAXTEMP), SS_LEFT); #endif - #if EXTRUDERS + #if HAS_EXTRUDERS STATIC_ITEM(TERN(WATCH_HOTENDS, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); #endif @@ -195,6 +195,16 @@ void menu_info_thermistors() { STATIC_ITEM(TERN(WATCH_CHAMBER, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); #endif + #if HAS_COOLER + #undef THERMISTOR_ID + #define THERMISTOR_ID TEMP_SENSOR_COOLER + #include "../thermistornames.h" + STATIC_ITEM_P(PSTR("COOL: " THERMISTOR_NAME), SS_INVERT); + PSTRING_ITEM(MSG_INFO_MIN_TEMP, STRINGIFY(COOLER_MINTEMP), SS_LEFT); + PSTRING_ITEM(MSG_INFO_MAX_TEMP, STRINGIFY(COOLER_MAXTEMP), SS_LEFT); + STATIC_ITEM(TERN(WATCH_COOLER, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); + #endif + END_SCREEN(); } @@ -268,7 +278,7 @@ void menu_info() { #else SUBMENU(MSG_INFO_PRINTER_MENU, menu_info_printer); // Printer Info > SUBMENU(MSG_INFO_BOARD_MENU, menu_info_board); // Board Info > - #if EXTRUDERS + #if HAS_EXTRUDERS SUBMENU(MSG_INFO_THERMISTOR_MENU, menu_info_thermistors); // Thermistors > #endif #endif diff --git a/Marlin/src/lcd/menu/menu_item.h b/Marlin/src/lcd/menu/menu_item.h index bd3af0cec6b3..0a4f4bb7d191 100644 --- a/Marlin/src/lcd/menu/menu_item.h +++ b/Marlin/src/lcd/menu/menu_item.h @@ -22,7 +22,7 @@ #pragma once #include "menu.h" -#include "../ultralcd.h" +#include "../marlinui.h" #include "../../gcode/queue.h" // for inject_P #include "../../inc/MarlinConfigPre.h" @@ -39,7 +39,7 @@ class MenuItem_submenu : public MenuItemBase { FORCE_INLINE static void draw(const bool sel, const uint8_t row, PGM_P const pstr, ...) { _draw(sel, row, pstr, '>', LCD_STR_ARROW_RIGHT[0]); } - static inline void action(PGM_P const, const screenFunc_t func) { ui.save_previous_screen(); ui.goto_screen(func); } + static inline void action(PGM_P const, const screenFunc_t func) { ui.push_current_screen(); ui.goto_screen(func); } }; // Any menu item that invokes an immediate action @@ -77,8 +77,8 @@ template class TMenuEditItem : MenuEditItemBase { private: typedef typename NAME::type_t type_t; - static inline float scale(const float value) { return NAME::scale(value); } - static inline float unscale(const float value) { return NAME::unscale(value); } + static inline float scale(const_float_t value) { return NAME::scale(value); } + static inline float unscale(const_float_t value) { return NAME::unscale(value); } static const char* to_string(const int32_t value) { return NAME::strfunc(unscale(value)); } static void load(void *ptr, const int32_t value) { *((type_t*)ptr) = unscale(value); } public: @@ -111,17 +111,18 @@ class TMenuEditItem : MenuEditItemBase { // These items call the Edit Item draw method passing the prepared string. #define __DOFIXfloat PROBE() #define _DOFIX(TYPE,V) TYPE(TERN(IS_PROBE(__DOFIX##TYPE),FIXFLOAT(V),(V))) -#define DEFINE_MENU_EDIT_ITEM_TYPE(NAME, TYPE, STRFUNC, SCALE, V...) \ +#define DEFINE_MENU_EDIT_ITEM_TYPE(NAME, TYPE, STRFUNC, SCALE, ETC...) \ struct MenuEditItemInfo_##NAME { \ typedef TYPE type_t; \ - static inline float scale(const float value) { return value * (SCALE) + (V+0); } \ - static inline float unscale(const float value) { return value / (SCALE) + (V+0); } \ - static inline const char* strfunc(const float value) { return STRFUNC(_DOFIX(TYPE,value)); } \ + static inline float scale(const_float_t value) { return value * (SCALE) ETC; } \ + static inline float unscale(const_float_t value) { return value / (SCALE) ETC; } \ + static inline const char* strfunc(const_float_t value) { return STRFUNC(_DOFIX(TYPE,value)); } \ }; \ typedef TMenuEditItem MenuItem_##NAME -// NAME TYPE STRFUNC SCALE +ROUND -DEFINE_MENU_EDIT_ITEM_TYPE(percent ,uint8_t ,ui8tostr4pctrj , 100.f/255.f, 0.5f); // 100% right-justified +// NAME TYPE STRFUNC SCALE ROUND +DEFINE_MENU_EDIT_ITEM_TYPE(percent ,uint8_t ,ui8tostr4pctrj , 100.f/255.f, +0.5f); // 100% right-justified +DEFINE_MENU_EDIT_ITEM_TYPE(percent_3 ,uint8_t ,pcttostrpctrj , 1 ); // 100% right-justified DEFINE_MENU_EDIT_ITEM_TYPE(int3 ,int16_t ,i16tostr3rj , 1 ); // 123, -12 right-justified DEFINE_MENU_EDIT_ITEM_TYPE(int4 ,int16_t ,i16tostr4signrj , 1 ); // 1234, -123 right-justified DEFINE_MENU_EDIT_ITEM_TYPE(int8 ,int8_t ,i8tostr3rj , 1 ); // 123, -12 right-justified @@ -132,6 +133,7 @@ DEFINE_MENU_EDIT_ITEM_TYPE(uint16_5 ,uint16_t ,ui16tostr5rj , 0.01f ); DEFINE_MENU_EDIT_ITEM_TYPE(float3 ,float ,ftostr3 , 1 ); // 123 right-justified DEFINE_MENU_EDIT_ITEM_TYPE(float42_52 ,float ,ftostr42_52 , 100 ); // _2.34, 12.34, -2.34 or 123.45, -23.45 DEFINE_MENU_EDIT_ITEM_TYPE(float43 ,float ,ftostr43sign ,1000 ); // -1.234, _1.234, +1.234 +DEFINE_MENU_EDIT_ITEM_TYPE(float4 ,float ,ftostr4sign , 1 ); // 1234 right-justified DEFINE_MENU_EDIT_ITEM_TYPE(float5 ,float ,ftostr5rj , 1 ); // 12345 right-justified DEFINE_MENU_EDIT_ITEM_TYPE(float5_25 ,float ,ftostr5rj , 0.04f ); // 12345 right-justified (25 increment) DEFINE_MENU_EDIT_ITEM_TYPE(float51 ,float ,ftostr51rj , 10 ); // 1234.5 right-justified @@ -354,6 +356,7 @@ class MenuItem_bool : public MenuEditItemBase { #define MENU_ITEM_P(TYPE, PLABEL, V...) _MENU_ITEM_P(TYPE, false, PLABEL, ##V) #define MENU_ITEM(TYPE, LABEL, V...) MENU_ITEM_P(TYPE, GET_TEXT(LABEL), ##V) +#define BACK_ITEM_P(PLABEL) MENU_ITEM_P(back, PLABEL) #define BACK_ITEM(LABEL) MENU_ITEM(back, LABEL) #define ACTION_ITEM_N_S_P(N, S, PLABEL, ACTION) MENU_ITEM_N_S_P(function, N, S, PLABEL, ACTION) @@ -403,7 +406,7 @@ class MenuItem_bool : public MenuEditItemBase { #define _CONFIRM_ITEM_INNER_P(PLABEL, V...) do { \ if (encoderLine == _thisItemNr && ui.use_click()) { \ - ui.save_previous_screen(); \ + ui.push_current_screen(); \ ui.goto_screen([]{MenuItem_confirm::select_screen(V);}); \ return; \ } \ @@ -431,23 +434,23 @@ class MenuItem_bool : public MenuEditItemBase { }while(0) // Indexed items set a global index value -#define _CONFIRM_ITEM_N_P(N, V...) _CONFIRM_ITEM_N_S_P(N, nullptr, V) +#define _CONFIRM_ITEM_N_P(N, V...) _CONFIRM_ITEM_N_S_P(N, nullptr, V) -#define CONFIRM_ITEM_P(PLABEL,A,B,V...) _CONFIRM_ITEM_P(PLABEL, GET_TEXT(A), GET_TEXT(B), ##V) -#define CONFIRM_ITEM(LABEL, V...) CONFIRM_ITEM_P(GET_TEXT(LABEL), ##V) +#define CONFIRM_ITEM_P(PLABEL,A,B,V...) _CONFIRM_ITEM_P(PLABEL, GET_TEXT(A), GET_TEXT(B), ##V) +#define CONFIRM_ITEM(LABEL, V...) CONFIRM_ITEM_P(GET_TEXT(LABEL), ##V) -#define YESNO_ITEM_P(PLABEL, V...) _CONFIRM_ITEM_P(PLABEL, ##V) -#define YESNO_ITEM(LABEL, V...) YESNO_ITEM_P(GET_TEXT(LABEL), ##V) +#define YESNO_ITEM_P(PLABEL, V...) CONFIRM_ITEM_P(PLABEL, MSG_YES, MSG_NO, ##V) +#define YESNO_ITEM(LABEL, V...) YESNO_ITEM_P(GET_TEXT(LABEL), ##V) #define CONFIRM_ITEM_N_S_P(N,S,PLABEL,A,B,V...) _CONFIRM_ITEM_N_S_P(N, S, PLABEL, GET_TEXT(A), GET_TEXT(B), ##V) #define CONFIRM_ITEM_N_S(N,S,LABEL,V...) CONFIRM_ITEM_N_S_P(N, S, GET_TEXT(LABEL), ##V) #define CONFIRM_ITEM_N_P(N,PLABEL,A,B,V...) _CONFIRM_ITEM_N_P(N, PLABEL, GET_TEXT(A), GET_TEXT(B), ##V) #define CONFIRM_ITEM_N(N,LABEL, V...) CONFIRM_ITEM_N_P(N, GET_TEXT(LABEL), ##V) -#define YESNO_ITEM_N_S_P(N,S,PLABEL, V...) _CONFIRM_ITEM_N_S_P(N, S, PLABEL, ##V) -#define YESNO_ITEM_N_S(N,S,LABEL, V...) YESNO_ITEM_N_S_P(N, S, GET_TEXT(LABEL), ##V) -#define YESNO_ITEM_N_P(N,PLABEL, V...) _CONFIRM_ITEM_N_P(N, PLABEL, ##V) -#define YESNO_ITEM_N(N,LABEL, V...) YESNO_ITEM_N_P(N, GET_TEXT(LABEL), ##V) +#define YESNO_ITEM_N_S_P(N,S,PLABEL, V...) _CONFIRM_ITEM_N_S_P(N, S, PLABEL, MSG_YES, MSG_NO, ##V) +#define YESNO_ITEM_N_S(N,S,LABEL, V...) YESNO_ITEM_N_S_P(N, S, GET_TEXT(LABEL), ##V) +#define YESNO_ITEM_N_P(N,PLABEL, V...) CONFIRM_ITEM_N_P(N, PLABEL, MSG_YES, MSG_NO, ##V) +#define YESNO_ITEM_N(N,LABEL, V...) YESNO_ITEM_N_P(N, GET_TEXT(LABEL), ##V) #if ENABLED(LEVEL_BED_CORNERS) void _lcd_level_bed_corners(); @@ -470,7 +473,7 @@ class MenuItem_bool : public MenuEditItemBase { #define _FAN_EDIT_ITEMS(F,L) do{ \ editable.uint8 = thermalManager.fan_speed[F]; \ EDIT_ITEM_FAST_N(percent, F, MSG_##L, &editable.uint8, 0, 255, on_fan_update); \ - EDIT_EXTRA_FAN_SPEED(percent, F, MSG_EXTRA_##L, &thermalManager.new_fan_speed[F], 3, 255); \ + EDIT_EXTRA_FAN_SPEED(percent, F, MSG_EXTRA_##L, &thermalManager.extra_fan_speed[F].speed, 3, 255); \ }while(0) #if FAN_COUNT > 1 @@ -482,7 +485,7 @@ class MenuItem_bool : public MenuEditItemBase { #if SNFAN(1) || SNFAN(2) || SNFAN(3) || SNFAN(4) || SNFAN(5) || SNFAN(6) || SNFAN(7) #define DEFINE_SINGLENOZZLE_ITEM() \ auto singlenozzle_item = [&](const uint8_t f) { \ - editable.uint8 = singlenozzle_fan_speed[f]; \ + editable.uint8 = thermalManager.singlenozzle_fan_speed[f]; \ EDIT_ITEM_FAST_N(percent, f, MSG_STORED_FAN_N, &editable.uint8, 0, 255, on_fan_update); \ } #else diff --git a/Marlin/src/lcd/menu/menu_language.cpp b/Marlin/src/lcd/menu/menu_language.cpp new file mode 100644 index 000000000000..4c4b7880f2c3 --- /dev/null +++ b/Marlin/src/lcd/menu/menu_language.cpp @@ -0,0 +1,59 @@ +/** + * 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 . + * + */ + +// +// Language Selection Menu +// + +#include "../../inc/MarlinConfig.h" + +#if HAS_MULTI_LANGUAGE + +#include "menu_item.h" +#include "../../MarlinCore.h" +#include "../../module/settings.h" + +static void set_lcd_language(const uint8_t inlang) { + ui.set_language(inlang); + TERN_(LCD_LANGUAGE_AUTO_SAVE, (void)settings.save()); +} + +void menu_language() { + START_MENU(); + BACK_ITEM(MSG_MAIN); + + MENU_ITEM_P(function, GET_LANG(LCD_LANGUAGE )::LANGUAGE, []{ set_lcd_language(0); }); + MENU_ITEM_P(function, GET_LANG(LCD_LANGUAGE_2)::LANGUAGE, []{ set_lcd_language(1); }); + #if NUM_LANGUAGES > 2 + MENU_ITEM_P(function, GET_LANG(LCD_LANGUAGE_3)::LANGUAGE, []{ set_lcd_language(2); }); + #if NUM_LANGUAGES > 3 + MENU_ITEM_P(function, GET_LANG(LCD_LANGUAGE_4)::LANGUAGE, []{ set_lcd_language(3); }); + #if NUM_LANGUAGES > 4 + MENU_ITEM_P(function, GET_LANG(LCD_LANGUAGE_5)::LANGUAGE, []{ set_lcd_language(4); }); + #endif + #endif + #endif + + END_MENU(); +} + +#endif // HAS_MULTI_LANGUAGE diff --git a/Marlin/src/lcd/menu/menu_led.cpp b/Marlin/src/lcd/menu/menu_led.cpp index 386a4d799aa2..284e80c931b7 100644 --- a/Marlin/src/lcd/menu/menu_led.cpp +++ b/Marlin/src/lcd/menu/menu_led.cpp @@ -84,18 +84,20 @@ EDIT_ITEM(uint8, MSG_INTENSITY_R, &leds.color.r, 0, 255, leds.update, true); EDIT_ITEM(uint8, MSG_INTENSITY_G, &leds.color.g, 0, 255, leds.update, true); EDIT_ITEM(uint8, MSG_INTENSITY_B, &leds.color.b, 0, 255, leds.update, true); - #if EITHER(RGBW_LED, NEOPIXEL_LED) + #if HAS_WHITE_LED EDIT_ITEM(uint8, MSG_INTENSITY_W, &leds.color.w, 0, 255, leds.update, true); - #if ENABLED(NEOPIXEL_LED) - EDIT_ITEM(uint8, MSG_LED_BRIGHTNESS, &leds.color.i, 0, 255, leds.update, true); - #endif + #endif + #if ENABLED(NEOPIXEL_LED) + EDIT_ITEM(uint8, MSG_LED_BRIGHTNESS, &leds.color.i, 0, 255, leds.update, true); #endif #if ENABLED(NEOPIXEL2_SEPARATE) STATIC_ITEM_N(MSG_LED_CHANNEL_N, 2, SS_DEFAULT|SS_INVERT); EDIT_ITEM(uint8, MSG_INTENSITY_R, &leds2.color.r, 0, 255, leds2.update, true); EDIT_ITEM(uint8, MSG_INTENSITY_G, &leds2.color.g, 0, 255, leds2.update, true); EDIT_ITEM(uint8, MSG_INTENSITY_B, &leds2.color.b, 0, 255, leds2.update, true); - EDIT_ITEM(uint8, MSG_INTENSITY_W, &leds2.color.w, 0, 255, leds2.update, true); + #if HAS_WHITE_LED2 + EDIT_ITEM(uint8, MSG_INTENSITY_W, &leds2.color.w, 0, 255, leds2.update, true); + #endif EDIT_ITEM(uint8, MSG_NEO2_BRIGHTNESS, &leds2.color.i, 0, 255, leds2.update, true); #endif END_MENU(); @@ -105,12 +107,14 @@ #if ENABLED(CASE_LIGHT_MENU) #include "../../feature/caselight.h" - #if DISABLED(CASE_LIGHT_NO_BRIGHTNESS) + #define CASELIGHT_TOGGLE_ITEM() EDIT_ITEM(bool, MSG_CASE_LIGHT, (bool*)&caselight.on, caselight.update_enabled) + + #if CASELIGHT_USES_BRIGHTNESS void menu_case_light() { START_MENU(); BACK_ITEM(MSG_CONFIGURATION); EDIT_ITEM(percent, MSG_CASE_LIGHT_BRIGHTNESS, &caselight.brightness, 0, 255, caselight.update_brightness, true); - EDIT_ITEM(bool, MSG_CASE_LIGHT, (bool*)&caselight.on, caselight.update_enabled); + CASELIGHT_TOGGLE_ITEM(); END_MENU(); } #endif @@ -121,13 +125,26 @@ void menu_led() { BACK_ITEM(MSG_MAIN); #if ENABLED(LED_CONTROL_MENU) - editable.state = leds.lights_on; - EDIT_ITEM(bool, MSG_LEDS, &editable.state, leds.toggle); - ACTION_ITEM(MSG_SET_LEDS_DEFAULT, leds.set_default); + #if ENABLED(PSU_CONTROL) + extern bool powersupply_on; + #else + constexpr bool powersupply_on = true; + #endif + if (powersupply_on) { + editable.state = leds.lights_on; + EDIT_ITEM(bool, MSG_LEDS, &editable.state, leds.toggle); + } + + #if ENABLED(LED_COLOR_PRESETS) + ACTION_ITEM(MSG_SET_LEDS_DEFAULT, leds.set_default); + #endif + #if ENABLED(NEOPIXEL2_SEPARATE) editable.state = leds2.lights_on; EDIT_ITEM(bool, MSG_LEDS2, &editable.state, leds2.toggle); - ACTION_ITEM(MSG_SET_LEDS_DEFAULT, leds2.set_default); + #if ENABLED(NEO2_COLOR_PRESETS) + ACTION_ITEM(MSG_SET_LEDS_DEFAULT, leds2.set_default); + #endif #endif #if ENABLED(LED_COLOR_PRESETS) SUBMENU(MSG_LED_PRESETS, menu_led_presets); @@ -142,13 +159,14 @@ void menu_led() { // Set Case light on/off/brightness // #if ENABLED(CASE_LIGHT_MENU) - #if DISABLED(CASE_LIGHT_NO_BRIGHTNESS) - if (TERN1(CASE_LIGHT_USE_NEOPIXEL, PWM_PIN(CASE_LIGHT_PIN))) + #if CASELIGHT_USES_BRIGHTNESS + if (caselight.has_brightness()) SUBMENU(MSG_CASE_LIGHT, menu_case_light); else #endif - EDIT_ITEM(bool, MSG_CASE_LIGHT, (bool*)&caselight.on, caselight.update_enabled); + CASELIGHT_TOGGLE_ITEM(); #endif + END_MENU(); } diff --git a/Marlin/src/lcd/menu/menu_main.cpp b/Marlin/src/lcd/menu/menu_main.cpp index 5b983825599e..57ee9845d7a6 100644 --- a/Marlin/src/lcd/menu/menu_main.cpp +++ b/Marlin/src/lcd/menu/menu_main.cpp @@ -46,8 +46,8 @@ #define MACHINE_CAN_PAUSE 1 #endif -#if ENABLED(PRUSA_MMU2) - #include "../../lcd/menu/menu_mmu2.h" +#if ENABLED(MMU2_MENUS) + #include "menu_mmu2.h" #endif #if ENABLED(PASSWORD_FEATURE) @@ -58,16 +58,16 @@ #include "../../feature/host_actions.h" #endif +#if ENABLED(GCODE_REPEAT_MARKERS) + #include "../../feature/repeat.h" +#endif + void menu_tune(); void menu_cancelobject(); void menu_motion(); void menu_temperature(); void menu_configuration(); -#if ENABLED(CUSTOM_USER_MENUS) - void menu_user(); -#endif - #if HAS_POWER_MONITOR void menu_power_monitor(); #endif @@ -77,7 +77,6 @@ void menu_configuration(); #endif #if ENABLED(ADVANCED_PAUSE_FEATURE) - void _menu_temp_filament_op(const PauseMode, const int8_t); void menu_change_filament(); #endif @@ -93,7 +92,155 @@ void menu_configuration(); void menu_spindle_laser(); #endif -extern const char M21_STR[]; +#if ENABLED(PREHEAT_SHORTCUT_MENU_ITEM) + void menu_preheat_only(); +#endif + +#if HAS_MULTI_LANGUAGE + void menu_language(); +#endif + +#if ENABLED(CUSTOM_MENU_MAIN) + + void _lcd_custom_menu_main_gcode(PGM_P const cmd) { + queue.inject_P(cmd); + TERN_(CUSTOM_MENU_MAIN_SCRIPT_AUDIBLE_FEEDBACK, ui.completion_feedback()); + TERN_(CUSTOM_MENU_MAIN_SCRIPT_RETURN, ui.return_to_status()); + } + + void custom_menus_main() { + START_MENU(); + BACK_ITEM(MSG_MAIN); + + #define HAS_CUSTOM_ITEM_MAIN(N) (defined(MAIN_MENU_ITEM_##N##_DESC) && defined(MAIN_MENU_ITEM_##N##_GCODE)) + + #define CUSTOM_TEST_MAIN(N) do{ \ + constexpr char c = MAIN_MENU_ITEM_##N##_GCODE[strlen(MAIN_MENU_ITEM_##N##_GCODE) - 1]; \ + static_assert(c != '\n' && c != '\r', "MAIN_MENU_ITEM_" STRINGIFY(N) "_GCODE cannot have a newline at the end. Please remove it."); \ + }while(0) + + #ifdef MAIN_MENU_ITEM_SCRIPT_DONE + #define _DONE_SCRIPT "\n" MAIN_MENU_ITEM_SCRIPT_DONE + #else + #define _DONE_SCRIPT "" + #endif + #define GCODE_LAMBDA_MAIN(N) []{ _lcd_custom_menu_main_gcode(PSTR(MAIN_MENU_ITEM_##N##_GCODE _DONE_SCRIPT)); } + #define _CUSTOM_ITEM_MAIN(N) ACTION_ITEM_P(PSTR(MAIN_MENU_ITEM_##N##_DESC), GCODE_LAMBDA_MAIN(N)); + #define _CUSTOM_ITEM_MAIN_CONFIRM(N) \ + SUBMENU_P(PSTR(MAIN_MENU_ITEM_##N##_DESC), []{ \ + MenuItem_confirm::confirm_screen( \ + GCODE_LAMBDA_MAIN(N), \ + ui.goto_previous_screen, \ + PSTR(MAIN_MENU_ITEM_##N##_DESC "?") \ + ); \ + }) + + #define CUSTOM_ITEM_MAIN(N) do{ if (ENABLED(MAIN_MENU_ITEM_##N##_CONFIRM)) _CUSTOM_ITEM_MAIN_CONFIRM(N); else _CUSTOM_ITEM_MAIN(N); }while(0) + + #if HAS_CUSTOM_ITEM_MAIN(1) + CUSTOM_TEST_MAIN(1); + CUSTOM_ITEM_MAIN(1); + #endif + #if HAS_CUSTOM_ITEM_MAIN(2) + CUSTOM_TEST_MAIN(2); + CUSTOM_ITEM_MAIN(2); + #endif + #if HAS_CUSTOM_ITEM_MAIN(3) + CUSTOM_TEST_MAIN(3); + CUSTOM_ITEM_MAIN(3); + #endif + #if HAS_CUSTOM_ITEM_MAIN(4) + CUSTOM_TEST_MAIN(4); + CUSTOM_ITEM_MAIN(4); + #endif + #if HAS_CUSTOM_ITEM_MAIN(5) + CUSTOM_TEST_MAIN(5); + CUSTOM_ITEM_MAIN(5); + #endif + #if HAS_CUSTOM_ITEM_MAIN(6) + CUSTOM_TEST_MAIN(6); + CUSTOM_ITEM_MAIN(6); + #endif + #if HAS_CUSTOM_ITEM_MAIN(7) + CUSTOM_TEST_MAIN(7); + CUSTOM_ITEM_MAIN(7); + #endif + #if HAS_CUSTOM_ITEM_MAIN(8) + CUSTOM_TEST_MAIN(8); + CUSTOM_ITEM_MAIN(8); + #endif + #if HAS_CUSTOM_ITEM_MAIN(9) + CUSTOM_TEST_MAIN(9); + CUSTOM_ITEM_MAIN(9); + #endif + #if HAS_CUSTOM_ITEM_MAIN(10) + CUSTOM_TEST_MAIN(10); + CUSTOM_ITEM_MAIN(10); + #endif + #if HAS_CUSTOM_ITEM_MAIN(11) + CUSTOM_TEST_MAIN(11); + CUSTOM_ITEM_MAIN(11); + #endif + #if HAS_CUSTOM_ITEM_MAIN(12) + CUSTOM_TEST_MAIN(12); + CUSTOM_ITEM_MAIN(12); + #endif + #if HAS_CUSTOM_ITEM_MAIN(13) + CUSTOM_TEST_MAIN(13); + CUSTOM_ITEM_MAIN(13); + #endif + #if HAS_CUSTOM_ITEM_MAIN(14) + CUSTOM_TEST_MAIN(14); + CUSTOM_ITEM_MAIN(14); + #endif + #if HAS_CUSTOM_ITEM_MAIN(15) + CUSTOM_TEST_MAIN(15); + CUSTOM_ITEM_MAIN(15); + #endif + #if HAS_CUSTOM_ITEM_MAIN(16) + CUSTOM_TEST_MAIN(16); + CUSTOM_ITEM_MAIN(16); + #endif + #if HAS_CUSTOM_ITEM_MAIN(17) + CUSTOM_TEST_MAIN(17); + CUSTOM_ITEM_MAIN(17); + #endif + #if HAS_CUSTOM_ITEM_MAIN(18) + CUSTOM_TEST_MAIN(18); + CUSTOM_ITEM_MAIN(18); + #endif + #if HAS_CUSTOM_ITEM_MAIN(19) + CUSTOM_TEST_MAIN(19); + CUSTOM_ITEM_MAIN(19); + #endif + #if HAS_CUSTOM_ITEM_MAIN(20) + CUSTOM_TEST_MAIN(20); + CUSTOM_ITEM_MAIN(20); + #endif + #if HAS_CUSTOM_ITEM_MAIN(21) + CUSTOM_TEST_MAIN(21); + CUSTOM_ITEM_MAIN(21); + #endif + #if HAS_CUSTOM_ITEM_MAIN(22) + CUSTOM_TEST_MAIN(22); + CUSTOM_ITEM_MAIN(22); + #endif + #if HAS_CUSTOM_ITEM_MAIN(23) + CUSTOM_TEST_MAIN(23); + CUSTOM_ITEM_MAIN(23); + #endif + #if HAS_CUSTOM_ITEM_MAIN(24) + CUSTOM_TEST_MAIN(24); + CUSTOM_ITEM_MAIN(24); + #endif + #if HAS_CUSTOM_ITEM_MAIN(25) + CUSTOM_TEST_MAIN(25); + CUSTOM_ITEM_MAIN(25); + #endif + END_MENU(); + } + +#endif // CUSTOM_MENU_MAIN void menu_main() { const bool busy = printingIsActive() @@ -106,6 +253,38 @@ void menu_main() { START_MENU(); BACK_ITEM(MSG_INFO_SCREEN); + #if ENABLED(SDSUPPORT) + + #if !defined(MEDIA_MENU_AT_TOP) && !HAS_ENCODER_WHEEL + #define MEDIA_MENU_AT_TOP + #endif + + auto sdcard_menu_items = [&]{ + #if ENABLED(MENU_ADDAUTOSTART) + ACTION_ITEM(MSG_RUN_AUTO_FILES, card.autofile_begin); // Run Auto Files + #endif + + if (card_detected) { + if (!card_open) { + #if PIN_EXISTS(SD_DETECT) + GCODES_ITEM(MSG_CHANGE_MEDIA, PSTR("M21")); // M21 Change Media + #else // - or - + GCODES_ITEM(MSG_RELEASE_MEDIA, PSTR("M22")); // M22 Release Media + #endif + SUBMENU(MSG_MEDIA_MENU, MEDIA_MENU_GATEWAY); // Media Menu (or Password First) + } + } + else { + #if PIN_EXISTS(SD_DETECT) + ACTION_ITEM(MSG_NO_MEDIA, nullptr); // "No Media" + #else + GCODES_ITEM(MSG_ATTACH_MEDIA, PSTR("M21")); // M21 Attach Media + #endif + } + }; + + #endif + if (busy) { #if MACHINE_CAN_PAUSE ACTION_ITEM(MSG_PAUSE_PRINT, ui.pause_print); @@ -120,6 +299,11 @@ void menu_main() { }); #endif + #if ENABLED(GCODE_REPEAT_MARKERS) + if (repeat.is_active()) + ACTION_ITEM(MSG_END_LOOPS, repeat.cancel); + #endif + SUBMENU(MSG_TUNE, menu_tune); #if ENABLED(CANCEL_OBJECTS) && DISABLED(SLIM_LCD_MENUS) @@ -128,36 +312,9 @@ void menu_main() { } else { - #if !HAS_ENCODER_WHEEL && ENABLED(SDSUPPORT) - - // *** IF THIS SECTION IS CHANGED, REPRODUCE BELOW *** - - // - // Autostart - // - #if ENABLED(MENU_ADDAUTOSTART) - ACTION_ITEM(MSG_AUTOSTART, card.beginautostart); - #endif - - if (card_detected) { - if (!card_open) { - SUBMENU(MSG_MEDIA_MENU, TERN(PASSWORD_ON_SD_PRINT_MENU, password.media_gatekeeper, menu_media)); - #if PIN_EXISTS(SD_DETECT) - GCODES_ITEM(MSG_CHANGE_MEDIA, M21_STR); - #else - GCODES_ITEM(MSG_RELEASE_MEDIA, PSTR("M22")); - #endif - } - } - else { - #if PIN_EXISTS(SD_DETECT) - ACTION_ITEM(MSG_NO_MEDIA, nullptr); - #else - GCODES_ITEM(MSG_ATTACH_MEDIA, M21_STR); - #endif - } - - #endif // !HAS_ENCODER_WHEEL && SDSUPPORT + #if BOTH(SDSUPPORT, MEDIA_MENU_AT_TOP) + sdcard_menu_items(); + #endif if (TERN0(MACHINE_CAN_PAUSE, printingIsPaused())) ACTION_ITEM(MSG_RESUME_PRINT, ui.resume_print); @@ -166,11 +323,15 @@ void menu_main() { ACTION_ITEM(MSG_HOST_START_PRINT, host_action_start); #endif + #if ENABLED(PREHEAT_SHORTCUT_MENU_ITEM) + SUBMENU(MSG_PREHEAT_CUSTOM, menu_preheat_only); + #endif + SUBMENU(MSG_MOTION, menu_motion); } #if HAS_CUTTER - SUBMENU(MSG_CUTTER(MENU), menu_spindle_laser); + SUBMENU(MSG_CUTTER(MENU), STICKY_SCREEN(menu_spindle_laser)); #endif #if HAS_TEMPERATURE @@ -191,20 +352,22 @@ void menu_main() { SUBMENU(MSG_CONFIGURATION, menu_configuration); - #if ENABLED(CUSTOM_USER_MENUS) - #ifdef CUSTOM_USER_MENU_TITLE - SUBMENU_P(PSTR(CUSTOM_USER_MENU_TITLE), menu_user); - #else - SUBMENU(MSG_USER_MENU, menu_user); - #endif + #if ENABLED(CUSTOM_MENU_MAIN) + if (TERN1(CUSTOM_MENU_MAIN_ONLY_IDLE, !busy)) { + #ifdef CUSTOM_MENU_MAIN_TITLE + SUBMENU_P(PSTR(CUSTOM_MENU_MAIN_TITLE), custom_menus_main); + #else + SUBMENU(MSG_CUSTOM_COMMANDS, custom_menus_main); + #endif + } #endif #if ENABLED(ADVANCED_PAUSE_FEATURE) #if E_STEPPERS == 1 && DISABLED(FILAMENT_LOAD_UNLOAD_GCODES) - if (thermalManager.targetHotEnoughToExtrude(active_extruder)) - GCODES_ITEM(MSG_FILAMENTCHANGE, PSTR("M600 B0")); - else - SUBMENU(MSG_FILAMENTCHANGE, []{ _menu_temp_filament_op(PAUSE_MODE_CHANGE_FILAMENT, 0); }); + YESNO_ITEM(MSG_FILAMENTCHANGE, + menu_change_filament, ui.goto_previous_screen, + GET_TEXT(MSG_FILAMENTCHANGE), (const char *)nullptr, PSTR("?") + ); #else SUBMENU(MSG_FILAMENTCHANGE, menu_change_filament); #endif @@ -228,39 +391,9 @@ void menu_main() { GCODES_ITEM(MSG_SWITCH_PS_ON, PSTR("M80")); #endif - #if BOTH(HAS_ENCODER_WHEEL, SDSUPPORT) - - if (!busy) { - - // *** IF THIS SECTION IS CHANGED, REPRODUCE ABOVE *** - - // - // Autostart - // - #if ENABLED(MENU_ADDAUTOSTART) - ACTION_ITEM(MSG_AUTOSTART, card.beginautostart); - #endif - - if (card_detected) { - if (!card_open) { - #if PIN_EXISTS(SD_DETECT) - GCODES_ITEM(MSG_CHANGE_MEDIA, M21_STR); - #else - GCODES_ITEM(MSG_RELEASE_MEDIA, PSTR("M22")); - #endif - SUBMENU(MSG_MEDIA_MENU, TERN(PASSWORD_ON_SD_PRINT_MENU, password.media_gatekeeper, menu_media)); - } - } - else { - #if PIN_EXISTS(SD_DETECT) - ACTION_ITEM(MSG_NO_MEDIA, nullptr); - #else - GCODES_ITEM(MSG_ATTACH_MEDIA, M21_STR); - #endif - } - } - - #endif // HAS_ENCODER_WHEEL && SDSUPPORT + #if ENABLED(SDSUPPORT) && DISABLED(MEDIA_MENU_AT_TOP) + sdcard_menu_items(); + #endif #if HAS_SERVICE_INTERVALS static auto _service_reset = [](const int index) { @@ -316,6 +449,10 @@ void menu_main() { } #endif + #if HAS_MULTI_LANGUAGE + SUBMENU(LANGUAGE, menu_language); + #endif + END_MENU(); } diff --git a/Marlin/src/lcd/menu/menu_media.cpp b/Marlin/src/lcd/menu/menu_media.cpp index 93ecc49d9859..8630f48b3736 100644 --- a/Marlin/src/lcd/menu/menu_media.cpp +++ b/Marlin/src/lcd/menu/menu_media.cpp @@ -104,7 +104,7 @@ class MenuItem_sdfolder : public MenuItem_sdbase { } }; -void menu_media() { +void menu_media_filelist() { ui.encoder_direction_menus(); #if HAS_MARLINUI_U8GLIB @@ -115,7 +115,11 @@ void menu_media() { #endif START_MENU(); - BACK_ITEM(MSG_MAIN); + #if ENABLED(MULTI_VOLUME) + ACTION_ITEM(MSG_BACK, []{ ui.goto_screen(menu_media); }); + #else + BACK_ITEM_P(TERN1(BROWSE_MEDIA_ON_INSERT, screen_history_depth) ? GET_TEXT(MSG_MAIN) : GET_TEXT(MSG_BACK)); + #endif if (card.flag.workDirIsRoot) { #if !PIN_EXISTS(SD_DETECT) ACTION_ITEM(MSG_REFRESH, []{ encoderTopLine = 0; card.mount(); }); @@ -138,4 +142,22 @@ void menu_media() { END_MENU(); } +#if ENABLED(MULTI_VOLUME) + void menu_media_select() { + START_MENU(); + BACK_ITEM_P(TERN1(BROWSE_MEDIA_ON_INSERT, screen_history_depth) ? GET_TEXT(MSG_MAIN) : GET_TEXT(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 + #if ENABLED(VOLUME_USB_FLASH_DRIVE) + ACTION_ITEM(MSG_USB_DISK, []{ card.changeMedia(&card.media_driver_usbFlash); card.mount(); ui.goto_screen(menu_media_filelist); }); + #endif + END_MENU(); + } +#endif + +void menu_media() { + TERN(MULTI_VOLUME, menu_media_select, menu_media_filelist)(); +} + #endif // HAS_LCD_MENU && SDSUPPORT diff --git a/Marlin/src/lcd/menu/menu_mixer.cpp b/Marlin/src/lcd/menu/menu_mixer.cpp index 8010239336ab..d07b89c7c045 100644 --- a/Marlin/src/lcd/menu/menu_mixer.cpp +++ b/Marlin/src/lcd/menu/menu_mixer.cpp @@ -33,6 +33,10 @@ #include "../../feature/mixing.h" +#if HAS_GRAPHICAL_TFT + #include "../tft/tft.h" +#endif + #define CHANNEL_MIX_EDITING !HAS_DUAL_MIXING #if ENABLED(GRADIENT_MIX) @@ -67,6 +71,9 @@ mixer.refresh_gradient(); ui.goto_previous_screen(); } + else { + TERN_(HAS_GRAPHICAL_TFT, tft.draw_edit_screen_buttons()); + } } void lcd_mixer_edit_gradient_menu() { @@ -155,6 +162,8 @@ void lcd_mixer_mix_edit() { ui.goto_previous_screen(); } + TERN_(HAS_GRAPHICAL_TFT, tft.draw_edit_screen_buttons()); + #else START_MENU(); diff --git a/Marlin/src/lcd/menu/menu_mmu2.cpp b/Marlin/src/lcd/menu/menu_mmu2.cpp index 0a63d90c6370..425a8ca75135 100644 --- a/Marlin/src/lcd/menu/menu_mmu2.cpp +++ b/Marlin/src/lcd/menu/menu_mmu2.cpp @@ -24,26 +24,20 @@ #if BOTH(HAS_LCD_MENU, MMU2_MENUS) -#include "../../feature/mmu2/mmu2.h" +#include "../../MarlinCore.h" +#include "../../feature/mmu/mmu2.h" #include "menu_mmu2.h" #include "menu_item.h" -uint8_t currentTool; -bool mmuMenuWait; - // // Load Filament // -void _mmu2_load_filamentToNozzle(uint8_t index) { +inline void action_mmu2_load_filament_to_nozzle(const uint8_t tool) { ui.reset_status(); ui.return_to_status(); - ui.status_printf_P(0, GET_TEXT(MSG_MMU2_LOADING_FILAMENT), int(index + 1)); - if (mmu2.load_filament_to_nozzle(index)) ui.reset_status(); -} - -inline void action_mmu2_load_filament_to_nozzle(const uint8_t tool) { - _mmu2_load_filamentToNozzle(tool); + ui.status_printf_P(0, GET_TEXT(MSG_MMU2_LOADING_FILAMENT), int(tool + 1)); + if (mmu2.load_filament_to_nozzle(tool)) ui.reset_status(); ui.return_to_status(); } @@ -62,14 +56,14 @@ void menu_mmu2_load_filament() { START_MENU(); BACK_ITEM(MSG_MMU2_MENU); ACTION_ITEM(MSG_MMU2_ALL, action_mmu2_load_all); - LOOP_L_N(i, 5) ACTION_ITEM_N(i, MSG_MMU2_FILAMENT_N, []{ _mmu2_load_filament(MenuItemBase::itemIndex); }); + LOOP_L_N(i, EXTRUDERS) ACTION_ITEM_N(i, MSG_MMU2_FILAMENT_N, []{ _mmu2_load_filament(MenuItemBase::itemIndex); }); END_MENU(); } void menu_mmu2_load_to_nozzle() { START_MENU(); BACK_ITEM(MSG_MMU2_MENU); - LOOP_L_N(i, 5) ACTION_ITEM_N(i, MSG_MMU2_FILAMENT_N, []{ action_mmu2_load_filament_to_nozzle(MenuItemBase::itemIndex); }); + LOOP_L_N(i, EXTRUDERS) ACTION_ITEM_N(i, MSG_MMU2_FILAMENT_N, []{ action_mmu2_load_filament_to_nozzle(MenuItemBase::itemIndex); }); END_MENU(); } @@ -95,7 +89,7 @@ void action_mmu2_unload_filament() { void menu_mmu2_eject_filament() { START_MENU(); BACK_ITEM(MSG_MMU2_MENU); - LOOP_L_N(i, 5) ACTION_ITEM_N(i, MSG_MMU2_FILAMENT_N, []{ _mmu2_eject_filament(MenuItemBase::itemIndex); }); + LOOP_L_N(i, EXTRUDERS) ACTION_ITEM_N(i, MSG_MMU2_FILAMENT_N, []{ _mmu2_eject_filament(MenuItemBase::itemIndex); }); END_MENU(); } @@ -123,9 +117,12 @@ void menu_mmu2() { // T* Choose Filament // -inline void action_mmu2_choose(const uint8_t tool) { - currentTool = tool; - mmuMenuWait = false; +uint8_t feeder_index; +bool wait_for_mmu_menu; + +inline void action_mmu2_chosen(const uint8_t index) { + feeder_index = index; + wait_for_mmu_menu = false; } void menu_mmu2_choose_filament() { @@ -133,7 +130,7 @@ void menu_mmu2_choose_filament() { #if LCD_HEIGHT > 2 STATIC_ITEM(MSG_MMU2_CHOOSE_FILAMENT_HEADER, SS_DEFAULT|SS_INVERT); #endif - LOOP_L_N(i, 5) ACTION_ITEM_N(i, MSG_MMU2_FILAMENT_N, []{ action_mmu2_choose(MenuItemBase::itemIndex); }); + LOOP_L_N(i, EXTRUDERS) ACTION_ITEM_N(i, MSG_MMU2_FILAMENT_N, []{ action_mmu2_chosen(MenuItemBase::itemIndex); }); END_MENU(); } @@ -142,32 +139,32 @@ void menu_mmu2_choose_filament() { // void menu_mmu2_pause() { - currentTool = mmu2.get_current_tool(); + feeder_index = mmu2.get_current_tool(); START_MENU(); #if LCD_HEIGHT > 2 STATIC_ITEM(MSG_FILAMENT_CHANGE_HEADER, SS_DEFAULT|SS_INVERT); #endif - ACTION_ITEM(MSG_MMU2_RESUME, []{ mmuMenuWait = false; }); + ACTION_ITEM(MSG_MMU2_RESUME, []{ wait_for_mmu_menu = false; }); ACTION_ITEM(MSG_MMU2_UNLOAD_FILAMENT, []{ mmu2.unload(); }); - ACTION_ITEM(MSG_MMU2_LOAD_FILAMENT, []{ mmu2.load_filament(currentTool); }); - ACTION_ITEM(MSG_MMU2_LOAD_TO_NOZZLE, []{ mmu2.load_filament_to_nozzle(currentTool); }); + ACTION_ITEM(MSG_MMU2_LOAD_FILAMENT, []{ mmu2.load_filament(feeder_index); }); + ACTION_ITEM(MSG_MMU2_LOAD_TO_NOZZLE, []{ mmu2.load_filament_to_nozzle(feeder_index); }); END_MENU(); } void mmu2_M600() { ui.defer_status_screen(); ui.goto_screen(menu_mmu2_pause); - mmuMenuWait = true; - while (mmuMenuWait) idle(); + wait_for_mmu_menu = true; + while (wait_for_mmu_menu) idle(); } uint8_t mmu2_choose_filament() { ui.defer_status_screen(); ui.goto_screen(menu_mmu2_choose_filament); - mmuMenuWait = true; - while (mmuMenuWait) idle(); + wait_for_mmu_menu = true; + while (wait_for_mmu_menu) idle(); ui.return_to_status(); - return currentTool; + return feeder_index; } #endif // HAS_LCD_MENU && MMU2_MENUS diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index 939a0480b94c..3e7977bac6ed 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -28,10 +28,13 @@ #if HAS_LCD_MENU +#define LARGE_AREA_TEST ((X_BED_SIZE) >= 1000 || (Y_BED_SIZE) >= 1000 || (Z_MAX_POS) >= 1000) + #include "menu_item.h" #include "menu_addon.h" #include "../../module/motion.h" +#include "../../gcode/parser.h" // for inch support #if ENABLED(DELTA) #include "../../module/delta.h" @@ -72,60 +75,58 @@ static void _lcd_move_xyz(PGM_P const name, const AxisEnum axis) { // Get the new position const float diff = float(int32_t(ui.encoderPosition)) * ui.manual_move.menu_scale; - #if IS_KINEMATIC - ui.manual_move.offset += diff; - if (int32_t(ui.encoderPosition) < 0) - NOLESS(ui.manual_move.offset, min - current_position[axis]); - else - NOMORE(ui.manual_move.offset, max - current_position[axis]); - #else - current_position[axis] += diff; - if (int32_t(ui.encoderPosition) < 0) - NOLESS(current_position[axis], min); - else - NOMORE(current_position[axis], max); - #endif - + (void)ui.manual_move.apply_diff(axis, diff, min, max); ui.manual_move.soon(axis); ui.refresh(LCDVIEW_REDRAW_NOW); } ui.encoderPosition = 0; if (ui.should_draw()) { - const float pos = NATIVE_TO_LOGICAL( - ui.manual_move.processing ? destination[axis] : current_position[axis] + TERN0(IS_KINEMATIC, ui.manual_move.offset), - axis - ); - MenuEditItemBase::draw_edit_screen(name, ui.manual_move.menu_scale >= 0.1f ? ftostr41sign(pos) : ftostr63(pos)); + const float pos = ui.manual_move.axis_value(axis); + if (parser.using_inch_units()) { + const float imp_pos = LINEAR_UNIT(pos); + MenuEditItemBase::draw_edit_screen(name, ftostr63(imp_pos)); + } + else + MenuEditItemBase::draw_edit_screen(name, ui.manual_move.menu_scale >= 0.1f ? (LARGE_AREA_TEST ? ftostr51sign(pos) : ftostr41sign(pos)) : ftostr63(pos)); } } void lcd_move_x() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_X), X_AXIS); } -void lcd_move_y() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_Y), Y_AXIS); } -void lcd_move_z() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_Z), Z_AXIS); } +#if HAS_Y_AXIS + void lcd_move_y() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_Y), Y_AXIS); } +#endif +#if HAS_Z_AXIS + void lcd_move_z() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_Z), Z_AXIS); } +#endif +#if LINEAR_AXES >= 4 + void lcd_move_i() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_I), I_AXIS); } +#endif +#if LINEAR_AXES >= 5 + void lcd_move_j() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_J), J_AXIS); } +#endif +#if LINEAR_AXES >= 6 + void lcd_move_k() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_K), K_AXIS); } +#endif #if E_MANUAL - static void lcd_move_e(TERN_(MULTI_MANUAL, const int8_t eindex=-1)) { + static void lcd_move_e(TERN_(MULTI_E_MANUAL, const int8_t eindex=active_extruder)) { if (ui.use_click()) return ui.goto_previous_screen_no_defer(); if (ui.encoderPosition) { if (!ui.manual_move.processing) { const float diff = float(int32_t(ui.encoderPosition)) * ui.manual_move.menu_scale; TERN(IS_KINEMATIC, ui.manual_move.offset, current_position.e) += diff; - ui.manual_move.soon(E_AXIS - #if MULTI_MANUAL - , eindex - #endif - ); + ui.manual_move.soon(E_AXIS OPTARG(MULTI_E_MANUAL, eindex)); ui.refresh(LCDVIEW_REDRAW_NOW); } ui.encoderPosition = 0; } if (ui.should_draw()) { - TERN_(MULTI_MANUAL, MenuItemBase::init(eindex)); + TERN_(MULTI_E_MANUAL, MenuItemBase::init(eindex)); MenuEditItemBase::draw_edit_screen( - GET_TEXT(TERN(MULTI_MANUAL, MSG_MOVE_EN, MSG_MOVE_E)), + GET_TEXT(TERN(MULTI_E_MANUAL, MSG_MOVE_EN, MSG_MOVE_E)), ftostr41sign(current_position.e - + TERN0(IS_KINEMATIC, ui.manual_move.offset) - - TERN0(MANUAL_E_MOVES_RELATIVE, manual_move_e_origin) + PLUS_TERN0(IS_KINEMATIC, ui.manual_move.offset) + MINUS_TERN0(MANUAL_E_MOVES_RELATIVE, manual_move_e_origin) ) ); } // should_draw @@ -137,19 +138,19 @@ void lcd_move_z() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_Z), Z_AXIS); } // "Motion" > "Move Xmm" > "Move XYZ" submenu // -#ifndef SHORT_MANUAL_Z_MOVE - #define SHORT_MANUAL_Z_MOVE 0.025 +#ifndef FINE_MANUAL_MOVE + #define FINE_MANUAL_MOVE 0.025 #endif screenFunc_t _manual_move_func_ptr; -void _goto_manual_move(const float scale) { +void _goto_manual_move(const_float_t scale) { ui.defer_status_screen(); ui.manual_move.menu_scale = scale; ui.goto_screen(_manual_move_func_ptr); } -void _menu_move_distance(const AxisEnum axis, const screenFunc_t func, const int8_t eindex=-1) { +void _menu_move_distance(const AxisEnum axis, const screenFunc_t func, const int8_t eindex=active_extruder) { _manual_move_func_ptr = func; START_MENU(); if (LCD_HEIGHT >= 4) { @@ -165,26 +166,33 @@ void _menu_move_distance(const AxisEnum axis, const screenFunc_t func, const int } BACK_ITEM(MSG_MOVE_AXIS); - SUBMENU(MSG_MOVE_10MM, []{ _goto_manual_move(10); }); - SUBMENU(MSG_MOVE_1MM, []{ _goto_manual_move( 1); }); - SUBMENU(MSG_MOVE_01MM, []{ _goto_manual_move( 0.1f); }); - if (axis == Z_AXIS && (SHORT_MANUAL_Z_MOVE) > 0.0f && (SHORT_MANUAL_Z_MOVE) < 0.1f) { - // Determine digits needed right of decimal - constexpr uint8_t digs = !UNEAR_ZERO((SHORT_MANUAL_Z_MOVE) * 1000 - int((SHORT_MANUAL_Z_MOVE) * 1000)) ? 4 : - !UNEAR_ZERO((SHORT_MANUAL_Z_MOVE) * 100 - int((SHORT_MANUAL_Z_MOVE) * 100)) ? 3 : 2; - PGM_P const label = GET_TEXT(MSG_MOVE_Z_DIST); - char tmp[strlen_P(label) + 10 + 1], numstr[10]; - sprintf_P(tmp, label, dtostrf(SHORT_MANUAL_Z_MOVE, 1, digs, numstr)); - - #if DISABLED(HAS_GRAPHICAL_TFT) - extern const char NUL_STR[]; - SUBMENU_P(NUL_STR, []{ _goto_manual_move(float(SHORT_MANUAL_Z_MOVE)); }); - MENU_ITEM_ADDON_START(0 + ENABLED(HAS_MARLINUI_HD44780)); - lcd_put_u8str(tmp); - MENU_ITEM_ADDON_END(); - #else - SUBMENU_P(tmp, []{ _goto_manual_move(float(SHORT_MANUAL_Z_MOVE)); }); - #endif + if (parser.using_inch_units()) { + if (LARGE_AREA_TEST) SUBMENU(MSG_MOVE_1IN, []{ _goto_manual_move(IN_TO_MM(1.000f)); }); + SUBMENU(MSG_MOVE_01IN, []{ _goto_manual_move(IN_TO_MM(0.100f)); }); + SUBMENU(MSG_MOVE_001IN, []{ _goto_manual_move(IN_TO_MM(0.010f)); }); + SUBMENU(MSG_MOVE_0001IN, []{ _goto_manual_move(IN_TO_MM(0.001f)); }); + } + else { + if (LARGE_AREA_TEST) SUBMENU(MSG_MOVE_100MM, []{ _goto_manual_move(100); }); + SUBMENU(MSG_MOVE_10MM, []{ _goto_manual_move(10); }); + SUBMENU(MSG_MOVE_1MM, []{ _goto_manual_move( 1); }); + SUBMENU(MSG_MOVE_01MM, []{ _goto_manual_move( 0.1f); }); + if (axis == Z_AXIS && (FINE_MANUAL_MOVE) > 0.0f && (FINE_MANUAL_MOVE) < 0.1f) { + // Determine digits needed right of decimal + constexpr uint8_t digs = !UNEAR_ZERO((FINE_MANUAL_MOVE) * 1000 - int((FINE_MANUAL_MOVE) * 1000)) ? 4 : + !UNEAR_ZERO((FINE_MANUAL_MOVE) * 100 - int((FINE_MANUAL_MOVE) * 100)) ? 3 : 2; + PGM_P const label = GET_TEXT(MSG_MOVE_N_MM); + char tmp[strlen_P(label) + 10 + 1], numstr[10]; + sprintf_P(tmp, label, dtostrf(FINE_MANUAL_MOVE, 1, digs, numstr)); + #if DISABLED(HAS_GRAPHICAL_TFT) + SUBMENU_P(NUL_STR, []{ _goto_manual_move(float(FINE_MANUAL_MOVE)); }); + MENU_ITEM_ADDON_START(0 + ENABLED(HAS_MARLINUI_HD44780)); + lcd_put_u8str(tmp); + MENU_ITEM_ADDON_END(); + #else + SUBMENU_P(tmp, []{ _goto_manual_move(float(FINE_MANUAL_MOVE)); }); + #endif + } } END_MENU(); } @@ -192,7 +200,7 @@ void _menu_move_distance(const AxisEnum axis, const screenFunc_t func, const int #if E_MANUAL inline void _goto_menu_move_distance_e() { - ui.goto_screen([]{ _menu_move_distance(E_AXIS, []{ lcd_move_e(TERN_(MULTI_MANUAL, active_extruder)); }, -1); }); + ui.goto_screen([]{ _menu_move_distance(E_AXIS, []{ lcd_move_e(); }); }); } inline void _menu_move_distance_e_maybe() { @@ -225,14 +233,27 @@ void menu_move() { if (NONE(IS_KINEMATIC, NO_MOTION_BEFORE_HOMING) || all_axes_homed()) { if (TERN1(DELTA, current_position.z <= delta_clip_start_height)) { SUBMENU(MSG_MOVE_X, []{ _menu_move_distance(X_AXIS, lcd_move_x); }); - SUBMENU(MSG_MOVE_Y, []{ _menu_move_distance(Y_AXIS, lcd_move_y); }); + #if HAS_Y_AXIS + SUBMENU(MSG_MOVE_Y, []{ _menu_move_distance(Y_AXIS, lcd_move_y); }); + #endif } #if ENABLED(DELTA) else ACTION_ITEM(MSG_FREE_XY, []{ line_to_z(delta_clip_start_height); ui.synchronize(); }); #endif - SUBMENU(MSG_MOVE_Z, []{ _menu_move_distance(Z_AXIS, lcd_move_z); }); + #if HAS_Z_AXIS + SUBMENU(MSG_MOVE_Z, []{ _menu_move_distance(Z_AXIS, lcd_move_z); }); + #endif + #if LINEAR_AXES >= 4 + SUBMENU(MSG_MOVE_I, []{ _menu_move_distance(I_AXIS, lcd_move_i); }); + #endif + #if LINEAR_AXES >= 5 + SUBMENU(MSG_MOVE_J, []{ _menu_move_distance(J_AXIS, lcd_move_j); }); + #endif + #if LINEAR_AXES >= 6 + SUBMENU(MSG_MOVE_K, []{ _menu_move_distance(K_AXIS, lcd_move_k); }); + #endif } else GCODES_ITEM(MSG_AUTO_HOME, G28_STR); @@ -287,7 +308,7 @@ void menu_move() { SUBMENU_MOVE_E(E_MANUAL - 1); #endif - #elif MULTI_MANUAL + #elif MULTI_E_MANUAL // Independent extruders with one E-stepper per hotend LOOP_L_N(n, E_MANUAL) SUBMENU_MOVE_E(n); @@ -305,6 +326,10 @@ void menu_move() { void menu_bed_leveling(); #endif +#if ENABLED(ASSISTED_TRAMMING_WIZARD) + void goto_tramming_wizard(); +#endif + void menu_motion() { START_MENU(); @@ -325,8 +350,21 @@ void menu_motion() { GCODES_ITEM(MSG_AUTO_HOME, G28_STR); #if ENABLED(INDIVIDUAL_AXIS_HOMING_MENU) GCODES_ITEM(MSG_AUTO_HOME_X, PSTR("G28X")); - GCODES_ITEM(MSG_AUTO_HOME_Y, PSTR("G28Y")); - GCODES_ITEM(MSG_AUTO_HOME_Z, PSTR("G28Z")); + #if HAS_Y_AXIS + GCODES_ITEM(MSG_AUTO_HOME_Y, PSTR("G28Y")); + #endif + #if HAS_Z_AXIS + GCODES_ITEM(MSG_AUTO_HOME_Z, PSTR("G28Z")); + #endif + #if LINEAR_AXES >= 4 + GCODES_ITEM(MSG_AUTO_HOME_I, PSTR("G28" AXIS4_STR)); + #endif + #if LINEAR_AXES >= 5 + GCODES_ITEM(MSG_AUTO_HOME_J, PSTR("G28" AXIS5_STR)); + #endif + #if LINEAR_AXES >= 6 + GCODES_ITEM(MSG_AUTO_HOME_K, PSTR("G28" AXIS6_STR)); + #endif #endif // @@ -346,8 +384,8 @@ void menu_motion() { // // Assisted Bed Tramming // - #if ENABLED(ASSISTED_TRAMMING_MENU_ITEM) - GCODES_ITEM(MSG_ASSISTED_TRAMMING, PSTR("G35")); + #if ENABLED(ASSISTED_TRAMMING_WIZARD) + SUBMENU(MSG_TRAMMING_WIZARD, goto_tramming_wizard); #endif // @@ -365,7 +403,7 @@ void menu_motion() { #elif HAS_LEVELING && DISABLED(SLIM_LCD_MENUS) #if DISABLED(PROBE_MANUALLY) - GCODES_ITEM(MSG_LEVEL_BED, PSTR("G28\nG29")); + GCODES_ITEM(MSG_LEVEL_BED, PSTR("G29N")); #endif if (all_axes_homed() && leveling_is_valid()) { @@ -381,11 +419,11 @@ void menu_motion() { #endif #if ENABLED(LEVEL_BED_CORNERS) && DISABLED(LCD_BED_LEVELING) - ACTION_ITEM(MSG_LEVEL_CORNERS, _lcd_level_bed_corners); + SUBMENU(MSG_BED_TRAMMING, _lcd_level_bed_corners); #endif #if ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST) - GCODES_ITEM(MSG_M48_TEST, PSTR("G28 O\nM48 P10")); + GCODES_ITEM(MSG_M48_TEST, PSTR("G28O\nM48 P10")); #endif // diff --git a/Marlin/src/lcd/menu/menu_password.cpp b/Marlin/src/lcd/menu/menu_password.cpp index c3924b568699..d3a35abff2e0 100644 --- a/Marlin/src/lcd/menu/menu_password.cpp +++ b/Marlin/src/lcd/menu/menu_password.cpp @@ -44,12 +44,18 @@ static uint8_t digit_no; // Screen for both editing and setting the password // void Password::menu_password_entry() { + ui.defer_status_screen(!did_first_run); // No timeout to status before first auth + START_MENU(); // "Login" or "New Code" STATIC_ITEM_P(authenticating ? GET_TEXT(MSG_LOGIN_REQUIRED) : GET_TEXT(MSG_EDIT_PASSWORD), SS_CENTER|SS_INVERT); - STATIC_ITEM_P(PSTR(""), SS_CENTER|SS_INVERT, string); + STATIC_ITEM_P(NUL_STR, SS_CENTER, string); + + #if HAS_MARLINUI_U8GLIB + STATIC_ITEM_P(NUL_STR, SS_CENTER, ""); + #endif // Make the digit edit item look like a sub-menu PGM_P const label = GET_TEXT(MSG_ENTER_DIGIT); @@ -57,7 +63,7 @@ void Password::menu_password_entry() { MENU_ITEM_ADDON_START(utf8_strlen_P(label) + 1); lcd_put_wchar(' '); lcd_put_wchar('1' + digit_no); - SETCURSOR_X(LCD_WIDTH - 1); + SETCURSOR_X(LCD_WIDTH - 2); lcd_put_wchar('>'); MENU_ITEM_ADDON_END(); @@ -104,7 +110,7 @@ void Password::screen_password_entry() { value_entry = 0; digit_no = 0; editable.uint8 = 0; - memset(string, '-', PASSWORD_LENGTH); + memset(string, '_', PASSWORD_LENGTH); string[PASSWORD_LENGTH] = '\0'; menu_password_entry(); } @@ -120,7 +126,6 @@ void Password::authenticate_user(const screenFunc_t in_succ_scr, const screenFun if (is_set) { authenticating = true; ui.goto_screen(screen_password_entry); - ui.defer_status_screen(); ui.update(); } else { @@ -152,19 +157,17 @@ void Password::menu_password_report() { END_SCREEN(); } -void Password::set_password_done() { - is_set = true; +void Password::set_password_done(const bool with_set/*=true*/) { + is_set = with_set; value = value_entry; ui.completion_feedback(true); ui.goto_screen(menu_password_report); } void Password::remove_password() { - is_set = false; string[0] = '0'; string[1] = '\0'; - ui.completion_feedback(true); - ui.goto_screen(menu_password_report); + set_password_done(false); } // @@ -174,7 +177,7 @@ void Password::menu_password() { START_MENU(); BACK_ITEM(MSG_ADVANCED_SETTINGS); SUBMENU(MSG_CHANGE_PASSWORD, screen_set_password); - ACTION_ITEM(MSG_REMOVE_PASSWORD, []{ ui.save_previous_screen(); remove_password(); } ); + ACTION_ITEM(MSG_REMOVE_PASSWORD, []{ ui.push_current_screen(); remove_password(); } ); #if ENABLED(EEPROM_SETTINGS) ACTION_ITEM(MSG_STORE_EEPROM, ui.store_settings); #endif diff --git a/Marlin/src/lcd/menu/menu_power_monitor.cpp b/Marlin/src/lcd/menu/menu_power_monitor.cpp index e88bdb28d8c8..b43327f63bc2 100644 --- a/Marlin/src/lcd/menu/menu_power_monitor.cpp +++ b/Marlin/src/lcd/menu/menu_power_monitor.cpp @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * Copyright (C) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. - * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm + * 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 @@ -42,7 +42,7 @@ void menu_power_monitor() { } #endif - #if HAS_POWER_MONITOR_VREF + #if ENABLED(POWER_MONITOR_VOLTAGE) { bool ena = power_monitor.voltage_display_enabled(); EDIT_ITEM(bool, MSG_VOLTAGE, &ena, power_monitor.toggle_voltage_display); diff --git a/Marlin/src/lcd/menu/menu_probe_offset.cpp b/Marlin/src/lcd/menu/menu_probe_offset.cpp index 6b7830b853d8..5ed217131a1f 100644 --- a/Marlin/src/lcd/menu/menu_probe_offset.cpp +++ b/Marlin/src/lcd/menu/menu_probe_offset.cpp @@ -16,7 +16,7 @@ * 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 . + * along with this program. If not, see . * */ @@ -28,14 +28,9 @@ #if ENABLED(PROBE_OFFSET_WIZARD) -#ifndef PROBE_OFFSET_START - #error "PROBE_OFFSET_WIZARD requires a PROBE_OFFSET_START with a negative value." -#else - static_assert(PROBE_OFFSET_START < 0, "PROBE_OFFSET_START must be < 0. Please update your configuration."); -#endif - #include "menu_item.h" #include "menu_addon.h" +#include "../../gcode/queue.h" #include "../../module/motion.h" #include "../../module/planner.h" #include "../../module/probe.h" @@ -45,38 +40,39 @@ #endif // Global storage -float z_offset_backup, calculated_z_offset; - -TERN_(HAS_LEVELING, bool leveling_was_active); - -void prepare_for_calibration() { - z_offset_backup = probe.offset.z; +float z_offset_backup, calculated_z_offset, z_offset_ref; - // Disable soft endstops for free Z movement - SET_SOFT_ENDSTOP_LOOSE(true); +#if HAS_LEVELING + bool leveling_was_active; +#endif - // Disable leveling for raw planner motion - #if HAS_LEVELING - leveling_was_active = planner.leveling_active; - set_bed_leveling_enabled(false); - #endif +inline void z_clearance_move() { + do_z_clearance( + #ifdef Z_AFTER_HOMING + Z_AFTER_HOMING + #elif defined(Z_HOMING_HEIGHT) + Z_HOMING_HEIGHT + #else + 10 + #endif + ); } -void set_offset_and_go_back(const float &z) { +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)); ui.goto_previous_screen_no_defer(); } -void _goto_manual_move_z(const float scale) { +void _goto_manual_move_z(const_float_t scale) { ui.manual_move.menu_scale = scale; ui.goto_screen(lcd_move_z); } void probe_offset_wizard_menu() { START_MENU(); - calculated_z_offset = probe.offset.z + current_position.z; + calculated_z_offset = probe.offset.z + current_position.z - z_offset_ref; if (LCD_HEIGHT >= 4) STATIC_ITEM(MSG_MOVE_NOZZLE_TO_BED, SS_CENTER|SS_INVERT); @@ -87,52 +83,110 @@ void probe_offset_wizard_menu() { SUBMENU(MSG_MOVE_1MM, []{ _goto_manual_move_z( 1); }); SUBMENU(MSG_MOVE_01MM, []{ _goto_manual_move_z( 0.1f); }); - if ((SHORT_MANUAL_Z_MOVE) > 0.0f && (SHORT_MANUAL_Z_MOVE) < 0.1f) { - extern const char NUL_STR[]; - SUBMENU_P(NUL_STR, []{ _goto_manual_move_z(float(SHORT_MANUAL_Z_MOVE)); }); - MENU_ITEM_ADDON_START(0 + ENABLED(HAS_MARLINUI_HD44780)); - char tmp[20], numstr[10]; - // Determine digits needed right of decimal - const uint8_t digs = !UNEAR_ZERO((SHORT_MANUAL_Z_MOVE) * 1000 - int((SHORT_MANUAL_Z_MOVE) * 1000)) ? 4 : - !UNEAR_ZERO((SHORT_MANUAL_Z_MOVE) * 100 - int((SHORT_MANUAL_Z_MOVE) * 100)) ? 3 : 2; - sprintf_P(tmp, GET_TEXT(MSG_MOVE_Z_DIST), dtostrf(SHORT_MANUAL_Z_MOVE, 1, digs, numstr)); + if ((FINE_MANUAL_MOVE) > 0.0f && (FINE_MANUAL_MOVE) < 0.1f) { + char tmp[20], numstr[10]; + // Determine digits needed right of decimal + const uint8_t digs = !UNEAR_ZERO((FINE_MANUAL_MOVE) * 1000 - int((FINE_MANUAL_MOVE) * 1000)) ? 4 : + !UNEAR_ZERO((FINE_MANUAL_MOVE) * 100 - int((FINE_MANUAL_MOVE) * 100)) ? 3 : 2; + sprintf_P(tmp, GET_TEXT(MSG_MOVE_N_MM), dtostrf(FINE_MANUAL_MOVE, 1, digs, numstr)); + #if DISABLED(HAS_GRAPHICAL_TFT) + SUBMENU_P(NUL_STR, []{ _goto_manual_move_z(float(FINE_MANUAL_MOVE)); }); + MENU_ITEM_ADDON_START(0 + ENABLED(HAS_MARLINUI_HD44780)); lcd_put_u8str(tmp); - MENU_ITEM_ADDON_END(); + MENU_ITEM_ADDON_END(); + #else + SUBMENU_P(tmp, []{ _goto_manual_move_z(float(FINE_MANUAL_MOVE)); }); + #endif } ACTION_ITEM(MSG_BUTTON_DONE, []{ set_offset_and_go_back(calculated_z_offset); - do_z_clearance(20.0 - #ifdef Z_AFTER_HOMING - - 20.0 + Z_AFTER_HOMING - #endif - ); + current_position.z = z_offset_ref; // Set Z to z_offset_ref, as we can expect it is at probe height + sync_plan_position(); + z_clearance_move(); // Raise Z as if it was homed }); ACTION_ITEM(MSG_BUTTON_CANCEL, []{ set_offset_and_go_back(z_offset_backup); + // If wizard-homing was done by probe with PROBE_OFFSET_WIZARD_START_Z + #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")); + #else // Otherwise do a Z clearance move like after Homing + z_clearance_move(); + #endif }); END_MENU(); } +void prepare_for_probe_offset_wizard() { + #if defined(PROBE_OFFSET_WIZARD_XY_POS) || !HOMING_Z_WITH_PROBE + if (ui.should_draw()) MenuItem_static::draw(1, GET_TEXT(MSG_PROBE_WIZARD_PROBING)); + + if (ui.wait_for_move) return; + + #ifndef PROBE_OFFSET_WIZARD_XY_POS + #define PROBE_OFFSET_WIZARD_XY_POS XY_CENTER + #endif + // Get X and Y from configuration, or use center + constexpr xy_pos_t wizard_pos = PROBE_OFFSET_WIZARD_XY_POS; + + // Probe for Z reference + ui.wait_for_move = true; + z_offset_ref = probe.probe_at_point(wizard_pos, PROBE_PT_RAISE, 0, true); + ui.wait_for_move = false; + + // Stow the probe, as the last call to probe.probe_at_point(...) left + // the probe deployed if it was successful. + probe.stow(); + #else + if (ui.wait_for_move) return; + #endif + + // 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)); + ui.synchronize(GET_TEXT(MSG_PROBE_WIZARD_MOVING)); + ui.wait_for_move = false; + + SET_SOFT_ENDSTOP_LOOSE(true); // Disable soft endstops for free Z movement + + // Go to Calibration Menu + ui.goto_screen(probe_offset_wizard_menu); + ui.defer_status_screen(); +} + void goto_probe_offset_wizard() { ui.defer_status_screen(); + set_all_unhomed(); + + // Store probe.offset.z for Case: Cancel + z_offset_backup = probe.offset.z; - prepare_for_calibration(); + #ifdef PROBE_OFFSET_WIZARD_START_Z + probe.offset.z = PROBE_OFFSET_WIZARD_START_Z; + #endif - probe.offset.z = PROBE_OFFSET_START; + // Store Bed-Leveling-State and disable + #if HAS_LEVELING + leveling_was_active = planner.leveling_active; + set_bed_leveling_enabled(false); + #endif - set_all_unhomed(); + // Home all axes queue.inject_P(G28_STR); ui.goto_screen([]{ _lcd_draw_homing(); if (all_axes_homed()) { - ui.goto_screen(probe_offset_wizard_menu); + z_offset_ref = 0; // Set Z Value for Wizard Position to 0 + ui.goto_screen(prepare_for_probe_offset_wizard); ui.defer_status_screen(); } }); + } #endif // PROBE_OFFSET_WIZARD diff --git a/Marlin/src/lcd/menu/menu_spindle_laser.cpp b/Marlin/src/lcd/menu/menu_spindle_laser.cpp index 04b999eaf620..a28c614c91ae 100644 --- a/Marlin/src/lcd/menu/menu_spindle_laser.cpp +++ b/Marlin/src/lcd/menu/menu_spindle_laser.cpp @@ -33,8 +33,10 @@ #include "../../feature/spindle_laser.h" void menu_spindle_laser() { - - const bool is_enabled = cutter.enabled() && cutter.isReady; + bool is_enabled = cutter.enabled() && cutter.isReady; + #if ENABLED(SPINDLE_CHANGE_DIR) + bool is_rev = cutter.is_reverse(); + #endif START_MENU(); BACK_ITEM(MSG_MAIN); @@ -46,20 +48,36 @@ cutter.mpower_min(), cutter.mpower_max(), cutter.update_from_mpower); #endif - if (is_enabled) - ACTION_ITEM(MSG_CUTTER(OFF), cutter.disable); - else { - ACTION_ITEM(MSG_CUTTER(ON), cutter.enable_forward); - #if ENABLED(SPINDLE_CHANGE_DIR) - ACTION_ITEM(MSG_SPINDLE_REVERSE, cutter.enable_reverse); - #endif - } - - #if ENABLED(MARLIN_DEV_MODE) - #if ENABLED(HAL_CAN_SET_PWM_FREQ) && defined(SPINDLE_LASER_FREQUENCY) - EDIT_ITEM_FAST(CUTTER_MENU_FREQUENCY_TYPE, MSG_CUTTER_FREQUENCY, &cutter.frequency, 2000, 50000, cutter.refresh_frequency); - #endif + editable.state = is_enabled; + EDIT_ITEM(bool, MSG_CUTTER(TOGGLE), &is_enabled, []{ if (editable.state) cutter.disable(); else cutter.enable_same_dir(); }); + + #if ENABLED(AIR_EVACUATION) + bool evac_state = cutter.air_evac_state(); + EDIT_ITEM(bool, MSG_CUTTER(EVAC_TOGGLE), &evac_state, cutter.air_evac_toggle); + #endif + + #if ENABLED(AIR_ASSIST) + bool air_assist_state = cutter.air_assist_state(); + EDIT_ITEM(bool, MSG_CUTTER(ASSIST_TOGGLE), &air_assist_state, cutter.air_assist_toggle); + #endif + + #if ENABLED(SPINDLE_CHANGE_DIR) + if (!is_enabled) { + editable.state = is_rev; + ACTION_ITEM_P(is_rev ? GET_TEXT(MSG_CUTTER(REVERSE)) : GET_TEXT(MSG_CUTTER(FORWARD)), []{ cutter.set_reverse(!editable.state); }); + } + #endif + + #if ENABLED(LASER_FEATURE) + // Setup and fire a test pulse using the current PWM power level for for a duration of test_pulse_min to test_pulse_max ms. + EDIT_ITEM_FAST(CUTTER_MENU_PULSE_TYPE, MSG_LASER_PULSE_MS, &cutter.testPulse, LASER_TEST_PULSE_MIN, LASER_TEST_PULSE_MAX); + ACTION_ITEM(MSG_LASER_FIRE_PULSE, cutter.test_fire_pulse); #endif + + #if BOTH(MARLIN_DEV_MODE, HAL_CAN_SET_PWM_FREQ) && defined(SPINDLE_LASER_FREQUENCY) + EDIT_ITEM_FAST(CUTTER_MENU_FREQUENCY_TYPE, MSG_CUTTER_FREQUENCY, &cutter.frequency, 2000, 80000, cutter.refresh_frequency); + #endif + END_MENU(); } diff --git a/Marlin/src/lcd/menu/menu_temperature.cpp b/Marlin/src/lcd/menu/menu_temperature.cpp index 0c70cd7e18e8..65cef5b76df7 100644 --- a/Marlin/src/lcd/menu/menu_temperature.cpp +++ b/Marlin/src/lcd/menu/menu_temperature.cpp @@ -31,11 +31,15 @@ #include "menu_item.h" #include "../../module/temperature.h" -#if FAN_COUNT > 1 || ENABLED(SINGLENOZZLE) +#if HAS_FAN || ENABLED(SINGLENOZZLE) #include "../../module/motion.h" #endif -#if ENABLED(SINGLENOZZLE) +#if EITHER(HAS_COOLER, LASER_COOLANT_FLOW_METER) + #include "../../feature/cooler.h" +#endif + +#if ENABLED(SINGLENOZZLE_STANDBY_TEMP) #include "../../module/tool_change.h" #endif @@ -43,25 +47,24 @@ // "Temperature" submenu items // -void Temperature::lcd_preheat(const int16_t e, const int8_t indh, const int8_t indb) { +void Temperature::lcd_preheat(const uint8_t e, const int8_t indh, const int8_t indb) { + UNUSED(e); UNUSED(indh); UNUSED(indb); #if HAS_HOTEND if (indh >= 0 && ui.material_preset[indh].hotend_temp > 0) - setTargetHotend(_MIN(thermalManager.heater_maxtemp[e] - HOTEND_OVERSHOOT, ui.material_preset[indh].hotend_temp), e); - #else - UNUSED(e); UNUSED(indh); + setTargetHotend(_MIN(thermalManager.hotend_max_target(e), ui.material_preset[indh].hotend_temp), e); #endif #if HAS_HEATED_BED if (indb >= 0 && ui.material_preset[indb].bed_temp > 0) setTargetBed(ui.material_preset[indb].bed_temp); - #else - UNUSED(indb); #endif #if HAS_FAN - set_fan_speed(( - #if FAN_COUNT > 1 - active_extruder < FAN_COUNT ? active_extruder : - #endif - 0), ui.material_preset[indh].fan_speed - ); + if (indh >= 0) { + const uint8_t fan_index = active_extruder < (FAN_COUNT) ? active_extruder : 0; + if (true + #if REDUNDANT_PART_COOLING_FAN + && fan_index != REDUNDANT_PART_COOLING_FAN + #endif + ) set_fan_speed(fan_index, ui.material_preset[indh].fan_speed); + } #endif ui.return_to_status(); } @@ -70,15 +73,18 @@ void Temperature::lcd_preheat(const int16_t e, const int8_t indh, const int8_t i #if HAS_TEMP_HOTEND inline void _preheat_end(const uint8_t m, const uint8_t e) { thermalManager.lcd_preheat(e, m, -1); } - #if HAS_HEATED_BED - inline void _preheat_both(const uint8_t m, const uint8_t e) { thermalManager.lcd_preheat(e, m, m); } - #endif + void do_preheat_end_m() { _preheat_end(editable.int8, 0); } #endif #if HAS_HEATED_BED - inline void _preheat_bed(const uint8_t m) { thermalManager.lcd_preheat(-1, -1, m); } + inline void _preheat_bed(const uint8_t m) { thermalManager.lcd_preheat(0, -1, m); } + #endif + #if HAS_COOLER + inline void _precool_laser(const uint8_t m, const uint8_t e) { thermalManager.lcd_preheat(e, m, -1); } + void do_precool_laser_m() { _precool_laser(editable.int8, thermalManager.temp_cooler.target); } #endif #if HAS_TEMP_HOTEND && HAS_HEATED_BED + inline void _preheat_both(const uint8_t m, const uint8_t e) { thermalManager.lcd_preheat(e, m, m); } // Indexed "Preheat ABC" and "Heat Bed" items #define PREHEAT_ITEMS(M,E) do{ \ @@ -93,8 +99,6 @@ void Temperature::lcd_preheat(const int16_t e, const int8_t indh, const int8_t i #endif - void do_preheat_end_m() { _preheat_end(editable.int8, 0); } - #if HAS_MULTI_HOTEND || HAS_HEATED_BED // Set editable.int8 to the Material index before entering this menu @@ -118,8 +122,8 @@ void Temperature::lcd_preheat(const int16_t e, const int8_t indh, const int8_t i HOTEND_LOOP() PREHEAT_ITEMS(editable.int8, e); ACTION_ITEM_S(ui.get_preheat_label(m), MSG_PREHEAT_M_ALL, []() { - TERN_(HAS_HEATED_BED, []{ _preheat_bed(editable.int8); }); HOTEND_LOOP() thermalManager.setTargetHotend(ui.material_preset[editable.int8].hotend_temp, e); + TERN(HAS_HEATED_BED, _preheat_bed(editable.int8), ui.return_to_status()); }); #endif @@ -149,10 +153,14 @@ void menu_temperature() { #if HAS_TEMP_HOTEND || HAS_HEATED_BED bool has_heat = false; #if HAS_TEMP_HOTEND - HOTEND_LOOP() if (thermalManager.temp_hotend[HOTEND_INDEX].target) { has_heat = true; break; } + HOTEND_LOOP() if (thermalManager.degTargetHotend(HOTEND_INDEX)) { has_heat = true; break; } #endif #endif + #if HAS_COOLER + if (thermalManager.temp_cooler.target == 0) thermalManager.temp_cooler.target = COOLER_DEFAULT_TEMP; + #endif + START_MENU(); BACK_ITEM(MSG_MAIN); @@ -161,15 +169,18 @@ void menu_temperature() { // Nozzle [1-5]: // #if HOTENDS == 1 - EDIT_ITEM_FAST(int3, MSG_NOZZLE, &thermalManager.temp_hotend[0].target, 0, HEATER_0_MAXTEMP - (HOTEND_OVERSHOOT), []{ thermalManager.start_watching_hotend(0); }); + editable.celsius = thermalManager.temp_hotend[0].target; + EDIT_ITEM_FAST(int3, MSG_NOZZLE, &editable.celsius, 0, thermalManager.hotend_max_target(0), []{ thermalManager.setTargetHotend(editable.celsius, 0); }); #elif HAS_MULTI_HOTEND - HOTEND_LOOP() - EDIT_ITEM_FAST_N(int3, e, MSG_NOZZLE_N, &thermalManager.temp_hotend[e].target, 0, thermalManager.heater_maxtemp[e] - (HOTEND_OVERSHOOT), []{ thermalManager.start_watching_hotend(MenuItemBase::itemIndex); }); + HOTEND_LOOP() { + editable.celsius = thermalManager.temp_hotend[e].target; + EDIT_ITEM_FAST_N(int3, e, MSG_NOZZLE_N, &editable.celsius, 0, thermalManager.hotend_max_target(e), []{ thermalManager.setTargetHotend(editable.celsius, MenuItemBase::itemIndex); }); + } #endif #if ENABLED(SINGLENOZZLE_STANDBY_TEMP) LOOP_S_L_N(e, 1, EXTRUDERS) - EDIT_ITEM_FAST_N(uint16_3, e, MSG_NOZZLE_STANDBY, &singlenozzle_temp[e], 0, thermalManager.heater_maxtemp[0] - (HOTEND_OVERSHOOT)); + EDIT_ITEM_FAST_N(int3, e, MSG_NOZZLE_STANDBY, &thermalManager.singlenozzle_temp[e], 0, thermalManager.hotend_max_target(0)); #endif // @@ -183,7 +194,24 @@ void menu_temperature() { // Chamber: // #if HAS_HEATED_CHAMBER - EDIT_ITEM_FAST(int3, MSG_CHAMBER, &thermalManager.temp_chamber.target, 0, CHAMBER_MAXTEMP - 10, thermalManager.start_watching_chamber); + EDIT_ITEM_FAST(int3, MSG_CHAMBER, &thermalManager.temp_chamber.target, 0, CHAMBER_MAX_TARGET, thermalManager.start_watching_chamber); + #endif + + // + // Cooler: + // + #if HAS_COOLER + bool cstate = cooler.enabled; + EDIT_ITEM(bool, MSG_COOLER_TOGGLE, &cstate, cooler.toggle); + EDIT_ITEM_FAST(int3, MSG_COOLER, &thermalManager.temp_cooler.target, COOLER_MIN_TARGET, COOLER_MAX_TARGET, thermalManager.start_watching_cooler); + #endif + + // + // Flow Meter Safety Shutdown: + // + #if ENABLED(FLOWMETER_SAFETY) + bool fstate = cooler.flowsafety_enabled; + EDIT_ITEM(bool, MSG_FLOWMETER_SAFETY, &fstate, cooler.flowsafety_toggle); #endif // @@ -196,37 +224,37 @@ void menu_temperature() { #if HAS_FAN0 _FAN_EDIT_ITEMS(0,FIRST_FAN_SPEED); #endif - #if HAS_FAN1 + #if HAS_FAN1 && REDUNDANT_PART_COOLING_FAN != 1 FAN_EDIT_ITEMS(1); #elif SNFAN(1) singlenozzle_item(1); #endif - #if HAS_FAN2 + #if HAS_FAN2 && REDUNDANT_PART_COOLING_FAN != 2 FAN_EDIT_ITEMS(2); #elif SNFAN(2) singlenozzle_item(2); #endif - #if HAS_FAN3 + #if HAS_FAN3 && REDUNDANT_PART_COOLING_FAN != 3 FAN_EDIT_ITEMS(3); #elif SNFAN(3) singlenozzle_item(3); #endif - #if HAS_FAN4 + #if HAS_FAN4 && REDUNDANT_PART_COOLING_FAN != 4 FAN_EDIT_ITEMS(4); #elif SNFAN(4) singlenozzle_item(4); #endif - #if HAS_FAN5 + #if HAS_FAN5 && REDUNDANT_PART_COOLING_FAN != 5 FAN_EDIT_ITEMS(5); #elif SNFAN(5) singlenozzle_item(5); #endif - #if HAS_FAN6 + #if HAS_FAN6 && REDUNDANT_PART_COOLING_FAN != 6 FAN_EDIT_ITEMS(6); #elif SNFAN(6) singlenozzle_item(6); #endif - #if HAS_FAN7 + #if HAS_FAN7 && REDUNDANT_PART_COOLING_FAN != 7 FAN_EDIT_ITEMS(7); #elif SNFAN(7) singlenozzle_item(7); @@ -236,13 +264,13 @@ void menu_temperature() { #if PREHEAT_COUNT // - // Preheat for Materials 1 to 5 + // Preheat for all Materials // LOOP_L_N(m, PREHEAT_COUNT) { editable.int8 = m; #if HOTENDS > 1 || HAS_HEATED_BED SUBMENU_S(ui.get_preheat_label(m), MSG_PREHEAT_M, menu_preheat_m); - #else + #elif HAS_HOTEND ACTION_ITEM_S(ui.get_preheat_label(m), MSG_PREHEAT_M, do_preheat_end_m); #endif } @@ -252,11 +280,31 @@ void menu_temperature() { // // Cooldown // - if (TERN0(HAS_HEATED_BED, thermalManager.temp_bed.target)) has_heat = true; + if (TERN0(HAS_HEATED_BED, thermalManager.degTargetBed())) has_heat = true; if (has_heat) ACTION_ITEM(MSG_COOLDOWN, lcd_cooldown); #endif END_MENU(); } +#if ENABLED(PREHEAT_SHORTCUT_MENU_ITEM) + + void menu_preheat_only() { + START_MENU(); + BACK_ITEM(MSG_MAIN); + + LOOP_L_N(m, PREHEAT_COUNT) { + editable.int8 = m; + #if HOTENDS > 1 || HAS_HEATED_BED + SUBMENU_S(ui.get_preheat_label(m), MSG_PREHEAT_M, menu_preheat_m); + #else + ACTION_ITEM_S(ui.get_preheat_label(m), MSG_PREHEAT_M, do_preheat_end_m); + #endif + } + + END_MENU(); + } + +#endif + #endif // HAS_LCD_MENU && HAS_TEMPERATURE diff --git a/Marlin/src/lcd/menu/menu_tmc.cpp b/Marlin/src/lcd/menu/menu_tmc.cpp index 402ee41a1b45..ad7d63205879 100644 --- a/Marlin/src/lcd/menu/menu_tmc.cpp +++ b/Marlin/src/lcd/menu/menu_tmc.cpp @@ -95,54 +95,22 @@ void menu_tmc_current() { void menu_tmc_hybrid_thrs() { START_MENU(); BACK_ITEM(MSG_TMC_DRIVERS); - #if AXIS_HAS_STEALTHCHOP(X) - TMC_EDIT_STORED_HYBRID_THRS(X, STR_X); - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - TMC_EDIT_STORED_HYBRID_THRS(Y, STR_Y); - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - TMC_EDIT_STORED_HYBRID_THRS(Z, STR_Z); - #endif - #if AXIS_HAS_STEALTHCHOP(X2) - TMC_EDIT_STORED_HYBRID_THRS(X2, STR_X2); - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - TMC_EDIT_STORED_HYBRID_THRS(Y2, STR_Y2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - TMC_EDIT_STORED_HYBRID_THRS(Z2, STR_Z2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z3) - TMC_EDIT_STORED_HYBRID_THRS(Z3, STR_Z3); - #endif - #if AXIS_HAS_STEALTHCHOP(Z4) - TMC_EDIT_STORED_HYBRID_THRS(Z4, STR_Z4); - #endif - #if AXIS_HAS_STEALTHCHOP(E0) - TMC_EDIT_STORED_HYBRID_THRS(E0, LCD_STR_E0); - #endif - #if AXIS_HAS_STEALTHCHOP(E1) - TMC_EDIT_STORED_HYBRID_THRS(E1, LCD_STR_E1); - #endif - #if AXIS_HAS_STEALTHCHOP(E2) - TMC_EDIT_STORED_HYBRID_THRS(E2, LCD_STR_E2); - #endif - #if AXIS_HAS_STEALTHCHOP(E3) - TMC_EDIT_STORED_HYBRID_THRS(E3, LCD_STR_E3); - #endif - #if AXIS_HAS_STEALTHCHOP(E4) - TMC_EDIT_STORED_HYBRID_THRS(E4, LCD_STR_E4); - #endif - #if AXIS_HAS_STEALTHCHOP(E5) - TMC_EDIT_STORED_HYBRID_THRS(E5, LCD_STR_E5); - #endif - #if AXIS_HAS_STEALTHCHOP(E6) - TMC_EDIT_STORED_HYBRID_THRS(E6, LCD_STR_E6); - #endif - #if AXIS_HAS_STEALTHCHOP(E7) - TMC_EDIT_STORED_HYBRID_THRS(E7, LCD_STR_E7); - #endif + TERN_(X_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(X, STR_X)); + TERN_(Y_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(Y, STR_Y)); + TERN_(Z_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(Z, STR_Z)); + TERN_(X2_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(X2, STR_X2)); + TERN_(Y2_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(Y2, STR_Y2)); + TERN_(Z2_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(Z2, STR_Z2)); + TERN_(Z3_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(Z3, STR_Z3)); + TERN_(Z4_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(Z4, STR_Z4)); + TERN_(E0_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E0, LCD_STR_E0)); + TERN_(E1_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E1, LCD_STR_E1)); + TERN_(E2_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E2, LCD_STR_E2)); + TERN_(E3_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E3, LCD_STR_E3)); + TERN_(E4_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E4, LCD_STR_E4)); + TERN_(E5_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E5, LCD_STR_E5)); + TERN_(E6_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E6, LCD_STR_E6)); + TERN_(E7_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E7, LCD_STR_E7)); END_MENU(); } @@ -155,30 +123,17 @@ void menu_tmc_current() { void menu_tmc_homing_thrs() { START_MENU(); BACK_ITEM(MSG_TMC_DRIVERS); - #if X_SENSORLESS - TMC_EDIT_STORED_SGT(X); - #if X2_SENSORLESS - TMC_EDIT_STORED_SGT(X2); - #endif - #endif - #if Y_SENSORLESS - TMC_EDIT_STORED_SGT(Y); - #if Y2_SENSORLESS - TMC_EDIT_STORED_SGT(Y2); - #endif - #endif - #if Z_SENSORLESS - TMC_EDIT_STORED_SGT(Z); - #if Z2_SENSORLESS - TMC_EDIT_STORED_SGT(Z2); - #endif - #if Z3_SENSORLESS - TMC_EDIT_STORED_SGT(Z3); - #endif - #if Z4_SENSORLESS - TMC_EDIT_STORED_SGT(Z4); - #endif - #endif + TERN_( X_SENSORLESS, TMC_EDIT_STORED_SGT(X)); + TERN_(X2_SENSORLESS, TMC_EDIT_STORED_SGT(X2)); + TERN_( Y_SENSORLESS, TMC_EDIT_STORED_SGT(Y)); + TERN_(Y2_SENSORLESS, TMC_EDIT_STORED_SGT(Y2)); + TERN_( Z_SENSORLESS, TMC_EDIT_STORED_SGT(Z)); + TERN_(Z2_SENSORLESS, TMC_EDIT_STORED_SGT(Z2)); + TERN_(Z3_SENSORLESS, TMC_EDIT_STORED_SGT(Z3)); + TERN_(Z4_SENSORLESS, TMC_EDIT_STORED_SGT(Z4)); + TERN_( I_SENSORLESS, TMC_EDIT_STORED_SGT(I)); + TERN_( J_SENSORLESS, TMC_EDIT_STORED_SGT(J)); + TERN_( K_SENSORLESS, TMC_EDIT_STORED_SGT(K)); END_MENU(); } @@ -192,54 +147,22 @@ void menu_tmc_current() { START_MENU(); STATIC_ITEM(MSG_TMC_STEALTH_ENABLED); BACK_ITEM(MSG_TMC_DRIVERS); - #if AXIS_HAS_STEALTHCHOP(X) - TMC_EDIT_STEP_MODE(X, STR_X); - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - TMC_EDIT_STEP_MODE(Y, STR_Y); - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - TMC_EDIT_STEP_MODE(Z, STR_Z); - #endif - #if AXIS_HAS_STEALTHCHOP(X2) - TMC_EDIT_STEP_MODE(X2, STR_X2); - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - TMC_EDIT_STEP_MODE(Y2, STR_Y2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - TMC_EDIT_STEP_MODE(Z2, STR_Z2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z3) - TMC_EDIT_STEP_MODE(Z3, STR_Z3); - #endif - #if AXIS_HAS_STEALTHCHOP(Z4) - TMC_EDIT_STEP_MODE(Z4, STR_Z4); - #endif - #if AXIS_HAS_STEALTHCHOP(E0) - TMC_EDIT_STEP_MODE(E0, LCD_STR_E0); - #endif - #if AXIS_HAS_STEALTHCHOP(E1) - TMC_EDIT_STEP_MODE(E1, LCD_STR_E1); - #endif - #if AXIS_HAS_STEALTHCHOP(E2) - TMC_EDIT_STEP_MODE(E2, LCD_STR_E2); - #endif - #if AXIS_HAS_STEALTHCHOP(E3) - TMC_EDIT_STEP_MODE(E3, LCD_STR_E3); - #endif - #if AXIS_HAS_STEALTHCHOP(E4) - TMC_EDIT_STEP_MODE(E4, LCD_STR_E4); - #endif - #if AXIS_HAS_STEALTHCHOP(E5) - TMC_EDIT_STEP_MODE(E5, LCD_STR_E5); - #endif - #if AXIS_HAS_STEALTHCHOP(E6) - TMC_EDIT_STEP_MODE(E6, LCD_STR_E6); - #endif - #if AXIS_HAS_STEALTHCHOP(E7) - TMC_EDIT_STEP_MODE(E7, LCD_STR_E7); - #endif + TERN_( X_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(X, STR_X)); + TERN_(X2_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(X2, STR_X2)); + TERN_( Y_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(Y, STR_Y)); + TERN_(Y2_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(Y2, STR_Y2)); + TERN_( Z_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(Z, STR_Z)); + TERN_(Z2_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(Z2, STR_Z2)); + TERN_(Z3_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(Z3, STR_Z3)); + TERN_(Z4_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(Z4, STR_Z4)); + TERN_(E0_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E0, LCD_STR_E0)); + TERN_(E1_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E1, LCD_STR_E1)); + TERN_(E2_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E2, LCD_STR_E2)); + TERN_(E3_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E3, LCD_STR_E3)); + TERN_(E4_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E4, LCD_STR_E4)); + TERN_(E5_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E5, LCD_STR_E5)); + TERN_(E6_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E6, LCD_STR_E6)); + TERN_(E7_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E7, LCD_STR_E7)); END_MENU(); } @@ -247,17 +170,11 @@ void menu_tmc_current() { void menu_tmc() { START_MENU(); - BACK_ITEM(MSG_CONTROL); + BACK_ITEM(MSG_ADVANCED_SETTINGS); SUBMENU(MSG_TMC_CURRENT, menu_tmc_current); - #if ENABLED(HYBRID_THRESHOLD) - SUBMENU(MSG_TMC_HYBRID_THRS, menu_tmc_hybrid_thrs); - #endif - #if ENABLED(SENSORLESS_HOMING) - SUBMENU(MSG_TMC_HOMING_THRS, menu_tmc_homing_thrs); - #endif - #if HAS_STEALTHCHOP - SUBMENU(MSG_TMC_STEPPING_MODE, menu_tmc_step_mode); - #endif + TERN_(HYBRID_THRESHOLD, SUBMENU(MSG_TMC_HYBRID_THRS, menu_tmc_hybrid_thrs)); + TERN_(SENSORLESS_HOMING, SUBMENU(MSG_TMC_HOMING_THRS, menu_tmc_homing_thrs)); + TERN_(HAS_STEALTHCHOP, SUBMENU(MSG_TMC_STEPPING_MODE, menu_tmc_step_mode)); END_MENU(); } diff --git a/Marlin/src/lcd/menu/menu_touch_screen.cpp b/Marlin/src/lcd/menu/menu_touch_screen.cpp index 96eae2298e6c..5fc4b584d51e 100644 --- a/Marlin/src/lcd/menu/menu_touch_screen.cpp +++ b/Marlin/src/lcd/menu/menu_touch_screen.cpp @@ -25,11 +25,11 @@ #if BOTH(HAS_LCD_MENU, TOUCH_SCREEN_CALIBRATION) #include "menu_item.h" -#include "../ultralcd.h" +#include "../marlinui.h" void touch_screen_calibration() { - ui.touch_calibration(); + ui.touch_calibration_screen(); } diff --git a/Marlin/src/lcd/menu/menu_tramming.cpp b/Marlin/src/lcd/menu/menu_tramming.cpp new file mode 100644 index 000000000000..b5868f40566c --- /dev/null +++ b/Marlin/src/lcd/menu/menu_tramming.cpp @@ -0,0 +1,104 @@ +/** + * 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 . + * + */ + +// +// Bed Tramming Wizard +// + +#include "../../inc/MarlinConfigPre.h" + +#if BOTH(HAS_LCD_MENU, ASSISTED_TRAMMING_WIZARD) + +#include "menu_item.h" + +#include "../../feature/tramming.h" + +#include "../../module/motion.h" +#include "../../module/probe.h" +#include "../../gcode/queue.h" + +//#define DEBUG_OUT 1 +#include "../../core/debug_out.h" + +float z_measured[G35_PROBE_COUNT] = { 0 }; +static uint8_t tram_index = 0; + +#if HAS_LEVELING + #include "../../feature/bedlevel/bedlevel.h" +#endif + +static bool probe_single_point() { + do_blocking_move_to_z(TERN(BLTOUCH, Z_CLEARANCE_DEPLOY_PROBE, Z_CLEARANCE_BETWEEN_PROBES)); + // Stow after each point with BLTouch "HIGH SPEED" mode for push-pin safety + const float z_probed_height = probe.probe_at_point(screws_tilt_adjust_pos[tram_index], TERN(BLTOUCH_HS_MODE, PROBE_PT_STOW, PROBE_PT_RAISE), 0, true); + DEBUG_ECHOLNPAIR("probe_single_point: ", z_probed_height, "mm"); + z_measured[tram_index] = z_probed_height; + move_to_tramming_wait_pos(); + + return !isnan(z_probed_height); +} + +static void _menu_single_probe(const uint8_t point) { + tram_index = point; + DEBUG_ECHOLNPAIR("Screen: single probe screen Arg:", point); + START_MENU(); + STATIC_ITEM(MSG_BED_TRAMMING, SS_LEFT); + STATIC_ITEM(MSG_LAST_VALUE_SP, SS_LEFT, ftostr42_52(z_measured[0] - z_measured[point])); // Print diff + ACTION_ITEM(MSG_UBL_BC_INSERT2, []{ if (probe_single_point()) ui.refresh(); }); + ACTION_ITEM(MSG_BUTTON_DONE, []{ ui.goto_previous_screen(); }); // Back + END_MENU(); +} + +static void tramming_wizard_menu() { + DEBUG_ECHOLNPAIR("Screen: tramming_wizard_menu"); + START_MENU(); + STATIC_ITEM(MSG_SELECT_ORIGIN); + + // Draw a menu item for each tramming point + LOOP_L_N(i, G35_PROBE_COUNT) + SUBMENU_N_P(i, (char*)pgm_read_ptr(&tramming_point_name[i]), []{ _menu_single_probe(MenuItemBase::itemIndex); }); + + ACTION_ITEM(MSG_BUTTON_DONE, []{ + probe.stow(); // Stow before exiting Tramming Wizard + ui.goto_previous_screen_no_defer(); + }); + END_MENU(); +} + +// Init the wizard and enter the submenu +void goto_tramming_wizard() { + DEBUG_ECHOLNPAIR("Screen: goto_tramming_wizard", 1); + tram_index = 0; + ui.defer_status_screen(); + + // Inject G28, wait for homing to complete, + set_all_unhomed(); + queue.inject_P(TERN(CAN_SET_LEVELING_AFTER_G28, PSTR("G28L0"), G28_STR)); + + ui.goto_screen([]{ + _lcd_draw_homing(); + if (all_axes_homed()) + ui.goto_screen(tramming_wizard_menu); + }); +} + +#endif // HAS_LCD_MENU && ASSISTED_TRAMMING_WIZARD diff --git a/Marlin/src/lcd/menu/menu_tune.cpp b/Marlin/src/lcd/menu/menu_tune.cpp index 6bf5c3a15d96..3a0d0c81caf8 100644 --- a/Marlin/src/lcd/menu/menu_tune.cpp +++ b/Marlin/src/lcd/menu/menu_tune.cpp @@ -34,12 +34,12 @@ #include "../../module/temperature.h" #include "../../MarlinCore.h" -#if HAS_LEVELING - #include "../../feature/bedlevel/bedlevel.h" +#if ENABLED(SINGLENOZZLE_STANDBY_TEMP) + #include "../../module/tool_change.h" #endif -#if ENABLED(SINGLENOZZLE) - #include "../../module/tool_change.h" +#if HAS_LEVELING + #include "../../feature/bedlevel/bedlevel.h" #endif #if ENABLED(BABYSTEPPING) @@ -47,7 +47,7 @@ #include "../../feature/babystep.h" #include "../lcdprint.h" #if HAS_MARLINUI_U8GLIB - #include "../dogm/ultralcd_DOGM.h" + #include "../dogm/marlinui_DOGM.h" #endif void _lcd_babystep(const AxisEnum axis, PGM_P const msg) { @@ -71,9 +71,16 @@ const bool in_view = TERN1(HAS_MARLINUI_U8GLIB, PAGE_CONTAINS(LCD_PIXEL_HEIGHT - MENU_FONT_HEIGHT, LCD_PIXEL_HEIGHT - 1)); if (in_view) { TERN_(HAS_MARLINUI_U8GLIB, ui.set_font(FONT_MENU)); - lcd_moveto(0, TERN(HAS_MARLINUI_U8GLIB, LCD_PIXEL_HEIGHT - MENU_FONT_DESCENT, LCD_HEIGHT - 1)); - lcd_put_u8str_P(GET_TEXT(MSG_BABYSTEP_TOTAL)); - lcd_put_wchar(':'); + #if ENABLED(TFT_COLOR_UI) + lcd_moveto(4, 3); + lcd_put_u8str_P(GET_TEXT(MSG_BABYSTEP_TOTAL)); + lcd_put_wchar(':'); + lcd_moveto(10, 3); + #else + lcd_moveto(0, TERN(HAS_MARLINUI_U8GLIB, LCD_PIXEL_HEIGHT - MENU_FONT_DESCENT, LCD_HEIGHT - 1)); + lcd_put_u8str_P(GET_TEXT(MSG_BABYSTEP_TOTAL)); + lcd_put_wchar(':'); + #endif lcd_put_u8str(BABYSTEP_TO_STR(spm * babystep.axis_total[BS_TOTAL_IND(axis)])); } #endif @@ -119,15 +126,15 @@ void menu_tune() { // Nozzle [1-4]: // #if HOTENDS == 1 - EDIT_ITEM_FAST(int3, MSG_NOZZLE, &thermalManager.temp_hotend[0].target, 0, HEATER_0_MAXTEMP - HOTEND_OVERSHOOT, []{ thermalManager.start_watching_hotend(0); }); + EDIT_ITEM_FAST(int3, MSG_NOZZLE, &thermalManager.temp_hotend[0].target, 0, thermalManager.hotend_max_target(0), []{ thermalManager.start_watching_hotend(0); }); #elif HAS_MULTI_HOTEND HOTEND_LOOP() - EDIT_ITEM_FAST_N(int3, e, MSG_NOZZLE_N, &thermalManager.temp_hotend[e].target, 0, thermalManager.heater_maxtemp[e] - HOTEND_OVERSHOOT, []{ thermalManager.start_watching_hotend(MenuItemBase::itemIndex); }); + EDIT_ITEM_FAST_N(int3, e, MSG_NOZZLE_N, &thermalManager.temp_hotend[e].target, 0, thermalManager.hotend_max_target(e), []{ thermalManager.start_watching_hotend(MenuItemBase::itemIndex); }); #endif #if ENABLED(SINGLENOZZLE_STANDBY_TEMP) LOOP_S_L_N(e, 1, EXTRUDERS) - EDIT_ITEM_FAST_N(uint16_3, e, MSG_NOZZLE_STANDBY, &singlenozzle_temp[e], 0, thermalManager.heater_maxtemp[0] - HOTEND_OVERSHOOT); + EDIT_ITEM_FAST_N(int3, e, MSG_NOZZLE_STANDBY, &thermalManager.singlenozzle_temp[e], 0, thermalManager.hotend_max_target(0)); #endif // @@ -188,7 +195,7 @@ void menu_tune() { // // Flow: // - #if EXTRUDERS + #if HAS_EXTRUDERS EDIT_ITEM(int3, MSG_FLOW, &planner.flow_percentage[active_extruder], 10, 999, []{ planner.refresh_e_factor(active_extruder); }); // Flow En: #if HAS_MULTI_EXTRUDER @@ -202,10 +209,10 @@ void menu_tune() { // #if ENABLED(LIN_ADVANCE) && DISABLED(SLIM_LCD_MENUS) #if EXTRUDERS == 1 - EDIT_ITEM(float42_52, MSG_ADVANCE_K, &planner.extruder_advance_K[0], 0, 999); + EDIT_ITEM(float42_52, MSG_ADVANCE_K, &planner.extruder_advance_K[0], 0, 10); #elif HAS_MULTI_EXTRUDER LOOP_L_N(n, EXTRUDERS) - EDIT_ITEM_N(float42_52, n, MSG_ADVANCE_K_E, &planner.extruder_advance_K[n], 0, 999); + EDIT_ITEM_N(float42_52, n, MSG_ADVANCE_K_E, &planner.extruder_advance_K[n], 0, 10); #endif #endif diff --git a/Marlin/src/lcd/menu/menu_ubl.cpp b/Marlin/src/lcd/menu/menu_ubl.cpp index f0f5c21beca2..467bd81acfc7 100644 --- a/Marlin/src/lcd/menu/menu_ubl.cpp +++ b/Marlin/src/lcd/menu/menu_ubl.cpp @@ -37,7 +37,7 @@ #include "../../feature/bedlevel/bedlevel.h" static int16_t ubl_storage_slot = 0, - custom_hotend_temp = 190, + custom_hotend_temp = 150, side_points = 3, ubl_fillin_amount = 5, ubl_height_amount = 1; @@ -56,15 +56,27 @@ inline float rounded_mesh_value() { return float(rounded - (rounded % 5L)) / 1000; } -static void _lcd_mesh_fine_tune(PGM_P const msg) { +/** + * This screen displays the temporary mesh value and updates it based on encoder + * movement. While this screen is active ubl.fine_tune_mesh sits in a loop getting + * the current value via ubl_mesh_value, moves the Z axis, and updates the mesh + * value until the encoder button is pressed. + * + * - Update the 'mesh_edit_accumulator' from encoder rotation + * - Draw the mesh value (with draw_edit_screen) + * - Draw the graphical overlay, if enabled. + * - Update the 'refresh' state according to the display type + */ +void _lcd_mesh_fine_tune(PGM_P const msg) { + constexpr float mesh_edit_step = 1.0f / 200.0f; ui.defer_status_screen(); if (ubl.encoder_diff) { mesh_edit_accumulator += TERN(IS_TFTGLCD_PANEL, - ubl.encoder_diff * 0.005f / ENCODER_PULSES_PER_STEP, - ubl.encoder_diff > 0 ? 0.005f : -0.005f + ubl.encoder_diff * mesh_edit_step / ENCODER_PULSES_PER_STEP, + ubl.encoder_diff > 0 ? mesh_edit_step : -mesh_edit_step ); ubl.encoder_diff = 0; - TERN(IS_TFTGLCD_PANEL,,ui.refresh(LCDVIEW_CALL_REDRAW_NEXT)); + IF_DISABLED(IS_TFTGLCD_PANEL, ui.refresh(LCDVIEW_CALL_REDRAW_NEXT)); } TERN_(IS_TFTGLCD_PANEL, ui.refresh(LCDVIEW_CALL_REDRAW_NEXT)); @@ -77,29 +89,19 @@ static void _lcd_mesh_fine_tune(PGM_P const msg) { } // -// Called external to the menu system to acquire the result of an edit. +// Init mesh editing and go to the fine tuning screen (ubl.fine_tune_mesh) +// To capture encoder events UBL will also call ui.capture and ui.release. // -float lcd_mesh_edit() { return rounded_mesh_value(); } - -void lcd_mesh_edit_setup(const float &initial) { - TERN_(HAS_GRAPHICAL_TFT, ui.clear_lcd()); +void MarlinUI::ubl_mesh_edit_start(const_float_t initial) { + TERN_(HAS_GRAPHICAL_TFT, clear_lcd()); mesh_edit_accumulator = initial; - ui.goto_screen([]{ _lcd_mesh_fine_tune(GET_TEXT(MSG_MESH_EDIT_Z)); }); -} - -void _lcd_z_offset_edit() { - _lcd_mesh_fine_tune(GET_TEXT(MSG_UBL_Z_OFFSET)); + goto_screen([]{ _lcd_mesh_fine_tune(GET_TEXT(MSG_MESH_EDIT_Z)); }); } -float lcd_z_offset_edit() { - ui.goto_screen(_lcd_z_offset_edit); - return rounded_mesh_value(); -} - -void lcd_z_offset_edit_setup(const float &initial) { - mesh_edit_accumulator = initial; - ui.goto_screen(_lcd_z_offset_edit); -} +// +// Get the mesh value within a Z adjustment loop (ubl.fine_tune_mesh) +// +float MarlinUI::ubl_mesh_value() { return rounded_mesh_value(); } /** * UBL Build Custom Mesh Command @@ -126,7 +128,7 @@ void _lcd_ubl_custom_mesh() { START_MENU(); BACK_ITEM(MSG_UBL_BUILD_MESH_MENU); #if HAS_HOTEND - EDIT_ITEM(int3, MSG_UBL_HOTEND_TEMP_CUSTOM, &custom_hotend_temp, EXTRUDE_MINTEMP, HEATER_0_MAXTEMP - HOTEND_OVERSHOOT); + EDIT_ITEM(int3, MSG_UBL_HOTEND_TEMP_CUSTOM, &custom_hotend_temp, EXTRUDE_MINTEMP, thermalManager.hotend_max_target(0)); #endif #if HAS_HEATED_BED EDIT_ITEM(int3, MSG_UBL_BED_TEMP_CUSTOM, &custom_bed_temp, BED_MINTEMP, BED_MAX_TARGET); @@ -139,9 +141,9 @@ void _lcd_ubl_custom_mesh() { * UBL Adjust Mesh Height Command */ void _lcd_ubl_adjust_height_cmd() { - char ubl_lcd_gcode[16]; - const int ind = ubl_height_amount > 0 ? 9 : 10; - strcpy_P(ubl_lcd_gcode, PSTR("G29 P6 C -")); + char ubl_lcd_gcode[13]; + const int ind = ubl_height_amount > 0 ? 6 : 7; + strcpy_P(ubl_lcd_gcode, PSTR("G29P6C-")); sprintf_P(&ubl_lcd_gcode[ind], PSTR(".%i"), ABS(ubl_height_amount)); queue.inject(ubl_lcd_gcode); } @@ -174,8 +176,8 @@ void _menu_ubl_height_adjust() { void _lcd_ubl_edit_mesh() { START_MENU(); BACK_ITEM(MSG_UBL_TOOLS); - GCODES_ITEM(MSG_UBL_FINE_TUNE_ALL, PSTR("G29 P4 R999 T")); - GCODES_ITEM(MSG_UBL_FINE_TUNE_CLOSEST, PSTR("G29 P4 T")); + GCODES_ITEM(MSG_UBL_FINE_TUNE_ALL, PSTR("G29P4RT")); + GCODES_ITEM(MSG_UBL_FINE_TUNE_CLOSEST, PSTR("G29P4T")); SUBMENU(MSG_UBL_MESH_HEIGHT_ADJUST, _menu_ubl_height_adjust); ACTION_ITEM(MSG_INFO_SCREEN, ui.return_to_status); END_MENU(); @@ -187,8 +189,8 @@ void _lcd_ubl_edit_mesh() { * UBL Validate Custom Mesh Command */ void _lcd_ubl_validate_custom_mesh() { - char ubl_lcd_gcode[24]; - sprintf_P(ubl_lcd_gcode, PSTR("G28\nG26 C P H%" PRIi16 TERN_(HAS_HEATED_BED, " B%" PRIi16)) + char ubl_lcd_gcode[20]; + sprintf_P(ubl_lcd_gcode, PSTR("G28\nG26CPH%" PRIi16 TERN_(HAS_HEATED_BED, "B%" PRIi16)) , custom_hotend_temp #if HAS_HEATED_BED , custom_bed_temp @@ -211,10 +213,10 @@ void _lcd_ubl_edit_mesh() { #if PREHEAT_COUNT #if HAS_HEATED_BED #define VALIDATE_MESH_GCODE_ITEM(M) \ - GCODES_ITEM_N_S(M, ui.get_preheat_label(M), MSG_UBL_VALIDATE_MESH_M, PSTR("G28\nG26 C P I" STRINGIFY(M))) + GCODES_ITEM_N_S(M, ui.get_preheat_label(M), MSG_UBL_VALIDATE_MESH_M, PSTR("G28\nG26CPI" STRINGIFY(M))) #else #define VALIDATE_MESH_GCODE_ITEM(M) \ - GCODES_ITEM_N_S(M, ui.get_preheat_label(M), MSG_UBL_VALIDATE_MESH_M, PSTR("G28\nG26 C P B0 I" STRINGIFY(M))) + GCODES_ITEM_N_S(M, ui.get_preheat_label(M), MSG_UBL_VALIDATE_MESH_M, PSTR("G28\nG26CPB0I" STRINGIFY(M))) #endif VALIDATE_MESH_GCODE_ITEM(0); @@ -251,7 +253,7 @@ void _lcd_ubl_grid_level() { EDIT_ITEM(int3, MSG_UBL_SIDE_POINTS, &side_points, 2, 6); ACTION_ITEM(MSG_UBL_MESH_LEVEL, []{ char ubl_lcd_gcode[12]; - sprintf_P(ubl_lcd_gcode, PSTR("G29 J%i"), side_points); + sprintf_P(ubl_lcd_gcode, PSTR("G29J%i"), side_points); queue.inject(ubl_lcd_gcode); }); END_MENU(); @@ -268,7 +270,7 @@ void _lcd_ubl_grid_level() { void _lcd_ubl_mesh_leveling() { START_MENU(); BACK_ITEM(MSG_UBL_TOOLS); - GCODES_ITEM(MSG_UBL_3POINT_MESH_LEVELING, PSTR("G29 J0")); + GCODES_ITEM(MSG_UBL_3POINT_MESH_LEVELING, PSTR("G29J0")); SUBMENU(MSG_UBL_GRID_MESH_LEVELING, _lcd_ubl_grid_level); ACTION_ITEM(MSG_INFO_SCREEN, ui.return_to_status); END_MENU(); @@ -279,7 +281,7 @@ void _lcd_ubl_mesh_leveling() { */ void _lcd_ubl_fillin_amount_cmd() { char ubl_lcd_gcode[18]; - sprintf_P(ubl_lcd_gcode, PSTR("G29 P3 R C.%i"), ubl_fillin_amount); + sprintf_P(ubl_lcd_gcode, PSTR("G29P3RC.%i"), ubl_fillin_amount); gcode.process_subcommands_now(ubl_lcd_gcode); } @@ -297,8 +299,8 @@ void _menu_ubl_fillin() { START_MENU(); BACK_ITEM(MSG_UBL_BUILD_MESH_MENU); EDIT_ITEM(int3, MSG_UBL_FILLIN_AMOUNT, &ubl_fillin_amount, 0, 9, _lcd_ubl_fillin_amount_cmd); - GCODES_ITEM(MSG_UBL_SMART_FILLIN, PSTR("G29 P3 T0")); - GCODES_ITEM(MSG_UBL_MANUAL_FILLIN, PSTR("G29 P2 B T0")); + GCODES_ITEM(MSG_UBL_SMART_FILLIN, PSTR("G29P3T0")); + GCODES_ITEM(MSG_UBL_MANUAL_FILLIN, PSTR("G29P2BT0")); ACTION_ITEM(MSG_INFO_SCREEN, ui.return_to_status); END_MENU(); } @@ -326,7 +328,7 @@ void _lcd_ubl_build_mesh() { BACK_ITEM(MSG_UBL_TOOLS); #if PREHEAT_COUNT #if HAS_HEATED_BED - #define PREHEAT_BED_GCODE(M) "M190 I" STRINGIFY(M) "\n" + #define PREHEAT_BED_GCODE(M) "M190I" STRINGIFY(M) "\n" #else #define PREHEAT_BED_GCODE(M) "" #endif @@ -334,10 +336,10 @@ void _lcd_ubl_build_mesh() { PSTR( \ "G28\n" \ PREHEAT_BED_GCODE(M) \ - "M109 I" STRINGIFY(M) "\n" \ - "G29 P1\n" \ - "M104 S0\n" \ - "M140 S0" \ + "M109I" STRINGIFY(M) "\n" \ + "G29P1\n" \ + "M104S0\n" \ + "M140S0" \ ) ) BUILD_MESH_GCODE_ITEM(0); #if PREHEAT_COUNT > 1 @@ -355,11 +357,11 @@ void _lcd_ubl_build_mesh() { #endif // PREHEAT_COUNT SUBMENU(MSG_UBL_BUILD_CUSTOM_MESH, _lcd_ubl_custom_mesh); - GCODES_ITEM(MSG_UBL_BUILD_COLD_MESH, PSTR("G28\nG29 P1")); + GCODES_ITEM(MSG_UBL_BUILD_COLD_MESH, PSTR("G29NP1")); SUBMENU(MSG_UBL_FILLIN_MESH, _menu_ubl_fillin); - GCODES_ITEM(MSG_UBL_CONTINUE_MESH, PSTR("G29 P1 C")); + GCODES_ITEM(MSG_UBL_CONTINUE_MESH, PSTR("G29P1C")); ACTION_ITEM(MSG_UBL_INVALIDATE_ALL, _lcd_ubl_invalidate); - GCODES_ITEM(MSG_UBL_INVALIDATE_CLOSEST, PSTR("G29 I")); + GCODES_ITEM(MSG_UBL_INVALIDATE_CLOSEST, PSTR("G29I")); ACTION_ITEM(MSG_INFO_SCREEN, ui.return_to_status); END_MENU(); } @@ -369,7 +371,7 @@ void _lcd_ubl_build_mesh() { */ inline void _lcd_ubl_load_save_cmd(const char loadsave, PGM_P const msg) { char ubl_lcd_gcode[40]; - sprintf_P(ubl_lcd_gcode, PSTR("G29 %c%i\nM117 "), loadsave, ubl_storage_slot); + sprintf_P(ubl_lcd_gcode, PSTR("G29%c%i\nM117 "), loadsave, ubl_storage_slot); sprintf_P(&ubl_lcd_gcode[strlen(ubl_lcd_gcode)], msg, ubl_storage_slot); gcode.process_subcommands_now(ubl_lcd_gcode); } @@ -405,7 +407,7 @@ void _lcd_ubl_map_edit_cmd() { char ubl_lcd_gcode[50], str[10], str2[10]; dtostrf(ubl.mesh_index_to_xpos(x_plot), 0, 2, str); dtostrf(ubl.mesh_index_to_ypos(y_plot), 0, 2, str2); - snprintf_P(ubl_lcd_gcode, sizeof(ubl_lcd_gcode), PSTR("G29 P4 X%s Y%s R%i"), str, str2, int(n_edit_pts)); + snprintf_P(ubl_lcd_gcode, sizeof(ubl_lcd_gcode), PSTR("G29P4X%sY%sR%i"), str, str2, int(n_edit_pts)); queue.inject(ubl_lcd_gcode); } @@ -413,6 +415,10 @@ void _lcd_ubl_map_edit_cmd() { * UBL LCD Map Movement */ void ubl_map_move_to_xy() { + const xy_pos_t xy = { ubl.mesh_index_to_xpos(x_plot), ubl.mesh_index_to_ypos(y_plot) }; + + // Some printers have unreachable areas in the mesh. Skip the move if unreachable. + if (!position_is_reachable(xy)) return; #if ENABLED(DELTA) if (current_position.z > delta_clip_start_height) { // Make sure the delta has fully free motion @@ -422,11 +428,9 @@ void ubl_map_move_to_xy() { } #endif - // Set the nozzle position to the mesh point - current_position.set(ubl.mesh_index_to_xpos(x_plot), ubl.mesh_index_to_ypos(y_plot)); - - // Use the built-in manual move handler - ui.manual_move.soon(ALL_AXES); + // Use the built-in manual move handler to move to the mesh point. + ui.manual_move.set_destination(xy); + ui.manual_move.soon(ALL_AXES_ENUM); } inline int32_t grid_index(const uint8_t x, const uint8_t y) { @@ -474,14 +478,14 @@ void ubl_map_screen() { if (position_is_reachable(xy)) break; // Found a valid point ui.encoderPosition += step_dir; // Test the next point #endif - } while(ENABLED(IS_KINEMATIC)); + } while (ENABLED(IS_KINEMATIC)); // Determine number of points to edit #if IS_KINEMATIC n_edit_pts = 9; // TODO: Delta accessible edit points #else - const bool xc = WITHIN(x, 1, GRID_MAX_POINTS_X - 2), - yc = WITHIN(y, 1, GRID_MAX_POINTS_Y - 2); + const bool xc = WITHIN(x, 1, (GRID_MAX_POINTS_X) - 2), + yc = WITHIN(y, 1, (GRID_MAX_POINTS_Y) - 2); n_edit_pts = yc ? (xc ? 9 : 6) : (xc ? 6 : 4); // Corners #endif @@ -524,7 +528,7 @@ void _ubl_map_screen_homing() { */ void _ubl_goto_map_screen() { if (planner.movesplanned()) return; // The ACTION_ITEM will do nothing - if (!all_axes_known()) { + if (!all_axes_trusted()) { set_all_unhomed(); queue.inject_P(G28_STR); } @@ -542,9 +546,9 @@ void _ubl_goto_map_screen() { void _lcd_ubl_output_map() { START_MENU(); BACK_ITEM(MSG_UBL_LEVEL_BED); - GCODES_ITEM(MSG_UBL_OUTPUT_MAP_HOST, PSTR("G29 T0")); - GCODES_ITEM(MSG_UBL_OUTPUT_MAP_CSV, PSTR("G29 T1")); - GCODES_ITEM(MSG_UBL_OUTPUT_MAP_BACKUP, PSTR("G29 S-1")); + GCODES_ITEM(MSG_UBL_OUTPUT_MAP_HOST, PSTR("G29T0")); + GCODES_ITEM(MSG_UBL_OUTPUT_MAP_CSV, PSTR("G29T1")); + GCODES_ITEM(MSG_UBL_OUTPUT_MAP_BACKUP, PSTR("G29S-1")); END_MENU(); } @@ -561,7 +565,7 @@ void _menu_ubl_tools() { START_MENU(); BACK_ITEM(MSG_UBL_LEVEL_BED); SUBMENU(MSG_UBL_BUILD_MESH_MENU, _lcd_ubl_build_mesh); - GCODES_ITEM(MSG_UBL_MANUAL_MESH, PSTR("G29 I999\nG29 P2 B T0")); + GCODES_ITEM(MSG_UBL_MANUAL_MESH, PSTR("G29I999\nG29P2BT0")); #if ENABLED(G26_MESH_VALIDATION) SUBMENU(MSG_UBL_VALIDATE_MESH_MENU, _lcd_ubl_validate_mesh); #endif @@ -587,18 +591,63 @@ void _menu_ubl_tools() { void _lcd_ubl_step_by_step() { START_MENU(); BACK_ITEM(MSG_UBL_LEVEL_BED); - GCODES_ITEM(MSG_UBL_1_BUILD_COLD_MESH, PSTR("G28\nG29 P1")); - GCODES_ITEM(MSG_UBL_2_SMART_FILLIN, PSTR("G29 P3 T0")); + GCODES_ITEM(MSG_UBL_1_BUILD_COLD_MESH, PSTR("G29NP1")); + GCODES_ITEM(MSG_UBL_2_SMART_FILLIN, PSTR("G29P3T0")); SUBMENU(MSG_UBL_3_VALIDATE_MESH_MENU, _lcd_ubl_validate_mesh); - GCODES_ITEM(MSG_UBL_4_FINE_TUNE_ALL, PSTR("G29 P4 R999 T")); + GCODES_ITEM(MSG_UBL_4_FINE_TUNE_ALL, PSTR("G29P4RT")); SUBMENU(MSG_UBL_5_VALIDATE_MESH_MENU, _lcd_ubl_validate_mesh); - GCODES_ITEM(MSG_UBL_6_FINE_TUNE_ALL, PSTR("G29 P4 R999 T")); + GCODES_ITEM(MSG_UBL_6_FINE_TUNE_ALL, PSTR("G29P4RT")); ACTION_ITEM(MSG_UBL_7_SAVE_MESH, _lcd_ubl_save_mesh_cmd); END_MENU(); } #endif +#if ENABLED(UBL_MESH_WIZARD) + + /** + * UBL Mesh Wizard - One-click mesh creation with or without a probe + */ + void _lcd_ubl_mesh_wizard() { + char ubl_lcd_gcode[30]; + #if HAS_HEATED_BED && HAS_HOTEND + sprintf_P(ubl_lcd_gcode, PSTR("M1004B%iH%iS%i"), custom_bed_temp, custom_hotend_temp, ubl_storage_slot); + #elif HAS_HOTEND + sprintf_P(ubl_lcd_gcode, PSTR("M1004H%iS%i"), custom_hotend_temp, ubl_storage_slot); + #else + sprintf_P(ubl_lcd_gcode, PSTR("M1004S%i"), ubl_storage_slot); + #endif + queue.inject(ubl_lcd_gcode); + ui.return_to_status(); + } + + void _menu_ubl_mesh_wizard() { + const int16_t total_slots = settings.calc_num_meshes(); + START_MENU(); + BACK_ITEM(MSG_UBL_LEVEL_BED); + + #if HAS_HOTEND + EDIT_ITEM(int3, MSG_UBL_HOTEND_TEMP_CUSTOM, &custom_hotend_temp, HEATER_0_MINTEMP + 20, thermalManager.hotend_max_target(0)); + #endif + + #if HAS_HEATED_BED + EDIT_ITEM(int3, MSG_UBL_BED_TEMP_CUSTOM, &custom_bed_temp, BED_MINTEMP + 20, BED_MAX_TARGET); + #endif + + EDIT_ITEM(int3, MSG_UBL_STORAGE_SLOT, &ubl_storage_slot, 0, total_slots); + + ACTION_ITEM(MSG_UBL_MESH_WIZARD, _lcd_ubl_mesh_wizard); + + #if ENABLED(G26_MESH_VALIDATION) + SUBMENU(MSG_UBL_VALIDATE_MESH_MENU, _lcd_ubl_validate_mesh); + #endif + + ACTION_ITEM(MSG_INFO_SCREEN, ui.return_to_status); + END_MENU(); + } + +#endif + /** * UBL System submenu * @@ -616,17 +665,20 @@ void _lcd_ubl_level_bed() { START_MENU(); BACK_ITEM(MSG_MOTION); if (planner.leveling_active) - GCODES_ITEM(MSG_UBL_DEACTIVATE_MESH, PSTR("G29 D")); + GCODES_ITEM(MSG_UBL_DEACTIVATE_MESH, PSTR("G29D")); else - GCODES_ITEM(MSG_UBL_ACTIVATE_MESH, PSTR("G29 A")); + GCODES_ITEM(MSG_UBL_ACTIVATE_MESH, PSTR("G29A")); #if ENABLED(G26_MESH_VALIDATION) SUBMENU(MSG_UBL_STEP_BY_STEP_MENU, _lcd_ubl_step_by_step); #endif + #if ENABLED(UBL_MESH_WIZARD) + SUBMENU(MSG_UBL_MESH_WIZARD, _menu_ubl_mesh_wizard); + #endif ACTION_ITEM(MSG_UBL_MESH_EDIT, _ubl_goto_map_screen); SUBMENU(MSG_UBL_STORAGE_MESH_MENU, _lcd_ubl_storage_mesh); SUBMENU(MSG_UBL_OUTPUT_MAP, _lcd_ubl_output_map); SUBMENU(MSG_UBL_TOOLS, _menu_ubl_tools); - GCODES_ITEM(MSG_UBL_INFO_UBL, PSTR("G29 W")); + GCODES_ITEM(MSG_UBL_INFO_UBL, PSTR("G29W")); #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) editable.decimal = planner.z_fade_height; EDIT_ITEM_FAST(float3, MSG_Z_FADE_HEIGHT, &editable.decimal, 0, 100, []{ set_z_fade_height(editable.decimal); }); diff --git a/Marlin/src/lcd/scaled_tft.h b/Marlin/src/lcd/scaled_tft.h index 2c05e5f26d81..54bf6f8d1342 100644 --- a/Marlin/src/lcd/scaled_tft.h +++ b/Marlin/src/lcd/scaled_tft.h @@ -49,7 +49,7 @@ #define TFT_PIXEL_OFFSET_X 48 #endif #endif + #ifndef TFT_PIXEL_OFFSET_Y - // 32 is better for both 320x240 and 480x320 - #define TFT_PIXEL_OFFSET_Y 32 + #define TFT_PIXEL_OFFSET_Y 32 // 32 is best for both 320x240 and 480x320 #endif diff --git a/Marlin/src/lcd/tft/bitmaps/btn_42x39_rounded.bmp b/Marlin/src/lcd/tft/bitmaps/btn_42x39_rounded.bmp new file mode 100644 index 000000000000..a89c7964e9fc Binary files /dev/null and b/Marlin/src/lcd/tft/bitmaps/btn_42x39_rounded.bmp differ diff --git a/Marlin/src/lcd/tft/canvas.cpp b/Marlin/src/lcd/tft/canvas.cpp index f6a5046b8d04..e8b89bad7060 100644 --- a/Marlin/src/lcd/tft/canvas.cpp +++ b/Marlin/src/lcd/tft/canvas.cpp @@ -50,7 +50,7 @@ bool CANVAS::ToScreen() { } void CANVAS::SetBackground(uint16_t color) { - /* TODO: test and optimize perfomance */ + /* TODO: test and optimize performance */ /* uint32_t count = (endLine - startLine) * width; uint16_t *pixel = buffer; @@ -79,7 +79,7 @@ void CANVAS::AddText(uint16_t x, uint16_t y, uint16_t color, uint8_t *string, ui void CANVAS::AddImage(int16_t x, int16_t y, MarlinImage image, uint16_t *colors) { uint16_t *data = (uint16_t *)Images[image].data; - if (data == NULL) return; + if (!data) return; uint16_t image_width = Images[image].width, image_height = Images[image].height; @@ -95,7 +95,7 @@ void CANVAS::AddImage(int16_t x, int16_t y, MarlinImage image, uint16_t *colors) if (line >= startLine && line < endLine) { uint16_t *pixel = buffer + x + (line - startLine) * width; for (int16_t j = 0; j < image_width; j++) { - if ((x + j >= 0) && (x + j < width)) *pixel = *data; + if ((x + j >= 0) && (x + j < width)) *pixel = ENDIAN_COLOR(*data); pixel++; data++; } diff --git a/Marlin/src/lcd/tft/fontdata/fontdata_10x20.cpp b/Marlin/src/lcd/tft/fontdata/fontdata_10x20.cpp index cc328e885d41..f03366d6f72f 100644 --- a/Marlin/src/lcd/tft/fontdata/fontdata_10x20.cpp +++ b/Marlin/src/lcd/tft/fontdata/fontdata_10x20.cpp @@ -1,6 +1,9 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * 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 diff --git a/Marlin/src/lcd/tft/fontdata/fontdata_ISO10646_1.cpp b/Marlin/src/lcd/tft/fontdata/fontdata_ISO10646_1.cpp index ade8bf23b8e4..21531f5c142f 100644 --- a/Marlin/src/lcd/tft/fontdata/fontdata_ISO10646_1.cpp +++ b/Marlin/src/lcd/tft/fontdata/fontdata_ISO10646_1.cpp @@ -1,6 +1,9 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * 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 diff --git a/Marlin/src/lcd/tft/fontdata/helvetica_12_bold.cpp b/Marlin/src/lcd/tft/fontdata/helvetica_12_bold.cpp index 12efb3ba4947..e7411ea9ed28 100644 --- a/Marlin/src/lcd/tft/fontdata/helvetica_12_bold.cpp +++ b/Marlin/src/lcd/tft/fontdata/helvetica_12_bold.cpp @@ -1,6 +1,9 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * 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 diff --git a/Marlin/src/lcd/tft/fontdata/helvetica_14.cpp b/Marlin/src/lcd/tft/fontdata/helvetica_14.cpp index a27ea4369793..87e7135e379e 100644 --- a/Marlin/src/lcd/tft/fontdata/helvetica_14.cpp +++ b/Marlin/src/lcd/tft/fontdata/helvetica_14.cpp @@ -1,6 +1,9 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * 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 diff --git a/Marlin/src/lcd/tft/images/btn_rounded_42x39x4.cpp b/Marlin/src/lcd/tft/images/btn_rounded_42x39x4.cpp new file mode 100644 index 000000000000..bd7b9220ebaa --- /dev/null +++ b/Marlin/src/lcd/tft/images/btn_rounded_42x39x4.cpp @@ -0,0 +1,69 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_GRAPHICAL_TFT + +extern const uint8_t btn_rounded_42x39x4[819] = { + 0x87, 0x87, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x78, 0x78, + 0x87, 0x77, 0xAB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xB9, 0x77, 0x78, + 0x87, 0x8E, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xD7, 0x68, + 0x87, 0xFF, 0x84, 0x32, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x37, 0xFF, 0x57, + 0x7B, 0xF6, 0x34, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x43, 0x6F, 0x95, + 0x7D, 0xC3, 0x45, 0x56, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x4D, 0xC4, + 0x7E, 0xC3, 0x56, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x6D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7D, 0xD3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x77, 0x7E, 0xC3, + 0x88, 0xFA, 0x56, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0xCF, 0x64, + 0x86, 0xBF, 0xDB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xCE, 0xFB, 0x34, + 0x87, 0x57, 0xEF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0x74, 0x45, + 0x87, 0x75, 0x33, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x33, 0x34, 0x56, + 0x87, 0x77, 0x65, 0x54, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x55, 0x67, + 0x87, 0x87, 0x77, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x67, 0x78 +}; + +#endif // HAS_GRAPHICAL_TFT diff --git a/Marlin/src/lcd/tft/tft.h b/Marlin/src/lcd/tft/tft.h index ed3d5e35c157..1576518b4bb7 100644 --- a/Marlin/src/lcd/tft/tft.h +++ b/Marlin/src/lcd/tft/tft.h @@ -30,12 +30,25 @@ #include "../../inc/MarlinConfig.h" +#if ENABLED(TFT_INTERFACE_FSMC_8BIT) + // When we have a 8 bit interface, we need to invert the bytes of the color + #define ENDIAN_COLOR(C) (((C) >> 8) | ((C) << 8)) +#else + #define ENDIAN_COLOR(C) (C) +#endif + #if HAS_UI_320x240 #define TFT_WIDTH 320 #define TFT_HEIGHT 240 #elif HAS_UI_480x320 #define TFT_WIDTH 480 #define TFT_HEIGHT 320 +#elif HAS_UI_480x272 + #define TFT_WIDTH 480 + #define TFT_HEIGHT 272 +#elif HAS_UI_1024x600 + #define TFT_WIDTH 1024 + #define TFT_HEIGHT 600 #else #error "Unsupported display resolution!" #endif @@ -86,6 +99,7 @@ class TFT { static inline void add_image(int16_t x, int16_t y, MarlinImage image, uint16_t color_main = COLOR_WHITE, uint16_t color_background = COLOR_BACKGROUND, uint16_t color_shadow = COLOR_BLACK) { queue.add_image(x, y, image, color_main, color_background, color_shadow); } static inline void add_bar(uint16_t x, uint16_t y, uint16_t width, uint16_t height, uint16_t color) { queue.add_bar(x, y, width, height, color); } static inline void add_rectangle(uint16_t x, uint16_t y, uint16_t width, uint16_t height, uint16_t color) { queue.add_rectangle(x, y, width, height, color); } + static void draw_edit_screen_buttons(); }; extern TFT tft; diff --git a/Marlin/src/lcd/tft/tft_color.h b/Marlin/src/lcd/tft/tft_color.h index a72a079f6ee4..a8668179e579 100644 --- a/Marlin/src/lcd/tft/tft_color.h +++ b/Marlin/src/lcd/tft/tft_color.h @@ -30,7 +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) -// see https://ee-programming-notepad.blogspot.com/2016/10/16-bit-color-generator-picker.html +// 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 #define COLOR_BLACK 0x0000 // #000000 #define COLOR_WHITE 0xFFFF // #FFFFFF @@ -38,7 +39,7 @@ #define COLOR_GREY 0x7BEF // #808080 #define COLOR_DARKGREY 0x4208 // #404040 #define COLOR_DARKGREY2 0x39E7 // #303030 -#define COLOR_DARK 0x0003 // Some dark color +#define COLOR_DARK 0x0003 // #000019 #define COLOR_RED 0xF800 // #FF0000 #define COLOR_SCARLET 0xF904 // #FF2020 @@ -51,7 +52,7 @@ #define COLOR_CYAN 0x07FF // #00FFFF #define COLOR_AQUA 0x07FF // #00FFFF #define COLOR_DODGER_BLUE 0x041F // #0080FF -#define COLOR_VIVID_VIOLET 0x7933 // #772399 +#define COLOR_VIVID_VIOLET 0x7933 // #772399 #define COLOR_DARK_PURPLE 0x9930 // #992380 @@ -73,10 +74,10 @@ #define COLOR_BACKGROUND 0x20AC // #1E156E #endif #ifndef COLOR_SELECTION_BG - #define COLOR_SELECTION_BG 0x9930 // #992380 + #define COLOR_SELECTION_BG 0x9930 // #992380 #endif #ifndef COLOR_WEBSITE_URL - #define COLOR_WEBSITE_URL 0x03B7 + #define COLOR_WEBSITE_URL 0x03B7 // #0075BD #endif #ifndef COLOR_INACTIVE @@ -94,6 +95,9 @@ #ifndef COLOR_CHAMBER #define COLOR_CHAMBER COLOR_DARK_ORANGE #endif +#ifndef COLOR_COOLER + #define COLOR_COOLER COLOR_DARK_ORANGE +#endif #ifndef COLOR_FAN #define COLOR_FAN COLOR_AQUA #endif diff --git a/Marlin/src/lcd/tft/tft_image.cpp b/Marlin/src/lcd/tft/tft_image.cpp index 27749cb7f3ae..3651899dd717 100644 --- a/Marlin/src/lcd/tft/tft_image.cpp +++ b/Marlin/src/lcd/tft/tft_image.cpp @@ -20,17 +20,23 @@ * */ +#include "../../inc/MarlinConfigPre.h" + +#if HAS_GRAPHICAL_TFT + #include "tft_image.h" -#include +#include "ui_common.h" -const tImage NoLogo = { (void *)NULL, 0, 0, NOCOLORS }; +const tImage NoLogo = { nullptr, 0, 0, NOCOLORS }; -const tImage MarlinLogo112x38x1 = { (void *)marlin_logo_112x38x1, 112, 38, GREYSCALE1 }; -const tImage MarlinLogo228x255x2 = { (void *)marlin_logo_228x255x2, 228, 255, GREYSCALE2 }; -const tImage MarlinLogo228x255x4 = { (void *)marlin_logo_228x255x4, 228, 255, GREYSCALE4 }; -const tImage MarlinLogo195x59x16 = { (void *)marlin_logo_195x59x16, 195, 59, HIGHCOLOR }; -const tImage MarlinLogo320x240x16 = { (void *)marlin_logo_320x240x16, 320, 240, HIGHCOLOR }; -const tImage MarlinLogo480x320x16 = { (void *)marlin_logo_480x320x16, 480, 320, HIGHCOLOR }; +#if ENABLED(SHOW_BOOTSCREEN) + const tImage MarlinLogo112x38x1 = { (void *)marlin_logo_112x38x1, 112, 38, GREYSCALE1 }; + const tImage MarlinLogo228x255x2 = { (void *)marlin_logo_228x255x2, 228, 255, GREYSCALE2 }; + const tImage MarlinLogo228x255x4 = { (void *)marlin_logo_228x255x4, 228, 255, GREYSCALE4 }; + const tImage MarlinLogo195x59x16 = { (void *)marlin_logo_195x59x16, 195, 59, HIGHCOLOR }; + const tImage MarlinLogo320x240x16 = { (void *)marlin_logo_320x240x16, 320, 240, HIGHCOLOR }; + const tImage MarlinLogo480x320x16 = { (void *)marlin_logo_480x320x16, 480, 320, HIGHCOLOR }; +#endif const tImage Background320x30x16 = { (void *)background_320x30x16, 320, 30, HIGHCOLOR }; const tImage HotEnd_64x64x4 = { (void *)hotend_64x64x4, 64, 64, GREYSCALE4 }; @@ -47,6 +53,7 @@ const tImage Fan_Fast1_64x64x4 = { (void *)fan_fast1_64x64x4, 64, 64, GREYS const tImage SD_64x64x4 = { (void *)sd_64x64x4, 64, 64, GREYSCALE4 }; const tImage Home_64x64x4 = { (void *)home_64x64x4, 64, 64, GREYSCALE4 }; const tImage BtnRounded_64x52x4 = { (void *)btn_rounded_64x52x4, 64, 52, GREYSCALE4 }; +const tImage BtnRounded_42x39x4 = { (void *)btn_rounded_42x39x4, 42, 39, GREYSCALE4 }; const tImage Menu_64x64x4 = { (void *)menu_64x64x4, 64, 64, GREYSCALE4 }; const tImage Settings_64x64x4 = { (void *)settings_64x64x4, 64, 64, GREYSCALE4 }; const tImage Confirm_64x64x4 = { (void *)confirm_64x64x4, 64, 64, GREYSCALE4 }; @@ -68,4 +75,39 @@ const tImage Leveling_32x32x4 = { (void *)leveling_32x32x4, 32, 32, GREYSC const tImage Slider8x16x4 = { (void *)slider_8x16x4, 8, 16, GREYSCALE4 }; -extern const tImage Images[imgCount]; +const tImage Images[imgCount] = { + TERN(SHOW_BOOTSCREEN, TERN(BOOT_MARLIN_LOGO_SMALL, MarlinLogo195x59x16, MARLIN_LOGO_FULL_SIZE), NoLogo), + HotEnd_64x64x4, + Bed_64x64x4, + Bed_Heated_64x64x4, + Chamber_64x64x4, + Chamber_Heated_64x64x4, + Fan0_64x64x4, + Fan_Slow0_64x64x4, + Fan_Slow1_64x64x4, + Fan_Fast0_64x64x4, + Fan_Fast1_64x64x4, + Feedrate_32x32x4, + Flowrate_32x32x4, + SD_64x64x4, + Menu_64x64x4, + Settings_64x64x4, + Directory_32x32x4, + Confirm_64x64x4, + Cancel_64x64x4, + Increase_64x64x4, + Decrease_64x64x4, + Back_32x32x4, + Up_32x32x4, + Down_32x32x4, + Left_32x32x4, + Right_32x32x4, + Refresh_32x32x4, + Leveling_32x32x4, + Slider8x16x4, + Home_64x64x4, + BtnRounded_64x52x4, + BtnRounded_42x39x4, +}; + +#endif // HAS_GRAPHICAL_TFT diff --git a/Marlin/src/lcd/tft/tft_image.h b/Marlin/src/lcd/tft/tft_image.h index 1f13967ba248..de046fb0c4c2 100644 --- a/Marlin/src/lcd/tft/tft_image.h +++ b/Marlin/src/lcd/tft/tft_image.h @@ -21,8 +21,9 @@ */ #pragma once -#include "stdint.h" +#include "../../inc/MarlinConfigPre.h" +#include extern const uint8_t marlin_logo_112x38x1[]; extern const uint8_t marlin_logo_228x255x2[]; @@ -41,6 +42,7 @@ extern const uint8_t fan_fast0_64x64x4[], fan_fast1_64x64x4[]; extern const uint8_t sd_64x64x4[]; extern const uint8_t home_64x64x4[]; extern const uint8_t btn_rounded_64x52x4[]; +extern const uint8_t btn_rounded_42x39x4[]; extern const uint8_t menu_64x64x4[]; extern const uint8_t settings_64x64x4[]; extern const uint8_t confirm_64x64x4[]; @@ -94,6 +96,7 @@ enum MarlinImage : uint8_t { imgSlider, imgHome, imgBtn52Rounded, + imgBtn39Rounded, imgCount, noImage = imgCount, imgPageUp = imgLeft, @@ -120,12 +123,14 @@ typedef struct __attribute__((__packed__)) { extern const tImage NoLogo; -extern const tImage MarlinLogo112x38x1; -extern const tImage MarlinLogo228x255x2; -extern const tImage MarlinLogo228x255x4; -extern const tImage MarlinLogo195x59x16; -extern const tImage MarlinLogo320x240x16; -extern const tImage MarlinLogo480x320x16; +#if ENABLED(SHOW_BOOTSCREEN) + extern const tImage MarlinLogo112x38x1; + extern const tImage MarlinLogo228x255x2; + extern const tImage MarlinLogo228x255x4; + extern const tImage MarlinLogo195x59x16; + extern const tImage MarlinLogo320x240x16; + extern const tImage MarlinLogo480x320x16; +#endif extern const tImage Background320x30x16; extern const tImage HotEnd_64x64x4; @@ -142,6 +147,7 @@ extern const tImage Fan_Fast1_64x64x4; extern const tImage SD_64x64x4; extern const tImage Home_64x64x4; extern const tImage BtnRounded_64x52x4; +extern const tImage BtnRounded_42x39x4; extern const tImage Menu_64x64x4; extern const tImage Settings_64x64x4; extern const tImage Confirm_64x64x4; diff --git a/Marlin/src/lcd/tft/tft_queue.cpp b/Marlin/src/lcd/tft/tft_queue.cpp index e77afaf716bf..3f604005f9e5 100644 --- a/Marlin/src/lcd/tft/tft_queue.cpp +++ b/Marlin/src/lcd/tft/tft_queue.cpp @@ -30,19 +30,21 @@ uint8_t TFT_Queue::queue[]; uint8_t *TFT_Queue::end_of_queue = queue; -uint8_t *TFT_Queue::current_task = NULL; -uint8_t *TFT_Queue::last_task = NULL; +uint8_t *TFT_Queue::current_task = nullptr; +uint8_t *TFT_Queue::last_task = nullptr; +uint8_t *TFT_Queue::last_parameter = nullptr; void TFT_Queue::reset() { tft.abort(); end_of_queue = queue; - current_task = NULL; - last_task = NULL; + current_task = nullptr; + last_task = nullptr; + last_parameter = nullptr; } void TFT_Queue::async() { - if (current_task == NULL) return; + if (!current_task) return; queueTask_t *task = (queueTask_t *)current_task; // Check IO busy status @@ -63,7 +65,7 @@ void TFT_Queue::async() { } void TFT_Queue::finish_sketch() { - if (last_task == NULL) return; + if (!last_task) return; queueTask_t *task = (queueTask_t *)last_task; if (task->state == TASK_STATE_SKETCH) { @@ -71,7 +73,7 @@ void TFT_Queue::finish_sketch() { task->nextTask = end_of_queue; task->state = TASK_STATE_READY; - if (current_task == NULL) current_task = (uint8_t *)task; + if (!current_task) current_task = (uint8_t *)task; } } @@ -113,55 +115,33 @@ void TFT_Queue::canvas(queueTask_t *task) { switch (*item) { case CANVAS_SET_BACKGROUND: Canvas.SetBackground(((parametersCanvasBackground_t *)item)->color); - item += sizeof(parametersCanvasBackground_t); break; case CANVAS_ADD_TEXT: Canvas.AddText(((parametersCanvasText_t *)item)->x, ((parametersCanvasText_t *)item)->y, ((parametersCanvasText_t *)item)->color, item + sizeof(parametersCanvasText_t), ((parametersCanvasText_t *)item)->maxWidth); - item += sizeof(parametersCanvasText_t) + ((parametersCanvasText_t *)item)->stringLength; break; case CANVAS_ADD_IMAGE: MarlinImage image; uint16_t *colors; - colorMode_t color_mode; image = ((parametersCanvasImage_t *)item)->image; colors = (uint16_t *)(item + sizeof(parametersCanvasImage_t)); Canvas.AddImage(((parametersCanvasImage_t *)item)->x, ((parametersCanvasImage_t *)item)->y, image, colors); - - item = (uint8_t *)colors; - color_mode = Images[image].colorMode; - - switch (color_mode) { - case GREYSCALE1: - item += sizeof(uint16_t); - break; - case GREYSCALE2: - item += sizeof(uint16_t) * 3; - break; - case GREYSCALE4: - item += sizeof(uint16_t) * 15; - break; - default: - break; - } break; case CANVAS_ADD_BAR: Canvas.AddBar(((parametersCanvasBar_t *)item)->x, ((parametersCanvasBar_t *)item)->y, ((parametersCanvasBar_t *)item)->width, ((parametersCanvasBar_t *)item)->height, ((parametersCanvasBar_t *)item)->color); - item += sizeof(parametersCanvasBar_t); break; case CANVAS_ADD_RECTANGLE: Canvas.AddRectangle(((parametersCanvasRectangle_t *)item)->x, ((parametersCanvasRectangle_t *)item)->y, ((parametersCanvasRectangle_t *)item)->width, ((parametersCanvasRectangle_t *)item)->height, ((parametersCanvasRectangle_t *)item)->color); - item += sizeof(parametersCanvasRectangle_t); break; } + item = ((parametersCanvasBackground_t *)item)->nextParameter; } if (Canvas.ToScreen()) task->state = TASK_STATE_COMPLETED; } - void TFT_Queue::fill(uint16_t x, uint16_t y, uint16_t width, uint16_t height, uint16_t color) { finish_sketch(); @@ -172,11 +152,12 @@ void TFT_Queue::fill(uint16_t x, uint16_t y, uint16_t width, uint16_t height, ui parametersFill_t *task_parameters = (parametersFill_t *)end_of_queue; end_of_queue += sizeof(parametersFill_t); + last_parameter = end_of_queue; task_parameters->x = x; task_parameters->y = y; task_parameters->width = width; task_parameters->height = height; - task_parameters->color = color; + task_parameters->color = ENDIAN_COLOR(color); task_parameters->count = width * height; *end_of_queue = TASK_END_OF_QUEUE; @@ -184,7 +165,7 @@ void TFT_Queue::fill(uint16_t x, uint16_t y, uint16_t width, uint16_t height, ui task->state = TASK_STATE_READY; task->type = TASK_FILL; - if (current_task == NULL) current_task = (uint8_t *)task; + if (!current_task) current_task = (uint8_t *)task; } void TFT_Queue::canvas(uint16_t x, uint16_t y, uint16_t width, uint16_t height) { @@ -195,42 +176,57 @@ void TFT_Queue::canvas(uint16_t x, uint16_t y, uint16_t width, uint16_t height) task->state = TASK_STATE_SKETCH; task->type = TASK_CANVAS; - task->nextTask = NULL; + task->nextTask = nullptr; end_of_queue += sizeof(queueTask_t); parametersCanvas_t *task_parameters = (parametersCanvas_t *)end_of_queue; end_of_queue += sizeof(parametersCanvas_t); + last_parameter = end_of_queue; task_parameters->x = x; task_parameters->y = y; task_parameters->width = width; task_parameters->height = height; task_parameters->count = 0; - if (current_task == NULL) current_task = (uint8_t *)task; + if (!current_task) current_task = (uint8_t *)task; } void TFT_Queue::set_background(uint16_t color) { + handle_queue_overflow(sizeof(parametersCanvasBackground_t)); parametersCanvas_t *task_parameters = (parametersCanvas_t *)(((uint8_t *)last_task) + sizeof(queueTask_t)); parametersCanvasBackground_t *parameters = (parametersCanvasBackground_t *)end_of_queue; + last_parameter = end_of_queue; parameters->type = CANVAS_SET_BACKGROUND; - parameters->color = color; + parameters->color = ENDIAN_COLOR(color); end_of_queue += sizeof(parametersCanvasBackground_t); task_parameters->count++; + parameters->nextParameter = end_of_queue; +} + +#define QUEUE_SAFETY_FREE_SPACE 100 + +void TFT_Queue::handle_queue_overflow(uint16_t sizeNeeded) { + if (uintptr_t(end_of_queue) + sizeNeeded + (QUEUE_SAFETY_FREE_SPACE) - uintptr_t(queue) >= TFT_QUEUE_SIZE) { + end_of_queue = queue; + ((parametersCanvasText_t *)last_parameter)->nextParameter = end_of_queue; + } } void TFT_Queue::add_text(uint16_t x, uint16_t y, uint16_t color, uint8_t *string, uint16_t maxWidth) { + handle_queue_overflow(sizeof(parametersCanvasText_t) + maxWidth); parametersCanvas_t *task_parameters = (parametersCanvas_t *)(((uint8_t *)last_task) + sizeof(queueTask_t)); parametersCanvasText_t *parameters = (parametersCanvasText_t *)end_of_queue; + last_parameter = end_of_queue; uint8_t *pointer = string; parameters->type = CANVAS_ADD_TEXT; parameters->x = x; parameters->y = y; - parameters->color = color; + parameters->color = ENDIAN_COLOR(color); parameters->stringLength = 0; parameters->maxWidth = maxWidth; @@ -239,13 +235,16 @@ void TFT_Queue::add_text(uint16_t x, uint16_t y, uint16_t color, uint8_t *string /* TODO: Deal with maxWidth */ while ((*(end_of_queue++) = *pointer++) != 0x00); + parameters->nextParameter = end_of_queue; parameters->stringLength = pointer - string; task_parameters->count++; } void TFT_Queue::add_image(int16_t x, int16_t y, MarlinImage image, uint16_t *colors) { + handle_queue_overflow(sizeof(parametersCanvasImage_t)); parametersCanvas_t *task_parameters = (parametersCanvas_t *)(((uint8_t *)last_task) + sizeof(queueTask_t)); parametersCanvasImage_t *parameters = (parametersCanvasImage_t *)end_of_queue; + last_parameter = end_of_queue; parameters->type = CANVAS_ADD_IMAGE; parameters->x = x; @@ -254,27 +253,30 @@ void TFT_Queue::add_image(int16_t x, int16_t y, MarlinImage image, uint16_t *col end_of_queue += sizeof(parametersCanvasImage_t); task_parameters->count++; + parameters->nextParameter = end_of_queue; colorMode_t color_mode = Images[image].colorMode; if (color_mode == HIGHCOLOR) return; uint16_t *color = (uint16_t *)end_of_queue; - uint8_t number_of_color = 0; + uint8_t color_count = 0; switch (color_mode) { - case GREYSCALE1: number_of_color = 1; break; - case GREYSCALE2: number_of_color = 3; break; - case GREYSCALE4: number_of_color = 15; break; - default: - break; + case GREYSCALE1: color_count = 1; break; + case GREYSCALE2: color_count = 3; break; + case GREYSCALE4: color_count = 15; break; + default: break; } - while (number_of_color--) { - *color++ = *colors++; + uint16_t tmp; + while (color_count--) { + tmp = *colors++; + *color++ = ENDIAN_COLOR(tmp); } end_of_queue = (uint8_t *)color; + parameters->nextParameter = end_of_queue; } uint16_t gradient(uint16_t colorA, uint16_t colorB, uint16_t factor) { @@ -314,33 +316,39 @@ void TFT_Queue::add_image(int16_t x, int16_t y, MarlinImage image, uint16_t colo } void TFT_Queue::add_bar(uint16_t x, uint16_t y, uint16_t width, uint16_t height, uint16_t color) { + handle_queue_overflow(sizeof(parametersCanvasBar_t)); parametersCanvas_t *task_parameters = (parametersCanvas_t *)(((uint8_t *)last_task) + sizeof(queueTask_t)); parametersCanvasBar_t *parameters = (parametersCanvasBar_t *)end_of_queue; + last_parameter = end_of_queue; parameters->type = CANVAS_ADD_BAR; parameters->x = x; parameters->y = y; parameters->width = width; parameters->height = height; - parameters->color = color; + parameters->color = ENDIAN_COLOR(color); end_of_queue += sizeof(parametersCanvasBar_t); task_parameters->count++; + parameters->nextParameter = end_of_queue; } void TFT_Queue::add_rectangle(uint16_t x, uint16_t y, uint16_t width, uint16_t height, uint16_t color) { + handle_queue_overflow(sizeof(parametersCanvasRectangle_t)); parametersCanvas_t *task_parameters = (parametersCanvas_t *)(((uint8_t *)last_task) + sizeof(queueTask_t)); parametersCanvasRectangle_t *parameters = (parametersCanvasRectangle_t *)end_of_queue; + last_parameter = end_of_queue; parameters->type = CANVAS_ADD_RECTANGLE; parameters->x = x; parameters->y = y; parameters->width = width; parameters->height = height; - parameters->color = color; + parameters->color = ENDIAN_COLOR(color); end_of_queue += sizeof(parametersCanvasRectangle_t); task_parameters->count++; + parameters->nextParameter = end_of_queue; } #endif // HAS_GRAPHICAL_TFT diff --git a/Marlin/src/lcd/tft/tft_queue.h b/Marlin/src/lcd/tft/tft_queue.h index 9aa0d5b6c91d..51387254c55d 100644 --- a/Marlin/src/lcd/tft/tft_queue.h +++ b/Marlin/src/lcd/tft/tft_queue.h @@ -25,7 +25,9 @@ #include "tft_string.h" #include "tft_image.h" -#define QUEUE_SIZE 8192 +#ifndef TFT_QUEUE_SIZE + #define TFT_QUEUE_SIZE 8192 +#endif enum QueueTaskType : uint8_t { TASK_END_OF_QUEUE = 0x00, @@ -73,11 +75,13 @@ typedef struct __attribute__((__packed__)) { typedef struct __attribute__((__packed__)) { CanvasSubtype type; + uint8_t *nextParameter; uint16_t color; } parametersCanvasBackground_t; typedef struct __attribute__((__packed__)) { CanvasSubtype type; + uint8_t *nextParameter; uint16_t x; uint16_t y; uint16_t color; @@ -88,6 +92,7 @@ typedef struct __attribute__((__packed__)) { typedef struct __attribute__((__packed__)) { CanvasSubtype type; + uint8_t *nextParameter; int16_t x; int16_t y; MarlinImage image; @@ -95,6 +100,7 @@ typedef struct __attribute__((__packed__)) { typedef struct __attribute__((__packed__)) { CanvasSubtype type; + uint8_t *nextParameter; uint16_t x; uint16_t y; uint16_t width; @@ -104,6 +110,7 @@ typedef struct __attribute__((__packed__)) { typedef struct __attribute__((__packed__)) { CanvasSubtype type; + uint8_t *nextParameter; uint16_t x; uint16_t y; uint16_t width; @@ -113,19 +120,21 @@ typedef struct __attribute__((__packed__)) { class TFT_Queue { private: - static uint8_t queue[QUEUE_SIZE]; + static uint8_t queue[TFT_QUEUE_SIZE]; static uint8_t *end_of_queue; static uint8_t *current_task; static uint8_t *last_task; + static uint8_t *last_parameter; static void finish_sketch(); static void fill(queueTask_t *task); static void canvas(queueTask_t *task); + static void handle_queue_overflow(uint16_t sizeNeeded); public: static void reset(); static void async(); - static void sync() { while (current_task != NULL) async(); } + static void sync() { while (current_task != nullptr) async(); } static void fill(uint16_t x, uint16_t y, uint16_t width, uint16_t height, uint16_t color); static void canvas(uint16_t x, uint16_t y, uint16_t width, uint16_t height); diff --git a/Marlin/src/lcd/tft/tft_string.cpp b/Marlin/src/lcd/tft/tft_string.cpp index 663ed97c36c8..c2a571e826ff 100644 --- a/Marlin/src/lcd/tft/tft_string.cpp +++ b/Marlin/src/lcd/tft/tft_string.cpp @@ -26,6 +26,7 @@ #include "tft_string.h" #include "../fontutils.h" +#include "../marlinui.h" //#define DEBUG_TFT_FONT #define DEBUG_OUT ENABLED(DEBUG_TFT_FONT) @@ -36,29 +37,29 @@ font_t *TFT_String::font_header; uint8_t TFT_String::data[]; uint16_t TFT_String::span; -uint16_t TFT_String::length; +uint8_t TFT_String::length; void TFT_String::set_font(const uint8_t *font) { font_header = (font_t *)font; uint32_t glyph; - for (glyph = 0; glyph < 256; glyph++) glyphs[glyph] = NULL; + for (glyph = 0; glyph < 256; glyph++) glyphs[glyph] = nullptr; - DEBUG_ECHOLNPAIR("Format: ", font_header->Format); - DEBUG_ECHOLNPAIR("BBXWidth: ", font_header->BBXWidth); - DEBUG_ECHOLNPAIR("BBXHeight: ", font_header->BBXHeight); - DEBUG_ECHOLNPAIR("BBXOffsetX: ", font_header->BBXOffsetX); - DEBUG_ECHOLNPAIR("BBXOffsetY: ", font_header->BBXOffsetY); - DEBUG_ECHOLNPAIR("CapitalAHeight: ", font_header->CapitalAHeight); - DEBUG_ECHOLNPAIR("Encoding65Pos: ", font_header->Encoding65Pos); - DEBUG_ECHOLNPAIR("Encoding97Pos: ", font_header->Encoding97Pos); + DEBUG_ECHOLNPAIR("Format: ", font_header->Format); + DEBUG_ECHOLNPAIR("BBXWidth: ", font_header->BBXWidth); + DEBUG_ECHOLNPAIR("BBXHeight: ", font_header->BBXHeight); + DEBUG_ECHOLNPAIR("BBXOffsetX: ", font_header->BBXOffsetX); + DEBUG_ECHOLNPAIR("BBXOffsetY: ", font_header->BBXOffsetY); + DEBUG_ECHOLNPAIR("CapitalAHeight: ", font_header->CapitalAHeight); + DEBUG_ECHOLNPAIR("Encoding65Pos: ", font_header->Encoding65Pos); + DEBUG_ECHOLNPAIR("Encoding97Pos: ", font_header->Encoding97Pos); DEBUG_ECHOLNPAIR("FontStartEncoding: ", font_header->FontStartEncoding); - DEBUG_ECHOLNPAIR("FontEndEncoding: ", font_header->FontEndEncoding); - DEBUG_ECHOLNPAIR("LowerGDescent: ", font_header->LowerGDescent); - DEBUG_ECHOLNPAIR("FontAscent: ", font_header->FontAscent); - DEBUG_ECHOLNPAIR("FontDescent: ", font_header->FontDescent); - DEBUG_ECHOLNPAIR("FontXAscent: ", font_header->FontXAscent); - DEBUG_ECHOLNPAIR("FontXDescent: ", font_header->FontXDescent); + DEBUG_ECHOLNPAIR("FontEndEncoding: ", font_header->FontEndEncoding); + DEBUG_ECHOLNPAIR("LowerGDescent: ", font_header->LowerGDescent); + DEBUG_ECHOLNPAIR("FontAscent: ", font_header->FontAscent); + DEBUG_ECHOLNPAIR("FontDescent: ", font_header->FontDescent); + DEBUG_ECHOLNPAIR("FontXAscent: ", font_header->FontXAscent); + DEBUG_ECHOLNPAIR("FontXDescent: ", font_header->FontXDescent); add_glyphs(font); } @@ -72,9 +73,8 @@ void TFT_String::add_glyphs(const uint8_t *font) { glyphs[glyph] = (glyph_t *)pointer; pointer += sizeof(glyph_t) + ((glyph_t *)pointer)->DataSize; } - else { + else pointer++; - } } } @@ -86,6 +86,13 @@ void TFT_String::set() { uint8_t read_byte(uint8_t *byte) { return *byte; } +/** + * Add a string, applying substitutions for the following characters: + * + * = 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) + */ void TFT_String::add(uint8_t *string, int8_t index, uint8_t *itemString) { wchar_t wchar; @@ -116,13 +123,14 @@ void TFT_String::add(uint8_t *string, int8_t index, uint8_t *itemString) { eol(); } -void TFT_String::add(uint8_t *string) { +void TFT_String::add(uint8_t *string, uint8_t max_len) { wchar_t wchar; - while (*string) { + while (*string && max_len) { string = get_utf8_value_cb(string, read_byte, &wchar); if (wchar > 255) wchar |= 0x0080; uint8_t ch = uint8_t(wchar & 0x00FF); add_character(ch); + max_len--; } eol(); } diff --git a/Marlin/src/lcd/tft/tft_string.h b/Marlin/src/lcd/tft/tft_string.h index 924d6de43027..133889d9ae54 100644 --- a/Marlin/src/lcd/tft/tft_string.h +++ b/Marlin/src/lcd/tft/tft_string.h @@ -69,7 +69,7 @@ class TFT_String { static uint8_t data[MAX_STRING_LENGTH + 1]; static uint16_t span; // in pixels - static uint16_t length; // in characters + static uint8_t length; // in characters static void add_character(uint8_t character); static void eol() { data[length] = 0x00; } @@ -80,22 +80,25 @@ class TFT_String { static font_t *font() { return font_header; }; static uint16_t font_height() { return font_header->FontAscent - font_header->FontDescent; } - static glyph_t *glyph(uint8_t character) { return glyphs[character] == NULL ? glyphs[0x3F] : glyphs[character]; } /* Use '?' for unknown glyphs */ + static glyph_t *glyph(uint8_t character) { return glyphs[character] ?: glyphs[0x3F]; } /* Use '?' for unknown glyphs */ static inline glyph_t *glyph(uint8_t *character) { return glyph(*character); } static void set(); static void add(uint8_t character) { add_character(character); eol(); } - static void add(uint8_t *string); - static void add(uint8_t *string, int8_t index, uint8_t *itemString = NULL); + static void add(uint8_t *string, uint8_t max_len=MAX_STRING_LENGTH); + static void add(uint8_t *string, int8_t index, uint8_t *itemString=nullptr); static void set(uint8_t *string) { set(); add(string); }; - static void set(uint8_t *string, int8_t index, const char *itemString = NULL) { set(); add(string, index, (uint8_t *)itemString); }; + static void set(uint8_t *string, int8_t index, const char *itemString=nullptr) { set(); add(string, index, (uint8_t *)itemString); }; static inline void set(const char *string) { set((uint8_t *)string); } - static inline void set(const char *string, int8_t index, const char *itemString = NULL) { set((uint8_t *)string, index, itemString); } + static inline void set(const char *string, int8_t index, const char *itemString=nullptr) { set((uint8_t *)string, index, itemString); } static inline void add(const char *string) { add((uint8_t *)string); } - static void trim(uint8_t character = 0x20); - static void rtrim(uint8_t character = 0x20); - static void ltrim(uint8_t character = 0x20); + static void trim(uint8_t character=0x20); + static void rtrim(uint8_t character=0x20); + static void ltrim(uint8_t character=0x20); + + static void truncate(uint8_t maxlen) { if (length > maxlen) { length = maxlen; eol(); } } + static uint16_t width() { return span; } static uint8_t *string() { return data; } static uint16_t center(uint16_t width) { return span > width ? 0 : (width - span) / 2; } diff --git a/Marlin/src/lcd/tft/touch.cpp b/Marlin/src/lcd/tft/touch.cpp index 80c65f074ae6..64dfaa5755f2 100644 --- a/Marlin/src/lcd/tft/touch.cpp +++ b/Marlin/src/lcd/tft/touch.cpp @@ -1,6 +1,9 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * 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 @@ -23,7 +26,7 @@ #include "touch.h" -#include "../ultralcd.h" // for ui methods +#include "../marlinui.h" // for ui methods #include "../menu/menu_item.h" // for touch_screen_calibration #include "../../module/temperature.h" @@ -40,28 +43,23 @@ int16_t Touch::x, Touch::y; touch_control_t Touch::controls[]; touch_control_t *Touch::current_control; uint16_t Touch::controls_count; -millis_t Touch::now = 0; -millis_t Touch::time_to_hold; -millis_t Touch::repeat_delay; -millis_t Touch::touch_time; +millis_t Touch::last_touch_ms = 0, + Touch::time_to_hold, + Touch::repeat_delay, + Touch::touch_time; TouchControlType Touch::touch_control_type = NONE; -touch_calibration_t Touch::calibration; -#if ENABLED(TOUCH_SCREEN_CALIBRATION) - calibrationState Touch::calibration_state = CALIBRATION_NONE; - touch_calibration_point_t Touch::calibration_points[4]; -#endif #if HAS_RESUME_CONTINUE extern bool wait_for_user; #endif void Touch::init() { - calibration_reset(); + TERN_(TOUCH_SCREEN_CALIBRATION, touch_calibration.calibration_reset()); reset(); io.Init(); enable(); } -void Touch::add_control(TouchControlType type, uint16_t x, uint16_t y, uint16_t width, uint16_t height, int32_t data) { +void Touch::add_control(TouchControlType type, uint16_t x, uint16_t y, uint16_t width, uint16_t height, intptr_t data) { if (controls_count == MAX_CONTROLS) return; controls[controls_count].type = type; @@ -79,8 +77,10 @@ void Touch::idle() { if (!enabled) return; - if (now == millis()) return; - now = millis(); + // Return if Touch::idle is called within the same millisecond + const millis_t now = millis(); + if (last_touch_ms == now) return; + last_touch_ms = now; if (get_point(&_x, &_y)) { #if HAS_RESUME_CONTINUE @@ -88,24 +88,23 @@ void Touch::idle() { if (wait_for_user) { touch_control_type = CLICK; ui.lcd_clicked = true; + if (ui.external_control) wait_for_user = false; return; } #endif - #if LCD_TIMEOUT_TO_STATUS - ui.return_to_status_ms = now + LCD_TIMEOUT_TO_STATUS; - #endif + ui.reset_status_timeout(last_touch_ms); if (touch_time) { #if ENABLED(TOUCH_SCREEN_CALIBRATION) - if (touch_control_type == NONE && ELAPSED(now, touch_time + TOUCH_SCREEN_HOLD_TO_CALIBRATE_MS) && ui.on_status_screen()) + if (touch_control_type == NONE && ELAPSED(last_touch_ms, touch_time + TOUCH_SCREEN_HOLD_TO_CALIBRATE_MS) && ui.on_status_screen()) ui.goto_screen(touch_screen_calibration); #endif return; } - if (time_to_hold == 0) time_to_hold = now + MINIMUM_HOLD_TIME; - if (PENDING(now, time_to_hold)) return; + if (time_to_hold == 0) time_to_hold = last_touch_ms + MINIMUM_HOLD_TIME; + if (PENDING(last_touch_ms, time_to_hold)) return; if (x != 0 && y != 0) { if (current_control) { @@ -116,9 +115,8 @@ void Touch::idle() { NOMORE(y, current_control->y + current_control->height); touch(current_control); } - else { - current_control = NULL; - } + else + current_control = nullptr; } else { for (i = 0; i < controls_count; i++) { @@ -130,15 +128,15 @@ void Touch::idle() { } } - if (current_control == NULL) - touch_time = now; + if (!current_control) + touch_time = last_touch_ms; } x = _x; y = _y; } else { x = y = 0; - current_control = NULL; + current_control = nullptr; touch_time = 0; touch_control_type = NONE; time_to_hold = 0; @@ -150,57 +148,16 @@ void Touch::touch(touch_control_t *control) { switch (control->type) { #if ENABLED(TOUCH_SCREEN_CALIBRATION) case CALIBRATE: - ui.refresh(); - - if (calibration_state < CALIBRATION_SUCCESS) { - calibration_points[calibration_state].x = int16_t(control->data >> 16); - calibration_points[calibration_state].y = int16_t(control->data & 0xFFFF); - calibration_points[calibration_state].raw_x = x; - calibration_points[calibration_state].raw_y = y; - } - - switch (calibration_state) { - case CALIBRATION_POINT_1: calibration_state = CALIBRATION_POINT_2; break; - case CALIBRATION_POINT_2: calibration_state = CALIBRATION_POINT_3; break; - case CALIBRATION_POINT_3: calibration_state = CALIBRATION_POINT_4; break; - case CALIBRATION_POINT_4: - if (validate_precision_x(0, 1) && validate_precision_x(2, 3) && validate_precision_y(0, 2) && validate_precision_y(1, 3)) { - calibration_state = CALIBRATION_SUCCESS; - calibration.x = ((calibration_points[2].x - calibration_points[0].x) << 17) / (calibration_points[3].raw_x + calibration_points[2].raw_x - calibration_points[1].raw_x - calibration_points[0].raw_x); - calibration.y = ((calibration_points[1].y - calibration_points[0].y) << 17) / (calibration_points[3].raw_y - calibration_points[2].raw_y + calibration_points[1].raw_y - calibration_points[0].raw_y); - calibration.offset_x = calibration_points[0].x - int16_t(((calibration_points[0].raw_x + calibration_points[1].raw_x) * calibration.x) >> 17); - calibration.offset_y = calibration_points[0].y - int16_t(((calibration_points[0].raw_y + calibration_points[2].raw_y) * calibration.y) >> 17); - calibration.orientation = TOUCH_LANDSCAPE; - } - else if (validate_precision_y(0, 1) && validate_precision_y(2, 3) && validate_precision_x(0, 2) && validate_precision_x(1, 3)) { - calibration_state = CALIBRATION_SUCCESS; - calibration.x = ((calibration_points[2].x - calibration_points[0].x) << 17) / (calibration_points[3].raw_y + calibration_points[2].raw_y - calibration_points[1].raw_y - calibration_points[0].raw_y); - calibration.y = ((calibration_points[1].y - calibration_points[0].y) << 17) / (calibration_points[3].raw_x - calibration_points[2].raw_x + calibration_points[1].raw_x - calibration_points[0].raw_x); - calibration.offset_x = calibration_points[0].x - int16_t(((calibration_points[0].raw_y + calibration_points[1].raw_y) * calibration.x) >> 17); - calibration.offset_y = calibration_points[0].y - int16_t(((calibration_points[0].raw_x + calibration_points[2].raw_x) * calibration.y) >> 17); - calibration.orientation = TOUCH_PORTRAIT; - } - else { - calibration_state = CALIBRATION_FAIL; - calibration_reset(); - } - - if (calibration_state == CALIBRATION_SUCCESS) { - SERIAL_ECHOLN("Touch screen calibration completed"); - SERIAL_ECHOLNPAIR("TOUCH_CALIBRATION_X ", calibration.x); - SERIAL_ECHOLNPAIR("TOUCH_CALIBRATION_Y ", calibration.y); - SERIAL_ECHOLNPAIR("TOUCH_OFFSET_X ", calibration.offset_x); - SERIAL_ECHOLNPAIR("TOUCH_OFFSET_Y ", calibration.offset_y); - SERIAL_ECHO("TOUCH_ORIENTATION "); if (calibration.orientation == TOUCH_LANDSCAPE) SERIAL_ECHOLN("TOUCH_LANDSCAPE"); else SERIAL_ECHOLN("TOUCH_PORTRAIT"); - } - break; - default: break; - } + if (touch_calibration.handleTouch(x, y)) ui.refresh(); break; #endif // TOUCH_SCREEN_CALIBRATION case MENU_SCREEN: ui.goto_screen((screenFunc_t)control->data); break; case BACK: ui.goto_previous_screen(); break; + case MENU_CLICK: + TERN_(SINGLE_TOUCH_NAVIGATION, ui.encoderPosition = control->data); + ui.lcd_clicked = true; + break; case CLICK: ui.lcd_clicked = true; break; #if HAS_RESUME_CONTINUE case RESUME_CONTINUE: extern bool wait_for_user; wait_for_user = false; break; @@ -225,24 +182,32 @@ void Touch::touch(touch_control_t *control) { int8_t heater; heater = control->data; ui.clear_lcd(); - if (heater >= 0) { // HotEnd - #if HOTENDS == 1 - MenuItem_int3::action((const char *)GET_TEXT_F(MSG_NOZZLE), &thermalManager.temp_hotend[0].target, 0, thermalManager.heater_maxtemp[0] - 15, []{ thermalManager.start_watching_hotend(0); }); - #else - MenuItemBase::itemIndex = heater; - MenuItem_int3::action((const char *)GET_TEXT_F(MSG_NOZZLE_N), &thermalManager.temp_hotend[heater].target, 0, thermalManager.heater_maxtemp[heater] - 15, []{ thermalManager.start_watching_hotend(MenuItemBase::itemIndex); }); - #endif - } + #if HAS_HOTEND + if (heater >= 0) { // HotEnd + #if HOTENDS == 1 + MenuItem_int3::action((const char *)GET_TEXT_F(MSG_NOZZLE), &thermalManager.temp_hotend[0].target, 0, thermalManager.hotend_max_target(0), []{ thermalManager.start_watching_hotend(0); }); + #else + MenuItemBase::itemIndex = heater; + MenuItem_int3::action((const char *)GET_TEXT_F(MSG_NOZZLE_N), &thermalManager.temp_hotend[heater].target, 0, thermalManager.hotend_max_target(heater), []{ thermalManager.start_watching_hotend(MenuItemBase::itemIndex); }); + #endif + } + #endif #if HAS_HEATED_BED else if (heater == H_BED) { - MenuItem_int3::action((const char *)GET_TEXT_F(MSG_BED), &thermalManager.temp_bed.target, 0, BED_MAXTEMP - 10, thermalManager.start_watching_bed); + MenuItem_int3::action((const char *)GET_TEXT_F(MSG_BED), &thermalManager.temp_bed.target, 0, BED_MAX_TARGET, thermalManager.start_watching_bed); } #endif #if HAS_HEATED_CHAMBER else if (heater == H_CHAMBER) { - MenuItem_int3::action((const char *)GET_TEXT_F(MSG_CHAMBER), &thermalManager.temp_chamber.target, 0, CHAMBER_MAXTEMP - 10, thermalManager.start_watching_chamber); + MenuItem_int3::action((const char *)GET_TEXT_F(MSG_CHAMBER), &thermalManager.temp_chamber.target, 0, CHAMBER_MAX_TARGET, thermalManager.start_watching_chamber); } #endif + #if HAS_COOLER + else if (heater == H_COOLER) { + MenuItem_int3::action((const char *)GET_TEXT_F(MSG_COOLER), &thermalManager.temp_cooler.target, 0, COOLER_MAX_TARGET, thermalManager.start_watching_cooler); + } + #endif + break; case FAN: ui.clear_lcd(); @@ -284,18 +249,29 @@ void Touch::hold(touch_control_t *control, millis_t delay) { current_control = control; if (delay) { repeat_delay = delay > MIN_REPEAT_DELAY ? delay : MIN_REPEAT_DELAY; - time_to_hold = now + repeat_delay; + time_to_hold = last_touch_ms + repeat_delay; } ui.refresh(); } bool Touch::get_point(int16_t *x, int16_t *y) { - bool is_touched = (calibration.orientation == TOUCH_PORTRAIT ? io.getRawPoint(y, x) : io.getRawPoint(x, y)); + #if ENABLED(TFT_TOUCH_DEVICE_XPT2046) + #if ENABLED(TOUCH_SCREEN_CALIBRATION) + bool is_touched = (touch_calibration.calibration.orientation == TOUCH_PORTRAIT ? io.getRawPoint(y, x) : io.getRawPoint(x, y)); + + if (is_touched && touch_calibration.calibration.orientation != TOUCH_ORIENTATION_NONE) { + *x = int16_t((int32_t(*x) * touch_calibration.calibration.x) >> 16) + touch_calibration.calibration.offset_x; + *y = int16_t((int32_t(*y) * touch_calibration.calibration.y) >> 16) + touch_calibration.calibration.offset_y; + } + #else + bool is_touched = (TOUCH_ORIENTATION == TOUCH_PORTRAIT ? io.getRawPoint(y, x) : io.getRawPoint(x, y)); + *x = uint16_t((uint32_t(*x) * TOUCH_CALIBRATION_X) >> 16) + TOUCH_OFFSET_X; + *y = uint16_t((uint32_t(*y) * TOUCH_CALIBRATION_Y) >> 16) + TOUCH_OFFSET_Y; + #endif + #elif ENABLED(TFT_TOUCH_DEVICE_GT911) + bool is_touched = (TOUCH_ORIENTATION == TOUCH_PORTRAIT ? io.getPoint(y, x) : io.getPoint(x, y)); + #endif - if (is_touched && calibration.orientation != TOUCH_ORIENTATION_NONE) { - *x = int16_t((int32_t(*x) * calibration.x) >> 16) + calibration.offset_x; - *y = int16_t((int32_t(*y) * calibration.y) >> 16) + calibration.offset_y; - } return is_touched; } Touch touch; @@ -304,7 +280,7 @@ bool MarlinUI::touch_pressed() { return touch.is_clicked(); } -void add_control(uint16_t x, uint16_t y, TouchControlType control_type, int32_t data, MarlinImage image, bool is_enabled, uint16_t color_enabled, uint16_t color_disabled) { +void add_control(uint16_t x, uint16_t y, TouchControlType control_type, intptr_t data, MarlinImage image, bool is_enabled, uint16_t color_enabled, uint16_t color_disabled) { uint16_t width = Images[image].width; uint16_t height = Images[image].height; tft.canvas(x, y, width, height); diff --git a/Marlin/src/lcd/tft/touch.h b/Marlin/src/lcd/tft/touch.h index 7d8f222918db..54dfb420d8d6 100644 --- a/Marlin/src/lcd/tft/touch.h +++ b/Marlin/src/lcd/tft/touch.h @@ -1,6 +1,9 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * 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 @@ -20,40 +23,21 @@ #include "../../inc/MarlinConfigPre.h" -#if ENABLED(TOUCH_SCREEN) - #include "tft_color.h" #include "tft_image.h" -#include HAL_PATH(../../HAL, tft/xpt2046.h) -#define TOUCH_DRIVER XPT2046 - -#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 +#if ENABLED(TOUCH_SCREEN_CALIBRATION) + #include "../tft_io/touch_calibration.h" #endif -#define TOUCH_ORIENTATION_NONE 0 -#define TOUCH_LANDSCAPE 1 -#define TOUCH_PORTRAIT 2 - -#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 - #else - #define TOUCH_CALIBRATION_X 0 - #define TOUCH_CALIBRATION_Y 0 - #define TOUCH_OFFSET_X 0 - #define TOUCH_OFFSET_Y 0 - #define TOUCH_ORIENTATION TOUCH_ORIENTATION_NONE - #endif +#if ENABLED(TFT_TOUCH_DEVICE_GT911) + #include HAL_PATH(../../HAL, tft/gt911.h) + #define TOUCH_DRIVER_CLASS GT911 +#elif ENABLED(TFT_TOUCH_DEVICE_XPT2046) + #include HAL_PATH(../../HAL, tft/xpt2046.h) + #define TOUCH_DRIVER_CLASS XPT2046 +#else + #error "Unknown Touch Screen Type." #endif // Menu Navigation @@ -68,6 +52,7 @@ enum TouchControlType : uint16_t { PAGE_UP, PAGE_DOWN, CLICK, + MENU_CLICK, RESUME_CONTINUE, SLIDER, INCREASE, @@ -85,9 +70,9 @@ enum TouchControlType : uint16_t { typedef void (*screenFunc_t)(); -void add_control(uint16_t x, uint16_t y, TouchControlType control_type, int32_t data, MarlinImage image, bool is_enabled = true, uint16_t color_enabled = COLOR_CONTROL_ENABLED, uint16_t color_disabled = COLOR_CONTROL_DISABLED); +void add_control(uint16_t x, uint16_t y, TouchControlType control_type, intptr_t data, MarlinImage image, bool is_enabled = true, uint16_t color_enabled = COLOR_CONTROL_ENABLED, uint16_t color_disabled = COLOR_CONTROL_DISABLED); inline void add_control(uint16_t x, uint16_t y, TouchControlType control_type, MarlinImage image, bool is_enabled = true, uint16_t color_enabled = COLOR_CONTROL_ENABLED, uint16_t color_disabled = COLOR_CONTROL_DISABLED) { add_control(x, y, control_type, 0, image, is_enabled, color_enabled, color_disabled); } -inline void add_control(uint16_t x, uint16_t y, screenFunc_t screen, MarlinImage image, bool is_enabled = true, uint16_t color_enabled = COLOR_CONTROL_ENABLED, uint16_t color_disabled = COLOR_CONTROL_DISABLED) { add_control(x, y, MENU_SCREEN, (int32_t)screen, image, is_enabled, color_enabled, color_disabled); } +inline void add_control(uint16_t x, uint16_t y, screenFunc_t screen, MarlinImage image, bool is_enabled = true, uint16_t color_enabled = COLOR_CONTROL_ENABLED, uint16_t color_disabled = COLOR_CONTROL_DISABLED) { add_control(x, y, MENU_SCREEN, (intptr_t)screen, image, is_enabled, color_enabled, color_disabled); } typedef struct __attribute__((__packed__)) { TouchControlType type; @@ -95,34 +80,9 @@ typedef struct __attribute__((__packed__)) { uint16_t y; uint16_t width; uint16_t height; - int32_t data; + intptr_t data; } touch_control_t; -typedef struct __attribute__((__packed__)) { - int32_t x; - int32_t y; - int16_t offset_x; - int16_t offset_y; - uint8_t orientation; -} touch_calibration_t; - -typedef struct __attribute__((__packed__)) { - uint16_t x; - uint16_t y; - int16_t raw_x; - int16_t raw_y; -} touch_calibration_point_t; - -enum calibrationState : uint8_t { - CALIBRATION_POINT_1 = 0x00, - CALIBRATION_POINT_2, - CALIBRATION_POINT_3, - CALIBRATION_POINT_4, - CALIBRATION_SUCCESS, - CALIBRATION_FAIL, - CALIBRATION_NONE, -}; - #define MAX_CONTROLS 16 #define MINIMUM_HOLD_TIME 15 #define TOUCH_REPEAT_DELAY 75 @@ -132,7 +92,7 @@ enum calibrationState : uint8_t { class Touch { private: - static TOUCH_DRIVER io; + static TOUCH_DRIVER_CLASS io; static int16_t x, y; static bool enabled; @@ -140,46 +100,29 @@ class Touch { static touch_control_t *current_control; static uint16_t controls_count; - static millis_t now; - static millis_t time_to_hold; - static millis_t repeat_delay; - static millis_t touch_time; + static millis_t last_touch_ms, time_to_hold, repeat_delay, touch_time; static TouchControlType touch_control_type; static inline bool get_point(int16_t *x, int16_t *y); static void touch(touch_control_t *control); static void hold(touch_control_t *control, millis_t delay = 0); - #if ENABLED(TOUCH_SCREEN_CALIBRATION) - static calibrationState calibration_state; - static touch_calibration_point_t calibration_points[4]; - - static bool validate_precision(int32_t a, int32_t b) { return (a > b ? (100 * b) / a : (100 * a) / b) > TOUCH_SCREEN_CALIBRATION_PRECISION; } - static bool validate_precision_x(uint8_t a, uint8_t b) { return validate_precision(calibration_points[a].raw_x, calibration_points[b].raw_x); } - static bool validate_precision_y(uint8_t a, uint8_t b) { return validate_precision(calibration_points[a].raw_y, calibration_points[b].raw_y); } - #endif // TOUCH_SCREEN_CALIBRATION - public: static void init(); - static void reset() { controls_count = 0; touch_time = -1; current_control = NULL; } + static void reset() { controls_count = 0; touch_time = 0; current_control = nullptr; } static void clear() { controls_count = 0; } static void idle(); - static bool is_clicked() { return touch_control_type == CLICK; } + static bool is_clicked() { + if (touch_control_type == CLICK) { + touch_control_type = NONE; + return true; + } + return false; + } static void disable() { enabled = false; } static void enable() { enabled = true; } - static void add_control(TouchControlType type, uint16_t x, uint16_t y, uint16_t width, uint16_t height, int32_t data = 0); - - static touch_calibration_t calibration; - static void calibration_reset() { calibration = {TOUCH_CALIBRATION_X, TOUCH_CALIBRATION_Y, TOUCH_OFFSET_X, TOUCH_OFFSET_Y, TOUCH_ORIENTATION}; } - - #if ENABLED(TOUCH_SCREEN_CALIBRATION) - static calibrationState calibration_start() { calibration = {0, 0, 0, 0, TOUCH_ORIENTATION_NONE}; return calibration_state = CALIBRATION_POINT_1; } - static void calibration_end() { calibration_state = CALIBRATION_NONE; } - static calibrationState get_calibration_state() { return calibration_state; } - #endif // TOUCH_SCREEN_CALIBRATION + 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; - -#endif // TOUCH_SCREEN diff --git a/Marlin/src/lcd/tft/ui_1024x600.cpp b/Marlin/src/lcd/tft/ui_1024x600.cpp new file mode 100644 index 000000000000..18c50c92f7a2 --- /dev/null +++ b/Marlin/src/lcd/tft/ui_1024x600.cpp @@ -0,0 +1,919 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../inc/MarlinConfigPre.h" + +#if HAS_UI_1024x600 + +#include "ui_common.h" + +#include "../marlinui.h" +#include "../menu/menu.h" +#include "../../libs/numtostr.h" + +#include "../../sd/cardreader.h" +#include "../../module/temperature.h" +#include "../../module/printcounter.h" +#include "../../module/planner.h" +#include "../../module/motion.h" + +#if DISABLED(LCD_PROGRESS_BAR) && BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) + #include "../../feature/filwidth.h" + #include "../../gcode/parser.h" +#endif + +#if ENABLED(AUTO_BED_LEVELING_UBL) + #include "../../feature/bedlevel/bedlevel.h" +#endif + +void MarlinUI::tft_idle() { + #if ENABLED(TOUCH_SCREEN) + if (draw_menu_navigation) { + add_control(164, TFT_HEIGHT - 50, PAGE_UP, imgPageUp, encoderTopLine > 0); + add_control(796, TFT_HEIGHT - 50, PAGE_DOWN, imgPageDown, encoderTopLine + LCD_HEIGHT < screen_items); + add_control(480, TFT_HEIGHT - 50, BACK, imgBack); + draw_menu_navigation = false; + } + #endif + + tft.queue.async(); + TERN_(TOUCH_SCREEN, touch.idle()); +} + +#if ENABLED(SHOW_BOOTSCREEN) + + void MarlinUI::show_bootscreen() { + tft.queue.reset(); + + tft.canvas(0, 0, TFT_WIDTH, TFT_HEIGHT); + #if ENABLED(BOOT_MARLIN_LOGO_SMALL) + #define BOOT_LOGO_W 195 // MarlinLogo195x59x16 + #define BOOT_LOGO_H 59 + #define SITE_URL_Y (TFT_HEIGHT - 70) + tft.set_background(COLOR_BACKGROUND); + #else + #define BOOT_LOGO_W TFT_WIDTH // MarlinLogo480x320x16 + #define BOOT_LOGO_H TFT_HEIGHT + #define SITE_URL_Y (TFT_HEIGHT - 90) + #endif + tft.add_image((TFT_WIDTH - BOOT_LOGO_W) / 2, (TFT_HEIGHT - BOOT_LOGO_H) / 2, imgBootScreen); + #ifdef WEBSITE_URL + tft_string.set(WEBSITE_URL); + tft.add_text(tft_string.center(TFT_WIDTH), SITE_URL_Y, COLOR_WEBSITE_URL, tft_string); + #endif + + tft.queue.sync(); + } + + void MarlinUI::bootscreen_completion(const millis_t sofar) { + if ((BOOTSCREEN_TIMEOUT) > sofar) safe_delay((BOOTSCREEN_TIMEOUT) - sofar); + clear_lcd(); + } + +#endif + +void MarlinUI::draw_kill_screen() { + tft.queue.reset(); + tft.fill(0, 0, TFT_WIDTH, TFT_HEIGHT, COLOR_KILL_SCREEN_BG); + + uint16_t line = 2; + + menu_line(line++, COLOR_KILL_SCREEN_BG); + tft_string.set(status_message); + tft_string.trim(); + tft.add_text(tft_string.center(TFT_WIDTH), 0, COLOR_MENU_TEXT, tft_string); + + line++; + menu_line(line++, COLOR_KILL_SCREEN_BG); + tft_string.set(GET_TEXT(MSG_HALTED)); + tft_string.trim(); + tft.add_text(tft_string.center(TFT_WIDTH), 0, COLOR_MENU_TEXT, tft_string); + + menu_line(line++, COLOR_KILL_SCREEN_BG); + tft_string.set(GET_TEXT(MSG_PLEASE_RESET)); + tft_string.trim(); + tft.add_text(tft_string.center(TFT_WIDTH), 0, COLOR_MENU_TEXT, tft_string); + + tft.queue.sync(); +} + +void draw_heater_status(uint16_t x, uint16_t y, const int8_t Heater) { + MarlinImage image = imgHotEnd; + uint16_t Color; + celsius_t currentTemperature, targetTemperature; + + if (Heater >= 0) { // HotEnd + currentTemperature = thermalManager.wholeDegHotend(Heater); + targetTemperature = thermalManager.degTargetHotend(Heater); + } + #if HAS_HEATED_BED + else if (Heater == H_BED) { + currentTemperature = thermalManager.wholeDegBed(); + targetTemperature = thermalManager.degTargetBed(); + } + #endif + #if HAS_TEMP_CHAMBER + else if (Heater == H_CHAMBER) { + currentTemperature = thermalManager.wholeDegChamber(); + #if HAS_HEATED_CHAMBER + targetTemperature = thermalManager.degTargetChamber(); + #else + targetTemperature = ABSOLUTE_ZERO; + #endif + } + #endif + #if HAS_TEMP_COOLER + else if (Heater == H_COOLER) { + currentTemperature = thermalManager.wholeDegCooler(); + targetTemperature = TERN(HAS_COOLER, thermalManager.degTargetCooler(), ABSOLUTE_ZERO); + } + #endif + else return; + + TERN_(TOUCH_SCREEN, if (targetTemperature >= 0) touch.add_control(HEATER, x, y, 80, 120, Heater)); + tft.canvas(x, y, 80, 120); + tft.set_background(COLOR_BACKGROUND); + + Color = currentTemperature < 0 ? COLOR_INACTIVE : COLOR_COLD; + + if (Heater >= 0) { // HotEnd + if (currentTemperature >= 50) Color = COLOR_HOTEND; + } + #if HAS_HEATED_BED + else if (Heater == H_BED) { + if (currentTemperature >= 50) Color = COLOR_HEATED_BED; + image = targetTemperature > 0 ? imgBedHeated : imgBed; + } + #endif + #if HAS_TEMP_CHAMBER + else if (Heater == H_CHAMBER) { + if (currentTemperature >= 50) Color = COLOR_CHAMBER; + image = targetTemperature > 0 ? imgChamberHeated : imgChamber; + } + #endif + #if HAS_TEMP_COOLER + else if (Heater == H_COOLER) { + if (currentTemperature <= 26) Color = COLOR_COLD; + if (currentTemperature > 26) Color = COLOR_RED; + image = targetTemperature > 26 ? imgCoolerHot : imgCooler; + } + #endif + + tft.add_image(8, 28, image, Color); + + tft_string.set((uint8_t *)i16tostr3rj(currentTemperature)); + tft_string.add(LCD_STR_DEGREE); + tft_string.trim(); + tft.add_text(tft_string.center(80) + 2, 82, Color, tft_string); + + if (targetTemperature >= 0) { + tft_string.set((uint8_t *)i16tostr3rj(targetTemperature)); + tft_string.add(LCD_STR_DEGREE); + tft_string.trim(); + tft.add_text(tft_string.center(80) + 2, 8, Color, tft_string); + } +} + +void draw_fan_status(uint16_t x, uint16_t y, const bool blink) { + TERN_(TOUCH_SCREEN, touch.add_control(FAN, x, y, 80, 120)); + tft.canvas(x, y, 80, 120); + tft.set_background(COLOR_BACKGROUND); + + uint8_t fanSpeed = thermalManager.fan_speed[0]; + MarlinImage image; + + if (fanSpeed >= 127) + image = blink ? imgFanFast1 : imgFanFast0; + else if (fanSpeed > 0) + image = blink ? imgFanSlow1 : imgFanSlow0; + else + image = imgFanIdle; + + tft.add_image(8, 20, image, COLOR_FAN); + + tft_string.set((uint8_t *)ui8tostr4pctrj(thermalManager.fan_speed[0])); + tft_string.trim(); + tft.add_text(tft_string.center(80) + 6, 82, COLOR_FAN, tft_string); +} + +void MarlinUI::draw_status_screen() { + const bool blink = get_blink(); + + TERN_(TOUCH_SCREEN, touch.clear()); + + // heaters and fan + uint16_t i, x, y = TFT_STATUS_TOP_Y; + + for (i = 0 ; i < ITEMS_COUNT; i++) { + x = (TFT_WIDTH / ITEMS_COUNT - 80) / 2 + (TFT_WIDTH * i / ITEMS_COUNT); + switch (i) { + #ifdef ITEM_E0 + case ITEM_E0: draw_heater_status(x, y, H_E0); break; + #endif + #ifdef ITEM_E1 + case ITEM_E1: draw_heater_status(x, y, H_E1); break; + #endif + #ifdef ITEM_E2 + case ITEM_E2: draw_heater_status(x, y, H_E2); break; + #endif + #ifdef ITEM_BED + case ITEM_BED: draw_heater_status(x, y, H_BED); break; + #endif + #ifdef ITEM_CHAMBER + case ITEM_CHAMBER: draw_heater_status(x, y, H_CHAMBER); break; + #endif + #ifdef ITEM_COOLER + case ITEM_COOLER: draw_heater_status(x, y, H_COOLER); break; + #endif + #ifdef ITEM_FAN + case ITEM_FAN: draw_fan_status(x, y, blink); break; + #endif + } + } + + y += 200; + + // coordinates + tft.canvas(4, y, TFT_WIDTH - 8, FONT_LINE_HEIGHT); + tft.set_background(COLOR_BACKGROUND); + tft.add_rectangle(0, 0, TFT_WIDTH - 8, FONT_LINE_HEIGHT, COLOR_AXIS_HOMED); + + tft.add_text(200, 3, COLOR_AXIS_HOMED , "X"); + tft.add_text(500, 3, COLOR_AXIS_HOMED , "Y"); + tft.add_text(800, 3, COLOR_AXIS_HOMED , "Z"); + + bool not_homed = axis_should_home(X_AXIS); + tft_string.set(blink && not_homed ? "?" : ftostr4sign(LOGICAL_X_POSITION(current_position.x))); + tft.add_text(300 - tft_string.width(), 3, not_homed ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); + + not_homed = axis_should_home(Y_AXIS); + tft_string.set(blink && not_homed ? "?" : ftostr4sign(LOGICAL_Y_POSITION(current_position.y))); + tft.add_text(600 - tft_string.width(), 3, not_homed ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); + + uint16_t offset = 32; + not_homed = axis_should_home(Z_AXIS); + if (blink && not_homed) + tft_string.set("?"); + else { + const float z = LOGICAL_Z_POSITION(current_position.z); + tft_string.set(ftostr52sp((int16_t)z)); + tft_string.rtrim(); + offset += tft_string.width(); + + tft_string.set(ftostr52sp(z)); + offset -= tft_string.width(); + } + tft.add_text(900 - tft_string.width() - offset, 3, not_homed ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); + TERN_(TOUCH_SCREEN, touch.add_control(MOVE_AXIS, 4, y, TFT_WIDTH - 8, FONT_LINE_HEIGHT)); + + y += 100; + // feed rate + tft.canvas(274, y, 100, 32); + tft.set_background(COLOR_BACKGROUND); + uint16_t color = feedrate_percentage == 100 ? COLOR_RATE_100 : COLOR_RATE_ALTERED; + tft.add_image(0, 0, imgFeedRate, color); + tft_string.set(i16tostr3rj(feedrate_percentage)); + tft_string.add('%'); + tft.add_text(36, 1, color , tft_string); + TERN_(TOUCH_SCREEN, touch.add_control(FEEDRATE, 274, y, 100, 32)); + + // flow rate + tft.canvas(650, y, 100, 32); + tft.set_background(COLOR_BACKGROUND); + color = planner.flow_percentage[0] == 100 ? COLOR_RATE_100 : COLOR_RATE_ALTERED; + tft.add_image(0, 0, imgFlowRate, color); + tft_string.set(i16tostr3rj(planner.flow_percentage[active_extruder])); + tft_string.add('%'); + tft.add_text(36, 1, color , tft_string); + TERN_(TOUCH_SCREEN, touch.add_control(FLOWRATE, 650, y, 100, 32, active_extruder)); + + #if ENABLED(TOUCH_SCREEN) + add_control(900, y, menu_main, imgSettings); + TERN_(SDSUPPORT, add_control(12, y, menu_media, imgSD, !printingIsActive(), COLOR_CONTROL_ENABLED, card.isMounted() && printingIsActive() ? COLOR_BUSY : COLOR_CONTROL_DISABLED)); + #endif + + y += 100; + // print duration + char buffer[14]; + duration_t elapsed = print_job_timer.duration(); + elapsed.toDigital(buffer); + + tft.canvas((TFT_WIDTH - 128) / 2, y, 128, 29); + tft.set_background(COLOR_BACKGROUND); + tft_string.set(buffer); + tft.add_text(tft_string.center(128), 0, COLOR_PRINT_TIME, tft_string); + + y += 50; + // progress bar + const uint8_t progress = ui.get_progress_percent(); + tft.canvas(4, y, TFT_WIDTH - 8, 9); + tft.set_background(COLOR_PROGRESS_BG); + tft.add_rectangle(0, 0, TFT_WIDTH - 8, 9, COLOR_PROGRESS_FRAME); + if (progress) + tft.add_bar(1, 1, ((TFT_WIDTH - 10) * progress) / 100, 7, COLOR_PROGRESS_BAR); + + y += 50; + // status message + tft.canvas(0, y, TFT_WIDTH, FONT_LINE_HEIGHT - 5); + tft.set_background(COLOR_BACKGROUND); + tft_string.set(status_message); + tft_string.trim(); + tft.add_text(tft_string.center(TFT_WIDTH), 0, COLOR_STATUS_MESSAGE, tft_string); +} + +// Low-level draw_edit_screen can be used to draw an edit screen from anyplace +void MenuEditItemBase::draw_edit_screen(PGM_P const pstr, const char * const value/*=nullptr*/) { + ui.encoder_direction_normal(); + TERN_(TOUCH_SCREEN, touch.clear()); + + uint16_t line = 1; + + menu_line(line++); + tft_string.set(pstr, itemIndex, itemString); + tft_string.trim(); + tft.add_text(tft_string.center(TFT_WIDTH), MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string); + + TERN_(AUTO_BED_LEVELING_UBL, if (ui.external_control) line++); // ftostr52() will overwrite *value so *value has to be displayed first + + menu_line(line); + tft_string.set(value); + tft_string.trim(); + tft.add_text(tft_string.center(TFT_WIDTH), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string); + + #if ENABLED(AUTO_BED_LEVELING_UBL) + if (ui.external_control) { + menu_line(line - 1); + + tft_string.set(X_LBL); + tft.add_text((TFT_WIDTH / 2 - 120), MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string); + tft_string.set(ftostr52(LOGICAL_X_POSITION(current_position.x))); + tft_string.trim(); + tft.add_text((TFT_WIDTH / 2 - 16) - tft_string.width(), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string); + + tft_string.set(Y_LBL); + tft.add_text((TFT_WIDTH / 2 + 16), MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string); + tft_string.set(ftostr52(LOGICAL_X_POSITION(current_position.y))); + tft_string.trim(); + tft.add_text((TFT_WIDTH / 2 + 120) - tft_string.width(), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string); + } + #endif + + extern screenFunc_t _manual_move_func_ptr; + if (ui.currentScreen != _manual_move_func_ptr && !ui.external_control) { + + #define SLIDER_LENGTH 600 + #define SLIDER_Y_POSITION 200 + + tft.canvas((TFT_WIDTH - SLIDER_LENGTH) / 2, SLIDER_Y_POSITION, SLIDER_LENGTH, 16); + tft.set_background(COLOR_BACKGROUND); + + int16_t position = (SLIDER_LENGTH - 2) * ui.encoderPosition / maxEditValue; + tft.add_bar(0, 7, 1, 2, ui.encoderPosition == 0 ? COLOR_SLIDER_INACTIVE : COLOR_SLIDER); + tft.add_bar(1, 6, position, 4, COLOR_SLIDER); + tft.add_bar(position + 1, 6, SLIDER_LENGTH - 2 - position, 4, COLOR_SLIDER_INACTIVE); + tft.add_bar(SLIDER_LENGTH - 1, 7, 1, 2, int32_t(ui.encoderPosition) == maxEditValue ? COLOR_SLIDER : COLOR_SLIDER_INACTIVE); + + #if ENABLED(TOUCH_SCREEN) + tft.add_image((SLIDER_LENGTH - 8) * ui.encoderPosition / maxEditValue, 0, imgSlider, COLOR_SLIDER); + touch.add_control(SLIDER, (TFT_WIDTH - SLIDER_LENGTH) / 2, SLIDER_Y_POSITION - 8, SLIDER_LENGTH, 32, maxEditValue); + #endif + } + + tft.draw_edit_screen_buttons(); +} + +void TFT::draw_edit_screen_buttons() { + #if ENABLED(TOUCH_SCREEN) + add_control(164, TFT_HEIGHT - 64, DECREASE, imgDecrease); + add_control(796, TFT_HEIGHT - 64, INCREASE, imgIncrease); + add_control(480, TFT_HEIGHT - 64, CLICK, imgConfirm); + #endif +} + +// The Select Screen presents a prompt and two "buttons" +void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const bool yesno, PGM_P const pref, const char * const string/*=nullptr*/, PGM_P const suff/*=nullptr*/) { + uint16_t line = 1; + + if (!string) line++; + + menu_line(line++); + tft_string.set(pref); + tft_string.trim(); + tft.add_text(tft_string.center(TFT_WIDTH), 0, COLOR_MENU_TEXT, tft_string); + + if (string) { + menu_line(line++); + tft_string.set(string); + tft_string.trim(); + tft.add_text(tft_string.center(TFT_WIDTH), 0, COLOR_MENU_TEXT, tft_string); + } + + if (suff) { + menu_line(line); + tft_string.set(suff); + tft_string.trim(); + tft.add_text(tft_string.center(TFT_WIDTH), 0, COLOR_MENU_TEXT, tft_string); + } + #if ENABLED(TOUCH_SCREEN) + add_control(88, TFT_HEIGHT - 64, CANCEL, imgCancel, true, yesno ? HALF(COLOR_CONTROL_CANCEL) : COLOR_CONTROL_CANCEL); + add_control(328, TFT_HEIGHT - 64, CONFIRM, imgConfirm, true, yesno ? COLOR_CONTROL_CONFIRM : HALF(COLOR_CONTROL_CONFIRM)); + #else + menu_line(++line); + if (no) { + tft_string.set(no); + tft_string.trim(); + tft.add_text(tft_string.center(TFT_WIDTH / 2), 0, !yesno ? COLOR_RED : COLOR_MENU_TEXT, tft_string); + } + + if (yes) { + tft_string.set(yes); + tft_string.trim(); + tft.add_text(TFT_WIDTH / 2 + tft_string.center(TFT_WIDTH / 2), 0, yesno ? COLOR_RED : COLOR_MENU_TEXT, tft_string); + } + #endif +} + +#if ENABLED(ADVANCED_PAUSE_FEATURE) + + void MarlinUI::draw_hotend_status(const uint8_t row, const uint8_t extruder) { + #if ENABLED(TOUCH_SCREEN) + touch.clear(); + draw_menu_navigation = false; + touch.add_control(RESUME_CONTINUE , 0, 0, TFT_WIDTH, TFT_HEIGHT); + #endif + + menu_line(row); + tft_string.set(GET_TEXT(MSG_FILAMENT_CHANGE_NOZZLE)); + tft_string.add('E'); + tft_string.add((char)('1' + extruder)); + tft_string.add(' '); + tft_string.add(i16tostr3rj(thermalManager.wholeDegHotend(extruder))); + tft_string.add(LCD_STR_DEGREE); + tft_string.add(" / "); + tft_string.add(i16tostr3rj(thermalManager.degTargetHotend(extruder))); + tft_string.add(LCD_STR_DEGREE); + tft_string.trim(); + tft.add_text(tft_string.center(TFT_WIDTH), 0, COLOR_MENU_TEXT, tft_string); + } + +#endif // ADVANCED_PAUSE_FEATURE + +#if ENABLED(AUTO_BED_LEVELING_UBL) + #define GRID_OFFSET_X 8 + #define GRID_OFFSET_Y 8 + #define GRID_WIDTH 192 + #define GRID_HEIGHT 192 + #define CONTROL_OFFSET 16 + + void MarlinUI::ubl_plot(const uint8_t x_plot, const uint8_t y_plot) { + + tft.canvas(GRID_OFFSET_X, GRID_OFFSET_Y, GRID_WIDTH, GRID_HEIGHT); + tft.set_background(COLOR_BACKGROUND); + tft.add_rectangle(0, 0, GRID_WIDTH, GRID_HEIGHT, COLOR_WHITE); + + for (uint16_t x = 0; x < GRID_MAX_POINTS_X ; x++) + for (uint16_t y = 0; y < GRID_MAX_POINTS_Y ; y++) + if (position_is_reachable({ ubl.mesh_index_to_xpos(x), ubl.mesh_index_to_ypos(y) })) + tft.add_bar(1 + (x * 2 + 1) * (GRID_WIDTH - 4) / GRID_MAX_POINTS_X / 2, GRID_HEIGHT - 3 - ((y * 2 + 1) * (GRID_HEIGHT - 4) / GRID_MAX_POINTS_Y / 2), 2, 2, COLOR_UBL); + + tft.add_rectangle((x_plot * 2 + 1) * (GRID_WIDTH - 4) / GRID_MAX_POINTS_X / 2 - 1, GRID_HEIGHT - 5 - ((y_plot * 2 + 1) * (GRID_HEIGHT - 4) / GRID_MAX_POINTS_Y / 2), 6, 6, COLOR_UBL); + + const xy_pos_t pos = { ubl.mesh_index_to_xpos(x_plot), ubl.mesh_index_to_ypos(y_plot) }, + lpos = pos.asLogical(); + + tft.canvas(320, GRID_OFFSET_Y + (GRID_HEIGHT - MENU_ITEM_HEIGHT) / 2 - MENU_ITEM_HEIGHT, 120, MENU_ITEM_HEIGHT); + tft.set_background(COLOR_BACKGROUND); + tft_string.set(X_LBL); + tft.add_text(0, MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string); + tft_string.set(ftostr52(lpos.x)); + tft_string.trim(); + tft.add_text(120 - tft_string.width(), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string); + + tft.canvas(320, GRID_OFFSET_Y + (GRID_HEIGHT - MENU_ITEM_HEIGHT) / 2, 120, MENU_ITEM_HEIGHT); + tft.set_background(COLOR_BACKGROUND); + tft_string.set(Y_LBL); + tft.add_text(0, MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string); + tft_string.set(ftostr52(lpos.y)); + tft_string.trim(); + tft.add_text(120 - tft_string.width(), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string); + + tft.canvas(320, GRID_OFFSET_Y + (GRID_HEIGHT - MENU_ITEM_HEIGHT) / 2 + MENU_ITEM_HEIGHT, 120, MENU_ITEM_HEIGHT); + tft.set_background(COLOR_BACKGROUND); + tft_string.set(Z_LBL); + tft.add_text(0, MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string); + tft_string.set(isnan(ubl.z_values[x_plot][y_plot]) ? "-----" : ftostr43sign(ubl.z_values[x_plot][y_plot])); + tft_string.trim(); + tft.add_text(120 - tft_string.width(), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string); + + constexpr uint8_t w = (TFT_WIDTH) / 10; + tft.canvas(GRID_OFFSET_X + (GRID_WIDTH - w) / 2, GRID_OFFSET_Y + GRID_HEIGHT + CONTROL_OFFSET - 5, w, MENU_ITEM_HEIGHT); + tft.set_background(COLOR_BACKGROUND); + tft_string.set(ui8tostr3rj(x_plot)); + tft_string.trim(); + tft.add_text(tft_string.center(w), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string); + + tft.canvas(GRID_OFFSET_X + GRID_WIDTH + CONTROL_OFFSET + 16 - 24, GRID_OFFSET_Y + (GRID_HEIGHT - MENU_ITEM_HEIGHT) / 2, w, MENU_ITEM_HEIGHT); + tft.set_background(COLOR_BACKGROUND); + tft_string.set(ui8tostr3rj(y_plot)); + tft_string.trim(); + tft.add_text(tft_string.center(w), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string); + + #if ENABLED(TOUCH_SCREEN) + touch.clear(); + draw_menu_navigation = false; + add_control(GRID_OFFSET_X + GRID_WIDTH + CONTROL_OFFSET, GRID_OFFSET_Y + CONTROL_OFFSET, UBL, ENCODER_STEPS_PER_MENU_ITEM * GRID_MAX_POINTS_X, imgUp); + add_control(GRID_OFFSET_X + GRID_WIDTH + CONTROL_OFFSET, GRID_OFFSET_Y + GRID_HEIGHT - CONTROL_OFFSET - 32, UBL, - ENCODER_STEPS_PER_MENU_ITEM * GRID_MAX_POINTS_X, imgDown); + add_control(GRID_OFFSET_X + CONTROL_OFFSET, GRID_OFFSET_Y + GRID_HEIGHT + CONTROL_OFFSET, UBL, - ENCODER_STEPS_PER_MENU_ITEM, imgLeft); + add_control(GRID_OFFSET_X + GRID_WIDTH - CONTROL_OFFSET - 32, GRID_OFFSET_Y + GRID_HEIGHT + CONTROL_OFFSET, UBL, ENCODER_STEPS_PER_MENU_ITEM, imgRight); + add_control(320, GRID_OFFSET_Y + GRID_HEIGHT + CONTROL_OFFSET, CLICK, imgLeveling); + add_control(224, TFT_HEIGHT - 34, BACK, imgBack); + #endif + } +#endif // AUTO_BED_LEVELING_UBL + +#if ENABLED(BABYSTEP_ZPROBE_OFFSET) + #include "../../feature/babystep.h" +#endif + +#if HAS_BED_PROBE + #include "../../module/probe.h" +#endif + +#define Z_SELECTION_Z 1 +#define Z_SELECTION_Z_PROBE -1 + +struct MotionAxisState { + xy_int_t xValuePos, yValuePos, zValuePos, eValuePos, stepValuePos, zTypePos, eNamePos; + float currentStepSize = 10.0; + int z_selection = Z_SELECTION_Z; + uint8_t e_selection = 0; + bool blocked = false; + char message[32]; +}; + +MotionAxisState motionAxisState; + +#define E_BTN_COLOR COLOR_YELLOW +#define X_BTN_COLOR COLOR_CORAL_RED +#define Y_BTN_COLOR COLOR_VIVID_GREEN +#define Z_BTN_COLOR COLOR_LIGHT_BLUE + +#define BTN_WIDTH 64 +#define BTN_HEIGHT 52 +#define X_MARGIN 20 +#define Y_MARGIN 15 + +static void quick_feedback() { + #if HAS_CHIRP + ui.chirp(); // Buzz and wait. Is the delay needed for buttons to settle? + #if BOTH(HAS_LCD_MENU, USE_BEEPER) + for (int8_t i = 5; i--;) { buzzer.tick(); delay(2); } + #elif HAS_LCD_MENU + delay(10); + #endif + #endif +} + +#define CUR_STEP_VALUE_WIDTH 104 +static void drawCurStepValue() { + tft_string.set((uint8_t *)ftostr52sp(motionAxisState.currentStepSize)); + tft_string.add("mm"); + tft.canvas(motionAxisState.stepValuePos.x, motionAxisState.stepValuePos.y, CUR_STEP_VALUE_WIDTH, BTN_HEIGHT); + tft.set_background(COLOR_BACKGROUND); + tft.add_text(tft_string.center(CUR_STEP_VALUE_WIDTH), 0, COLOR_AXIS_HOMED, tft_string); +} + +static void drawCurZSelection() { + tft_string.set("Z"); + tft.canvas(motionAxisState.zTypePos.x, motionAxisState.zTypePos.y, tft_string.width(), 34); + tft.set_background(COLOR_BACKGROUND); + tft.add_text(0, 0, Z_BTN_COLOR, tft_string); + tft.queue.sync(); + tft_string.set("Offset"); + tft.canvas(motionAxisState.zTypePos.x, motionAxisState.zTypePos.y + 34, tft_string.width(), 34); + tft.set_background(COLOR_BACKGROUND); + if (motionAxisState.z_selection == Z_SELECTION_Z_PROBE) { + tft.add_text(0, 0, Z_BTN_COLOR, tft_string); + } +} + +static void drawCurESelection() { + tft.canvas(motionAxisState.eNamePos.x, motionAxisState.eNamePos.y, BTN_WIDTH, BTN_HEIGHT); + tft.set_background(COLOR_BACKGROUND); + tft_string.set("E"); + tft.add_text(0, 0, E_BTN_COLOR , tft_string); + tft.add_text(tft_string.width(), 0, E_BTN_COLOR, ui8tostr3rj(motionAxisState.e_selection)); +} + +static void drawMessage(const char *msg) { + tft.canvas(X_MARGIN, TFT_HEIGHT - Y_MARGIN - 34, TFT_HEIGHT / 2, 34); + tft.set_background(COLOR_BACKGROUND); + tft.add_text(0, 0, COLOR_YELLOW, msg); +} + +static void drawAxisValue(const AxisEnum axis) { + const float value = ( + TERN_(HAS_BED_PROBE, axis == Z_AXIS && motionAxisState.z_selection == Z_SELECTION_Z_PROBE ? probe.offset.z :) + ui.manual_move.axis_value(axis) + ); + xy_int_t pos; + uint16_t color; + switch (axis) { + case X_AXIS: pos = motionAxisState.xValuePos; color = X_BTN_COLOR; break; + case Y_AXIS: pos = motionAxisState.yValuePos; color = Y_BTN_COLOR; break; + case Z_AXIS: pos = motionAxisState.zValuePos; color = Z_BTN_COLOR; break; + case E_AXIS: pos = motionAxisState.eValuePos; color = E_BTN_COLOR; break; + default: return; + } + tft.canvas(pos.x, pos.y, BTN_WIDTH + X_MARGIN, BTN_HEIGHT); + tft.set_background(COLOR_BACKGROUND); + tft_string.set(ftostr52sp(value)); + tft.add_text(0, 0, color, tft_string); +} + +static void moveAxis(const AxisEnum axis, const int8_t direction) { + quick_feedback(); + + #if ENABLED(PREVENT_COLD_EXTRUSION) + if (axis == E_AXIS && thermalManager.tooColdToExtrude(motionAxisState.e_selection)) { + drawMessage("Too cold"); + return; + } + #endif + + const float diff = motionAxisState.currentStepSize * direction; + + if (axis == Z_AXIS && motionAxisState.z_selection == Z_SELECTION_Z_PROBE) { + #if ENABLED(BABYSTEP_ZPROBE_OFFSET) + const int16_t babystep_increment = direction * BABYSTEP_SIZE_Z; + const bool do_probe = DISABLED(BABYSTEP_HOTEND_Z_OFFSET) || active_extruder == 0; + const float bsDiff = planner.steps_to_mm[Z_AXIS] * babystep_increment, + new_probe_offset = probe.offset.z + bsDiff, + new_offs = TERN(BABYSTEP_HOTEND_Z_OFFSET + , do_probe ? new_probe_offset : hotend_offset[active_extruder].z - bsDiff + , new_probe_offset + ); + if (WITHIN(new_offs, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX)) { + babystep.add_steps(Z_AXIS, babystep_increment); + if (do_probe) + probe.offset.z = new_offs; + else + TERN(BABYSTEP_HOTEND_Z_OFFSET, hotend_offset[active_extruder].z = new_offs, NOOP); + drawMessage(""); // clear the error + drawAxisValue(axis); + } + else { + drawMessage(GET_TEXT(MSG_LCD_SOFT_ENDSTOPS)); + } + #elif HAS_BED_PROBE + // only change probe.offset.z + probe.offset.z += diff; + if (direction < 0 && current_position[axis] < Z_PROBE_OFFSET_RANGE_MIN) { + current_position[axis] = Z_PROBE_OFFSET_RANGE_MIN; + drawMessage(GET_TEXT(MSG_LCD_SOFT_ENDSTOPS)); + } + else if (direction > 0 && current_position[axis] > Z_PROBE_OFFSET_RANGE_MAX) { + current_position[axis] = Z_PROBE_OFFSET_RANGE_MAX; + drawMessage(GET_TEXT(MSG_LCD_SOFT_ENDSTOPS)); + } + else { + drawMessage(""); // clear the error + } + drawAxisValue(axis); + #endif + return; + } + + if (!ui.manual_move.processing) { + // Get motion limit from software endstops, if any + float min, max; + soft_endstop.get_manual_axis_limits(axis, min, max); + + // Delta limits XY based on the current offset from center + // This assumes the center is 0,0 + #if ENABLED(DELTA) + if (axis != Z_AXIS && axis != E_AXIS) { + max = SQRT(sq((float)(DELTA_PRINTABLE_RADIUS)) - sq(current_position[Y_AXIS - axis])); // (Y_AXIS - axis) == the other axis + min = -max; + } + #endif + + // Get the new position + const bool limited = ui.manual_move.apply_diff(axis, diff, min, max); + #if IS_KINEMATIC + UNUSED(limited); + #else + PGM_P const msg = limited ? GET_TEXT(MSG_LCD_SOFT_ENDSTOPS) : NUL_STR; + drawMessage(msg); + #endif + + ui.manual_move.soon(axis OPTARG(MULTI_E_MANUAL, motionAxisState.e_selection)); + } + + drawAxisValue(axis); +} + +static void e_plus() { moveAxis(E_AXIS, 1); } +static void e_minus() { moveAxis(E_AXIS, -1); } +static void x_minus() { moveAxis(X_AXIS, -1); } +static void x_plus() { moveAxis(X_AXIS, 1); } +static void y_plus() { moveAxis(Y_AXIS, 1); } +static void y_minus() { moveAxis(Y_AXIS, -1); } +static void z_plus() { moveAxis(Z_AXIS, 1); } +static void z_minus() { moveAxis(Z_AXIS, -1); } + +#if ENABLED(TOUCH_SCREEN) + static void e_select() { + motionAxisState.e_selection++; + if (motionAxisState.e_selection >= EXTRUDERS) { + motionAxisState.e_selection = 0; + } + + quick_feedback(); + drawCurESelection(); + drawAxisValue(E_AXIS); + } + + static void do_home() { + quick_feedback(); + drawMessage(GET_TEXT(MSG_LEVEL_BED_HOMING)); + queue.inject_P(G28_STR); + // Disable touch until home is done + TERN_(TOUCH_SCREEN, touch.disable()); + drawAxisValue(E_AXIS); + drawAxisValue(X_AXIS); + drawAxisValue(Y_AXIS); + drawAxisValue(Z_AXIS); + } + + static void step_size() { + motionAxisState.currentStepSize = motionAxisState.currentStepSize / 10.0; + if (motionAxisState.currentStepSize < 0.0015) motionAxisState.currentStepSize = 10.0; + quick_feedback(); + drawCurStepValue(); + } +#endif + +#if HAS_BED_PROBE + static void z_select() { + motionAxisState.z_selection *= -1; + quick_feedback(); + drawCurZSelection(); + drawAxisValue(Z_AXIS); + } +#endif + +static void disable_steppers() { + quick_feedback(); + queue.inject_P(PSTR("M84")); +} + +static void drawBtn(int x, int y, const char *label, intptr_t data, MarlinImage img, uint16_t bgColor, bool enabled = true) { + uint16_t width = Images[imgBtn52Rounded].width; + uint16_t height = Images[imgBtn52Rounded].height; + + if (!enabled) bgColor = COLOR_CONTROL_DISABLED; + + tft.canvas(x, y, width, height); + tft.set_background(COLOR_BACKGROUND); + tft.add_image(0, 0, imgBtn52Rounded, bgColor, COLOR_BACKGROUND, COLOR_DARKGREY); + + // TODO: Make an add_text() taking a font arg + if (label) { + tft_string.set(label); + tft_string.trim(); + tft.add_text(tft_string.center(width), height / 2 - tft_string.font_height() / 2, bgColor, tft_string); + } + else { + tft.add_image(0, 0, img, bgColor, COLOR_BACKGROUND, COLOR_DARKGREY); + } + + TERN_(TOUCH_SCREEN, if (enabled) touch.add_control(BUTTON, x, y, width, height, data)); +} + +void MarlinUI::move_axis_screen() { + // Reset + defer_status_screen(true); + motionAxisState.blocked = false; + TERN_(TOUCH_SCREEN, touch.enable()); + + ui.clear_lcd(); + + TERN_(TOUCH_SCREEN, touch.clear()); + + const bool busy = printingIsActive(); + + // Babysteps during printing? Select babystep for Z probe offset + if (busy && ENABLED(BABYSTEP_ZPROBE_OFFSET)) + motionAxisState.z_selection = Z_SELECTION_Z_PROBE; + + // ROW 1 -> E- Y- CurY Z+ + int x = X_MARGIN, y = Y_MARGIN, spacing = 0; + + drawBtn(x, y, "E+", (intptr_t)e_plus, imgUp, E_BTN_COLOR, !busy); + + spacing = (TFT_WIDTH - X_MARGIN * 2 - 3 * BTN_WIDTH) / 2; + x += BTN_WIDTH + spacing; + drawBtn(x, y, "Y+", (intptr_t)y_plus, imgUp, Y_BTN_COLOR, !busy); + + // Cur Y + x += BTN_WIDTH; + motionAxisState.yValuePos.x = x + 2; + motionAxisState.yValuePos.y = y; + drawAxisValue(Y_AXIS); + + x += spacing; + drawBtn(x, y, "Z+", (intptr_t)z_plus, imgUp, Z_BTN_COLOR, !busy || ENABLED(BABYSTEP_ZPROBE_OFFSET)); //only enabled when not busy or have baby step + + // ROW 2 -> "Ex" X- HOME X+ "Z" + y += BTN_HEIGHT + (TFT_HEIGHT - Y_MARGIN * 2 - 4 * BTN_HEIGHT) / 3; + x = X_MARGIN; + spacing = (TFT_WIDTH - X_MARGIN * 2 - 5 * BTN_WIDTH) / 4; + + motionAxisState.eNamePos.x = x; + motionAxisState.eNamePos.y = y; + drawCurESelection(); + TERN_(TOUCH_SCREEN, if (!busy) touch.add_control(BUTTON, x, y, BTN_WIDTH, BTN_HEIGHT, (intptr_t)e_select)); + + x += BTN_WIDTH + spacing; + drawBtn(x, y, "X-", (intptr_t)x_minus, imgLeft, X_BTN_COLOR, !busy); + + x += BTN_WIDTH + spacing; //imgHome is 64x64 + TERN_(TOUCH_SCREEN, add_control(TFT_WIDTH / 2 - Images[imgHome].width / 2, y - (Images[imgHome].width - BTN_HEIGHT) / 2, BUTTON, (intptr_t)do_home, imgHome, !busy)); + + x += BTN_WIDTH + spacing; + uint16_t xplus_x = x; + drawBtn(x, y, "X+", (intptr_t)x_plus, imgRight, X_BTN_COLOR, !busy); + + x += BTN_WIDTH + spacing; + motionAxisState.zTypePos.x = x; + motionAxisState.zTypePos.y = y; + drawCurZSelection(); + #if BOTH(HAS_BED_PROBE, TOUCH_SCREEN) + if (!busy) touch.add_control(BUTTON, x, y, BTN_WIDTH, 34 * 2, (intptr_t)z_select); + #endif + + // ROW 3 -> E- CurX Y- Z- + y += BTN_HEIGHT + (TFT_HEIGHT - Y_MARGIN * 2 - 4 * BTN_HEIGHT) / 3; + x = X_MARGIN; + spacing = (TFT_WIDTH - X_MARGIN * 2 - 3 * BTN_WIDTH) / 2; + + drawBtn(x, y, "E-", (intptr_t)e_minus, imgDown, E_BTN_COLOR, !busy); + + // Cur E + motionAxisState.eValuePos.x = x; + motionAxisState.eValuePos.y = y + BTN_HEIGHT + 2; + drawAxisValue(E_AXIS); + + // Cur X + motionAxisState.xValuePos.x = BTN_WIDTH + (TFT_WIDTH - X_MARGIN * 2 - 5 * BTN_WIDTH) / 4; //X- pos + motionAxisState.xValuePos.y = y - 10; + drawAxisValue(X_AXIS); + + x += BTN_WIDTH + spacing; + drawBtn(x, y, "Y-", (intptr_t)y_minus, imgDown, Y_BTN_COLOR, !busy); + + x += BTN_WIDTH + spacing; + drawBtn(x, y, "Z-", (intptr_t)z_minus, imgDown, Z_BTN_COLOR, !busy || ENABLED(BABYSTEP_ZPROBE_OFFSET)); //only enabled when not busy or have baby step + + // Cur Z + motionAxisState.zValuePos.x = x; + motionAxisState.zValuePos.y = y + BTN_HEIGHT + 2; + drawAxisValue(Z_AXIS); + + // ROW 4 -> step_size disable steppers back + y = TFT_HEIGHT - Y_MARGIN - 32; // + x = TFT_WIDTH / 2 - CUR_STEP_VALUE_WIDTH / 2; + motionAxisState.stepValuePos.x = x; + motionAxisState.stepValuePos.y = y; + if (!busy) { + drawCurStepValue(); + TERN_(TOUCH_SCREEN, touch.add_control(BUTTON, motionAxisState.stepValuePos.x, motionAxisState.stepValuePos.y, CUR_STEP_VALUE_WIDTH, BTN_HEIGHT, (intptr_t)step_size)); + } + + // aligned with x+ + drawBtn(xplus_x, TFT_HEIGHT - Y_MARGIN - BTN_HEIGHT, "off", (intptr_t)disable_steppers, imgCancel, COLOR_WHITE, !busy); + + TERN_(TOUCH_SCREEN, add_control(TFT_WIDTH - X_MARGIN - BTN_WIDTH, y, BACK, imgBack)); +} + +#endif // HAS_UI_480x320 diff --git a/Marlin/src/lcd/tft/ui_1024x600.h b/Marlin/src/lcd/tft/ui_1024x600.h new file mode 100644 index 000000000000..dd8c1cc6ec47 --- /dev/null +++ b/Marlin/src/lcd/tft/ui_1024x600.h @@ -0,0 +1,43 @@ +/** + * 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 MARLIN_LOGO_FULL_SIZE MarlinLogo480x320x16 + +#include "ui_common.h" + +#define TFT_STATUS_TOP_Y 4 +#define TFT_TOP_LINE_Y 4 + +#define MENU_TEXT_X_OFFSET 16 +#define MENU_TEXT_Y_OFFSET 7 + +#define MENU_ITEM_ICON_X 5 +#define MENU_ITEM_ICON_Y 5 +#define MENU_ITEM_ICON_SPACE 42 + +#define MENU_FONT_NAME Helvetica18 +#define SYMBOLS_FONT_NAME Helvetica18_symbols +#define MENU_ITEM_HEIGHT 43 +#define FONT_LINE_HEIGHT 34 + +#define MENU_LINE_HEIGHT (MENU_ITEM_HEIGHT + 2) diff --git a/Marlin/src/lcd/tft/ui_320x240.cpp b/Marlin/src/lcd/tft/ui_320x240.cpp index de8498c5ff0f..786dc61f60d9 100644 --- a/Marlin/src/lcd/tft/ui_320x240.cpp +++ b/Marlin/src/lcd/tft/ui_320x240.cpp @@ -24,9 +24,9 @@ #if HAS_UI_320x240 -#include "ui_320x240.h" +#include "ui_common.h" -#include "../ultralcd.h" +#include "../marlinui.h" #include "../menu/menu.h" #include "../../libs/numtostr.h" @@ -45,12 +45,6 @@ #include "../../feature/bedlevel/bedlevel.h" #endif -#if !HAS_LCD_MENU - #error "Seriously? High resolution TFT screen without menu?" -#endif - -static bool draw_menu_navigation = false; - void MarlinUI::tft_idle() { #if ENABLED(TOUCH_SCREEN) if (draw_menu_navigation) { @@ -65,48 +59,37 @@ void MarlinUI::tft_idle() { TERN_(TOUCH_SCREEN, touch.idle()); } -void MarlinUI::init_lcd() { - tft.init(); - tft.set_font(MENU_FONT_NAME); - #ifdef SYMBOLS_FONT_NAME - tft.add_glyphs(SYMBOLS_FONT_NAME); - #endif - TERN_(TOUCH_SCREEN, touch.init()); - clear_lcd(); -} - -bool MarlinUI::detected() { return true; } - -void MarlinUI::clear_lcd() { - #if ENABLED(TOUCH_SCREEN) - touch.reset(); - draw_menu_navigation = false; - #endif - - tft.queue.reset(); - tft.fill(0, 0, TFT_WIDTH, TFT_HEIGHT, COLOR_BACKGROUND); -} - #if ENABLED(SHOW_BOOTSCREEN) - #ifndef BOOTSCREEN_TIMEOUT - #define BOOTSCREEN_TIMEOUT 1500 - #endif void MarlinUI::show_bootscreen() { tft.queue.reset(); tft.canvas(0, 0, TFT_WIDTH, TFT_HEIGHT); - tft.add_image(0, 0, imgBootScreen); // MarlinLogo320x240x16 - + #if ENABLED(BOOT_MARLIN_LOGO_SMALL) + #define BOOT_LOGO_W 195 // MarlinLogo195x59x16 + #define BOOT_LOGO_H 59 + #define SITE_URL_Y (TFT_HEIGHT - 46) + tft.set_background(COLOR_BACKGROUND); + #else + #define BOOT_LOGO_W TFT_WIDTH // MarlinLogo320x240x16 + #define BOOT_LOGO_H TFT_HEIGHT + #define SITE_URL_Y (TFT_HEIGHT - 52) + #endif + tft.add_image((TFT_WIDTH - BOOT_LOGO_W) / 2, (TFT_HEIGHT - BOOT_LOGO_H) / 2, imgBootScreen); #ifdef WEBSITE_URL - tft.add_text(4, 188, COLOR_WEBSITE_URL, WEBSITE_URL); + tft_string.set(WEBSITE_URL); + tft.add_text(tft_string.center(TFT_WIDTH), SITE_URL_Y, COLOR_WEBSITE_URL, tft_string); #endif tft.queue.sync(); - safe_delay(BOOTSCREEN_TIMEOUT); + } + + void MarlinUI::bootscreen_completion(const millis_t sofar) { + if ((BOOTSCREEN_TIMEOUT) > sofar) safe_delay((BOOTSCREEN_TIMEOUT) - sofar); clear_lcd(); } -#endif // SHOW_BOOTSCREEN + +#endif void MarlinUI::draw_kill_screen() { tft.queue.reset(); @@ -136,28 +119,34 @@ void MarlinUI::draw_kill_screen() { void draw_heater_status(uint16_t x, uint16_t y, const int8_t Heater) { MarlinImage image = imgHotEnd; uint16_t Color; - float currentTemperature, targetTemperature; + celsius_t currentTemperature, targetTemperature; if (Heater >= 0) { // HotEnd - currentTemperature = thermalManager.degHotend(Heater); + currentTemperature = thermalManager.wholeDegHotend(Heater); targetTemperature = thermalManager.degTargetHotend(Heater); } -#if HAS_HEATED_BED - else if (Heater == H_BED) { - currentTemperature = thermalManager.degBed(); - targetTemperature = thermalManager.degTargetBed(); - } -#endif // HAS_HEATED_BED -#if HAS_TEMP_CHAMBER - else if (Heater == H_CHAMBER) { - currentTemperature = thermalManager.degChamber(); - #if HAS_HEATED_CHAMBER - targetTemperature = thermalManager.degTargetChamber(); - #else - targetTemperature = ABSOLUTE_ZERO; - #endif - } -#endif // HAS_TEMP_CHAMBER + #if HAS_HEATED_BED + else if (Heater == H_BED) { + currentTemperature = thermalManager.wholeDegBed(); + targetTemperature = thermalManager.degTargetBed(); + } + #endif + #if HAS_TEMP_CHAMBER + else if (Heater == H_CHAMBER) { + currentTemperature = thermalManager.wholeDegChamber(); + #if HAS_HEATED_CHAMBER + targetTemperature = thermalManager.degTargetChamber(); + #else + targetTemperature = ABSOLUTE_ZERO; + #endif + } + #endif + #if HAS_TEMP_COOLER + else if (Heater == H_COOLER) { + currentTemperature = thermalManager.wholeDegCooler(); + targetTemperature = TERN(HAS_COOLER, thermalManager.degTargetCooler(), ABSOLUTE_ZERO); + } + #endif else return; TERN_(TOUCH_SCREEN, if (targetTemperature >= 0) touch.add_control(HEATER, x, y, 64, 100, Heater)); @@ -170,31 +159,37 @@ void draw_heater_status(uint16_t x, uint16_t y, const int8_t Heater) { if (currentTemperature >= 50) Color = COLOR_HOTEND; } #if HAS_HEATED_BED - else if (Heater == H_BED) { - if (currentTemperature >= 50) Color = COLOR_HEATED_BED; - image = targetTemperature > 0 ? imgBedHeated : imgBed; - } - #endif // HAS_HEATED_BED + else if (Heater == H_BED) { + if (currentTemperature >= 50) Color = COLOR_HEATED_BED; + image = targetTemperature > 0 ? imgBedHeated : imgBed; + } + #endif #if HAS_TEMP_CHAMBER - else if (Heater == H_CHAMBER) { - if (currentTemperature >= 50) Color = COLOR_CHAMBER; - image = targetTemperature > 0 ? imgChamberHeated : imgChamber; - } - #endif // HAS_TEMP_CHAMBER + else if (Heater == H_CHAMBER) { + if (currentTemperature >= 50) Color = COLOR_CHAMBER; + image = targetTemperature > 0 ? imgChamberHeated : imgChamber; + } + #endif + #if HAS_TEMP_COOLER + else if (Heater == H_COOLER) { + if (currentTemperature <= 26) Color = COLOR_COLD; + if (currentTemperature > 26) Color = COLOR_RED; + image = targetTemperature > 26 ? imgCoolerHot : imgCooler; + } + #endif tft.add_image(0, 18, image, Color); - tft_string.set((uint8_t *)i16tostr3rj(currentTemperature + 0.5)); + tft_string.set((uint8_t *)i16tostr3rj(currentTemperature)); tft_string.add(LCD_STR_DEGREE); tft_string.trim(); tft.add_text(tft_string.center(64) + 2, 72, Color, tft_string); if (targetTemperature >= 0) { - tft_string.set((uint8_t *)i16tostr3rj(targetTemperature + 0.5)); + tft_string.set((uint8_t *)i16tostr3rj(targetTemperature)); tft_string.add(LCD_STR_DEGREE); tft_string.trim(); tft.add_text(tft_string.center(64) + 2, 8, Color, tft_string); - } } @@ -226,7 +221,7 @@ void MarlinUI::draw_status_screen() { TERN_(TOUCH_SCREEN, touch.clear()); // heaters and fan - uint16_t i, x, y = POS_Y; + uint16_t i, x, y = TFT_STATUS_TOP_Y; for (i = 0 ; i < ITEMS_COUNT; i++) { x = (320 / ITEMS_COUNT - 64) / 2 + (320 * i / ITEMS_COUNT); @@ -246,6 +241,9 @@ void MarlinUI::draw_status_screen() { #ifdef ITEM_CHAMBER case ITEM_CHAMBER: draw_heater_status(x, y, H_CHAMBER); break; #endif + #ifdef ITEM_COOLER + case ITEM_COOLER: draw_heater_status(x, y, H_COOLER); break; + #endif #ifdef ITEM_FAN case ITEM_FAN: draw_fan_status(x, y, blink); break; #endif @@ -257,42 +255,38 @@ void MarlinUI::draw_status_screen() { tft.set_background(COLOR_BACKGROUND); tft.add_rectangle(0, 0, 312, 24, COLOR_AXIS_HOMED); - uint16_t color; - uint16_t offset; - bool is_homed; - tft.add_text( 10, 3, COLOR_AXIS_HOMED , "X"); tft.add_text(127, 3, COLOR_AXIS_HOMED , "Y"); tft.add_text(219, 3, COLOR_AXIS_HOMED , "Z"); - is_homed = TEST(axis_homed, X_AXIS); - tft_string.set(blink & !is_homed ? "?" : ftostr4sign(LOGICAL_X_POSITION(current_position.x))); - tft.add_text( 68 - tft_string.width(), 3, is_homed ? COLOR_AXIS_HOMED : COLOR_AXIS_NOT_HOMED, tft_string); + bool not_homed = axis_should_home(X_AXIS); + tft_string.set(blink && not_homed ? "?" : ftostr4sign(LOGICAL_X_POSITION(current_position.x))); + tft.add_text( 68 - tft_string.width(), 3, not_homed ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); - is_homed = TEST(axis_homed, Y_AXIS); - tft_string.set(blink & !is_homed ? "?" : ftostr4sign(LOGICAL_Y_POSITION(current_position.y))); - tft.add_text(185 - tft_string.width(), 3, is_homed ? COLOR_AXIS_HOMED : COLOR_AXIS_NOT_HOMED, tft_string); + not_homed = axis_should_home(Y_AXIS); + tft_string.set(blink && not_homed ? "?" : ftostr4sign(LOGICAL_Y_POSITION(current_position.y))); + tft.add_text(185 - tft_string.width(), 3, not_homed ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); - is_homed = TEST(axis_homed, Z_AXIS); - if (blink & !is_homed) { + not_homed = axis_should_home(Z_AXIS); + uint16_t offset = 25; + if (blink && not_homed) tft_string.set("?"); - offset = 25; // ".00" - } else { const float z = LOGICAL_Z_POSITION(current_position.z); tft_string.set(ftostr52sp((int16_t)z)); tft_string.rtrim(); - offset = tft_string.width(); + offset += tft_string.width(); tft_string.set(ftostr52sp(z)); - offset += 25 - tft_string.width(); + offset -= tft_string.width(); } - tft.add_text(301 - tft_string.width() - offset, 3, is_homed ? COLOR_AXIS_HOMED : COLOR_AXIS_NOT_HOMED, tft_string); + tft.add_text(301 - tft_string.width() - offset, 3, not_homed ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); + TERN_(TOUCH_SCREEN, touch.add_control(MOVE_AXIS, 0, 103, 312, 24)); // feed rate tft.canvas(70, 136, 80, 32); tft.set_background(COLOR_BACKGROUND); - color = feedrate_percentage == 100 ? COLOR_RATE_100 : COLOR_RATE_ALTERED; + uint16_t color = feedrate_percentage == 100 ? COLOR_RATE_100 : COLOR_RATE_ALTERED; tft.add_image(0, 0, imgFeedRate, color); tft_string.set(i16tostr3rj(feedrate_percentage)); tft_string.add('%'); @@ -336,55 +330,12 @@ void MarlinUI::draw_status_screen() { #if ENABLED(TOUCH_SCREEN) add_control(256, 130, menu_main, imgSettings); - TERN_(SDSUPPORT, add_control(0, 130, menu_media, imgSD, card.isMounted() && !printingIsActive(), COLOR_CONTROL_ENABLED, card.isMounted() && printingIsActive() ? COLOR_BUSY : COLOR_CONTROL_DISABLED)); + TERN_(SDSUPPORT, add_control(0, 130, menu_media, imgSD, !printingIsActive(), COLOR_CONTROL_ENABLED, card.isMounted() && printingIsActive() ? COLOR_BUSY : COLOR_CONTROL_DISABLED)); #endif } -// Draw a static item with no left-right margin required. Centered by default. -void MenuItem_static::draw(const uint8_t row, PGM_P const pstr, const uint8_t style/*=SS_DEFAULT*/, const char * const vstr/*=nullptr*/) { - menu_item(row); - tft_string.set(pstr, itemIndex, itemString); - if (vstr) - tft_string.add(vstr); - tft.add_text(tft_string.center(TFT_WIDTH), MENU_TEXT_Y_OFFSET, COLOR_YELLOW, tft_string); -} - -// Draw a generic menu item with pre_char (if selected) and post_char -void MenuItemBase::_draw(const bool sel, const uint8_t row, PGM_P const pstr, const char pre_char, const char post_char) { - menu_item(row, sel); - - uint8_t *string = (uint8_t *)pstr; - MarlinImage image = noImage; - switch (*string) { - case 0x01: image = imgRefresh; break; // LCD_STR_REFRESH - case 0x02: image = imgDirectory; break; // LCD_STR_FOLDER - } - - uint8_t offset = MENU_TEXT_X_OFFSET; - if (image != noImage) { - string++; - offset = 32; - tft.add_image(0, 0, image, COLOR_MENU_TEXT, sel ? COLOR_SELECTION_BG : COLOR_BACKGROUND); - } - - tft_string.set(string, itemIndex, itemString); - tft.add_text(offset, MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string); -} - -// Draw a menu item with a (potentially) editable value -void MenuEditItemBase::draw(const bool sel, const uint8_t row, PGM_P const pstr, const char* const data, const bool pgm) { - menu_item(row, sel); - - tft_string.set(pstr, itemIndex, itemString); - tft.add_text(MENU_TEXT_X_OFFSET, MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string); - if (data) { - tft_string.set(data); - tft.add_text(TFT_WIDTH - MENU_TEXT_X_OFFSET - tft_string.width(), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string); - } -} - // Low-level draw_edit_screen can be used to draw an edit screen from anyplace -void MenuEditItemBase::draw_edit_screen(PGM_P const pstr, const char* const value/*=nullptr*/) { +void MenuEditItemBase::draw_edit_screen(PGM_P const pstr, const char * const value/*=nullptr*/) { ui.encoder_direction_normal(); TERN_(TOUCH_SCREEN, touch.clear()); @@ -407,44 +358,48 @@ void MenuEditItemBase::draw_edit_screen(PGM_P const pstr, const char* const valu menu_line(line - 1); tft_string.set(X_LBL); - tft.add_text(52, MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string); + tft.add_text(TFT_WIDTH / 2 - 120, MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string); tft_string.set(ftostr52(LOGICAL_X_POSITION(current_position.x))); tft_string.trim(); - tft.add_text(144 - tft_string.width(), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string); + tft.add_text(TFT_WIDTH / 2 - 16 - tft_string.width(), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string); tft_string.set(Y_LBL); - tft.add_text(176, MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string); + tft.add_text(TFT_WIDTH / 2 + 16, MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string); tft_string.set(ftostr52(LOGICAL_X_POSITION(current_position.y))); tft_string.trim(); - tft.add_text(268 - tft_string.width(), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string); + tft.add_text(TFT_WIDTH / 2 + 120 - tft_string.width(), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string); } #endif extern screenFunc_t _manual_move_func_ptr; if (ui.currentScreen != _manual_move_func_ptr && !ui.external_control) { - #define SLIDER_LENGHT 224 + #define SLIDER_LENGTH 224 #define SLIDER_Y_POSITION 140 - tft.canvas((TFT_WIDTH - SLIDER_LENGHT) / 2, SLIDER_Y_POSITION, SLIDER_LENGHT, 16); + tft.canvas((TFT_WIDTH - SLIDER_LENGTH) / 2, SLIDER_Y_POSITION, SLIDER_LENGTH, 16); tft.set_background(COLOR_BACKGROUND); - int16_t position = (SLIDER_LENGHT - 2) * ui.encoderPosition / maxEditValue; + int16_t position = (SLIDER_LENGTH - 2) * ui.encoderPosition / maxEditValue; tft.add_bar(0, 7, 1, 2, ui.encoderPosition == 0 ? COLOR_SLIDER_INACTIVE : COLOR_SLIDER); tft.add_bar(1, 6, position, 4, COLOR_SLIDER); - tft.add_bar(position + 1, 6, SLIDER_LENGHT - 2 - position, 4, COLOR_SLIDER_INACTIVE); - tft.add_bar(SLIDER_LENGHT - 1, 7, 1, 2, int32_t(ui.encoderPosition) == maxEditValue ? COLOR_SLIDER : COLOR_SLIDER_INACTIVE); + tft.add_bar(position + 1, 6, SLIDER_LENGTH - 2 - position, 4, COLOR_SLIDER_INACTIVE); + tft.add_bar(SLIDER_LENGTH - 1, 7, 1, 2, int32_t(ui.encoderPosition) == maxEditValue ? COLOR_SLIDER : COLOR_SLIDER_INACTIVE); #if ENABLED(TOUCH_SCREEN) - tft.add_image((SLIDER_LENGHT - 8) * ui.encoderPosition / maxEditValue, 0, imgSlider, COLOR_SLIDER); - touch.add_control(SLIDER, (TFT_WIDTH - SLIDER_LENGHT) / 2, SLIDER_Y_POSITION - 8, SLIDER_LENGHT, 32, maxEditValue); + tft.add_image((SLIDER_LENGTH - 8) * ui.encoderPosition / maxEditValue, 0, imgSlider, COLOR_SLIDER); + touch.add_control(SLIDER, (TFT_WIDTH - SLIDER_LENGTH) / 2, SLIDER_Y_POSITION - 8, SLIDER_LENGTH, 32, maxEditValue); #endif } + tft.draw_edit_screen_buttons(); +} + +void TFT::draw_edit_screen_buttons() { #if ENABLED(TOUCH_SCREEN) - add_control(32, 176, DECREASE, imgDecrease); - add_control(224, 176, INCREASE, imgIncrease); - add_control(128, 176, CLICK, imgConfirm); + add_control(32, TFT_HEIGHT - 64, DECREASE, imgDecrease); + add_control(224, TFT_HEIGHT - 64, INCREASE, imgIncrease); + add_control(128, TFT_HEIGHT - 64, CLICK, imgConfirm); #endif } @@ -452,7 +407,7 @@ void MenuEditItemBase::draw_edit_screen(PGM_P const pstr, const char* const valu void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const bool yesno, PGM_P const pref, const char * const string/*=nullptr*/, PGM_P const suff/*=nullptr*/) { uint16_t line = 1; - if (string == NULL) line++; + if (!string) line++; menu_line(line++); tft_string.set(pref); @@ -473,26 +428,18 @@ void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const tft.add_text(tft_string.center(TFT_WIDTH), MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string); } #if ENABLED(TOUCH_SCREEN) - add_control(48, 176, CANCEL, imgCancel, true, yesno ? HALF(COLOR_CONTROL_CANCEL) : COLOR_CONTROL_CANCEL); - add_control(208, 176, CONFIRM, imgConfirm, true, yesno ? COLOR_CONTROL_CONFIRM : HALF(COLOR_CONTROL_CONFIRM)); + add_control(48, TFT_HEIGHT - 64, CANCEL, imgCancel, true, yesno ? HALF(COLOR_CONTROL_CANCEL) : COLOR_CONTROL_CANCEL); + add_control(208, TFT_HEIGHT - 64, CONFIRM, imgConfirm, true, yesno ? COLOR_CONTROL_CONFIRM : HALF(COLOR_CONTROL_CONFIRM)); #endif } -#if ENABLED(SDSUPPORT) - void MenuItem_sdbase::draw(const bool sel, const uint8_t row, PGM_P const, CardReader &theCard, const bool isDir) { - menu_item(row, sel); - if (isDir) - tft.add_image(0, 0, imgDirectory, COLOR_MENU_TEXT, sel ? COLOR_SELECTION_BG : COLOR_BACKGROUND); - tft.add_text(32, MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, theCard.longest_filename()); - } -#endif - #if ENABLED(ADVANCED_PAUSE_FEATURE) + void MarlinUI::draw_hotend_status(const uint8_t row, const uint8_t extruder) { #if ENABLED(TOUCH_SCREEN) touch.clear(); draw_menu_navigation = false; - touch.add_control(RESUME_CONTINUE , 0, 0, 320, 240); + touch.add_control(RESUME_CONTINUE , 0, 0, TFT_WIDTH, TFT_HEIGHT); #endif menu_line(row); @@ -500,7 +447,7 @@ void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const tft_string.add('E'); tft_string.add((char)('1' + extruder)); tft_string.add(' '); - tft_string.add(i16tostr3rj(thermalManager.degHotend(extruder))); + tft_string.add(i16tostr3rj(thermalManager.wholeDegHotend(extruder))); tft_string.add(LCD_STR_DEGREE); tft_string.add(" / "); tft_string.add(i16tostr3rj(thermalManager.degTargetHotend(extruder))); @@ -508,6 +455,7 @@ void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const tft_string.trim(); tft.add_text(tft_string.center(TFT_WIDTH), MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string); } + #endif // ADVANCED_PAUSE_FEATURE #if ENABLED(AUTO_BED_LEVELING_UBL) @@ -523,17 +471,17 @@ void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const tft.set_background(COLOR_BACKGROUND); tft.add_rectangle(0, 0, GRID_WIDTH, GRID_HEIGHT, COLOR_WHITE); - for (uint16_t x = 0; x < GRID_MAX_POINTS_X ; x++) - for (uint16_t y = 0; y < GRID_MAX_POINTS_Y ; y++) + for (uint16_t x = 0; x < (GRID_MAX_POINTS_X); x++) + for (uint16_t y = 0; y < (GRID_MAX_POINTS_Y); y++) if (position_is_reachable({ ubl.mesh_index_to_xpos(x), ubl.mesh_index_to_ypos(y) })) - tft.add_bar(1 + (x * 2 + 1) * (GRID_WIDTH - 4) / GRID_MAX_POINTS_X / 2, GRID_HEIGHT - 3 - ((y * 2 + 1) * (GRID_HEIGHT - 4) / GRID_MAX_POINTS_Y / 2), 2, 2, COLOR_UBL); + tft.add_bar(1 + (x * 2 + 1) * (GRID_WIDTH - 4) / (GRID_MAX_POINTS_X) / 2, GRID_HEIGHT - 3 - ((y * 2 + 1) * (GRID_HEIGHT - 4) / (GRID_MAX_POINTS_Y) / 2), 2, 2, COLOR_UBL); - tft.add_rectangle((x_plot * 2 + 1) * (GRID_WIDTH - 4) / GRID_MAX_POINTS_X / 2 - 1, GRID_HEIGHT - 5 - ((y_plot * 2 + 1) * (GRID_HEIGHT - 4) / GRID_MAX_POINTS_Y / 2), 6, 6, COLOR_UBL); + tft.add_rectangle((x_plot * 2 + 1) * (GRID_WIDTH - 4) / (GRID_MAX_POINTS_X) / 2 - 1, GRID_HEIGHT - 5 - ((y_plot * 2 + 1) * (GRID_HEIGHT - 4) / (GRID_MAX_POINTS_Y) / 2), 6, 6, COLOR_UBL); const xy_pos_t pos = { ubl.mesh_index_to_xpos(x_plot), ubl.mesh_index_to_ypos(y_plot) }, lpos = pos.asLogical(); - tft.canvas(216, GRID_OFFSET_Y + (GRID_HEIGHT - 32) / 2 - 32, 96, 32); + tft.canvas(216, GRID_OFFSET_Y + (GRID_HEIGHT - MENU_ITEM_HEIGHT) / 2 - MENU_ITEM_HEIGHT, 96, MENU_ITEM_HEIGHT); tft.set_background(COLOR_BACKGROUND); tft_string.set(X_LBL); tft.add_text(0, MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string); @@ -541,7 +489,7 @@ void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const tft_string.trim(); tft.add_text(96 - tft_string.width(), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string); - tft.canvas(216, GRID_OFFSET_Y + (GRID_HEIGHT - 32) / 2, 96, 32); + tft.canvas(216, GRID_OFFSET_Y + (GRID_HEIGHT - MENU_ITEM_HEIGHT) / 2, 96, MENU_ITEM_HEIGHT); tft.set_background(COLOR_BACKGROUND); tft_string.set(Y_LBL); tft.add_text(0, MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string); @@ -549,7 +497,7 @@ void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const tft_string.trim(); tft.add_text(96 - tft_string.width(), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string); - tft.canvas(216, GRID_OFFSET_Y + (GRID_HEIGHT - 32) / 2 + 32, 96, 32); + tft.canvas(216, GRID_OFFSET_Y + (GRID_HEIGHT - MENU_ITEM_HEIGHT) / 2 + MENU_ITEM_HEIGHT, 96, MENU_ITEM_HEIGHT); tft.set_background(COLOR_BACKGROUND); tft_string.set(Z_LBL); tft.add_text(0, MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string); @@ -557,25 +505,25 @@ void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const tft_string.trim(); tft.add_text(96 - tft_string.width(), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string); - - tft.canvas(GRID_OFFSET_X + (GRID_WIDTH - 32) / 2, GRID_OFFSET_Y + GRID_HEIGHT + CONTROL_OFFSET - 1, 32, 32); + constexpr uint8_t w = (TFT_WIDTH) / 10; + tft.canvas(GRID_OFFSET_X + (GRID_WIDTH - w) / 2, GRID_OFFSET_Y + GRID_HEIGHT + CONTROL_OFFSET - 1, w, MENU_ITEM_HEIGHT); tft.set_background(COLOR_BACKGROUND); tft_string.set(ui8tostr3rj(x_plot)); tft_string.trim(); - tft.add_text(tft_string.center(32), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string); + tft.add_text(tft_string.center(w), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string); - tft.canvas(GRID_OFFSET_X + GRID_WIDTH + CONTROL_OFFSET, GRID_OFFSET_Y + (GRID_HEIGHT - 27) / 2, 32, 32); + tft.canvas(GRID_OFFSET_X + GRID_WIDTH + CONTROL_OFFSET, GRID_OFFSET_Y + (GRID_HEIGHT - 27) / 2, w, MENU_ITEM_HEIGHT); tft.set_background(COLOR_BACKGROUND); tft_string.set(ui8tostr3rj(y_plot)); tft_string.trim(); - tft.add_text(tft_string.center(32), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string); + tft.add_text(tft_string.center(w), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string); #if ENABLED(TOUCH_SCREEN) touch.clear(); draw_menu_navigation = false; - add_control(GRID_OFFSET_X + GRID_WIDTH + CONTROL_OFFSET, GRID_OFFSET_Y + CONTROL_OFFSET, UBL, ENCODER_STEPS_PER_MENU_ITEM * GRID_MAX_POINTS_X, imgUp); - add_control(GRID_OFFSET_X + GRID_WIDTH + CONTROL_OFFSET, GRID_OFFSET_Y + GRID_HEIGHT - CONTROL_OFFSET - 32, UBL, - ENCODER_STEPS_PER_MENU_ITEM * GRID_MAX_POINTS_X, imgDown); - add_control(GRID_OFFSET_X + CONTROL_OFFSET, GRID_OFFSET_Y + GRID_HEIGHT + CONTROL_OFFSET, UBL, - ENCODER_STEPS_PER_MENU_ITEM, imgLeft); + add_control(GRID_OFFSET_X + GRID_WIDTH + CONTROL_OFFSET, GRID_OFFSET_Y + CONTROL_OFFSET, UBL, (ENCODER_STEPS_PER_MENU_ITEM) * (GRID_MAX_POINTS_X), imgUp); + add_control(GRID_OFFSET_X + GRID_WIDTH + CONTROL_OFFSET, GRID_OFFSET_Y + GRID_HEIGHT - CONTROL_OFFSET - 32, UBL, -(ENCODER_STEPS_PER_MENU_ITEM) * (GRID_MAX_POINTS_X), imgDown); + add_control(GRID_OFFSET_X + CONTROL_OFFSET, GRID_OFFSET_Y + GRID_HEIGHT + CONTROL_OFFSET, UBL, -(ENCODER_STEPS_PER_MENU_ITEM), imgLeft); add_control(GRID_OFFSET_X + GRID_WIDTH - CONTROL_OFFSET - 32, GRID_OFFSET_Y + GRID_HEIGHT + CONTROL_OFFSET, UBL, ENCODER_STEPS_PER_MENU_ITEM, imgRight); add_control(224, GRID_OFFSET_Y + GRID_HEIGHT + CONTROL_OFFSET, CLICK, imgLeveling); add_control(144, 206, BACK, imgBack); @@ -583,74 +531,374 @@ void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const } #endif // AUTO_BED_LEVELING_UBL -#if ENABLED(TOUCH_SCREEN_CALIBRATION) - void MarlinUI::touch_calibration() { - static uint16_t x, y; +#if ENABLED(BABYSTEP_ZPROBE_OFFSET) + #include "../../feature/babystep.h" +#endif - calibrationState calibration_stage = touch.get_calibration_state(); +#if HAS_BED_PROBE + #include "../../module/probe.h" +#endif - if (calibration_stage == CALIBRATION_NONE) { - defer_status_screen(true); - clear_lcd(); - calibration_stage = touch.calibration_start(); - } - else { - tft.canvas(x - 15, y - 15, 31, 31); - tft.set_background(COLOR_BACKGROUND); +#define Z_SELECTION_Z 1 +#define Z_SELECTION_Z_PROBE -1 + +struct MotionAxisState { + xy_int_t xValuePos, yValuePos, zValuePos, eValuePos, stepValuePos, zTypePos, eNamePos; + float currentStepSize = 10.0; + int z_selection = Z_SELECTION_Z; + uint8_t e_selection = 0; + bool blocked = false; + char message[32]; +}; + +MotionAxisState motionAxisState; + +#define E_BTN_COLOR COLOR_YELLOW +#define X_BTN_COLOR COLOR_CORAL_RED +#define Y_BTN_COLOR COLOR_VIVID_GREEN +#define Z_BTN_COLOR COLOR_LIGHT_BLUE + +#define BTN_WIDTH 48 +#define BTN_HEIGHT 39 +#define X_MARGIN 15 +#define Y_MARGIN 11 + +static void quick_feedback() { + #if HAS_CHIRP + ui.chirp(); // Buzz and wait. Is the delay needed for buttons to settle? + #if BOTH(HAS_LCD_MENU, USE_BEEPER) + for (int8_t i = 5; i--;) { buzzer.tick(); delay(2); } + #elif HAS_LCD_MENU + delay(10); + #endif + #endif +} + +#define CUR_STEP_VALUE_WIDTH 38 +static void drawCurStepValue() { + tft_string.set((uint8_t *)ftostr52sp(motionAxisState.currentStepSize)); + tft.canvas(motionAxisState.stepValuePos.x, motionAxisState.stepValuePos.y, CUR_STEP_VALUE_WIDTH, 20); + tft.set_background(COLOR_BACKGROUND); + tft.add_text(CUR_STEP_VALUE_WIDTH - tft_string.width(), 0, COLOR_AXIS_HOMED, tft_string); + tft.queue.sync(); + tft_string.set("mm"); + tft.canvas(motionAxisState.stepValuePos.x, motionAxisState.stepValuePos.y + 20, CUR_STEP_VALUE_WIDTH, 20); + tft.set_background(COLOR_BACKGROUND); + tft.add_text(CUR_STEP_VALUE_WIDTH - tft_string.width(), 0, COLOR_AXIS_HOMED, tft_string); +} + +static void drawCurZSelection() { + tft_string.set("Z"); + tft.canvas(motionAxisState.zTypePos.x, motionAxisState.zTypePos.y, tft_string.width(), 20); + tft.set_background(COLOR_BACKGROUND); + tft.add_text(0, 0, Z_BTN_COLOR, tft_string); + tft.queue.sync(); + tft_string.set("Offset"); + tft.canvas(motionAxisState.zTypePos.x, motionAxisState.zTypePos.y + 34, tft_string.width(), 20); + tft.set_background(COLOR_BACKGROUND); + if (motionAxisState.z_selection == Z_SELECTION_Z_PROBE) { + tft.add_text(0, 0, Z_BTN_COLOR, tft_string); + } +} + +static void drawCurESelection() { + tft.canvas(motionAxisState.eNamePos.x, motionAxisState.eNamePos.y, BTN_WIDTH, BTN_HEIGHT); + tft.set_background(COLOR_BACKGROUND); + tft_string.set("E"); + tft.add_text(0, 0, E_BTN_COLOR , tft_string); + tft.add_text(tft_string.width(), 0, E_BTN_COLOR, ui8tostr3rj(motionAxisState.e_selection)); +} + +static void drawMessage(const char *msg) { + tft.canvas(X_MARGIN, TFT_HEIGHT - Y_MARGIN - 29, (TFT_WIDTH / 2) - (BTN_WIDTH / 2) - X_MARGIN, 20); + tft.set_background(COLOR_BACKGROUND); + tft.add_text(0, 0, COLOR_YELLOW, msg); +} + +static void drawAxisValue(const AxisEnum axis) { + const float value = ( + TERN_(HAS_BED_PROBE, axis == Z_AXIS && motionAxisState.z_selection == Z_SELECTION_Z_PROBE ? probe.offset.z :) + ui.manual_move.axis_value(axis) + ); + xy_int_t pos; + uint16_t color; + switch (axis) { + case X_AXIS: pos = motionAxisState.xValuePos; color = X_BTN_COLOR; break; + case Y_AXIS: pos = motionAxisState.yValuePos; color = Y_BTN_COLOR; break; + case Z_AXIS: pos = motionAxisState.zValuePos; color = Z_BTN_COLOR; break; + case E_AXIS: pos = motionAxisState.eValuePos; color = E_BTN_COLOR; break; + default: return; + } + tft.canvas(pos.x, pos.y, BTN_WIDTH + X_MARGIN, 20); + tft.set_background(COLOR_BACKGROUND); + tft_string.set(ftostr52sp(value)); + tft.add_text(0, 0, color, tft_string); +} + +static void moveAxis(const AxisEnum axis, const int8_t direction) { + quick_feedback(); + + #if ENABLED(PREVENT_COLD_EXTRUSION) + if (axis == E_AXIS && thermalManager.tooColdToExtrude(motionAxisState.e_selection)) { + drawMessage("Too cold"); + return; } + #endif - x = 20; y = 20; - touch.clear(); + const float diff = motionAxisState.currentStepSize * direction; + + if (axis == Z_AXIS && motionAxisState.z_selection == Z_SELECTION_Z_PROBE) { + #if ENABLED(BABYSTEP_ZPROBE_OFFSET) + const int16_t babystep_increment = direction * BABYSTEP_SIZE_Z; + const bool do_probe = DISABLED(BABYSTEP_HOTEND_Z_OFFSET) || active_extruder == 0; + const float bsDiff = planner.steps_to_mm[Z_AXIS] * babystep_increment, + new_probe_offset = probe.offset.z + bsDiff, + new_offs = TERN(BABYSTEP_HOTEND_Z_OFFSET + , do_probe ? new_probe_offset : hotend_offset[active_extruder].z - bsDiff + , new_probe_offset + ); + if (WITHIN(new_offs, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX)) { + babystep.add_steps(Z_AXIS, babystep_increment); + if (do_probe) + probe.offset.z = new_offs; + else + TERN(BABYSTEP_HOTEND_Z_OFFSET, hotend_offset[active_extruder].z = new_offs, NOOP); + drawMessage(""); // clear the error + drawAxisValue(axis); + } + else { + drawMessage(GET_TEXT(MSG_LCD_SOFT_ENDSTOPS)); + } + #elif HAS_BED_PROBE + // only change probe.offset.z + probe.offset.z += diff; + if (direction < 0 && current_position[axis] < Z_PROBE_OFFSET_RANGE_MIN) { + current_position[axis] = Z_PROBE_OFFSET_RANGE_MIN; + drawMessage(GET_TEXT(MSG_LCD_SOFT_ENDSTOPS)); + } + else if (direction > 0 && current_position[axis] > Z_PROBE_OFFSET_RANGE_MAX) { + current_position[axis] = Z_PROBE_OFFSET_RANGE_MAX; + drawMessage(GET_TEXT(MSG_LCD_SOFT_ENDSTOPS)); + } + else { + drawMessage(""); // clear the error + } + drawAxisValue(axis); + #endif + return; + } - if (calibration_stage < CALIBRATION_SUCCESS) { - switch (calibration_stage) { - case CALIBRATION_POINT_1: tft_string.set("Top Left"); break; - case CALIBRATION_POINT_2: y = TFT_HEIGHT - 21; tft_string.set("Bottom Left"); break; - case CALIBRATION_POINT_3: x = TFT_WIDTH - 21; tft_string.set("Top Right"); break; - case CALIBRATION_POINT_4: x = TFT_WIDTH - 21; y = TFT_HEIGHT - 21; tft_string.set("Bottom Right"); break; - default: break; + if (!ui.manual_move.processing) { + // Get motion limit from software endstops, if any + float min, max; + soft_endstop.get_manual_axis_limits(axis, min, max); + + // Delta limits XY based on the current offset from center + // This assumes the center is 0,0 + #if ENABLED(DELTA) + if (axis != Z_AXIS && axis != E_AXIS) { + max = SQRT(sq((float)(DELTA_PRINTABLE_RADIUS)) - sq(current_position[Y_AXIS - axis])); // (Y_AXIS - axis) == the other axis + min = -max; } + #endif - tft.canvas(x - 15, y - 15, 31, 31); - tft.set_background(COLOR_BACKGROUND); - tft.add_bar(0, 15, 31, 1, COLOR_TOUCH_CALIBRATION); - tft.add_bar(15, 0, 1, 31, COLOR_TOUCH_CALIBRATION); + // Get the new position + const bool limited = ui.manual_move.apply_diff(axis, diff, min, max); + #if IS_KINEMATIC + UNUSED(limited); + #else + PGM_P const msg = limited ? GET_TEXT(MSG_LCD_SOFT_ENDSTOPS) : NUL_STR; + drawMessage(msg); + #endif - touch.add_control(CALIBRATE, 0, 0, TFT_WIDTH, TFT_HEIGHT, uint32_t(x) << 16 | uint32_t(y)); - } - else { - tft_string.set(calibration_stage == CALIBRATION_SUCCESS ? "Calibration Completed" : "Calibration Failed"); - defer_status_screen(false); - touch.calibration_end(); - touch.add_control(BACK, 0, 0, TFT_WIDTH, TFT_HEIGHT); + ui.manual_move.soon(axis OPTARG(MULTI_E_MANUAL, motionAxisState.e_selection)); + } + + drawAxisValue(axis); +} + +static void e_plus() { moveAxis(E_AXIS, 1); } +static void e_minus() { moveAxis(E_AXIS, -1); } +static void x_minus() { moveAxis(X_AXIS, -1); } +static void x_plus() { moveAxis(X_AXIS, 1); } +static void y_plus() { moveAxis(Y_AXIS, 1); } +static void y_minus() { moveAxis(Y_AXIS, -1); } +static void z_plus() { moveAxis(Z_AXIS, 1); } +static void z_minus() { moveAxis(Z_AXIS, -1); } + +#if ENABLED(TOUCH_SCREEN) + static void e_select() { + motionAxisState.e_selection++; + if (motionAxisState.e_selection >= EXTRUDERS) { + motionAxisState.e_selection = 0; } - tft.canvas(0, (TFT_HEIGHT - tft_string.font_height()) >> 1, TFT_WIDTH, tft_string.font_height()); - tft.set_background(COLOR_BACKGROUND); - tft.add_text(tft_string.center(TFT_WIDTH), 0, COLOR_MENU_TEXT, tft_string); + quick_feedback(); + drawCurESelection(); + drawAxisValue(E_AXIS); } -#endif // TOUCH_SCREEN_CALIBRATION -void menu_line(const uint8_t row, uint16_t color) { - tft.canvas(0, 2 + 34 * row, TFT_WIDTH, 32); - tft.set_background(color); -} + static void do_home() { + quick_feedback(); + drawMessage(GET_TEXT(MSG_LEVEL_BED_HOMING)); + queue.inject_P(G28_STR); + // Disable touch until home is done + TERN_(HAS_TFT_XPT2046, touch.disable()); + drawAxisValue(E_AXIS); + drawAxisValue(X_AXIS); + drawAxisValue(Y_AXIS); + drawAxisValue(Z_AXIS); + } -void menu_pause_option(); + static void step_size() { + motionAxisState.currentStepSize = motionAxisState.currentStepSize / 10.0; + if (motionAxisState.currentStepSize < 0.0015) motionAxisState.currentStepSize = 10.0; + quick_feedback(); + drawCurStepValue(); + } +#endif -void menu_item(const uint8_t row, bool sel ) { - #if ENABLED(TOUCH_SCREEN) - if (row == 0) { - touch.clear(); - draw_menu_navigation = TERN(ADVANCED_PAUSE_FEATURE, ui.currentScreen != menu_pause_option, true); - } - #endif +#if HAS_BED_PROBE + static void z_select() { + motionAxisState.z_selection *= -1; + quick_feedback(); + drawCurZSelection(); + drawAxisValue(Z_AXIS); + } +#endif - menu_line(row, sel ? COLOR_SELECTION_BG : COLOR_BACKGROUND); - TERN_(TOUCH_SCREEN, touch.add_control(sel ? CLICK : MENU_ITEM, 0, 2 + 34 * row, 320, 32, encoderTopLine + row)); +static void disable_steppers() { + quick_feedback(); + queue.inject_P(PSTR("M84")); } +static void drawBtn(int x, int y, const char *label, intptr_t data, MarlinImage img, uint16_t bgColor, bool enabled = true) { + uint16_t width = Images[imgBtn39Rounded].width; + uint16_t height = Images[imgBtn39Rounded].height; + + if (!enabled) bgColor = COLOR_CONTROL_DISABLED; + + tft.canvas(x, y, width, height); + tft.set_background(COLOR_BACKGROUND); + tft.add_image(0, 0, imgBtn39Rounded, bgColor, COLOR_BACKGROUND, COLOR_DARKGREY); + + // TODO: Make an add_text() taking a font arg + if (label) { + tft_string.set(label); + tft_string.trim(); + tft.add_text(tft_string.center(width), height / 2 - tft_string.font_height() / 2, bgColor, tft_string); + } + else { + tft.add_image(0, 0, img, bgColor, COLOR_BACKGROUND, COLOR_DARKGREY); + } + + TERN_(HAS_TFT_XPT2046, if (enabled) touch.add_control(BUTTON, x, y, width, height, data)); +} void MarlinUI::move_axis_screen() { + // Reset + defer_status_screen(true); + motionAxisState.blocked = false; + TERN_(HAS_TFT_XPT2046, touch.enable()); + + ui.clear_lcd(); + + TERN_(TOUCH_SCREEN, touch.clear()); + + const bool busy = printingIsActive(); + + // Babysteps during printing? Select babystep for Z probe offset + if (busy && ENABLED(BABYSTEP_ZPROBE_OFFSET)) + motionAxisState.z_selection = Z_SELECTION_Z_PROBE; + + // ROW 1 -> E- Y- CurY Z+ + int x = X_MARGIN, y = Y_MARGIN, spacing = 0; + + drawBtn(x, y, "E+", (intptr_t)e_plus, imgUp, E_BTN_COLOR, !busy); + + spacing = (TFT_WIDTH - X_MARGIN * 2 - 3 * BTN_WIDTH) / 2; + x += BTN_WIDTH + spacing; + uint16_t yplus_x = x; + drawBtn(x, y, "Y+", (intptr_t)y_plus, imgUp, Y_BTN_COLOR, !busy); + + // Cur Y + x += BTN_WIDTH; + motionAxisState.yValuePos.x = x + 2; + motionAxisState.yValuePos.y = y; + drawAxisValue(Y_AXIS); + + x += spacing; + drawBtn(x, y, "Z+", (intptr_t)z_plus, imgUp, Z_BTN_COLOR, !busy || ENABLED(BABYSTEP_ZPROBE_OFFSET)); //only enabled when not busy or have baby step + + // ROW 2 -> "Ex" X- HOME X+ "Z" + y += BTN_HEIGHT + (TFT_HEIGHT - Y_MARGIN * 2 - 4 * BTN_HEIGHT) / 3; + x = X_MARGIN; + spacing = (TFT_WIDTH - X_MARGIN * 2 - 5 * BTN_WIDTH) / 4; + + motionAxisState.eNamePos.x = x; + motionAxisState.eNamePos.y = y; + drawCurESelection(); + TERN_(HAS_TFT_XPT2046, if (!busy) touch.add_control(BUTTON, x, y, BTN_WIDTH, BTN_HEIGHT, (intptr_t)e_select)); + + x += BTN_WIDTH + spacing; + drawBtn(x, y, "X-", (intptr_t)x_minus, imgLeft, X_BTN_COLOR, !busy); + + x += BTN_WIDTH + spacing; //imgHome is 64x64 + TERN_(HAS_TFT_XPT2046, add_control(TFT_WIDTH / 2 - Images[imgHome].width / 2, y - (Images[imgHome].width - BTN_HEIGHT) / 2, BUTTON, (intptr_t)do_home, imgHome, !busy)); + + x += BTN_WIDTH + spacing; + uint16_t xplus_x = x; + drawBtn(x, y, "X+", (intptr_t)x_plus, imgRight, X_BTN_COLOR, !busy); + + x += BTN_WIDTH + spacing; + motionAxisState.zTypePos.x = x; + motionAxisState.zTypePos.y = y; + drawCurZSelection(); + #if BOTH(HAS_BED_PROBE, TOUCH_SCREEN) + if (!busy) touch.add_control(BUTTON, x, y, BTN_WIDTH, 34 * 2, (intptr_t)z_select); + #endif + + // ROW 3 -> E- CurX Y- Z- + y += BTN_HEIGHT + (TFT_HEIGHT - Y_MARGIN * 2 - 4 * BTN_HEIGHT) / 3; + x = X_MARGIN; + spacing = (TFT_WIDTH - X_MARGIN * 2 - 3 * BTN_WIDTH) / 2; + + drawBtn(x, y, "E-", (intptr_t)e_minus, imgDown, E_BTN_COLOR, !busy); + + // Cur E + motionAxisState.eValuePos.x = x; + motionAxisState.eValuePos.y = y + BTN_HEIGHT + 2; + drawAxisValue(E_AXIS); + + // Cur X + motionAxisState.xValuePos.x = BTN_WIDTH + (TFT_WIDTH - X_MARGIN * 2 - 5 * BTN_WIDTH) / 4; //X- pos + motionAxisState.xValuePos.y = y - 10; + drawAxisValue(X_AXIS); + + x += BTN_WIDTH + spacing; + drawBtn(x, y, "Y-", (intptr_t)y_minus, imgDown, Y_BTN_COLOR, !busy); + + x += BTN_WIDTH + spacing; + drawBtn(x, y, "Z-", (intptr_t)z_minus, imgDown, Z_BTN_COLOR, !busy || ENABLED(BABYSTEP_ZPROBE_OFFSET)); //only enabled when not busy or have baby step + + // Cur Z + motionAxisState.zValuePos.x = x; + motionAxisState.zValuePos.y = y + BTN_HEIGHT + 2; + drawAxisValue(Z_AXIS); + + // ROW 4 -> step_size disable steppers back + y = TFT_HEIGHT - Y_MARGIN - BTN_HEIGHT; // + x = xplus_x - CUR_STEP_VALUE_WIDTH - 10; + motionAxisState.stepValuePos.x = yplus_x + BTN_WIDTH - CUR_STEP_VALUE_WIDTH; + motionAxisState.stepValuePos.y = TFT_HEIGHT - Y_MARGIN - BTN_HEIGHT; + if (!busy) { + drawCurStepValue(); + TERN_(HAS_TFT_XPT2046, touch.add_control(BUTTON, motionAxisState.stepValuePos.x, motionAxisState.stepValuePos.y, CUR_STEP_VALUE_WIDTH, BTN_HEIGHT, (intptr_t)step_size)); + } + + // aligned with x+ + drawBtn(xplus_x, y, "off", (intptr_t)disable_steppers, imgCancel, COLOR_WHITE, !busy); + + TERN_(HAS_TFT_XPT2046, add_control(TFT_WIDTH - X_MARGIN - BTN_WIDTH, y, BACK, imgBack)); } #endif // HAS_UI_320x240 diff --git a/Marlin/src/lcd/tft/ui_320x240.h b/Marlin/src/lcd/tft/ui_320x240.h index c9822f11cc69..40b2185577b9 100644 --- a/Marlin/src/lcd/tft/ui_320x240.h +++ b/Marlin/src/lcd/tft/ui_320x240.h @@ -21,88 +21,22 @@ */ #pragma once -#include "../../inc/MarlinConfigPre.h" +#define MARLIN_LOGO_FULL_SIZE MarlinLogo320x240x16 -#include "tft.h" -#include "tft_image.h" +#define TFT_STATUS_TOP_Y 0 +#define TFT_TOP_LINE_Y 2 -#if ENABLED(TOUCH_SCREEN) - #include "touch.h" -#endif +#define MENU_TEXT_X_OFFSET 10 +#define MENU_TEXT_Y_OFFSET 7 -void draw_heater_status(uint16_t x, uint16_t y, const int8_t Heater); -void draw_fan_status(uint16_t x, uint16_t y, const bool blink); +#define MENU_ITEM_ICON_X 0 +#define MENU_ITEM_ICON_Y 0 +#define MENU_ITEM_ICON_SPACE 32 -#define MENU_TEXT_X_OFFSET 10 -#define MENU_TEXT_Y_OFFSET 7 -void menu_line(const uint8_t row, uint16_t color = COLOR_BACKGROUND); -void menu_item(const uint8_t row, bool sel = false); +#define MENU_ITEM_HEIGHT 32 +#define MENU_LINE_HEIGHT (MENU_ITEM_HEIGHT + 2) -#define MENU_FONT_NAME Helvetica14 -#define SYMBOLS_FONT_NAME Helvetica14_symbols +#define MENU_FONT_NAME Helvetica14 +#define SYMBOLS_FONT_NAME Helvetica14_symbols -#define ABSOLUTE_ZERO -273.15 - -const tImage Images[imgCount] = { - MarlinLogo320x240x16, - HotEnd_64x64x4, - Bed_64x64x4, - Bed_Heated_64x64x4, - Chamber_64x64x4, - Chamber_Heated_64x64x4, - Fan0_64x64x4, - Fan_Slow0_64x64x4, - Fan_Slow1_64x64x4, - Fan_Fast0_64x64x4, - Fan_Fast1_64x64x4, - Feedrate_32x32x4, - Flowrate_32x32x4, - SD_64x64x4, - Menu_64x64x4, - Settings_64x64x4, - Directory_32x32x4, - Confirm_64x64x4, - Cancel_64x64x4, - Increase_64x64x4, - Decrease_64x64x4, - Back_32x32x4, - Up_32x32x4, - Down_32x32x4, - Left_32x32x4, - Right_32x32x4, - Refresh_32x32x4, - Leveling_32x32x4, - Slider8x16x4, - Home_64x64x4, - BtnRounded_64x52x4, -}; - -#if HAS_TEMP_CHAMBER && HOTENDS > 1 - #define ITEM_E0 0 - #define ITEM_E1 1 - #define ITEM_BED 2 - #define ITEM_CHAMBER 3 - #define ITEM_FAN 4 - #define ITEMS_COUNT 5 - #define POS_Y 0 -#elif HAS_TEMP_CHAMBER - #define ITEM_E0 0 - #define ITEM_BED 1 - #define ITEM_CHAMBER 2 - #define ITEM_FAN 3 - #define ITEMS_COUNT 4 - #define POS_Y 0 -#elif HOTENDS > 1 - #define ITEM_E0 0 - #define ITEM_E1 1 - #define ITEM_BED 2 - #define ITEM_FAN 3 - #define ITEMS_COUNT 4 - #define POS_Y 0 -#else - #define ITEM_E0 0 - #define ITEM_BED 1 - #define ITEM_FAN 2 - #define ITEMS_COUNT 3 - #define POS_Y 0 -#endif +#include "ui_common.h" diff --git a/Marlin/src/lcd/tft/ui_480x320.cpp b/Marlin/src/lcd/tft/ui_480x320.cpp index 3dab9418f5fa..02e3354d93af 100644 --- a/Marlin/src/lcd/tft/ui_480x320.cpp +++ b/Marlin/src/lcd/tft/ui_480x320.cpp @@ -22,11 +22,11 @@ #include "../../inc/MarlinConfigPre.h" -#if HAS_UI_480x320 +#if HAS_UI_480x320 || HAS_UI_480x272 -#include "ui_480x320.h" +#include "ui_common.h" -#include "../ultralcd.h" +#include "../marlinui.h" #include "../menu/menu.h" #include "../../libs/numtostr.h" @@ -45,18 +45,12 @@ #include "../../feature/bedlevel/bedlevel.h" #endif -#if !HAS_LCD_MENU - #error "Seriously? High resolution TFT screen without menu?" -#endif - -static bool draw_menu_navigation = false; - void MarlinUI::tft_idle() { #if ENABLED(TOUCH_SCREEN) if (draw_menu_navigation) { - add_control(104, 286, PAGE_UP, imgPageUp, encoderTopLine > 0); - add_control(344, 286, PAGE_DOWN, imgPageDown, encoderTopLine + LCD_HEIGHT < screen_items); - add_control(224, 286, BACK, imgBack); + add_control(104, TFT_HEIGHT - 34, PAGE_UP, imgPageUp, encoderTopLine > 0); + add_control(344, TFT_HEIGHT - 34, PAGE_DOWN, imgPageDown, encoderTopLine + LCD_HEIGHT < screen_items); + add_control(224, TFT_HEIGHT - 34, BACK, imgBack); draw_menu_navigation = false; } #endif @@ -65,52 +59,37 @@ void MarlinUI::tft_idle() { TERN_(TOUCH_SCREEN, touch.idle()); } -void MarlinUI::init_lcd() { - tft.init(); - tft.set_font(MENU_FONT_NAME); - #ifdef SYMBOLS_FONT_NAME - tft.add_glyphs(SYMBOLS_FONT_NAME); - #endif - TERN_(TOUCH_SCREEN, touch.init()); - clear_lcd(); -} - -bool MarlinUI::detected() { return true; } - -void MarlinUI::clear_lcd() { - #if ENABLED(TOUCH_SCREEN) - touch.reset(); - draw_menu_navigation = false; - #endif - - tft.queue.reset(); - tft.fill(0, 0, TFT_WIDTH, TFT_HEIGHT, COLOR_BACKGROUND); -} - #if ENABLED(SHOW_BOOTSCREEN) - #ifndef BOOTSCREEN_TIMEOUT - #define BOOTSCREEN_TIMEOUT 1500 - #endif - - #undef BOOTSCREEN_TIMEOUT - #define BOOTSCREEN_TIMEOUT 5000 void MarlinUI::show_bootscreen() { tft.queue.reset(); tft.canvas(0, 0, TFT_WIDTH, TFT_HEIGHT); - tft.set_background(COLOR_BACKGROUND); - tft.add_image(142, 130, imgBootScreen); // MarlinLogo195x59x16 - + #if ENABLED(BOOT_MARLIN_LOGO_SMALL) + #define BOOT_LOGO_W 195 // MarlinLogo195x59x16 + #define BOOT_LOGO_H 59 + #define SITE_URL_Y (TFT_HEIGHT - 70) + tft.set_background(COLOR_BACKGROUND); + #else + #define BOOT_LOGO_W TFT_WIDTH // MarlinLogo480x320x16 + #define BOOT_LOGO_H TFT_HEIGHT + #define SITE_URL_Y (TFT_HEIGHT - 90) + #endif + tft.add_image((TFT_WIDTH - BOOT_LOGO_W) / 2, (TFT_HEIGHT - BOOT_LOGO_H) / 2, imgBootScreen); #ifdef WEBSITE_URL - tft.add_text(8, 250, COLOR_WEBSITE_URL, WEBSITE_URL); + tft_string.set(WEBSITE_URL); + tft.add_text(tft_string.center(TFT_WIDTH), SITE_URL_Y, COLOR_WEBSITE_URL, tft_string); #endif tft.queue.sync(); - safe_delay(BOOTSCREEN_TIMEOUT); + } + + void MarlinUI::bootscreen_completion(const millis_t sofar) { + if ((BOOTSCREEN_TIMEOUT) > sofar) safe_delay((BOOTSCREEN_TIMEOUT) - sofar); clear_lcd(); } -#endif // SHOW_BOOTSCREEN + +#endif void MarlinUI::draw_kill_screen() { tft.queue.reset(); @@ -140,28 +119,34 @@ void MarlinUI::draw_kill_screen() { void draw_heater_status(uint16_t x, uint16_t y, const int8_t Heater) { MarlinImage image = imgHotEnd; uint16_t Color; - float currentTemperature, targetTemperature; + celsius_t currentTemperature, targetTemperature; if (Heater >= 0) { // HotEnd - currentTemperature = thermalManager.degHotend(Heater); + currentTemperature = thermalManager.wholeDegHotend(Heater); targetTemperature = thermalManager.degTargetHotend(Heater); } -#if HAS_HEATED_BED - else if (Heater == H_BED) { - currentTemperature = thermalManager.degBed(); - targetTemperature = thermalManager.degTargetBed(); - } -#endif // HAS_HEATED_BED -#if HAS_TEMP_CHAMBER - else if (Heater == H_CHAMBER) { - currentTemperature = thermalManager.degChamber(); - #if HAS_HEATED_CHAMBER - targetTemperature = thermalManager.degTargetChamber(); - #else - targetTemperature = ABSOLUTE_ZERO; - #endif - } -#endif // HAS_TEMP_CHAMBER + #if HAS_HEATED_BED + else if (Heater == H_BED) { + currentTemperature = thermalManager.wholeDegBed(); + targetTemperature = thermalManager.degTargetBed(); + } + #endif + #if HAS_TEMP_CHAMBER + else if (Heater == H_CHAMBER) { + currentTemperature = thermalManager.wholeDegChamber(); + #if HAS_HEATED_CHAMBER + targetTemperature = thermalManager.degTargetChamber(); + #else + targetTemperature = ABSOLUTE_ZERO; + #endif + } + #endif + #if HAS_TEMP_COOLER + else if (Heater == H_COOLER) { + currentTemperature = thermalManager.wholeDegCooler(); + targetTemperature = TERN(HAS_COOLER, thermalManager.degTargetCooler(), ABSOLUTE_ZERO); + } + #endif else return; TERN_(TOUCH_SCREEN, if (targetTemperature >= 0) touch.add_control(HEATER, x, y, 80, 120, Heater)); @@ -174,27 +159,34 @@ void draw_heater_status(uint16_t x, uint16_t y, const int8_t Heater) { if (currentTemperature >= 50) Color = COLOR_HOTEND; } #if HAS_HEATED_BED - else if (Heater == H_BED) { - if (currentTemperature >= 50) Color = COLOR_HEATED_BED; - image = targetTemperature > 0 ? imgBedHeated : imgBed; - } - #endif // HAS_HEATED_BED + else if (Heater == H_BED) { + if (currentTemperature >= 50) Color = COLOR_HEATED_BED; + image = targetTemperature > 0 ? imgBedHeated : imgBed; + } + #endif #if HAS_TEMP_CHAMBER - else if (Heater == H_CHAMBER) { - if (currentTemperature >= 50) Color = COLOR_CHAMBER; - image = targetTemperature > 0 ? imgChamberHeated : imgChamber; - } - #endif // HAS_TEMP_CHAMBER + else if (Heater == H_CHAMBER) { + if (currentTemperature >= 50) Color = COLOR_CHAMBER; + image = targetTemperature > 0 ? imgChamberHeated : imgChamber; + } + #endif + #if HAS_TEMP_COOLER + else if (Heater == H_COOLER) { + if (currentTemperature <= 26) Color = COLOR_COLD; + if (currentTemperature > 26) Color = COLOR_RED; + image = targetTemperature > 26 ? imgCoolerHot : imgCooler; + } + #endif tft.add_image(8, 28, image, Color); - tft_string.set((uint8_t *)i16tostr3rj(currentTemperature + 0.5)); + tft_string.set((uint8_t *)i16tostr3rj(currentTemperature)); tft_string.add(LCD_STR_DEGREE); tft_string.trim(); tft.add_text(tft_string.center(80) + 2, 82, Color, tft_string); if (targetTemperature >= 0) { - tft_string.set((uint8_t *)i16tostr3rj(targetTemperature + 0.5)); + tft_string.set((uint8_t *)i16tostr3rj(targetTemperature)); tft_string.add(LCD_STR_DEGREE); tft_string.trim(); tft.add_text(tft_string.center(80) + 2, 8, Color, tft_string); @@ -229,7 +221,7 @@ void MarlinUI::draw_status_screen() { TERN_(TOUCH_SCREEN, touch.clear()); // heaters and fan - uint16_t i, x, y = POS_Y; + uint16_t i, x, y = TFT_STATUS_TOP_Y; for (i = 0 ; i < ITEMS_COUNT; i++) { x = (TFT_WIDTH / ITEMS_COUNT - 80) / 2 + (TFT_WIDTH * i / ITEMS_COUNT); @@ -249,54 +241,55 @@ void MarlinUI::draw_status_screen() { #ifdef ITEM_CHAMBER case ITEM_CHAMBER: draw_heater_status(x, y, H_CHAMBER); break; #endif + #ifdef ITEM_COOLER + case ITEM_COOLER: draw_heater_status(x, y, H_COOLER); break; + #endif #ifdef ITEM_FAN case ITEM_FAN: draw_fan_status(x, y, blink); break; #endif } } + y += TERN(HAS_UI_480x272, 118, 128); + // coordinates - tft.canvas(4, 132, TFT_WIDTH - 8, 34); + tft.canvas(4, y, TFT_WIDTH - 8, FONT_LINE_HEIGHT); tft.set_background(COLOR_BACKGROUND); - tft.add_rectangle(0, 0, TFT_WIDTH - 8, 34, COLOR_AXIS_HOMED); - - uint16_t color; - uint16_t offset; - bool is_homed; + tft.add_rectangle(0, 0, TFT_WIDTH - 8, FONT_LINE_HEIGHT, COLOR_AXIS_HOMED); tft.add_text( 16, 3, COLOR_AXIS_HOMED , "X"); tft.add_text(192, 3, COLOR_AXIS_HOMED , "Y"); tft.add_text(330, 3, COLOR_AXIS_HOMED , "Z"); - is_homed = TEST(axis_homed, X_AXIS); - tft_string.set(blink & !is_homed ? "?" : ftostr4sign(LOGICAL_X_POSITION(current_position.x))); - tft.add_text(102 - tft_string.width(), 3, is_homed ? COLOR_AXIS_HOMED : COLOR_AXIS_NOT_HOMED, tft_string); + bool not_homed = axis_should_home(X_AXIS); + tft_string.set(blink && not_homed ? "?" : ftostr4sign(LOGICAL_X_POSITION(current_position.x))); + tft.add_text(102 - tft_string.width(), 3, not_homed ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); - is_homed = TEST(axis_homed, Y_AXIS); - tft_string.set(blink & !is_homed ? "?" : ftostr4sign(LOGICAL_Y_POSITION(current_position.y))); - tft.add_text(280 - tft_string.width(), 3, is_homed ? COLOR_AXIS_HOMED : COLOR_AXIS_NOT_HOMED, tft_string); + not_homed = axis_should_home(Y_AXIS); + tft_string.set(blink && not_homed ? "?" : ftostr4sign(LOGICAL_Y_POSITION(current_position.y))); + tft.add_text(280 - tft_string.width(), 3, not_homed ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); - is_homed = TEST(axis_homed, Z_AXIS); - if (blink & !is_homed) { + uint16_t offset = 32; + not_homed = axis_should_home(Z_AXIS); + if (blink && not_homed) tft_string.set("?"); - offset = 32; // ".00" - } else { const float z = LOGICAL_Z_POSITION(current_position.z); tft_string.set(ftostr52sp((int16_t)z)); tft_string.rtrim(); - offset = tft_string.width(); + offset += tft_string.width(); tft_string.set(ftostr52sp(z)); - offset += 32 - tft_string.width(); + offset -= tft_string.width(); } - tft.add_text(455 - tft_string.width() - offset, 3, is_homed ? COLOR_AXIS_HOMED : COLOR_AXIS_NOT_HOMED, tft_string); - TERN_(TOUCH_SCREEN, touch.add_control(MOVE_AXIS, 4, 132, TFT_WIDTH - 8, 34)); + tft.add_text(455 - tft_string.width() - offset, 3, not_homed ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); + TERN_(TOUCH_SCREEN, touch.add_control(MOVE_AXIS, 4, y, TFT_WIDTH - 8, FONT_LINE_HEIGHT)); + y += TERN(HAS_UI_480x272, 38, 48); // feed rate - tft.canvas(96, 180, 100, 32); + tft.canvas(96, y, 100, 32); tft.set_background(COLOR_BACKGROUND); - color = feedrate_percentage == 100 ? COLOR_RATE_100 : COLOR_RATE_ALTERED; + uint16_t color = feedrate_percentage == 100 ? COLOR_RATE_100 : COLOR_RATE_ALTERED; tft.add_image(0, 0, imgFeedRate, color); tft_string.set(i16tostr3rj(feedrate_percentage)); tft_string.add('%'); @@ -304,7 +297,7 @@ void MarlinUI::draw_status_screen() { TERN_(TOUCH_SCREEN, touch.add_control(FEEDRATE, 96, 176, 100, 32)); // flow rate - tft.canvas(284, 180, 100, 32); + tft.canvas(284, y, 100, 32); tft.set_background(COLOR_BACKGROUND); color = planner.flow_percentage[0] == 100 ? COLOR_RATE_100 : COLOR_RATE_ALTERED; tft.add_image(0, 0, imgFlowRate, color); @@ -313,83 +306,42 @@ void MarlinUI::draw_status_screen() { tft.add_text(36, 1, color , tft_string); TERN_(TOUCH_SCREEN, touch.add_control(FLOWRATE, 284, 176, 100, 32, active_extruder)); + #if ENABLED(TOUCH_SCREEN) + add_control(404, y, menu_main, imgSettings); + TERN_(SDSUPPORT, add_control(12, y, menu_media, imgSD, !printingIsActive(), COLOR_CONTROL_ENABLED, card.isMounted() && printingIsActive() ? COLOR_BUSY : COLOR_CONTROL_DISABLED)); + #endif + + y += TERN(HAS_UI_480x272, 36, 44); // print duration char buffer[14]; duration_t elapsed = print_job_timer.duration(); elapsed.toDigital(buffer); - tft.canvas((TFT_WIDTH - 128) / 2, 224, 128, 29); + tft.canvas((TFT_WIDTH - 128) / 2, y, 128, 29); tft.set_background(COLOR_BACKGROUND); tft_string.set(buffer); tft.add_text(tft_string.center(128), 0, COLOR_PRINT_TIME, tft_string); + y += TERN(HAS_UI_480x272, 28, 36); // progress bar const uint8_t progress = ui.get_progress_percent(); - tft.canvas(4, 260, TFT_WIDTH - 8, 9); + tft.canvas(4, y, TFT_WIDTH - 8, 9); tft.set_background(COLOR_PROGRESS_BG); tft.add_rectangle(0, 0, TFT_WIDTH - 8, 9, COLOR_PROGRESS_FRAME); if (progress) tft.add_bar(1, 1, ((TFT_WIDTH - 10) * progress) / 100, 7, COLOR_PROGRESS_BAR); + y += 20; // status message - tft.canvas(0, 280, TFT_WIDTH, 29); + tft.canvas(0, y, TFT_WIDTH, FONT_LINE_HEIGHT - 5); tft.set_background(COLOR_BACKGROUND); tft_string.set(status_message); tft_string.trim(); tft.add_text(tft_string.center(TFT_WIDTH), 0, COLOR_STATUS_MESSAGE, tft_string); - - - #if ENABLED(TOUCH_SCREEN) - add_control(404, 180, menu_main, imgSettings); - TERN_(SDSUPPORT, add_control(12, 180, menu_media, imgSD, card.isMounted() && !printingIsActive(), COLOR_CONTROL_ENABLED, card.isMounted() && printingIsActive() ? COLOR_BUSY : COLOR_CONTROL_DISABLED)); - #endif -} - -// Draw a static item with no left-right margin required. Centered by default. -void MenuItem_static::draw(const uint8_t row, PGM_P const pstr, const uint8_t style/*=SS_DEFAULT*/, const char * const vstr/*=nullptr*/) { - menu_item(row); - tft_string.set(pstr, itemIndex, itemString); - if (vstr) - tft_string.add(vstr); - tft.add_text(tft_string.center(TFT_WIDTH), MENU_TEXT_Y_OFFSET, COLOR_YELLOW, tft_string); -} - -// Draw a generic menu item with pre_char (if selected) and post_char -void MenuItemBase::_draw(const bool sel, const uint8_t row, PGM_P const pstr, const char pre_char, const char post_char) { - menu_item(row, sel); - - uint8_t *string = (uint8_t *)pstr; - MarlinImage image = noImage; - switch (*string) { - case 0x01: image = imgRefresh; break; // LCD_STR_REFRESH - case 0x02: image = imgDirectory; break; // LCD_STR_FOLDER - } - - uint8_t offset = MENU_TEXT_X_OFFSET; - if (image != noImage) { - string++; - offset = 42; - tft.add_image(5, 5, image, COLOR_MENU_TEXT, sel ? COLOR_SELECTION_BG : COLOR_BACKGROUND); - } - - tft_string.set(string, itemIndex, itemString); - tft.add_text(offset, MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string); -} - -// Draw a menu item with a (potentially) editable value -void MenuEditItemBase::draw(const bool sel, const uint8_t row, PGM_P const pstr, const char* const data, const bool pgm) { - menu_item(row, sel); - - tft_string.set(pstr, itemIndex, itemString); - tft.add_text(MENU_TEXT_X_OFFSET, MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string); - if (data) { - tft_string.set(data); - tft.add_text(TFT_WIDTH - MENU_TEXT_X_OFFSET - tft_string.width(), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string); - } } // Low-level draw_edit_screen can be used to draw an edit screen from anyplace -void MenuEditItemBase::draw_edit_screen(PGM_P const pstr, const char* const value/*=nullptr*/) { +void MenuEditItemBase::draw_edit_screen(PGM_P const pstr, const char * const value/*=nullptr*/) { ui.encoder_direction_normal(); TERN_(TOUCH_SCREEN, touch.clear()); @@ -428,28 +380,32 @@ void MenuEditItemBase::draw_edit_screen(PGM_P const pstr, const char* const valu extern screenFunc_t _manual_move_func_ptr; if (ui.currentScreen != _manual_move_func_ptr && !ui.external_control) { - #define SLIDER_LENGHT 336 + #define SLIDER_LENGTH 336 #define SLIDER_Y_POSITION 186 - tft.canvas((TFT_WIDTH - SLIDER_LENGHT) / 2, SLIDER_Y_POSITION, SLIDER_LENGHT, 16); + tft.canvas((TFT_WIDTH - SLIDER_LENGTH) / 2, SLIDER_Y_POSITION, SLIDER_LENGTH, 16); tft.set_background(COLOR_BACKGROUND); - int16_t position = (SLIDER_LENGHT - 2) * ui.encoderPosition / maxEditValue; + int16_t position = (SLIDER_LENGTH - 2) * ui.encoderPosition / maxEditValue; tft.add_bar(0, 7, 1, 2, ui.encoderPosition == 0 ? COLOR_SLIDER_INACTIVE : COLOR_SLIDER); tft.add_bar(1, 6, position, 4, COLOR_SLIDER); - tft.add_bar(position + 1, 6, SLIDER_LENGHT - 2 - position, 4, COLOR_SLIDER_INACTIVE); - tft.add_bar(SLIDER_LENGHT - 1, 7, 1, 2, int32_t(ui.encoderPosition) == maxEditValue ? COLOR_SLIDER : COLOR_SLIDER_INACTIVE); + tft.add_bar(position + 1, 6, SLIDER_LENGTH - 2 - position, 4, COLOR_SLIDER_INACTIVE); + tft.add_bar(SLIDER_LENGTH - 1, 7, 1, 2, int32_t(ui.encoderPosition) == maxEditValue ? COLOR_SLIDER : COLOR_SLIDER_INACTIVE); #if ENABLED(TOUCH_SCREEN) - tft.add_image((SLIDER_LENGHT - 8) * ui.encoderPosition / maxEditValue, 0, imgSlider, COLOR_SLIDER); - touch.add_control(SLIDER, (TFT_WIDTH - SLIDER_LENGHT) / 2, SLIDER_Y_POSITION - 8, SLIDER_LENGHT, 32, maxEditValue); + tft.add_image((SLIDER_LENGTH - 8) * ui.encoderPosition / maxEditValue, 0, imgSlider, COLOR_SLIDER); + touch.add_control(SLIDER, (TFT_WIDTH - SLIDER_LENGTH) / 2, SLIDER_Y_POSITION - 8, SLIDER_LENGTH, 32, maxEditValue); #endif } + tft.draw_edit_screen_buttons(); +} + +void TFT::draw_edit_screen_buttons() { #if ENABLED(TOUCH_SCREEN) - add_control(64, 256, DECREASE, imgDecrease); - add_control(352, 256, INCREASE, imgIncrease); - add_control(208, 256, CLICK, imgConfirm); + add_control(64, TFT_HEIGHT - 64, DECREASE, imgDecrease); + add_control(352, TFT_HEIGHT - 64, INCREASE, imgIncrease); + add_control(208, TFT_HEIGHT - 64, CLICK, imgConfirm); #endif } @@ -457,7 +413,7 @@ void MenuEditItemBase::draw_edit_screen(PGM_P const pstr, const char* const valu void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const bool yesno, PGM_P const pref, const char * const string/*=nullptr*/, PGM_P const suff/*=nullptr*/) { uint16_t line = 1; - if (string == NULL) line++; + if (!string) line++; menu_line(line++); tft_string.set(pref); @@ -478,21 +434,13 @@ void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const tft.add_text(tft_string.center(TFT_WIDTH), 0, COLOR_MENU_TEXT, tft_string); } #if ENABLED(TOUCH_SCREEN) - add_control(88, 256, CANCEL, imgCancel, true, yesno ? HALF(COLOR_CONTROL_CANCEL) : COLOR_CONTROL_CANCEL); - add_control(328, 256, CONFIRM, imgConfirm, true, yesno ? COLOR_CONTROL_CONFIRM : HALF(COLOR_CONTROL_CONFIRM)); + add_control(88, TFT_HEIGHT - 64, CANCEL, imgCancel, true, yesno ? HALF(COLOR_CONTROL_CANCEL) : COLOR_CONTROL_CANCEL); + add_control(328, TFT_HEIGHT - 64, CONFIRM, imgConfirm, true, yesno ? COLOR_CONTROL_CONFIRM : HALF(COLOR_CONTROL_CONFIRM)); #endif } -#if ENABLED(SDSUPPORT) - void MenuItem_sdbase::draw(const bool sel, const uint8_t row, PGM_P const, CardReader &theCard, const bool isDir) { - menu_item(row, sel); - if (isDir) - tft.add_image(5, 5, imgDirectory, COLOR_MENU_TEXT, sel ? COLOR_SELECTION_BG : COLOR_BACKGROUND); - tft.add_text(42, MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, theCard.longest_filename()); - } -#endif - #if ENABLED(ADVANCED_PAUSE_FEATURE) + void MarlinUI::draw_hotend_status(const uint8_t row, const uint8_t extruder) { #if ENABLED(TOUCH_SCREEN) touch.clear(); @@ -505,7 +453,7 @@ void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const tft_string.add('E'); tft_string.add((char)('1' + extruder)); tft_string.add(' '); - tft_string.add(i16tostr3rj(thermalManager.degHotend(extruder))); + tft_string.add(i16tostr3rj(thermalManager.wholeDegHotend(extruder))); tft_string.add(LCD_STR_DEGREE); tft_string.add(" / "); tft_string.add(i16tostr3rj(thermalManager.degTargetHotend(extruder))); @@ -513,6 +461,7 @@ void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const tft_string.trim(); tft.add_text(tft_string.center(TFT_WIDTH), 0, COLOR_MENU_TEXT, tft_string); } + #endif // ADVANCED_PAUSE_FEATURE #if ENABLED(AUTO_BED_LEVELING_UBL) @@ -528,17 +477,17 @@ void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const tft.set_background(COLOR_BACKGROUND); tft.add_rectangle(0, 0, GRID_WIDTH, GRID_HEIGHT, COLOR_WHITE); - for (uint16_t x = 0; x < GRID_MAX_POINTS_X ; x++) - for (uint16_t y = 0; y < GRID_MAX_POINTS_Y ; y++) + for (uint16_t x = 0; x < (GRID_MAX_POINTS_X); x++) + for (uint16_t y = 0; y < (GRID_MAX_POINTS_Y); y++) if (position_is_reachable({ ubl.mesh_index_to_xpos(x), ubl.mesh_index_to_ypos(y) })) - tft.add_bar(1 + (x * 2 + 1) * (GRID_WIDTH - 4) / GRID_MAX_POINTS_X / 2, GRID_HEIGHT - 3 - ((y * 2 + 1) * (GRID_HEIGHT - 4) / GRID_MAX_POINTS_Y / 2), 2, 2, COLOR_UBL); + tft.add_bar(1 + (x * 2 + 1) * (GRID_WIDTH - 4) / (GRID_MAX_POINTS_X) / 2, GRID_HEIGHT - 3 - ((y * 2 + 1) * (GRID_HEIGHT - 4) / (GRID_MAX_POINTS_Y) / 2), 2, 2, COLOR_UBL); - tft.add_rectangle((x_plot * 2 + 1) * (GRID_WIDTH - 4) / GRID_MAX_POINTS_X / 2 - 1, GRID_HEIGHT - 5 - ((y_plot * 2 + 1) * (GRID_HEIGHT - 4) / GRID_MAX_POINTS_Y / 2), 6, 6, COLOR_UBL); + tft.add_rectangle((x_plot * 2 + 1) * (GRID_WIDTH - 4) / (GRID_MAX_POINTS_X) / 2 - 1, GRID_HEIGHT - 5 - ((y_plot * 2 + 1) * (GRID_HEIGHT - 4) / (GRID_MAX_POINTS_Y) / 2), 6, 6, COLOR_UBL); const xy_pos_t pos = { ubl.mesh_index_to_xpos(x_plot), ubl.mesh_index_to_ypos(y_plot) }, lpos = pos.asLogical(); - tft.canvas(320, GRID_OFFSET_Y + (GRID_HEIGHT - 43) / 2 - 43, 120, 43); + tft.canvas(320, GRID_OFFSET_Y + (GRID_HEIGHT - MENU_ITEM_HEIGHT) / 2 - MENU_ITEM_HEIGHT, 120, MENU_ITEM_HEIGHT); tft.set_background(COLOR_BACKGROUND); tft_string.set(X_LBL); tft.add_text(0, MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string); @@ -546,7 +495,7 @@ void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const tft_string.trim(); tft.add_text(120 - tft_string.width(), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string); - tft.canvas(320, GRID_OFFSET_Y + (GRID_HEIGHT - 43) / 2, 120, 43); + tft.canvas(320, GRID_OFFSET_Y + (GRID_HEIGHT - MENU_ITEM_HEIGHT) / 2, 120, MENU_ITEM_HEIGHT); tft.set_background(COLOR_BACKGROUND); tft_string.set(Y_LBL); tft.add_text(0, MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string); @@ -554,7 +503,7 @@ void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const tft_string.trim(); tft.add_text(120 - tft_string.width(), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string); - tft.canvas(320, GRID_OFFSET_Y + (GRID_HEIGHT - 43) / 2 + 43, 120, 43); + tft.canvas(320, GRID_OFFSET_Y + (GRID_HEIGHT - MENU_ITEM_HEIGHT) / 2 + MENU_ITEM_HEIGHT, 120, MENU_ITEM_HEIGHT); tft.set_background(COLOR_BACKGROUND); tft_string.set(Z_LBL); tft.add_text(0, MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string); @@ -562,99 +511,32 @@ void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const tft_string.trim(); tft.add_text(120 - tft_string.width(), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string); - - tft.canvas(GRID_OFFSET_X + (GRID_WIDTH - 48) / 2, GRID_OFFSET_Y + GRID_HEIGHT + CONTROL_OFFSET - 5, 48, 43); + constexpr uint8_t w = (TFT_WIDTH) / 10; + tft.canvas(GRID_OFFSET_X + (GRID_WIDTH - w) / 2, GRID_OFFSET_Y + GRID_HEIGHT + CONTROL_OFFSET - 5, w, MENU_ITEM_HEIGHT); tft.set_background(COLOR_BACKGROUND); tft_string.set(ui8tostr3rj(x_plot)); tft_string.trim(); - tft.add_text(tft_string.center(48), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string); + tft.add_text(tft_string.center(w), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string); - tft.canvas(GRID_OFFSET_X + GRID_WIDTH + CONTROL_OFFSET + 16 - 24, GRID_OFFSET_Y + (GRID_HEIGHT - 43) / 2, 48, 43); + tft.canvas(GRID_OFFSET_X + GRID_WIDTH + CONTROL_OFFSET + 16 - 24, GRID_OFFSET_Y + (GRID_HEIGHT - MENU_ITEM_HEIGHT) / 2, w, MENU_ITEM_HEIGHT); tft.set_background(COLOR_BACKGROUND); tft_string.set(ui8tostr3rj(y_plot)); tft_string.trim(); - tft.add_text(tft_string.center(48), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string); + tft.add_text(tft_string.center(w), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string); #if ENABLED(TOUCH_SCREEN) touch.clear(); draw_menu_navigation = false; - add_control(GRID_OFFSET_X + GRID_WIDTH + CONTROL_OFFSET, GRID_OFFSET_Y + CONTROL_OFFSET, UBL, ENCODER_STEPS_PER_MENU_ITEM * GRID_MAX_POINTS_X, imgUp); - add_control(GRID_OFFSET_X + GRID_WIDTH + CONTROL_OFFSET, GRID_OFFSET_Y + GRID_HEIGHT - CONTROL_OFFSET - 32, UBL, - ENCODER_STEPS_PER_MENU_ITEM * GRID_MAX_POINTS_X, imgDown); - add_control(GRID_OFFSET_X + CONTROL_OFFSET, GRID_OFFSET_Y + GRID_HEIGHT + CONTROL_OFFSET, UBL, - ENCODER_STEPS_PER_MENU_ITEM, imgLeft); + add_control(GRID_OFFSET_X + GRID_WIDTH + CONTROL_OFFSET, GRID_OFFSET_Y + CONTROL_OFFSET, UBL, (ENCODER_STEPS_PER_MENU_ITEM) * (GRID_MAX_POINTS_X), imgUp); + add_control(GRID_OFFSET_X + GRID_WIDTH + CONTROL_OFFSET, GRID_OFFSET_Y + GRID_HEIGHT - CONTROL_OFFSET - 32, UBL, -(ENCODER_STEPS_PER_MENU_ITEM) * (GRID_MAX_POINTS_X), imgDown); + add_control(GRID_OFFSET_X + CONTROL_OFFSET, GRID_OFFSET_Y + GRID_HEIGHT + CONTROL_OFFSET, UBL, -(ENCODER_STEPS_PER_MENU_ITEM), imgLeft); add_control(GRID_OFFSET_X + GRID_WIDTH - CONTROL_OFFSET - 32, GRID_OFFSET_Y + GRID_HEIGHT + CONTROL_OFFSET, UBL, ENCODER_STEPS_PER_MENU_ITEM, imgRight); add_control(320, GRID_OFFSET_Y + GRID_HEIGHT + CONTROL_OFFSET, CLICK, imgLeveling); - add_control(224, 286, BACK, imgBack); + add_control(224, TFT_HEIGHT - 34, BACK, imgBack); #endif } #endif // AUTO_BED_LEVELING_UBL -#if ENABLED(TOUCH_SCREEN_CALIBRATION) - void MarlinUI::touch_calibration() { - static uint16_t x, y; - - calibrationState calibration_stage = touch.get_calibration_state(); - - if (calibration_stage == CALIBRATION_NONE) { - defer_status_screen(true); - clear_lcd(); - calibration_stage = touch.calibration_start(); - } - else { - tft.canvas(x - 15, y - 15, 31, 31); - tft.set_background(COLOR_BACKGROUND); - } - - x = 20; y = 20; - touch.clear(); - - if (calibration_stage < CALIBRATION_SUCCESS) { - switch (calibration_stage) { - case CALIBRATION_POINT_1: tft_string.set("Top Left"); break; - case CALIBRATION_POINT_2: y = TFT_HEIGHT - 21; tft_string.set("Bottom Left"); break; - case CALIBRATION_POINT_3: x = TFT_WIDTH - 21; tft_string.set("Top Right"); break; - case CALIBRATION_POINT_4: x = TFT_WIDTH - 21; y = TFT_HEIGHT - 21; tft_string.set("Bottom Right"); break; - default: break; - } - - tft.canvas(x - 15, y - 15, 31, 31); - tft.set_background(COLOR_BACKGROUND); - tft.add_bar(0, 15, 31, 1, COLOR_TOUCH_CALIBRATION); - tft.add_bar(15, 0, 1, 31, COLOR_TOUCH_CALIBRATION); - - touch.add_control(CALIBRATE, 0, 0, TFT_WIDTH, TFT_HEIGHT, uint32_t(x) << 16 | uint32_t(y)); - } - else { - tft_string.set(calibration_stage == CALIBRATION_SUCCESS ? "Calibration Completed" : "Calibration Failed"); - defer_status_screen(false); - touch.calibration_end(); - touch.add_control(BACK, 0, 0, TFT_WIDTH, TFT_HEIGHT); - } - - tft.canvas(0, (TFT_HEIGHT - tft_string.font_height()) >> 1, TFT_WIDTH, tft_string.font_height()); - tft.set_background(COLOR_BACKGROUND); - tft.add_text(tft_string.center(TFT_WIDTH), 0, COLOR_MENU_TEXT, tft_string); - } -#endif // TOUCH_SCREEN_CALIBRATION - -void menu_line(const uint8_t row, uint16_t color) { - tft.canvas(0, 4 + 45 * row, TFT_WIDTH, 43); - tft.set_background(color); -} - -void menu_pause_option(); - -void menu_item(const uint8_t row, bool sel ) { - #if ENABLED(TOUCH_SCREEN) - if (row == 0) { - touch.clear(); - draw_menu_navigation = TERN(ADVANCED_PAUSE_FEATURE, ui.currentScreen != menu_pause_option, true); - } - #endif - - menu_line(row, sel ? COLOR_SELECTION_BG : COLOR_BACKGROUND); - TERN_(TOUCH_SCREEN, touch.add_control(sel ? CLICK : MENU_ITEM, 0, 4 + 45 * row, TFT_WIDTH, 43, encoderTopLine + row)); -} - #if ENABLED(BABYSTEP_ZPROBE_OFFSET) #include "../../feature/babystep.h" #endif @@ -671,7 +553,6 @@ struct MotionAxisState { float currentStepSize = 10.0; int z_selection = Z_SELECTION_Z; uint8_t e_selection = 0; - bool homming = false; bool blocked = false; char message[32]; }; @@ -736,16 +617,11 @@ static void drawMessage(const char *msg) { tft.add_text(0, 0, COLOR_YELLOW, msg); } -static void drawAxisValue(AxisEnum axis) { - const float value = - #if HAS_BED_PROBE - axis == Z_AXIS && motionAxisState.z_selection == Z_SELECTION_Z_PROBE ? - probe.offset.z : - #endif - NATIVE_TO_LOGICAL( - ui.manual_move.processing ? destination[axis] : current_position[axis] + TERN0(IS_KINEMATIC, ui.manual_move.offset), - axis - ); +static void drawAxisValue(const AxisEnum axis) { + const float value = ( + TERN_(HAS_BED_PROBE, axis == Z_AXIS && motionAxisState.z_selection == Z_SELECTION_Z_PROBE ? probe.offset.z :) + ui.manual_move.axis_value(axis) + ); xy_int_t pos; uint16_t color; switch (axis) { @@ -761,13 +637,15 @@ static void drawAxisValue(AxisEnum axis) { tft.add_text(0, 0, color, tft_string); } -static void moveAxis(AxisEnum axis, const int8_t direction) { +static void moveAxis(const AxisEnum axis, const int8_t direction) { quick_feedback(); - if (axis == E_AXIS && thermalManager.temp_hotend[motionAxisState.e_selection].celsius < EXTRUDE_MINTEMP) { - drawMessage("Too cold"); - return; - } + #if ENABLED(PREVENT_COLD_EXTRUSION) + if (axis == E_AXIS && thermalManager.tooColdToExtrude(motionAxisState.e_selection)) { + drawMessage("Too cold"); + return; + } + #endif const float diff = motionAxisState.currentStepSize * direction; @@ -827,98 +705,60 @@ static void moveAxis(AxisEnum axis, const int8_t direction) { #endif // Get the new position + const bool limited = ui.manual_move.apply_diff(axis, diff, min, max); #if IS_KINEMATIC - ui.manual_move.offset += diff; - if (direction < 0) - NOLESS(ui.manual_move.offset, min - current_position[axis]); - else - NOMORE(ui.manual_move.offset, max - current_position[axis]); + UNUSED(limited); #else - current_position[axis] += diff; - if (direction < 0 && current_position[axis] < min) { - current_position[axis] = min; - drawMessage(GET_TEXT(MSG_LCD_SOFT_ENDSTOPS)); - } - else if (direction > 0 && current_position[axis] > max) { - current_position[axis] = max; - drawMessage(GET_TEXT(MSG_LCD_SOFT_ENDSTOPS)); - } - else { - drawMessage(""); // clear the error - } + PGM_P const msg = limited ? GET_TEXT(MSG_LCD_SOFT_ENDSTOPS) : NUL_STR; + drawMessage(msg); #endif - ui.manual_move.soon(axis - #if MULTI_MANUAL - , motionAxisState.e_selection - #endif - ); + ui.manual_move.soon(axis OPTARG(MULTI_E_MANUAL, motionAxisState.e_selection)); } drawAxisValue(axis); } -static void e_plus() { - moveAxis(E_AXIS, 1); -} - -static void e_minus() { - moveAxis(E_AXIS, -1); -} - -static void x_minus() { - moveAxis(X_AXIS, -1); -} - -static void x_plus() { - moveAxis(X_AXIS, 1); -} - -static void y_plus() { - moveAxis(Y_AXIS, 1); -} - -static void y_minus() { - moveAxis(Y_AXIS, -1); -} - -static void z_plus() { - moveAxis(Z_AXIS, 1); -} - -static void z_minus() { - moveAxis(Z_AXIS, -1); -} +static void e_plus() { moveAxis(E_AXIS, 1); } +static void e_minus() { moveAxis(E_AXIS, -1); } +static void x_minus() { moveAxis(X_AXIS, -1); } +static void x_plus() { moveAxis(X_AXIS, 1); } +static void y_plus() { moveAxis(Y_AXIS, 1); } +static void y_minus() { moveAxis(Y_AXIS, -1); } +static void z_plus() { moveAxis(Z_AXIS, 1); } +static void z_minus() { moveAxis(Z_AXIS, -1); } + +#if ENABLED(TOUCH_SCREEN) + static void e_select() { + motionAxisState.e_selection++; + if (motionAxisState.e_selection >= EXTRUDERS) { + motionAxisState.e_selection = 0; + } -static void e_select() { - motionAxisState.e_selection++; - if (motionAxisState.e_selection >= EXTRUDERS) { - motionAxisState.e_selection = 0; + quick_feedback(); + drawCurESelection(); + drawAxisValue(E_AXIS); } - quick_feedback(); - drawCurESelection(); - drawAxisValue(E_AXIS); -} - -static void do_home() { - quick_feedback(); - drawMessage(GET_TEXT(MSG_LEVEL_BED_HOMING)); - queue.inject_P(G28_STR); - // Disable touch until home is done - TERN_(HAS_TFT_XPT2046, touch.disable()); - drawAxisValue(E_AXIS); - drawAxisValue(X_AXIS); - drawAxisValue(Y_AXIS); - drawAxisValue(Z_AXIS); -} + static void do_home() { + quick_feedback(); + drawMessage(GET_TEXT(MSG_LEVEL_BED_HOMING)); + queue.inject_P(G28_STR); + // Disable touch until home is done + TERN_(HAS_TFT_XPT2046, touch.disable()); + drawAxisValue(E_AXIS); + drawAxisValue(X_AXIS); + drawAxisValue(Y_AXIS); + drawAxisValue(Z_AXIS); + } -static void step_size() { - motionAxisState.currentStepSize = motionAxisState.currentStepSize / 10.0; - if (motionAxisState.currentStepSize < 0.0015) motionAxisState.currentStepSize = 10.0; - quick_feedback(); - drawCurStepValue(); -} + static void step_size() { + motionAxisState.currentStepSize = motionAxisState.currentStepSize / 10.0; + if (motionAxisState.currentStepSize < 0.0015) motionAxisState.currentStepSize = 10.0; + quick_feedback(); + drawCurStepValue(); + } +#endif #if HAS_BED_PROBE static void z_select() { @@ -934,7 +774,7 @@ static void disable_steppers() { queue.inject_P(PSTR("M84")); } -static void drawBtn(int x, int y, const char* label, int32_t data, MarlinImage img, uint16_t bgColor, bool enabled = true) { +static void drawBtn(int x, int y, const char *label, intptr_t data, MarlinImage img, uint16_t bgColor, bool enabled = true) { uint16_t width = Images[imgBtn52Rounded].width; uint16_t height = Images[imgBtn52Rounded].height; @@ -945,7 +785,7 @@ static void drawBtn(int x, int y, const char* label, int32_t data, MarlinImage i tft.add_image(0, 0, imgBtn52Rounded, bgColor, COLOR_BACKGROUND, COLOR_DARKGREY); // TODO: Make an add_text() taking a font arg - if (label != NULL) { + if (label) { tft_string.set(label); tft_string.trim(); tft.add_text(tft_string.center(width), height / 2 - tft_string.font_height() / 2, bgColor, tft_string); @@ -969,17 +809,18 @@ void MarlinUI::move_axis_screen() { const bool busy = printingIsActive(); - // if we have baby step and we are printing, select baby step - if (busy && ENABLED(BABYSTEP_ZPROBE_OFFSET)) motionAxisState.z_selection = Z_SELECTION_Z_PROBE; + // Babysteps during printing? Select babystep for Z probe offset + if (busy && ENABLED(BABYSTEP_ZPROBE_OFFSET)) + motionAxisState.z_selection = Z_SELECTION_Z_PROBE; // ROW 1 -> E- Y- CurY Z+ int x = X_MARGIN, y = Y_MARGIN, spacing = 0; - drawBtn(x, y, "E+", (int32_t)e_plus, imgUp, E_BTN_COLOR, !busy); + drawBtn(x, y, "E+", (intptr_t)e_plus, imgUp, E_BTN_COLOR, !busy); spacing = (TFT_WIDTH - X_MARGIN * 2 - 3 * BTN_WIDTH) / 2; x += BTN_WIDTH + spacing; - drawBtn(x, y, "Y+", (int32_t)y_plus, imgUp, Y_BTN_COLOR, !busy); + drawBtn(x, y, "Y+", (intptr_t)y_plus, imgUp, Y_BTN_COLOR, !busy); // Cur Y x += BTN_WIDTH; @@ -988,7 +829,7 @@ void MarlinUI::move_axis_screen() { drawAxisValue(Y_AXIS); x += spacing; - drawBtn(x, y, "Z+", (int32_t)z_plus, imgUp, Z_BTN_COLOR, !busy || ENABLED(BABYSTEP_ZPROBE_OFFSET)); //only enabled when not busy or have baby step + drawBtn(x, y, "Z+", (intptr_t)z_plus, imgUp, Z_BTN_COLOR, !busy || ENABLED(BABYSTEP_ZPROBE_OFFSET)); //only enabled when not busy or have baby step // ROW 2 -> "Ex" X- HOME X+ "Z" y += BTN_HEIGHT + (TFT_HEIGHT - Y_MARGIN * 2 - 4 * BTN_HEIGHT) / 3; @@ -998,24 +839,24 @@ void MarlinUI::move_axis_screen() { motionAxisState.eNamePos.x = x; motionAxisState.eNamePos.y = y; drawCurESelection(); - TERN_(HAS_TFT_XPT2046, if (!busy) touch.add_control(BUTTON, x, y, BTN_WIDTH, BTN_HEIGHT, (int32_t)e_select)); + TERN_(HAS_TFT_XPT2046, if (!busy) touch.add_control(BUTTON, x, y, BTN_WIDTH, BTN_HEIGHT, (intptr_t)e_select)); x += BTN_WIDTH + spacing; - drawBtn(x, y, "X-", (int32_t)x_minus, imgLeft, X_BTN_COLOR, !busy); + drawBtn(x, y, "X-", (intptr_t)x_minus, imgLeft, X_BTN_COLOR, !busy); x += BTN_WIDTH + spacing; //imgHome is 64x64 - TERN_(HAS_TFT_XPT2046, add_control(TFT_WIDTH / 2 - Images[imgHome].width / 2, y - (Images[imgHome].width - BTN_HEIGHT) / 2, BUTTON, (int32_t)do_home, imgHome, !busy)); + TERN_(HAS_TFT_XPT2046, add_control(TFT_WIDTH / 2 - Images[imgHome].width / 2, y - (Images[imgHome].width - BTN_HEIGHT) / 2, BUTTON, (intptr_t)do_home, imgHome, !busy)); x += BTN_WIDTH + spacing; uint16_t xplus_x = x; - drawBtn(x, y, "X+", (int32_t)x_plus, imgRight, X_BTN_COLOR, !busy); + drawBtn(x, y, "X+", (intptr_t)x_plus, imgRight, X_BTN_COLOR, !busy); x += BTN_WIDTH + spacing; motionAxisState.zTypePos.x = x; motionAxisState.zTypePos.y = y; drawCurZSelection(); - #if HAS_BED_PROBE - if (!busy) touch.add_control(BUTTON, x, y, BTN_WIDTH, 34 * 2, (int32_t)z_select); + #if BOTH(HAS_BED_PROBE, TOUCH_SCREEN) + if (!busy) touch.add_control(BUTTON, x, y, BTN_WIDTH, 34 * 2, (intptr_t)z_select); #endif // ROW 3 -> E- CurX Y- Z- @@ -1023,7 +864,7 @@ void MarlinUI::move_axis_screen() { x = X_MARGIN; spacing = (TFT_WIDTH - X_MARGIN * 2 - 3 * BTN_WIDTH) / 2; - drawBtn(x, y, "E-", (int32_t)e_minus, imgDown, E_BTN_COLOR, !busy); + drawBtn(x, y, "E-", (intptr_t)e_minus, imgDown, E_BTN_COLOR, !busy); // Cur E motionAxisState.eValuePos.x = x; @@ -1036,10 +877,10 @@ void MarlinUI::move_axis_screen() { drawAxisValue(X_AXIS); x += BTN_WIDTH + spacing; - drawBtn(x, y, "Y-", (int32_t)y_minus, imgDown, Y_BTN_COLOR, !busy); + drawBtn(x, y, "Y-", (intptr_t)y_minus, imgDown, Y_BTN_COLOR, !busy); x += BTN_WIDTH + spacing; - drawBtn(x, y, "Z-", (int32_t)z_minus, imgDown, Z_BTN_COLOR, !busy || ENABLED(BABYSTEP_ZPROBE_OFFSET)); //only enabled when not busy or have baby step + drawBtn(x, y, "Z-", (intptr_t)z_minus, imgDown, Z_BTN_COLOR, !busy || ENABLED(BABYSTEP_ZPROBE_OFFSET)); //only enabled when not busy or have baby step // Cur Z motionAxisState.zValuePos.x = x; @@ -1053,16 +894,13 @@ void MarlinUI::move_axis_screen() { motionAxisState.stepValuePos.y = y; if (!busy) { drawCurStepValue(); - TERN_(HAS_TFT_XPT2046, touch.add_control(BUTTON, motionAxisState.stepValuePos.x, motionAxisState.stepValuePos.y, CUR_STEP_VALUE_WIDTH, BTN_HEIGHT, (int32_t)step_size)); + TERN_(HAS_TFT_XPT2046, touch.add_control(BUTTON, motionAxisState.stepValuePos.x, motionAxisState.stepValuePos.y, CUR_STEP_VALUE_WIDTH, BTN_HEIGHT, (intptr_t)step_size)); } - // alinged with x+ - drawBtn(xplus_x, TFT_HEIGHT - Y_MARGIN - BTN_HEIGHT, "off", (int32_t)disable_steppers, imgCancel, COLOR_WHITE, !busy); + // aligned with x+ + drawBtn(xplus_x, TFT_HEIGHT - Y_MARGIN - BTN_HEIGHT, "off", (intptr_t)disable_steppers, imgCancel, COLOR_WHITE, !busy); TERN_(HAS_TFT_XPT2046, add_control(TFT_WIDTH - X_MARGIN - BTN_WIDTH, y, BACK, imgBack)); } -#undef BTN_WIDTH -#undef BTN_HEIGHT - #endif // HAS_UI_480x320 diff --git a/Marlin/src/lcd/tft/ui_480x320.h b/Marlin/src/lcd/tft/ui_480x320.h index 053ee78158cb..fca9ed9c2a22 100644 --- a/Marlin/src/lcd/tft/ui_480x320.h +++ b/Marlin/src/lcd/tft/ui_480x320.h @@ -21,88 +21,29 @@ */ #pragma once -#include "../../inc/MarlinConfigPre.h" - -#include "tft.h" -#include "tft_image.h" - -#if ENABLED(TOUCH_SCREEN) - #include "touch.h" -#endif - -void draw_heater_status(uint16_t x, uint16_t y, const int8_t Heater); -void draw_fan_status(uint16_t x, uint16_t y, const bool blink); - -#define MENU_TEXT_X_OFFSET 16 -#define MENU_TEXT_Y_OFFSET 7 -void menu_line(const uint8_t row, uint16_t color = COLOR_BACKGROUND); -void menu_item(const uint8_t row, bool sel = false); - -#define MENU_FONT_NAME Helvetica18 -#define SYMBOLS_FONT_NAME Helvetica18_symbols - -#define ABSOLUTE_ZERO -273.15 - -const tImage Images[imgCount] = { - MarlinLogo195x59x16, - HotEnd_64x64x4, - Bed_64x64x4, - Bed_Heated_64x64x4, - Chamber_64x64x4, - Chamber_Heated_64x64x4, - Fan0_64x64x4, - Fan_Slow0_64x64x4, - Fan_Slow1_64x64x4, - Fan_Fast0_64x64x4, - Fan_Fast1_64x64x4, - Feedrate_32x32x4, - Flowrate_32x32x4, - SD_64x64x4, - Menu_64x64x4, - Settings_64x64x4, - Directory_32x32x4, - Confirm_64x64x4, - Cancel_64x64x4, - Increase_64x64x4, - Decrease_64x64x4, - Back_32x32x4, - Up_32x32x4, - Down_32x32x4, - Left_32x32x4, - Right_32x32x4, - Refresh_32x32x4, - Leveling_32x32x4, - Slider8x16x4, - Home_64x64x4, - BtnRounded_64x52x4, -}; - -#if HAS_TEMP_CHAMBER && HOTENDS > 1 - #define ITEM_E0 0 - #define ITEM_E1 1 - #define ITEM_BED 2 - #define ITEM_CHAMBER 3 - #define ITEM_FAN 4 - #define ITEMS_COUNT 5 - #define POS_Y 4 -#elif HAS_TEMP_CHAMBER - #define ITEM_E0 0 - #define ITEM_BED 1 - #define ITEM_CHAMBER 2 - #define ITEM_FAN 3 - #define ITEMS_COUNT 4 - #define POS_Y 4 -#elif HOTENDS > 1 - #define ITEM_E0 0 - #define ITEM_E1 1 - #define ITEM_BED 2 - #define ITEM_FAN 3 - #define ITEMS_COUNT 4 - #define POS_Y 4 -#else - #define ITEM_E0 0 - #define ITEM_BED 1 - #define ITEM_FAN 2 - #define ITEMS_COUNT 3 - #define POS_Y 4 +#define MARLIN_LOGO_FULL_SIZE MarlinLogo480x320x16 + +#include "ui_common.h" + +#define TFT_STATUS_TOP_Y 4 +#define TFT_TOP_LINE_Y 4 + +#define MENU_TEXT_X_OFFSET 16 +#define MENU_TEXT_Y_OFFSET 7 + +#define MENU_ITEM_ICON_X 5 +#define MENU_ITEM_ICON_Y 5 +#define MENU_ITEM_ICON_SPACE 42 + +#if HAS_UI_480x320 + #define MENU_FONT_NAME Helvetica18 + #define SYMBOLS_FONT_NAME Helvetica18_symbols + #define MENU_ITEM_HEIGHT 43 + #define FONT_LINE_HEIGHT 34 +#elif HAS_UI_480x272 + #define MENU_FONT_NAME Helvetica14 + #define SYMBOLS_FONT_NAME Helvetica14_symbols + #define MENU_ITEM_HEIGHT 36 + #define FONT_LINE_HEIGHT 24 #endif +#define MENU_LINE_HEIGHT (MENU_ITEM_HEIGHT + 2) diff --git a/Marlin/src/lcd/tft/ui_common.cpp b/Marlin/src/lcd/tft/ui_common.cpp new file mode 100644 index 000000000000..7c053e7be711 --- /dev/null +++ b/Marlin/src/lcd/tft/ui_common.cpp @@ -0,0 +1,246 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../inc/MarlinConfigPre.h" + +#if HAS_GRAPHICAL_TFT + +#include "ui_common.h" +#include "../lcdprint.h" +#include "../../libs/numtostr.h" +#include "../menu/menu.h" + +void menu_pause_option(); + +static xy_uint_t cursor; + +#if ENABLED(TOUCH_SCREEN) + bool draw_menu_navigation = false; +#endif + +void menu_line(const uint8_t row, uint16_t color) { + cursor.set(0, row); + tft.canvas(0, TFT_TOP_LINE_Y + cursor.y * MENU_LINE_HEIGHT, TFT_WIDTH, MENU_ITEM_HEIGHT); + tft.set_background(color); +} + +void menu_item(const uint8_t row, bool sel ) { + #if ENABLED(TOUCH_SCREEN) + if (row == 0) { + touch.clear(); + draw_menu_navigation = TERN(ADVANCED_PAUSE_FEATURE, ui.currentScreen != menu_pause_option, true); + } + #endif + + menu_line(row, sel ? COLOR_SELECTION_BG : COLOR_BACKGROUND); + #if ENABLED(TOUCH_SCREEN) + const TouchControlType tct = TERN(SINGLE_TOUCH_NAVIGATION, true, sel) ? MENU_CLICK : MENU_ITEM; + touch.add_control(tct, 0, TFT_TOP_LINE_Y + row * MENU_LINE_HEIGHT, TFT_WIDTH, MENU_ITEM_HEIGHT, encoderTopLine + row); + #endif +} + +// +// lcdprint.h functions +// + +#define TFT_COL_WIDTH ((TFT_WIDTH) / (LCD_WIDTH)) + +void lcd_gotopixel(const uint16_t x, const uint16_t y) { + if (x >= TFT_WIDTH) return; + cursor.set(x / (TFT_COL_WIDTH), y / MENU_LINE_HEIGHT); + tft.canvas(x, TFT_TOP_LINE_Y + y, (TFT_WIDTH) - x, MENU_ITEM_HEIGHT); + tft.set_background(COLOR_BACKGROUND); +} + +void lcd_moveto(const lcd_uint_t col, const lcd_uint_t row) { + lcd_gotopixel(int(col) * (TFT_COL_WIDTH), int(row) * MENU_LINE_HEIGHT); +} + +int lcd_put_wchar_max(wchar_t c, pixel_len_t max_length) { + if (max_length < 1) return 0; + tft_string.set(); + tft_string.add(c); + tft.add_text(MENU_TEXT_X_OFFSET, MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string); + lcd_gotopixel((cursor.x + 1) * (TFT_COL_WIDTH) + tft_string.width(), cursor.y * MENU_LINE_HEIGHT); + return tft_string.width(); +} + +int lcd_put_u8str_max_P(PGM_P utf8_str_P, pixel_len_t max_length) { + if (max_length < 1) return 0; + tft_string.set(utf8_str_P); + tft_string.trim(); + tft_string.truncate(max_length); + tft.add_text(MENU_TEXT_X_OFFSET, MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string); + lcd_gotopixel((cursor.x + 1) * (TFT_COL_WIDTH) + tft_string.width(), cursor.y * MENU_LINE_HEIGHT); + return tft_string.width(); +} + +int lcd_put_u8str_max(const char * utf8_str, pixel_len_t max_length) { + return lcd_put_u8str_max_P(utf8_str, max_length); +} + +void lcd_put_int(const int i) { + // 3 digits max for this one... + const char* str = i16tostr3left(int16_t(i)); + lcd_put_u8str_max(str, 3); +} + +// +// Menu Item methods +// + +// Draw a generic menu item with pre_char (if selected) and post_char +void MenuItemBase::_draw(const bool sel, const uint8_t row, PGM_P const pstr, const char pre_char, const char post_char) { + menu_item(row, sel); + + uint8_t *string = (uint8_t *)pstr; + MarlinImage image = noImage; + switch (*string) { + case 0x01: image = imgRefresh; break; // LCD_STR_REFRESH + case 0x02: image = imgDirectory; break; // LCD_STR_FOLDER + } + + uint8_t offset = MENU_TEXT_X_OFFSET; + if (image != noImage) { + string++; + offset = MENU_ITEM_ICON_SPACE; + tft.add_image(MENU_ITEM_ICON_X, MENU_ITEM_ICON_Y, image, COLOR_MENU_TEXT, sel ? COLOR_SELECTION_BG : COLOR_BACKGROUND); + } + + tft_string.set(string, itemIndex, itemString); + tft.add_text(offset, MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string); +} + +// Draw a menu item with a (potentially) editable value +void MenuEditItemBase::draw(const bool sel, const uint8_t row, PGM_P const pstr, const char * const data, const bool pgm) { + menu_item(row, sel); + + tft_string.set(pstr, itemIndex, itemString); + tft.add_text(MENU_TEXT_X_OFFSET, MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string); + if (data) { + tft_string.set(data); + tft.add_text(TFT_WIDTH - MENU_TEXT_X_OFFSET - tft_string.width(), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string); + } +} + +// Draw a static item with no left-right margin required. Centered by default. +void MenuItem_static::draw(const uint8_t row, PGM_P const pstr, const uint8_t style/*=SS_DEFAULT*/, const char * const vstr/*=nullptr*/) { + menu_item(row); + tft_string.set(pstr, itemIndex, itemString); + if (vstr) + tft_string.add(vstr); + tft.add_text(tft_string.center(TFT_WIDTH), MENU_TEXT_Y_OFFSET, COLOR_YELLOW, tft_string); +} + +#if ENABLED(SDSUPPORT) + + void MenuItem_sdbase::draw(const bool sel, const uint8_t row, PGM_P const, CardReader &theCard, const bool isDir) { + menu_item(row, sel); + if (isDir) + tft.add_image(MENU_ITEM_ICON_X, MENU_ITEM_ICON_Y, imgDirectory, COLOR_MENU_TEXT, sel ? COLOR_SELECTION_BG : COLOR_BACKGROUND); + tft.add_text(MENU_ITEM_ICON_SPACE, MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, theCard.longest_filename()); + } + +#endif + +// +// MarlinUI methods +// + +bool MarlinUI::detected() { return true; } + +void MarlinUI::init_lcd() { + tft.init(); + tft.set_font(MENU_FONT_NAME); + #ifdef SYMBOLS_FONT_NAME + tft.add_glyphs(SYMBOLS_FONT_NAME); + #endif + TERN_(TOUCH_SCREEN, touch.init()); + clear_lcd(); +} + +void MarlinUI::clear_lcd() { + #if ENABLED(TOUCH_SCREEN) + touch.reset(); + draw_menu_navigation = false; + #endif + + tft.queue.reset(); + tft.fill(0, 0, TFT_WIDTH, TFT_HEIGHT, COLOR_BACKGROUND); + cursor.set(0, 0); +} + +#if ENABLED(TOUCH_SCREEN_CALIBRATION) + + void MarlinUI::touch_calibration_screen() { + uint16_t x, y; + + calibrationState calibration_stage = touch_calibration.get_calibration_state(); + + if (calibration_stage == CALIBRATION_NONE) { + defer_status_screen(true); + clear_lcd(); + calibration_stage = touch_calibration.calibration_start(); + } + else { + x = touch_calibration.calibration_points[_MIN(calibration_stage - 1, CALIBRATION_BOTTOM_RIGHT)].x; + y = touch_calibration.calibration_points[_MIN(calibration_stage - 1, CALIBRATION_BOTTOM_RIGHT)].y; + tft.canvas(x - 15, y - 15, 31, 31); + tft.set_background(COLOR_BACKGROUND); + } + + touch.clear(); + + if (calibration_stage < CALIBRATION_SUCCESS) { + switch (calibration_stage) { + case CALIBRATION_TOP_LEFT: tft_string.set(GET_TEXT(MSG_TOP_LEFT)); break; + case CALIBRATION_BOTTOM_LEFT: tft_string.set(GET_TEXT(MSG_BOTTOM_LEFT)); break; + case CALIBRATION_TOP_RIGHT: tft_string.set(GET_TEXT(MSG_TOP_RIGHT)); break; + case CALIBRATION_BOTTOM_RIGHT: tft_string.set(GET_TEXT(MSG_BOTTOM_RIGHT)); break; + default: break; + } + + x = touch_calibration.calibration_points[calibration_stage].x; + y = touch_calibration.calibration_points[calibration_stage].y; + + tft.canvas(x - 15, y - 15, 31, 31); + tft.set_background(COLOR_BACKGROUND); + tft.add_bar(0, 15, 31, 1, COLOR_TOUCH_CALIBRATION); + tft.add_bar(15, 0, 1, 31, COLOR_TOUCH_CALIBRATION); + + touch.add_control(CALIBRATE, 0, 0, TFT_WIDTH, TFT_HEIGHT, uint32_t(x) << 16 | uint32_t(y)); + } + else { + tft_string.set(calibration_stage == CALIBRATION_SUCCESS ? GET_TEXT(MSG_CALIBRATION_COMPLETED) : GET_TEXT(MSG_CALIBRATION_FAILED)); + defer_status_screen(false); + touch_calibration.calibration_end(); + touch.add_control(BACK, 0, 0, TFT_WIDTH, TFT_HEIGHT); + } + + tft.canvas(0, (TFT_HEIGHT - tft_string.font_height()) >> 1, TFT_WIDTH, tft_string.font_height()); + tft.set_background(COLOR_BACKGROUND); + tft.add_text(tft_string.center(TFT_WIDTH), 0, COLOR_MENU_TEXT, tft_string); + } + +#endif // TOUCH_SCREEN_CALIBRATION + +#endif // HAS_GRAPHICAL_TFT diff --git a/Marlin/src/lcd/tft/ui_common.h b/Marlin/src/lcd/tft/ui_common.h new file mode 100644 index 000000000000..617447a1817a --- /dev/null +++ b/Marlin/src/lcd/tft/ui_common.h @@ -0,0 +1,84 @@ +/** + * 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 + +#include "../../inc/MarlinConfigPre.h" + +#if !HAS_LCD_MENU + #error "Seriously? High resolution TFT screen without menu?" +#endif + +#include "tft.h" +#include "tft_image.h" + +#if ENABLED(TOUCH_SCREEN) + #include "touch.h" + extern bool draw_menu_navigation; +#endif + +#if HAS_UI_320x240 + #include "ui_320x240.h" +#elif HAS_UI_480x320 || HAS_UI_480x272 + #include "ui_480x320.h" +#elif HAS_UI_1024x600 + #include "ui_1024x600.h" +#else + #error "Unsupported display resolution!" +#endif + +void draw_heater_status(uint16_t x, uint16_t y, const int8_t Heater); +void draw_fan_status(uint16_t x, uint16_t y, const bool blink); + +void menu_line(const uint8_t row, uint16_t color=COLOR_BACKGROUND); +void menu_item(const uint8_t row, bool sel = false); + +#define ABSOLUTE_ZERO -273.15 + +#if HAS_TEMP_CHAMBER && HOTENDS > 1 + #define ITEM_E0 0 + #define ITEM_E1 1 + #define ITEM_BED 2 + #define ITEM_CHAMBER 3 + #define ITEM_FAN 4 + #define ITEMS_COUNT 5 +#elif HAS_TEMP_CHAMBER + #define ITEM_E0 0 + #define ITEM_BED 1 + #define ITEM_CHAMBER 2 + #define ITEM_FAN 3 + #define ITEMS_COUNT 4 +#elif HAS_TEMP_COOLER + #define ITEM_COOLER 0 + #define ITEM_FAN 1 + #define ITEMS_COUNT 2 +#elif HOTENDS > 1 + #define ITEM_E0 0 + #define ITEM_E1 1 + #define ITEM_BED 2 + #define ITEM_FAN 3 + #define ITEMS_COUNT 4 +#else + #define ITEM_E0 0 + #define ITEM_BED 1 + #define ITEM_FAN 2 + #define ITEMS_COUNT 3 +#endif diff --git a/Marlin/src/lcd/tft_io/ssd1963.h b/Marlin/src/lcd/tft_io/ssd1963.h index 4953a96233e8..8564b28bfb1d 100644 --- a/Marlin/src/lcd/tft_io/ssd1963.h +++ b/Marlin/src/lcd/tft_io/ssd1963.h @@ -39,10 +39,10 @@ IF_0((TFT_ORIENTATION) & TFT_INVERT_X, SSD1963_MADCTL_FH) | \ IF_0((TFT_ORIENTATION) & TFT_INVERT_Y, SSD1963_MADCTL_FV) -#if !defined(TFT_COLOR) || TFT_COLOR == TFT_COLOR_BGR - #define SSD1963_COLOR SSD1963_MADCTL_BGR -#elif TFT_COLOR == TFT_COLOR_RGB +#if !defined(TFT_COLOR) || TFT_COLOR == TFT_COLOR_RGB #define SSD1963_COLOR SSD1963_MADCTL_RGB +#elif TFT_COLOR == TFT_COLOR_BGR + #define SSD1963_COLOR SSD1963_MADCTL_BGR #endif #define SSD1963_MADCTL_DATA (SSD1963_ORIENTATION) | (SSD1963_COLOR) @@ -125,7 +125,7 @@ static const uint16_t ssd1963_init[] = { ESC_REG(SSD1963_NORON), ESC_REG(SSD1963_DISPON), - ESC_REG(SSD1963_SPWMCFG), 0x0006, 0x00f0, 0x0001, 0x00f0, 0x0000, 0x0000, + ESC_REG(SSD1963_SPWMCFG), 0x0006, 0x00F0, 0x0001, 0x00F0, 0x0000, 0x0000, ESC_REG(SSD1963_SDBCCFG), 0x000D, ESC_END }; diff --git a/Marlin/src/lcd/tft_io/st7796s.h b/Marlin/src/lcd/tft_io/st7796s.h index 8653a49ca2ef..e1931ed55148 100644 --- a/Marlin/src/lcd/tft_io/st7796s.h +++ b/Marlin/src/lcd/tft_io/st7796s.h @@ -154,6 +154,9 @@ static const uint16_t st7796s_init[] = { static const uint16_t lerdge_st7796s_init[] = { DATASIZE_8BIT, + ESC_REG(ST7796S_SWRESET), ESC_DELAY(100), + ESC_REG(ST7796S_SLPOUT), ESC_DELAY(20), + ESC_REG(ST7796S_CSCON), 0x00C3, // enable command 2 part I ESC_REG(ST7796S_CSCON), 0x0096, // enable command 2 part II @@ -165,7 +168,6 @@ static const uint16_t lerdge_st7796s_init[] = { ESC_REG(ST7796S_PWR2), 0x0015, ESC_REG(ST7796S_PWR3), 0x00AF, - ESC_REG(0xC3), 0x0009, // Register not documented in datasheet ESC_REG(ST7796S_VCMPCTL), 0x0022, ESC_REG(ST7796S_VCMOST), 0x0000, ESC_REG(ST7796S_DOCA), 0x0040, 0x008A, 0x0000, 0x0000, 0x0029, 0x0019, 0x00A5, 0x0033, diff --git a/Marlin/src/lcd/tft_io/tft_ids.h b/Marlin/src/lcd/tft_io/tft_ids.h new file mode 100644 index 000000000000..c4f6127c685a --- /dev/null +++ b/Marlin/src/lcd/tft_io/tft_ids.h @@ -0,0 +1,35 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#define LTDC_RGB 0xABAB +#define SSD1963 0x5761 +#define ST7735 0x89F0 +#define ST7789 0x8552 +#define ST7796 0x7796 +#define R61505 0x1505 +#define ILI9328 0x9328 +#define ILI9341 0x9341 +#define ILI9488 0x9488 +#define ILI9488_ID1 0x8066 // Some ILI9488 have 0x8066 in the 0x04 +#define LERDGE_ST7796 0xFFFE +#define AUTO 0xFFFF diff --git a/Marlin/src/lcd/tft_io/tft_io.cpp b/Marlin/src/lcd/tft_io/tft_io.cpp index cd535458a181..ded711b57768 100644 --- a/Marlin/src/lcd/tft_io/tft_io.cpp +++ b/Marlin/src/lcd/tft_io/tft_io.cpp @@ -20,18 +20,34 @@ * */ -#include "tft_io.h" +#include "../../inc/MarlinConfigPre.h" -#if HAS_SPI_TFT || HAS_FSMC_TFT +#if HAS_SPI_TFT || HAS_FSMC_TFT || HAS_LTDC_TFT + +#include "tft_io.h" +#include "tft_ids.h" + +#if TFT_DRIVER == ST7735 || TFT_DRIVER == AUTO + #include "st7735.h" +#endif +#if TFT_DRIVER == ST7789 || TFT_DRIVER == AUTO + #include "st7789v.h" +#endif +#if TFT_DRIVER == ST7796 || TFT_DRIVER == AUTO + #include "st7796s.h" +#endif +#if TFT_DRIVER == R61505 || TFT_DRIVER == AUTO + #include "r65105.h" +#endif +#if TFT_DRIVER == ILI9488 || TFT_DRIVER == ILI9488_ID1 || TFT_DRIVER == AUTO + #include "ili9488.h" +#endif +#if TFT_DRIVER == SSD1963 || TFT_DRIVER == AUTO + #include "ssd1963.h" +#endif -#include "st7735.h" -#include "st7789v.h" -#include "st7796s.h" -#include "r65105.h" -#include "ili9328.h" #include "ili9341.h" -#include "ili9488.h" -#include "ssd1963.h" +#include "ili9328.h" #define DEBUG_OUT ENABLED(DEBUG_GRAPHICAL_TFT) #include "../../core/debug_out.h" @@ -49,13 +65,13 @@ if (lcd_id != 0xFFFFFFFF) return; #if PIN_EXISTS(TFT_RESET) OUT_WRITE(TFT_RESET_PIN, HIGH); delay(10); - OUT_WRITE(TFT_RESET_PIN, LOW); + WRITE(TFT_RESET_PIN, LOW); delay(10); - OUT_WRITE(TFT_RESET_PIN, HIGH); + WRITE(TFT_RESET_PIN, HIGH); #endif #if PIN_EXISTS(TFT_BACKLIGHT) - OUT_WRITE(TFT_BACKLIGHT_PIN, DISABLED(DELAYED_BACKLIGHT_INIT)); + WRITE(TFT_BACKLIGHT_PIN, DISABLED(DELAYED_BACKLIGHT_INIT)); #endif // io.Init(); @@ -90,6 +106,8 @@ if (lcd_id != 0xFFFFFFFF) return; lcd_id = io.GetID() & 0xFFFF; switch (lcd_id) { + case LTDC_RGB: + break; case ST7796: // ST7796S 480x320 DEBUG_ECHO_MSG(" ST7796S"); write_esc_sequence(st7796s_init); @@ -131,7 +149,7 @@ if (lcd_id != 0xFFFFFFFF) return; #endif #if PIN_EXISTS(TFT_BACKLIGHT) && ENABLED(DELAYED_BACKLIGHT_INIT) - OUT_WRITE(TFT_BACKLIGHT_PIN, HIGH); + WRITE(TFT_BACKLIGHT_PIN, HIGH); #endif } @@ -144,6 +162,17 @@ void TFT_IO::set_window(uint16_t Xmin, uint16_t Ymin, uint16_t Xmax, uint16_t Ym #endif switch (lcd_id) { + case LTDC_RGB: + io.WriteReg(0x01); + io.WriteData(Xmin); + io.WriteReg(0x02); + io.WriteData(Xmax); + io.WriteReg(0x03); + io.WriteData(Ymin); + io.WriteReg(0x04); + io.WriteData(Ymax); + io.WriteReg(0x00); + break; case ST7735: // ST7735 160x128 case ST7789: // ST7789V 320x240 case ST7796: // ST7796 480x320 @@ -223,4 +252,4 @@ void TFT_IO::write_esc_sequence(const uint16_t *Sequence) { io.DataTransferEnd(); } -#endif // HAS_SPI_TFT || HAS_FSMC_TFT +#endif // HAS_SPI_TFT || HAS_FSMC_TFT || HAS_LTDC_TFT diff --git a/Marlin/src/lcd/tft_io/tft_io.h b/Marlin/src/lcd/tft_io/tft_io.h index 63d6936ac0b8..0e4322f0d71b 100644 --- a/Marlin/src/lcd/tft_io/tft_io.h +++ b/Marlin/src/lcd/tft_io/tft_io.h @@ -23,19 +23,19 @@ #include "../../inc/MarlinConfig.h" -#if HAS_SPI_TFT || HAS_FSMC_TFT - #if HAS_SPI_TFT #include HAL_PATH(../../HAL, tft/tft_spi.h) #elif HAS_FSMC_TFT #include HAL_PATH(../../HAL, tft/tft_fsmc.h) +#elif HAS_LTDC_TFT + #include HAL_PATH(../../HAL, tft/tft_ltdc.h) #else - #error "TFT IO only supports SPI or FSMC interface" + #error "TFT IO only supports SPI, FSMC or LTDC interface" #endif -#define TFT_EXCHANGE_XY (1UL << 1) -#define TFT_INVERT_X (1UL << 2) -#define TFT_INVERT_Y (1UL << 3) +#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) @@ -63,34 +63,42 @@ // 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 (1UL << 3) -#define TFT_COLOR_BGR (1UL << 4) +#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 SSD1963 0x5761 -#define ST7735 0x89F0 -#define ST7789 0x8552 -#define ST7796 0x7796 -#define R61505 0x1505 -#define ILI9328 0x9328 -#define ILI9341 0x9341 -#define ILI9488 0x9488 -#define ILI9488_ID1 0x8066 //Some ILI9488 have 0x8066 in the 0x04 -#define LERDGE_ST7796 0xFFFE -#define AUTO 0xFFFF +#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 #endif -#define ESC_REG(x) 0xFFFF, 0x00FF & (uint16_t)x -#define ESC_DELAY(x) 0xFFFF, 0x8000 | (x & 0x7FFF) -#define ESC_END 0xFFFF, 0x7FFF -#define ESC_FFFF 0xFFFF, 0xFFFF +#define ESC_REG(x) 0xFFFF, 0x00FF & (uint16_t)x +#define ESC_DELAY(x) 0xFFFF, 0x8000 | (x & 0x7FFF) +#define ESC_END 0xFFFF, 0x7FFF +#define ESC_FFFF 0xFFFF, 0xFFFF class TFT_IO { public: @@ -101,7 +109,7 @@ class TFT_IO { static void write_esc_sequence(const uint16_t *Sequence); // Deletaged methods - inline static void Init() { io.Init(); }; + inline static void Init() { io.Init(); io.Abort(); }; inline static bool isBusy() { return io.isBusy(); }; inline static void Abort() { io.Abort(); }; inline static uint32_t GetID() { return io.GetID(); }; @@ -120,5 +128,3 @@ class TFT_IO { protected: static uint32_t lcd_id; }; - -#endif // HAS_SPI_TFT || HAS_FSMC_TFT diff --git a/Marlin/src/lcd/tft_io/touch_calibration.cpp b/Marlin/src/lcd/tft_io/touch_calibration.cpp new file mode 100644 index 000000000000..2a54d2af4005 --- /dev/null +++ b/Marlin/src/lcd/tft_io/touch_calibration.cpp @@ -0,0 +1,112 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(TOUCH_SCREEN_CALIBRATION) + +#include "touch_calibration.h" + +#define TOUCH_CALIBRATION_MAX_RETRIES 5 + +#define DEBUG_OUT ENABLED(DEBUG_TOUCH_CALIBRATION) +#include "../../core/debug_out.h" + +#if ENABLED(TOUCH_CALIBRATION_AUTO_SAVE) + #include "../../module/settings.h" +#endif + +TouchCalibration touch_calibration; + +touch_calibration_t TouchCalibration::calibration; +calibrationState TouchCalibration::calibration_state = CALIBRATION_NONE; +touch_calibration_point_t TouchCalibration::calibration_points[4]; +uint8_t TouchCalibration::failed_count; + +void TouchCalibration::validate_calibration() { + #define VALIDATE_PRECISION(XY, A, B) validate_precision_##XY(CALIBRATION_##A, CALIBRATION_##B) + const bool landscape = VALIDATE_PRECISION(x, TOP_LEFT, BOTTOM_LEFT) + && VALIDATE_PRECISION(x, TOP_RIGHT, BOTTOM_RIGHT) + && VALIDATE_PRECISION(y, TOP_LEFT, TOP_RIGHT) + && VALIDATE_PRECISION(y, BOTTOM_LEFT, BOTTOM_RIGHT); + const bool portrait = VALIDATE_PRECISION(y, TOP_LEFT, BOTTOM_LEFT) + && VALIDATE_PRECISION(y, TOP_RIGHT, BOTTOM_RIGHT) + && VALIDATE_PRECISION(x, TOP_LEFT, TOP_RIGHT) + && VALIDATE_PRECISION(x, BOTTOM_LEFT, BOTTOM_RIGHT); + #undef VALIDATE_PRECISION + + #define CAL_PTS(N) calibration_points[CALIBRATION_##N] + if (landscape) { + calibration_state = CALIBRATION_SUCCESS; + calibration.x = ((CAL_PTS(TOP_RIGHT).x - CAL_PTS(TOP_LEFT).x) << 17) / (CAL_PTS(BOTTOM_RIGHT).raw_x + CAL_PTS(TOP_RIGHT).raw_x - CAL_PTS(BOTTOM_LEFT).raw_x - CAL_PTS(TOP_LEFT).raw_x); + calibration.y = ((CAL_PTS(BOTTOM_LEFT).y - CAL_PTS(TOP_LEFT).y) << 17) / (CAL_PTS(BOTTOM_RIGHT).raw_y - CAL_PTS(TOP_RIGHT).raw_y + CAL_PTS(BOTTOM_LEFT).raw_y - CAL_PTS(TOP_LEFT).raw_y); + calibration.offset_x = CAL_PTS(TOP_LEFT).x - int16_t(((CAL_PTS(TOP_LEFT).raw_x + CAL_PTS(BOTTOM_LEFT).raw_x) * calibration.x) >> 17); + calibration.offset_y = CAL_PTS(TOP_LEFT).y - int16_t(((CAL_PTS(TOP_LEFT).raw_y + CAL_PTS(TOP_RIGHT).raw_y) * calibration.y) >> 17); + calibration.orientation = TOUCH_LANDSCAPE; + } + else if (portrait) { + calibration_state = CALIBRATION_SUCCESS; + calibration.x = ((CAL_PTS(TOP_RIGHT).x - CAL_PTS(TOP_LEFT).x) << 17) / (CAL_PTS(BOTTOM_RIGHT).raw_y + CAL_PTS(TOP_RIGHT).raw_y - CAL_PTS(BOTTOM_LEFT).raw_y - CAL_PTS(TOP_LEFT).raw_y); + calibration.y = ((CAL_PTS(BOTTOM_LEFT).y - CAL_PTS(TOP_LEFT).y) << 17) / (CAL_PTS(BOTTOM_RIGHT).raw_x - CAL_PTS(TOP_RIGHT).raw_x + CAL_PTS(BOTTOM_LEFT).raw_x - CAL_PTS(TOP_LEFT).raw_x); + calibration.offset_x = CAL_PTS(TOP_LEFT).x - int16_t(((CAL_PTS(TOP_LEFT).raw_y + CAL_PTS(BOTTOM_LEFT).raw_y) * calibration.x) >> 17); + calibration.offset_y = CAL_PTS(TOP_LEFT).y - int16_t(((CAL_PTS(TOP_LEFT).raw_x + CAL_PTS(TOP_RIGHT).raw_x) * calibration.y) >> 17); + calibration.orientation = TOUCH_PORTRAIT; + } + else { + calibration_state = CALIBRATION_FAIL; + calibration_reset(); + if (need_calibration() && failed_count++ < TOUCH_CALIBRATION_MAX_RETRIES) calibration_state = CALIBRATION_TOP_LEFT; + } + #undef CAL_PTS + + if (calibration_state == CALIBRATION_SUCCESS) { + SERIAL_ECHOLNPGM("Touch screen calibration completed"); + SERIAL_ECHOLNPAIR("TOUCH_CALIBRATION_X ", calibration.x); + SERIAL_ECHOLNPAIR("TOUCH_CALIBRATION_Y ", calibration.y); + SERIAL_ECHOLNPAIR("TOUCH_OFFSET_X ", calibration.offset_x); + SERIAL_ECHOLNPAIR("TOUCH_OFFSET_Y ", calibration.offset_y); + SERIAL_ECHO_TERNARY(calibration.orientation == TOUCH_LANDSCAPE, "TOUCH_ORIENTATION ", "TOUCH_LANDSCAPE", "TOUCH_PORTRAIT", "\n"); + TERN_(TOUCH_CALIBRATION_AUTO_SAVE, settings.save()); + } +} + +bool TouchCalibration::handleTouch(uint16_t x, uint16_t y) { + static millis_t next_button_update_ms = 0; + const millis_t now = millis(); + if (PENDING(now, next_button_update_ms)) return false; + next_button_update_ms = now + BUTTON_DELAY_MENU; + + if (calibration_state < CALIBRATION_SUCCESS) { + calibration_points[calibration_state].raw_x = x; + calibration_points[calibration_state].raw_y = y; + DEBUG_ECHOLNPAIR("TouchCalibration - State: ", calibration_state, ", x: ", calibration_points[calibration_state].x, ", raw_x: ", x, ", y: ", calibration_points[calibration_state].y, ", raw_y: ", y); + } + + switch (calibration_state) { + case CALIBRATION_TOP_LEFT: calibration_state = CALIBRATION_BOTTOM_LEFT; break; + case CALIBRATION_BOTTOM_LEFT: calibration_state = CALIBRATION_TOP_RIGHT; break; + case CALIBRATION_TOP_RIGHT: calibration_state = CALIBRATION_BOTTOM_RIGHT; break; + case CALIBRATION_BOTTOM_RIGHT: validate_calibration(); break; + default: break; + } + + return true; +} + +#endif // TOUCH_SCREEN_CALIBRATION diff --git a/Marlin/src/lcd/tft_io/touch_calibration.h b/Marlin/src/lcd/tft_io/touch_calibration.h new file mode 100644 index 000000000000..112fbdca301e --- /dev/null +++ b/Marlin/src/lcd/tft_io/touch_calibration.h @@ -0,0 +1,92 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include "../../inc/MarlinConfigPre.h" +#include "tft_io.h" + +#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 + +typedef struct __attribute__((__packed__)) { + int32_t x, y; + int16_t offset_x, offset_y; + uint8_t orientation; +} touch_calibration_t; + +typedef struct __attribute__((__packed__)) { + uint16_t x, y; + int16_t raw_x, raw_y; +} touch_calibration_point_t; + +enum calibrationState : uint8_t { + CALIBRATION_TOP_LEFT = 0x00, + CALIBRATION_BOTTOM_LEFT, + CALIBRATION_TOP_RIGHT, + CALIBRATION_BOTTOM_RIGHT, + CALIBRATION_SUCCESS, + CALIBRATION_FAIL, + CALIBRATION_NONE, +}; + +class TouchCalibration { +public: + static calibrationState calibration_state; + static touch_calibration_point_t calibration_points[4]; + + static bool validate_precision(int32_t a, int32_t b) { return (a > b ? (100 * b) / a : (100 * a) / b) > TOUCH_SCREEN_CALIBRATION_PRECISION; } + static bool validate_precision_x(uint8_t a, uint8_t b) { return validate_precision(calibration_points[a].raw_x, calibration_points[b].raw_x); } + static bool validate_precision_y(uint8_t a, uint8_t b) { return validate_precision(calibration_points[a].raw_y, calibration_points[b].raw_y); } + static void validate_calibration(); + + static touch_calibration_t calibration; + static uint8_t failed_count; + static void calibration_reset() { calibration = { TOUCH_CALIBRATION_X, TOUCH_CALIBRATION_Y, TOUCH_OFFSET_X, TOUCH_OFFSET_Y, TOUCH_ORIENTATION }; } + static bool need_calibration() { return !calibration.offset_x && !calibration.offset_y && !calibration.x && !calibration.y; } + + static calibrationState calibration_start() { + calibration = { 0, 0, 0, 0, TOUCH_ORIENTATION_NONE }; + calibration_state = CALIBRATION_TOP_LEFT; + calibration_points[CALIBRATION_TOP_LEFT].x = 30; + calibration_points[CALIBRATION_TOP_LEFT].y = 30; + calibration_points[CALIBRATION_BOTTOM_LEFT].x = 30; + calibration_points[CALIBRATION_BOTTOM_LEFT].y = TFT_HEIGHT - 31; + calibration_points[CALIBRATION_TOP_RIGHT].x = TFT_WIDTH - 31; + calibration_points[CALIBRATION_TOP_RIGHT].y = 30; + calibration_points[CALIBRATION_BOTTOM_RIGHT].x = TFT_WIDTH - 31; + calibration_points[CALIBRATION_BOTTOM_RIGHT].y = TFT_HEIGHT - 31; + failed_count = 0; + return calibration_state; + } + static void calibration_end() { calibration_state = CALIBRATION_NONE; } + static calibrationState get_calibration_state() { return calibration_state; } + static bool calibration_loaded() { + if (need_calibration()) calibration_reset(); + return !need_calibration(); + } + + static bool handleTouch(uint16_t x, uint16_t y); +}; + +extern TouchCalibration touch_calibration; diff --git a/Marlin/src/lcd/thermistornames.h b/Marlin/src/lcd/thermistornames.h index 37f285d483cd..f9f91ac49a5c 100644 --- a/Marlin/src/lcd/thermistornames.h +++ b/Marlin/src/lcd/thermistornames.h @@ -68,6 +68,8 @@ #define THERMISTOR_NAME "Zonestar (Tronxy X3A)" #elif THERMISTOR_ID == 502 #define THERMISTOR_NAME "Zonestar (P802M Hot Bed)" +#elif THERMISTOR_ID == 503 + #define THERMISTOR_NAME "Zonestar (Z8XM2 Bed)" #elif THERMISTOR_ID == 512 #define THERMISTOR_NAME "RPW-Ultra" #elif THERMISTOR_ID == 6 diff --git a/Marlin/src/lcd/touch/touch_buttons.cpp b/Marlin/src/lcd/touch/touch_buttons.cpp index 7d25c0df7eb9..c9476bd2bb0e 100644 --- a/Marlin/src/lcd/touch/touch_buttons.cpp +++ b/Marlin/src/lcd/touch/touch_buttons.cpp @@ -19,55 +19,36 @@ #include "../../inc/MarlinConfig.h" -#if HAS_TOUCH_XPT2046 +#if HAS_TOUCH_BUTTONS #include "touch_buttons.h" #include "../scaled_tft.h" -#include HAL_PATH(../../HAL, tft/xpt2046.h) -XPT2046 touchIO; +#if ENABLED(TFT_TOUCH_DEVICE_GT911) + #include HAL_PATH(../../HAL, tft/gt911.h) + GT911 touchIO; +#elif ENABLED(TFT_TOUCH_DEVICE_XPT2046) + #include HAL_PATH(../../HAL, tft/xpt2046.h) + XPT2046 touchIO; +#else + #error "Unknown Touch Screen Type." +#endif -#include "../../lcd/ultralcd.h" // For EN_C bit mask +#if ENABLED(TOUCH_SCREEN_CALIBRATION) + #include "../tft_io/touch_calibration.h" +#endif -/** - * Draw and Touch processing - * - * LCD_PIXEL_WIDTH/HEIGHT (128x64) is the (emulated DOGM) Pixel Drawing resolution. - * TOUCH_SENSOR_WIDTH/HEIGHT (320x240) is the Touch Area resolution. - * TFT_WIDTH/HEIGHT (320x240 or 480x320) is the Actual (FSMC) Display resolution. - * - * - All native (u8g) drawing is done in LCD_PIXEL_* (128x64) - * - The DOGM pixels are is upscaled 2-3x (as needed) for display. - * - Touch coordinates use TOUCH_SENSOR_* resolution and are converted to - * click and scroll-wheel events (emulating of a common DOGM display). - * - * TOUCH_SCREEN resolution exists to fit our calibration values. The original touch code was made - * and originally calibrated for 320x240. If you decide to change the resolution of the touch code, - * new calibration values will be needed. - * - * The Marlin menus are drawn scaled in the upper region of the screen. The bottom region (in a - * fixed location in TOUCH_SCREEN* coordinate space) is used for 4 general-purpose buttons to - * navigate and select menu items. Both regions are touchable. - * - * The Marlin screen touchable area starts at TFT_PIXEL_OFFSET_X/Y (translated to SCREEN_PCT_LEFT/TOP) - * and spans LCD_PIXEL_WIDTH/HEIGHT (scaled to SCREEN_PCT_WIDTH/HEIGHT). - */ - -// Touch sensor resolution independent of display resolution -#define TOUCH_SENSOR_WIDTH 320 -#define TOUCH_SENSOR_HEIGHT 240 - -#define SCREEN_PCT_WIDE(X) ((X) * (TOUCH_SENSOR_WIDTH) / (TFT_WIDTH)) -#define SCREEN_PCT_HIGH(Y) ((Y) * (TOUCH_SENSOR_HEIGHT) / (TFT_HEIGHT)) +#include "../buttons.h" // For EN_C bit mask +#include "../marlinui.h" // For ui.refresh +#include "../tft_io/tft_io.h" -#define SCREEN_PCT_LEFT SCREEN_PCT_WIDE(TFT_PIXEL_OFFSET_X) -#define SCREEN_PCT_TOP SCREEN_PCT_HIGH(TFT_PIXEL_OFFSET_Y) -#define SCREEN_PCT_WIDTH SCREEN_PCT_WIDE((GRAPHICAL_TFT_UPSCALE) * (LCD_PIXEL_WIDTH)) -#define SCREEN_PCT_HEIGHT SCREEN_PCT_HIGH((GRAPHICAL_TFT_UPSCALE) * (LCD_PIXEL_HEIGHT)) +#define DOGM_AREA_LEFT TFT_PIXEL_OFFSET_X +#define DOGM_AREA_TOP TFT_PIXEL_OFFSET_Y +#define DOGM_AREA_WIDTH (GRAPHICAL_TFT_UPSCALE) * (LCD_PIXEL_WIDTH) +#define DOGM_AREA_HEIGHT (GRAPHICAL_TFT_UPSCALE) * (LCD_PIXEL_HEIGHT) -// Coordinates in terms of 240-unit-tall touch area -#define BUTTON_AREA_TOP 175 -#define BUTTON_AREA_BOT 234 +#define BUTTON_AREA_TOP BUTTON_Y_LO +#define BUTTON_AREA_BOT BUTTON_Y_HI TouchButtons touch; @@ -77,31 +58,37 @@ uint8_t TouchButtons::read_buttons() { #ifdef HAS_WIRED_LCD int16_t x, y; - if (!touchIO.getRawPoint(&x, &y)) return 0; - - x = uint16_t((uint32_t(x) * XPT2046_X_CALIBRATION) >> 16) + XPT2046_X_OFFSET; - y = uint16_t((uint32_t(y) * XPT2046_Y_CALIBRATION) >> 16) + XPT2046_Y_OFFSET; - - #if (TFT_ROTATION & TFT_ROTATE_180) - x = TOUCH_SENSOR_WIDTH - x; - y = TOUCH_SENSOR_HEIGHT - y; + const bool is_touched = (TERN(TOUCH_SCREEN_CALIBRATION, touch_calibration.calibration.orientation, TOUCH_ORIENTATION) == TOUCH_PORTRAIT ? touchIO.getRawPoint(&y, &x) : touchIO.getRawPoint(&x, &y)); + if (!is_touched) return 0; + + #if ENABLED(TOUCH_SCREEN_CALIBRATION) + const calibrationState state = touch_calibration.get_calibration_state(); + if (state >= CALIBRATION_TOP_LEFT && state <= CALIBRATION_BOTTOM_RIGHT) { + if (touch_calibration.handleTouch(x, y)) ui.refresh(); + return 0; + } + x = int16_t((int32_t(x) * touch_calibration.calibration.x) >> 16) + touch_calibration.calibration.offset_x; + y = int16_t((int32_t(y) * touch_calibration.calibration.y) >> 16) + touch_calibration.calibration.offset_y; + #else + x = uint16_t((uint32_t(x) * TOUCH_CALIBRATION_X) >> 16) + TOUCH_OFFSET_X; + y = uint16_t((uint32_t(y) * TOUCH_CALIBRATION_Y) >> 16) + TOUCH_OFFSET_Y; #endif // Touch within the button area simulates an encoder button if (y > BUTTON_AREA_TOP && y < BUTTON_AREA_BOT) - return WITHIN(x, 14, 77) ? EN_D - : WITHIN(x, 90, 153) ? EN_A - : WITHIN(x, 166, 229) ? EN_B - : WITHIN(x, 242, 305) ? EN_C + return WITHIN(x, BUTTOND_X_LO, BUTTOND_X_HI) ? EN_D + : WITHIN(x, BUTTONA_X_LO, BUTTONA_X_HI) ? EN_A + : WITHIN(x, BUTTONB_X_LO, BUTTONB_X_HI) ? EN_B + : WITHIN(x, BUTTONC_X_LO, BUTTONC_X_HI) ? EN_C : 0; - if ( !WITHIN(x, SCREEN_PCT_LEFT, SCREEN_PCT_LEFT + SCREEN_PCT_WIDTH) - || !WITHIN(y, SCREEN_PCT_TOP, SCREEN_PCT_TOP + SCREEN_PCT_HEIGHT) + if ( !WITHIN(x, DOGM_AREA_LEFT, DOGM_AREA_LEFT + DOGM_AREA_WIDTH) + || !WITHIN(y, DOGM_AREA_TOP, DOGM_AREA_TOP + DOGM_AREA_HEIGHT) ) return 0; // Column and row above BUTTON_AREA_TOP - int8_t col = (x - (SCREEN_PCT_LEFT)) * (LCD_WIDTH) / (SCREEN_PCT_WIDTH), - row = (y - (SCREEN_PCT_TOP)) * (LCD_HEIGHT) / (SCREEN_PCT_HEIGHT); + int8_t col = (x - (DOGM_AREA_LEFT)) * (LCD_WIDTH) / (DOGM_AREA_WIDTH), + row = (y - (DOGM_AREA_TOP)) * (LCD_HEIGHT) / (DOGM_AREA_HEIGHT); // Send the touch to the UI (which will simulate the encoder wheel) MarlinUI::screen_click(row, col, x, y); @@ -109,4 +96,4 @@ uint8_t TouchButtons::read_buttons() { return 0; } -#endif // HAS_TOUCH_XPT2046 +#endif // HAS_TOUCH_BUTTONS diff --git a/Marlin/src/lcd/touch/touch_buttons.h b/Marlin/src/lcd/touch/touch_buttons.h index 451e5a5a37ca..a79bb15be427 100644 --- a/Marlin/src/lcd/touch/touch_buttons.h +++ b/Marlin/src/lcd/touch/touch_buttons.h @@ -20,6 +20,36 @@ #include +#include "../../inc/MarlinConfig.h" +#include "../scaled_tft.h" + +#define UPSCALE0(M) ((M) * (GRAPHICAL_TFT_UPSCALE)) +#define UPSCALE(A,M) (UPSCALE0(M) + (A)) + +#define BUTTON_DRAW_WIDTH 32 +#define BUTTON_DRAW_HEIGHT 20 + +#define BUTTON_WIDTH UPSCALE0(BUTTON_DRAW_WIDTH) +#define BUTTON_HEIGHT UPSCALE0(BUTTON_DRAW_HEIGHT) + +// calc the space between buttons +#define BUTTON_SPACING (((TFT_WIDTH) - (BUTTON_WIDTH * 4)) / 5) + +#define BUTTOND_X_LO BUTTON_SPACING +#define BUTTOND_X_HI BUTTOND_X_LO + BUTTON_WIDTH - 1 + +#define BUTTONA_X_LO BUTTOND_X_HI + BUTTON_SPACING +#define BUTTONA_X_HI BUTTONA_X_LO + BUTTON_WIDTH - 1 + +#define BUTTONB_X_LO BUTTONA_X_HI + BUTTON_SPACING +#define BUTTONB_X_HI BUTTONB_X_LO + BUTTON_WIDTH - 1 + +#define BUTTONC_X_LO BUTTONB_X_HI + BUTTON_SPACING +#define BUTTONC_X_HI BUTTONC_X_LO + BUTTON_WIDTH - 1 + +#define BUTTON_Y_HI (TFT_HEIGHT) - BUTTON_SPACING +#define BUTTON_Y_LO BUTTON_Y_HI - BUTTON_HEIGHT + class TouchButtons { public: static void init(); diff --git a/Marlin/src/lcd/ultralcd.cpp b/Marlin/src/lcd/ultralcd.cpp deleted file mode 100644 index 7003d13fdd7a..000000000000 --- a/Marlin/src/lcd/ultralcd.cpp +++ /dev/null @@ -1,1692 +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 . - * - */ - -#include "../inc/MarlinConfig.h" - -#ifdef LED_BACKLIGHT_TIMEOUT - #include "../feature/leds/leds.h" -#endif - -#if ENABLED(HOST_ACTION_COMMANDS) - #include "../feature/host_actions.h" -#endif - -// All displays share the MarlinUI class -#include "ultralcd.h" -MarlinUI ui; - -#if HAS_DISPLAY - #include "../module/printcounter.h" - #include "../MarlinCore.h" - #include "../gcode/queue.h" - #include "fontutils.h" - #include "../sd/cardreader.h" - #if EITHER(EXTENSIBLE_UI, DWIN_CREALITY_LCD) - #define START_OF_UTF8_CHAR(C) (((C) & 0xC0u) != 0x80U) - #endif -#endif - -#if LCD_HAS_WAIT_FOR_MOVE - bool MarlinUI::wait_for_move; // = false -#endif - -constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; - -#if HAS_WIRED_LCD - #if ENABLED(STATUS_MESSAGE_SCROLLING) - uint8_t MarlinUI::status_scroll_offset; // = 0 - constexpr uint8_t MAX_MESSAGE_LENGTH = _MAX(LONG_FILENAME_LENGTH, MAX_LANG_CHARSIZE * 2 * (LCD_WIDTH)); - #else - constexpr uint8_t MAX_MESSAGE_LENGTH = MAX_LANG_CHARSIZE * (LCD_WIDTH); - #endif -#elif EITHER(EXTENSIBLE_UI, DWIN_CREALITY_LCD) - constexpr uint8_t MAX_MESSAGE_LENGTH = 63; -#endif - -#if EITHER(HAS_WIRED_LCD, EXTENSIBLE_UI) - uint8_t MarlinUI::alert_level; // = 0 - char MarlinUI::status_message[MAX_MESSAGE_LENGTH + 1]; -#endif - -#if ENABLED(LCD_SET_PROGRESS_MANUALLY) - MarlinUI::progress_t MarlinUI::progress_override; // = 0 - #if BOTH(LCD_SET_PROGRESS_MANUALLY, USE_M73_REMAINING_TIME) - uint32_t MarlinUI::remaining_time; - #endif -#endif - -#if EITHER(PCA9632_BUZZER, USE_BEEPER) - #include "../libs/buzzer.h" // for BUZZ() macro - #if ENABLED(PCA9632_BUZZER) - #include "../feature/leds/pca9632.h" - #endif - void MarlinUI::buzz(const long duration, const uint16_t freq) { - #if ENABLED(PCA9632_BUZZER) - PCA9632_buzz(duration, freq); - #elif USE_BEEPER - buzzer.tone(duration, freq); - #endif - } -#endif - -#if PREHEAT_COUNT - preheat_t MarlinUI::material_preset[PREHEAT_COUNT]; // Initialized by settings.load() - PGM_P MarlinUI::get_preheat_label(const uint8_t m) { - #ifdef PREHEAT_1_LABEL - static PGMSTR(preheat_0_label, PREHEAT_1_LABEL); - #endif - #ifdef PREHEAT_2_LABEL - static PGMSTR(preheat_1_label, PREHEAT_2_LABEL); - #endif - #ifdef PREHEAT_3_LABEL - static PGMSTR(preheat_2_label, PREHEAT_3_LABEL); - #endif - #ifdef PREHEAT_4_LABEL - static PGMSTR(preheat_3_label, PREHEAT_4_LABEL); - #endif - #ifdef PREHEAT_5_LABEL - static PGMSTR(preheat_4_label, PREHEAT_5_LABEL); - #endif - - #define _PLBL(N) preheat_##N##_label, - static PGM_P const preheat_labels[PREHEAT_COUNT] PROGMEM = { REPEAT(PREHEAT_COUNT, _PLBL) }; - - return (PGM_P)pgm_read_ptr(&preheat_labels[m]); - } -#endif - -#if HAS_WIRED_LCD - -#if HAS_MARLINUI_U8GLIB - #include "dogm/ultralcd_DOGM.h" -#endif - -#include "lcdprint.h" - -#include "../sd/cardreader.h" - -#include "../module/temperature.h" -#include "../module/planner.h" -#include "../module/motion.h" - -#if HAS_LCD_MENU - #include "../module/settings.h" -#endif - -#if ENABLED(AUTO_BED_LEVELING_UBL) - #include "../feature/bedlevel/bedlevel.h" -#endif - -#if HAS_TRINAMIC_CONFIG - #include "../feature/tmc_util.h" -#endif - -#if HAS_ADC_BUTTONS - #include "../module/thermistor/thermistors.h" -#endif - -#if HAS_POWER_MONITOR - #include "../feature/power_monitor.h" -#endif - -#if HAS_ENCODER_ACTION - volatile uint8_t MarlinUI::buttons; - #if HAS_SLOW_BUTTONS - volatile uint8_t MarlinUI::slow_buttons; - #endif - #if HAS_TOUCH_XPT2046 - #include "touch/touch_buttons.h" - bool MarlinUI::on_edit_screen = false; - #endif -#endif - -#if HAS_LCD_MENU && LCD_TIMEOUT_TO_STATUS > 0 - bool MarlinUI::defer_return_to_status; -#endif - -uint8_t MarlinUI::lcd_status_update_delay = 1; // First update one loop delayed - -#if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) - millis_t MarlinUI::next_filament_display; // = 0 -#endif - -millis_t MarlinUI::next_button_update_ms; // = 0 - -#if HAS_MARLINUI_U8GLIB - bool MarlinUI::drawing_screen, MarlinUI::first_page; // = false -#endif - -// Encoder Handling -#if HAS_ENCODER_ACTION - uint32_t MarlinUI::encoderPosition; - volatile int8_t encoderDiff; // Updated in update_buttons, added to encoderPosition every LCD update -#endif - -#if ENABLED(SDSUPPORT) - - #include "../sd/cardreader.h" - - #if MARLINUI_SCROLL_NAME - uint8_t MarlinUI::filename_scroll_pos, MarlinUI::filename_scroll_max; - #endif - - const char * MarlinUI::scrolled_filename(CardReader &theCard, const uint8_t maxlen, uint8_t hash, const bool doScroll) { - const char *outstr = theCard.longest_filename(); - if (theCard.longFilename[0]) { - #if MARLINUI_SCROLL_NAME - if (doScroll) { - for (uint8_t l = FILENAME_LENGTH; l--;) - hash = ((hash << 1) | (hash >> 7)) ^ theCard.filename[l]; // rotate, xor - static uint8_t filename_scroll_hash; - if (filename_scroll_hash != hash) { // If the hash changed... - filename_scroll_hash = hash; // Save the new hash - filename_scroll_max = _MAX(0, utf8_strlen(theCard.longFilename) - maxlen); // Update the scroll limit - filename_scroll_pos = 0; // Reset scroll to the start - lcd_status_update_delay = 8; // Don't scroll right away - } - outstr += filename_scroll_pos; - } - #else - theCard.longFilename[maxlen] = '\0'; // cutoff at screen edge - #endif - } - return outstr; - } - -#endif - -#if HAS_LCD_MENU - #include "menu/menu.h" - - screenFunc_t MarlinUI::currentScreen; // Initialized in CTOR - bool MarlinUI::screen_changed; - - #if ENABLED(ENCODER_RATE_MULTIPLIER) - bool MarlinUI::encoderRateMultiplierEnabled; - millis_t MarlinUI::lastEncoderMovementMillis = 0; - void MarlinUI::enable_encoder_multiplier(const bool onoff) { - encoderRateMultiplierEnabled = onoff; - lastEncoderMovementMillis = 0; - } - #endif - - #if EITHER(REVERSE_MENU_DIRECTION, REVERSE_SELECT_DIRECTION) - int8_t MarlinUI::encoderDirection = ENCODERBASE; - #endif - - #if HAS_TOUCH_XPT2046 - uint8_t MarlinUI::touch_buttons; - uint8_t MarlinUI::repeat_delay; - #endif - - bool MarlinUI::lcd_clicked; - - bool MarlinUI::use_click() { - const bool click = lcd_clicked; - lcd_clicked = false; - return click; - } - - #if EITHER(AUTO_BED_LEVELING_UBL, G26_MESH_VALIDATION) - - bool MarlinUI::external_control; // = false - - void MarlinUI::wait_for_release() { - while (button_pressed()) safe_delay(50); - safe_delay(50); - } - - #endif - - void _wrap_string(uint8_t &col, uint8_t &row, const char * const string, read_byte_cb_t cb_read_byte, bool wordwrap/*=false*/) { - SETCURSOR(col, row); - if (!string) return; - - auto _newline = [&col, &row]{ - col = 0; row++; // Move col to string len (plus space) - SETCURSOR(0, row); // Simulate carriage return - }; - - uint8_t *p = (uint8_t*)string; - wchar_t ch; - if (wordwrap) { - uint8_t *wrd = nullptr, c = 0; - // find the end of the part - for (;;) { - if (!wrd) wrd = p; // Get word start /before/ advancing - p = get_utf8_value_cb(p, cb_read_byte, &ch); - const bool eol = !ch; // zero ends the string - // End or a break between phrases? - if (eol || ch == ' ' || ch == '-' || ch == '+' || ch == '.') { - if (!c && ch == ' ') { 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 - col += c; // advance col to new position - while (c) { // character countdown - --c; // count down to zero - wrd = get_utf8_value_cb(wrd, cb_read_byte, &ch); // get characters again - lcd_put_wchar(ch); // character to the LCD - } - if (eol) break; // all done! - wrd = nullptr; // set up for next word - } - else c++; // count word characters - } - } - else { - for (;;) { - p = get_utf8_value_cb(p, cb_read_byte, &ch); - if (!ch) break; - lcd_put_wchar(ch); - col++; - if (col >= LCD_WIDTH) _newline(); - } - } - } - - void MarlinUI::draw_select_screen_prompt(PGM_P const pref, const char * const string/*=nullptr*/, PGM_P const suff/*=nullptr*/) { - const uint8_t plen = utf8_strlen_P(pref), slen = suff ? utf8_strlen_P(suff) : 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; - } - wrap_string_P(col, row, pref, 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, suff); - } - -#endif // HAS_LCD_MENU - -void MarlinUI::init() { - - init_lcd(); - - #if HAS_DIGITAL_BUTTONS - - #if BUTTON_EXISTS(EN1) - SET_INPUT_PULLUP(BTN_EN1); - #endif - #if BUTTON_EXISTS(EN2) - SET_INPUT_PULLUP(BTN_EN2); - #endif - #if BUTTON_EXISTS(ENC) - SET_INPUT_PULLUP(BTN_ENC); - #endif - - #if BUTTON_EXISTS(BACK) - SET_INPUT_PULLUP(BTN_BACK); - #endif - - #if BUTTON_EXISTS(UP) - SET_INPUT(BTN_UP); - #endif - #if BUTTON_EXISTS(DWN) - SET_INPUT(BTN_DWN); - #endif - #if BUTTON_EXISTS(LFT) - SET_INPUT(BTN_LFT); - #endif - #if BUTTON_EXISTS(RT) - SET_INPUT(BTN_RT); - #endif - - #endif // !HAS_DIGITAL_BUTTONS - - #if HAS_SHIFT_ENCODER - - #if ENABLED(SR_LCD_2W_NL) // Non latching 2 wire shift register - - SET_OUTPUT(SR_DATA_PIN); - SET_OUTPUT(SR_CLK_PIN); - - #elif defined(SHIFT_CLK) - - SET_OUTPUT(SHIFT_CLK); - OUT_WRITE(SHIFT_LD, HIGH); - #if defined(SHIFT_EN) && SHIFT_EN >= 0 - OUT_WRITE(SHIFT_EN, LOW); - #endif - SET_INPUT_PULLUP(SHIFT_OUT); - - #endif - - #endif // HAS_SHIFT_ENCODER - - #if BOTH(HAS_ENCODER_ACTION, HAS_SLOW_BUTTONS) - slow_buttons = 0; - #endif - - update_buttons(); - - TERN_(HAS_ENCODER_ACTION, encoderDiff = 0); -} - -bool MarlinUI::get_blink() { - static uint8_t blink = 0; - static millis_t next_blink_ms = 0; - millis_t ms = millis(); - if (ELAPSED(ms, next_blink_ms)) { - blink ^= 0xFF; - next_blink_ms = ms + 1000 - (LCD_UPDATE_INTERVAL) / 2; - } - return blink != 0; -} - -//////////////////////////////////////////// -///////////// Keypad Handling ////////////// -//////////////////////////////////////////// - -#if BOTH(REPRAPWORLD_KEYPAD, HAS_ENCODER_ACTION) - - volatile uint8_t MarlinUI::keypad_buttons; - - #if HAS_LCD_MENU && !HAS_ADC_BUTTONS - - void lcd_move_x(); - void lcd_move_y(); - void lcd_move_z(); - - void _reprapworld_keypad_move(const AxisEnum axis, const int16_t dir) { - ui.manual_move.menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP; - ui.encoderPosition = dir; - switch (axis) { - case X_AXIS: lcd_move_x(); break; - case Y_AXIS: lcd_move_y(); break; - case Z_AXIS: lcd_move_z(); - default: break; - } - } - - #endif - - bool MarlinUI::handle_keypad() { - - #if HAS_ADC_BUTTONS - - #define ADC_MIN_KEY_DELAY 100 - if (keypad_buttons) { - #if HAS_ENCODER_ACTION - refresh(LCDVIEW_REDRAW_NOW); - #if HAS_LCD_MENU - if (encoderDirection == -(ENCODERBASE)) { // ADC_KEYPAD forces REVERSE_MENU_DIRECTION, so this indicates menu navigation - if (RRK(EN_KEYPAD_UP)) encoderPosition += ENCODER_STEPS_PER_MENU_ITEM; - else if (RRK(EN_KEYPAD_DOWN)) encoderPosition -= ENCODER_STEPS_PER_MENU_ITEM; - else if (RRK(EN_KEYPAD_LEFT)) { MenuItem_back::action(); quick_feedback(); } - else if (RRK(EN_KEYPAD_RIGHT)) { return_to_status(); quick_feedback(); } - } - else - #endif - { - #if HAS_LCD_MENU - if (RRK(EN_KEYPAD_UP)) encoderPosition -= epps; - else if (RRK(EN_KEYPAD_DOWN)) encoderPosition += epps; - else if (RRK(EN_KEYPAD_LEFT)) { MenuItem_back::action(); quick_feedback(); } - else if (RRK(EN_KEYPAD_RIGHT)) encoderPosition = 0; - #else - if (RRK(EN_KEYPAD_UP) || RRK(EN_KEYPAD_LEFT)) encoderPosition -= epps; - else if (RRK(EN_KEYPAD_DOWN) || RRK(EN_KEYPAD_RIGHT)) encoderPosition += epps; - #endif - } - #endif - next_button_update_ms = millis() + ADC_MIN_KEY_DELAY; - return true; - } - - #else // !HAS_ADC_BUTTONS - - static uint8_t keypad_debounce = 0; - - if (!RRK( EN_KEYPAD_F1 | EN_KEYPAD_F2 - | EN_KEYPAD_F3 | EN_KEYPAD_DOWN - | EN_KEYPAD_RIGHT | EN_KEYPAD_MIDDLE - | EN_KEYPAD_UP | EN_KEYPAD_LEFT ) - ) { - if (keypad_debounce > 0) keypad_debounce--; - } - else if (!keypad_debounce) { - keypad_debounce = 2; - - const bool homed = all_axes_homed(); - - #if HAS_LCD_MENU - - if (RRK(EN_KEYPAD_MIDDLE)) goto_screen(menu_move); - - #if DISABLED(DELTA) && Z_HOME_DIR < 0 - if (RRK(EN_KEYPAD_F2)) _reprapworld_keypad_move(Z_AXIS, 1); - #endif - - if (homed) { - #if ENABLED(DELTA) || Z_HOME_DIR != -1 - if (RRK(EN_KEYPAD_F2)) _reprapworld_keypad_move(Z_AXIS, 1); - #endif - if (RRK(EN_KEYPAD_F3)) _reprapworld_keypad_move(Z_AXIS, -1); - if (RRK(EN_KEYPAD_LEFT)) _reprapworld_keypad_move(X_AXIS, -1); - if (RRK(EN_KEYPAD_RIGHT)) _reprapworld_keypad_move(X_AXIS, 1); - if (RRK(EN_KEYPAD_DOWN)) _reprapworld_keypad_move(Y_AXIS, 1); - if (RRK(EN_KEYPAD_UP)) _reprapworld_keypad_move(Y_AXIS, -1); - } - - #endif // HAS_LCD_MENU - - if (!homed && RRK(EN_KEYPAD_F1)) queue.inject_P(G28_STR); - return true; - } - - #endif // !ADC_KEYPAD - - return false; - } - -#endif // REPRAPWORLD_KEYPAD - -/** - * Status Screen - * - * This is very display-dependent, so the lcd implementation draws this. - */ - -#if ENABLED(LCD_PROGRESS_BAR) && !IS_TFTGLCD_PANEL - millis_t MarlinUI::progress_bar_ms; // = 0 - #if PROGRESS_MSG_EXPIRE > 0 - millis_t MarlinUI::expire_status_ms; // = 0 - #endif -#endif - -void MarlinUI::status_screen() { - - TERN_(HAS_LCD_MENU, ENCODER_RATE_MULTIPLY(false)); - - #if ENABLED(LCD_PROGRESS_BAR) && !IS_TFTGLCD_PANEL - - // - // HD44780 implements the following message blinking and - // message expiration because Status Line and Progress Bar - // share the same line on the display. - // - - #if DISABLED(PROGRESS_MSG_ONCE) || (PROGRESS_MSG_EXPIRE > 0) - #define GOT_MS - const millis_t ms = millis(); - #endif - - // If the message will blink rather than expire... - #if DISABLED(PROGRESS_MSG_ONCE) - if (ELAPSED(ms, progress_bar_ms + PROGRESS_BAR_MSG_TIME + PROGRESS_BAR_BAR_TIME)) - progress_bar_ms = ms; - #endif - - #if PROGRESS_MSG_EXPIRE > 0 - - // Handle message expire - if (expire_status_ms) { - - // Expire the message if a job is active and the bar has ticks - if (get_progress_percent() > 2 && !print_job_timer.isPaused()) { - if (ELAPSED(ms, expire_status_ms)) { - status_message[0] = '\0'; - expire_status_ms = 0; - } - } - else { - // Defer message expiration before bar appears - // and during any pause (not just SD) - expire_status_ms += LCD_UPDATE_INTERVAL; - } - } - - #endif // PROGRESS_MSG_EXPIRE - - #endif // LCD_PROGRESS_BAR - - #if HAS_LCD_MENU - if (use_click()) { - #if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) - next_filament_display = millis() + 5000UL; // Show status message for 5s - #endif - goto_screen(menu_main); - #if DISABLED(NO_LCD_REINIT) - init_lcd(); // May revive the LCD if static electricity killed it - #endif - return; - } - - #endif - - #if ENABLED(ULTIPANEL_FEEDMULTIPLY) - - const int16_t old_frm = feedrate_percentage; - int16_t new_frm = old_frm + int16_t(encoderPosition); - - // Dead zone at 100% feedrate - if (old_frm == 100) { - if (int16_t(encoderPosition) > ENCODER_FEEDRATE_DEADZONE) - new_frm -= ENCODER_FEEDRATE_DEADZONE; - else if (int16_t(encoderPosition) < -(ENCODER_FEEDRATE_DEADZONE)) - new_frm += ENCODER_FEEDRATE_DEADZONE; - else - new_frm = old_frm; - } - else if ((old_frm < 100 && new_frm > 100) || (old_frm > 100 && new_frm < 100)) - new_frm = 100; - - LIMIT(new_frm, 10, 999); - - if (old_frm != new_frm) { - feedrate_percentage = new_frm; - encoderPosition = 0; - #if BOTH(HAS_BUZZER, BEEP_ON_FEEDRATE_CHANGE) - static millis_t next_beep; - #ifndef GOT_MS - const millis_t ms = millis(); - #endif - if (ELAPSED(ms, next_beep)) { - buzz(FEEDRATE_CHANGE_BEEP_DURATION, FEEDRATE_CHANGE_BEEP_FREQUENCY); - next_beep = ms + 500UL; - } - #endif - } - - #endif // ULTIPANEL_FEEDMULTIPLY - - draw_status_screen(); -} - -void MarlinUI::kill_screen(PGM_P lcd_error, PGM_P lcd_component) { - init(); - status_printf_P(1, PSTR(S_FMT ": " S_FMT), lcd_error, lcd_component); - TERN_(HAS_LCD_MENU, return_to_status()); - - // RED ALERT. RED ALERT. - #ifdef LED_BACKLIGHT_TIMEOUT - leds.set_color(LEDColorRed()); - #ifdef NEOPIXEL_BKGD_LED_INDEX - neo.set_pixel_color(NEOPIXEL_BKGD_LED_INDEX, 255, 0, 0, 0); - neo.show(); - #endif - #endif - - draw_kill_screen(); -} - -void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { - - TERN_(HAS_LCD_MENU, refresh()); - - #if HAS_ENCODER_ACTION - if (clear_buttons) buttons = 0; - next_button_update_ms = millis() + 500; - #else - UNUSED(clear_buttons); - #endif - - #if HAS_CHIRP - chirp(); // Buzz and wait. Is the delay needed for buttons to settle? - #if BOTH(HAS_LCD_MENU, USE_BEEPER) - for (int8_t i = 5; i--;) { buzzer.tick(); delay(2); } - #elif HAS_LCD_MENU - delay(10); - #endif - #endif -} - -//////////////////////////////////////////// -/////////////// Manual Move //////////////// -//////////////////////////////////////////// - -#if HAS_LCD_MENU - - ManualMove MarlinUI::manual_move{}; - - millis_t ManualMove::start_time = 0; - float ManualMove::menu_scale = 1; - TERN_(IS_KINEMATIC, float ManualMove::offset = 0); - TERN_(IS_KINEMATIC, bool ManualMove::processing = false); - TERN_(MULTI_MANUAL, int8_t ManualMove::e_index = 0); - uint8_t ManualMove::axis = (uint8_t)NO_AXIS; - - /** - * If a manual move has been posted and its time has arrived, and if the planner - * has a space for it, then add a linear move to current_position the planner. - * - * If any manual move needs to be interrupted, make sure to force a manual move - * by setting manual_move.start_time to millis() after updating current_position. - * - * To post a manual move: - * - Update current_position to the new place you want to go. - * - Set manual_move.axis to an axis like X_AXIS. Use ALL_AXES for diagonal moves. - * - Set manual_move.start_time to a point in the future (in ms) when the move should be done. - * - * For kinematic machines: - * - Set manual_move.offset to modify one axis and post the move. - * This is used to achieve more rapid stepping on kinematic machines. - * - * Currently used by the _lcd_move_xyz function in menu_motion.cpp - * and the ubl_map_move_to_xy funtion in menu_ubl.cpp. - */ - void ManualMove::task() { - - if (processing) return; // Prevent re-entry from idle() calls - - // Add a manual move to the queue? - if (axis != (uint8_t)NO_AXIS && ELAPSED(millis(), start_time) && !planner.is_full()) { - - const feedRate_t fr_mm_s = (uint8_t(axis) <= E_AXIS) ? manual_feedrate_mm_s[axis] : XY_PROBE_FEEDRATE_MM_S; - - #if IS_KINEMATIC - - #if HAS_MULTI_EXTRUDER - const int8_t old_extruder = active_extruder; - if (axis == E_AXIS) active_extruder = e_index; - #endif - - // Apply a linear offset to a single axis - destination = current_position; - if (axis <= XYZE) destination[axis] += offset; - - // Reset for the next move - offset = 0; - axis = (uint8_t)NO_AXIS; - - // DELTA and SCARA machines use segmented moves, which could fill the planner during the call to - // move_to_destination. This will cause idle() to be called, which can then call this function while the - // previous invocation is being blocked. Modifications to offset shouldn't be made while - // processing is true or the planner will get out of sync. - processing = true; - prepare_internal_move_to_destination(fr_mm_s); // will set current_position from destination - processing = false; - - TERN_(HAS_MULTI_EXTRUDER, active_extruder = old_extruder); - - #else - - // For Cartesian / Core motion simply move to the current_position - planner.buffer_line(current_position, fr_mm_s, axis == E_AXIS ? e_index : active_extruder); - - //SERIAL_ECHOLNPAIR("Add planner.move with Axis ", int(axis), " at FR ", fr_mm_s); - - axis = (uint8_t)NO_AXIS; - - #endif - } - } - - // - // Tell ui.update() to start a move to current_position after a short delay. - // - void ManualMove::soon(AxisEnum move_axis - #if MULTI_MANUAL - , const int8_t eindex/*=-1*/ - #endif - ) { - #if MULTI_MANUAL - if (move_axis == E_AXIS) e_index = eindex >= 0 ? eindex : active_extruder; - #endif - start_time = millis() + (menu_scale < 0.99f ? 0UL : 250UL); // delay for bigger moves - axis = (uint8_t)move_axis; - //SERIAL_ECHOLNPAIR("Post Move with Axis ", int(axis), " soon."); - } - - #if ENABLED(AUTO_BED_LEVELING_UBL) - - void MarlinUI::external_encoder() { - if (external_control && encoderDiff) { - ubl.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. - } - } - - #endif - -#endif // HAS_LCD_MENU - -/** - * Update the LCD, read encoder buttons, etc. - * - Read button states - * - Check the SD Card slot state - * - Act on RepRap World keypad input - * - Update the encoder position - * - Apply acceleration to the encoder position - * - Do refresh(LCDVIEW_CALL_REDRAW_NOW) on controller events - * - Reset the Info Screen timeout if there's any input - * - Update status indicators, if any - * - * Run the current LCD menu handler callback function: - * - Call the handler only if lcdDrawUpdate != LCDVIEW_NONE - * - Before calling the handler, LCDVIEW_CALL_NO_REDRAW => LCDVIEW_NONE - * - Call the menu handler. Menu handlers should do the following: - * - If a value changes, set lcdDrawUpdate to LCDVIEW_REDRAW_NOW and draw the value - * (Encoder events automatically set lcdDrawUpdate for you.) - * - if (should_draw()) { redraw } - * - Before exiting the handler set lcdDrawUpdate to: - * - LCDVIEW_CLEAR_CALL_REDRAW to clear screen and set LCDVIEW_CALL_REDRAW_NEXT. - * - LCDVIEW_REDRAW_NOW to draw now (including remaining stripes). - * - LCDVIEW_CALL_REDRAW_NEXT to draw now and get LCDVIEW_REDRAW_NOW on the next loop. - * - LCDVIEW_CALL_NO_REDRAW to draw now and get LCDVIEW_NONE on the next loop. - * - NOTE: For graphical displays menu handlers may be called 2 or more times per loop, - * so don't change lcdDrawUpdate without considering this. - * - * After the menu handler callback runs (or not): - * - Clear the LCD if lcdDrawUpdate == LCDVIEW_CLEAR_CALL_REDRAW - * - Update lcdDrawUpdate for the next loop (i.e., move one state down, usually) - * - * This function is only called from the main thread. - */ - -LCDViewAction MarlinUI::lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; -millis_t next_lcd_update_ms; -#if HAS_LCD_MENU && LCD_TIMEOUT_TO_STATUS - millis_t MarlinUI::return_to_status_ms = 0; -#endif - -void MarlinUI::update() { - - static uint16_t max_display_update_time = 0; - millis_t ms = millis(); - - #if HAS_LCD_MENU && LCD_TIMEOUT_TO_STATUS > 0 - #define RESET_STATUS_TIMEOUT() (return_to_status_ms = ms + LCD_TIMEOUT_TO_STATUS) - #else - #define RESET_STATUS_TIMEOUT() NOOP - #endif - - #ifdef LED_BACKLIGHT_TIMEOUT - leds.update_timeout(powersupply_on); - #endif - - #if HAS_LCD_MENU - - // Handle any queued Move Axis motion - manual_move.task(); - - // Update button states for button_pressed(), etc. - // If the state changes the next update may be delayed 300-500ms. - update_buttons(); - - // If the action button is pressed... - static bool wait_for_unclick; // = false - - auto do_click = [&]{ - wait_for_unclick = true; // - Set debounce flag to ignore continous clicks - lcd_clicked = !wait_for_user; // - Keep the click if not waiting for a user-click - wait_for_user = false; // - Any click clears wait for user - quick_feedback(); // - Always make a click sound - }; - - #if HAS_TOUCH_XPT2046 - if (touch_buttons) { - RESET_STATUS_TIMEOUT(); - if (touch_buttons & (EN_A | EN_B)) { // Menu arrows, in priority - if (ELAPSED(ms, next_button_update_ms)) { - encoderDiff = (ENCODER_STEPS_PER_MENU_ITEM) * epps * encoderDirection; - if (touch_buttons & EN_A) encoderDiff *= -1; - TERN_(AUTO_BED_LEVELING_UBL, external_encoder()); - next_button_update_ms = ms + repeat_delay; // Assume the repeat delay - if (!wait_for_unclick) { - next_button_update_ms += 250; // Longer delay on first press - wait_for_unclick = true; // Avoid Back/Select click while repeating - chirp(); - } - } - } - else if (!wait_for_unclick && (buttons & EN_C)) // OK button, if not waiting for a debounce release: - do_click(); - } - else // keep wait_for_unclick value - - #endif // HAS_TOUCH_XPT2046 - - { - // Integrated LCD click handling via button_pressed - if (!external_control && button_pressed()) { - if (!wait_for_unclick) do_click(); // Handle the click - } - else - wait_for_unclick = false; - } - - if (LCD_BACK_CLICKED()) { - quick_feedback(); - goto_previous_screen(); - } - - #endif // HAS_LCD_MENU - - if (ELAPSED(ms, next_lcd_update_ms) || TERN0(HAS_MARLINUI_U8GLIB, drawing_screen)) { - - next_lcd_update_ms = ms + LCD_UPDATE_INTERVAL; - - #if HAS_TOUCH_XPT2046 - - if (on_status_screen()) next_lcd_update_ms += (LCD_UPDATE_INTERVAL) * 2; - - TERN_(HAS_ENCODER_ACTION, touch_buttons = touch.read_buttons()); - - #endif - - TERN_(LCD_HAS_STATUS_INDICATORS, update_indicators()); - - #if HAS_ENCODER_ACTION - - TERN_(HAS_SLOW_BUTTONS, slow_buttons = read_slow_buttons()); // Buttons that take too long to read in interrupt context - - if (TERN0(REPRAPWORLD_KEYPAD, handle_keypad())) - RESET_STATUS_TIMEOUT(); - - uint8_t abs_diff = ABS(encoderDiff); - - #if ENCODER_PULSES_PER_STEP > 1 - // When reversing the encoder direction, a movement step can be missed because - // encoderDiff has a non-zero residual value, making the controller unresponsive. - // The fix clears the residual value when the encoder is idle. - // Also check if past half the threshold to compensate for missed single steps. - static int8_t lastEncoderDiff; - - // Timeout? No decoder change since last check. 10 or 20 times per second. - if (encoderDiff == lastEncoderDiff && abs_diff <= epps / 2) // Same direction & size but not over a half-step? - encoderDiff = 0; // Clear residual pulses. - else if (WITHIN(abs_diff, epps / 2 + 1, epps - 1)) { // Past half of threshold? - abs_diff = epps; // Treat as a full step size - encoderDiff = (encoderDiff < 0 ? -1 : 1) * abs_diff; // ...in the spin direction. - } - lastEncoderDiff = encoderDiff; - #endif - - const bool encoderPastThreshold = (abs_diff >= epps); - if (encoderPastThreshold || lcd_clicked) { - if (encoderPastThreshold && TERN1(IS_TFTGLCD_PANEL, !external_control)) { - - #if BOTH(HAS_LCD_MENU, ENCODER_RATE_MULTIPLIER) - - int32_t encoderMultiplier = 1; - - if (encoderRateMultiplierEnabled) { - const float encoderMovementSteps = float(abs_diff) / epps; - - if (lastEncoderMovementMillis) { - // Note that the rate is always calculated between two passes through the - // loop and that the abs of the encoderDiff value is tracked. - const float encoderStepRate = encoderMovementSteps / float(ms - lastEncoderMovementMillis) * 1000; - - if (encoderStepRate >= ENCODER_100X_STEPS_PER_SEC) encoderMultiplier = 100; - else if (encoderStepRate >= ENCODER_10X_STEPS_PER_SEC) encoderMultiplier = 10; - - // Enable to output the encoder steps per second value - //#define ENCODER_RATE_MULTIPLIER_DEBUG - #if ENABLED(ENCODER_RATE_MULTIPLIER_DEBUG) - SERIAL_ECHO_START(); - SERIAL_ECHOPAIR("Enc Step Rate: ", encoderStepRate); - SERIAL_ECHOPAIR(" Multiplier: ", encoderMultiplier); - SERIAL_ECHOPAIR(" ENCODER_10X_STEPS_PER_SEC: ", ENCODER_10X_STEPS_PER_SEC); - SERIAL_ECHOPAIR(" ENCODER_100X_STEPS_PER_SEC: ", ENCODER_100X_STEPS_PER_SEC); - SERIAL_EOL(); - #endif - } - - lastEncoderMovementMillis = ms; - } // encoderRateMultiplierEnabled - - #else - - constexpr int32_t encoderMultiplier = 1; - - #endif // ENCODER_RATE_MULTIPLIER - - encoderPosition += (encoderDiff * encoderMultiplier) / epps; - encoderDiff = 0; - } - - RESET_STATUS_TIMEOUT(); - - refresh(LCDVIEW_REDRAW_NOW); - - #ifdef LED_BACKLIGHT_TIMEOUT - leds.reset_timeout(ms); - #endif - } - - #endif - - // This runs every ~100ms when idling often enough. - // Instead of tracking changes just redraw the Status Screen once per second. - if (on_status_screen() && !lcd_status_update_delay--) { - lcd_status_update_delay = TERN(HAS_MARLINUI_U8GLIB, 12, 9); - if (max_display_update_time) max_display_update_time--; // Be sure never go to a very big number - refresh(LCDVIEW_REDRAW_NOW); - } - - #if BOTH(HAS_LCD_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--) { - lcd_status_update_delay = 4; - if (++filename_scroll_pos > filename_scroll_max) { - filename_scroll_pos = 0; - lcd_status_update_delay = 12; - } - refresh(LCDVIEW_REDRAW_NOW); - RESET_STATUS_TIMEOUT(); - } - #endif - - // Then we want to use only 50% of the time - const uint16_t bbr2 = planner.block_buffer_runtime() >> 1; - - if ((should_draw() || drawing_screen) && (!bbr2 || bbr2 > max_display_update_time)) { - - // Change state of drawing flag between screen updates - if (!drawing_screen) switch (lcdDrawUpdate) { - case LCDVIEW_CALL_NO_REDRAW: - refresh(LCDVIEW_NONE); - break; - case LCDVIEW_CLEAR_CALL_REDRAW: - case LCDVIEW_CALL_REDRAW_NEXT: - refresh(LCDVIEW_REDRAW_NOW); - case LCDVIEW_REDRAW_NOW: // set above, or by a handler through LCDVIEW_CALL_REDRAW_NEXT - case LCDVIEW_NONE: - break; - } // switch - - TERN_(HAS_ADC_BUTTONS, keypad_buttons = 0); - - #if HAS_MARLINUI_U8GLIB - - #if ENABLED(LIGHTWEIGHT_UI) - const bool in_status = on_status_screen(), - do_u8g_loop = !in_status; - lcd_in_status(in_status); - if (in_status) status_screen(); - #else - constexpr bool do_u8g_loop = true; - #endif - - if (do_u8g_loop) { - if (!drawing_screen) { // If not already drawing pages - u8g.firstPage(); // Start the first page - drawing_screen = first_page = true; // Flag as drawing pages - } - set_font(FONT_MENU); // Setup font for every page draw - u8g.setColorIndex(1); // And reset the color - run_current_screen(); // Draw and process the current screen - first_page = false; - - // The screen handler can clear drawing_screen for an action that changes the screen. - // If still drawing and there's another page, update max-time and return now. - // The nextPage will already be set up on the next call. - if (drawing_screen && (drawing_screen = u8g.nextPage())) { - if (on_status_screen()) - NOLESS(max_display_update_time, millis() - ms); - return; - } - } - - #else - - run_current_screen(); - - #endif - - TERN_(HAS_LCD_MENU, lcd_clicked = false); - - // Keeping track of the longest time for an individual LCD update. - // Used to do screen throttling when the planner starts to fill up. - if (on_status_screen()) - NOLESS(max_display_update_time, millis() - ms); - } - - #if HAS_LCD_MENU && LCD_TIMEOUT_TO_STATUS > 0 - // Return to Status Screen after a timeout - if (on_status_screen() || defer_return_to_status) - RESET_STATUS_TIMEOUT(); - else if (ELAPSED(ms, return_to_status_ms)) - return_to_status(); - #endif - - // Change state of drawing flag between screen updates - if (!drawing_screen) switch (lcdDrawUpdate) { - case LCDVIEW_CLEAR_CALL_REDRAW: - clear_lcd(); break; - case LCDVIEW_REDRAW_NOW: - refresh(LCDVIEW_NONE); - case LCDVIEW_NONE: - case LCDVIEW_CALL_REDRAW_NEXT: - case LCDVIEW_CALL_NO_REDRAW: - default: break; - } // switch - - } // ELAPSED(ms, next_lcd_update_ms) - - TERN_(HAS_GRAPHICAL_TFT, tft_idle()); -} - -#if HAS_ADC_BUTTONS - - typedef struct { - uint16_t ADCKeyValueMin, ADCKeyValueMax; - uint8_t ADCKeyNo; - } _stADCKeypadTable_; - - #ifndef ADC_BUTTONS_VALUE_SCALE - #define ADC_BUTTONS_VALUE_SCALE 1.0 // for the power voltage equal to the reference voltage - #endif - #ifndef ADC_BUTTONS_R_PULLUP - #define ADC_BUTTONS_R_PULLUP 4.7 // common pull-up resistor in the voltage divider - #endif - #ifndef ADC_BUTTONS_LEFT_R_PULLDOWN - #define ADC_BUTTONS_LEFT_R_PULLDOWN 0.47 // pull-down resistor for LEFT button voltage divider - #endif - #ifndef ADC_BUTTONS_RIGHT_R_PULLDOWN - #define ADC_BUTTONS_RIGHT_R_PULLDOWN 4.7 // pull-down resistor for RIGHT button voltage divider - #endif - #ifndef ADC_BUTTONS_UP_R_PULLDOWN - #define ADC_BUTTONS_UP_R_PULLDOWN 1.0 // pull-down resistor for UP button voltage divider - #endif - #ifndef ADC_BUTTONS_DOWN_R_PULLDOWN - #define ADC_BUTTONS_DOWN_R_PULLDOWN 10.0 // pull-down resistor for DOWN button voltage divider - #endif - #ifndef ADC_BUTTONS_MIDDLE_R_PULLDOWN - #define ADC_BUTTONS_MIDDLE_R_PULLDOWN 2.2 // pull-down resistor for MIDDLE button voltage divider - #endif - - // Calculate the ADC value for the voltage divider with specified pull-down resistor value - #define ADC_BUTTON_VALUE(r) int(HAL_ADC_RANGE * (ADC_BUTTONS_VALUE_SCALE) * r / (r + ADC_BUTTONS_R_PULLUP)) - - static constexpr uint16_t adc_button_tolerance = HAL_ADC_RANGE * 25 / 1024, - adc_other_button = HAL_ADC_RANGE * 1000 / 1024; - static const _stADCKeypadTable_ stADCKeyTable[] PROGMEM = { - // VALUE_MIN, VALUE_MAX, KEY - { adc_other_button, HAL_ADC_RANGE, 1 + BLEN_KEYPAD_F1 }, // F1 - { adc_other_button, HAL_ADC_RANGE, 1 + BLEN_KEYPAD_F2 }, // F2 - { adc_other_button, HAL_ADC_RANGE, 1 + BLEN_KEYPAD_F3 }, // F3 - { ADC_BUTTON_VALUE(ADC_BUTTONS_LEFT_R_PULLDOWN) - adc_button_tolerance, - ADC_BUTTON_VALUE(ADC_BUTTONS_LEFT_R_PULLDOWN) + adc_button_tolerance, 1 + BLEN_KEYPAD_LEFT }, // LEFT ( 272 ... 472) - { ADC_BUTTON_VALUE(ADC_BUTTONS_RIGHT_R_PULLDOWN) - adc_button_tolerance, - ADC_BUTTON_VALUE(ADC_BUTTONS_RIGHT_R_PULLDOWN) + adc_button_tolerance, 1 + BLEN_KEYPAD_RIGHT }, // RIGHT (1948 ... 2148) - { ADC_BUTTON_VALUE(ADC_BUTTONS_UP_R_PULLDOWN) - adc_button_tolerance, - ADC_BUTTON_VALUE(ADC_BUTTONS_UP_R_PULLDOWN) + adc_button_tolerance, 1 + BLEN_KEYPAD_UP }, // UP ( 618 ... 818) - { ADC_BUTTON_VALUE(ADC_BUTTONS_DOWN_R_PULLDOWN) - adc_button_tolerance, - ADC_BUTTON_VALUE(ADC_BUTTONS_DOWN_R_PULLDOWN) + adc_button_tolerance, 1 + BLEN_KEYPAD_DOWN }, // DOWN (2686 ... 2886) - { ADC_BUTTON_VALUE(ADC_BUTTONS_MIDDLE_R_PULLDOWN) - adc_button_tolerance, - ADC_BUTTON_VALUE(ADC_BUTTONS_MIDDLE_R_PULLDOWN) + adc_button_tolerance, 1 + BLEN_KEYPAD_MIDDLE }, // ENTER (1205 ... 1405) - }; - - uint8_t get_ADC_keyValue() { - if (thermalManager.ADCKey_count >= 16) { - const uint16_t currentkpADCValue = thermalManager.current_ADCKey_raw; - thermalManager.current_ADCKey_raw = HAL_ADC_RANGE; - thermalManager.ADCKey_count = 0; - if (currentkpADCValue < adc_other_button) - LOOP_L_N(i, ADC_KEY_NUM) { - const uint16_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); - } - } - return 0; - } - -#endif // HAS_ADC_BUTTONS - -#if HAS_ENCODER_ACTION - - /** - * Read encoder buttons from the hardware registers - * Warning: This function is called from interrupt context! - */ - void MarlinUI::update_buttons() { - const millis_t now = millis(); - if (ELAPSED(now, next_button_update_ms)) { - - #if HAS_DIGITAL_BUTTONS - - #if ANY_BUTTON(EN1, EN2, ENC, BACK) - - uint8_t newbutton = 0; - - #if BUTTON_EXISTS(EN1) - if (BUTTON_PRESSED(EN1)) newbutton |= EN_A; - #endif - #if BUTTON_EXISTS(EN2) - if (BUTTON_PRESSED(EN2)) newbutton |= EN_B; - #endif - #if BUTTON_EXISTS(ENC) - if (BUTTON_PRESSED(ENC)) newbutton |= EN_C; - #endif - #if BUTTON_EXISTS(BACK) - if (BUTTON_PRESSED(BACK)) newbutton |= EN_D; - #endif - - #else - - constexpr uint8_t newbutton = 0; - - #endif - - // - // Directional buttons - // - #if ANY_BUTTON(UP, DWN, LFT, RT) - - const int8_t pulses = epps * encoderDirection; - - if (false) { - // for the else-ifs below - } - #if BUTTON_EXISTS(UP) - else if (BUTTON_PRESSED(UP)) { - encoderDiff = (ENCODER_STEPS_PER_MENU_ITEM) * pulses; - next_button_update_ms = now + 300; - } - #endif - #if BUTTON_EXISTS(DWN) - else if (BUTTON_PRESSED(DWN)) { - encoderDiff = -(ENCODER_STEPS_PER_MENU_ITEM) * pulses; - next_button_update_ms = now + 300; - } - #endif - #if BUTTON_EXISTS(LFT) - else if (BUTTON_PRESSED(LFT)) { - encoderDiff = -pulses; - next_button_update_ms = now + 300; - } - #endif - #if BUTTON_EXISTS(RT) - else if (BUTTON_PRESSED(RT)) { - encoderDiff = pulses; - next_button_update_ms = now + 300; - } - #endif - - #endif // UP || DWN || LFT || RT - - buttons = (newbutton - #if HAS_SLOW_BUTTONS - | slow_buttons - #endif - #if BOTH(HAS_TOUCH_XPT2046, HAS_ENCODER_ACTION) - | (touch_buttons & TERN(HAS_ENCODER_WHEEL, ~(EN_A | EN_B), 0xFF)) - #endif - ); - - #elif HAS_ADC_BUTTONS - - buttons = 0; - - #endif - - #if HAS_ADC_BUTTONS - if (keypad_buttons == 0) { - const uint8_t b = get_ADC_keyValue(); - if (WITHIN(b, 1, 8)) keypad_buttons = _BV(b - 1); - } - #endif - - #if HAS_SHIFT_ENCODER - /** - * Set up Rotary Encoder bit values (for two pin encoders to indicate movement). - * These values are independent of which pins are used for EN_A / EN_B indications. - * The rotary encoder part is also independent of the LCD chipset. - */ - uint8_t val = 0; - WRITE(SHIFT_LD, LOW); - WRITE(SHIFT_LD, HIGH); - LOOP_L_N(i, 8) { - val >>= 1; - if (READ(SHIFT_OUT)) SBI(val, 7); - WRITE(SHIFT_CLK, HIGH); - WRITE(SHIFT_CLK, LOW); - } - TERN(REPRAPWORLD_KEYPAD, keypad_buttons, buttons) = ~val; - #endif - - #if IS_TFTGLCD_PANEL - next_button_update_ms = now + (LCD_UPDATE_INTERVAL / 2); - buttons = slow_buttons; - TERN_(AUTO_BED_LEVELING_UBL, external_encoder()); - #endif - - } // next_button_update_ms - - #if HAS_ENCODER_WHEEL - static uint8_t lastEncoderBits; - - #define encrot0 0 - #define encrot1 2 - #define encrot2 3 - #define encrot3 1 - - // Manage encoder rotation - #define ENCODER_SPIN(_E1, _E2) switch (lastEncoderBits) { case _E1: encoderDiff += encoderDirection; break; case _E2: encoderDiff -= encoderDirection; } - - uint8_t enc = 0; - if (buttons & EN_A) enc |= B01; - if (buttons & EN_B) enc |= B10; - if (enc != lastEncoderBits) { - switch (enc) { - case encrot0: ENCODER_SPIN(encrot3, encrot1); break; - case encrot1: ENCODER_SPIN(encrot0, encrot2); break; - case encrot2: ENCODER_SPIN(encrot1, encrot3); break; - case encrot3: ENCODER_SPIN(encrot2, encrot0); break; - } - #if BOTH(HAS_LCD_MENU, AUTO_BED_LEVELING_UBL) - external_encoder(); - #endif - lastEncoderBits = enc; - } - - #endif // HAS_ENCODER_WHEEL - } - -#endif // HAS_ENCODER_ACTION - -#endif // HAS_WIRED_LCD - -#if HAS_DISPLAY - - #if ENABLED(EXTENSIBLE_UI) - #include "extui/ui_api.h" - #endif - - //////////////////////////////////////////// - /////////////// Status Line //////////////// - //////////////////////////////////////////// - - #if ENABLED(STATUS_MESSAGE_SCROLLING) - void MarlinUI::advance_status_scroll() { - // Advance by one UTF8 code-word - if (status_scroll_offset < utf8_strlen(status_message)) - while (!START_OF_UTF8_CHAR(status_message[++status_scroll_offset])); - else - status_scroll_offset = 0; - } - char* MarlinUI::status_and_len(uint8_t &len) { - char *out = status_message + status_scroll_offset; - len = utf8_strlen(out); - return out; - } - #endif - - void MarlinUI::finish_status(const bool persist) { - - #if !(ENABLED(LCD_PROGRESS_BAR) && (PROGRESS_MSG_EXPIRE) > 0) - UNUSED(persist); - #endif - - #if ENABLED(LCD_PROGRESS_BAR) || BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) - const millis_t ms = millis(); - #endif - - #if ENABLED(LCD_PROGRESS_BAR) && !IS_TFTGLCD_PANEL - progress_bar_ms = ms; - #if PROGRESS_MSG_EXPIRE > 0 - expire_status_ms = persist ? 0 : ms + PROGRESS_MSG_EXPIRE; - #endif - #endif - - #if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) - next_filament_display = ms + 5000UL; // Show status message for 5s - #endif - - #if BOTH(HAS_WIRED_LCD, STATUS_MESSAGE_SCROLLING) - status_scroll_offset = 0; - #endif - - TERN_(EXTENSIBLE_UI, ExtUI::onStatusChanged(status_message)); - } - - bool MarlinUI::has_status() { return (status_message[0] != '\0'); } - - void MarlinUI::set_status(const char * const message, const bool persist) { - if (alert_level) return; - - TERN_(HOST_PROMPT_SUPPORT, host_action_notify(message)); - - // Here we have a problem. The message is encoded in UTF8, so - // arbitrarily cutting it will be a problem. We MUST be sure - // that there is no cutting in the middle of a multibyte character! - - // Get a pointer to the null terminator - const char* pend = message + strlen(message); - - // If length of supplied UTF8 string is greater than - // our buffer size, start cutting whole UTF8 chars - while ((pend - message) > MAX_MESSAGE_LENGTH) { - --pend; - while (!START_OF_UTF8_CHAR(*pend)) --pend; - }; - - // At this point, we have the proper cut point. Use it - uint8_t maxLen = pend - message; - strncpy(status_message, message, maxLen); - status_message[maxLen] = '\0'; - - finish_status(persist); - } - - #include - - void MarlinUI::status_printf_P(const uint8_t level, PGM_P const fmt, ...) { - if (level < alert_level) return; - alert_level = level; - va_list args; - va_start(args, fmt); - vsnprintf_P(status_message, MAX_MESSAGE_LENGTH, fmt, args); - va_end(args); - finish_status(level > 0); - } - - void MarlinUI::set_status_P(PGM_P const message, int8_t level) { - if (level < 0) level = alert_level = 0; - if (level < alert_level) return; - alert_level = level; - - TERN_(HOST_PROMPT_SUPPORT, host_action_notify_P(message)); - - // Since the message is encoded in UTF8 it must - // only be cut on a character boundary. - - // Get a pointer to the null terminator - PGM_P pend = message + strlen_P(message); - - // If length of supplied UTF8 string is greater than - // the buffer size, start cutting whole UTF8 chars - while ((pend - message) > MAX_MESSAGE_LENGTH) { - --pend; - while (!START_OF_UTF8_CHAR(pgm_read_byte(pend))) --pend; - }; - - // At this point, we have the proper cut point. Use it - uint8_t maxLen = pend - message; - strncpy_P(status_message, message, maxLen); - status_message[maxLen] = '\0'; - - finish_status(level > 0); - } - - void MarlinUI::set_alert_status_P(PGM_P const message) { - set_status_P(message, 1); - TERN_(HAS_LCD_MENU, return_to_status()); - } - - PGM_P print_paused = GET_TEXT(MSG_PRINT_PAUSED); - - /** - * Reset the status message - */ - void MarlinUI::reset_status(const bool no_welcome) { - PGM_P printing = GET_TEXT(MSG_PRINTING); - PGM_P welcome = GET_TEXT(WELCOME_MSG); - #if SERVICE_INTERVAL_1 > 0 - static PGMSTR(service1, "> " SERVICE_NAME_1 "!"); - #endif - #if SERVICE_INTERVAL_2 > 0 - static PGMSTR(service2, "> " SERVICE_NAME_2 "!"); - #endif - #if SERVICE_INTERVAL_3 > 0 - static PGMSTR(service3, "> " SERVICE_NAME_3 "!"); - #endif - PGM_P msg; - if (printingIsPaused()) - msg = print_paused; - #if ENABLED(SDSUPPORT) - else if (IS_SD_PRINTING()) - return set_status(card.longest_filename(), true); - #endif - else if (print_job_timer.isRunning()) - msg = printing; - - #if SERVICE_INTERVAL_1 > 0 - else if (print_job_timer.needsService(1)) msg = service1; - #endif - #if SERVICE_INTERVAL_2 > 0 - else if (print_job_timer.needsService(2)) msg = service2; - #endif - #if SERVICE_INTERVAL_3 > 0 - else if (print_job_timer.needsService(3)) msg = service3; - #endif - - else if (!no_welcome) - msg = welcome; - else - return; - - set_status_P(msg, -1); - } - - #if ENABLED(SDSUPPORT) - extern bool wait_for_user, wait_for_heatup; - #endif - - void MarlinUI::abort_print() { - #if ENABLED(SDSUPPORT) - wait_for_heatup = wait_for_user = false; - card.flag.abort_sd_printing = true; - #endif - #ifdef ACTION_ON_CANCEL - host_action_cancel(); - #endif - TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_INFO, PSTR("UI Aborted"), DISMISS_STR)); - print_job_timer.stop(); - set_status_P(GET_TEXT(MSG_PRINT_ABORTED)); - TERN_(HAS_LCD_MENU, return_to_status()); - } - - #if ANY(PARK_HEAD_ON_PAUSE, SDSUPPORT) - #include "../gcode/queue.h" - #endif - - void MarlinUI::pause_print() { - #if HAS_LCD_MENU - synchronize(GET_TEXT(MSG_PAUSING)); - defer_status_screen(); - #endif - - TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_PAUSE_RESUME, PSTR("UI Pause"), PSTR("Resume"))); - - set_status_P(print_paused); - - #if ENABLED(PARK_HEAD_ON_PAUSE) - TERN_(HAS_WIRED_LCD, lcd_pause_show_message(PAUSE_MESSAGE_PARKING, PAUSE_MODE_PAUSE_PRINT)); // Show message immediately to let user know about pause in progress - queue.inject_P(PSTR("M25 P\nM24")); - #elif ENABLED(SDSUPPORT) - queue.inject_P(PSTR("M25")); - #elif defined(ACTION_ON_PAUSE) - host_action_pause(); - #endif - } - - void MarlinUI::resume_print() { - reset_status(); - TERN_(PARK_HEAD_ON_PAUSE, wait_for_heatup = wait_for_user = false); - if (IS_SD_PAUSED()) queue.inject_P(M24_STR); - #ifdef ACTION_ON_RESUME - host_action_resume(); - #endif - print_job_timer.start(); // Also called by M24 - } - - #if HAS_PRINT_PROGRESS - - MarlinUI::progress_t MarlinUI::_get_progress() { - return ( - TERN0(LCD_SET_PROGRESS_MANUALLY, (progress_override & PROGRESS_MASK)) - #if ENABLED(SDSUPPORT) - ?: TERN(HAS_PRINT_PROGRESS_PERMYRIAD, card.permyriadDone(), card.percentDone()) - #endif - ); - } - - #endif - - #if HAS_TOUCH_XPT2046 - - // - // 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 + - // - 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; - next_button_update_ms = now + repeat_delay; // Assume the repeat delay - const int8_t xdir = col < (LCD_WIDTH ) / 2 ? -1 : 1, - ydir = row < (LCD_HEIGHT) / 2 ? -1 : 1; - if (on_edit_screen) - encoderDiff = epps * ydir; - else if (screen_items > 0) { - // Last 5 cols act as a scroll :-) - if (col > (LCD_WIDTH) - 5) - // 2 * LCD_HEIGHT to scroll to bottom of next page. (LCD_HEIGHT would only go 1 item down.) - encoderDiff = epps * (encoderLine - encoderTopLine + 2 * (LCD_HEIGHT)) * ydir; - else - encoderDiff = epps * (row - encoderPosition + encoderTopLine); - } - else if (!on_status_screen()) - encoderDiff = epps * xdir; - } - - #endif - -#else // !HAS_DISPLAY - - // - // Send the status line as a host notification - // - void MarlinUI::set_status(const char * const message, const bool) { - TERN(HOST_PROMPT_SUPPORT, host_action_notify(message), UNUSED(message)); - } - void MarlinUI::set_status_P(PGM_P message, const int8_t) { - TERN(HOST_PROMPT_SUPPORT, host_action_notify_P(message), UNUSED(message)); - } - void MarlinUI::status_printf_P(const uint8_t, PGM_P const message, ...) { - TERN(HOST_PROMPT_SUPPORT, host_action_notify_P(message), UNUSED(message)); - } - -#endif // !HAS_DISPLAY - -#if ENABLED(SDSUPPORT) - - void MarlinUI::media_changed(const uint8_t old_status, const uint8_t status) { - if (old_status == status) { - TERN_(EXTENSIBLE_UI, ExtUI::onMediaError()); // Failed to mount/unmount - return; - } - - if (status) { - if (old_status < 2) { - TERN_(EXTENSIBLE_UI, ExtUI::onMediaInserted()); // ExtUI response - set_status_P(GET_TEXT(MSG_MEDIA_INSERTED)); - } - } - else { - if (old_status < 2) { - TERN_(EXTENSIBLE_UI, ExtUI::onMediaRemoved()); // ExtUI response - #if PIN_EXISTS(SD_DETECT) - set_status_P(GET_TEXT(MSG_MEDIA_REMOVED)); - #if HAS_LCD_MENU - if (!defer_return_to_status) return_to_status(); - #endif - #endif - } - } - - #if PIN_EXISTS(SD_DETECT) && DISABLED(NO_LCD_REINIT) - init_lcd(); // Revive a noisy shared SPI LCD - #endif - - refresh(); - - #if HAS_WIRED_LCD || defined(LED_BACKLIGHT_TIMEOUT) - const millis_t ms = millis(); - #endif - - TERN_(HAS_WIRED_LCD, next_lcd_update_ms = ms + LCD_UPDATE_INTERVAL); // Delay LCD update for SD activity - - #ifdef LED_BACKLIGHT_TIMEOUT - leds.reset_timeout(ms); - #endif - } - -#endif // SDSUPPORT - -#if HAS_LCD_MENU - void MarlinUI::reset_settings() { settings.reset(); completion_feedback(); } -#endif - -#if ENABLED(EEPROM_SETTINGS) - - #if HAS_LCD_MENU - void MarlinUI::init_eeprom() { - const bool good = settings.init_eeprom(); - completion_feedback(good); - return_to_status(); - } - void MarlinUI::load_settings() { - const bool good = settings.load(); - completion_feedback(good); - } - void MarlinUI::store_settings() { - const bool good = settings.save(); - completion_feedback(good); - } - #endif - - #if DISABLED(EEPROM_AUTO_INIT) - - static inline PGM_P eeprom_err(const uint8_t msgid) { - switch (msgid) { - default: - case 0: return GET_TEXT(MSG_ERR_EEPROM_CRC); - case 1: return GET_TEXT(MSG_ERR_EEPROM_INDEX); - case 2: return GET_TEXT(MSG_ERR_EEPROM_VERSION); - } - } - - void MarlinUI::eeprom_alert(const uint8_t msgid) { - #if HAS_LCD_MENU - editable.uint8 = msgid; - goto_screen([]{ - PGM_P const restore_msg = GET_TEXT(MSG_INIT_EEPROM); - char msg[utf8_strlen_P(restore_msg) + 1]; - strcpy_P(msg, restore_msg); - MenuItem_confirm::select_screen( - GET_TEXT(MSG_BUTTON_RESET), GET_TEXT(MSG_BUTTON_IGNORE), - init_eeprom, return_to_status, - eeprom_err(editable.uint8), msg, PSTR("?") - ); - }); - #else - set_status_P(eeprom_err(msgid)); - #endif - } - - #endif // EEPROM_AUTO_INIT - -#endif // EEPROM_SETTINGS diff --git a/Marlin/src/lcd/ultralcd.h b/Marlin/src/lcd/ultralcd.h deleted file mode 100644 index c7ef41596df5..000000000000 --- a/Marlin/src/lcd/ultralcd.h +++ /dev/null @@ -1,717 +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 - -#include "../inc/MarlinConfig.h" - -#if HAS_BUZZER - #include "../libs/buzzer.h" -#endif - -#if ENABLED(SDSUPPORT) - #include "../sd/cardreader.h" -#endif - -#if EITHER(HAS_LCD_MENU, ULTIPANEL_FEEDMULTIPLY) - #define HAS_ENCODER_ACTION 1 -#endif -#if ((!HAS_ADC_BUTTONS && ENABLED(NEWPANEL)) || BUTTONS_EXIST(EN1, EN2)) && !IS_TFTGLCD_PANEL - #define HAS_ENCODER_WHEEL 1 -#endif -#if HAS_ENCODER_WHEEL || ANY_BUTTON(ENC, BACK, UP, DWN, LFT, RT) - #define HAS_DIGITAL_BUTTONS 1 -#endif -#if !HAS_ADC_BUTTONS && (ENABLED(REPRAPWORLD_KEYPAD) || (HAS_WIRED_LCD && DISABLED(NEWPANEL))) - #define HAS_SHIFT_ENCODER 1 -#endif - -// I2C buttons must be read in the main thread -#if ANY(LCD_I2C_VIKI, LCD_I2C_PANELOLU2, IS_TFTGLCD_PANEL) - #define HAS_SLOW_BUTTONS 1 -#endif - -#if E_MANUAL > 1 - #define MULTI_MANUAL 1 -#endif - -#if HAS_WIRED_LCD - - #include "../MarlinCore.h" - - #if ENABLED(ADVANCED_PAUSE_FEATURE) - #include "../feature/pause.h" - #include "../module/motion.h" // for active_extruder - #endif - - enum LCDViewAction : uint8_t { - LCDVIEW_NONE, - LCDVIEW_REDRAW_NOW, - LCDVIEW_CALL_REDRAW_NEXT, - LCDVIEW_CLEAR_CALL_REDRAW, - LCDVIEW_CALL_NO_REDRAW - }; - - #if HAS_ADC_BUTTONS - uint8_t get_ADC_keyValue(); - #endif - - #define LCD_UPDATE_INTERVAL TERN(HAS_TOUCH_XPT2046, 50, 100) - - #if HAS_LCD_MENU - - #include "lcdprint.h" - - void _wrap_string(uint8_t &col, uint8_t &row, const char * const string, read_byte_cb_t cb_read_byte, const bool wordwrap=false); - inline void wrap_string_P(uint8_t &col, uint8_t &row, PGM_P const pstr, const bool wordwrap=false) { _wrap_string(col, row, pstr, read_byte_rom, wordwrap); } - inline void wrap_string(uint8_t &col, uint8_t &row, const char * const string, const bool wordwrap=false) { _wrap_string(col, row, string, read_byte_ram, wordwrap); } - - #if ENABLED(SDSUPPORT) - #include "../sd/cardreader.h" - #endif - - typedef void (*screenFunc_t)(); - typedef void (*menuAction_t)(); - - #if ENABLED(ADVANCED_PAUSE_FEATURE) - void lcd_pause_show_message(const PauseMessage message, - const PauseMode mode=PAUSE_MODE_SAME, - const uint8_t extruder=active_extruder); - #endif - - #if ENABLED(AUTO_BED_LEVELING_UBL) - void lcd_mesh_edit_setup(const float &initial); - float lcd_mesh_edit(); - #endif - - #endif // HAS_LCD_MENU - -#endif // HAS_WIRED_LCD - -// REPRAPWORLD_KEYPAD (and ADC_KEYPAD) -#if ENABLED(REPRAPWORLD_KEYPAD) - #define BTN_OFFSET 0 // Bit offset into buttons for shift register values - - #define BLEN_KEYPAD_F3 0 - #define BLEN_KEYPAD_F2 1 - #define BLEN_KEYPAD_F1 2 - #define BLEN_KEYPAD_DOWN 3 - #define BLEN_KEYPAD_RIGHT 4 - #define BLEN_KEYPAD_MIDDLE 5 - #define BLEN_KEYPAD_UP 6 - #define BLEN_KEYPAD_LEFT 7 - - #define EN_KEYPAD_F1 _BV(BTN_OFFSET + BLEN_KEYPAD_F1) - #define EN_KEYPAD_F2 _BV(BTN_OFFSET + BLEN_KEYPAD_F2) - #define EN_KEYPAD_F3 _BV(BTN_OFFSET + BLEN_KEYPAD_F3) - #define EN_KEYPAD_DOWN _BV(BTN_OFFSET + BLEN_KEYPAD_DOWN) - #define EN_KEYPAD_RIGHT _BV(BTN_OFFSET + BLEN_KEYPAD_RIGHT) - #define EN_KEYPAD_MIDDLE _BV(BTN_OFFSET + BLEN_KEYPAD_MIDDLE) - #define EN_KEYPAD_UP _BV(BTN_OFFSET + BLEN_KEYPAD_UP) - #define EN_KEYPAD_LEFT _BV(BTN_OFFSET + BLEN_KEYPAD_LEFT) - - #define RRK(B) (keypad_buttons & (B)) - - #ifdef EN_C - #define BUTTON_CLICK() ((buttons & EN_C) || RRK(EN_KEYPAD_MIDDLE)) - #else - #define BUTTON_CLICK() RRK(EN_KEYPAD_MIDDLE) - #endif - -#endif - -#if HAS_DIGITAL_BUTTONS - - // Wheel spin pins where BA is 00, 10, 11, 01 (1 bit always changes) - #define BLEN_A 0 - #define BLEN_B 1 - - #define EN_A _BV(BLEN_A) - #define EN_B _BV(BLEN_B) - - #define BUTTON_PRESSED(BN) !READ(BTN_## BN) - - #if BUTTON_EXISTS(ENC) || HAS_TOUCH_XPT2046 - #define BLEN_C 2 - #define EN_C _BV(BLEN_C) - #endif - - #if ENABLED(LCD_I2C_VIKI) - - #include - - #define B_I2C_BTN_OFFSET 3 // (the first three bit positions reserved for EN_A, EN_B, EN_C) - - // button and encoder bit positions within 'buttons' - #define B_LE (BUTTON_LEFT << B_I2C_BTN_OFFSET) // The remaining normalized buttons are all read via I2C - #define B_UP (BUTTON_UP << B_I2C_BTN_OFFSET) - #define B_MI (BUTTON_SELECT << B_I2C_BTN_OFFSET) - #define B_DW (BUTTON_DOWN << B_I2C_BTN_OFFSET) - #define B_RI (BUTTON_RIGHT << B_I2C_BTN_OFFSET) - - #if BUTTON_EXISTS(ENC) // The pause/stop/restart button is connected to BTN_ENC when used - #define B_ST (EN_C) // Map the pause/stop/resume button into its normalized functional name - #define BUTTON_CLICK() (buttons & (B_MI|B_RI|B_ST)) // Pause/stop also acts as click until a proper pause/stop is implemented. - #else - #define BUTTON_CLICK() (buttons & (B_MI|B_RI)) - #endif - - // I2C buttons take too long to read inside an interrupt context and so we read them during lcd_update - - #elif ENABLED(LCD_I2C_PANELOLU2) - - #if !BUTTON_EXISTS(ENC) // Use I2C if not directly connected to a pin - - #define B_I2C_BTN_OFFSET 3 // (the first three bit positions reserved for EN_A, EN_B, EN_C) - - #define B_MI (PANELOLU2_ENCODER_C << B_I2C_BTN_OFFSET) // requires LiquidTWI2 library v1.2.3 or later - - #define BUTTON_CLICK() (buttons & B_MI) - - #endif - - #endif - -#else - - #undef BUTTON_EXISTS - #define BUTTON_EXISTS(...) false - - // Shift register bits correspond to buttons: - #define BL_LE 7 // Left - #define BL_UP 6 // Up - #define BL_MI 5 // Middle - #define BL_DW 4 // Down - #define BL_RI 3 // Right - #define BL_ST 2 // Red Button - #define B_LE _BV(BL_LE) - #define B_UP _BV(BL_UP) - #define B_MI _BV(BL_MI) - #define B_DW _BV(BL_DW) - #define B_RI _BV(BL_RI) - #define B_ST _BV(BL_ST) - - #ifndef BUTTON_CLICK - #define BUTTON_CLICK() (buttons & (B_MI|B_ST)) - #endif - -#endif - -#if BUTTON_EXISTS(BACK) || EITHER(HAS_TOUCH_XPT2046, IS_TFTGLCD_PANEL) - #define BLEN_D 3 - #define EN_D _BV(BLEN_D) - #define LCD_BACK_CLICKED() (buttons & EN_D) -#else - #define LCD_BACK_CLICKED() false -#endif - -#ifndef BUTTON_CLICK - #ifdef EN_C - #define BUTTON_CLICK() (buttons & EN_C) - #else - #define BUTTON_CLICK() false - #endif -#endif - -#if HAS_MARLINUI_U8GLIB - enum MarlinFont : uint8_t { - FONT_STATUSMENU = 1, - FONT_EDIT, - FONT_MENU - }; -#else - enum HD44780CharSet : uint8_t { - CHARSET_MENU, - CHARSET_INFO, - CHARSET_BOOT - }; -#endif - -#if PREHEAT_COUNT - typedef struct { - TERN_(HAS_HOTEND, uint16_t hotend_temp); - TERN_(HAS_HEATED_BED, uint16_t bed_temp ); - TERN_(HAS_FAN, uint16_t fan_speed ); - } preheat_t; -#endif - -#if HAS_LCD_MENU - - // Manual Movement class - class ManualMove { - public: - static millis_t start_time; - static float menu_scale; - TERN_(IS_KINEMATIC, static float offset); - #if IS_KINEMATIC - static bool processing; - #else - static bool constexpr processing = false; - #endif - #if MULTI_MANUAL - static int8_t e_index; - #else - static int8_t constexpr e_index = 0; - #endif - static uint8_t axis; - static void task(); - static void soon(AxisEnum axis - #if MULTI_MANUAL - , const int8_t eindex=-1 - #endif - ); - }; - -#endif - -//////////////////////////////////////////// -//////////// MarlinUI Singleton //////////// -//////////////////////////////////////////// - -class MarlinUI { -public: - - MarlinUI() { - TERN_(HAS_LCD_MENU, currentScreen = status_screen); - } - - #if HAS_BUZZER - static void buzz(const long duration, const uint16_t freq); - #endif - - FORCE_INLINE static void chirp() { - TERN_(HAS_CHIRP, buzz(LCD_FEEDBACK_FREQUENCY_DURATION_MS, LCD_FEEDBACK_FREQUENCY_HZ)); - } - - #if ENABLED(LCD_HAS_STATUS_INDICATORS) - static void update_indicators(); - #endif - - // LCD implementations - static void clear_lcd(); - - #if ENABLED(SDSUPPORT) - static void media_changed(const uint8_t old_stat, const uint8_t stat); - #endif - - #if ENABLED(DWIN_CREALITY_LCD) - static void refresh(); - #else - FORCE_INLINE static void refresh() { - TERN_(HAS_WIRED_LCD, refresh(LCDVIEW_CLEAR_CALL_REDRAW)); - } - #endif - - #if HAS_WIRED_LCD - static bool detected(); - static void init_lcd(); - #else - static inline bool detected() { return true; } - static inline void init_lcd() {} - #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(LCD_SET_PROGRESS_MANUALLY) - 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); } - #if BOTH(LCD_SET_PROGRESS_MANUALLY, USE_M73_REMAINING_TIME) - static uint32_t remaining_time; - FORCE_INLINE static void set_remaining_time(const uint32_t r) { remaining_time = r; } - FORCE_INLINE static uint32_t get_remaining_time() { return remaining_time; } - FORCE_INLINE static void reset_remaining_time() { set_remaining_time(0); } - #endif - #endif - static progress_t _get_progress(); - #if HAS_PRINT_PROGRESS_PERMYRIAD - FORCE_INLINE static uint16_t get_progress_permyriad() { return _get_progress(); } - #endif - static uint8_t get_progress_percent() { return uint8_t(_get_progress() / (PROGRESS_SCALE)); } - #else - static constexpr uint8_t get_progress_percent() { return 0; } - #endif - - #if HAS_DISPLAY - - static void init(); - static void update(); - static void set_alert_status_P(PGM_P const message); - - static char status_message[]; - static bool has_status(); - - static uint8_t alert_level; // Higher levels block lower levels - static inline void reset_alert_level() { alert_level = 0; } - - #if ENABLED(STATUS_MESSAGE_SCROLLING) - static uint8_t status_scroll_offset; - static void advance_status_scroll(); - static char* status_and_len(uint8_t &len); - #endif - - static void abort_print(); - static void pause_print(); - static void resume_print(); - - #if HAS_WIRED_LCD - - static millis_t next_button_update_ms; - - static LCDViewAction lcdDrawUpdate; - FORCE_INLINE static bool should_draw() { return bool(lcdDrawUpdate); } - FORCE_INLINE static void refresh(const LCDViewAction type) { lcdDrawUpdate = type; } - - #if ENABLED(SHOW_CUSTOM_BOOTSCREEN) - static void draw_custom_bootscreen(const uint8_t frame=0); - static void show_custom_bootscreen(); - #endif - - #if ENABLED(SHOW_BOOTSCREEN) - #ifndef BOOTSCREEN_TIMEOUT - #define BOOTSCREEN_TIMEOUT 2500 - #endif - static void draw_marlin_bootscreen(const bool line2=false); - static void show_marlin_bootscreen(); - static void show_bootscreen(); - #endif - - #if HAS_MARLINUI_U8GLIB - - static void set_font(const MarlinFont font_nr); - - #else - - static void set_custom_characters(const HD44780CharSet screen_charset=CHARSET_INFO); - - #if ENABLED(LCD_PROGRESS_BAR) - static millis_t progress_bar_ms; // Start time for the current progress bar cycle - static void draw_progress_bar(const uint8_t percent); - #if PROGRESS_MSG_EXPIRE > 0 - static millis_t expire_status_ms; // = 0 - FORCE_INLINE static void reset_progress_bar_timeout() { expire_status_ms = 0; } - #endif - #endif - - #endif - - static uint8_t lcd_status_update_delay; - - #if HAS_LCD_CONTRAST - static int16_t contrast; - static void set_contrast(const int16_t value); - FORCE_INLINE static void refresh_contrast() { set_contrast(contrast); } - #endif - - #if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) - static millis_t next_filament_display; - #endif - - static void quick_feedback(const bool clear_buttons=true); - #if HAS_BUZZER - static void completion_feedback(const bool good=true); - #else - static inline void completion_feedback(const bool=true) {} - #endif - - #if DISABLED(LIGHTWEIGHT_UI) - static void draw_status_message(const bool blink); - #endif - - #if ENABLED(ADVANCED_PAUSE_FEATURE) - static void draw_hotend_status(const uint8_t row, const uint8_t extruder); - #endif - - #if HAS_TOUCH_XPT2046 - static bool on_edit_screen; - static void screen_click(const uint8_t row, const uint8_t col, const uint8_t x, const uint8_t y); - #endif - - static void status_screen(); - - #endif - - #if HAS_MARLINUI_U8GLIB - static bool drawing_screen, first_page; - #else - static constexpr bool drawing_screen = false, first_page = true; - #endif - - static bool get_blink(); - static void kill_screen(PGM_P const lcd_error, PGM_P const lcd_component); - static void draw_kill_screen(); - static void set_status(const char* const message, const bool persist=false); - static void set_status_P(PGM_P const message, const int8_t level=0); - static void status_printf_P(const uint8_t level, PGM_P const fmt, ...); - static void reset_status(const bool no_welcome=false); - - #else // No LCD - - // Send status to host as a notification - static void set_status(const char* message, const bool=false); - static void set_status_P(PGM_P message, const int8_t=0); - static void status_printf_P(const uint8_t, PGM_P message, ...); - - static inline void init() {} - static inline void update() {} - static inline void return_to_status() {} - static inline void set_alert_status_P(PGM_P const) {} - static inline void reset_status(const bool=false) {} - static inline void reset_alert_level() {} - static constexpr bool has_status() { return false; } - - #endif - - #if ENABLED(SDSUPPORT) - #if BOTH(SCROLL_LONG_FILENAMES, HAS_LCD_MENU) - #define MARLINUI_SCROLL_NAME 1 - #endif - #if MARLINUI_SCROLL_NAME - static uint8_t filename_scroll_pos, filename_scroll_max; - #endif - static const char * scrolled_filename(CardReader &theCard, const uint8_t maxlen, uint8_t hash, const bool doScroll); - #endif - - #if PREHEAT_COUNT - static preheat_t material_preset[PREHEAT_COUNT]; - static PGM_P get_preheat_label(const uint8_t m); - #endif - - #if HAS_LCD_MENU - #if LCD_TIMEOUT_TO_STATUS - static millis_t return_to_status_ms; - #endif - - #if HAS_TOUCH_XPT2046 - static uint8_t touch_buttons; - static uint8_t repeat_delay; - #endif - - #if ENABLED(ENCODER_RATE_MULTIPLIER) - static bool encoderRateMultiplierEnabled; - static millis_t lastEncoderMovementMillis; - static void enable_encoder_multiplier(const bool onoff); - #define ENCODER_RATE_MULTIPLY(F) (ui.encoderRateMultiplierEnabled = F) - #else - #define ENCODER_RATE_MULTIPLY(F) NOOP - #endif - - // Manual Movement - static ManualMove manual_move; - - // Select Screen (modal NO/YES style dialog) - static bool selection; - static void set_selection(const bool sel) { selection = sel; } - static bool update_selection(); - - static bool lcd_clicked; - static bool use_click(); - - static void synchronize(PGM_P const msg=nullptr); - - static screenFunc_t currentScreen; - static bool screen_changed; - static void goto_screen(const screenFunc_t screen, const uint16_t encoder=0, const uint8_t top=0, const uint8_t items=0); - static void save_previous_screen(); - - // goto_previous_screen and go_back may also be used as menu item callbacks - static void _goto_previous_screen(TERN_(TURBO_BACK_MENU_ITEM, const bool is_back)); - static inline void goto_previous_screen() { _goto_previous_screen(TERN_(TURBO_BACK_MENU_ITEM, false)); } - static inline void go_back() { _goto_previous_screen(TERN_(TURBO_BACK_MENU_ITEM, true)); } - - static void return_to_status(); - static inline bool on_status_screen() { return currentScreen == status_screen; } - FORCE_INLINE static void run_current_screen() { (*currentScreen)(); } - - #if ENABLED(LIGHTWEIGHT_UI) - static void lcd_in_status(const bool inStatus); - #endif - - FORCE_INLINE static void defer_status_screen(const bool defer=true) { - #if LCD_TIMEOUT_TO_STATUS > 0 - defer_return_to_status = defer; - #else - UNUSED(defer); - #endif - } - - static inline void goto_previous_screen_no_defer() { - defer_status_screen(false); - goto_previous_screen(); - } - - #if ENABLED(SD_REPRINT_LAST_SELECTED_FILE) - static void reselect_last_file(); - #endif - - #if ENABLED(AUTO_BED_LEVELING_UBL) - static void ubl_plot(const uint8_t x_plot, const uint8_t y_plot); - #endif - - static void draw_select_screen_prompt(PGM_P const pref, const char * const string=nullptr, PGM_P const suff=nullptr); - - #elif HAS_WIRED_LCD - - static constexpr bool lcd_clicked = false; - static constexpr bool on_status_screen() { return true; } - FORCE_INLINE static void run_current_screen() { status_screen(); } - - #endif - - // - // EEPROM: Reset / Init / Load / Store - // - #if HAS_LCD_MENU - static void reset_settings(); - #endif - - #if ENABLED(EEPROM_SETTINGS) - #if HAS_LCD_MENU - static void init_eeprom(); - static void load_settings(); - static void store_settings(); - #endif - #if DISABLED(EEPROM_AUTO_INIT) - static void eeprom_alert(const uint8_t msgid); - static inline void eeprom_alert_crc() { eeprom_alert(0); } - static inline void eeprom_alert_index() { eeprom_alert(1); } - static inline void eeprom_alert_version() { eeprom_alert(2); } - #endif - #endif - - // - // Special handling if a move is underway - // - #if EITHER(DELTA_CALIBRATION_MENU, DELTA_AUTO_CALIBRATION) || (ENABLED(LCD_BED_LEVELING) && EITHER(PROBE_MANUALLY, MESH_BED_LEVELING)) - #define LCD_HAS_WAIT_FOR_MOVE 1 - static bool wait_for_move; - #else - static constexpr bool wait_for_move = false; - #endif - - // - // Block interaction while under external control - // - #if HAS_LCD_MENU && EITHER(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; } - #if ENABLED(AUTO_BED_LEVELING_UBL) - static void external_encoder(); - #endif - #else - static constexpr bool external_control = false; - #endif - - #if HAS_ENCODER_ACTION - - static volatile uint8_t buttons; - #if ENABLED(REPRAPWORLD_KEYPAD) - static volatile uint8_t keypad_buttons; - static bool handle_keypad(); - #endif - #if HAS_SLOW_BUTTONS - static volatile uint8_t slow_buttons; - static uint8_t read_slow_buttons(); - #endif - - static void update_buttons(); - static inline bool button_pressed() { return BUTTON_CLICK() || TERN(TOUCH_SCREEN, touch_pressed(), false); } - #if EITHER(AUTO_BED_LEVELING_UBL, G26_MESH_VALIDATION) - static void wait_for_release(); - #endif - - static uint32_t encoderPosition; - - #define ENCODERBASE (TERN(REVERSE_ENCODER_DIRECTION, -1, +1)) - - #if EITHER(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) - encoderDirection = ENCODERBASE; - #endif - } - - FORCE_INLINE static void encoder_direction_menus() { - TERN_(REVERSE_MENU_DIRECTION, encoderDirection = -(ENCODERBASE)); - } - - FORCE_INLINE static void encoder_direction_select() { - TERN_(REVERSE_SELECT_DIRECTION, encoderDirection = -(ENCODERBASE)); - } - - #else - - static inline void update_buttons() {} - - #endif - - #if ENABLED(TOUCH_SCREEN_CALIBRATION) - static void touch_calibration(); - #endif - - #if HAS_GRAPHICAL_TFT - static void move_axis_screen(); - #endif - -private: - - #if HAS_DISPLAY - static void finish_status(const bool persist); - #endif - - #if HAS_WIRED_LCD - #if HAS_LCD_MENU && LCD_TIMEOUT_TO_STATUS > 0 - static bool defer_return_to_status; - #else - static constexpr bool defer_return_to_status = false; - #endif - static void draw_status_screen(); - #if HAS_GRAPHICAL_TFT - static void tft_idle(); - #if ENABLED(TOUCH_SCREEN) - static bool touch_pressed(); - #endif - #endif - #endif -}; - -extern MarlinUI ui; - -#define LCD_MESSAGEPGM_P(x) ui.set_status_P(x) -#define LCD_ALERTMESSAGEPGM_P(x) ui.set_alert_status_P(x) - -#define LCD_MESSAGEPGM(x) LCD_MESSAGEPGM_P(GET_TEXT(x)) -#define LCD_ALERTMESSAGEPGM(x) LCD_ALERTMESSAGEPGM_P(GET_TEXT(x)) diff --git a/Marlin/src/libs/BL24CXX.cpp b/Marlin/src/libs/BL24CXX.cpp index d34ed8340f83..adcd5ed8943a 100644 --- a/Marlin/src/libs/BL24CXX.cpp +++ b/Marlin/src/libs/BL24CXX.cpp @@ -1,6 +1,5 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * This program is free software: you can redistribute it and/or modify @@ -28,7 +27,12 @@ */ #include "BL24CXX.h" -#include +#ifdef __STM32F1__ + #include +#else + #include "../HAL/shared/Delay.h" + #define delay_us(n) DELAY_US(n) +#endif #ifndef EEPROM_WRITE_DELAY #define EEPROM_WRITE_DELAY 10 @@ -38,8 +42,13 @@ #endif // IO direction setting -#define SDA_IN() do{ PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH &= 0XFFFF0FFF; PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH |= 8 << 12; }while(0) -#define SDA_OUT() do{ PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH &= 0XFFFF0FFF; PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH |= 3 << 12; }while(0) +#ifdef __STM32F1__ + #define SDA_IN() do{ PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH &= 0XFFFF0FFF; PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH |= 8 << 12; }while(0) + #define SDA_OUT() do{ PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH &= 0XFFFF0FFF; PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH |= 3 << 12; }while(0) +#elif STM32F1 + #define SDA_IN() SET_INPUT(IIC_EEPROM_SDA) + #define SDA_OUT() SET_OUTPUT(IIC_EEPROM_SDA) +#endif // IO ops #define IIC_SCL_0() WRITE(IIC_EEPROM_SCL, LOW) diff --git a/Marlin/src/libs/L64XX/L64XX_Marlin.cpp b/Marlin/src/libs/L64XX/L64XX_Marlin.cpp index dd85473e9802..876405a40c5f 100644 --- a/Marlin/src/libs/L64XX/L64XX_Marlin.cpp +++ b/Marlin/src/libs/L64XX/L64XX_Marlin.cpp @@ -37,42 +37,46 @@ L64XX_Marlin L64xxManager; #include "../../module/planner.h" #include "../../HAL/shared/Delay.h" -void echo_yes_no(const bool yes) { serialprintPGM(yes ? PSTR(" YES") : PSTR(" NO ")); } - -static const char str_X[] PROGMEM = "X ", str_Y[] PROGMEM = "Y ", str_Z[] PROGMEM = "Z ", +static const char LINEAR_AXIS_LIST( + str_X[] PROGMEM = "X ", str_Y[] PROGMEM = "Y ", str_Z[] PROGMEM = "Z ", + str_I[] PROGMEM = AXIS4_STR " ", str_J[] PROGMEM = AXIS5_STR " ", str_K[] PROGMEM = AXIS6_STR " " + ), str_X2[] PROGMEM = "X2", str_Y2[] PROGMEM = "Y2", str_Z2[] PROGMEM = "Z2", str_Z3[] PROGMEM = "Z3", str_Z4[] PROGMEM = "Z4", - str_E0[] PROGMEM = "E0", str_E1[] PROGMEM = "E1", - str_E2[] PROGMEM = "E2", str_E3[] PROGMEM = "E3", - str_E4[] PROGMEM = "E4", str_E5[] PROGMEM = "E5", - str_E6[] PROGMEM = "E6", str_E7[] PROGMEM = "E7" + LIST_N(EXTRUDERS, + str_E0[] PROGMEM = "E0", str_E1[] PROGMEM = "E1", + str_E2[] PROGMEM = "E2", str_E3[] PROGMEM = "E3", + str_E4[] PROGMEM = "E4", str_E5[] PROGMEM = "E5", + str_E6[] PROGMEM = "E6", str_E7[] PROGMEM = "E7" + ) ; +#define _EN_ITEM(N) , str_E##N PGM_P const L64XX_Marlin::index_to_axis[] PROGMEM = { - str_X, str_Y, str_Z, str_X2, str_Y2, str_Z2, str_Z3, str_Z4, - str_E0, str_E1, str_E2, str_E3, str_E4, str_E5, str_E6, str_E7 + LINEAR_AXIS_LIST(str_X, str_Y, str_Z, str_I, str_J, str_K), + str_X2, str_Y2, str_Z2, str_Z3, str_Z4 + REPEAT(E_STEPPERS, _EN_ITEM) }; +#undef _EN_ITEM #define DEBUG_OUT ENABLED(L6470_CHITCHAT) #include "../../core/debug_out.h" +void echo_yes_no(const bool yes) { DEBUG_ECHOPGM_P(yes ? PSTR(" YES") : PSTR(" NO ")); UNUSED(yes); } + uint8_t L64XX_Marlin::dir_commands[MAX_L64XX]; // array to hold direction command for each driver +#define _EN_ITEM(N) , INVERT_E##N##_DIR const uint8_t L64XX_Marlin::index_to_dir[MAX_L64XX] = { - INVERT_X_DIR, INVERT_Y_DIR, INVERT_Z_DIR - , (INVERT_X_DIR) // X2 - #if ENABLED(X_DUAL_STEPPER_DRIVERS) - ^ (INVERT_X2_VS_X_DIR) - #endif - , (INVERT_Y_DIR) // Y2 - #if ENABLED(Y_DUAL_STEPPER_DRIVERS) - ^ (INVERT_Y2_VS_Y_DIR) - #endif - , INVERT_Z_DIR, INVERT_Z_DIR, INVERT_Z_DIR // Z2,Z3,Z4 - - , INVERT_E0_DIR, INVERT_E1_DIR, INVERT_E2_DIR, INVERT_E3_DIR - , INVERT_E4_DIR, INVERT_E5_DIR, INVERT_E6_DIR, INVERT_E7_DIR + LINEAR_AXIS_LIST(INVERT_X_DIR, INVERT_Y_DIR, INVERT_Z_DIR, INVERT_I_DIR, INVERT_J_DIR, INVERT_K_DIR) + , (INVERT_X_DIR) ^ BOTH(X_DUAL_STEPPER_DRIVERS, INVERT_X2_VS_X_DIR) // X2 + , (INVERT_Y_DIR) ^ BOTH(Y_DUAL_STEPPER_DRIVERS, INVERT_Y2_VS_Y_DIR) // Y2 + , (INVERT_Z_DIR) ^ ENABLED(INVERT_Z2_VS_Z_DIR) // Z2 + , (INVERT_Z_DIR) ^ ENABLED(INVERT_Z3_VS_Z_DIR) // Z3 + , (INVERT_Z_DIR) ^ ENABLED(INVERT_Z4_VS_Z_DIR) // Z4 + REPEAT(E_STEPPERS, _EN_ITEM) }; +#undef _EN_ITEM volatile uint8_t L64XX_Marlin::spi_abort = false; uint8_t L64XX_Marlin::spi_active = false; @@ -331,6 +335,15 @@ void L64XX_Marlin::set_param(const L64XX_axis_t axis, const uint8_t param, const #if AXIS_IS_L64XX(Z) case Z : SET_L6470_PARAM(Z); break; #endif + #if AXIS_IS_L64XX(I) + case I : SET_L6470_PARAM(I); break; + #endif + #if AXIS_IS_L64XX(J) + case J : SET_L6470_PARAM(J); break; + #endif + #if AXIS_IS_L64XX(K) + case K : SET_L6470_PARAM(K); break; + #endif #if AXIS_IS_L64XX(X2) case X2: SET_L6470_PARAM(X2); break; #endif @@ -373,14 +386,13 @@ void L64XX_Marlin::set_param(const L64XX_axis_t axis, const uint8_t param, const } } -inline void echo_min_max(const char a, const float &min, const float &max) { +inline void echo_min_max(const char a, const_float_t min, const_float_t max) { DEBUG_CHAR(' '); DEBUG_CHAR(a); - DEBUG_ECHOPAIR(" min = ", min); - DEBUG_ECHOLNPAIR(" max = ", max); + DEBUG_ECHOLNPAIR(" min = ", min, " max = ", max); } -inline void echo_oct_used(const float &oct, const uint8_t stall) { +inline void echo_oct_used(const_float_t oct, const uint8_t stall) { DEBUG_ECHOPAIR("over_current_threshold used : ", oct); - serialprintPGM(stall ? PSTR(" (Stall") : PSTR(" (OCD")); + DEBUG_ECHOPGM_P(stall ? PSTR(" (Stall") : PSTR(" (OCD")); DEBUG_ECHOLNPGM(" threshold)"); } inline void err_out_of_bounds() { DEBUG_ECHOLNPGM("Test aborted - motion out of bounds"); } @@ -400,7 +412,7 @@ uint8_t L64XX_Marlin::get_user_input(uint8_t &driver_count, L64XX_axis_t axis_in } uint8_t found_displacement = false; - LOOP_XYZE(i) if (uint16_t _displacement = parser.intval(axis_codes[i])) { + LOOP_LOGICAL_AXES(i) if (uint16_t _displacement = parser.intval(axis_codes[i])) { found_displacement = true; displacement = _displacement; uint8_t axis_offset = parser.byteval('J'); @@ -438,10 +450,15 @@ uint8_t L64XX_Marlin::get_user_input(uint8_t &driver_count, L64XX_axis_t axis_in // Position calcs & checks // - const float X_center = LOGICAL_X_POSITION(current_position.x), - Y_center = LOGICAL_Y_POSITION(current_position.y), - Z_center = LOGICAL_Z_POSITION(current_position.z), - E_center = current_position.e; + const float LOGICAL_AXIS_LIST( + E_center = current_position.e, + X_center = LOGICAL_X_POSITION(current_position.x), + Y_center = LOGICAL_Y_POSITION(current_position.y), + Z_center = LOGICAL_Z_POSITION(current_position.z), + I_center = LOGICAL_I_POSITION(current_position.i), + J_center = LOGICAL_J_POSITION(current_position.j), + K_center = LOGICAL_K_POSITION(current_position.k) + ); switch (axis_mon[0][0]) { default: position_max = position_min = 0; break; @@ -450,58 +467,79 @@ uint8_t L64XX_Marlin::get_user_input(uint8_t &driver_count, L64XX_axis_t axis_in position_min = X_center - displacement; position_max = X_center + displacement; echo_min_max('X', position_min, position_max); - if (false - #ifdef X_MIN_POS - || position_min < (X_MIN_POS) - #endif - #ifdef X_MAX_POS - || position_max > (X_MAX_POS) - #endif - ) { + if (TERN0(HAS_ENDSTOPS, position_min < (X_MIN_POS) || position_max > (X_MAX_POS))) { err_out_of_bounds(); return true; } } break; - case 'Y': { - position_min = Y_center - displacement; - position_max = Y_center + displacement; - echo_min_max('Y', position_min, position_max); - if (false - #ifdef Y_MIN_POS - || position_min < (Y_MIN_POS) - #endif - #ifdef Y_MAX_POS - || position_max > (Y_MAX_POS) - #endif - ) { - err_out_of_bounds(); - return true; - } - } break; + #if HAS_Y_AXIS + case 'Y': { + position_min = Y_center - displacement; + position_max = Y_center + displacement; + echo_min_max('Y', position_min, position_max); + if (TERN0(HAS_ENDSTOPS, position_min < (Y_MIN_POS) || position_max > (Y_MAX_POS))) { + err_out_of_bounds(); + return true; + } + } break; + #endif - case 'Z': { - position_min = Z_center - displacement; - position_max = Z_center + displacement; - echo_min_max('Z', position_min, position_max); - if (false - #ifdef Z_MIN_POS - || position_min < (Z_MIN_POS) - #endif - #ifdef Z_MAX_POS - || position_max > (Z_MAX_POS) - #endif - ) { - err_out_of_bounds(); - return true; - } - } break; + #if HAS_Z_AXIS + case 'Z': { + position_min = Z_center - displacement; + position_max = Z_center + displacement; + echo_min_max('Z', position_min, position_max); + if (TERN0(HAS_ENDSTOPS, position_min < (Z_MIN_POS) || position_max > (Z_MAX_POS))) { + err_out_of_bounds(); + return true; + } + } break; + #endif - case 'E': { - position_min = E_center - displacement; - position_max = E_center + displacement; - echo_min_max('E', position_min, position_max); - } break; + #if LINEAR_AXES >= 4 + case AXIS4_NAME: { + position_min = I_center - displacement; + position_max = I_center + displacement; + echo_min_max(AXIS4_NAME, position_min, position_max); + if (TERN0(HAS_ENDSTOPS, position_min < (I_MIN_POS) || position_max > (I_MAX_POS))) { + err_out_of_bounds(); + return true; + } + } break; + #endif + + #if LINEAR_AXES >= 5 + case AXIS5_NAME: { + position_min = J_center - displacement; + position_max = J_center + displacement; + echo_min_max(AXIS5_NAME, position_min, position_max); + if (TERN1(HAS_ENDSTOPS, position_min < (J_MIN_POS) || position_max > (J_MAX_POS))) { + err_out_of_bounds(); + return true; + } + } break; + #endif + + #if LINEAR_AXES >= 6 + case AXIS6_NAME: { + position_min = K_center - displacement; + position_max = K_center + displacement; + echo_min_max(AXIS6_NAME, position_min, position_max); + if (TERN2(HAS_ENDSTOPS, position_min < (K_MIN_POS) || position_max > (K_MAX_POS))) { + err_out_of_bounds(); + return true; + } + } break; + #endif + + #if HAS_EXTRUDERS + case 'E': { + position_min = E_center - displacement; + position_max = E_center + displacement; + echo_min_max('E', position_min, position_max); + } break; + #endif } // @@ -663,7 +701,7 @@ void L64XX_Marlin::say_axis(const L64XX_axis_t axis, const uint8_t label/*=true* ) { say_axis(axis); DEBUG_ECHOPGM(" THERMAL: "); - serialprintPGM((status & _status_axis_th_sd) ? PSTR("SHUTDOWN") : (status & _status_axis_th_wrn) ? PSTR("WARNING ") : PSTR("OK ")); + DEBUG_ECHOPGM_P((status & _status_axis_th_sd) ? PSTR("SHUTDOWN") : (status & _status_axis_th_wrn) ? PSTR("WARNING ") : PSTR("OK ")); DEBUG_ECHOPGM(" OVERCURRENT: "); echo_yes_no((status & _status_axis_ocd) != 0); if (!(_status_axis_layout == L6474_STATUS_LAYOUT)) { // L6474 doesn't have these bits @@ -686,7 +724,7 @@ void L64XX_Marlin::say_axis(const L64XX_axis_t axis, const uint8_t label/*=true* bool L64XX_Marlin::monitor_paused = false; // Flag to skip monitor during M122, M906, M916, M917, M918, etc. struct L6470_driver_data { - uint8_t driver_index; + L64XX_axis_t driver_index; uint32_t driver_status; uint8_t is_otw; uint8_t otw_counter; @@ -697,52 +735,61 @@ void L64XX_Marlin::say_axis(const L64XX_axis_t axis, const uint8_t label/*=true* L6470_driver_data driver_L6470_data[] = { #if AXIS_IS_L64XX(X) - { 0, 0, 0, 0, 0, 0, 0 }, + { X, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(Y) - { 1, 0, 0, 0, 0, 0, 0 }, + { Y, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(Z) - { 2, 0, 0, 0, 0, 0, 0 }, + { Z, 0, 0, 0, 0, 0, 0 }, + #endif + #if AXIS_IS_L64XX(I) + { I, 0, 0, 0, 0, 0, 0 }, + #endif + #if AXIS_IS_L64XX(J) + { J, 0, 0, 0, 0, 0, 0 }, + #endif + #if AXIS_IS_L64XX(K) + { K, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(X2) - { 3, 0, 0, 0, 0, 0, 0 }, + { X2, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(Y2) - { 4, 0, 0, 0, 0, 0, 0 }, + { Y2, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(Z2) - { 5, 0, 0, 0, 0, 0, 0 }, + { Z2, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(Z3) - { 6, 0, 0, 0, 0, 0, 0 }, + { Z3, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(Z4) - { 7, 0, 0, 0, 0, 0, 0 }, + { Z4, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(E0) - { 8, 0, 0, 0, 0, 0, 0 }, + { E0, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(E1) - { 9, 0, 0, 0, 0, 0, 0 }, + { E1, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(E2) - { 10, 0, 0, 0, 0, 0, 0 }, + { E2, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(E3) - { 11, 0, 0, 0, 0, 0, 0 }, + { E3, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(E4) - { 12, 0, 0, 0, 0, 0, 0 }, + { E4, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(E5) - { 13, 0, 0, 0, 0, 0, 0 } + { E5, 0, 0, 0, 0, 0, 0 } #endif #if AXIS_IS_L64XX(E6) - { 14, 0, 0, 0, 0, 0, 0 } + { E6, 0, 0, 0, 0, 0, 0 } #endif #if AXIS_IS_L64XX(E7) - { 16, 0, 0, 0, 0, 0, 0 } + { E7, 0, 0, 0, 0, 0, 0 } #endif }; @@ -889,6 +936,15 @@ void L64XX_Marlin::say_axis(const L64XX_axis_t axis, const uint8_t label/*=true* #if AXIS_IS_L64XX(Z) monitor_update(Z); #endif + #if AXIS_IS_L64XX(I) + monitor_update(I); + #endif + #if AXIS_IS_L64XX(J) + monitor_update(J); + #endif + #if AXIS_IS_L64XX(K) + monitor_update(K); + #endif #if AXIS_IS_L64XX(X2) monitor_update(X2); #endif @@ -922,6 +978,12 @@ void L64XX_Marlin::say_axis(const L64XX_axis_t axis, const uint8_t label/*=true* #if AXIS_IS_L64XX(E5) monitor_update(E5); #endif + #if AXIS_IS_L64XX(E6) + monitor_update(E6); + #endif + #if AXIS_IS_L64XX(E7) + monitor_update(E7); + #endif if (TERN0(L6470_DEBUG, report_L6470_status)) DEBUG_EOL(); diff --git a/Marlin/src/libs/L64XX/L64XX_Marlin.h b/Marlin/src/libs/L64XX/L64XX_Marlin.h index c8d273990f5a..e11d8e872e60 100644 --- a/Marlin/src/libs/L64XX/L64XX_Marlin.h +++ b/Marlin/src/libs/L64XX/L64XX_Marlin.h @@ -35,7 +35,9 @@ #define dSPIN_STEP_CLOCK_REV dSPIN_STEP_CLOCK+1 #define HAS_L64XX_EXTRUDER (AXIS_IS_L64XX(E0) || AXIS_IS_L64XX(E1) || AXIS_IS_L64XX(E2) || AXIS_IS_L64XX(E3) || AXIS_IS_L64XX(E4) || AXIS_IS_L64XX(E5) || AXIS_IS_L64XX(E6) || AXIS_IS_L64XX(E7)) -enum L64XX_axis_t : uint8_t { X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7, MAX_L64XX }; +#define _EN_ITEM(N) , E##N +enum L64XX_axis_t : uint8_t { LINEAR_AXIS_LIST(X, Y, Z, I, J, K), X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM), MAX_L64XX }; +#undef _EN_ITEM class L64XX_Marlin : public L64XXHelper { public: diff --git a/Marlin/src/libs/L64XX/README.md b/Marlin/src/libs/L64XX/README.md index c68d8ca0edbc..d28bec5e67f5 100644 --- a/Marlin/src/libs/L64XX/README.md +++ b/Marlin/src/libs/L64XX/README.md @@ -16,7 +16,7 @@ This software assumes that all drivers are in one SPI daisy chain. - SDO of the last device is tied to MISO of the controller -- All devices share the same `SCK` and `SS_PIN` pins. The user must supply a macro to control the `RESET_PIN`(s). +- All devices share the same `SCK_PIN` and `SS_PIN` pins. The user must supply a macro to control the `RESET_PIN`(s). - Each L6470 passes the data it saw on its SDI to its neighbor on the **NEXT** SPI cycle (8 bit delay). diff --git a/Marlin/src/libs/MAX31865.cpp b/Marlin/src/libs/MAX31865.cpp new file mode 100644 index 000000000000..909adb3807c8 --- /dev/null +++ b/Marlin/src/libs/MAX31865.cpp @@ -0,0 +1,500 @@ +/** + * 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 . + * + */ + +/** + * Based on Based on Adafruit MAX31865 library: + * + * This is a library for the Adafruit PT100/P1000 RTD Sensor w/MAX31865 + * Designed specifically to work with the Adafruit RTD Sensor + * https://www.adafruit.com/products/3328 + * + * This sensor uses SPI to communicate, 4 pins are required to interface. + * + * Adafruit invests time and resources providing this open source code, + * please support Adafruit and open-source hardware by purchasing + * products from Adafruit! + * + * Written by Limor Fried/Ladyada for Adafruit Industries. + * + * Modifications by JoAnn Manges (@GadgetAngel) + * Copyright (c) 2020, JoAnn Manges + * All rights reserved. + */ + +// Useful for RTD debugging. +//#define MAX31865_DEBUG +//#define MAX31865_DEBUG_SPI + +//TODO: switch to SPIclass/SoftSPI + +#include "../inc/MarlinConfig.h" + +#if HAS_MAX31865 && !LIB_USR_MAX31865 + +#include "MAX31865.h" + +// The maximum speed the MAX31865 can do is 5 MHz +SPISettings MAX31865::spiConfig = SPISettings( + #if defined(TARGET_LPC1768) + SPI_QUARTER_SPEED + #elif defined(ARDUINO_ARCH_STM32) + SPI_CLOCK_DIV4 + #else + 500000 + #endif + , MSBFIRST + , SPI_MODE_1 // CPOL0 CPHA1 +); + +#ifndef LARGE_PINMAP + + /** + * Create the interface object using software (bitbang) SPI for PIN values + * less than or equal to 127. + * + * @param spi_cs the SPI CS pin to use + * @param spi_mosi the SPI MOSI pin to use + * @param spi_miso the SPI MISO pin to use + * @param spi_clk the SPI clock pin to use + */ + MAX31865::MAX31865(int8_t spi_cs, int8_t spi_mosi, int8_t spi_miso, int8_t spi_clk) { + _cs = spi_cs; + _mosi = spi_mosi; + _miso = spi_miso; + _sclk = spi_clk; + } + + /** + * Create the interface object using hardware SPI for PIN for PIN values less + * than or equal to 127. + * + * @param spi_cs the SPI CS pin to use along with the default SPI device + */ + MAX31865::MAX31865(int8_t spi_cs) { + _cs = spi_cs; + _sclk = _miso = _mosi = -1; + } + +#else + + /** + * Create the interface object using software (bitbang) SPI for PIN values + * which are larger than 127. If you have PIN values less than or equal to + * 127 use the other call for SW SPI. + * + * @param spi_cs the SPI CS pin to use + * @param spi_mosi the SPI MOSI pin to use + * @param spi_miso the SPI MISO pin to use + * @param spi_clk the SPI clock pin to use + * @param pin_mapping set to 1 for positive pin values + */ + MAX31865::MAX31865(uint32_t spi_cs, uint32_t spi_mosi, + uint32_t spi_miso, uint32_t spi_clk, + uint8_t pin_mapping) { + _cs = spi_cs; + _mosi = spi_mosi; + _miso = spi_miso; + _sclk = spi_clk; + } + + /** + * Create the interface object using hardware SPI for PIN values which are + * larger than 127. If you have PIN values less than or equal to 127 use + * the other call for HW SPI. + * + * @param spi_cs the SPI CS pin to use along with the default SPI device + * @param pin_mapping set to 1 for positive pin values + */ + MAX31865::MAX31865(uint32_t spi_cs, uint8_t pin_mapping) { + _cs = spi_cs; + _sclk = _miso = _mosi = -1UL; //-1UL or 0xFFFFFFFF or 4294967295 + } + +#endif // LARGE_PINMAP + + +/** + * + * Instance & Class methods + * + */ + + +/** + * Initialize the SPI interface and set the number of RTD wires used + * + * @param wires The number of wires in enum format. Can be MAX31865_2WIRE, MAX31865_3WIRE, or MAX31865_4WIRE. + * @param zero The resistance of the RTD at 0 degC, in ohms. + * @param ref The resistance of the reference resistor, in ohms. + */ +void MAX31865::begin(max31865_numwires_t wires, float zero, float ref) { + Rzero = zero; + Rref = ref; + + OUT_WRITE(_cs, HIGH); + + if (_sclk != TERN(LARGE_PINMAP, -1UL, -1)) { + // define pin modes for Software SPI + #ifdef MAX31865_DEBUG + SERIAL_ECHOLN("Initializing MAX31865 Software SPI"); + #endif + + OUT_WRITE(_sclk, LOW); + SET_OUTPUT(_mosi); + SET_INPUT(_miso); + } else { + // start and configure hardware SPI + #ifdef MAX31865_DEBUG + SERIAL_ECHOLN("Initializing MAX31865 Hardware SPI"); + #endif + + SPI.begin(); + } + + setWires(wires); + enableBias(false); + autoConvert(false); + clearFault(); + + #ifdef MAX31865_DEBUG_SPI + #ifndef LARGE_PINMAP + SERIAL_ECHOLNPAIR( + "Regular begin call with _cs: ", _cs, + " _miso: ", _miso, + " _sclk: ", _sclk, + " _mosi: ", _mosi + ); + #else + SERIAL_ECHOLNPAIR( + "LARGE_PINMAP begin call with _cs: ", _cs, + " _miso: ", _miso, + " _sclk: ", _sclk, + " _mosi: ", _mosi + ); + #endif // LARGE_PINMAP + + SERIAL_ECHOLNPAIR("config: ", readRegister8(MAX31856_CONFIG_REG)); + SERIAL_EOL(); + #endif // MAX31865_DEBUG_SPI +} + +/** + * Read the raw 8-bit FAULTSTAT register + * + * @return The raw unsigned 8-bit FAULT status register + */ +uint8_t MAX31865::readFault() { + return readRegister8(MAX31856_FAULTSTAT_REG); +} + +/** + * Clear all faults in FAULTSTAT. + */ +void MAX31865::clearFault() { + setConfig(MAX31856_CONFIG_FAULTSTAT, 1); +} + +/** + * Whether we want to have continuous conversions (50/60 Hz) + * + * @param b If true, auto conversion is enabled + */ +void MAX31865::autoConvert(bool b) { + setConfig(MAX31856_CONFIG_MODEAUTO, b); +} + +/** + * Whether we want filter out 50Hz noise or 60Hz noise + * + * @param b If true, 50Hz noise is filtered, else 60Hz(default) + */ +void MAX31865::enable50HzFilter(bool b) { + setConfig(MAX31856_CONFIG_FILT50HZ, b); +} + +/** + * Enable the bias voltage on the RTD sensor + * + * @param b If true bias is enabled, else disabled + */ +void MAX31865::enableBias(bool b) { + setConfig(MAX31856_CONFIG_BIAS, b); + + // From the datasheet: + // Note that if VBIAS is off (to reduce supply current between conversions), any filter + // capacitors at the RTDIN inputs need to charge before an accurate conversion can be + // performed. Therefore, enable VBIAS and wait at least 10.5 time constants of the input + // RC network plus an additional 1ms before initiating the conversion. + if (b) + DELAY_US(11500); //11.5ms +} + +/** + * Start a one-shot temperature reading. + */ +void MAX31865::oneShot() { + setConfig(MAX31856_CONFIG_1SHOT, 1); + + // From the datasheet: + // Note that a single conversion requires approximately 52ms in 60Hz filter + // mode or 62.5ms in 50Hz filter mode to complete. 1-Shot is a self-clearing bit. + // TODO: switch this out depending on the filter mode. + DELAY_US(65000); // 65ms +} + +/** + * How many wires we have in our RTD setup, can be MAX31865_2WIRE, + * MAX31865_3WIRE, or MAX31865_4WIRE + * + * @param wires The number of wires in enum format + */ +void MAX31865::setWires(max31865_numwires_t wires) { + uint8_t t = readRegister8(MAX31856_CONFIG_REG); + if (wires == MAX31865_3WIRE) + t |= MAX31856_CONFIG_3WIRE; + else // 2 or 4 wire + t &= ~MAX31856_CONFIG_3WIRE; + writeRegister8(MAX31856_CONFIG_REG, t); +} + +/** + * Read the raw 16-bit value from the RTD_REG in one shot mode. This will include + * the fault bit, D0. + * + * @return The raw unsigned 16-bit register value with ERROR bit attached, NOT temperature! + */ +uint16_t MAX31865::readRaw() { + clearFault(); + enableBias(true); + + oneShot(); + uint16_t rtd = readRegister16(MAX31856_RTDMSB_REG); + + #ifdef MAX31865_DEBUG + SERIAL_ECHOLNPAIR("RTD MSB:", (rtd >> 8), " RTD LSB:", (rtd & 0x00FF)); + #endif + + // Disable the bias to lower power dissipation between reads. + // If the ref resistor heats up, the temperature reading will be skewed. + enableBias(false); + + return rtd; +} + +/** + * Calculate and return the resistance value of the connected RTD. + * + * @param refResistor The value of the matching reference resistor, usually 430 or 4300 + * @return The raw RTD resistance value, NOT temperature! + */ +float MAX31865::readResistance() { + // Strip the error bit (D0) and convert to a float ratio. + // less precise method: (readRaw() * Rref) >> 16 + return (((readRaw() >> 1) / 32768.0f) * Rref); +} + +/** + * Read the RTD and pass it to temperature(float) for calculation. + * + * @return Temperature in C + */ +float MAX31865::temperature() { + return temperature(readResistance()); +} + +/** + * Given the 15-bit ADC value, calculate the resistance and pass it to temperature(float) for calculation. + * + * @return Temperature in C + */ +float MAX31865::temperature(uint16_t adcVal) { + return temperature(((adcVal) / 32768.0f) * Rref); +} + +/** + * Calculate the temperature in C from the RTD resistance. + * Uses the technique outlined in this PDF: + * http://www.analog.com/media/en/technical-documentation/application-notes/AN709_0.pdf + * + * @param Rrtd the resistance value in ohms + * @return the temperature in degC + */ +float MAX31865::temperature(float Rrtd) { + float temp = (RTD_Z1 + sqrt(RTD_Z2 + (RTD_Z3 * Rrtd))) / RTD_Z4; + + // From the PDF... + // + // The previous equation is valid only for temperatures of 0°C and above. + // The equation for RRTD(t) that defines negative temperature behavior is a + // fourth-order polynomial (after expanding the third term) and is quite + // impractical to solve for a single expression of temperature as a function + // of resistance. + // + if (temp < 0) { + Rrtd = (Rrtd / Rzero) * 100; // normalize to 100 ohm + float rpoly = Rrtd; + + temp = -242.02 + (2.2228 * rpoly); + rpoly *= Rrtd; // square + temp += 2.5859e-3 * rpoly; + rpoly *= Rrtd; // ^3 + temp -= 4.8260e-6 * rpoly; + rpoly *= Rrtd; // ^4 + temp -= 2.8183e-8 * rpoly; + rpoly *= Rrtd; // ^5 + temp += 1.5243e-10 * rpoly; + } + + return temp; +} + +// +// private: +// + + +/** + * Set a value in the configuration register. + * + * @param config 8-bit value for the config item + * @param enable whether to enable or disable the value + */ +void MAX31865::setConfig(uint8_t config, bool enable) { + uint8_t t = readRegister8(MAX31856_CONFIG_REG); + if (enable) + t |= config; + else + t &= ~config; // disable + writeRegister8(MAX31856_CONFIG_REG, t); +} + +/** + * Read a single byte from the specified register address. + * + * @param addr the register address + * @return the register contents + */ +uint8_t MAX31865::readRegister8(uint8_t addr) { + uint8_t ret = 0; + readRegisterN(addr, &ret, 1); + + return ret; +} + +/** + * Read two bytes: 1 from the specified register address, and 1 from the next address. + * + * @param addr the first register address + * @return both register contents as a single 16-bit int + */ +uint16_t MAX31865::readRegister16(uint8_t addr) { + uint8_t buffer[2] = {0, 0}; + readRegisterN(addr, buffer, 2); + + uint16_t ret = buffer[0]; + ret <<= 8; + ret |= buffer[1]; + + return ret; +} + +/** + * Read +n+ bytes from a specified address into +buffer+. Set D7 to 0 to specify a read. + * + * @param addr the first register address + * @param buffer storage for the read bytes + * @param n the number of bytes to read + */ +void MAX31865::readRegisterN(uint8_t addr, uint8_t buffer[], uint8_t n) { + addr &= 0x7F; // make sure top bit is not set + if (_sclk == TERN(LARGE_PINMAP, -1UL, -1)) + SPI.beginTransaction(spiConfig); + else + WRITE(_sclk, LOW); + + WRITE(_cs, LOW); + spixfer(addr); + + while (n--) { + buffer[0] = spixfer(0xFF); + #ifdef MAX31865_DEBUG_SPI + SERIAL_ECHOLNPAIR("buffer read ", n, " data: ", buffer[0]); + #endif + buffer++; + } + + if (_sclk == TERN(LARGE_PINMAP, -1UL, -1)) + SPI.endTransaction(); + + WRITE(_cs, HIGH); +} + +/** + * Write an 8-bit value to a register. Set D7 to 1 to specify a write. + * + * @param addr the address to write to + * @param data the data to write + */ +void MAX31865::writeRegister8(uint8_t addr, uint8_t data) { + if (_sclk == TERN(LARGE_PINMAP, -1UL, -1)) + SPI.beginTransaction(spiConfig); + else + WRITE(_sclk, LOW); + + WRITE(_cs, LOW); + + spixfer(addr | 0x80); // make sure top bit is set + spixfer(data); + + if (_sclk == TERN(LARGE_PINMAP, -1UL, -1)) + SPI.endTransaction(); + + WRITE(_cs, HIGH); +} + +/** + * Transfer SPI data +x+ and read the response. From the datasheet... + * Input data (SDI) is latched on the internal strobe edge and output data (SDO) is + * shifted out on the shift edge. There is one clock for each bit transferred. + * Address and data bits are transferred in groups of eight, MSB first. + * + * @param x an 8-bit chunk of data to write + * @return the 8-bit response + */ +uint8_t MAX31865::spixfer(uint8_t x) { + if (_sclk == TERN(LARGE_PINMAP, -1UL, -1)) + return SPI.transfer(x); + + uint8_t reply = 0; + for (int i = 7; i >= 0; i--) { + reply <<= 1; + WRITE(_sclk, HIGH); + WRITE(_mosi, x & (1 << i)); + WRITE(_sclk, LOW); + if (READ(_miso)) + reply |= 1; + } + + return reply; +} + +#endif // HAS_MAX31865 && !LIB_USR_MAX31865 diff --git a/Marlin/src/libs/MAX31865.h b/Marlin/src/libs/MAX31865.h new file mode 100644 index 000000000000..5d50e870ecd2 --- /dev/null +++ b/Marlin/src/libs/MAX31865.h @@ -0,0 +1,131 @@ +/** + * 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 . + * + */ + +/** + * Based on Adafruit MAX31865 library: + * + * This is a library for the Adafruit PT100/P1000 RTD Sensor w/MAX31865 + * Designed specifically to work with the Adafruit RTD Sensor + * https://www.adafruit.com/products/3328 + * + * This sensor uses SPI to communicate, 4 pins are required to interface. + * + * Adafruit invests time and resources providing this open source code, + * please support Adafruit and open-source hardware by purchasing + * products from Adafruit! + * + * Written by Limor Fried/Ladyada for Adafruit Industries. + * + * Modifications by JoAnn Manges (@GadgetAngel) + * Copyright (c) 2020, JoAnn Manges + * All rights reserved. + */ +#pragma once + +#include "../inc/MarlinConfig.h" +#include "../HAL/shared/Delay.h" +#include HAL_PATH(../HAL, MarlinSPI.h) + +#define MAX31856_CONFIG_REG 0x00 +#define MAX31856_CONFIG_BIAS 0x80 +#define MAX31856_CONFIG_MODEAUTO 0x40 +#define MAX31856_CONFIG_MODEOFF 0x00 +#define MAX31856_CONFIG_1SHOT 0x20 +#define MAX31856_CONFIG_3WIRE 0x10 +#define MAX31856_CONFIG_24WIRE 0x00 +#define MAX31856_CONFIG_FAULTSTAT 0x02 +#define MAX31856_CONFIG_FILT50HZ 0x01 +#define MAX31856_CONFIG_FILT60HZ 0x00 + +#define MAX31856_RTDMSB_REG 0x01 +#define MAX31856_RTDLSB_REG 0x02 +#define MAX31856_HFAULTMSB_REG 0x03 +#define MAX31856_HFAULTLSB_REG 0x04 +#define MAX31856_LFAULTMSB_REG 0x05 +#define MAX31856_LFAULTLSB_REG 0x06 +#define MAX31856_FAULTSTAT_REG 0x07 + +#define MAX31865_FAULT_HIGHTHRESH 0x80 // D7 +#define MAX31865_FAULT_LOWTHRESH 0x40 // D6 +#define MAX31865_FAULT_REFINLOW 0x20 // D5 +#define MAX31865_FAULT_REFINHIGH 0x10 // D4 +#define MAX31865_FAULT_RTDINLOW 0x08 // D3 +#define MAX31865_FAULT_OVUV 0x04 // D2 + +// http://www.analog.com/media/en/technical-documentation/application-notes/AN709_0.pdf +// constants for calculating temperature from the measured RTD resistance. +#define RTD_Z1 -0.0039083 +#define RTD_Z2 0.00001758480889 +#define RTD_Z3 -0.0000000231 +#define RTD_Z4 -0.000001155 + +typedef enum max31865_numwires { + MAX31865_2WIRE = 0, + MAX31865_3WIRE = 1, + MAX31865_4WIRE = 0 +} max31865_numwires_t; + +/* Interface class for the MAX31865 RTD Sensor reader */ +class MAX31865 { +private: + static SPISettings spiConfig; + + TERN(LARGE_PINMAP, uint32_t, uint8_t) _sclk, _miso, _mosi, _cs; + float Rzero, Rref; + + void setConfig(uint8_t config, bool enable); + + void readRegisterN(uint8_t addr, uint8_t buffer[], uint8_t n); + uint8_t readRegister8(uint8_t addr); + uint16_t readRegister16(uint8_t addr); + + void writeRegister8(uint8_t addr, uint8_t reg); + uint8_t spixfer(uint8_t addr); + +public: + #ifdef LARGE_PINMAP + MAX31865(uint32_t spi_cs, uint8_t pin_mapping); + MAX31865(uint32_t spi_cs, uint32_t spi_mosi, uint32_t spi_miso, + uint32_t spi_clk, uint8_t pin_mapping); + #else + MAX31865(int8_t spi_cs); + MAX31865(int8_t spi_cs, int8_t spi_mosi, int8_t spi_miso, + int8_t spi_clk); + #endif + + void begin(max31865_numwires_t wires, float zero, float ref); + + uint8_t readFault(); + void clearFault(); + + void setWires(max31865_numwires_t wires); + void autoConvert(bool b); + void enable50HzFilter(bool b); + void enableBias(bool b); + void oneShot(); + + uint16_t readRaw(); + float readResistance(); + float temperature(); + float temperature(uint16_t adcVal); + float temperature(float Rrtd); +}; diff --git a/Marlin/src/libs/W25Qxx.cpp b/Marlin/src/libs/W25Qxx.cpp index 03e002f66f82..56581ed46eb7 100644 --- a/Marlin/src/libs/W25Qxx.cpp +++ b/Marlin/src/libs/W25Qxx.cpp @@ -25,7 +25,6 @@ #if HAS_SPI_FLASH #include "W25Qxx.h" -#include W25QXXFlash W25QXX; @@ -41,10 +40,17 @@ W25QXXFlash W25QXX; #ifndef SPI_FLASH_CS_PIN #define SPI_FLASH_CS_PIN W25QXX_CS_PIN #endif +#ifndef NC + #define NC -1 +#endif + +MarlinSPI W25QXXFlash::mySPI(SPI_FLASH_MOSI_PIN, SPI_FLASH_MISO_PIN, SPI_FLASH_SCK_PIN, NC); #define W25QXX_CS_H OUT_WRITE(SPI_FLASH_CS_PIN, HIGH) #define W25QXX_CS_L OUT_WRITE(SPI_FLASH_CS_PIN, LOW) +bool flash_dma_mode = true; + void W25QXXFlash::init(uint8_t spiRate) { OUT_WRITE(SPI_FLASH_CS_PIN, HIGH); @@ -69,11 +75,11 @@ void W25QXXFlash::init(uint8_t spiRate) { case SPI_SPEED_6: clock = SPI_CLOCK_DIV64; break; default: clock = SPI_CLOCK_DIV2;// Default from the SPI library } - SPI.setModule(SPI_DEVICE); - SPI.begin(); - SPI.setClockDivider(clock); - SPI.setBitOrder(MSBFIRST); - SPI.setDataMode(SPI_MODE0); + + mySPI.setClockDivider(clock); + mySPI.setBitOrder(MSBFIRST); + mySPI.setDataMode(SPI_MODE0); + mySPI.begin(); } /** @@ -82,12 +88,12 @@ void W25QXXFlash::init(uint8_t spiRate) { * @return Byte received */ uint8_t W25QXXFlash::spi_flash_Rec() { - const uint8_t returnByte = SPI.transfer(0xFF); + const uint8_t returnByte = mySPI.transfer(0xFF); return returnByte; } uint8_t W25QXXFlash::spi_flash_read_write_byte(uint8_t data) { - const uint8_t returnByte = SPI.transfer(data); + const uint8_t returnByte = mySPI.transfer(data); return returnByte; } @@ -100,7 +106,9 @@ uint8_t W25QXXFlash::spi_flash_read_write_byte(uint8_t data) { * * @details Uses DMA */ -void W25QXXFlash::spi_flash_Read(uint8_t* buf, uint16_t nbyte) { SPI.dmaTransfer(0, const_cast(buf), nbyte); } +void W25QXXFlash::spi_flash_Read(uint8_t *buf, uint16_t nbyte) { + mySPI.dmaTransfer(0, const_cast(buf), nbyte); +} /** * @brief Send a single byte on SPI port @@ -109,7 +117,7 @@ void W25QXXFlash::spi_flash_Read(uint8_t* buf, uint16_t nbyte) { SPI.dmaTransfer * * @details */ -void W25QXXFlash::spi_flash_Send(uint8_t b) { SPI.send(b); } +void W25QXXFlash::spi_flash_Send(uint8_t b) { mySPI.transfer(b); } /** * @brief Write token and then write from 512 byte buffer to SPI (for SD card) @@ -119,9 +127,9 @@ void W25QXXFlash::spi_flash_Send(uint8_t b) { SPI.send(b); } * * @details Use DMA */ -void W25QXXFlash::spi_flash_SendBlock(uint8_t token, const uint8_t* buf) { - SPI.send(token); - SPI.dmaSend(const_cast(buf), 512); +void W25QXXFlash::spi_flash_SendBlock(uint8_t token, const uint8_t *buf) { + mySPI.transfer(token); + mySPI.dmaSend(const_cast(buf), 512); } uint16_t W25QXXFlash::W25QXX_ReadID(void) { @@ -138,19 +146,19 @@ uint16_t W25QXXFlash::W25QXX_ReadID(void) { } void W25QXXFlash::SPI_FLASH_WriteEnable(void) { - /* Select the FLASH: Chip Select low */ + // Select the FLASH: Chip Select low W25QXX_CS_L; - /* Send "Write Enable" instruction */ + // Send "Write Enable" instruction spi_flash_Send(W25X_WriteEnable); - /* Deselect the FLASH: Chip Select high */ + // Deselect the FLASH: Chip Select high W25QXX_CS_H; } /******************************************************************************* * Function Name : SPI_FLASH_WaitForWriteEnd * Description : Polls the status of the Write In Progress (WIP) flag in the -* FLASH's status register and loop until write opertaion -* has completed. +* FLASH's status register and loop until write operation has +* completed. * Input : None * Output : None * Return : None @@ -158,54 +166,54 @@ void W25QXXFlash::SPI_FLASH_WriteEnable(void) { void W25QXXFlash::SPI_FLASH_WaitForWriteEnd(void) { uint8_t FLASH_Status = 0; - /* Select the FLASH: Chip Select low */ + // Select the FLASH: Chip Select low W25QXX_CS_L; - /* Send "Read Status Register" instruction */ + // Send "Read Status Register" instruction spi_flash_Send(W25X_ReadStatusReg); - /* Loop as long as the memory is busy with a write cycle */ + // Loop as long as the memory is busy with a write cycle do /* Send a dummy byte to generate the clock needed by the FLASH and put the value of the status register in FLASH_Status variable */ FLASH_Status = spi_flash_Rec(); - while ((FLASH_Status & WIP_Flag) == 0x01); /* Write in progress */ + while ((FLASH_Status & WIP_Flag) == 0x01); // Write in progress - /* Deselect the FLASH: Chip Select high */ + // Deselect the FLASH: Chip Select high W25QXX_CS_H; } void W25QXXFlash::SPI_FLASH_SectorErase(uint32_t SectorAddr) { - /* Send write enable instruction */ + // Send write enable instruction SPI_FLASH_WriteEnable(); - /* Sector Erase */ - /* Select the FLASH: Chip Select low */ + // Sector Erase + // Select the FLASH: Chip Select low W25QXX_CS_L; - /* Send Sector Erase instruction */ + // Send Sector Erase instruction spi_flash_Send(W25X_SectorErase); - /* Send SectorAddr high nibble address byte */ + // Send SectorAddr high nybble address byte spi_flash_Send((SectorAddr & 0xFF0000) >> 16); - /* Send SectorAddr medium nibble address byte */ + // Send SectorAddr medium nybble address byte spi_flash_Send((SectorAddr & 0xFF00) >> 8); - /* Send SectorAddr low nibble address byte */ + // Send SectorAddr low nybble address byte spi_flash_Send(SectorAddr & 0xFF); - /* Deselect the FLASH: Chip Select high */ + // Deselect the FLASH: Chip Select high W25QXX_CS_H; - /* Wait the end of Flash writing */ + // Wait the end of Flash writing SPI_FLASH_WaitForWriteEnd(); } void W25QXXFlash::SPI_FLASH_BlockErase(uint32_t BlockAddr) { SPI_FLASH_WriteEnable(); W25QXX_CS_L; - /* Send Sector Erase instruction */ + // Send Sector Erase instruction spi_flash_Send(W25X_BlockErase); - /* Send SectorAddr high nibble address byte */ + // Send SectorAddr high nybble address byte spi_flash_Send((BlockAddr & 0xFF0000) >> 16); - /* Send SectorAddr medium nibble address byte */ + // Send SectorAddr medium nybble address byte spi_flash_Send((BlockAddr & 0xFF00) >> 8); - /* Send SectorAddr low nibble address byte */ + // Send SectorAddr low nybble address byte spi_flash_Send(BlockAddr & 0xFF); W25QXX_CS_H; @@ -221,18 +229,18 @@ void W25QXXFlash::SPI_FLASH_BlockErase(uint32_t BlockAddr) { * Return : None *******************************************************************************/ void W25QXXFlash::SPI_FLASH_BulkErase(void) { - /* Send write enable instruction */ + // Send write enable instruction SPI_FLASH_WriteEnable(); - /* Bulk Erase */ - /* Select the FLASH: Chip Select low */ + // Bulk Erase + // Select the FLASH: Chip Select low W25QXX_CS_L; - /* Send Bulk Erase instruction */ + // Send Bulk Erase instruction spi_flash_Send(W25X_ChipErase); - /* Deselect the FLASH: Chip Select high */ + // Deselect the FLASH: Chip Select high W25QXX_CS_H; - /* Wait the end of Flash writing */ + // Wait the end of Flash writing SPI_FLASH_WaitForWriteEnd(); } @@ -249,35 +257,35 @@ void W25QXXFlash::SPI_FLASH_BulkErase(void) { * Output : None * Return : None *******************************************************************************/ -void W25QXXFlash::SPI_FLASH_PageWrite(uint8_t* pBuffer, uint32_t WriteAddr, uint16_t NumByteToWrite) { - /* Enable the write access to the FLASH */ +void W25QXXFlash::SPI_FLASH_PageWrite(uint8_t *pBuffer, uint32_t WriteAddr, uint16_t NumByteToWrite) { + // Enable the write access to the FLASH SPI_FLASH_WriteEnable(); - /* Select the FLASH: Chip Select low */ + // Select the FLASH: Chip Select low W25QXX_CS_L; - /* Send "Write to Memory " instruction */ + // Send "Write to Memory " instruction spi_flash_Send(W25X_PageProgram); - /* Send WriteAddr high nibble address byte to write to */ + // Send WriteAddr high nybble address byte to write to spi_flash_Send((WriteAddr & 0xFF0000) >> 16); - /* Send WriteAddr medium nibble address byte to write to */ + // Send WriteAddr medium nybble address byte to write to spi_flash_Send((WriteAddr & 0xFF00) >> 8); - /* Send WriteAddr low nibble address byte to write to */ + // Send WriteAddr low nybble address byte to write to spi_flash_Send(WriteAddr & 0xFF); NOMORE(NumByteToWrite, SPI_FLASH_PerWritePageSize); - /* while there is data to be written on the FLASH */ + // While there is data to be written on the FLASH while (NumByteToWrite--) { - /* Send the current byte */ + // Send the current byte spi_flash_Send(*pBuffer); - /* Point on the next byte to be written */ + // Point on the next byte to be written pBuffer++; } - /* Deselect the FLASH: Chip Select high */ + // Deselect the FLASH: Chip Select high W25QXX_CS_H; - /* Wait the end of Flash writing */ + // Wait the end of Flash writing SPI_FLASH_WaitForWriteEnd(); } @@ -292,7 +300,7 @@ void W25QXXFlash::SPI_FLASH_PageWrite(uint8_t* pBuffer, uint32_t WriteAddr, uint * Output : None * Return : None *******************************************************************************/ -void W25QXXFlash::SPI_FLASH_BufferWrite(uint8_t* pBuffer, uint32_t WriteAddr, uint16_t NumByteToWrite) { +void W25QXXFlash::SPI_FLASH_BufferWrite(uint8_t *pBuffer, uint32_t WriteAddr, uint16_t NumByteToWrite) { uint8_t NumOfPage = 0, NumOfSingle = 0, Addr = 0, count = 0, temp = 0; Addr = WriteAddr % SPI_FLASH_PageSize; @@ -300,11 +308,11 @@ void W25QXXFlash::SPI_FLASH_BufferWrite(uint8_t* pBuffer, uint32_t WriteAddr, ui NumOfPage = NumByteToWrite / SPI_FLASH_PageSize; NumOfSingle = NumByteToWrite % SPI_FLASH_PageSize; - if (Addr == 0) { /* WriteAddr is SPI_FLASH_PageSize aligned */ - if (NumOfPage == 0) { /* NumByteToWrite < SPI_FLASH_PageSize */ + if (Addr == 0) { // WriteAddr is SPI_FLASH_PageSize aligned + if (NumOfPage == 0) { // NumByteToWrite < SPI_FLASH_PageSize SPI_FLASH_PageWrite(pBuffer, WriteAddr, NumByteToWrite); } - else { /* NumByteToWrite > SPI_FLASH_PageSize */ + else { // NumByteToWrite > SPI_FLASH_PageSize while (NumOfPage--) { SPI_FLASH_PageWrite(pBuffer, WriteAddr, SPI_FLASH_PageSize); WriteAddr += SPI_FLASH_PageSize; @@ -313,20 +321,19 @@ void W25QXXFlash::SPI_FLASH_BufferWrite(uint8_t* pBuffer, uint32_t WriteAddr, ui SPI_FLASH_PageWrite(pBuffer, WriteAddr, NumOfSingle); } } - else { /* WriteAddr is not SPI_FLASH_PageSize aligned */ - if (NumOfPage == 0) { /* NumByteToWrite < SPI_FLASH_PageSize */ - if (NumOfSingle > count) { /* (NumByteToWrite + WriteAddr) > SPI_FLASH_PageSize */ + else { // WriteAddr is not SPI_FLASH_PageSize aligned + if (NumOfPage == 0) { // NumByteToWrite < SPI_FLASH_PageSize + if (NumOfSingle > count) { // (NumByteToWrite + WriteAddr) > SPI_FLASH_PageSize temp = NumOfSingle - count; SPI_FLASH_PageWrite(pBuffer, WriteAddr, count); WriteAddr += count; pBuffer += count; SPI_FLASH_PageWrite(pBuffer, WriteAddr, temp); } - else { + else SPI_FLASH_PageWrite(pBuffer, WriteAddr, NumByteToWrite); - } } - else { /* NumByteToWrite > SPI_FLASH_PageSize */ + else { // NumByteToWrite > SPI_FLASH_PageSize NumByteToWrite -= count; NumOfPage = NumByteToWrite / SPI_FLASH_PageSize; NumOfSingle = NumByteToWrite % SPI_FLASH_PageSize; @@ -357,31 +364,31 @@ void W25QXXFlash::SPI_FLASH_BufferWrite(uint8_t* pBuffer, uint32_t WriteAddr, ui * Output : None * Return : None *******************************************************************************/ -void W25QXXFlash::SPI_FLASH_BufferRead(uint8_t* pBuffer, uint32_t ReadAddr, uint16_t NumByteToRead) { - /* Select the FLASH: Chip Select low */ +void W25QXXFlash::SPI_FLASH_BufferRead(uint8_t *pBuffer, uint32_t ReadAddr, uint16_t NumByteToRead) { + // Select the FLASH: Chip Select low W25QXX_CS_L; - /* Send "Read from Memory " instruction */ + // Send "Read from Memory " instruction spi_flash_Send(W25X_ReadData); - /* Send ReadAddr high nibble address byte to read from */ + // Send ReadAddr high nybble address byte to read from spi_flash_Send((ReadAddr & 0xFF0000) >> 16); - /* Send ReadAddr medium nibble address byte to read from */ + // Send ReadAddr medium nybble address byte to read from spi_flash_Send((ReadAddr & 0xFF00) >> 8); - /* Send ReadAddr low nibble address byte to read from */ + // Send ReadAddr low nybble address byte to read from spi_flash_Send(ReadAddr & 0xFF); - if (NumByteToRead < 33) { - while (NumByteToRead--) { /* while there is data to be read */ - /* Read a byte from the FLASH */ + if (NumByteToRead <= 32 || !flash_dma_mode) { + while (NumByteToRead--) { // While there is data to be read + // Read a byte from the FLASH *pBuffer = spi_flash_Rec(); - /* Point to the next location where the byte read will be saved */ + // Point to the next location where the byte read will be saved pBuffer++; } } - else { + else spi_flash_Read(pBuffer, NumByteToRead); - } + W25QXX_CS_H; } diff --git a/Marlin/src/libs/W25Qxx.h b/Marlin/src/libs/W25Qxx.h index ac3e8a169b24..1133af2e74dd 100644 --- a/Marlin/src/libs/W25Qxx.h +++ b/Marlin/src/libs/W25Qxx.h @@ -23,6 +23,8 @@ #include +#include HAL_PATH(../HAL, MarlinSPI.h) + #define W25X_WriteEnable 0x06 #define W25X_WriteDisable 0x04 #define W25X_ReadStatusReg 0x05 @@ -49,22 +51,24 @@ #define SPI_FLASH_PerWritePageSize 256 class W25QXXFlash { +private: + static MarlinSPI mySPI; public: void init(uint8_t spiRate); static uint8_t spi_flash_Rec(); static uint8_t spi_flash_read_write_byte(uint8_t data); - static void spi_flash_Read(uint8_t* buf, uint16_t nbyte); + static void spi_flash_Read(uint8_t *buf, uint16_t nbyte); static void spi_flash_Send(uint8_t b); - static void spi_flash_SendBlock(uint8_t token, const uint8_t* buf); + static void spi_flash_SendBlock(uint8_t token, const uint8_t *buf); static uint16_t W25QXX_ReadID(void); static void SPI_FLASH_WriteEnable(void); static void SPI_FLASH_WaitForWriteEnd(void); static void SPI_FLASH_SectorErase(uint32_t SectorAddr); static void SPI_FLASH_BlockErase(uint32_t BlockAddr); static void SPI_FLASH_BulkErase(void); - static void SPI_FLASH_PageWrite(uint8_t* pBuffer, uint32_t WriteAddr, uint16_t NumByteToWrite); - static void SPI_FLASH_BufferWrite(uint8_t* pBuffer, uint32_t WriteAddr, uint16_t NumByteToWrite); - static void SPI_FLASH_BufferRead(uint8_t* pBuffer, uint32_t ReadAddr, uint16_t NumByteToRead); + static void SPI_FLASH_PageWrite(uint8_t *pBuffer, uint32_t WriteAddr, uint16_t NumByteToWrite); + static void SPI_FLASH_BufferWrite(uint8_t *pBuffer, uint32_t WriteAddr, uint16_t NumByteToWrite); + static void SPI_FLASH_BufferRead(uint8_t *pBuffer, uint32_t ReadAddr, uint16_t NumByteToRead); }; extern W25QXXFlash W25QXX; diff --git a/Marlin/src/libs/autoreport.h b/Marlin/src/libs/autoreport.h new file mode 100644 index 000000000000..a6bc5adbf770 --- /dev/null +++ b/Marlin/src/libs/autoreport.h @@ -0,0 +1,50 @@ +/** + * 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 + +#include "../inc/MarlinConfig.h" + +template +struct AutoReporter { + millis_t next_report_ms; + uint8_t report_interval; + #if HAS_MULTI_SERIAL + SerialMask report_port_mask; + AutoReporter() : report_port_mask(SerialMask::All) {} + #endif + + inline void set_interval(uint8_t seconds, const uint8_t limit=60) { + report_interval = _MIN(seconds, limit); + next_report_ms = millis() + SEC_TO_MS(seconds); + } + + inline void tick() { + if (!report_interval) return; + const millis_t ms = millis(); + if (ELAPSED(ms, next_report_ms)) { + next_report_ms = ms + SEC_TO_MS(report_interval); + PORT_REDIRECT(report_port_mask); + Helper::report(); + //PORT_RESTORE(); + } + } +}; diff --git a/Marlin/src/libs/bresenham.h b/Marlin/src/libs/bresenham.h index ade231e26dc7..6e4162fd1364 100644 --- a/Marlin/src/libs/bresenham.h +++ b/Marlin/src/libs/bresenham.h @@ -120,7 +120,7 @@ class Bresenham { static void report(const uint8_t index) { if (index < Cfg::SIZE) { - SERIAL_ECHOPAIR("bresenham ", int(index), " : (", dividend[index], "/", divisor, ") "); + SERIAL_ECHOPAIR("bresenham ", index, " : (", dividend[index], "/", divisor, ") "); if (counter[index] >= 0) SERIAL_CHAR(' '); if (labs(counter[index]) < 100) { SERIAL_CHAR(' '); if (labs(counter[index]) < 10) SERIAL_CHAR(' '); } SERIAL_ECHO(counter[index]); diff --git a/Marlin/src/libs/buzzer.cpp b/Marlin/src/libs/buzzer.cpp index 84596953596c..57ed5fb41910 100644 --- a/Marlin/src/libs/buzzer.cpp +++ b/Marlin/src/libs/buzzer.cpp @@ -26,6 +26,7 @@ #include "buzzer.h" #include "../module/temperature.h" +#include "../lcd/marlinui.h" #if ENABLED(EXTENSIBLE_UI) #include "../lcd/extui/ui_api.h" @@ -44,6 +45,7 @@ Buzzer buzzer; * @param frequency Frequency of the tone in hertz */ void Buzzer::tone(const uint16_t duration, const uint16_t frequency/*=0*/) { + if (!ui.buzzer_enabled) return; while (buffer.isFull()) { tick(); thermalManager.manage_heater(); @@ -53,6 +55,7 @@ void Buzzer::tone(const uint16_t duration, const uint16_t frequency/*=0*/) { } void Buzzer::tick() { + if (!ui.buzzer_enabled) return; const millis_t now = millis(); if (!state.endtime) { @@ -62,12 +65,11 @@ void Buzzer::tick() { state.endtime = now + state.tone.duration; if (state.tone.frequency > 0) { - #if ENABLED(EXTENSIBLE_UI) + #if ENABLED(EXTENSIBLE_UI) && DISABLED(EXTUI_LOCAL_BEEPER) CRITICAL_SECTION_START(); ExtUI::onPlayTone(state.tone.frequency, state.tone.duration); CRITICAL_SECTION_END(); - #endif - #if ENABLED(SPEAKER) && (DISABLED(EXTENSIBLE_UI) || ENABLED(EXTUI_LOCAL_BEEPER)) + #elif ENABLED(SPEAKER) CRITICAL_SECTION_START(); ::tone(BEEPER_PIN, state.tone.frequency, state.tone.duration); CRITICAL_SECTION_END(); diff --git a/Marlin/src/libs/buzzer.h b/Marlin/src/libs/buzzer.h index e901660c87d1..21b69002ffd3 100644 --- a/Marlin/src/libs/buzzer.h +++ b/Marlin/src/libs/buzzer.h @@ -56,7 +56,7 @@ static CircularQueue buffer; /** - * @brief Inverts the sate of a digital PIN + * @brief Inverts the state of a digital PIN * @details This will invert the current state of an digital IO pin. */ FORCE_INLINE static void invert() { TOGGLE(BEEPER_PIN); } @@ -118,6 +118,7 @@ #elif HAS_BUZZER // Buzz indirectly via the MarlinUI instance + #include "../lcd/marlinui.h" #define BUZZ(d,f) ui.buzz(d,f) #else diff --git a/Marlin/src/libs/duration_t.h b/Marlin/src/libs/duration_t.h index 31d8bab38581..4d722a296c92 100644 --- a/Marlin/src/libs/duration_t.h +++ b/Marlin/src/libs/duration_t.h @@ -106,11 +106,17 @@ struct duration_t { return this->value; } + #if GCC_VERSION <= 50000 + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wformat-overflow" + #endif + /** * @brief Formats the duration as a string - * @details String will be formated using a "full" representation of duration + * @details String will be formatted using a "full" representation of duration * - * @param buffer The array pointed to must be able to accommodate 21 bytes + * @param buffer The array pointed to must be able to accommodate 22 bytes + * (21 for the string, 1 more for the terminating nul) * * Output examples: * 123456789012345678901 (strlen) @@ -127,7 +133,7 @@ struct duration_t { m = this->minute() % 60, s = this->second() % 60; - if (y) sprintf_P(buffer, PSTR("%iy %id %ih %im %is"), y, d, h, m, s); + 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); @@ -137,7 +143,7 @@ struct duration_t { /** * @brief Formats the duration as a string - * @details String will be formated using a "digital" representation of duration + * @details String will be formatted using a "digital" representation of duration * * @param buffer The array pointed to must be able to accommodate 10 bytes * @@ -163,4 +169,8 @@ struct duration_t { return 6; } } + + #if GCC_VERSION <= 50000 + #pragma GCC diagnostic pop + #endif }; diff --git a/Marlin/src/libs/heatshrink/heatshrink_common.h b/Marlin/src/libs/heatshrink/heatshrink_common.h index c8dc95406e90..68653e4793c1 100644 --- a/Marlin/src/libs/heatshrink/heatshrink_common.h +++ b/Marlin/src/libs/heatshrink/heatshrink_common.h @@ -4,7 +4,7 @@ #pragma once #define HEATSHRINK_AUTHOR "Scott Vokes " -#define HEATSHRINK_URL "https://github.com/atomicobject/heatshrink" +#define HEATSHRINK_URL "github.com/atomicobject/heatshrink" /* Version 0.4.1 */ #define HEATSHRINK_VERSION_MAJOR 0 diff --git a/Marlin/src/libs/heatshrink/heatshrink_decoder.cpp b/Marlin/src/libs/heatshrink/heatshrink_decoder.cpp index 3f0f828cd78b..073a7ed0b6ec 100644 --- a/Marlin/src/libs/heatshrink/heatshrink_decoder.cpp +++ b/Marlin/src/libs/heatshrink/heatshrink_decoder.cpp @@ -89,7 +89,7 @@ heatshrink_decoder *heatshrink_decoder_alloc(uint16_t input_buffer_size, uint8_t size_t buffers_sz = (1 << window_sz2) + input_buffer_size; size_t sz = sizeof(heatshrink_decoder) + buffers_sz; heatshrink_decoder *hsd = HEATSHRINK_MALLOC(sz); - if (hsd == nullptr) return nullptr; + if (!hsd) return nullptr; hsd->input_buffer_size = input_buffer_size; hsd->window_sz2 = window_sz2; hsd->lookahead_sz2 = lookahead_sz2; @@ -124,7 +124,7 @@ void heatshrink_decoder_reset(heatshrink_decoder *hsd) { /* Copy SIZE bytes into the decoder's input buffer, if it will fit. */ HSD_sink_res heatshrink_decoder_sink(heatshrink_decoder *hsd, uint8_t *in_buf, size_t size, size_t *input_size) { - if (hsd == nullptr || in_buf == nullptr || input_size == nullptr) + if (!hsd || !in_buf || !input_size) return HSDR_SINK_ERROR_NULL; size_t rem = HEATSHRINK_DECODER_INPUT_BUFFER_SIZE(hsd) - hsd->input_size; @@ -160,7 +160,7 @@ static HSD_state st_backref_count_lsb(heatshrink_decoder *hsd); static HSD_state st_yield_backref(heatshrink_decoder *hsd, output_info *oi); HSD_poll_res heatshrink_decoder_poll(heatshrink_decoder *hsd, uint8_t *out_buf, size_t out_buf_size, size_t *output_size) { - if (hsd == nullptr || out_buf == nullptr || output_size == nullptr) + if (!hsd || !out_buf || !output_size) return HSDR_POLL_ERROR_NULL; *output_size = 0; @@ -351,7 +351,7 @@ static uint16_t get_bits(heatshrink_decoder *hsd, uint8_t count) { } HSD_finish_res heatshrink_decoder_finish(heatshrink_decoder *hsd) { - if (hsd == nullptr) { return HSDR_FINISH_ERROR_NULL; } + if (!hsd) return HSDR_FINISH_ERROR_NULL; switch (hsd->state) { case HSDS_TAG_BIT: return hsd->input_size == 0 ? HSDR_FINISH_DONE : HSDR_FINISH_MORE; diff --git a/Marlin/src/libs/least_squares_fit.cpp b/Marlin/src/libs/least_squares_fit.cpp index c7593c049fc4..aac21c019295 100644 --- a/Marlin/src/libs/least_squares_fit.cpp +++ b/Marlin/src/libs/least_squares_fit.cpp @@ -46,23 +46,23 @@ int finish_incremental_LSF(struct linear_fit_data *lsf) { if (N == 0.0) return 1; - lsf->xbar /= N; - lsf->ybar /= N; - lsf->zbar /= N; - lsf->x2bar = lsf->x2bar / N - sq(lsf->xbar); - lsf->y2bar = lsf->y2bar / N - sq(lsf->ybar); - lsf->z2bar = lsf->z2bar / N - sq(lsf->zbar); - lsf->xybar = lsf->xybar / N - lsf->xbar * lsf->ybar; - lsf->yzbar = lsf->yzbar / N - lsf->ybar * lsf->zbar; - lsf->xzbar = lsf->xzbar / N - lsf->xbar * lsf->zbar; - const float DD = lsf->x2bar * lsf->y2bar - sq(lsf->xybar); + const float RN = 1.0f / N, + xbar = lsf->xbar * RN, + ybar = lsf->ybar * RN, + zbar = lsf->zbar * RN, + x2bar = lsf->x2bar * RN - sq(xbar), + y2bar = lsf->y2bar * RN - sq(ybar), + xybar = lsf->xybar * RN - xbar * ybar, + yzbar = lsf->yzbar * RN - ybar * zbar, + xzbar = lsf->xzbar * RN - xbar * zbar, + DD = x2bar * y2bar - sq(xybar); if (ABS(DD) <= 1e-10 * (lsf->max_absx + lsf->max_absy)) return 1; - lsf->A = (lsf->yzbar * lsf->xybar - lsf->xzbar * lsf->y2bar) / DD; - lsf->B = (lsf->xzbar * lsf->xybar - lsf->yzbar * lsf->x2bar) / DD; - lsf->D = -(lsf->zbar + lsf->A * lsf->xbar + lsf->B * lsf->ybar); + lsf->A = (yzbar * xybar - xzbar * y2bar) / DD; + lsf->B = (xzbar * xybar - yzbar * x2bar) / DD; + lsf->D = -(zbar + lsf->A * xbar + lsf->B * ybar); return 0; } diff --git a/Marlin/src/libs/least_squares_fit.h b/Marlin/src/libs/least_squares_fit.h index 44ca8afc76d8..374a1f5adacd 100644 --- a/Marlin/src/libs/least_squares_fit.h +++ b/Marlin/src/libs/least_squares_fit.h @@ -37,7 +37,7 @@ struct linear_fit_data { float xbar, ybar, zbar, - x2bar, y2bar, z2bar, + x2bar, y2bar, xybar, xzbar, yzbar, max_absx, max_absy, A, B, D, N; @@ -47,7 +47,7 @@ inline void incremental_LSF_reset(struct linear_fit_data *lsf) { memset(lsf, 0, sizeof(linear_fit_data)); } -inline void incremental_WLSF(struct linear_fit_data *lsf, const float &x, const float &y, const float &z, const float &w) { +inline void incremental_WLSF(struct linear_fit_data *lsf, const_float_t x, const_float_t y, const_float_t z, const_float_t w) { // weight each accumulator by factor w, including the "number" of samples // (analogous to calling inc_LSF twice with same values to weight it by 2X) const float wx = w * x, wy = w * y, wz = w * z; @@ -56,7 +56,6 @@ inline void incremental_WLSF(struct linear_fit_data *lsf, const float &x, const lsf->zbar += wz; lsf->x2bar += wx * x; lsf->y2bar += wy * y; - lsf->z2bar += wz * z; lsf->xybar += wx * y; lsf->xzbar += wx * z; lsf->yzbar += wy * z; @@ -64,17 +63,16 @@ inline void incremental_WLSF(struct linear_fit_data *lsf, const float &x, const lsf->max_absx = _MAX(ABS(wx), lsf->max_absx); lsf->max_absy = _MAX(ABS(wy), lsf->max_absy); } -inline void incremental_WLSF(struct linear_fit_data *lsf, const xy_pos_t &pos, const float &z, const float &w) { +inline void incremental_WLSF(struct linear_fit_data *lsf, const xy_pos_t &pos, const_float_t z, const_float_t w) { incremental_WLSF(lsf, pos.x, pos.y, z, w); } -inline void incremental_LSF(struct linear_fit_data *lsf, const float &x, const float &y, const float &z) { +inline void incremental_LSF(struct linear_fit_data *lsf, const_float_t x, const_float_t y, const_float_t z) { lsf->xbar += x; lsf->ybar += y; lsf->zbar += z; lsf->x2bar += sq(x); lsf->y2bar += sq(y); - lsf->z2bar += sq(z); lsf->xybar += x * y; lsf->xzbar += x * z; lsf->yzbar += y * z; @@ -82,7 +80,7 @@ inline void incremental_LSF(struct linear_fit_data *lsf, const float &x, const f lsf->max_absy = _MAX(ABS(y), lsf->max_absy); lsf->N += 1.0; } -inline void incremental_LSF(struct linear_fit_data *lsf, const xy_pos_t &pos, const float &z) { +inline void incremental_LSF(struct linear_fit_data *lsf, const xy_pos_t &pos, const_float_t z) { incremental_LSF(lsf, pos.x, pos.y, z); } diff --git a/Marlin/src/libs/nozzle.cpp b/Marlin/src/libs/nozzle.cpp index 10021005e5b3..e277216ab4e5 100644 --- a/Marlin/src/libs/nozzle.cpp +++ b/Marlin/src/libs/nozzle.cpp @@ -31,6 +31,10 @@ Nozzle nozzle; #include "../MarlinCore.h" #include "../module/motion.h" +#if NOZZLE_CLEAN_MIN_TEMP > 20 + #include "../module/temperature.h" +#endif + #if ENABLED(NOZZLE_CLEAN_FEATURE) /** @@ -42,7 +46,9 @@ Nozzle nozzle; * @param strokes number of strokes to execute */ void Nozzle::stroke(const xyz_pos_t &start, const xyz_pos_t &end, const uint8_t &strokes) { - TERN_(NOZZLE_CLEAN_GOBACK, const xyz_pos_t oldpos = current_position); + #if ENABLED(NOZZLE_CLEAN_GOBACK) + const xyz_pos_t oldpos = current_position; + #endif // Move to the starting point #if ENABLED(NOZZLE_CLEAN_NO_Z) @@ -82,7 +88,9 @@ Nozzle nozzle; const xy_pos_t diff = end - start; if (!diff.x || !diff.y) return; - TERN_(NOZZLE_CLEAN_GOBACK, const xyz_pos_t back = current_position); + #if ENABLED(NOZZLE_CLEAN_GOBACK) + const xyz_pos_t back = current_position; + #endif #if ENABLED(NOZZLE_CLEAN_NO_Z) do_blocking_move_to_xy(start); @@ -122,10 +130,12 @@ Nozzle nozzle; * @param strokes number of strokes to execute * @param radius radius of circle */ - void Nozzle::circle(const xyz_pos_t &start, const xyz_pos_t &middle, const uint8_t &strokes, const float &radius) { + void Nozzle::circle(const xyz_pos_t &start, const xyz_pos_t &middle, const uint8_t &strokes, const_float_t radius) { if (strokes == 0) return; - TERN_(NOZZLE_CLEAN_GOBACK, const xyz_pos_t back = current_position); + #if ENABLED(NOZZLE_CLEAN_GOBACK) + const xyz_pos_t back = current_position; + #endif TERN(NOZZLE_CLEAN_NO_Z, do_blocking_move_to_xy, do_blocking_move_to)(start); LOOP_L_N(s, strokes) @@ -148,11 +158,24 @@ Nozzle nozzle; * @param pattern one of the available patterns * @param argument depends on the cleaning pattern */ - void Nozzle::clean(const uint8_t &pattern, const uint8_t &strokes, const float &radius, const uint8_t &objects, const uint8_t cleans) { + 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 = ANY(SINGLENOZZLE, MIXING_EXTRUDER) ? 0 : active_extruder; + #if NOZZLE_CLEAN_MIN_TEMP > 20 + if (thermalManager.degTargetHotend(arrPos) < NOZZLE_CLEAN_MIN_TEMP) { + #if ENABLED(NOZZLE_CLEAN_HEATUP) + SERIAL_ECHOLNPGM("Nozzle too Cold - Heating"); + thermalManager.setTargetHotend(NOZZLE_CLEAN_MIN_TEMP, arrPos); + thermalManager.wait_for_hotend(arrPos); + #else + SERIAL_ECHOLNPGM("Nozzle too cold - Skipping wipe"); + return; + #endif + } + #endif + #if HAS_SOFTWARE_ENDSTOPS #define LIMIT_AXIS(A) do{ \ @@ -202,6 +225,18 @@ Nozzle nozzle; #if ENABLED(NOZZLE_PARK_FEATURE) + float Nozzle::park_mode_0_height(const_float_t park_z) { + // Apply a minimum raise, if specified. Use park.z as a minimum height instead. + return _MAX(park_z, // Minimum height over 0 based on input + _MIN(Z_MAX_POS, // Maximum height is fixed + #ifdef NOZZLE_PARK_Z_RAISE_MIN + NOZZLE_PARK_Z_RAISE_MIN + // Minimum raise... + #endif + current_position.z // ...over current position + ) + ); + } + void Nozzle::park(const uint8_t z_action, const xyz_pos_t &park/*=NOZZLE_PARK_POINT*/) { constexpr feedRate_t fr_xy = NOZZLE_PARK_XY_FEEDRATE, fr_z = NOZZLE_PARK_Z_FEEDRATE; @@ -214,15 +249,9 @@ Nozzle nozzle; do_blocking_move_to_z(_MIN(current_position.z + park.z, Z_MAX_POS), fr_z); break; - default: { - // Apply a minimum raise, overriding G27 Z - const float min_raised_z =_MIN(Z_MAX_POS, current_position.z - #ifdef NOZZLE_PARK_Z_RAISE_MIN - + NOZZLE_PARK_Z_RAISE_MIN - #endif - ); - do_blocking_move_to_z(_MAX(park.z, min_raised_z), fr_z); - } break; + default: // Raise by NOZZLE_PARK_Z_RAISE_MIN, use park.z as a minimum height + do_blocking_move_to_z(park_mode_0_height(park.z), fr_z); + break; } do_blocking_move_to_xy( diff --git a/Marlin/src/libs/nozzle.h b/Marlin/src/libs/nozzle.h index 81594b13817d..7bbd0e35c11b 100644 --- a/Marlin/src/libs/nozzle.h +++ b/Marlin/src/libs/nozzle.h @@ -62,7 +62,7 @@ class Nozzle { * @param strokes number of strokes to execute * @param radius radius of circle */ - static void circle(const xyz_pos_t &start, const xyz_pos_t &middle, const uint8_t &strokes, const float &radius) _Os; + static void circle(const xyz_pos_t &start, const xyz_pos_t &middle, const uint8_t &strokes, const_float_t radius) _Os; #endif // NOZZLE_CLEAN_FEATURE @@ -77,12 +77,13 @@ class Nozzle { * @param pattern one of the available patterns * @param argument depends on the cleaning pattern */ - static void clean(const uint8_t &pattern, const uint8_t &strokes, const float &radius, const uint8_t &objects, const uint8_t cleans) _Os; + static void clean(const uint8_t &pattern, const uint8_t &strokes, const_float_t radius, const uint8_t &objects, const uint8_t cleans) _Os; #endif // NOZZLE_CLEAN_FEATURE #if ENABLED(NOZZLE_PARK_FEATURE) + static float park_mode_0_height(const_float_t park_z) _Os; static void park(const uint8_t z_action, const xyz_pos_t &park=NOZZLE_PARK_POINT) _Os; #endif diff --git a/Marlin/src/libs/numtostr.cpp b/Marlin/src/libs/numtostr.cpp index c3efb2b25a84..1e1ac0571012 100644 --- a/Marlin/src/libs/numtostr.cpp +++ b/Marlin/src/libs/numtostr.cpp @@ -34,16 +34,20 @@ char conv[8] = { 0 }; #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) -// Convert a full-range unsigned 8bit int to a percentage -const char* ui8tostr4pctrj(const uint8_t i) { - const uint8_t n = ui8_to_percent(i); - conv[3] = RJDIGIT(n, 100); - conv[4] = RJDIGIT(n, 10); - conv[5] = DIGIMOD(n, 1); +// Format uint8_t (0-100) as rj string with 123% / _12% / __1% format +const char* pcttostrpctrj(const uint8_t i) { + conv[3] = RJDIGIT(i, 100); + conv[4] = RJDIGIT(i, 10); + conv[5] = DIGIMOD(i, 1); conv[6] = '%'; return &conv[3]; } +// Convert uint8_t (0-255) to a percentage, format as above +const char* ui8tostr4pctrj(const uint8_t i) { + return pcttostrpctrj(ui8_to_percent(i)); +} + // Convert unsigned 8bit int to string 123 format const char* ui8tostr3rj(const uint8_t i) { conv[4] = RJDIGIT(i, 100); @@ -173,8 +177,17 @@ const char* i16tostr4signrj(const int16_t i) { return &conv[3]; } +// Convert unsigned float to string with 1.1 format +const char* ftostr11ns(const_float_t f) { + const long i = UINTFLOAT(f, 1); + conv[4] = DIGIMOD(i, 10); + conv[5] = '.'; + conv[6] = DIGIMOD(i, 1); + return &conv[4]; +} + // Convert unsigned float to string with 1.23 format -const char* ftostr12ns(const float &f) { +const char* ftostr12ns(const_float_t f) { const long i = UINTFLOAT(f, 2); conv[3] = DIGIMOD(i, 100); conv[4] = '.'; @@ -184,7 +197,7 @@ const char* ftostr12ns(const float &f) { } // Convert unsigned float to string with 12.3 format -const char* ftostr31ns(const float &f) { +const char* ftostr31ns(const_float_t f) { const long i = UINTFLOAT(f, 1); conv[3] = DIGIMOD(i, 100); conv[4] = DIGIMOD(i, 10); @@ -194,7 +207,7 @@ const char* ftostr31ns(const float &f) { } // Convert unsigned float to string with 123.4 format -const char* ftostr41ns(const float &f) { +const char* ftostr41ns(const_float_t f) { const long i = UINTFLOAT(f, 1); conv[2] = DIGIMOD(i, 1000); conv[3] = DIGIMOD(i, 100); @@ -205,7 +218,7 @@ const char* ftostr41ns(const float &f) { } // Convert signed float to fixed-length string with 12.34 / _2.34 / -2.34 or -23.45 / 123.45 format -const char* ftostr42_52(const float &f) { +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); conv[2] = (f >= 0 && f < 10) ? ' ' : MINUSOR(i, DIGIMOD(i, 1000)); @@ -217,7 +230,7 @@ const char* ftostr42_52(const float &f) { } // Convert signed float to fixed-length string with 023.45 / -23.45 format -const char* ftostr52(const float &f) { +const char* ftostr52(const_float_t f) { long i = INTFLOAT(f, 2); conv[1] = MINUSOR(i, DIGIMOD(i, 10000)); conv[2] = DIGIMOD(i, 1000); @@ -229,7 +242,7 @@ const char* ftostr52(const float &f) { } // Convert signed float to fixed-length string with 12.345 / _2.345 / -2.345 or -23.45 / 123.45 format -const char* ftostr53_63(const float &f) { +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); conv[1] = (f >= 0 && f < 10) ? ' ' : MINUSOR(i, DIGIMOD(i, 10000)); @@ -242,7 +255,7 @@ const char* ftostr53_63(const float &f) { } // Convert signed float to fixed-length string with 023.456 / -23.456 format -const char* ftostr63(const float &f) { +const char* ftostr63(const_float_t f) { long i = INTFLOAT(f, 3); conv[0] = MINUSOR(i, DIGIMOD(i, 100000)); conv[1] = DIGIMOD(i, 10000); @@ -257,7 +270,7 @@ const char* ftostr63(const float &f) { #if ENABLED(LCD_DECIMAL_SMALL_XY) // Convert float to rj string with 1234, _123, -123, _-12, 12.3, _1.2, or -1.2 format - const char* ftostr4sign(const float &f) { + const char* ftostr4sign(const_float_t f) { const int i = INTFLOAT(f, 1); if (!WITHIN(i, -99, 999)) return i16tostr4signrj((int)f); const bool neg = i < 0; @@ -272,7 +285,7 @@ const char* ftostr63(const float &f) { #endif // Convert float to fixed-length string with +12.3 / -12.3 format -const char* ftostr31sign(const float &f) { +const char* ftostr31sign(const_float_t f) { int i = INTFLOAT(f, 1); conv[2] = MINUSOR(i, '+'); conv[3] = DIGIMOD(i, 100); @@ -283,7 +296,7 @@ const char* ftostr31sign(const float &f) { } // Convert float to fixed-length string with +123.4 / -123.4 format -const char* ftostr41sign(const float &f) { +const char* ftostr41sign(const_float_t f) { int i = INTFLOAT(f, 1); conv[1] = MINUSOR(i, '+'); conv[2] = DIGIMOD(i, 1000); @@ -295,7 +308,7 @@ const char* ftostr41sign(const float &f) { } // Convert signed float to string (6 digit) with -1.234 / _0.000 / +1.234 format -const char* ftostr43sign(const float &f, char plus/*=' '*/) { +const char* ftostr43sign(const_float_t f, char plus/*=' '*/) { long i = INTFLOAT(f, 3); conv[1] = i ? MINUSOR(i, plus) : ' '; conv[2] = DIGIMOD(i, 1000); @@ -307,7 +320,7 @@ const char* ftostr43sign(const float &f, char plus/*=' '*/) { } // Convert signed float to string (5 digit) with -1.2345 / _0.0000 / +1.2345 format -const char* ftostr54sign(const float &f, char plus/*=' '*/) { +const char* ftostr54sign(const_float_t f, char plus/*=' '*/) { long i = INTFLOAT(f, 4); conv[0] = i ? MINUSOR(i, plus) : ' '; conv[1] = DIGIMOD(i, 10000); @@ -320,13 +333,13 @@ const char* ftostr54sign(const float &f, char plus/*=' '*/) { } // Convert unsigned float to rj string with 12345 format -const char* ftostr5rj(const float &f) { +const char* ftostr5rj(const_float_t f) { const long i = UINTFLOAT(f, 0); return ui16tostr5rj(i); } // Convert signed float to string with +1234.5 format -const char* ftostr51sign(const float &f) { +const char* ftostr51sign(const_float_t f) { long i = INTFLOAT(f, 1); conv[0] = MINUSOR(i, '+'); conv[1] = DIGIMOD(i, 10000); @@ -339,7 +352,7 @@ const char* ftostr51sign(const float &f) { } // Convert signed float to string with +123.45 format -const char* ftostr52sign(const float &f) { +const char* ftostr52sign(const_float_t f) { long i = INTFLOAT(f, 2); conv[0] = MINUSOR(i, '+'); conv[1] = DIGIMOD(i, 10000); @@ -352,7 +365,7 @@ const char* ftostr52sign(const float &f) { } // Convert signed float to string with +12.345 format -const char* ftostr53sign(const float &f) { +const char* ftostr53sign(const_float_t f) { long i = INTFLOAT(f, 3); conv[0] = MINUSOR(i, '+'); conv[1] = DIGIMOD(i, 10000); @@ -365,7 +378,7 @@ const char* ftostr53sign(const float &f) { } // Convert unsigned float to string with ____4.5, __34.5, _234.5, 1234.5 format -const char* ftostr51rj(const float &f) { +const char* ftostr51rj(const_float_t f) { const long i = UINTFLOAT(f, 1); conv[0] = ' '; conv[1] = RJDIGIT(i, 10000); @@ -378,7 +391,7 @@ const char* ftostr51rj(const float &f) { } // Convert signed float to space-padded string with -_23.4_ format -const char* ftostr52sp(const float &f) { +const char* ftostr52sp(const_float_t f) { long i = INTFLOAT(f, 2); uint8_t dig; conv[0] = MINUSOR(i, ' '); diff --git a/Marlin/src/libs/numtostr.h b/Marlin/src/libs/numtostr.h index e7c1e67e12d5..b058f3cdf6c6 100644 --- a/Marlin/src/libs/numtostr.h +++ b/Marlin/src/libs/numtostr.h @@ -21,9 +21,13 @@ */ #pragma once -#include +#include "../inc/MarlinConfigPre.h" +#include "../core/types.h" + +// Format uint8_t (0-100) as rj string with 123% / _12% / __1% format +const char* pcttostrpctrj(const uint8_t i); -// Convert a full-range unsigned 8bit int to a percentage +// Convert uint8_t (0-255) to a percentage, format as above const char* ui8tostr4pctrj(const uint8_t i); // Convert uint8_t to string with 12 format @@ -58,68 +62,67 @@ const char* i16tostr3left(const int16_t xx); // Convert signed int to rj string with _123, -123, _-12, or __-1 format const char* i16tostr4signrj(const int16_t x); +// Convert unsigned float to string with 1.2 format +const char* ftostr11ns(const_float_t x); + // Convert unsigned float to string with 1.23 format -const char* ftostr12ns(const float &x); +const char* ftostr12ns(const_float_t x); // Convert unsigned float to string with 12.3 format -const char* ftostr31ns(const float &x); +const char* ftostr31ns(const_float_t x); // Convert unsigned float to string with 123.4 format -const char* ftostr41ns(const float &x); +const char* ftostr41ns(const_float_t x); // Convert signed float to fixed-length string with 12.34 / _2.34 / -2.34 or -23.45 / 123.45 format -const char* ftostr42_52(const float &x); +const char* ftostr42_52(const_float_t x); // Convert signed float to fixed-length string with 023.45 / -23.45 format -const char* ftostr52(const float &x); +const char* ftostr52(const_float_t x); // Convert signed float to fixed-length string with 12.345 / -2.345 or 023.456 / -23.456 format -const char* ftostr53_63(const float &x); +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 &x); +const char* ftostr63(const_float_t x); // Convert float to fixed-length string with +12.3 / -12.3 format -const char* ftostr31sign(const float &x); +const char* ftostr31sign(const_float_t x); // Convert float to fixed-length string with +123.4 / -123.4 format -const char* ftostr41sign(const float &x); +const char* ftostr41sign(const_float_t x); // Convert signed float to string (6 digit) with -1.234 / _0.000 / +1.234 format -const char* ftostr43sign(const float &x, char plus=' '); +const char* ftostr43sign(const_float_t x, char plus=' '); // Convert signed float to string (5 digit) with -1.2345 / _0.0000 / +1.2345 format -const char* ftostr54sign(const float &x, char plus=' '); +const char* ftostr54sign(const_float_t x, char plus=' '); // Convert unsigned float to rj string with 12345 format -const char* ftostr5rj(const float &x); +const char* ftostr5rj(const_float_t x); // Convert signed float to string with +1234.5 format -const char* ftostr51sign(const float &x); +const char* ftostr51sign(const_float_t x); // Convert signed float to space-padded string with -_23.4_ format -const char* ftostr52sp(const float &x); +const char* ftostr52sp(const_float_t x); // Convert signed float to string with +123.45 format -const char* ftostr52sign(const float &x); +const char* ftostr52sign(const_float_t x); // Convert signed float to string with +12.345 format -const char* ftostr53sign(const float &f); +const char* ftostr53sign(const_float_t f); // Convert unsigned float to string with 1234.5 format omitting trailing zeros -const char* ftostr51rj(const float &x); - -#include "../core/macros.h" +const char* ftostr51rj(const_float_t x); // Convert float to rj string with 123 or -12 format -FORCE_INLINE const char* ftostr3(const float &x) { return i16tostr3rj(int16_t(x + (x < 0 ? -0.5f : 0.5f))); } - -#include "../inc/MarlinConfigPre.h" +FORCE_INLINE const char* ftostr3(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 - const char* ftostr4sign(const float &fx); + const char* ftostr4sign(const_float_t fx); #else // Convert float to rj string with 1234, _123, -123, __12, _-12, ___1, or __-1 format - FORCE_INLINE const char* ftostr4sign(const float &x) { return i16tostr4signrj(int16_t(x + (x < 0 ? -0.5f : 0.5f))); } + 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/private_spi.h b/Marlin/src/libs/private_spi.h index 9c0ffe7486d7..1d8eacd22d04 100644 --- a/Marlin/src/libs/private_spi.h +++ b/Marlin/src/libs/private_spi.h @@ -35,12 +35,12 @@ class SPIclass { // Hardware SPI template<> -class SPIclass { +class SPIclass { public: FORCE_INLINE static void init() { - OUT_WRITE(SCK_PIN, LOW); - OUT_WRITE(MOSI_PIN, HIGH); - SET_INPUT_PULLUP(MISO_PIN); + OUT_WRITE(SD_SCK_PIN, LOW); + OUT_WRITE(SD_MOSI_PIN, HIGH); + SET_INPUT_PULLUP(SD_MISO_PIN); } FORCE_INLINE static uint8_t receive() { #if defined(__AVR__) || defined(__MK20DX256__) || defined(__MK64FX512__) || defined(__MK66FX1M0__) || defined(__IMXRT1062__) diff --git a/Marlin/src/libs/softspi.h b/Marlin/src/libs/softspi.h index 5d48f9fd8cb9..cc36d658cd2f 100644 --- a/Marlin/src/libs/softspi.h +++ b/Marlin/src/libs/softspi.h @@ -25,11 +25,7 @@ // Based on https://github.com/niteris/ArduinoSoftSpi // -#include "../HAL/shared/Marduino.h" - -#ifndef FORCE_INLINE - #define FORCE_INLINE inline __attribute__((always_inline)) -#endif +#include "../HAL/shared/Marduino.h" // CORE_TEENSY #define nop __asm__ volatile ("nop") // NOP for timing @@ -715,7 +711,7 @@ class SoftSPI { FORCE_INLINE bool MODE_CPHA(uint8_t mode) { return bool(mode & 1); } FORCE_INLINE bool MODE_CPOL(uint8_t mode) { return bool(mode & 2); } - FORCE_INLINE void receiveBit(uint8_t bit, uint8_t* data) { + FORCE_INLINE void receiveBit(uint8_t bit, uint8_t *data) { if (MODE_CPHA(Mode)) fastDigitalWrite(SckPin, !MODE_CPOL(Mode)); nop; nop; @@ -734,7 +730,7 @@ class SoftSPI { if (!MODE_CPHA(Mode)) fastDigitalWrite(SckPin, MODE_CPOL(Mode)); } - FORCE_INLINE void transferBit(uint8_t bit, uint8_t* rxData, uint8_t txData) { + FORCE_INLINE void transferBit(uint8_t bit, uint8_t *rxData, uint8_t txData) { if (MODE_CPHA(Mode)) fastDigitalWrite(SckPin, !MODE_CPOL(Mode)); fastDigitalWrite(MosiPin, txData & _BV(bit)); fastDigitalWrite(SckPin, diff --git a/Marlin/src/libs/stopwatch.cpp b/Marlin/src/libs/stopwatch.cpp index 601efe55178f..adfaa3b043e5 100644 --- a/Marlin/src/libs/stopwatch.cpp +++ b/Marlin/src/libs/stopwatch.cpp @@ -98,7 +98,7 @@ millis_t Stopwatch::duration() { void Stopwatch::debug(const char func[]) { if (DEBUGGING(INFO)) { SERIAL_ECHOPGM("Stopwatch::"); - serialprintPGM(func); + SERIAL_ECHOPGM_P(func); SERIAL_ECHOLNPGM("()"); } } diff --git a/Marlin/src/libs/stopwatch.h b/Marlin/src/libs/stopwatch.h index 6e8e95a9a5f1..b64a36a90e78 100644 --- a/Marlin/src/libs/stopwatch.h +++ b/Marlin/src/libs/stopwatch.h @@ -56,6 +56,7 @@ class Stopwatch { * @return true on success */ static bool stop(); + static inline bool abort() { return stop(); } // Alias by default /** * @brief Pause the stopwatch diff --git a/Marlin/src/libs/vector_3.cpp b/Marlin/src/libs/vector_3.cpp index 75a30aef8222..4db8fb5f2e15 100644 --- a/Marlin/src/libs/vector_3.cpp +++ b/Marlin/src/libs/vector_3.cpp @@ -52,10 +52,9 @@ */ vector_3 vector_3::cross(const vector_3 &left, const vector_3 &right) { - const xyz_float_t &lv = left, &rv = right; - return vector_3(lv.y * rv.z - lv.z * rv.y, // YZ cross - lv.z * rv.x - lv.x * rv.z, // ZX cross - lv.x * rv.y - lv.y * rv.x); // XY cross + return vector_3(left.y * right.z - left.z * right.y, // YZ cross + left.z * right.x - left.x * right.z, // ZX cross + left.x * right.y - left.y * right.x); // XY cross } vector_3 vector_3::get_normal() const { @@ -64,22 +63,20 @@ vector_3 vector_3::get_normal() const { return normalized; } -void vector_3::normalize() { - *this *= RSQRT(sq(x) + sq(y) + sq(z)); -} +float vector_3::magnitude() const { return SQRT(sq(x) + sq(y) + sq(z)); } + +void vector_3::normalize() { *this *= RSQRT(sq(x) + sq(y) + sq(z)); } // Apply a rotation to the matrix void vector_3::apply_rotation(const matrix_3x3 &matrix) { const float _x = x, _y = y, _z = z; - *this = { matrix.vectors[0][0] * _x + matrix.vectors[1][0] * _y + matrix.vectors[2][0] * _z, - matrix.vectors[0][1] * _x + matrix.vectors[1][1] * _y + matrix.vectors[2][1] * _z, - matrix.vectors[0][2] * _x + matrix.vectors[1][2] * _y + matrix.vectors[2][2] * _z }; + *this = { matrix.vectors[0].x * _x + matrix.vectors[1].x * _y + matrix.vectors[2].x * _z, + matrix.vectors[0].y * _x + matrix.vectors[1].y * _y + matrix.vectors[2].y * _z, + matrix.vectors[0].z * _x + matrix.vectors[1].z * _y + matrix.vectors[2].z * _z }; } -extern const char SP_X_STR[], SP_Y_STR[], SP_Z_STR[]; - void vector_3::debug(PGM_P const title) { - serialprintPGM(title); + SERIAL_ECHOPGM_P(title); SERIAL_ECHOPAIR_F_P(SP_X_STR, x, 6); SERIAL_ECHOPAIR_F_P(SP_Y_STR, y, 6); SERIAL_ECHOLNPAIR_F_P(SP_Z_STR, z, 6); @@ -89,8 +86,8 @@ void vector_3::debug(PGM_P const title) { * matrix_3x3 */ -void apply_rotation_xyz(const matrix_3x3 &matrix, float &_x, float &_y, float &_z) { - vector_3 vec = vector_3(_x, _y, _z); vec.apply_rotation(matrix); +void matrix_3x3::apply_rotation_xyz(float &_x, float &_y, float &_z) { + vector_3 vec = vector_3(_x, _y, _z); vec.apply_rotation(*this); _x = vec.x; _y = vec.y; _z = vec.z; } @@ -141,10 +138,7 @@ matrix_3x3 matrix_3x3::transpose(const matrix_3x3 &original) { } void matrix_3x3::debug(PGM_P const title) { - if (title != nullptr) { - serialprintPGM(title); - SERIAL_EOL(); - } + if (title) SERIAL_ECHOLNPGM_P(title); LOOP_L_N(i, 3) { LOOP_L_N(j, 3) { if (vectors[i][j] >= 0.0) SERIAL_CHAR('+'); diff --git a/Marlin/src/libs/vector_3.h b/Marlin/src/libs/vector_3.h index 58428314d9d4..5d99fcec20db 100644 --- a/Marlin/src/libs/vector_3.h +++ b/Marlin/src/libs/vector_3.h @@ -44,13 +44,16 @@ class matrix_3x3; -struct vector_3 : xyz_float_t { - - vector_3(const float &_x, const float &_y, const float &_z) { set(_x, _y, _z); } - vector_3(const xy_float_t &in) { set(in.x, in.y); } - vector_3(const xyz_float_t &in) { set(in.x, in.y, in.z); } - vector_3(const xyze_float_t &in) { set(in.x, in.y, in.z); } - vector_3() { reset(); } +struct vector_3 { + union { + struct { float x, y, z; }; + 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() { x = y = z = 0; } // Factory method static vector_3 cross(const vector_3 &a, const vector_3 &b); @@ -60,19 +63,26 @@ struct vector_3 : xyz_float_t { void apply_rotation(const matrix_3x3 &matrix); // Accessors - float get_length() const; + float magnitude() const; vector_3 get_normal() const; // Operators - FORCE_INLINE vector_3 operator+(const vector_3 &v) const { vector_3 o = *this; o += v; return o; } - FORCE_INLINE vector_3 operator-(const vector_3 &v) const { vector_3 o = *this; o -= v; return o; } - FORCE_INLINE vector_3 operator*(const float &v) const { vector_3 o = *this; o *= v; return o; } + float& operator[](const int n) { return pos[n]; } + const float& operator[](const int n) const { return pos[n]; } + + vector_3& operator*=(const float &v) { x *= v; y *= v; z *= v; return *this; } + vector_3 operator+(const vector_3 &v) { return vector_3(x + v.x, y + v.y, z + v.z); } + 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, y }); } + operator xyz_float_t() { return xyz_float_t({ x, y, z }); } void debug(PGM_P const title); }; struct matrix_3x3 { - abc_float_t vectors[3]; + vector_3 vectors[3]; // Factory methods static matrix_3x3 create_from_rows(const vector_3 &row_0, const vector_3 &row_1, const vector_3 &row_2); @@ -82,9 +92,6 @@ struct matrix_3x3 { void set_to_identity(); void debug(PGM_P const title); -}; -void apply_rotation_xyz(const matrix_3x3 &rotationMatrix, float &x, float &y, float &z); -FORCE_INLINE void apply_rotation_xyz(const matrix_3x3 &rotationMatrix, xyz_pos_t &pos) { - apply_rotation_xyz(rotationMatrix, pos.x, pos.y, pos.z); -} + void apply_rotation_xyz(float &x, float &y, float &z); +}; diff --git a/Marlin/src/module/delta.cpp b/Marlin/src/module/delta.cpp index df6cae6e0a97..992c3a09b469 100644 --- a/Marlin/src/module/delta.cpp +++ b/Marlin/src/module/delta.cpp @@ -34,7 +34,7 @@ // For homing: #include "planner.h" #include "endstops.h" -#include "../lcd/ultralcd.h" +#include "../lcd/marlinui.h" #include "../MarlinCore.h" #if HAS_BED_PROBE @@ -54,7 +54,7 @@ float delta_height; abc_float_t delta_endstop_adj{0}; float delta_radius, delta_diagonal_rod, - delta_segments_per_second; + segments_per_second; abc_float_t delta_tower_angle_trim; xy_float_t delta_tower[ABC]; abc_float_t delta_diagonal_rod_2_tower; @@ -177,7 +177,7 @@ float delta_safe_distance_from_top() { * * The result is stored in the cartes[] array. */ -void forward_kinematics_DELTA(const float &z1, const float &z2, const float &z3) { +void forward_kinematics(const_float_t z1, const_float_t z2, const_float_t z3) { // Create a vector in old coordinates along x axis of new coordinate const float p12[3] = { delta_tower[B_AXIS].x - delta_tower[A_AXIS].x, delta_tower[B_AXIS].y - delta_tower[A_AXIS].y, z2 - z1 }, @@ -242,21 +242,28 @@ void home_delta() { // Disable stealthChop if used. Enable diag1 pin on driver. #if ENABLED(SENSORLESS_HOMING) - TERN_(X_SENSORLESS, sensorless_t stealth_states_x = start_sensorless_homing_per_axis(X_AXIS)); - TERN_(Y_SENSORLESS, sensorless_t stealth_states_y = start_sensorless_homing_per_axis(Y_AXIS)); - TERN_(Z_SENSORLESS, sensorless_t stealth_states_z = start_sensorless_homing_per_axis(Z_AXIS)); + TERN_(X_SENSORLESS, sensorless_t stealth_states_x = start_sensorless_homing_per_axis(X_AXIS)); + TERN_(Y_SENSORLESS, sensorless_t stealth_states_y = start_sensorless_homing_per_axis(Y_AXIS)); + TERN_(Z_SENSORLESS, sensorless_t stealth_states_z = start_sensorless_homing_per_axis(Z_AXIS)); + TERN_(I_SENSORLESS, sensorless_t stealth_states_i = start_sensorless_homing_per_axis(I_AXIS)); + TERN_(J_SENSORLESS, sensorless_t stealth_states_j = start_sensorless_homing_per_axis(J_AXIS)); + TERN_(K_SENSORLESS, sensorless_t stealth_states_k = start_sensorless_homing_per_axis(K_AXIS)); #endif // Move all carriages together linearly until an endstop is hit. - current_position.z = (delta_height + 10 - TERN0(HAS_BED_PROBE, probe.offset.z)); + current_position.z = DIFF_TERN(HAS_BED_PROBE, delta_height + 10, probe.offset.z); line_to_current_position(homing_feedrate(Z_AXIS)); planner.synchronize(); + TERN_(SENSORLESS_PROBING,endstops.report_states()); // Re-enable stealthChop if used. Disable diag1 pin on driver. - #if ENABLED(SENSORLESS_HOMING) - TERN_(X_SENSORLESS, end_sensorless_homing_per_axis(X_AXIS, stealth_states_x)); - TERN_(Y_SENSORLESS, end_sensorless_homing_per_axis(Y_AXIS, stealth_states_y)); - TERN_(Z_SENSORLESS, end_sensorless_homing_per_axis(Z_AXIS, stealth_states_z)); + #if ENABLED(SENSORLESS_HOMING) && DISABLED(ENDSTOPS_ALWAYS_ON_DEFAULT) + TERN_(X_SENSORLESS, end_sensorless_homing_per_axis(X_AXIS, stealth_states_x)); + TERN_(Y_SENSORLESS, end_sensorless_homing_per_axis(Y_AXIS, stealth_states_y)); + TERN_(Z_SENSORLESS, end_sensorless_homing_per_axis(Z_AXIS, stealth_states_z)); + TERN_(I_SENSORLESS, end_sensorless_homing_per_axis(I_AXIS, stealth_states_i)); + TERN_(J_SENSORLESS, end_sensorless_homing_per_axis(J_AXIS, stealth_states_j)); + TERN_(K_SENSORLESS, end_sensorless_homing_per_axis(K_AXIS, stealth_states_k)); #endif endstops.validate_homing_move(); @@ -271,7 +278,7 @@ void home_delta() { // Do this here all at once for Delta, because // XYZ isn't ABC. Applying this per-tower would // give the impression that they are the same. - LOOP_XYZ(i) set_axis_is_at_home((AxisEnum)i); + LOOP_ABC(i) set_axis_is_at_home((AxisEnum)i); sync_plan_position(); diff --git a/Marlin/src/module/delta.h b/Marlin/src/module/delta.h index 5e9a78bd8672..308e20670042 100644 --- a/Marlin/src/module/delta.h +++ b/Marlin/src/module/delta.h @@ -32,7 +32,7 @@ extern float delta_height; extern abc_float_t delta_endstop_adj; extern float delta_radius, delta_diagonal_rod, - delta_segments_per_second; + segments_per_second; extern abc_float_t delta_tower_angle_trim; extern xy_float_t delta_tower[ABC]; extern abc_float_t delta_diagonal_rod_2_tower; @@ -120,10 +120,10 @@ float delta_safe_distance_from_top(); * * The result is stored in the cartes[] array. */ -void forward_kinematics_DELTA(const float &z1, const float &z2, const float &z3); +void forward_kinematics(const_float_t z1, const_float_t z2, const_float_t z3); -FORCE_INLINE void forward_kinematics_DELTA(const abc_float_t &point) { - forward_kinematics_DELTA(point.a, point.b, point.c); +FORCE_INLINE void forward_kinematics(const abc_float_t &point) { + forward_kinematics(point.a, point.b, point.c); } void home_delta(); diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 712182a0ea40..0f4716ed870e 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -27,10 +27,9 @@ #include "endstops.h" #include "stepper.h" -#include "../MarlinCore.h" #include "../sd/cardreader.h" #include "temperature.h" -#include "../lcd/ultralcd.h" +#include "../lcd/marlinui.h" #if ENABLED(ENDSTOP_INTERRUPTS_FEATURE) #include HAL_PATH(../HAL, endstop_interrupts.h) @@ -48,17 +47,21 @@ #include "../feature/joystick.h" #endif +#if HAS_BED_PROBE + #include "probe.h" +#endif + Endstops endstops; // private: bool Endstops::enabled, Endstops::enabled_globally; // Initialized by settings.load() -volatile uint8_t Endstops::hit_state; -Endstops::esbits_t Endstops::live_state = 0; +volatile Endstops::endstop_mask_t Endstops::hit_state; +Endstops::endstop_mask_t Endstops::live_state = 0; #if ENDSTOP_NOISE_THRESHOLD - Endstops::esbits_t Endstops::validated_live_state; + Endstops::endstop_mask_t Endstops::validated_live_state; uint8_t Endstops::endstop_poll_count; #endif @@ -256,6 +259,66 @@ void Endstops::init() { #endif #endif + #if HAS_I_MIN + #if ENABLED(ENDSTOPPULLUP_IMIN) + SET_INPUT_PULLUP(I_MIN_PIN); + #elif ENABLED(ENDSTOPPULLDOWN_IMIN) + SET_INPUT_PULLDOWN(I_MIN_PIN); + #else + SET_INPUT(I_MIN_PIN); + #endif + #endif + + #if HAS_I_MAX + #if ENABLED(ENDSTOPPULLUP_IMAX) + SET_INPUT_PULLUP(I_MAX_PIN); + #elif ENABLED(ENDSTOPPULLDOWN_IMAX) + SET_INPUT_PULLDOWN(I_MAX_PIN); + #else + SET_INPUT(I_MAX_PIN); + #endif + #endif + + #if HAS_J_MIN + #if ENABLED(ENDSTOPPULLUP_JMIN) + SET_INPUT_PULLUP(J_MIN_PIN); + #elif ENABLED(ENDSTOPPULLDOWN_IMIN) + SET_INPUT_PULLDOWN(J_MIN_PIN); + #else + SET_INPUT(J_MIN_PIN); + #endif + #endif + + #if HAS_J_MAX + #if ENABLED(ENDSTOPPULLUP_JMAX) + SET_INPUT_PULLUP(J_MAX_PIN); + #elif ENABLED(ENDSTOPPULLDOWN_JMAX) + SET_INPUT_PULLDOWN(J_MAX_PIN); + #else + SET_INPUT(J_MAX_PIN); + #endif + #endif + + #if HAS_K_MIN + #if ENABLED(ENDSTOPPULLUP_KMIN) + SET_INPUT_PULLUP(K_MIN_PIN); + #elif ENABLED(ENDSTOPPULLDOWN_KMIN) + SET_INPUT_PULLDOWN(K_MIN_PIN); + #else + SET_INPUT(K_MIN_PIN); + #endif + #endif + + #if HAS_K_MAX + #if ENABLED(ENDSTOPPULLUP_KMAX) + SET_INPUT_PULLUP(K_MAX_PIN); + #elif ENABLED(ENDSTOPPULLDOWN_KMIN) + SET_INPUT_PULLDOWN(K_MAX_PIN); + #else + SET_INPUT(K_MAX_PIN); + #endif + #endif + #if PIN_EXISTS(CALIBRATION) #if ENABLED(CALIBRATION_PIN_PULLUP) SET_INPUT_PULLUP(CALIBRATION_PIN); @@ -266,7 +329,7 @@ void Endstops::init() { #endif #endif - #if HAS_CUSTOM_PROBE_PIN + #if USES_Z_MIN_PROBE_PIN #if ENABLED(ENDSTOPPULLUP_ZMIN_PROBE) SET_INPUT_PULLUP(Z_MIN_PROBE_PIN); #elif ENABLED(ENDSTOPPULLDOWN_ZMIN_PROBE) @@ -276,6 +339,12 @@ void Endstops::init() { #endif #endif + #if ENABLED(PROBE_ACTIVATION_SWITCH) + SET_INPUT(PROBE_ACTIVATION_SWITCH_PIN); + #endif + + TERN_(PROBE_TARE, probe.tare()); + TERN_(ENDSTOP_INTERRUPTS_FEATURE, setup_endstop_interrupts()); // Enable endstops @@ -347,46 +416,60 @@ void Endstops::resync() { #endif void Endstops::event_handler() { - static uint8_t prev_hit_state; // = 0 + static endstop_mask_t prev_hit_state; // = 0 if (hit_state == prev_hit_state) return; prev_hit_state = hit_state; if (hit_state) { - #if HAS_WIRED_LCD - char chrX = ' ', chrY = ' ', chrZ = ' ', chrP = ' '; + #if HAS_STATUS_MESSAGE + char LINEAR_AXIS_LIST(chrX = ' ', chrY = ' ', chrZ = ' ', chrI = ' ', chrJ = ' ', chrK = ' '), + chrP = ' '; #define _SET_STOP_CHAR(A,C) (chr## A = C) #else - #define _SET_STOP_CHAR(A,C) ; + #define _SET_STOP_CHAR(A,C) NOOP #endif #define _ENDSTOP_HIT_ECHO(A,C) do{ \ - SERIAL_ECHOPAIR(" " STRINGIFY(A) ":", planner.triggered_position_mm(_AXIS(A))); \ - _SET_STOP_CHAR(A,C); }while(0) + SERIAL_ECHOPAIR(" " STRINGIFY(A) ":", planner.triggered_position_mm(_AXIS(A))); _SET_STOP_CHAR(A,C); }while(0) #define _ENDSTOP_HIT_TEST(A,C) \ - if (TEST(hit_state, A ##_MIN) || TEST(hit_state, A ##_MAX)) \ + if (TERN0(HAS_##A##_MIN, TEST(hit_state, A##_MIN)) || TERN0(HAS_##A##_MAX, TEST(hit_state, A##_MAX))) \ _ENDSTOP_HIT_ECHO(A,C) #define ENDSTOP_HIT_TEST_X() _ENDSTOP_HIT_TEST(X,'X') #define ENDSTOP_HIT_TEST_Y() _ENDSTOP_HIT_TEST(Y,'Y') #define ENDSTOP_HIT_TEST_Z() _ENDSTOP_HIT_TEST(Z,'Z') + #define ENDSTOP_HIT_TEST_I() _ENDSTOP_HIT_TEST(I,'I') + #define ENDSTOP_HIT_TEST_J() _ENDSTOP_HIT_TEST(J,'J') + #define ENDSTOP_HIT_TEST_K() _ENDSTOP_HIT_TEST(K,'K') SERIAL_ECHO_START(); SERIAL_ECHOPGM(STR_ENDSTOPS_HIT); - ENDSTOP_HIT_TEST_X(); - ENDSTOP_HIT_TEST_Y(); - ENDSTOP_HIT_TEST_Z(); - - #if HAS_CUSTOM_PROBE_PIN + LINEAR_AXIS_CODE( + ENDSTOP_HIT_TEST_X(), + ENDSTOP_HIT_TEST_Y(), + ENDSTOP_HIT_TEST_Z(), + _ENDSTOP_HIT_TEST(I,'I'), + _ENDSTOP_HIT_TEST(J,'J'), + _ENDSTOP_HIT_TEST(K,'K') + ); + + #if USES_Z_MIN_PROBE_PIN #define P_AXIS Z_AXIS if (TEST(hit_state, Z_MIN_PROBE)) _ENDSTOP_HIT_ECHO(P, 'P'); #endif SERIAL_EOL(); - TERN_(HAS_WIRED_LCD, ui.status_printf_P(0, PSTR(S_FMT " %c %c %c %c"), GET_TEXT(MSG_LCD_ENDSTOPS), chrX, chrY, chrZ, chrP)); + TERN_(HAS_STATUS_MESSAGE, + ui.status_printf_P(0, + PSTR(S_FMT GANG_N_1(LINEAR_AXES, " %c") " %c"), + GET_TEXT(MSG_LCD_ENDSTOPS), + LINEAR_AXIS_LIST(chrX, chrY, chrZ, chrI, chrJ, chrK), chrP + ) + ); #if BOTH(SD_ABORT_ON_ENDSTOP_HIT, SDSUPPORT) if (planner.abort_on_endstop_hit) { - card.endFilePrint(); + card.abortFilePrintNow(); quickstop_stepper(); thermalManager.disable_all_heaters(); print_job_timer.stop(); @@ -395,13 +478,21 @@ void Endstops::event_handler() { } } +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + static void print_es_state(const bool is_hit, PGM_P const label=nullptr) { - if (label) serialprintPGM(label); + if (label) SERIAL_ECHOPGM_P(label); SERIAL_ECHOPGM(": "); - serialprintPGM(is_hit ? PSTR(STR_ENDSTOP_HIT) : PSTR(STR_ENDSTOP_OPEN)); - SERIAL_EOL(); + SERIAL_ECHOLNPGM_P(is_hit ? PSTR(STR_ENDSTOP_HIT) : PSTR(STR_ENDSTOP_OPEN)); } +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic pop +#endif + void _O2 Endstops::report_states() { TERN_(BLTOUCH, bltouch._set_SW_mode()); SERIAL_ECHOLNPGM(STR_M119_REPORT); @@ -454,26 +545,46 @@ void _O2 Endstops::report_states() { #if HAS_Z4_MAX ES_REPORT(Z4_MAX); #endif - #if HAS_CUSTOM_PROBE_PIN - print_es_state(READ(Z_MIN_PROBE_PIN) != Z_MIN_PROBE_ENDSTOP_INVERTING, PSTR(STR_Z_PROBE)); + #if HAS_I_MIN + ES_REPORT(I_MIN); #endif - #if HAS_FILAMENT_SENSOR - #if NUM_RUNOUT_SENSORS == 1 - print_es_state(READ(FIL_RUNOUT_PIN) != FIL_RUNOUT_STATE, PSTR(STR_FILAMENT_RUNOUT_SENSOR)); - #else - #define _CASE_RUNOUT(N) case N: pin = FIL_RUNOUT##N##_PIN; break; - LOOP_S_LE_N(i, 1, NUM_RUNOUT_SENSORS) { - pin_t pin; - switch (i) { - default: continue; - REPEAT_S(1, INCREMENT(NUM_RUNOUT_SENSORS), _CASE_RUNOUT) - } - SERIAL_ECHOPGM(STR_FILAMENT_RUNOUT_SENSOR); - if (i > 1) SERIAL_CHAR(' ', '0' + i); - print_es_state(extDigitalRead(pin) != FIL_RUNOUT_STATE); + #if HAS_I_MAX + ES_REPORT(I_MAX); + #endif + #if HAS_J_MIN + ES_REPORT(J_MIN); + #endif + #if HAS_J_MAX + ES_REPORT(J_MAX); + #endif + #if HAS_K_MIN + ES_REPORT(K_MIN); + #endif + #if HAS_K_MAX + ES_REPORT(K_MAX); + #endif + #if BOTH(MARLIN_DEV_MODE, PROBE_ACTIVATION_SWITCH) + print_es_state(probe_switch_activated(), PSTR(STR_PROBE_EN)); + #endif + #if USES_Z_MIN_PROBE_PIN + print_es_state(PROBE_TRIGGERED(), PSTR(STR_Z_PROBE)); + #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) { + pin_t pin; + uint8_t state; + switch (i) { + default: continue; + REPEAT_1(NUM_RUNOUT_SENSORS, _CASE_RUNOUT) } - #undef _CASE_RUNOUT - #endif + SERIAL_ECHOPGM(STR_FILAMENT_RUNOUT_SENSOR); + if (i > 1) SERIAL_CHAR(' ', '0' + i); + print_es_state(extDigitalRead(pin) != state); + } + #undef _CASE_RUNOUT + #elif HAS_FILAMENT_SENSOR + print_es_state(READ(FIL_RUNOUT1_PIN) != FIL_RUNOUT1_STATE, PSTR(STR_FILAMENT_RUNOUT_SENSOR)); #endif TERN_(BLTOUCH, bltouch._reset_SW_mode()); @@ -484,9 +595,16 @@ void _O2 Endstops::report_states() { // The following routines are called from an ISR context. It could be the temperature ISR, the // endstop ISR or the Stepper ISR. -#define _ENDSTOP(AXIS, MINMAX) AXIS ##_## MINMAX -#define _ENDSTOP_PIN(AXIS, MINMAX) AXIS ##_## MINMAX ##_PIN -#define _ENDSTOP_INVERTING(AXIS, MINMAX) AXIS ##_## MINMAX ##_ENDSTOP_INVERTING +#if BOTH(DELTA, SENSORLESS_PROBING) + #define __ENDSTOP(AXIS, ...) AXIS ##_MAX + #define _ENDSTOP_PIN(AXIS, ...) AXIS ##_MAX_PIN + #define _ENDSTOP_INVERTING(AXIS, ...) AXIS ##_MAX_ENDSTOP_INVERTING +#else + #define __ENDSTOP(AXIS, MINMAX) AXIS ##_## MINMAX + #define _ENDSTOP_PIN(AXIS, MINMAX) AXIS ##_## MINMAX ##_PIN + #define _ENDSTOP_INVERTING(AXIS, MINMAX) AXIS ##_## MINMAX ##_ENDSTOP_INVERTING +#endif +#define _ENDSTOP(AXIS, MINMAX) __ENDSTOP(AXIS, MINMAX) // Check endstops - Could be called from Temperature ISR! void Endstops::update() { @@ -498,20 +616,15 @@ void Endstops::update() { #define UPDATE_ENDSTOP_BIT(AXIS, MINMAX) SET_BIT_TO(live_state, _ENDSTOP(AXIS, MINMAX), (READ(_ENDSTOP_PIN(AXIS, MINMAX)) != _ENDSTOP_INVERTING(AXIS, MINMAX))) #define COPY_LIVE_STATE(SRC_BIT, DST_BIT) SET_BIT_TO(live_state, DST_BIT, TEST(live_state, SRC_BIT)) - #if ENABLED(G38_PROBE_TARGET) && PIN_EXISTS(Z_MIN_PROBE) && NONE(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY) - // If G38 command is active check Z_MIN_PROBE for ALL movement - if (G38_move) UPDATE_ENDSTOP_BIT(Z, MIN_PROBE); + #if ENABLED(G38_PROBE_TARGET) && NONE(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY) + #define HAS_G38_PROBE 1 + // For G38 moves check the probe's pin for ALL movement + if (G38_move) UPDATE_ENDSTOP_BIT(Z, TERN(USES_Z_MIN_PROBE_PIN, MIN_PROBE, MIN)); #endif // With Dual X, endstops are only checked in the homing direction for the active extruder - #if ENABLED(DUAL_X_CARRIAGE) - #define E0_ACTIVE stepper.last_moved_extruder == 0 - #define X_MIN_TEST() ((X_HOME_DIR < 0 && E0_ACTIVE) || (X2_HOME_DIR < 0 && !E0_ACTIVE)) - #define X_MAX_TEST() ((X_HOME_DIR > 0 && E0_ACTIVE) || (X2_HOME_DIR > 0 && !E0_ACTIVE)) - #else - #define X_MIN_TEST() true - #define X_MAX_TEST() true - #endif + #define X_MIN_TEST() TERN1(DUAL_X_CARRIAGE, TERN0(X_HOME_TO_MIN, stepper.last_moved_extruder == 0) || TERN0(X2_HOME_TO_MIN, stepper.last_moved_extruder != 0)) + #define X_MAX_TEST() TERN1(DUAL_X_CARRIAGE, TERN0(X_HOME_TO_MAX, stepper.last_moved_extruder == 0) || TERN0(X2_HOME_TO_MAX, stepper.last_moved_extruder != 0)) // Use HEAD for core axes, AXIS for others #if ANY(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY) @@ -530,6 +643,10 @@ void Endstops::update() { #define Z_AXIS_HEAD Z_AXIS #endif + #define I_AXIS_HEAD I_AXIS + #define J_AXIS_HEAD J_AXIS + #define K_AXIS_HEAD K_AXIS + /** * Check and update endstops */ @@ -577,7 +694,7 @@ void Endstops::update() { #endif #endif - #if HAS_Z_MIN && !Z_SPI_SENSORLESS + #if HAS_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 @@ -602,9 +719,10 @@ void Endstops::update() { #endif #endif - // When closing the gap check the enabled probe - #if HAS_CUSTOM_PROBE_PIN - UPDATE_ENDSTOP_BIT(Z, MIN_PROBE); + #if HAS_BED_PROBE + // When closing the gap check the enabled probe + if (probe_switch_activated()) + UPDATE_ENDSTOP_BIT(Z, TERN(USES_Z_MIN_PROBE_PIN, MIN_PROBE, MIN)); #endif #if HAS_Z_MAX && !Z_SPI_SENSORLESS @@ -630,12 +748,90 @@ void Endstops::update() { COPY_LIVE_STATE(Z_MAX, Z4_MAX); #endif #endif - #elif !HAS_CUSTOM_PROBE_PIN || Z_MAX_PIN != Z_MIN_PROBE_PIN + #elif TERN1(USES_Z_MIN_PROBE_PIN, Z_MAX_PIN != Z_MIN_PROBE_PIN) // If this pin isn't the bed probe it's the Z endstop UPDATE_ENDSTOP_BIT(Z, MAX); #endif #endif + #if HAS_I_MIN && !I_SPI_SENSORLESS + #if ENABLED(I_DUAL_ENDSTOPS) + UPDATE_ENDSTOP_BIT(I, MIN); + #if HAS_I2_MIN + UPDATE_ENDSTOP_BIT(I2, MAX); + #else + COPY_LIVE_STATE(I_MIN, I2_MIN); + #endif + #else + UPDATE_ENDSTOP_BIT(I, MIN); + #endif + #endif + + #if HAS_I_MAX && !I_SPI_SENSORLESS + #if ENABLED(I_DUAL_ENDSTOPS) + UPDATE_ENDSTOP_BIT(I, MAX); + #if HAS_I2_MAX + UPDATE_ENDSTOP_BIT(I2, MAX); + #else + COPY_LIVE_STATE(I_MAX, I2_MAX); + #endif + #else + UPDATE_ENDSTOP_BIT(I, MAX); + #endif + #endif + + #if HAS_J_MIN && !J_SPI_SENSORLESS + #if ENABLED(J_DUAL_ENDSTOPS) + UPDATE_ENDSTOP_BIT(J, MIN); + #if HAS_J2_MIN + UPDATE_ENDSTOP_BIT(J2, MIN); + #else + COPY_LIVE_STATE(J_MIN, J2_MIN); + #endif + #else + UPDATE_ENDSTOP_BIT(J, MIN); + #endif + #endif + + #if HAS_J_MAX && !J_SPI_SENSORLESS + #if ENABLED(J_DUAL_ENDSTOPS) + UPDATE_ENDSTOP_BIT(J, MAX); + #if HAS_J2_MAX + UPDATE_ENDSTOP_BIT(J2, MAX); + #else + COPY_LIVE_STATE(J_MAX, J2_MAX); + #endif + #else + UPDATE_ENDSTOP_BIT(J, MAX); + #endif + #endif + + #if HAS_K_MIN && !K_SPI_SENSORLESS + #if ENABLED(K_DUAL_ENDSTOPS) + UPDATE_ENDSTOP_BIT(K, MIN); + #if HAS_K2_MIN + UPDATE_ENDSTOP_BIT(K2, MIN); + #else + COPY_LIVE_STATE(K_MIN, K2_MIN); + #endif + #else + UPDATE_ENDSTOP_BIT(K, MIN); + #endif + #endif + + #if HAS_K_MAX && !K_SPI_SENSORLESS + #if ENABLED(K_DUAL_ENDSTOPS) + UPDATE_ENDSTOP_BIT(K, MAX); + #if HAS_K2_MAX + UPDATE_ENDSTOP_BIT(K2, MAX); + #else + COPY_LIVE_STATE(K_MAX, K2_MAX); + #endif + #else + UPDATE_ENDSTOP_BIT(K, MAX); + #endif + #endif + #if ENDSTOP_NOISE_THRESHOLD /** @@ -648,7 +844,7 @@ void Endstops::update() { * still exist. The only way to reduce them further is to increase the number of samples. * To reduce the chance to 1% (1/128th) requires 7 samples (adding 7ms of delay). */ - static esbits_t old_live_state; + static endstop_mask_t old_live_state; if (old_live_state != live_state) { endstop_poll_count = ENDSTOP_NOISE_THRESHOLD; old_live_state = live_state; @@ -688,7 +884,7 @@ void Endstops::update() { const byte dual_hit = TEST_ENDSTOP(_ENDSTOP(A, MINMAX)) | (TEST_ENDSTOP(_ENDSTOP(A##2, MINMAX)) << 1); \ if (dual_hit) { \ _ENDSTOP_HIT(A, MINMAX); \ - /* if not performing home or if both endstops were trigged during homing... */ \ + /* if not performing home or if both endstops were triggered during homing... */ \ if (!stepper.separate_multi_axis || dual_hit == 0b11) \ planner.endstop_triggered(_AXIS(A)); \ } \ @@ -698,7 +894,7 @@ void Endstops::update() { const byte triple_hit = TEST_ENDSTOP(_ENDSTOP(A, MINMAX)) | (TEST_ENDSTOP(_ENDSTOP(A##2, MINMAX)) << 1) | (TEST_ENDSTOP(_ENDSTOP(A##3, MINMAX)) << 2); \ if (triple_hit) { \ _ENDSTOP_HIT(A, MINMAX); \ - /* if not performing home or if both endstops were trigged during homing... */ \ + /* if not performing home or if both endstops were triggered during homing... */ \ if (!stepper.separate_multi_axis || triple_hit == 0b111) \ planner.endstop_triggered(_AXIS(A)); \ } \ @@ -708,7 +904,7 @@ void Endstops::update() { const byte quad_hit = TEST_ENDSTOP(_ENDSTOP(A, MINMAX)) | (TEST_ENDSTOP(_ENDSTOP(A##2, MINMAX)) << 1) | (TEST_ENDSTOP(_ENDSTOP(A##3, MINMAX)) << 2) | (TEST_ENDSTOP(_ENDSTOP(A##4, MINMAX)) << 3); \ if (quad_hit) { \ _ENDSTOP_HIT(A, MINMAX); \ - /* if not performing home or if both endstops were trigged during homing... */ \ + /* if not performing home or if both endstops were triggered during homing... */ \ if (!stepper.separate_multi_axis || quad_hit == 0b1111) \ planner.endstop_triggered(_AXIS(A)); \ } \ @@ -736,17 +932,17 @@ void Endstops::update() { #define PROCESS_ENDSTOP_Z(MINMAX) PROCESS_DUAL_ENDSTOP(Z, MINMAX) #endif - #if ENABLED(G38_PROBE_TARGET) && PIN_EXISTS(Z_MIN_PROBE) && NONE(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY) - #if ENABLED(G38_PROBE_AWAY) - #define _G38_OPEN_STATE (G38_move >= 4) - #else - #define _G38_OPEN_STATE LOW - #endif - // If G38 command is active check Z_MIN_PROBE for ALL movement - if (G38_move && TEST_ENDSTOP(_ENDSTOP(Z, MIN_PROBE)) != _G38_OPEN_STATE) { - if (stepper.axis_is_moving(X_AXIS)) { _ENDSTOP_HIT(X, MIN); planner.endstop_triggered(X_AXIS); } - else if (stepper.axis_is_moving(Y_AXIS)) { _ENDSTOP_HIT(Y, MIN); planner.endstop_triggered(Y_AXIS); } - else if (stepper.axis_is_moving(Z_AXIS)) { _ENDSTOP_HIT(Z, MIN); planner.endstop_triggered(Z_AXIS); } + #if HAS_G38_PROBE + #define _G38_OPEN_STATE TERN(G38_PROBE_AWAY, (G38_move >= 4), LOW) + // For G38 moves check the probe's pin for ALL movement + if (G38_move && TEST_ENDSTOP(_ENDSTOP(Z, TERN(USES_Z_MIN_PROBE_PIN, MIN_PROBE, MIN))) != _G38_OPEN_STATE) { + if (stepper.axis_is_moving(X_AXIS)) { _ENDSTOP_HIT(X, TERN(X_HOME_TO_MIN, MIN, MAX)); planner.endstop_triggered(X_AXIS); } + #if HAS_Y_AXIS + else if (stepper.axis_is_moving(Y_AXIS)) { _ENDSTOP_HIT(Y, TERN(Y_HOME_TO_MIN, MIN, MAX)); planner.endstop_triggered(Y_AXIS); } + #endif + #if HAS_Z_AXIS + else if (stepper.axis_is_moving(Z_AXIS)) { _ENDSTOP_HIT(Z, TERN(Z_HOME_TO_MIN, MIN, MAX)); planner.endstop_triggered(Z_AXIS); } + #endif G38_did_trigger = true; } #endif @@ -755,7 +951,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_DIR < 0) + #if HAS_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); @@ -769,7 +965,7 @@ void Endstops::update() { #endif } else { // +direction - #if HAS_X_MAX || (X_SPI_SENSORLESS && X_HOME_DIR > 0) + #if HAS_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); @@ -784,79 +980,128 @@ void Endstops::update() { } } - if (stepper.axis_is_moving(Y_AXIS)) { - if (stepper.motor_direction(Y_AXIS_HEAD)) { // -direction - #if HAS_Y_MIN || (Y_SPI_SENSORLESS && Y_HOME_DIR < 0) - PROCESS_ENDSTOP_Y(MIN); - #if CORE_DIAG(XY, X, MIN) - PROCESS_CORE_ENDSTOP(X,MIN,Y,MIN); - #elif CORE_DIAG(XY, X, MAX) - PROCESS_CORE_ENDSTOP(X,MAX,Y,MIN); - #elif CORE_DIAG(YZ, Z, MIN) - PROCESS_CORE_ENDSTOP(Z,MIN,Y,MIN); - #elif CORE_DIAG(YZ, Z, MAX) - PROCESS_CORE_ENDSTOP(Z,MAX,Y,MIN); + #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) + PROCESS_ENDSTOP_Y(MIN); + #if CORE_DIAG(XY, X, MIN) + PROCESS_CORE_ENDSTOP(X,MIN,Y,MIN); + #elif CORE_DIAG(XY, X, MAX) + PROCESS_CORE_ENDSTOP(X,MAX,Y,MIN); + #elif CORE_DIAG(YZ, Z, MIN) + PROCESS_CORE_ENDSTOP(Z,MIN,Y,MIN); + #elif CORE_DIAG(YZ, Z, MAX) + PROCESS_CORE_ENDSTOP(Z,MAX,Y,MIN); + #endif #endif - #endif + } + else { // +direction + #if HAS_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); + #elif CORE_DIAG(XY, X, MAX) + PROCESS_CORE_ENDSTOP(X,MAX,Y,MAX); + #elif CORE_DIAG(YZ, Z, MIN) + PROCESS_CORE_ENDSTOP(Z,MIN,Y,MAX); + #elif CORE_DIAG(YZ, Z, MAX) + PROCESS_CORE_ENDSTOP(Z,MAX,Y,MAX); + #endif + #endif + } } - else { // +direction - #if HAS_Y_MAX || (Y_SPI_SENSORLESS && Y_HOME_DIR > 0) - PROCESS_ENDSTOP_Y(MAX); - #if CORE_DIAG(XY, X, MIN) - PROCESS_CORE_ENDSTOP(X,MIN,Y,MAX); - #elif CORE_DIAG(XY, X, MAX) - PROCESS_CORE_ENDSTOP(X,MAX,Y,MAX); - #elif CORE_DIAG(YZ, Z, MIN) - PROCESS_CORE_ENDSTOP(Z,MIN,Y,MAX); - #elif CORE_DIAG(YZ, Z, MAX) - PROCESS_CORE_ENDSTOP(Z,MAX,Y,MAX); + #endif + + #if HAS_Z_AXIS + 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 ( 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); + #if CORE_DIAG(XZ, X, MIN) + PROCESS_CORE_ENDSTOP(X,MIN,Z,MIN); + #elif CORE_DIAG(XZ, X, MAX) + PROCESS_CORE_ENDSTOP(X,MAX,Z,MIN); + #elif CORE_DIAG(YZ, Y, MIN) + PROCESS_CORE_ENDSTOP(Y,MIN,Z,MIN); + #elif CORE_DIAG(YZ, Y, MAX) + PROCESS_CORE_ENDSTOP(Y,MAX,Z,MIN); + #endif #endif - #endif + + // When closing the gap check the enabled probe + #if USES_Z_MIN_PROBE_PIN + if (z_probe_enabled) PROCESS_ENDSTOP(Z, MIN_PROBE); + #endif + } + else { // Z +direction. Gantry up, bed down. + #if HAS_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 + PROCESS_ENDSTOP(Z, MAX); + #endif + #if CORE_DIAG(XZ, X, MIN) + PROCESS_CORE_ENDSTOP(X,MIN,Z,MAX); + #elif CORE_DIAG(XZ, X, MAX) + PROCESS_CORE_ENDSTOP(X,MAX,Z,MAX); + #elif CORE_DIAG(YZ, Y, MIN) + PROCESS_CORE_ENDSTOP(Y,MIN,Z,MAX); + #elif CORE_DIAG(YZ, Y, MAX) + PROCESS_CORE_ENDSTOP(Y,MAX,Z,MAX); + #endif + #endif + } } - } + #endif - 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_DIR < 0) - if ( TERN1(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN, z_probe_enabled) - && TERN1(HAS_CUSTOM_PROBE_PIN, !z_probe_enabled) - ) PROCESS_ENDSTOP_Z(MIN); - #if CORE_DIAG(XZ, X, MIN) - PROCESS_CORE_ENDSTOP(X,MIN,Z,MIN); - #elif CORE_DIAG(XZ, X, MAX) - PROCESS_CORE_ENDSTOP(X,MAX,Z,MIN); - #elif CORE_DIAG(YZ, Y, MIN) - PROCESS_CORE_ENDSTOP(Y,MIN,Z,MIN); - #elif CORE_DIAG(YZ, Y, MAX) - PROCESS_CORE_ENDSTOP(Y,MAX,Z,MIN); + #if LINEAR_AXES >= 4 + 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) + PROCESS_ENDSTOP(I, MIN); #endif - #endif + } + else { // +direction + #if HAS_I_MAX || (I_SPI_SENSORLESS && I_HOME_TO_MAX) + PROCESS_ENDSTOP(I, MAX); + #endif + } + } + #endif - // When closing the gap check the enabled probe - #if HAS_CUSTOM_PROBE_PIN - if (z_probe_enabled) PROCESS_ENDSTOP(Z, MIN_PROBE); - #endif + #if LINEAR_AXES >= 5 + 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) + PROCESS_ENDSTOP(J, MIN); + #endif + } + else { // +direction + #if HAS_J_MAX || (J_SPI_SENSORLESS && J_HOME_TO_MAX) + PROCESS_ENDSTOP(J, MAX); + #endif + } } - else { // Z +direction. Gantry up, bed down. - #if HAS_Z_MAX || (Z_SPI_SENSORLESS && Z_HOME_DIR > 0) - #if ENABLED(Z_MULTI_ENDSTOPS) - PROCESS_ENDSTOP_Z(MAX); - #elif !HAS_CUSTOM_PROBE_PIN || Z_MAX_PIN != Z_MIN_PROBE_PIN // No probe or probe is Z_MIN || Probe is not Z_MAX - PROCESS_ENDSTOP(Z, MAX); + #endif + + #if LINEAR_AXES >= 6 + 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) + PROCESS_ENDSTOP(K, MIN); #endif - #if CORE_DIAG(XZ, X, MIN) - PROCESS_CORE_ENDSTOP(X,MIN,Z,MAX); - #elif CORE_DIAG(XZ, X, MAX) - PROCESS_CORE_ENDSTOP(X,MAX,Z,MAX); - #elif CORE_DIAG(YZ, Y, MIN) - PROCESS_CORE_ENDSTOP(Y,MIN,Z,MAX); - #elif CORE_DIAG(YZ, Y, MAX) - PROCESS_CORE_ENDSTOP(Y,MAX,Z,MAX); + } + else { // +direction + #if HAS_K_MAX || (K_SPI_SENSORLESS && K_HOME_TO_MAX) + PROCESS_ENDSTOP(K, MAX); #endif - #endif + } } - } + #endif } // Endstops::update() #if ENABLED(SPI_ENDSTOPS) @@ -899,6 +1144,27 @@ void Endstops::update() { hit = true; } #endif + #if I_SPI_SENSORLESS + if (tmc_spi_homing.i && stepperI.test_stall_status()) { + SBI(live_state, I_ENDSTOP); + hit = true; + } + #endif + #if J_SPI_SENSORLESS + if (tmc_spi_homing.j && stepperJ.test_stall_status()) { + SBI(live_state, J_ENDSTOP); + hit = true; + } + #endif + #if K_SPI_SENSORLESS + if (tmc_spi_homing.k && stepperK.test_stall_status()) { + SBI(live_state, K_ENDSTOP); + hit = true; + } + #endif + + if (TERN0(ENDSTOP_INTERRUPTS_FEATURE, hit)) update(); + return hit; } @@ -906,6 +1172,9 @@ void Endstops::update() { TERN_(X_SPI_SENSORLESS, CBI(live_state, X_ENDSTOP)); TERN_(Y_SPI_SENSORLESS, CBI(live_state, Y_ENDSTOP)); TERN_(Z_SPI_SENSORLESS, CBI(live_state, Z_ENDSTOP)); + TERN_(I_SPI_SENSORLESS, CBI(live_state, I_ENDSTOP)); + TERN_(J_SPI_SENSORLESS, CBI(live_state, J_ENDSTOP)); + TERN_(K_SPI_SENSORLESS, CBI(live_state, K_ENDSTOP)); } #endif // SPI_ENDSTOPS @@ -982,6 +1251,24 @@ void Endstops::update() { #if HAS_Z4_MAX ES_GET_STATE(Z4_MAX); #endif + #if HAS_I_MAX + ES_GET_STATE(I_MAX); + #endif + #if HAS_I_MIN + ES_GET_STATE(I_MIN); + #endif + #if HAS_J_MAX + ES_GET_STATE(J_MAX); + #endif + #if HAS_J_MIN + ES_GET_STATE(J_MIN); + #endif + #if HAS_K_MAX + ES_GET_STATE(K_MAX); + #endif + #if HAS_K_MIN + ES_GET_STATE(K_MIN); + #endif uint16_t endstop_change = live_state_local ^ old_live_state_local; #define ES_REPORT_CHANGE(S) if (TEST(endstop_change, S)) SERIAL_ECHOPAIR(" " STRINGIFY(S) ":", TEST(live_state_local, S)) @@ -1038,6 +1325,24 @@ void Endstops::update() { #if HAS_Z4_MAX ES_REPORT_CHANGE(Z4_MAX); #endif + #if HAS_I_MIN + ES_REPORT_CHANGE(I_MIN); + #endif + #if HAS_I_MAX + ES_REPORT_CHANGE(I_MAX); + #endif + #if HAS_J_MIN + ES_REPORT_CHANGE(J_MIN); + #endif + #if HAS_J_MAX + ES_REPORT_CHANGE(J_MAX); + #endif + #if HAS_K_MIN + ES_REPORT_CHANGE(K_MIN); + #endif + #if HAS_K_MAX + ES_REPORT_CHANGE(K_MAX); + #endif SERIAL_ECHOLNPGM("\n"); analogWrite(pin_t(LED_PIN), local_LED_status); local_LED_status ^= 255; diff --git a/Marlin/src/module/endstops.h b/Marlin/src/module/endstops.h index 888d25a8bdf3..e688d3a78844 100644 --- a/Marlin/src/module/endstops.h +++ b/Marlin/src/module/endstops.h @@ -28,44 +28,94 @@ #include "../inc/MarlinConfig.h" #include +#define __ES_ITEM(N) N, +#define _ES_ITEM(K,N) TERN_(K,DEFER4(__ES_ITEM)(N)) + enum EndstopEnum : char { - X_MIN, Y_MIN, Z_MIN, Z_MIN_PROBE, - X_MAX, Y_MAX, Z_MAX, - X2_MIN, X2_MAX, - Y2_MIN, Y2_MAX, - Z2_MIN, Z2_MAX, - Z3_MIN, Z3_MAX, - Z4_MIN, Z4_MAX + // 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) + + // Extra Endstops for XYZ + _ES_ITEM(HAS_X2_MIN, X2_MIN) + _ES_ITEM(HAS_X2_MAX, X2_MAX) + _ES_ITEM(HAS_Y2_MIN, Y2_MIN) + _ES_ITEM(HAS_Y2_MAX, Y2_MAX) + _ES_ITEM(HAS_Z2_MIN, Z2_MIN) + _ES_ITEM(HAS_Z2_MAX, Z2_MAX) + _ES_ITEM(HAS_Z3_MIN, Z3_MIN) + _ES_ITEM(HAS_Z3_MAX, Z3_MAX) + _ES_ITEM(HAS_Z4_MIN, Z4_MIN) + _ES_ITEM(HAS_Z4_MAX, Z4_MAX) + + // Bed Probe state is distinct or shared with Z_MIN (i.e., when the probe is the only Z endstop) + _ES_ITEM(HAS_BED_PROBE, Z_MIN_PROBE IF_DISABLED(USES_Z_MIN_PROBE_PIN, = Z_MIN)) + + // The total number of states + NUM_ENDSTOP_STATES + + // Endstops can be either MIN or MAX but not both + #if HAS_X_MIN || HAS_X_MAX + , X_ENDSTOP = TERN(X_HOME_TO_MAX, X_MAX, X_MIN) + #endif + #if HAS_Y_MIN || HAS_Y_MAX + , Y_ENDSTOP = TERN(Y_HOME_TO_MAX, Y_MAX, Y_MIN) + #endif + #if HAS_Z_MIN || HAS_Z_MAX || HOMING_Z_WITH_PROBE + , Z_ENDSTOP = TERN(Z_HOME_TO_MAX, Z_MAX, TERN(HOMING_Z_WITH_PROBE, Z_MIN_PROBE, Z_MIN)) + #endif + #if HAS_I_MIN || HAS_I_MAX + , I_ENDSTOP = TERN(I_HOME_TO_MAX, I_MAX, I_MIN) + #endif + #if HAS_J_MIN || HAS_J_MAX + , J_ENDSTOP = TERN(J_HOME_TO_MAX, J_MAX, J_MIN) + #endif + #if HAS_K_MIN || HAS_K_MAX + , K_ENDSTOP = TERN(K_HOME_TO_MAX, K_MAX, K_MIN) + #endif }; -#define X_ENDSTOP (X_HOME_DIR < 0 ? X_MIN : X_MAX) -#define Y_ENDSTOP (Y_HOME_DIR < 0 ? Y_MIN : Y_MAX) -#define Z_ENDSTOP (Z_HOME_DIR < 0 ? TERN(HOMING_Z_WITH_PROBE, Z_MIN, Z_MIN_PROBE) : Z_MAX) +#undef __ES_ITEM +#undef _ES_ITEM class Endstops { public: - #if HAS_EXTRA_ENDSTOPS - typedef uint16_t esbits_t; - TERN_(X_DUAL_ENDSTOPS, static float x2_endstop_adj); - TERN_(Y_DUAL_ENDSTOPS, static float y2_endstop_adj); - TERN_(Z_MULTI_ENDSTOPS, static float z2_endstop_adj); - #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 3 - static float z3_endstop_adj; - #endif - #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4 - static float z4_endstop_adj; - #endif - #else - typedef uint8_t esbits_t; + + typedef IF<(NUM_ENDSTOP_STATES > 8), uint16_t, uint8_t>::type endstop_mask_t; + + #if ENABLED(X_DUAL_ENDSTOPS) + static float x2_endstop_adj; + #endif + #if ENABLED(Y_DUAL_ENDSTOPS) + static float y2_endstop_adj; + #endif + #if ENABLED(Z_MULTI_ENDSTOPS) + static float z2_endstop_adj; + #endif + #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 3 + static float z3_endstop_adj; + #endif + #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4 + static float z4_endstop_adj; #endif private: static bool enabled, enabled_globally; - static esbits_t live_state; - static volatile uint8_t hit_state; // Use X_MIN, Y_MIN, Z_MIN and Z_MIN_PROBE as BIT index + static endstop_mask_t live_state; + static volatile endstop_mask_t hit_state; // Use X_MIN, Y_MIN, Z_MIN and Z_MIN_PROBE as BIT index #if ENDSTOP_NOISE_THRESHOLD - static esbits_t validated_live_state; + static endstop_mask_t validated_live_state; static uint8_t endstop_poll_count; // Countdown from threshold for polling #endif @@ -101,12 +151,12 @@ class Endstops { /** * Get Endstop hit state. */ - FORCE_INLINE static uint8_t trigger_state() { return hit_state; } + FORCE_INLINE static endstop_mask_t trigger_state() { return hit_state; } /** * Get current endstops state */ - FORCE_INLINE static esbits_t state() { + FORCE_INLINE static endstop_mask_t state() { return #if ENDSTOP_NOISE_THRESHOLD validated_live_state @@ -116,6 +166,14 @@ class Endstops { ; } + static inline bool probe_switch_activated() { + return (true + #if ENABLED(PROBE_ACTIVATION_SWITCH) + && READ(PROBE_ACTIVATION_SWITCH_PIN) == PROBE_ACTIVATION_SWITCH_STATE + #endif + ); + } + /** * Report endstop hits to serial. Called from loop(). */ @@ -164,7 +222,7 @@ class Endstops { typedef struct { union { bool any; - struct { bool x:1, y:1, z:1; }; + struct { bool LINEAR_AXIS_LIST(x:1, y:1, z:1, i:1, j:1, k:1); }; }; } tmc_spi_homing_t; static tmc_spi_homing_t tmc_spi_homing; diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 5b3fab10b1e9..eb6dc6597ce4 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -36,7 +36,7 @@ #if IS_SCARA #include "../libs/buzzer.h" - #include "../lcd/ultralcd.h" + #include "../lcd/marlinui.h" #endif #if HAS_BED_PROBE @@ -51,8 +51,8 @@ #include "../feature/bltouch.h" #endif -#if HAS_DISPLAY - #include "../lcd/ultralcd.h" +#if HAS_STATUS_MESSAGE + #include "../lcd/marlinui.h" #endif #if HAS_FILAMENT_SENSOR @@ -74,17 +74,6 @@ #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) #include "../core/debug_out.h" -/** - * axis_homed - * Flags that each linear axis was homed. - * XYZ on cartesian, ABC on delta, ABZ on SCARA. - * - * axis_known_position - * Flags that the position is known in each linear axis. Set when homed. - * Cleared whenever a stepper powers off, potentially losing its position. - */ -uint8_t axis_homed, axis_known_position; // = 0 - // Relative Mode. Enable with G91, disable with G90. bool relative_mode; // = false; @@ -94,7 +83,13 @@ bool relative_mode; // = false; * Used by 'line_to_current_position' to do a move after changing it. * Used by 'sync_plan_position' to update 'planner.position'. */ -xyze_pos_t current_position = { X_HOME_POS, Y_HOME_POS, Z_HOME_POS }; +#ifdef Z_IDLE_HEIGHT + #define Z_INIT_POS Z_IDLE_HEIGHT +#else + #define Z_INIT_POS Z_HOME_POS +#endif + +xyze_pos_t current_position = LOGICAL_AXIS_ARRAY(0, X_HOME_POS, Y_HOME_POS, Z_INIT_POS, I_HOME_POS, J_HOME_POS, K_HOME_POS); /** * Cartesian Destination @@ -107,7 +102,7 @@ xyze_pos_t destination; // {0} // G60/G61 Position Save and Return #if SAVED_POSITIONS uint8_t saved_slots[(SAVED_POSITIONS + 7) >> 3]; - xyz_pos_t stored_position[SAVED_POSITIONS]; + xyze_pos_t stored_position[SAVED_POSITIONS]; #endif // The active extruder (tool). Set with T command. @@ -129,7 +124,7 @@ xyze_pos_t destination; // {0} "Offsets for the first hotend must be 0.0." ); // Transpose from [XYZ][HOTENDS] to [HOTENDS][XYZ] - HOTEND_LOOP() LOOP_XYZ(a) hotend_offset[e][a] = tmp[a][e]; + HOTEND_LOOP() LOOP_LINEAR_AXES(a) hotend_offset[e][a] = tmp[a][e]; #if ENABLED(DUAL_X_CARRIAGE) hotend_offset[1].x = _MAX(X2_HOME_POS, X2_MAX_POS); #endif @@ -143,22 +138,12 @@ xyze_pos_t destination; // {0} feedRate_t feedrate_mm_s = MMM_TO_MMS(1500); int16_t feedrate_percentage = 100; -// Homing feedrate is const progmem - compare to constexpr in the header -const feedRate_t homing_feedrate_mm_s[XYZ] PROGMEM = { - #if ENABLED(DELTA) - MMM_TO_MMS(HOMING_FEEDRATE_Z), MMM_TO_MMS(HOMING_FEEDRATE_Z), - #else - MMM_TO_MMS(HOMING_FEEDRATE_XY), MMM_TO_MMS(HOMING_FEEDRATE_XY), - #endif - MMM_TO_MMS(HOMING_FEEDRATE_Z) -}; - // Cartesian conversion result goes here: xyz_pos_t cartes; #if IS_KINEMATIC - abc_pos_t delta; + abce_pos_t delta; #if HAS_SCARA_OFFSET abc_pos_t scara_home_offset; @@ -195,7 +180,7 @@ xyz_pos_t cartes; #endif #if HAS_ABL_NOT_UBL - float xy_probe_feedrate_mm_s = MMM_TO_MMS(XY_PROBE_SPEED); + feedRate_t xy_probe_feedrate_mm_s = MMM_TO_MMS(XY_PROBE_FEEDRATE); #endif /** @@ -210,19 +195,34 @@ 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_ECHOPAIR_P(X_LBL, lpos.x, SP_Y_LBL, lpos.y, SP_Z_LBL, lpos.z, SP_E_LBL, lpos.e); + SERIAL_ECHOPAIR_P( + LIST_N(DOUBLE(LINEAR_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 + ) + #if HAS_EXTRUDERS + , SP_E_LBL, lpos.e + #endif + ); } // Report the real current position according to the steppers. // Forward kinematics and un-leveling are applied. void report_real_position() { get_cartesian_from_steppers(); - xyze_pos_t npos = cartes; - npos.e = planner.get_axis_position_mm(E_AXIS); + xyze_pos_t npos = LOGICAL_AXIS_ARRAY( + planner.get_axis_position_mm(E_AXIS), + cartes.x, cartes.y, cartes.z, + planner.get_axis_position_mm(I_AXIS), + planner.get_axis_position_mm(J_AXIS), + planner.get_axis_position_mm(K_AXIS) + ); - #if HAS_POSITION_MODIFIERS - planner.unapply_modifiers(npos, true); - #endif + TERN_(HAS_POSITION_MODIFIERS, planner.unapply_modifiers(npos, true)); report_logical_position(npos); report_more_positions(); @@ -245,9 +245,96 @@ void report_current_position_projected() { stepper.report_a_position(planner.position); } +#if ENABLED(AUTO_REPORT_POSITION) + //struct PositionReport { void report() { report_current_position_projected(); } }; + AutoReporter position_auto_reporter; +#endif + +#if EITHER(FULL_REPORT_TO_HOST_FEATURE, REALTIME_REPORTING_COMMANDS) + + M_StateEnum M_State_grbl = M_INIT; + + /** + * Output the current grbl compatible state to serial while moving + */ + void report_current_grblstate_moving() { SERIAL_ECHOLNPAIR("S_XYZ:", int(M_State_grbl)); } + + /** + * Output the current position (processed) to serial while moving + */ + void report_current_position_moving() { + + get_cartesian_from_steppers(); + const xyz_pos_t lpos = cartes.asLogical(); + SERIAL_ECHOPAIR( + "X:", lpos.x + #if HAS_Y_AXIS + , " Y:", lpos.y + #endif + #if HAS_Z_AXIS + , " Z:", lpos.z + #endif + #if HAS_EXTRUDERS + , " E:", current_position.e + #endif + ); + + stepper.report_positions(); + #if IS_SCARA + scara_report_positions(); + #endif + + report_current_grblstate_moving(); + } + + /** + * Set a Grbl-compatible state from the current marlin_state + */ + M_StateEnum grbl_state_for_marlin_state() { + switch (marlin_state) { + case MF_INITIALIZING: return M_INIT; + case MF_SD_COMPLETE: return M_ALARM; + case MF_WAITING: return M_IDLE; + case MF_STOPPED: return M_END; + case MF_RUNNING: return M_RUNNING; + case MF_PAUSED: return M_HOLD; + case MF_KILLED: return M_ERROR; + default: return M_IDLE; + } + } + +#endif + +void home_if_needed(const bool keeplev/*=false*/) { + if (!all_axes_trusted()) gcode.home_all_axes(keeplev); +} + +/** + * Run out the planner buffer and re-sync the current + * position from the last-updated stepper positions. + */ +void quickstop_stepper() { + planner.quick_stop(); + planner.synchronize(); + set_current_from_steppers_for_axis(ALL_AXES_ENUM); + sync_plan_position(); +} + +#if ENABLED(REALTIME_REPORTING_COMMANDS) + + void quickpause_stepper() { + planner.quick_pause(); + //planner.synchronize(); + } + + void quickresume_stepper() { + planner.quick_resume(); + //planner.synchronize(); + } + +#endif + /** - * sync_plan_position - * * Set the planner/stepper positions directly from current_position with * no kinematic translation. Used for homing axes and cartesian/core syncing. */ @@ -256,7 +343,9 @@ void sync_plan_position() { planner.set_position_mm(current_position); } -void sync_plan_position_e() { planner.set_e_position_mm(current_position.e); } +#if HAS_EXTRUDERS + void sync_plan_position_e() { planner.set_e_position_mm(current_position.e); } +#endif /** * Get the stepper positions in the cartes[] array. @@ -269,17 +358,22 @@ void sync_plan_position_e() { planner.set_e_position_mm(current_position.e); } */ void get_cartesian_from_steppers() { #if ENABLED(DELTA) - forward_kinematics_DELTA(planner.get_axis_positions_mm()); - #else - #if IS_SCARA - forward_kinematics_SCARA( - planner.get_axis_position_degrees(A_AXIS), - planner.get_axis_position_degrees(B_AXIS) - ); - #else - cartes.set(planner.get_axis_position_mm(X_AXIS), planner.get_axis_position_mm(Y_AXIS)); - #endif + forward_kinematics(planner.get_axis_positions_mm()); + #elif IS_SCARA + forward_kinematics( + planner.get_axis_position_degrees(A_AXIS), planner.get_axis_position_degrees(B_AXIS) + OPTARG(AXEL_TPARA, planner.get_axis_position_degrees(C_AXIS)) + ); cartes.z = planner.get_axis_position_mm(Z_AXIS); + #else + LINEAR_AXIS_CODE( + cartes.x = planner.get_axis_position_mm(X_AXIS), + cartes.y = planner.get_axis_position_mm(Y_AXIS), + cartes.z = planner.get_axis_position_mm(Z_AXIS), + cartes.i = planner.get_axis_position_mm(I_AXIS), + cartes.j = planner.get_axis_position_mm(J_AXIS), + cartes.k = planner.get_axis_position_mm(K_AXIS) + ); #endif } @@ -297,13 +391,12 @@ void get_cartesian_from_steppers() { void set_current_from_steppers_for_axis(const AxisEnum axis) { get_cartesian_from_steppers(); xyze_pos_t pos = cartes; - pos.e = planner.get_axis_position_mm(E_AXIS); - #if HAS_POSITION_MODIFIERS - planner.unapply_modifiers(pos, true); - #endif + TERN_(HAS_EXTRUDERS, pos.e = planner.get_axis_position_mm(E_AXIS)); - if (axis == ALL_AXES) + TERN_(HAS_POSITION_MODIFIERS, planner.unapply_modifiers(pos, true)); + + if (axis == ALL_AXES_ENUM) current_position = pos; else current_position[axis] = pos[axis]; @@ -313,12 +406,12 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) { * Move the planner to the current position from wherever it last moved * (or from wherever it has been told it is located). */ -void line_to_current_position(const feedRate_t &fr_mm_s/*=feedrate_mm_s*/) { - planner.buffer_line(current_position, fr_mm_s, active_extruder); +void line_to_current_position(const_feedRate_t fr_mm_s/*=feedrate_mm_s*/) { + planner.buffer_line(current_position, fr_mm_s); } -#if EXTRUDERS - void unscaled_e_move(const float &length, const feedRate_t &fr_mm_s) { +#if HAS_EXTRUDERS + void unscaled_e_move(const_float_t length, const_feedRate_t fr_mm_s) { TERN_(HAS_FILAMENT_SENSOR, runout.reset()); current_position.e += length / planner.e_factor[active_extruder]; line_to_current_position(fr_mm_s); @@ -331,7 +424,7 @@ void line_to_current_position(const feedRate_t &fr_mm_s/*=feedrate_mm_s*/) { /** * Buffer a fast move without interpolation. Set current_position to destination */ - void prepare_fast_move_to_destination(const feedRate_t &scaled_fr_mm_s/*=MMS_SCALED(feedrate_mm_s)*/) { + void prepare_fast_move_to_destination(const_feedRate_t scaled_fr_mm_s/*=MMS_SCALED(feedrate_mm_s)*/) { if (DEBUGGING(LEVELING)) DEBUG_POS("prepare_fast_move_to_destination", destination); #if UBL_SEGMENTED @@ -340,7 +433,7 @@ void line_to_current_position(const feedRate_t &fr_mm_s/*=feedrate_mm_s*/) { #else if (current_position == destination) return; - planner.buffer_line(destination, scaled_fr_mm_s, active_extruder); + planner.buffer_line(destination, scaled_fr_mm_s); #endif current_position = destination; @@ -353,10 +446,8 @@ void line_to_current_position(const feedRate_t &fr_mm_s/*=feedrate_mm_s*/) { * - Move at normal speed regardless of feedrate percentage. * - Extrude the specified length regardless of flow percentage. */ -void _internal_move_to_destination(const feedRate_t &fr_mm_s/*=0.0f*/ - #if IS_KINEMATIC - , const bool is_fast/*=false*/ - #endif +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; @@ -364,49 +455,55 @@ void _internal_move_to_destination(const feedRate_t &fr_mm_s/*=0.0f*/ const uint16_t old_pct = feedrate_percentage; feedrate_percentage = 100; - #if EXTRUDERS + #if HAS_EXTRUDERS const float old_fac = planner.e_factor[active_extruder]; planner.e_factor[active_extruder] = 1.0f; #endif - #if IS_KINEMATIC - if (is_fast) - prepare_fast_move_to_destination(); - else - #endif - prepare_line_to_destination(); + 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; - #if EXTRUDERS - planner.e_factor[active_extruder] = old_fac; - #endif + TERN_(HAS_EXTRUDERS, planner.e_factor[active_extruder] = old_fac); } /** - * Plan a move to (X, Y, Z) and set the current_position + * Plan a move to (X, Y, Z, [I, [J, [K]]]) and set the current_position + * Plan a move to (X, Y, Z) with separation of Z from other components. + * + * - If Z is moving up, the Z move is done before XY, etc. + * - If Z is moving down, the Z move is done after XY, etc. + * - 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(const float rx, const float ry, const float rz, const feedRate_t &fr_mm_s/*=0.0*/) { +void do_blocking_move_to(LINEAR_AXIS_ARGS(const float), const_feedRate_t fr_mm_s/*=0.0f*/) { DEBUG_SECTION(log_move, "do_blocking_move_to", DEBUGGING(LEVELING)); - if (DEBUGGING(LEVELING)) DEBUG_XYZ("> ", rx, ry, rz); + if (DEBUGGING(LEVELING)) DEBUG_XYZ("> ", LINEAR_AXIS_ARGS()); - const feedRate_t z_feedrate = fr_mm_s ?: homing_feedrate(Z_AXIS), - xy_feedrate = fr_mm_s ?: feedRate_t(XY_PROBE_FEEDRATE_MM_S); + const feedRate_t xy_feedrate = fr_mm_s ?: feedRate_t(XY_PROBE_FEEDRATE_MM_S); - #if ENABLED(DELTA) + #if HAS_Z_AXIS + const feedRate_t z_feedrate = fr_mm_s ?: homing_feedrate(Z_AXIS); + #endif - if (!position_is_reachable(rx, ry)) return; + #if EITHER(DELTA, IS_SCARA) + if (!position_is_reachable(x, y)) return; + destination = current_position; // sync destination at the start + #endif - REMEMBER(fr, feedrate_mm_s, xy_feedrate); + #if ENABLED(DELTA) - destination = current_position; // sync destination at the start + REMEMBER(fr, feedrate_mm_s, xy_feedrate); if (DEBUGGING(LEVELING)) DEBUG_POS("destination = current_position", destination); // when in the danger zone if (current_position.z > delta_clip_start_height) { - if (rz > delta_clip_start_height) { // staying in the danger zone - destination.set(rx, ry, rz); // move directly (uninterpolated) + if (z > delta_clip_start_height) { // staying in the danger zone + destination.set(x, y, z); // move directly (uninterpolated) prepare_internal_fast_move_to_destination(); // set current_position from destination if (DEBUGGING(LEVELING)) DEBUG_POS("danger zone move", current_position); return; @@ -416,102 +513,157 @@ void do_blocking_move_to(const float rx, const float ry, const float rz, const f if (DEBUGGING(LEVELING)) DEBUG_POS("zone border move", current_position); } - if (rz > current_position.z) { // raising? - destination.z = rz; + if (z > current_position.z) { // raising? + destination.z = z; prepare_internal_fast_move_to_destination(z_feedrate); // set current_position from destination if (DEBUGGING(LEVELING)) DEBUG_POS("z raise move", current_position); } - destination.set(rx, ry); + destination.set(x, y); prepare_internal_move_to_destination(); // set current_position from destination if (DEBUGGING(LEVELING)) DEBUG_POS("xy move", current_position); - if (rz < current_position.z) { // lowering? - destination.z = rz; + if (z < current_position.z) { // lowering? + destination.z = z; prepare_internal_fast_move_to_destination(z_feedrate); // set current_position from destination if (DEBUGGING(LEVELING)) DEBUG_POS("z lower move", current_position); } #elif IS_SCARA - if (!position_is_reachable(rx, ry)) return; - - destination = current_position; - // If Z needs to raise, do it before moving XY - if (destination.z < rz) { - destination.z = rz; + if (destination.z < z) { + destination.z = z; prepare_internal_fast_move_to_destination(z_feedrate); } - destination.set(rx, ry); + destination.set(x, y); prepare_internal_fast_move_to_destination(xy_feedrate); // If Z needs to lower, do it after moving XY - if (destination.z > rz) { - destination.z = rz; + if (destination.z > z) { + destination.z = z; prepare_internal_fast_move_to_destination(z_feedrate); } #else - // If Z needs to raise, do it before moving XY - if (current_position.z < rz) { - current_position.z = rz; - line_to_current_position(z_feedrate); - } + #if HAS_Z_AXIS + // If Z needs to raise, do it before moving XY + if (current_position.z < z) { + current_position.z = z; + line_to_current_position(z_feedrate); + } + #endif - current_position.set(rx, ry); + current_position.set(x, y); line_to_current_position(xy_feedrate); - // If Z needs to lower, do it after moving XY - if (current_position.z > rz) { - current_position.z = rz; - line_to_current_position(z_feedrate); - } + #if HAS_Z_AXIS + // If Z needs to lower, do it after moving XY + if (current_position.z > z) { + current_position.z = z; + line_to_current_position(z_feedrate); + } + #endif #endif planner.synchronize(); } -void do_blocking_move_to(const xy_pos_t &raw, const feedRate_t &fr_mm_s/*=0.0f*/) { - do_blocking_move_to(raw.x, raw.y, current_position.z, 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(raw.x, raw.y, raw.z, 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(LINEAR_AXIS_LIST(raw.x, raw.y, current_position.z, current_position.i, current_position.j, current_position.k), 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(raw.x, raw.y, raw.z, 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(LINEAR_AXIS_ELEM(raw), fr_mm_s); } - -void do_blocking_move_to_x(const float &rx, const feedRate_t &fr_mm_s/*=0.0*/) { - do_blocking_move_to(rx, current_position.y, current_position.z, fr_mm_s); -} -void do_blocking_move_to_y(const float &ry, const feedRate_t &fr_mm_s/*=0.0*/) { - do_blocking_move_to(current_position.x, ry, current_position.z, 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(LINEAR_AXIS_ELEM(raw), fr_mm_s); } -void do_blocking_move_to_z(const float &rz, const feedRate_t &fr_mm_s/*=0.0*/) { - do_blocking_move_to_xy_z(current_position, rz, 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( + LINEAR_AXIS_LIST(rx, current_position.y, current_position.z, current_position.i, current_position.j, current_position.k), + fr_mm_s + ); } -void do_blocking_move_to_xy(const float &rx, const float &ry, const feedRate_t &fr_mm_s/*=0.0*/) { - do_blocking_move_to(rx, ry, current_position.z, fr_mm_s); -} -void do_blocking_move_to_xy(const xy_pos_t &raw, const feedRate_t &fr_mm_s/*=0.0f*/) { - do_blocking_move_to_xy(raw.x, raw.y, fr_mm_s); -} +#if HAS_Y_AXIS + void do_blocking_move_to_y(const_float_t ry, const_feedRate_t fr_mm_s/*=0.0*/) { + do_blocking_move_to( + LINEAR_AXIS_LIST(current_position.x, ry, current_position.z, current_position.i, current_position.j, current_position.k), + fr_mm_s + ); + } +#endif -void do_blocking_move_to_xy_z(const xy_pos_t &raw, const float &z, const feedRate_t &fr_mm_s/*=0.0f*/) { - do_blocking_move_to(raw.x, raw.y, z, fr_mm_s); -} +#if HAS_Z_AXIS + void do_blocking_move_to_z(const_float_t rz, const_feedRate_t fr_mm_s/*=0.0*/) { + do_blocking_move_to_xy_z(current_position, rz, fr_mm_s); + } +#endif -void do_z_clearance(const float &zclear, const bool z_known/*=true*/, const bool raise_on_unknown/*=true*/, const bool lower_allowed/*=false*/) { - const bool rel = raise_on_unknown && !z_known; - float zdest = zclear + (rel ? current_position.z : 0.0f); - if (!lower_allowed) NOLESS(zdest, current_position.z); - do_blocking_move_to_z(_MIN(zdest, Z_MAX_POS), MMM_TO_MMS(TERN(HAS_BED_PROBE, Z_PROBE_SPEED_FAST, HOMING_FEEDRATE_Z))); -} +#if LINEAR_AXES >= 4 + void do_blocking_move_to_i(const_float_t ri, const_feedRate_t fr_mm_s/*=0.0*/) { + do_blocking_move_to_xyz_i(current_position, ri, fr_mm_s); + } + 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( + LINEAR_AXIS_LIST(raw.x, raw.y, raw.z, i, raw.j, raw.k), + fr_mm_s + ); + } +#endif + +#if LINEAR_AXES >= 5 + void do_blocking_move_to_j(const_float_t rj, const_feedRate_t fr_mm_s/*=0.0*/) { + do_blocking_move_to_xyzi_j(current_position, rj, fr_mm_s); + } + 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( + LINEAR_AXIS_LIST(raw.x, raw.y, raw.z, raw.i, j, raw.k), + fr_mm_s + ); + } +#endif + +#if LINEAR_AXES >= 6 + void do_blocking_move_to_k(const_float_t rk, const_feedRate_t fr_mm_s/*=0.0*/) { + do_blocking_move_to_xyzij_k(current_position, rk, fr_mm_s); + } + 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( + LINEAR_AXIS_LIST(raw.x, raw.y, raw.z, raw.i, raw.j, k), + fr_mm_s + ); + } +#endif + +#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*/) { + do_blocking_move_to( + LINEAR_AXIS_LIST(rx, ry, current_position.z, current_position.i, current_position.j, current_position.k), + fr_mm_s + ); + } + void do_blocking_move_to_xy(const xy_pos_t &raw, const_feedRate_t fr_mm_s/*=0.0f*/) { + do_blocking_move_to_xy(raw.x, raw.y, fr_mm_s); + } +#endif + +#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( + LINEAR_AXIS_LIST(raw.x, raw.y, z, current_position.i, current_position.j, current_position.k), + fr_mm_s + ); + } + void do_z_clearance(const_float_t zclear, const bool lower_allowed/*=false*/) { + float zdest = zclear; + 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))); + } +#endif // // Prepare to do endstop or probe moves with custom feedrates. @@ -537,8 +689,8 @@ void restore_feedrate_and_scaling() { // Software Endstops are based on the configured limits. soft_endstops_t soft_endstop = { true, false, - { X_MIN_POS, Y_MIN_POS, Z_MIN_POS }, - { X_MAX_POS, Y_MAX_POS, Z_MAX_POS } + LINEAR_AXIS_ARRAY(X_MIN_POS, Y_MIN_POS, Z_MIN_POS, I_MIN_POS, J_MIN_POS, K_MIN_POS), + LINEAR_AXIS_ARRAY(X_MAX_BED, Y_MAX_BED, Z_MAX_POS, I_MAX_POS, J_MAX_POS, K_MAX_POS) }; /** @@ -551,10 +703,7 @@ void restore_feedrate_and_scaling() { * at the same positions relative to the machine. */ void update_software_endstops(const AxisEnum axis - #if HAS_HOTEND_OFFSET - , const uint8_t old_tool_index/*=0*/ - , const uint8_t new_tool_index/*=0*/ - #endif + OPTARG(HAS_HOTEND_OFFSET, const uint8_t old_tool_index/*=0*/, const uint8_t new_tool_index/*=0*/) ) { #if ENABLED(DUAL_X_CARRIAGE) @@ -569,7 +718,7 @@ void restore_feedrate_and_scaling() { soft_endstop.min.x = X2_MIN_POS; soft_endstop.max.x = dual_max_x; } - else if (dxc_is_duplicating()) { + else if (idex_is_duplicating()) { // In Duplication Mode, T0 can move as far left as X1_MIN_POS // but not so far to the right that T1 would move past the end soft_endstop.min.x = X1_MIN_POS; @@ -586,7 +735,7 @@ void restore_feedrate_and_scaling() { #elif ENABLED(DELTA) soft_endstop.min[axis] = base_min_pos(axis); - soft_endstop.max[axis] = (axis == Z_AXIS) ? delta_height - TERN0(HAS_BED_PROBE, probe.offset.z) : base_max_pos(axis); + soft_endstop.max[axis] = (axis == Z_AXIS) ? DIFF_TERN(HAS_BED_PROBE, delta_height, probe.offset.z) : base_max_pos(axis); switch (axis) { case X_AXIS: @@ -605,16 +754,17 @@ void restore_feedrate_and_scaling() { // Software endstops are relative to the tool 0 workspace, so // the movement limits must be shifted by the tool offset to // retain the same physical limit when other tools are selected. - if (old_tool_index != new_tool_index) { - const float offs = hotend_offset[new_tool_index][axis] - hotend_offset[old_tool_index][axis]; - soft_endstop.min[axis] += offs; - soft_endstop.max[axis] += offs; - } - else { - const float offs = hotend_offset[active_extruder][axis]; + + if (new_tool_index == old_tool_index || axis == Z_AXIS) { // The Z axis is "special" and shouldn't be modified + const float offs = (axis == Z_AXIS) ? 0 : hotend_offset[active_extruder][axis]; soft_endstop.min[axis] = base_min_pos(axis) + offs; soft_endstop.max[axis] = base_max_pos(axis) + offs; } + else { + const float diff = hotend_offset[new_tool_index][axis] - hotend_offset[old_tool_index][axis]; + soft_endstop.min[axis] += diff; + soft_endstop.max[axis] += diff; + } #else @@ -624,7 +774,7 @@ void restore_feedrate_and_scaling() { #endif if (DEBUGGING(LEVELING)) - SERIAL_ECHOLNPAIR("Axis ", XYZ_CHAR(axis), " min:", soft_endstop.min[axis], " max:", soft_endstop.max[axis]); + SERIAL_ECHOLNPAIR("Axis ", AS_CHAR(AXIS_CHAR(axis)), " min:", soft_endstop.min[axis], " max:", soft_endstop.max[axis]); } /** @@ -649,7 +799,7 @@ void restore_feedrate_and_scaling() { constexpr xy_pos_t offs{0}; #endif - if (TERN1(IS_SCARA, TEST(axis_homed, X_AXIS) && TEST(axis_homed, Y_AXIS))) { + if (TERN1(IS_SCARA, axis_was_homed(X_AXIS) && axis_was_homed(Y_AXIS))) { const float dist_2 = HYPOT2(target.x - offs.x, target.y - offs.y); if (dist_2 > delta_max_radius_2) target *= float(delta_max_radius / SQRT(dist_2)); // 200 / 300 = 0.66 @@ -657,7 +807,7 @@ void restore_feedrate_and_scaling() { #else - if (TEST(axis_homed, 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 @@ -666,25 +816,59 @@ void restore_feedrate_and_scaling() { #endif } - if (TEST(axis_homed, Y_AXIS)) { - #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_Y) - NOLESS(target.y, soft_endstop.min.y); + #if HAS_Y_AXIS + if (axis_was_homed(Y_AXIS)) { + #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_Y) + NOLESS(target.y, soft_endstop.min.y); + #endif + #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_Y) + NOMORE(target.y, soft_endstop.max.y); + #endif + } + #endif + + #endif + + #if HAS_Z_AXIS + if (axis_was_homed(Z_AXIS)) { + #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_Z) + NOLESS(target.z, soft_endstop.min.z); #endif - #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_Y) - NOMORE(target.y, soft_endstop.max.y); + #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_Z) + NOMORE(target.z, soft_endstop.max.z); + #endif + } + #endif + #if LINEAR_AXES >= 4 + if (axis_was_homed(I_AXIS)) { + #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_I) + NOLESS(target.i, soft_endstop.min.i); + #endif + #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_I) + NOMORE(target.i, soft_endstop.max.i); + #endif + } + #endif + #if LINEAR_AXES >= 5 + if (axis_was_homed(J_AXIS)) { + #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_J) + NOLESS(target.j, soft_endstop.min.j); + #endif + #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_J) + NOMORE(target.j, soft_endstop.max.j); + #endif + } + #endif + #if LINEAR_AXES >= 6 + if (axis_was_homed(K_AXIS)) { + #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_K) + NOLESS(target.k, soft_endstop.min.k); + #endif + #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_K) + NOMORE(target.k, soft_endstop.max.k); #endif } - #endif - - if (TEST(axis_homed, Z_AXIS)) { - #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_Z) - NOLESS(target.z, soft_endstop.min.z); - #endif - #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_Z) - NOMORE(target.z, soft_endstop.max.z); - #endif - } } #else // !HAS_SOFTWARE_ENDSTOPS @@ -744,7 +928,7 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { // If the move is only in Z/E don't split up the move if (!diff.x && !diff.y) { - planner.buffer_line(destination, scaled_fr_mm_s, active_extruder); + planner.buffer_line(destination, scaled_fr_mm_s); return false; // caller will update current_position } @@ -755,7 +939,7 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { float cartesian_mm = diff.magnitude(); // If the move is very short, check the E move distance - if (UNEAR_ZERO(cartesian_mm)) cartesian_mm = ABS(diff.e); + TERN_(HAS_EXTRUDERS, if (UNEAR_ZERO(cartesian_mm)) cartesian_mm = ABS(diff.e)); // No E move either? Game over. if (UNEAR_ZERO(cartesian_mm)) return true; @@ -765,7 +949,7 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { // The number of segments-per-second times the duration // gives the number of segments - uint16_t segments = delta_segments_per_second * seconds; + uint16_t segments = segments_per_second * seconds; // For SCARA enforce a minimum segment size #if IS_SCARA @@ -800,19 +984,11 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { while (--segments) { segment_idle(next_idle_ms); raw += segment_distance; - if (!planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, cartesian_segment_mm - #if ENABLED(SCARA_FEEDRATE_SCALING) - , inv_duration - #endif - )) break; + if (!planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, cartesian_segment_mm OPTARG(SCARA_FEEDRATE_SCALING, inv_duration))) break; } // Ensure last segment arrives at target location. - planner.buffer_line(destination, scaled_fr_mm_s, active_extruder, cartesian_segment_mm - #if ENABLED(SCARA_FEEDRATE_SCALING) - , inv_duration - #endif - ); + planner.buffer_line(destination, scaled_fr_mm_s, active_extruder, cartesian_segment_mm OPTARG(SCARA_FEEDRATE_SCALING, inv_duration)); return false; // caller will update current_position } @@ -828,13 +1004,13 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { * small incremental moves. This allows the planner to * apply more detailed bed leveling to the full move. */ - inline void segmented_line_to_destination(const feedRate_t &fr_mm_s, const float segment_size=LEVELED_SEGMENT_LENGTH) { + inline void segmented_line_to_destination(const_feedRate_t fr_mm_s, const float segment_size=LEVELED_SEGMENT_LENGTH) { const xyze_float_t diff = destination - current_position; // If the move is only in Z/E don't split up the move if (!diff.x && !diff.y) { - planner.buffer_line(destination, fr_mm_s, active_extruder); + planner.buffer_line(destination, fr_mm_s); return; } @@ -842,7 +1018,7 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { // If the move is very short, check the E move distance // No E move either? Game over. float cartesian_mm = diff.magnitude(); - if (UNEAR_ZERO(cartesian_mm)) cartesian_mm = ABS(diff.e); + TERN_(HAS_EXTRUDERS, if (UNEAR_ZERO(cartesian_mm)) cartesian_mm = ABS(diff.e)); if (UNEAR_ZERO(cartesian_mm)) return; // The length divided by the segment size @@ -871,20 +1047,12 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { while (--segments) { segment_idle(next_idle_ms); raw += segment_distance; - if (!planner.buffer_line(raw, fr_mm_s, active_extruder, cartesian_segment_mm - #if ENABLED(SCARA_FEEDRATE_SCALING) - , inv_duration - #endif - )) break; + if (!planner.buffer_line(raw, fr_mm_s, active_extruder, cartesian_segment_mm OPTARG(SCARA_FEEDRATE_SCALING, inv_duration))) break; } // Since segment_distance is only approximate, // the final move must be to the exact destination. - planner.buffer_line(destination, fr_mm_s, active_extruder, cartesian_segment_mm - #if ENABLED(SCARA_FEEDRATE_SCALING) - , inv_duration - #endif - ); + planner.buffer_line(destination, fr_mm_s, active_extruder, cartesian_segment_mm OPTARG(SCARA_FEEDRATE_SCALING, inv_duration)); } #endif // SEGMENT_LEVELED_MOVES @@ -924,7 +1092,7 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { } #endif // HAS_MESH - planner.buffer_line(destination, scaled_fr_mm_s, active_extruder); + planner.buffer_line(destination, scaled_fr_mm_s); return false; // caller will update current_position } @@ -932,8 +1100,7 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { #endif // !UBL_SEGMENTED #if HAS_DUPLICATION_MODE - bool extruder_duplication_enabled, - mirrored_duplication_mode; + bool extruder_duplication_enabled; #if ENABLED(MULTI_NOZZLE_DUPLICATION) uint8_t duplication_e_mask; // = 0 #endif @@ -942,16 +1109,17 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { #if ENABLED(DUAL_X_CARRIAGE) DualXMode dual_x_carriage_mode = DEFAULT_DUAL_X_CARRIAGE_MODE; - float inactive_extruder_x_pos = X2_MAX_POS, // used in mode 0 & 1 - duplicate_extruder_x_offset = DEFAULT_DUPLICATION_X_OFFSET; // used in mode 2 - xyz_pos_t raised_parked_position; // used in mode 1 - bool active_extruder_parked = false; // used in mode 1 & 2 - millis_t delayed_move_time = 0; // used in mode 1 - int16_t duplicate_extruder_temp_offset = 0; // used in mode 2 + float inactive_extruder_x = X2_MAX_POS, // Used in mode 0 & 1 + duplicate_extruder_x_offset = DEFAULT_DUPLICATION_X_OFFSET; // Used in mode 2 & 3 + xyz_pos_t raised_parked_position; // Used in mode 1 + bool active_extruder_parked = false; // Used in mode 1, 2 & 3 + millis_t delayed_move_time = 0; // Used in mode 1 + celsius_t duplicate_extruder_temp_offset = 0; // Used in mode 2 & 3 + bool idex_mirrored_mode = false; // Used in mode 3 float x_home_pos(const uint8_t extruder) { if (extruder == 0) - return base_home_pos(X_AXIS); + return X_HOME_POS; else /** * In dual carriage mode the extruder offset provides an override of the @@ -962,6 +1130,23 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { return hotend_offset[1].x > 0 ? hotend_offset[1].x : X2_HOME_POS; } + void idex_set_mirrored_mode(const bool mirr) { + idex_mirrored_mode = mirr; + stepper.set_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(); + } + + void idex_set_parked(const bool park/*=true*/) { + delayed_move_time = 0; + active_extruder_parked = park; + if (park) raised_parked_position = current_position; // Remember current raised toolhead position for use by unpark + } + /** * Prepare a linear move in a dual X axis setup * @@ -970,9 +1155,10 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { inline bool dual_x_carriage_unpark() { if (active_extruder_parked) { switch (dual_x_carriage_mode) { - case DXC_FULL_CONTROL_MODE: - break; - case DXC_AUTO_PARK_MODE: + + case DXC_FULL_CONTROL_MODE: break; + + case DXC_AUTO_PARK_MODE: { if (current_position.e == destination.e) { // This is a travel move (with no extrusion) // Skip it, but keep track of the current position @@ -980,50 +1166,57 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { if (delayed_move_time != 0xFFFFFFFFUL) { current_position = destination; NOLESS(raised_parked_position.z, destination.z); - delayed_move_time = millis(); + delayed_move_time = millis() + 1000UL; return true; } } - // unpark extruder: 1) raise, 2) move into starting XY position, 3) lower - - #define CUR_X current_position.x - #define CUR_Y current_position.y - #define CUR_Z current_position.z - #define CUR_E current_position.e - #define RAISED_X raised_parked_position.x - #define RAISED_Y raised_parked_position.y - #define RAISED_Z raised_parked_position.z - - if ( planner.buffer_line(RAISED_X, RAISED_Y, RAISED_Z, CUR_E, planner.settings.max_feedrate_mm_s[Z_AXIS], active_extruder)) - if (planner.buffer_line( CUR_X, CUR_Y, RAISED_Z, CUR_E, PLANNER_XY_FEEDRATE(), active_extruder)) - line_to_current_position(planner.settings.max_feedrate_mm_s[Z_AXIS]); - delayed_move_time = 0; - active_extruder_parked = false; - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Clear active_extruder_parked"); - break; + // + // Un-park the active extruder + // + const feedRate_t fr_zfast = planner.settings.max_feedrate_mm_s[Z_AXIS]; + // 1. Move to the raised parked XYZ. Presumably the tool is already at XY. + xyze_pos_t raised = raised_parked_position; raised.e = current_position.e; + if (planner.buffer_line(raised, fr_zfast)) { + // 2. Move to the current native XY and raised Z. Presumably this is a null move. + xyze_pos_t curpos = current_position; curpos.z = raised_parked_position.z; + if (planner.buffer_line(curpos, PLANNER_XY_FEEDRATE())) { + // 3. Lower Z back down + line_to_current_position(fr_zfast); + } + } + stepper.set_directions(); + + idex_set_parked(false); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("idex_set_parked(false)"); + } break; + case DXC_MIRRORED_MODE: case DXC_DUPLICATION_MODE: if (active_extruder == 0) { - xyze_pos_t new_pos = current_position; + // Restore planner to parked head (T1) X position + xyze_pos_t pos_now = current_position; + pos_now.x = inactive_extruder_x; + planner.set_position_mm(pos_now); + + // Keep the same X or add the duplication X offset + xyze_pos_t new_pos = pos_now; if (dual_x_carriage_mode == DXC_DUPLICATION_MODE) new_pos.x += duplicate_extruder_x_offset; - else - new_pos.x = inactive_extruder_x_pos; - // move duplicate extruder into correct duplication position. - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Set planner X", inactive_extruder_x_pos, " ... Line to X", new_pos.x); - planner.set_position_mm(inactive_extruder_x_pos, current_position.y, current_position.z, current_position.e); + + // Move duplicate extruder into the correct position + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Set planner X", inactive_extruder_x, " ... Line to X", new_pos.x); if (!planner.buffer_line(new_pos, planner.settings.max_feedrate_mm_s[X_AXIS], 1)) break; planner.synchronize(); - sync_plan_position(); - extruder_duplication_enabled = true; - active_extruder_parked = false; - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Set extruder_duplication_enabled\nClear active_extruder_parked"); + + sync_plan_position(); // Extra sync for good measure + set_duplication_enabled(true); // Enable Duplication + idex_set_parked(false); // No longer parked + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("set_duplication_enabled(true)\nidex_set_parked(false)"); } else if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Active extruder not 0"); break; } } - stepper.set_directions(); return false; } @@ -1100,750 +1293,849 @@ void prepare_line_to_destination() { current_position = destination; } -uint8_t axes_should_home(uint8_t axis_bits/*=0x07*/) { - // Clear test bits that are trusted - if (TEST(axis_bits, X_AXIS) && TEST(axis_homed, X_AXIS)) CBI(axis_bits, X_AXIS); - if (TEST(axis_bits, Y_AXIS) && TEST(axis_homed, Y_AXIS)) CBI(axis_bits, Y_AXIS); - if (TEST(axis_bits, Z_AXIS) && TEST(axis_homed, Z_AXIS)) CBI(axis_bits, Z_AXIS); - return axis_bits; -} +#if HAS_ENDSTOPS -bool homing_needed_error(uint8_t axis_bits/*=0x07*/) { - if ((axis_bits = axes_should_home(axis_bits))) { - PGM_P home_first = GET_TEXT(MSG_HOME_FIRST); - char msg[strlen_P(home_first)+1]; - sprintf_P(msg, home_first, - TEST(axis_bits, X_AXIS) ? "X" : "", - TEST(axis_bits, Y_AXIS) ? "Y" : "", - TEST(axis_bits, Z_AXIS) ? "Z" : "" + linear_axis_bits_t axis_homed, axis_trusted; // = 0 + + linear_axis_bits_t axes_should_home(linear_axis_bits_t axis_bits/*=linear_bits*/) { + auto set_should = [](linear_axis_bits_t &b, AxisEnum a) { + if (TEST(b, a) && TERN(HOME_AFTER_DEACTIVATE, axis_is_trusted, axis_was_homed)(a)) + CBI(b, a); + }; + // Clear test bits that are trusted + LINEAR_AXIS_CODE( + set_should(axis_bits, X_AXIS), set_should(axis_bits, Y_AXIS), set_should(axis_bits, Z_AXIS), + set_should(axis_bits, I_AXIS), set_should(axis_bits, J_AXIS), set_should(axis_bits, K_AXIS) ); - SERIAL_ECHO_START(); - SERIAL_ECHOLN(msg); - TERN_(HAS_DISPLAY, ui.set_status(msg)); - return true; + return axis_bits; } - return false; -} -/** - * Homing bump feedrate (mm/s) - */ -feedRate_t get_homing_bump_feedrate(const AxisEnum axis) { - #if HOMING_Z_WITH_PROBE - if (axis == Z_AXIS) return MMM_TO_MMS(Z_PROBE_SPEED_SLOW); - #endif - static const uint8_t homing_bump_divisor[] PROGMEM = HOMING_BUMP_DIVISOR; - uint8_t hbd = pgm_read_byte(&homing_bump_divisor[axis]); - if (hbd < 1) { - hbd = 10; - SERIAL_ECHO_MSG("Warning: Homing Bump Divisor < 1"); + bool homing_needed_error(linear_axis_bits_t axis_bits/*=linear_bits*/) { + if ((axis_bits = axes_should_home(axis_bits))) { + PGM_P home_first = GET_TEXT(MSG_HOME_FIRST); + char msg[strlen_P(home_first)+1]; + sprintf_P(msg, home_first, + LINEAR_AXIS_LIST( + TEST(axis_bits, X_AXIS) ? "X" : "", + TEST(axis_bits, Y_AXIS) ? "Y" : "", + TEST(axis_bits, Z_AXIS) ? "Z" : "", + TEST(axis_bits, I_AXIS) ? AXIS4_STR : "", + TEST(axis_bits, J_AXIS) ? AXIS5_STR : "", + TEST(axis_bits, K_AXIS) ? AXIS6_STR : "" + ) + ); + SERIAL_ECHO_START(); + SERIAL_ECHOLN(msg); + TERN_(HAS_STATUS_MESSAGE, ui.set_status(msg)); + return true; + } + return false; } - return homing_feedrate(axis) / float(hbd); -} -#if ENABLED(SENSORLESS_HOMING) /** - * Set sensorless homing if the axis has it, accounting for Core Kinematics. + * Homing bump feedrate (mm/s) */ - sensorless_t start_sensorless_homing_per_axis(const AxisEnum axis) { - sensorless_t stealth_states { false }; + feedRate_t get_homing_bump_feedrate(const AxisEnum axis) { + #if HOMING_Z_WITH_PROBE + if (axis == Z_AXIS) return MMM_TO_MMS(Z_PROBE_FEEDRATE_SLOW); + #endif + static const uint8_t homing_bump_divisor[] PROGMEM = HOMING_BUMP_DIVISOR; + uint8_t hbd = pgm_read_byte(&homing_bump_divisor[axis]); + if (hbd < 1) { + hbd = 10; + SERIAL_ECHO_MSG("Warning: Homing Bump Divisor < 1"); + } + return homing_feedrate(axis) / float(hbd); + } - switch (axis) { - default: break; - #if X_SENSORLESS - case X_AXIS: - stealth_states.x = tmc_enable_stallguard(stepperX); - #if AXIS_HAS_STALLGUARD(X2) - stealth_states.x2 = tmc_enable_stallguard(stepperX2); - #endif - #if EITHER(CORE_IS_XY, MARKFORGED_XY) && Y_SENSORLESS - stealth_states.y = tmc_enable_stallguard(stepperY); - #elif CORE_IS_XZ && Z_SENSORLESS - stealth_states.z = tmc_enable_stallguard(stepperZ); - #endif - break; - #endif - #if Y_SENSORLESS - case Y_AXIS: - stealth_states.y = tmc_enable_stallguard(stepperY); - #if AXIS_HAS_STALLGUARD(Y2) - stealth_states.y2 = tmc_enable_stallguard(stepperY2); - #endif - #if EITHER(CORE_IS_XY, MARKFORGED_XY) && X_SENSORLESS + #if ENABLED(SENSORLESS_HOMING) + /** + * Set sensorless homing if the axis has it, accounting for Core Kinematics. + */ + sensorless_t start_sensorless_homing_per_axis(const AxisEnum axis) { + sensorless_t stealth_states { false }; + + switch (axis) { + default: break; + #if X_SENSORLESS + case X_AXIS: stealth_states.x = tmc_enable_stallguard(stepperX); - #elif CORE_IS_YZ && Z_SENSORLESS + #if AXIS_HAS_STALLGUARD(X2) + stealth_states.x2 = tmc_enable_stallguard(stepperX2); + #endif + #if EITHER(CORE_IS_XY, MARKFORGED_XY) && Y_SENSORLESS + stealth_states.y = tmc_enable_stallguard(stepperY); + #elif CORE_IS_XZ && Z_SENSORLESS + stealth_states.z = tmc_enable_stallguard(stepperZ); + #endif + break; + #endif + #if Y_SENSORLESS + case Y_AXIS: + stealth_states.y = tmc_enable_stallguard(stepperY); + #if AXIS_HAS_STALLGUARD(Y2) + stealth_states.y2 = tmc_enable_stallguard(stepperY2); + #endif + #if EITHER(CORE_IS_XY, MARKFORGED_XY) && X_SENSORLESS + stealth_states.x = tmc_enable_stallguard(stepperX); + #elif CORE_IS_YZ && Z_SENSORLESS + stealth_states.z = tmc_enable_stallguard(stepperZ); + #endif + break; + #endif + #if Z_SENSORLESS + case Z_AXIS: stealth_states.z = tmc_enable_stallguard(stepperZ); + #if AXIS_HAS_STALLGUARD(Z2) + stealth_states.z2 = tmc_enable_stallguard(stepperZ2); + #endif + #if AXIS_HAS_STALLGUARD(Z3) + stealth_states.z3 = tmc_enable_stallguard(stepperZ3); + #endif + #if AXIS_HAS_STALLGUARD(Z4) + stealth_states.z4 = tmc_enable_stallguard(stepperZ4); + #endif + #if CORE_IS_XZ && X_SENSORLESS + stealth_states.x = tmc_enable_stallguard(stepperX); + #elif CORE_IS_YZ && Y_SENSORLESS + stealth_states.y = tmc_enable_stallguard(stepperY); + #endif + break; + #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 - break; - #endif - #if Z_SENSORLESS - case Z_AXIS: - stealth_states.z = tmc_enable_stallguard(stepperZ); - #if AXIS_HAS_STALLGUARD(Z2) - stealth_states.z2 = tmc_enable_stallguard(stepperZ2); + #if HAS_Z_AXIS + case Z_AXIS: if (ENABLED(Z_SPI_SENSORLESS)) endstops.tmc_spi_homing.z = true; break; #endif - #if AXIS_HAS_STALLGUARD(Z3) - stealth_states.z3 = tmc_enable_stallguard(stepperZ3); + #if LINEAR_AXES >= 4 + case I_AXIS: if (ENABLED(I_SPI_SENSORLESS)) endstops.tmc_spi_homing.i = true; break; #endif - #if AXIS_HAS_STALLGUARD(Z4) - stealth_states.z4 = tmc_enable_stallguard(stepperZ4); + #if LINEAR_AXES >= 5 + case J_AXIS: if (ENABLED(J_SPI_SENSORLESS)) endstops.tmc_spi_homing.j = true; break; #endif - #if CORE_IS_XZ && X_SENSORLESS - stealth_states.x = tmc_enable_stallguard(stepperX); - #elif CORE_IS_YZ && Y_SENSORLESS - stealth_states.y = tmc_enable_stallguard(stepperY); + #if LINEAR_AXES >= 6 + case K_AXIS: if (ENABLED(K_SPI_SENSORLESS)) endstops.tmc_spi_homing.k = true; break; #endif - break; + default: break; + } #endif + + TERN_(IMPROVE_HOMING_RELIABILITY, sg_guard_period = millis() + default_sg_guard_duration); + + return stealth_states; } - #if ENABLED(SPI_ENDSTOPS) + void end_sensorless_homing_per_axis(const AxisEnum axis, sensorless_t enable_stealth) { switch (axis) { - case X_AXIS: if (ENABLED(X_SPI_SENSORLESS)) endstops.tmc_spi_homing.x = true; break; - case Y_AXIS: if (ENABLED(Y_SPI_SENSORLESS)) endstops.tmc_spi_homing.y = true; break; - case Z_AXIS: if (ENABLED(Z_SPI_SENSORLESS)) endstops.tmc_spi_homing.z = true; break; default: break; + #if X_SENSORLESS + case X_AXIS: + tmc_disable_stallguard(stepperX, enable_stealth.x); + #if AXIS_HAS_STALLGUARD(X2) + tmc_disable_stallguard(stepperX2, enable_stealth.x2); + #endif + #if EITHER(CORE_IS_XY, MARKFORGED_XY) && Y_SENSORLESS + tmc_disable_stallguard(stepperY, enable_stealth.y); + #elif CORE_IS_XZ && Z_SENSORLESS + tmc_disable_stallguard(stepperZ, enable_stealth.z); + #endif + break; + #endif + #if Y_SENSORLESS + case Y_AXIS: + tmc_disable_stallguard(stepperY, enable_stealth.y); + #if AXIS_HAS_STALLGUARD(Y2) + tmc_disable_stallguard(stepperY2, enable_stealth.y2); + #endif + #if EITHER(CORE_IS_XY, MARKFORGED_XY) && X_SENSORLESS + tmc_disable_stallguard(stepperX, enable_stealth.x); + #elif CORE_IS_YZ && Z_SENSORLESS + tmc_disable_stallguard(stepperZ, enable_stealth.z); + #endif + break; + #endif + #if Z_SENSORLESS + case Z_AXIS: + tmc_disable_stallguard(stepperZ, enable_stealth.z); + #if AXIS_HAS_STALLGUARD(Z2) + tmc_disable_stallguard(stepperZ2, enable_stealth.z2); + #endif + #if AXIS_HAS_STALLGUARD(Z3) + tmc_disable_stallguard(stepperZ3, enable_stealth.z3); + #endif + #if AXIS_HAS_STALLGUARD(Z4) + tmc_disable_stallguard(stepperZ4, enable_stealth.z4); + #endif + #if CORE_IS_XZ && X_SENSORLESS + tmc_disable_stallguard(stepperX, enable_stealth.x); + #elif CORE_IS_YZ && Y_SENSORLESS + tmc_disable_stallguard(stepperY, enable_stealth.y); + #endif + break; + #endif } - #endif - TERN_(IMPROVE_HOMING_RELIABILITY, sg_guard_period = millis() + default_sg_guard_duration); - - return stealth_states; - } - - void end_sensorless_homing_per_axis(const AxisEnum axis, sensorless_t enable_stealth) { - switch (axis) { - default: break; - #if X_SENSORLESS - case X_AXIS: - tmc_disable_stallguard(stepperX, enable_stealth.x); - #if AXIS_HAS_STALLGUARD(X2) - tmc_disable_stallguard(stepperX2, enable_stealth.x2); + #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 EITHER(CORE_IS_XY, MARKFORGED_XY) && Y_SENSORLESS - tmc_disable_stallguard(stepperY, enable_stealth.y); - #elif CORE_IS_XZ && Z_SENSORLESS - tmc_disable_stallguard(stepperZ, enable_stealth.z); + #if HAS_Z_AXIS + case Z_AXIS: if (ENABLED(Z_SPI_SENSORLESS)) endstops.tmc_spi_homing.z = false; break; #endif - break; - #endif - #if Y_SENSORLESS - case Y_AXIS: - tmc_disable_stallguard(stepperY, enable_stealth.y); - #if AXIS_HAS_STALLGUARD(Y2) - tmc_disable_stallguard(stepperY2, enable_stealth.y2); + #if LINEAR_AXES >= 4 + case I_AXIS: if (ENABLED(I_SPI_SENSORLESS)) endstops.tmc_spi_homing.i = false; break; #endif - #if EITHER(CORE_IS_XY, MARKFORGED_XY) && X_SENSORLESS - tmc_disable_stallguard(stepperX, enable_stealth.x); - #elif CORE_IS_YZ && Z_SENSORLESS - tmc_disable_stallguard(stepperZ, enable_stealth.z); - #endif - break; - #endif - #if Z_SENSORLESS - case Z_AXIS: - tmc_disable_stallguard(stepperZ, enable_stealth.z); - #if AXIS_HAS_STALLGUARD(Z2) - tmc_disable_stallguard(stepperZ2, enable_stealth.z2); + #if LINEAR_AXES >= 5 + case J_AXIS: if (ENABLED(J_SPI_SENSORLESS)) endstops.tmc_spi_homing.j = false; break; #endif - #if AXIS_HAS_STALLGUARD(Z3) - tmc_disable_stallguard(stepperZ3, enable_stealth.z3); + #if LINEAR_AXES >= 6 + case K_AXIS: if (ENABLED(K_SPI_SENSORLESS)) endstops.tmc_spi_homing.k = false; break; #endif - #if AXIS_HAS_STALLGUARD(Z4) - tmc_disable_stallguard(stepperZ4, enable_stealth.z4); - #endif - #if CORE_IS_XZ && X_SENSORLESS - tmc_disable_stallguard(stepperX, enable_stealth.x); - #elif CORE_IS_YZ && Y_SENSORLESS - tmc_disable_stallguard(stepperY, enable_stealth.y); - #endif - break; + default: break; + } #endif } - #if ENABLED(SPI_ENDSTOPS) - switch (axis) { - case X_AXIS: if (ENABLED(X_SPI_SENSORLESS)) endstops.tmc_spi_homing.x = false; break; - case Y_AXIS: if (ENABLED(Y_SPI_SENSORLESS)) endstops.tmc_spi_homing.y = false; break; - case Z_AXIS: if (ENABLED(Z_SPI_SENSORLESS)) endstops.tmc_spi_homing.z = false; break; - default: break; - } - #endif - } - -#endif // SENSORLESS_HOMING + #endif // SENSORLESS_HOMING -/** - * Home an individual linear axis - */ -void do_homing_move(const AxisEnum axis, const float distance, const feedRate_t fr_mm_s=0.0) { - DEBUG_SECTION(log_move, "do_homing_move", DEBUGGING(LEVELING)); + /** + * Home an individual linear axis + */ + void do_homing_move(const AxisEnum axis, const float distance, const feedRate_t fr_mm_s=0.0, const bool final_approach=true) { + DEBUG_SECTION(log_move, "do_homing_move", DEBUGGING(LEVELING)); - const feedRate_t real_fr_mm_s = fr_mm_s ?: homing_feedrate(axis); + const feedRate_t home_fr_mm_s = fr_mm_s ?: homing_feedrate(axis); - if (DEBUGGING(LEVELING)) { - DEBUG_ECHOPAIR("...(", axis_codes[axis], ", ", distance, ", "); - if (fr_mm_s) - DEBUG_ECHO(fr_mm_s); - else - DEBUG_ECHOPAIR("[", real_fr_mm_s, "]"); - DEBUG_ECHOLNPGM(")"); - } + if (DEBUGGING(LEVELING)) { + DEBUG_ECHOPAIR("...(", AS_CHAR(AXIS_CHAR(axis)), ", ", distance, ", "); + if (fr_mm_s) + DEBUG_ECHO(fr_mm_s); + else + DEBUG_ECHOPAIR("[", home_fr_mm_s, "]"); + DEBUG_ECHOLNPGM(")"); + } - #if ALL(HOMING_Z_WITH_PROBE, HAS_HEATED_BED, WAIT_FOR_BED_HEATER) - // Wait for bed to heat back up between probing points - if (axis == Z_AXIS && distance < 0) - thermalManager.wait_for_bed_heating(); - #endif + // Only do some things when moving towards an endstop + const int8_t axis_home_dir = TERN0(DUAL_X_CARRIAGE, axis == X_AXIS) + ? TOOL_X_HOME_DIR(active_extruder) : home_dir(axis); + const bool is_home_dir = (axis_home_dir > 0) == (distance > 0); - // Only do some things when moving towards an endstop - const int8_t axis_home_dir = TERN0(DUAL_X_CARRIAGE, axis == X_AXIS) - ? x_home_dir(active_extruder) : home_dir(axis); - const bool is_home_dir = (axis_home_dir > 0) == (distance > 0); + #if ENABLED(SENSORLESS_HOMING) + sensorless_t stealth_states; + #endif - #if ENABLED(SENSORLESS_HOMING) - sensorless_t stealth_states; - #endif + if (is_home_dir) { - if (is_home_dir) { + if (TERN0(HOMING_Z_WITH_PROBE, axis == Z_AXIS)) { + #if BOTH(HAS_HEATED_BED, WAIT_FOR_BED_HEATER) + // Wait for bed to heat back up between probing points + thermalManager.wait_for_bed_heating(); + #endif - #if HOMING_Z_WITH_PROBE && QUIET_PROBING - if (axis == Z_AXIS) probe.set_probing_paused(true); - #endif + #if BOTH(HAS_HOTEND, WAIT_FOR_HOTEND) + // Wait for the hotend to heat back up between probing points + thermalManager.wait_for_hotend_heating(active_extruder); + #endif - // Disable stealthChop if used. Enable diag1 pin on driver. - TERN_(SENSORLESS_HOMING, stealth_states = start_sensorless_homing_per_axis(axis)); - } + TERN_(HAS_QUIET_PROBING, if (final_approach) probe.set_probing_paused(true)); + } - #if IS_SCARA - // Tell the planner the axis is at 0 - current_position[axis] = 0; - sync_plan_position(); - current_position[axis] = distance; - line_to_current_position(real_fr_mm_s); - #else - // Get the ABC or XYZ positions in mm - abce_pos_t target = planner.get_axis_positions_mm(); + // Disable stealthChop if used. Enable diag1 pin on driver. + TERN_(SENSORLESS_HOMING, stealth_states = start_sensorless_homing_per_axis(axis)); + } - target[axis] = 0; // Set the single homing axis to 0 - planner.set_machine_position_mm(target); // Update the machine position + #if EITHER(MORGAN_SCARA, MP_SCARA) + // Tell the planner the axis is at 0 + current_position[axis] = 0; + sync_plan_position(); + current_position[axis] = distance; + line_to_current_position(home_fr_mm_s); + #else + // Get the ABC or XYZ positions in mm + abce_pos_t target = planner.get_axis_positions_mm(); - #if HAS_DIST_MM_ARG - const xyze_float_t cart_dist_mm{0}; - #endif + target[axis] = 0; // Set the single homing axis to 0 + planner.set_machine_position_mm(target); // Update the machine position - // Set delta/cartesian axes directly - target[axis] = distance; // The move will be towards the endstop - planner.buffer_segment(target #if HAS_DIST_MM_ARG - , cart_dist_mm + const xyze_float_t cart_dist_mm{0}; #endif - , real_fr_mm_s, active_extruder - ); - #endif - - planner.synchronize(); - if (is_home_dir) { - - #if HOMING_Z_WITH_PROBE && QUIET_PROBING - if (axis == Z_AXIS) probe.set_probing_paused(false); + // Set delta/cartesian axes directly + target[axis] = distance; // The move will be towards the endstop + planner.buffer_segment(target OPTARG(HAS_DIST_MM_ARG, cart_dist_mm), home_fr_mm_s, active_extruder); #endif - endstops.validate_homing_move(); - - // Re-enable stealthChop if used. Disable diag1 pin on driver. - TERN_(SENSORLESS_HOMING, end_sensorless_homing_per_axis(axis, stealth_states)); - } -} - -/** - * Set an axis' current position to its home position (after homing). - * - * For Core and Cartesian robots this applies one-to-one when an - * individual axis has been homed. - * - * DELTA should wait until all homing is done before setting the XYZ - * current_position to home, because homing is a single operation. - * In the case where the axis positions are already known and previously - * homed, DELTA could home to X or Y individually by moving either one - * to the center. However, homing Z always homes XY and Z. - * - * SCARA should wait until all XY homing is done before setting the XY - * current_position to home, because neither X nor Y is at home until - * both are at home. Z can however be homed individually. - * - * Callers must sync the planner position after calling this! - */ -void set_axis_is_at_home(const AxisEnum axis) { - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> set_axis_is_at_home(", axis_codes[axis], ")"); - - SBI(axis_known_position, axis); - SBI(axis_homed, axis); - - #if ENABLED(DUAL_X_CARRIAGE) - if (axis == X_AXIS && (active_extruder == 1 || dual_x_carriage_mode == DXC_DUPLICATION_MODE)) { - current_position.x = x_home_pos(active_extruder); - return; - } - #endif - - #if ENABLED(MORGAN_SCARA) - scara_set_axis_is_at_home(axis); - #elif ENABLED(DELTA) - current_position[axis] = (axis == Z_AXIS) ? delta_height - TERN0(HAS_BED_PROBE, probe.offset.z) : base_home_pos(axis); - #else - current_position[axis] = base_home_pos(axis); - #endif - - /** - * Z Probe Z Homing? Account for the probe's Z offset. - */ - #if HAS_BED_PROBE && Z_HOME_DIR < 0 - if (axis == Z_AXIS) { - #if HOMING_Z_WITH_PROBE - - current_position.z -= probe.offset.z; - - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("*** Z HOMED WITH PROBE (Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) ***\n> probe.offset.z = ", probe.offset.z); - - #else + planner.synchronize(); - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("*** Z HOMED TO ENDSTOP ***"); + if (is_home_dir) { + #if HOMING_Z_WITH_PROBE && HAS_QUIET_PROBING + if (axis == Z_AXIS && final_approach) probe.set_probing_paused(false); #endif - } - #endif - TERN_(I2C_POSITION_ENCODERS, I2CPEM.homed(axis)); - - TERN_(BABYSTEP_DISPLAY_TOTAL, babystep.reset_total(axis)); - - #if HAS_POSITION_SHIFT - position_shift[axis] = 0; - update_workspace_offset(axis); - #endif + endstops.validate_homing_move(); - if (DEBUGGING(LEVELING)) { - #if HAS_HOME_OFFSET - DEBUG_ECHOLNPAIR("> home_offset[", axis_codes[axis], "] = ", home_offset[axis]); - #endif - DEBUG_POS("", current_position); - DEBUG_ECHOLNPAIR("<<< set_axis_is_at_home(", axis_codes[axis], ")"); + // Re-enable stealthChop if used. Disable diag1 pin on driver. + TERN_(SENSORLESS_HOMING, end_sensorless_homing_per_axis(axis, stealth_states)); + } } -} - -/** - * Set an axis to be unhomed. - */ -void set_axis_never_homed(const AxisEnum axis) { - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> set_axis_never_homed(", axis_codes[axis], ")"); - - CBI(axis_known_position, axis); - CBI(axis_homed, axis); - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("<<< set_axis_never_homed(", axis_codes[axis], ")"); - - TERN_(I2C_POSITION_ENCODERS, I2CPEM.unhomed(axis)); -} - -#ifdef TMC_HOME_PHASE /** - * Move the axis back to its home_phase if set and driver is capable (TMC) - * - * Improves homing repeatability by homing to stepper coil's nearest absolute - * phase position. Trinamic drivers use a stepper phase table with 1024 values - * spanning 4 full steps with 256 positions each (ergo, 1024 positions). + * Set an axis to be unhomed. (Unless we are on a machine - e.g. a cheap Chinese CNC machine - + * that has no endstops. Such machines should always be considered to be in a "known" and + * "trusted" position). */ - void backout_to_tmc_homing_phase(const AxisEnum axis) { - const xyz_long_t home_phase = TMC_HOME_PHASE; - - // check if home phase is disabled for this axis. - if (home_phase[axis] < 0) return; + void set_axis_never_homed(const AxisEnum axis) { + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> set_axis_never_homed(", AS_CHAR(AXIS_CHAR(axis)), ")"); - int16_t phasePerUStep, // TMC µsteps(phase) per Marlin µsteps - phaseCurrent, // The TMC µsteps(phase) count of the current position - effectorBackoutDir, // Direction in which the effector mm coordinates move away from endstop. - stepperBackoutDir; // Direction in which the TMC µstep count(phase) move away from endstop. - - switch (axis) { - #ifdef X_MICROSTEPS - case X_AXIS: - phasePerUStep = 256 / (X_MICROSTEPS); - phaseCurrent = stepperX.get_microstep_counter(); - effectorBackoutDir = -X_HOME_DIR; - stepperBackoutDir = INVERT_X_DIR ? effectorBackoutDir : -effectorBackoutDir; - break; - #endif - #ifdef Y_MICROSTEPS - case Y_AXIS: - phasePerUStep = 256 / (Y_MICROSTEPS); - phaseCurrent = stepperY.get_microstep_counter(); - effectorBackoutDir = -Y_HOME_DIR; - stepperBackoutDir = INVERT_Y_DIR ? effectorBackoutDir : -effectorBackoutDir; - break; - #endif - #ifdef Z_MICROSTEPS - case Z_AXIS: - phasePerUStep = 256 / (Z_MICROSTEPS); - phaseCurrent = stepperZ.get_microstep_counter(); - effectorBackoutDir = -Z_HOME_DIR; - stepperBackoutDir = INVERT_Z_DIR ? effectorBackoutDir : -effectorBackoutDir; - break; - #endif - default: return; - } + set_axis_untrusted(axis); + set_axis_unhomed(axis); - // Phase distance to nearest home phase position when moving in the backout direction from endstop(may be negative). - int16_t phaseDelta = (home_phase[axis] - phaseCurrent) * stepperBackoutDir; + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("<<< set_axis_never_homed(", AS_CHAR(AXIS_CHAR(axis)), ")"); - // Check if home distance within endstop assumed repeatability noise of .05mm and warn. - if (ABS(phaseDelta) * planner.steps_to_mm[axis] / phasePerUStep < 0.05f) - SERIAL_ECHOLNPAIR("Selected home phase ", home_phase[axis], - " too close to endstop trigger phase ", phaseCurrent, - ". Pick a different phase for ", axis_codes[axis]); + TERN_(I2C_POSITION_ENCODERS, I2CPEM.unhomed(axis)); + } - // Skip to next if target position is behind current. So it only moves away from endstop. - if (phaseDelta < 0) phaseDelta += 1024; + #ifdef TMC_HOME_PHASE + /** + * Move the axis back to its home_phase if set and driver is capable (TMC) + * + * Improves homing repeatability by homing to stepper coil's nearest absolute + * phase position. Trinamic drivers use a stepper phase table with 1024 values + * spanning 4 full steps with 256 positions each (ergo, 1024 positions). + */ + void backout_to_tmc_homing_phase(const AxisEnum axis) { + const xyz_long_t home_phase = TMC_HOME_PHASE; - // Convert TMC µsteps(phase) to whole Marlin µsteps to effector backout direction to mm - const float mmDelta = int16_t(phaseDelta / phasePerUStep) * effectorBackoutDir * planner.steps_to_mm[axis]; + // check if home phase is disabled for this axis. + if (home_phase[axis] < 0) return; - // Optional debug messages - if (DEBUGGING(LEVELING)) { - DEBUG_ECHOLNPAIR( - "Endstop ", axis_codes[axis], " hit at Phase:", phaseCurrent, - " Delta:", phaseDelta, " Distance:", mmDelta - ); - } + int16_t phasePerUStep, // TMC µsteps(phase) per Marlin µsteps + phaseCurrent, // The TMC µsteps(phase) count of the current position + effectorBackoutDir, // Direction in which the effector mm coordinates move away from endstop. + stepperBackoutDir; // Direction in which the TMC µstep count(phase) move away from endstop. - if (mmDelta != 0) { - // Retrace by the amount computed in mmDelta. - do_homing_move(axis, mmDelta, get_homing_bump_feedrate(axis)); - } - } -#endif + #define PHASE_PER_MICROSTEP(N) (256 / _MAX(1, N##_MICROSTEPS)) -/** - * Home an individual "raw axis" to its endstop. - * This applies to XYZ on Cartesian and Core robots, and - * to the individual ABC steppers on DELTA and SCARA. - * - * At the end of the procedure the axis is marked as - * homed and the current position of that axis is updated. - * Kinematic robots should wait till all axes are homed - * before updating the current position. - */ + switch (axis) { + #ifdef X_MICROSTEPS + case X_AXIS: + phasePerUStep = PHASE_PER_MICROSTEP(X); + phaseCurrent = stepperX.get_microstep_counter(); + effectorBackoutDir = -X_HOME_DIR; + stepperBackoutDir = INVERT_X_DIR ? effectorBackoutDir : -effectorBackoutDir; + break; + #endif + #ifdef Y_MICROSTEPS + case Y_AXIS: + phasePerUStep = PHASE_PER_MICROSTEP(Y); + phaseCurrent = stepperY.get_microstep_counter(); + effectorBackoutDir = -Y_HOME_DIR; + stepperBackoutDir = INVERT_Y_DIR ? effectorBackoutDir : -effectorBackoutDir; + break; + #endif + #ifdef Z_MICROSTEPS + case Z_AXIS: + phasePerUStep = PHASE_PER_MICROSTEP(Z); + phaseCurrent = stepperZ.get_microstep_counter(); + effectorBackoutDir = -Z_HOME_DIR; + stepperBackoutDir = INVERT_Z_DIR ? effectorBackoutDir : -effectorBackoutDir; + break; + #endif + #ifdef I_MICROSTEPS + case I_AXIS: + phasePerUStep = PHASE_PER_MICROSTEP(I); + phaseCurrent = stepperI.get_microstep_counter(); + effectorBackoutDir = -I_HOME_DIR; + stepperBackoutDir = INVERT_I_DIR ? effectorBackoutDir : -effectorBackoutDir; + break; + #endif + #ifdef J_MICROSTEPS + case J_AXIS: + phasePerUStep = PHASE_PER_MICROSTEP(J); + phaseCurrent = stepperJ.get_microstep_counter(); + effectorBackoutDir = -J_HOME_DIR; + stepperBackoutDir = INVERT_J_DIR ? effectorBackoutDir : -effectorBackoutDir; + break; + #endif + #ifdef K_MICROSTEPS + case K_AXIS: + phasePerUStep = PHASE_PER_MICROSTEP(K); + phaseCurrent = stepperK.get_microstep_counter(); + effectorBackoutDir = -K_HOME_DIR; + stepperBackoutDir = INVERT_K_DIR ? effectorBackoutDir : -effectorBackoutDir; + break; + #endif + default: return; + } -void homeaxis(const AxisEnum axis) { + // Phase distance to nearest home phase position when moving in the backout direction from endstop(may be negative). + int16_t phaseDelta = (home_phase[axis] - phaseCurrent) * stepperBackoutDir; - #if IS_SCARA - // Only Z homing (with probe) is permitted - if (axis != Z_AXIS) { BUZZ(100, 880); return; } - #else - #define _CAN_HOME(A) (axis == _AXIS(A) && ( \ - ENABLED(A##_SPI_SENSORLESS) \ - || (_AXIS(A) == Z_AXIS && ENABLED(HOMING_Z_WITH_PROBE)) \ - || (A##_MIN_PIN > -1 && A##_HOME_DIR < 0) \ - || (A##_MAX_PIN > -1 && A##_HOME_DIR > 0) \ - )) - if (!_CAN_HOME(X) && !_CAN_HOME(Y) && !_CAN_HOME(Z)) return; - #endif + // Check if home distance within endstop assumed repeatability noise of .05mm and warn. + if (ABS(phaseDelta) * planner.steps_to_mm[axis] / phasePerUStep < 0.05f) + SERIAL_ECHOLNPAIR("Selected home phase ", home_phase[axis], + " too close to endstop trigger phase ", phaseCurrent, + ". Pick a different phase for ", AS_CHAR(AXIS_CHAR(axis))); - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> homeaxis(", axis_codes[axis], ")"); + // Skip to next if target position is behind current. So it only moves away from endstop. + if (phaseDelta < 0) phaseDelta += 1024; - const int axis_home_dir = TERN0(DUAL_X_CARRIAGE, axis == X_AXIS) - ? x_home_dir(active_extruder) : home_dir(axis); + // Convert TMC µsteps(phase) to whole Marlin µsteps to effector backout direction to mm + const float mmDelta = int16_t(phaseDelta / phasePerUStep) * effectorBackoutDir * planner.steps_to_mm[axis]; - // Homing Z towards the bed? Deploy the Z probe or endstop. - if (TERN0(HOMING_Z_WITH_PROBE, axis == Z_AXIS && probe.deploy())) - return; + // Optional debug messages + if (DEBUGGING(LEVELING)) { + DEBUG_ECHOLNPAIR( + "Endstop ", AS_CHAR(AXIS_CHAR(axis)), " hit at Phase:", phaseCurrent, + " Delta:", phaseDelta, " Distance:", mmDelta + ); + } - // Set flags for X, Y, Z motor locking - #if HAS_EXTRA_ENDSTOPS - switch (axis) { - TERN_(X_DUAL_ENDSTOPS, case X_AXIS:) - TERN_(Y_DUAL_ENDSTOPS, case Y_AXIS:) - TERN_(Z_MULTI_ENDSTOPS, case Z_AXIS:) - stepper.set_separate_multi_axis(true); - default: break; + if (mmDelta != 0) { + // Retrace by the amount computed in mmDelta. + do_homing_move(axis, mmDelta, get_homing_bump_feedrate(axis)); + } } #endif - // Fast move towards endstop until triggered - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Home 1 Fast:"); + /** + * Home an individual "raw axis" to its endstop. + * This applies to XYZ on Cartesian and Core robots, and + * to the individual ABC steppers on DELTA and SCARA. + * + * At the end of the procedure the axis is marked as + * homed and the current position of that axis is updated. + * Kinematic robots should wait till all axes are homed + * before updating the current position. + */ - #if BOTH(HOMING_Z_WITH_PROBE, BLTOUCH) - if (axis == Z_AXIS && bltouch.deploy()) return; // The initial DEPLOY - #endif + void homeaxis(const AxisEnum axis) { - #if DISABLED(DELTA) && defined(SENSORLESS_BACKOFF_MM) - const xy_float_t backoff = SENSORLESS_BACKOFF_MM; - if (((ENABLED(X_SENSORLESS) && axis == X_AXIS) || (ENABLED(Y_SENSORLESS) && axis == Y_AXIS)) && backoff[axis]) - do_homing_move(axis, -ABS(backoff[axis]) * axis_home_dir, homing_feedrate(axis)); - #endif + #if EITHER(MORGAN_SCARA, MP_SCARA) + // Only Z homing (with probe) is permitted + if (axis != Z_AXIS) { BUZZ(100, 880); return; } + #else + #define _CAN_HOME(A) (axis == _AXIS(A) && ( \ + ENABLED(A##_SPI_SENSORLESS) \ + || TERN0(HAS_Z_AXIS, TERN0(HOMING_Z_WITH_PROBE, _AXIS(A) == Z_AXIS)) \ + || TERN0(A##_HOME_TO_MIN, A##_MIN_PIN > -1) \ + || TERN0(A##_HOME_TO_MAX, A##_MAX_PIN > -1) \ + )) + if (LINEAR_AXIS_GANG( + !_CAN_HOME(X), + && !_CAN_HOME(Y), + && !_CAN_HOME(Z), + && !_CAN_HOME(I), + && !_CAN_HOME(J), + && !_CAN_HOME(K)) + ) return; + #endif - do_homing_move(axis, 1.5f * max_length(TERN(DELTA, Z_AXIS, axis)) * axis_home_dir); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> homeaxis(", AS_CHAR(AXIS_CHAR(axis)), ")"); - #if BOTH(HOMING_Z_WITH_PROBE, BLTOUCH) && DISABLED(BLTOUCH_HS_MODE) - if (axis == Z_AXIS) bltouch.stow(); // Intermediate STOW (in LOW SPEED MODE) - #endif - - // When homing Z with probe respect probe clearance - const bool use_probe_bump = TERN0(HOMING_Z_WITH_PROBE, axis == Z_AXIS && home_bump_mm(Z_AXIS)); - const float bump = axis_home_dir * ( - use_probe_bump ? _MAX(TERN0(HOMING_Z_WITH_PROBE, Z_CLEARANCE_BETWEEN_PROBES), home_bump_mm(Z_AXIS)) : home_bump_mm(axis) - ); + const int axis_home_dir = TERN0(DUAL_X_CARRIAGE, axis == X_AXIS) + ? TOOL_X_HOME_DIR(active_extruder) : home_dir(axis); - // If a second homing move is configured... - if (bump) { - // Move away from the endstop by the axis HOMING_BUMP_MM - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Move Away:"); - do_homing_move(axis, -bump - #if HOMING_Z_WITH_PROBE - , MMM_TO_MMS(axis == Z_AXIS ? Z_PROBE_SPEED_FAST : 0) - #endif - ); + // + // Homing Z with a probe? Raise Z (maybe) and deploy the Z probe. + // + if (TERN0(HOMING_Z_WITH_PROBE, axis == Z_AXIS && probe.deploy())) + return; - #if ENABLED(DETECT_BROKEN_ENDSTOP) - // Check for a broken endstop - EndstopEnum es; + // Set flags for X, Y, Z motor locking + #if HAS_EXTRA_ENDSTOPS switch (axis) { - default: - case X_AXIS: es = X_ENDSTOP; break; - case Y_AXIS: es = Y_ENDSTOP; break; - case Z_AXIS: es = Z_ENDSTOP; break; - } - if (TEST(endstops.state(), es)) { - SERIAL_ECHO_MSG("Bad ", axis_codes[axis], " Endstop?"); - kill(GET_TEXT(MSG_KILL_HOMING_FAILED)); + TERN_(X_DUAL_ENDSTOPS, case X_AXIS:) + TERN_(Y_DUAL_ENDSTOPS, case Y_AXIS:) + TERN_(Z_MULTI_ENDSTOPS, case Z_AXIS:) + stepper.set_separate_multi_axis(true); + default: break; } #endif - // Slow move towards endstop until triggered - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Home 2 Slow:"); + // + // Deploy BLTouch or tare the probe just before probing + // + #if HOMING_Z_WITH_PROBE + if (axis == Z_AXIS) { + if (TERN0(BLTOUCH, bltouch.deploy())) return; // BLTouch was deployed above, but get the alarm state. + if (TERN0(PROBE_TARE, probe.tare())) return; + } + #endif - #if BOTH(HOMING_Z_WITH_PROBE, BLTOUCH) && DISABLED(BLTOUCH_HS_MODE) - if (axis == Z_AXIS && bltouch.deploy()) return; // Intermediate DEPLOY (in LOW SPEED MODE) + // + // Back away to prevent an early sensorless trigger + // + #if DISABLED(DELTA) && defined(SENSORLESS_BACKOFF_MM) + const xyz_float_t backoff = SENSORLESS_BACKOFF_MM; + if ((TERN0(X_SENSORLESS, axis == X_AXIS) || TERN0(Y_SENSORLESS, axis == Y_AXIS) || TERN0(Z_SENSORLESS, axis == Z_AXIS) || TERN0(I_SENSORLESS, axis == I_AXIS) || TERN0(J_SENSORLESS, axis == J_AXIS) || TERN0(K_SENSORLESS, axis == K_AXIS)) && backoff[axis]) { + const float backoff_length = -ABS(backoff[axis]) * axis_home_dir; + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Sensorless backoff: ", backoff_length, "mm"); + do_homing_move(axis, backoff_length, homing_feedrate(axis)); + } #endif - do_homing_move(axis, 2 * bump, get_homing_bump_feedrate(axis)); + // Determine if a homing bump will be done and the bumps distance + // When homing Z with probe respect probe clearance + const bool use_probe_bump = TERN0(HOMING_Z_WITH_PROBE, axis == Z_AXIS && home_bump_mm(axis)); + const float bump = axis_home_dir * ( + use_probe_bump ? _MAX(TERN0(HOMING_Z_WITH_PROBE, Z_CLEARANCE_BETWEEN_PROBES), home_bump_mm(axis)) : home_bump_mm(axis) + ); + + // + // Fast move towards endstop until triggered + // + const float move_length = 1.5f * max_length(TERN(DELTA, Z_AXIS, axis)) * axis_home_dir; + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("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.stow(); // The final STOW + #if BOTH(HOMING_Z_WITH_PROBE, BLTOUCH_SLOW_MODE) + if (axis == Z_AXIS) bltouch.stow(); // Intermediate STOW (in LOW SPEED MODE) #endif - } - #if HAS_EXTRA_ENDSTOPS - const bool pos_dir = axis_home_dir > 0; - #if ENABLED(X_DUAL_ENDSTOPS) - if (axis == X_AXIS) { - const float adj = ABS(endstops.x2_endstop_adj); - if (adj) { - if (pos_dir ? (endstops.x2_endstop_adj > 0) : (endstops.x2_endstop_adj < 0)) stepper.set_x_lock(true); else stepper.set_x2_lock(true); - do_homing_move(axis, pos_dir ? -adj : adj); - stepper.set_x_lock(false); - stepper.set_x2_lock(false); + // If a second homing move is configured... + if (bump) { + // Move away from the endstop by the axis HOMING_BUMP_MM + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("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); + + #if ENABLED(DETECT_BROKEN_ENDSTOP) + // Check for a broken endstop + EndstopEnum es; + switch (axis) { + default: + case X_AXIS: es = X_ENDSTOP; break; + case Y_AXIS: es = Y_ENDSTOP; break; + case Z_AXIS: es = Z_ENDSTOP; break; + #if LINEAR_AXES >= 4 + case I_AXIS: es = I_ENDSTOP; break; + #endif + #if LINEAR_AXES >= 5 + case J_AXIS: es = J_ENDSTOP; break; + #endif + #if LINEAR_AXES >= 6 + case K_AXIS: es = K_ENDSTOP; break; + #endif } - } - #endif - #if ENABLED(Y_DUAL_ENDSTOPS) - if (axis == Y_AXIS) { - const float adj = ABS(endstops.y2_endstop_adj); - if (adj) { - if (pos_dir ? (endstops.y2_endstop_adj > 0) : (endstops.y2_endstop_adj < 0)) stepper.set_y_lock(true); else stepper.set_y2_lock(true); - do_homing_move(axis, pos_dir ? -adj : adj); - stepper.set_y_lock(false); - stepper.set_y2_lock(false); + if (TEST(endstops.state(), es)) { + SERIAL_ECHO_MSG("Bad ", AS_CHAR(AXIS_CHAR(axis)), " Endstop?"); + kill(GET_TEXT(MSG_KILL_HOMING_FAILED)); } - } - #endif + #endif - #if ENABLED(Z_MULTI_ENDSTOPS) - if (axis == Z_AXIS) { + #if BOTH(HOMING_Z_WITH_PROBE, BLTOUCH_SLOW_MODE) + if (axis == Z_AXIS && bltouch.deploy()) return; // Intermediate DEPLOY (in LOW SPEED MODE) + #endif + + // Slow move towards endstop until triggered + const float rebump = bump * 2; + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Re-bump: ", rebump, "mm"); + do_homing_move(axis, rebump, get_homing_bump_feedrate(axis), true); - #if NUM_Z_STEPPER_DRIVERS == 2 + #if BOTH(HOMING_Z_WITH_PROBE, BLTOUCH) + if (axis == Z_AXIS) bltouch.stow(); // The final STOW + #endif + } - const float adj = ABS(endstops.z2_endstop_adj); + #if HAS_EXTRA_ENDSTOPS + const bool pos_dir = axis_home_dir > 0; + #if ENABLED(X_DUAL_ENDSTOPS) + if (axis == X_AXIS) { + const float adj = ABS(endstops.x2_endstop_adj); if (adj) { - if (pos_dir ? (endstops.z2_endstop_adj > 0) : (endstops.z2_endstop_adj < 0)) stepper.set_z1_lock(true); else stepper.set_z2_lock(true); + if (pos_dir ? (endstops.x2_endstop_adj > 0) : (endstops.x2_endstop_adj < 0)) stepper.set_x_lock(true); else stepper.set_x2_lock(true); do_homing_move(axis, pos_dir ? -adj : adj); - stepper.set_z1_lock(false); - stepper.set_z2_lock(false); + stepper.set_x_lock(false); + stepper.set_x2_lock(false); } + } + #endif + #if ENABLED(Y_DUAL_ENDSTOPS) + if (axis == Y_AXIS) { + const float adj = ABS(endstops.y2_endstop_adj); + if (adj) { + if (pos_dir ? (endstops.y2_endstop_adj > 0) : (endstops.y2_endstop_adj < 0)) stepper.set_y_lock(true); else stepper.set_y2_lock(true); + do_homing_move(axis, pos_dir ? -adj : adj); + stepper.set_y_lock(false); + stepper.set_y2_lock(false); + } + } + #endif - #else - - // Handy arrays of stepper lock function pointers + #if ENABLED(Z_MULTI_ENDSTOPS) + if (axis == Z_AXIS) { - typedef void (*adjustFunc_t)(const bool); + #if NUM_Z_STEPPER_DRIVERS == 2 - adjustFunc_t lock[] = { - stepper.set_z1_lock, stepper.set_z2_lock, stepper.set_z3_lock - #if NUM_Z_STEPPER_DRIVERS >= 4 - , stepper.set_z4_lock - #endif - }; - float adj[] = { - 0, endstops.z2_endstop_adj, endstops.z3_endstop_adj - #if NUM_Z_STEPPER_DRIVERS >= 4 - , endstops.z4_endstop_adj - #endif - }; + const float adj = ABS(endstops.z2_endstop_adj); + if (adj) { + if (pos_dir ? (endstops.z2_endstop_adj > 0) : (endstops.z2_endstop_adj < 0)) stepper.set_z1_lock(true); else stepper.set_z2_lock(true); + do_homing_move(axis, pos_dir ? -adj : adj); + stepper.set_z1_lock(false); + stepper.set_z2_lock(false); + } - adjustFunc_t tempLock; - float tempAdj; + #else - // Manual bubble sort by adjust value - if (adj[1] < adj[0]) { - tempLock = lock[0], tempAdj = adj[0]; - lock[0] = lock[1], adj[0] = adj[1]; - lock[1] = tempLock, adj[1] = tempAdj; - } - if (adj[2] < adj[1]) { - tempLock = lock[1], tempAdj = adj[1]; - lock[1] = lock[2], adj[1] = adj[2]; - lock[2] = tempLock, adj[2] = tempAdj; - } - #if NUM_Z_STEPPER_DRIVERS >= 4 - if (adj[3] < adj[2]) { - tempLock = lock[2], tempAdj = adj[2]; - lock[2] = lock[3], adj[2] = adj[3]; - lock[3] = tempLock, adj[3] = tempAdj; + // Handy arrays of stepper lock function pointers + + typedef void (*adjustFunc_t)(const bool); + + adjustFunc_t lock[] = { + stepper.set_z1_lock, stepper.set_z2_lock, stepper.set_z3_lock + #if NUM_Z_STEPPER_DRIVERS >= 4 + , stepper.set_z4_lock + #endif + }; + float adj[] = { + 0, endstops.z2_endstop_adj, endstops.z3_endstop_adj + #if NUM_Z_STEPPER_DRIVERS >= 4 + , endstops.z4_endstop_adj + #endif + }; + + adjustFunc_t tempLock; + float tempAdj; + + // Manual bubble sort by adjust value + if (adj[1] < adj[0]) { + tempLock = lock[0], tempAdj = adj[0]; + lock[0] = lock[1], adj[0] = adj[1]; + lock[1] = tempLock, adj[1] = tempAdj; } if (adj[2] < adj[1]) { tempLock = lock[1], tempAdj = adj[1]; lock[1] = lock[2], adj[1] = adj[2]; lock[2] = tempLock, adj[2] = tempAdj; } - #endif - if (adj[1] < adj[0]) { - tempLock = lock[0], tempAdj = adj[0]; - lock[0] = lock[1], adj[0] = adj[1]; - lock[1] = tempLock, adj[1] = tempAdj; - } - - if (pos_dir) { - // normalize adj to smallest value and do the first move - (*lock[0])(true); - do_homing_move(axis, adj[1] - adj[0]); - // lock the second stepper for the final correction - (*lock[1])(true); - do_homing_move(axis, adj[2] - adj[1]); #if NUM_Z_STEPPER_DRIVERS >= 4 - // lock the third stepper for the final correction - (*lock[2])(true); - do_homing_move(axis, adj[3] - adj[2]); + if (adj[3] < adj[2]) { + tempLock = lock[2], tempAdj = adj[2]; + lock[2] = lock[3], adj[2] = adj[3]; + lock[3] = tempLock, adj[3] = tempAdj; + } + if (adj[2] < adj[1]) { + tempLock = lock[1], tempAdj = adj[1]; + lock[1] = lock[2], adj[1] = adj[2]; + lock[2] = tempLock, adj[2] = tempAdj; + } #endif - } - else { + if (adj[1] < adj[0]) { + tempLock = lock[0], tempAdj = adj[0]; + lock[0] = lock[1], adj[0] = adj[1]; + lock[1] = tempLock, adj[1] = tempAdj; + } + + if (pos_dir) { + // normalize adj to smallest value and do the first move + (*lock[0])(true); + do_homing_move(axis, adj[1] - adj[0]); + // lock the second stepper for the final correction + (*lock[1])(true); + do_homing_move(axis, adj[2] - adj[1]); + #if NUM_Z_STEPPER_DRIVERS >= 4 + // lock the third stepper for the final correction + (*lock[2])(true); + do_homing_move(axis, adj[3] - adj[2]); + #endif + } + else { + #if NUM_Z_STEPPER_DRIVERS >= 4 + (*lock[3])(true); + do_homing_move(axis, adj[2] - adj[3]); + #endif + (*lock[2])(true); + do_homing_move(axis, adj[1] - adj[2]); + (*lock[1])(true); + do_homing_move(axis, adj[0] - adj[1]); + } + + stepper.set_z1_lock(false); + stepper.set_z2_lock(false); + stepper.set_z3_lock(false); #if NUM_Z_STEPPER_DRIVERS >= 4 - (*lock[3])(true); - do_homing_move(axis, adj[2] - adj[3]); + stepper.set_z4_lock(false); #endif - (*lock[2])(true); - do_homing_move(axis, adj[1] - adj[2]); - (*lock[1])(true); - do_homing_move(axis, adj[0] - adj[1]); - } - stepper.set_z1_lock(false); - stepper.set_z2_lock(false); - stepper.set_z3_lock(false); - #if NUM_Z_STEPPER_DRIVERS >= 4 - stepper.set_z4_lock(false); #endif + } + #endif - #endif + // Reset flags for X, Y, Z motor locking + switch (axis) { + default: break; + TERN_(X_DUAL_ENDSTOPS, case X_AXIS:) + TERN_(Y_DUAL_ENDSTOPS, case Y_AXIS:) + TERN_(Z_MULTI_ENDSTOPS, case Z_AXIS:) + stepper.set_separate_multi_axis(false); } + + #endif // HAS_EXTRA_ENDSTOPS + + #ifdef TMC_HOME_PHASE + // move back to homing phase if configured and capable + backout_to_tmc_homing_phase(axis); #endif - // Reset flags for X, Y, Z motor locking - switch (axis) { - default: break; - TERN_(X_DUAL_ENDSTOPS, case X_AXIS:) - TERN_(Y_DUAL_ENDSTOPS, case Y_AXIS:) - TERN_(Z_MULTI_ENDSTOPS, case Z_AXIS:) - stepper.set_separate_multi_axis(false); - } - #endif + #if IS_SCARA - #ifdef TMC_HOME_PHASE - // move back to homing phase if configured and capable - backout_to_tmc_homing_phase(axis); - #endif + set_axis_is_at_home(axis); + sync_plan_position(); - #if IS_SCARA + #elif ENABLED(DELTA) - set_axis_is_at_home(axis); - sync_plan_position(); + // Delta has already moved all three towers up in G28 + // so here it re-homes each tower in turn. + // Delta homing treats the axes as normal linear axes. - #elif ENABLED(DELTA) + const float adjDistance = delta_endstop_adj[axis], + minDistance = (MIN_STEPS_PER_SEGMENT) * planner.steps_to_mm[axis]; - // Delta has already moved all three towers up in G28 - // so here it re-homes each tower in turn. - // Delta homing treats the axes as normal linear axes. + // Retrace by the amount specified in delta_endstop_adj if more than min steps. + if (adjDistance * (Z_HOME_DIR) < 0 && ABS(adjDistance) > minDistance) { // away from endstop, more than min distance + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("adjDistance:", adjDistance); + do_homing_move(axis, adjDistance, get_homing_bump_feedrate(axis)); + } - const float adjDistance = delta_endstop_adj[axis], - minDistance = (MIN_STEPS_PER_SEGMENT) * planner.steps_to_mm[axis]; + #else // CARTESIAN / CORE / MARKFORGED_XY - // Retrace by the amount specified in delta_endstop_adj if more than min steps. - if (adjDistance * (Z_HOME_DIR) < 0 && ABS(adjDistance) > minDistance) { // away from endstop, more than min distance - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("adjDistance:", adjDistance); - do_homing_move(axis, adjDistance, get_homing_bump_feedrate(axis)); - } + set_axis_is_at_home(axis); + sync_plan_position(); + + destination[axis] = current_position[axis]; - #else // CARTESIAN / CORE / MARKFORGED_XY + if (DEBUGGING(LEVELING)) DEBUG_POS("> AFTER set_axis_is_at_home", current_position); + + #endif + + // Put away the Z probe + #if HOMING_Z_WITH_PROBE + if (axis == Z_AXIS && probe.stow()) return; + #endif + + #if DISABLED(DELTA) && defined(HOMING_BACKOFF_POST_MM) + const xyz_float_t endstop_backoff = HOMING_BACKOFF_POST_MM; + if (endstop_backoff[axis]) { + current_position[axis] -= ABS(endstop_backoff[axis]) * axis_home_dir; + line_to_current_position( + #if HOMING_Z_WITH_PROBE + (axis == Z_AXIS) ? z_probe_fast_mm_s : + #endif + homing_feedrate(axis) + ); + + #if ENABLED(SENSORLESS_HOMING) + planner.synchronize(); + if (false + #if EITHER(IS_CORE, MARKFORGED_XY) + || axis != NORMAL_AXIS + #endif + ) safe_delay(200); // Short delay to allow belts to spring back + #endif + } + #endif + + // Clear retracted status if homing the Z axis + #if ENABLED(FWRETRACT) + if (axis == Z_AXIS) fwretract.current_hop = 0.0; + #endif - set_axis_is_at_home(axis); - sync_plan_position(); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("<<< homeaxis(", AS_CHAR(AXIS_CHAR(axis)), ")"); - destination[axis] = current_position[axis]; + } // homeaxis() + +#endif // HAS_ENDSTOPS + +/** + * Set an axis' current position to its home position (after homing). + * + * For Core and Cartesian robots this applies one-to-one when an + * individual axis has been homed. + * + * DELTA should wait until all homing is done before setting the XYZ + * current_position to home, because homing is a single operation. + * In the case where the axis positions are trusted and previously + * homed, DELTA could home to X or Y individually by moving either one + * to the center. However, homing Z always homes XY and Z. + * + * SCARA should wait until all XY homing is done before setting the XY + * current_position to home, because neither X nor Y is at home until + * both are at home. Z can however be homed individually. + * + * Callers must sync the planner position after calling this! + */ +void set_axis_is_at_home(const AxisEnum axis) { + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> set_axis_is_at_home(", AS_CHAR(AXIS_CHAR(axis)), ")"); - if (DEBUGGING(LEVELING)) DEBUG_POS("> AFTER set_axis_is_at_home", current_position); + set_axis_trusted(axis); + set_axis_homed(axis); + #if ENABLED(DUAL_X_CARRIAGE) + if (axis == X_AXIS && (active_extruder == 1 || dual_x_carriage_mode == DXC_DUPLICATION_MODE)) { + current_position.x = x_home_pos(active_extruder); + return; + } #endif - // Put away the Z probe - #if HOMING_Z_WITH_PROBE - if (axis == Z_AXIS && probe.stow()) return; + #if EITHER(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); + #else + current_position[axis] = base_home_pos(axis); #endif - #if DISABLED(DELTA) && defined(HOMING_BACKOFF_POST_MM) - const xyz_float_t endstop_backoff = HOMING_BACKOFF_POST_MM; - if (endstop_backoff[axis]) { - current_position[axis] -= ABS(endstop_backoff[axis]) * axis_home_dir; - line_to_current_position( - #if HOMING_Z_WITH_PROBE - (axis == Z_AXIS) ? MMM_TO_MMS(Z_PROBE_SPEED_FAST) : - #endif - homing_feedrate(axis) - ); + /** + * Z Probe Z Homing? Account for the probe's Z offset. + */ + #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_ECHOLNPAIR("*** 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 ***"); - #if ENABLED(SENSORLESS_HOMING) - planner.synchronize(); - if (false - #if EITHER(IS_CORE, MARKFORGED_XY) - || axis != NORMAL_AXIS - #endif - ) safe_delay(200); // Short delay to allow belts to spring back #endif } #endif - // Clear retracted status if homing the Z axis - #if ENABLED(FWRETRACT) - if (axis == Z_AXIS) fwretract.current_hop = 0.0; - #endif + TERN_(I2C_POSITION_ENCODERS, I2CPEM.homed(axis)); - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("<<< homeaxis(", axis_codes[axis], ")"); + TERN_(BABYSTEP_DISPLAY_TOTAL, babystep.reset_total(axis)); + + #if HAS_POSITION_SHIFT + position_shift[axis] = 0; + update_workspace_offset(axis); + #endif -} // homeaxis() + if (DEBUGGING(LEVELING)) { + #if HAS_HOME_OFFSET + DEBUG_ECHOLNPAIR("> home_offset[", AS_CHAR(AXIS_CHAR(axis)), "] = ", home_offset[axis]); + #endif + DEBUG_POS("", current_position); + DEBUG_ECHOLNPAIR("<<< set_axis_is_at_home(", AS_CHAR(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_ECHOLNPAIR("Axis ", XYZ_CHAR(axis), " home_offset = ", home_offset[axis], " position_shift = ", position_shift[axis]); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Axis ", AS_CHAR(AXIS_CHAR(axis)), " home_offset = ", home_offset[axis], " position_shift = ", position_shift[axis]); } #endif @@ -1856,4 +2148,4 @@ void homeaxis(const AxisEnum axis) { home_offset[axis] = v; update_workspace_offset(axis); } -#endif // HAS_M206_COMMAND +#endif diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index 85b70c057aa9..c41738a5ab67 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -34,19 +34,6 @@ #include "scara.h" #endif -// Axis homed and known-position states -extern uint8_t axis_homed, axis_known_position; -constexpr uint8_t xyz_bits = _BV(X_AXIS) | _BV(Y_AXIS) | _BV(Z_AXIS); -FORCE_INLINE bool no_axes_homed() { return !axis_homed; } -FORCE_INLINE bool all_axes_homed() { return (axis_homed & xyz_bits) == xyz_bits; } -FORCE_INLINE bool all_axes_known() { return (axis_known_position & xyz_bits) == xyz_bits; } -FORCE_INLINE void set_all_homed() { axis_homed = axis_known_position = xyz_bits; } -FORCE_INLINE void set_all_unhomed() { axis_homed = axis_known_position = 0; } - -FORCE_INLINE bool homing_needed() { - return !TERN(HOME_AFTER_DEACTIVATE, all_axes_known, all_axes_homed)(); -} - // Error margin to work around float imprecision constexpr float fslop = 0.0001; @@ -57,8 +44,8 @@ extern xyze_pos_t current_position, // High-level current tool position // G60/G61 Position Save and Return #if SAVED_POSITIONS - extern uint8_t saved_slots[(SAVED_POSITIONS + 7) >> 3]; - extern xyz_pos_t stored_position[SAVED_POSITIONS]; + extern uint8_t saved_slots[(SAVED_POSITIONS + 7) >> 3]; // TODO: Add support for LINEAR_AXES >= 4 + extern xyze_pos_t stored_position[SAVED_POSITIONS]; #endif // Scratch space for a cartesian result @@ -66,36 +53,54 @@ extern xyz_pos_t cartes; // Until kinematics.cpp is created, declare this here #if IS_KINEMATIC - extern abc_pos_t delta; + extern abce_pos_t delta; #endif #if HAS_ABL_NOT_UBL - extern float xy_probe_feedrate_mm_s; + extern feedRate_t xy_probe_feedrate_mm_s; #define XY_PROBE_FEEDRATE_MM_S xy_probe_feedrate_mm_s -#elif defined(XY_PROBE_SPEED) - #define XY_PROBE_FEEDRATE_MM_S MMM_TO_MMS(XY_PROBE_SPEED) +#elif defined(XY_PROBE_FEEDRATE) + #define XY_PROBE_FEEDRATE_MM_S MMM_TO_MMS(XY_PROBE_FEEDRATE) #else #define XY_PROBE_FEEDRATE_MM_S PLANNER_XY_FEEDRATE() #endif -#if ENABLED(Z_SAFE_HOMING) - constexpr xy_float_t safe_homing_xy = { Z_SAFE_HOMING_X_POINT, Z_SAFE_HOMING_Y_POINT }; +#if HAS_BED_PROBE + constexpr feedRate_t z_probe_fast_mm_s = MMM_TO_MMS(Z_PROBE_FEEDRATE_FAST); #endif /** * Feed rates are often configured with mm/m * but the planner and stepper like mm/s units. */ -extern const feedRate_t homing_feedrate_mm_s[XYZ]; -FORCE_INLINE feedRate_t homing_feedrate(const AxisEnum a) { return pgm_read_float(&homing_feedrate_mm_s[a]); } +constexpr xyz_feedrate_t homing_feedrate_mm_m = HOMING_FEEDRATE_MM_M; +FORCE_INLINE feedRate_t homing_feedrate(const AxisEnum a) { + float v = TERN0(HAS_Z_AXIS, homing_feedrate_mm_m.z); + #if DISABLED(DELTA) + LINEAR_AXIS_CODE( + if (a == X_AXIS) v = homing_feedrate_mm_m.x, + else if (a == Y_AXIS) v = homing_feedrate_mm_m.y, + else if (a == Z_AXIS) v = homing_feedrate_mm_m.z, + else if (a == I_AXIS) v = homing_feedrate_mm_m.i, + else if (a == J_AXIS) v = homing_feedrate_mm_m.j, + else if (a == K_AXIS) v = homing_feedrate_mm_m.k + ); + #endif + return MMM_TO_MMS(v); +} + feedRate_t get_homing_bump_feedrate(const AxisEnum axis); +/** + * The default feedrate for many moves, set by the most recent move + */ extern feedRate_t feedrate_mm_s; /** - * Feedrate scaling + * Feedrate scaling is applied to all G0/G1, G2/G3, and G5 moves */ extern int16_t feedrate_percentage; +#define MMS_SCALED(V) ((V) * 0.01f * feedrate_percentage) // The active extruder (tool). Set with T command. #if HAS_MULTI_EXTRUDER @@ -119,7 +124,7 @@ inline int8_t pgm_read_any(const int8_t *p) { return TERN(__IMXRT1062__, *p, pgm #define XYZ_DEFS(T, NAME, OPT) \ inline T NAME(const AxisEnum axis) { \ - static const XYZval NAME##_P DEFS_PROGMEM = { X_##OPT, Y_##OPT, Z_##OPT }; \ + static const XYZval NAME##_P DEFS_PROGMEM = LINEAR_AXIS_ARRAY(X_##OPT, Y_##OPT, Z_##OPT, I_##OPT, J_##OPT, K_##OPT); \ return pgm_read_any(&NAME##_P[axis]); \ } XYZ_DEFS(float, base_min_pos, MIN_POS); @@ -163,13 +168,36 @@ inline float home_bump_mm(const AxisEnum axis) { TERN_(MIN_SOFTWARE_ENDSTOP_X, amin = min.x); TERN_(MAX_SOFTWARE_ENDSTOP_X, amax = max.x); break; - case Y_AXIS: - TERN_(MIN_SOFTWARE_ENDSTOP_Y, amin = min.y); - TERN_(MAX_SOFTWARE_ENDSTOP_Y, amax = max.y); - break; - case Z_AXIS: - TERN_(MIN_SOFTWARE_ENDSTOP_Z, amin = min.z); - TERN_(MAX_SOFTWARE_ENDSTOP_Z, amax = max.z); + #if HAS_Y_AXIS + case Y_AXIS: + TERN_(MIN_SOFTWARE_ENDSTOP_Y, amin = min.y); + TERN_(MAX_SOFTWARE_ENDSTOP_Y, amax = max.y); + break; + #endif + #if HAS_Z_AXIS + case Z_AXIS: + TERN_(MIN_SOFTWARE_ENDSTOP_Z, amin = min.z); + TERN_(MAX_SOFTWARE_ENDSTOP_Z, amax = max.z); + break; + #endif + #if LINEAR_AXES >= 4 + case I_AXIS: + TERN_(MIN_SOFTWARE_ENDSTOP_I, amin = min.i); + TERN_(MIN_SOFTWARE_ENDSTOP_I, amax = max.i); + break; + #endif + #if LINEAR_AXES >= 5 + case J_AXIS: + TERN_(MIN_SOFTWARE_ENDSTOP_J, amin = min.j); + TERN_(MIN_SOFTWARE_ENDSTOP_J, amax = max.j); + break; + #endif + #if LINEAR_AXES >= 6 + case K_AXIS: + TERN_(MIN_SOFTWARE_ENDSTOP_K, amin = min.k); + TERN_(MIN_SOFTWARE_ENDSTOP_K, amax = max.k); + break; + #endif default: break; } #endif @@ -206,44 +234,86 @@ void report_real_position(); void report_current_position(); void report_current_position_projected(); +#if ENABLED(AUTO_REPORT_POSITION) + #include "../libs/autoreport.h" + struct PositionReport { static void report() { report_current_position_projected(); } }; + extern AutoReporter position_auto_reporter; +#endif + +#if EITHER(FULL_REPORT_TO_HOST_FEATURE, REALTIME_REPORTING_COMMANDS) + #define HAS_GRBL_STATE 1 + /** + * Machine states for GRBL or TinyG + */ + enum M_StateEnum : uint8_t { + M_INIT = 0, // 0 machine is initializing + M_RESET, // 1 machine is ready for use + M_ALARM, // 2 machine is in alarm state (soft shut down) + M_IDLE, // 3 program stop or no more blocks (M0, M1, M60) + M_END, // 4 program end via M2, M30 + M_RUNNING, // 5 motion is running + M_HOLD, // 6 motion is holding + M_PROBE, // 7 probe cycle active + M_CYCLING, // 8 machine is running (cycling) + M_HOMING, // 9 machine is homing + M_JOGGING, // 10 machine is jogging + M_ERROR // 11 machine is in hard alarm state (shut down) + }; + extern M_StateEnum M_State_grbl; + M_StateEnum grbl_state_for_marlin_state(); + void report_current_grblstate_moving(); + void report_current_position_moving(); + + #if ENABLED(FULL_REPORT_TO_HOST_FEATURE) + inline void set_and_report_grblstate(const M_StateEnum state) { + M_State_grbl = state; + report_current_grblstate_moving(); + } + #endif + + #if ENABLED(REALTIME_REPORTING_COMMANDS) + void quickpause_stepper(); + void quickresume_stepper(); + #endif +#endif + void get_cartesian_from_steppers(); void set_current_from_steppers_for_axis(const AxisEnum axis); +void quickstop_stepper(); + /** - * sync_plan_position - * * Set the planner/stepper positions directly from current_position with * no kinematic translation. Used for homing axes and cartesian/core syncing. */ void sync_plan_position(); -void sync_plan_position_e(); + +#if HAS_EXTRUDERS + void sync_plan_position_e(); +#endif /** * Move the planner to the current position from wherever it last moved * (or from wherever it has been told it is located). */ -void line_to_current_position(const feedRate_t &fr_mm_s=feedrate_mm_s); +void line_to_current_position(const_feedRate_t fr_mm_s=feedrate_mm_s); -#if EXTRUDERS - void unscaled_e_move(const float &length, const feedRate_t &fr_mm_s); +#if HAS_EXTRUDERS + void unscaled_e_move(const_float_t length, const_feedRate_t fr_mm_s); #endif void prepare_line_to_destination(); -void _internal_move_to_destination(const feedRate_t &fr_mm_s=0.0f - #if IS_KINEMATIC - , const bool is_fast=false - #endif -); +void _internal_move_to_destination(const_feedRate_t fr_mm_s=0.0f OPTARG(IS_KINEMATIC, const bool is_fast=false)); -inline void prepare_internal_move_to_destination(const feedRate_t &fr_mm_s=0.0f) { +inline void prepare_internal_move_to_destination(const_feedRate_t fr_mm_s=0.0f) { _internal_move_to_destination(fr_mm_s); } #if IS_KINEMATIC - void prepare_fast_move_to_destination(const feedRate_t &scaled_fr_mm_s=MMS_SCALED(feedrate_mm_s)); + void prepare_fast_move_to_destination(const_feedRate_t scaled_fr_mm_s=MMS_SCALED(feedrate_mm_s)); - inline void prepare_internal_fast_move_to_destination(const feedRate_t &fr_mm_s=0.0f) { + inline void prepare_internal_fast_move_to_destination(const_feedRate_t fr_mm_s=0.0f) { _internal_move_to_destination(fr_mm_s, true); } #endif @@ -251,38 +321,106 @@ 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(const float rx, const float ry, const float rz, 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 &rx, const feedRate_t &fr_mm_s=0.0f); -void do_blocking_move_to_y(const float &ry, const feedRate_t &fr_mm_s=0.0f); -void do_blocking_move_to_z(const float &rz, const feedRate_t &fr_mm_s=0.0f); +void do_blocking_move_to(LINEAR_AXIS_ARGS(const float), 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_Y_AXIS + void do_blocking_move_to_y(const_float_t ry, const_feedRate_t fr_mm_s=0.0f); +#endif +#if HAS_Z_AXIS + void do_blocking_move_to_z(const_float_t rz, const_feedRate_t fr_mm_s=0.0f); +#endif +#if LINEAR_AXES >= 4 + void do_blocking_move_to_i(const_float_t ri, const_feedRate_t fr_mm_s=0.0f); + void do_blocking_move_to_xyz_i(const xyze_pos_t &raw, const_float_t i, const_feedRate_t fr_mm_s=0.0f); +#endif +#if LINEAR_AXES >= 5 + void do_blocking_move_to_j(const_float_t rj, const_feedRate_t fr_mm_s=0.0f); + void do_blocking_move_to_xyzi_j(const xyze_pos_t &raw, const_float_t j, const_feedRate_t fr_mm_s=0.0f); +#endif +#if LINEAR_AXES >= 6 + void do_blocking_move_to_k(const_float_t rk, const_feedRate_t fr_mm_s=0.0f); + void do_blocking_move_to_xyzij_k(const xyze_pos_t &raw, const_float_t k, const_feedRate_t fr_mm_s=0.0f); +#endif -void do_blocking_move_to_xy(const float &rx, const float &ry, const feedRate_t &fr_mm_s=0.0f); -void do_blocking_move_to_xy(const xy_pos_t &raw, const feedRate_t &fr_mm_s=0.0f); -FORCE_INLINE void do_blocking_move_to_xy(const xyz_pos_t &raw, const feedRate_t &fr_mm_s=0.0f) { do_blocking_move_to_xy(xy_pos_t(raw), fr_mm_s); } -FORCE_INLINE void do_blocking_move_to_xy(const xyze_pos_t &raw, const feedRate_t &fr_mm_s=0.0f) { do_blocking_move_to_xy(xy_pos_t(raw), fr_mm_s); } +#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.0f); + void do_blocking_move_to_xy(const xy_pos_t &raw, const_feedRate_t fr_mm_s=0.0f); + FORCE_INLINE void do_blocking_move_to_xy(const xyz_pos_t &raw, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy(xy_pos_t(raw), fr_mm_s); } + FORCE_INLINE void do_blocking_move_to_xy(const xyze_pos_t &raw, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy(xy_pos_t(raw), fr_mm_s); } +#endif -void do_blocking_move_to_xy_z(const xy_pos_t &raw, const float &z, const feedRate_t &fr_mm_s=0.0f); -FORCE_INLINE void do_blocking_move_to_xy_z(const xyz_pos_t &raw, const float &z, const feedRate_t &fr_mm_s=0.0f) { do_blocking_move_to_xy_z(xy_pos_t(raw), z, fr_mm_s); } -FORCE_INLINE void do_blocking_move_to_xy_z(const xyze_pos_t &raw, const float &z, const feedRate_t &fr_mm_s=0.0f) { do_blocking_move_to_xy_z(xy_pos_t(raw), z, fr_mm_s); } +#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); + FORCE_INLINE void do_blocking_move_to_xy_z(const xyz_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy_z(xy_pos_t(raw), z, fr_mm_s); } + FORCE_INLINE void do_blocking_move_to_xy_z(const xyze_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy_z(xy_pos_t(raw), z, fr_mm_s); } +#endif void remember_feedrate_and_scaling(); void remember_feedrate_scaling_off(); void restore_feedrate_and_scaling(); -void do_z_clearance(const float &zclear, const bool z_known=true, const bool raise_on_unknown=true, const bool lower_allowed=false); +#if HAS_Z_AXIS + void do_z_clearance(const_float_t zclear, const bool lower_allowed=false); +#else + inline void do_z_clearance(float, bool=false) {} +#endif + +/** + * Homing and Trusted Axes + */ +typedef IF<(LINEAR_AXES > 8), uint16_t, uint8_t>::type linear_axis_bits_t; +constexpr linear_axis_bits_t linear_bits = _BV(LINEAR_AXES) - 1; -// -// Homing -// -void homeaxis(const AxisEnum axis); void set_axis_is_at_home(const AxisEnum axis); -void set_axis_never_homed(const AxisEnum axis); -uint8_t axes_should_home(uint8_t axis_bits=0x07); -bool homing_needed_error(uint8_t axis_bits=0x07); + +#if HAS_ENDSTOPS + /** + * axis_homed + * Flags that each linear axis was homed. + * XYZ on cartesian, ABC on delta, ABZ on SCARA. + * + * axis_trusted + * Flags that the position is trusted in each linear axis. Set when homed. + * Cleared whenever a stepper powers off, potentially losing its position. + */ + extern linear_axis_bits_t axis_homed, axis_trusted; + void homeaxis(const AxisEnum axis); + void set_axis_never_homed(const AxisEnum axis); + linear_axis_bits_t axes_should_home(linear_axis_bits_t axis_bits=linear_bits); + bool homing_needed_error(linear_axis_bits_t axis_bits=linear_bits); + inline void set_axis_unhomed(const AxisEnum axis) { CBI(axis_homed, axis); } + inline void set_axis_untrusted(const AxisEnum axis) { CBI(axis_trusted, axis); } + inline void set_all_unhomed() { axis_homed = axis_trusted = 0; } + inline void set_axis_homed(const AxisEnum axis) { SBI(axis_homed, axis); } + inline void set_axis_trusted(const AxisEnum axis) { SBI(axis_trusted, axis); } + inline void set_all_homed() { axis_homed = axis_trusted = linear_bits; } +#else + constexpr linear_axis_bits_t axis_homed = linear_bits, axis_trusted = linear_bits; // Zero-endstop machines are always homed and trusted + inline void homeaxis(const AxisEnum axis) {} + inline void set_axis_never_homed(const AxisEnum) {} + inline linear_axis_bits_t axes_should_home(linear_axis_bits_t=linear_bits) { return false; } + inline bool homing_needed_error(linear_axis_bits_t=linear_bits) { 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 bool axis_was_homed(const AxisEnum axis) { return TEST(axis_homed, axis); } +inline bool axis_is_trusted(const AxisEnum axis) { return TEST(axis_trusted, axis); } +inline bool axis_should_home(const AxisEnum axis) { return (axes_should_home() & _BV(axis)) != 0; } +inline bool no_axes_homed() { return !axis_homed; } +inline bool all_axes_homed() { return linear_bits == (axis_homed & linear_bits); } +inline bool homing_needed() { return !all_axes_homed(); } +inline bool all_axes_trusted() { return linear_bits == (axis_trusted & linear_bits); } + +void home_if_needed(const bool keeplev=false); #if ENABLED(NO_MOTION_BEFORE_HOMING) #define MOTION_CONDITIONS (IsRunning() && !homing_needed_error()) @@ -290,6 +428,8 @@ bool homing_needed_error(uint8_t axis_bits=0x07); #define MOTION_CONDITIONS IsRunning() #endif +#define BABYSTEP_ALLOWED() ((ENABLED(BABYSTEP_WITHOUT_HOMING) || all_axes_trusted()) && (ENABLED(BABYSTEP_ALWAYS_AVAILABLE) || printer_busy())) + /** * Workspace offsets */ @@ -327,16 +467,31 @@ bool homing_needed_error(uint8_t axis_bits=0x07); FORCE_INLINE void toNative(xyze_pos_t&) {} #endif #define LOGICAL_X_POSITION(POS) NATIVE_TO_LOGICAL(POS, X_AXIS) -#define LOGICAL_Y_POSITION(POS) NATIVE_TO_LOGICAL(POS, Y_AXIS) -#define LOGICAL_Z_POSITION(POS) NATIVE_TO_LOGICAL(POS, Z_AXIS) #define RAW_X_POSITION(POS) LOGICAL_TO_NATIVE(POS, X_AXIS) -#define RAW_Y_POSITION(POS) LOGICAL_TO_NATIVE(POS, Y_AXIS) -#define RAW_Z_POSITION(POS) LOGICAL_TO_NATIVE(POS, Z_AXIS) +#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) +#endif +#if HAS_Z_AXIS + #define LOGICAL_Z_POSITION(POS) NATIVE_TO_LOGICAL(POS, Z_AXIS) + #define RAW_Z_POSITION(POS) LOGICAL_TO_NATIVE(POS, Z_AXIS) +#endif +#if LINEAR_AXES >= 4 + #define LOGICAL_I_POSITION(POS) NATIVE_TO_LOGICAL(POS, I_AXIS) + #define RAW_I_POSITION(POS) LOGICAL_TO_NATIVE(POS, I_AXIS) +#endif +#if LINEAR_AXES >= 5 + #define LOGICAL_J_POSITION(POS) NATIVE_TO_LOGICAL(POS, J_AXIS) + #define RAW_J_POSITION(POS) LOGICAL_TO_NATIVE(POS, J_AXIS) +#endif +#if LINEAR_AXES >= 6 + #define LOGICAL_K_POSITION(POS) NATIVE_TO_LOGICAL(POS, K_AXIS) + #define RAW_K_POSITION(POS) LOGICAL_TO_NATIVE(POS, K_AXIS) +#endif /** * position_is_reachable family of functions */ - #if IS_KINEMATIC // (DELTA or SCARA) #if HAS_SCARA_OFFSET @@ -344,10 +499,23 @@ bool homing_needed_error(uint8_t axis_bits=0x07); #endif // Return true if the given point is within the printable area - inline bool position_is_reachable(const float &rx, const float &ry, const float inset=0) { + inline bool position_is_reachable(const_float_t rx, const_float_t ry, const float inset=0) { #if ENABLED(DELTA) + return HYPOT2(rx, ry) <= sq(DELTA_PRINTABLE_RADIUS - inset + fslop); + + #elif ENABLED(AXEL_TPARA) + + const float R2 = HYPOT2(rx - TPARA_OFFSET_X, ry - TPARA_OFFSET_Y); + return ( + R2 <= sq(L1 + L2) - inset + #if MIDDLE_DEAD_ZONE_R > 0 + && R2 >= sq(float(MIDDLE_DEAD_ZONE_R)) + #endif + ); + #elif IS_SCARA + const float R2 = HYPOT2(rx - SCARA_OFFSET_X, ry - SCARA_OFFSET_Y); return ( R2 <= sq(L1 + L2) - inset @@ -355,6 +523,7 @@ bool homing_needed_error(uint8_t axis_bits=0x07); && R2 >= sq(float(MIDDLE_DEAD_ZONE_R)) #endif ); + #endif } @@ -365,15 +534,15 @@ bool homing_needed_error(uint8_t axis_bits=0x07); #else // CARTESIAN // Return true if the given position is within the machine bounds. - inline bool position_is_reachable(const float &rx, const float &ry) { - if (!WITHIN(ry, Y_MIN_POS - fslop, Y_MAX_POS + fslop)) return false; + inline bool position_is_reachable(const_float_t rx, const_float_t ry) { + if (!COORDINATE_OKAY(ry, Y_MIN_POS - fslop, Y_MAX_POS + fslop)) return false; #if ENABLED(DUAL_X_CARRIAGE) if (active_extruder) - return WITHIN(rx, X2_MIN_POS - fslop, X2_MAX_POS + fslop); + return COORDINATE_OKAY(rx, X2_MIN_POS - fslop, X2_MAX_POS + fslop); else - return WITHIN(rx, X1_MIN_POS - fslop, X1_MAX_POS + fslop); + return COORDINATE_OKAY(rx, X1_MIN_POS - fslop, X1_MAX_POS + fslop); #else - return WITHIN(rx, X_MIN_POS - fslop, X_MAX_POS + fslop); + return COORDINATE_OKAY(rx, X_MIN_POS - fslop, X_MAX_POS + fslop); #endif } inline bool position_is_reachable(const xy_pos_t &pos) { return position_is_reachable(pos.x, pos.y); } @@ -384,11 +553,7 @@ bool homing_needed_error(uint8_t axis_bits=0x07); * Duplication mode */ #if HAS_DUPLICATION_MODE - extern bool extruder_duplication_enabled, // Used in Dual X mode 2 - mirrored_duplication_mode; // Used in Dual X mode 3 - #if ENABLED(MULTI_NOZZLE_DUPLICATION) - extern uint8_t duplication_e_mask; - #endif + extern bool extruder_duplication_enabled; // Used in Dual X mode 2 #endif /** @@ -404,26 +569,33 @@ bool homing_needed_error(uint8_t axis_bits=0x07); }; extern DualXMode dual_x_carriage_mode; - extern float inactive_extruder_x_pos, // Used in mode 0 & 1 - duplicate_extruder_x_offset; // Used in mode 2 & 3 - extern xyz_pos_t raised_parked_position; // Used in mode 1 - extern bool active_extruder_parked; // Used in mode 1, 2 & 3 - extern millis_t delayed_move_time; // Used in mode 1 - extern int16_t duplicate_extruder_temp_offset; // Used in mode 2 & 3 + extern float inactive_extruder_x, // Used in mode 0 & 1 + duplicate_extruder_x_offset; // Used in mode 2 & 3 + extern xyz_pos_t raised_parked_position; // Used in mode 1 + extern bool active_extruder_parked; // Used in mode 1, 2 & 3 + extern millis_t delayed_move_time; // Used in mode 1 + extern celsius_t duplicate_extruder_temp_offset; // Used in mode 2 & 3 + extern bool idex_mirrored_mode; // Used in mode 3 - FORCE_INLINE bool dxc_is_duplicating() { return dual_x_carriage_mode >= DXC_DUPLICATION_MODE; } + FORCE_INLINE bool idex_is_duplicating() { return dual_x_carriage_mode >= DXC_DUPLICATION_MODE; } float x_home_pos(const uint8_t extruder); - FORCE_INLINE int x_home_dir(const uint8_t extruder) { return extruder ? X2_HOME_DIR : X_HOME_DIR; } + #define TOOL_X_HOME_DIR(T) ((T) ? X2_HOME_DIR : X_HOME_DIR) + + void set_duplication_enabled(const bool dupe, const int8_t tool_index=-1); + void idex_set_mirrored_mode(const bool mirr); + void idex_set_parked(const bool park=true); #else #if ENABLED(MULTI_NOZZLE_DUPLICATION) + extern uint8_t duplication_e_mask; enum DualXMode : char { DXC_DUPLICATION_MODE = 2 }; + FORCE_INLINE void set_duplication_enabled(const bool dupe) { extruder_duplication_enabled = dupe; } #endif - FORCE_INLINE int x_home_dir(const uint8_t) { return home_dir(X_AXIS); } + #define TOOL_X_HOME_DIR(T) X_HOME_DIR #endif diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 4ad7c4ccf044..7bf672a85d60 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -66,7 +66,7 @@ #include "stepper.h" #include "motion.h" #include "temperature.h" -#include "../lcd/ultralcd.h" +#include "../lcd/marlinui.h" #include "../gcode/parser.h" #include "../MarlinCore.h" @@ -136,9 +136,9 @@ planner_settings_t Planner::settings; // Initialized by settings.load( laser_state_t Planner::laser_inline; // Current state for blocks #endif -uint32_t Planner::max_acceleration_steps_per_s2[XYZE_N]; // (steps/s^2) Derived from mm_per_s2 +uint32_t Planner::max_acceleration_steps_per_s2[DISTINCT_AXES]; // (steps/s^2) Derived from mm_per_s2 -float Planner::steps_to_mm[XYZE_N]; // (mm) Millimeters per step +float Planner::steps_to_mm[DISTINCT_AXES]; // (mm) Millimeters per step #if HAS_JUNCTION_DEVIATION float Planner::junction_deviation_mm; // (mm) M205 J @@ -164,7 +164,7 @@ float Planner::steps_to_mm[XYZE_N]; // (mm) Millimeters per step xyze_bool_t Planner::last_page_dir{0}; #endif -#if EXTRUDERS +#if HAS_EXTRUDERS int16_t Planner::flow_percentage[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(100); // Extrusion factor for each extruder float Planner::e_factor[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(1.0f); // The flow percentage and volumetric multiplier combine to scale E movement #endif @@ -197,9 +197,9 @@ float Planner::steps_to_mm[XYZE_N]; // (mm) Millimeters per step skew_factor_t Planner::skew_factor; // Initialized by settings.load() #if ENABLED(AUTOTEMP) - float Planner::autotemp_max = 250, - Planner::autotemp_min = 210, - Planner::autotemp_factor = 0.1f; + celsius_t Planner::autotemp_max = 250, + Planner::autotemp_min = 210; + float Planner::autotemp_factor = 0.1f; bool Planner::autotemp_enabled = false; #endif @@ -207,13 +207,13 @@ skew_factor_t Planner::skew_factor; // Initialized by settings.load() xyze_long_t Planner::position{0}; -uint32_t Planner::cutoff_long; +uint32_t Planner::acceleration_long_cutoff; xyze_float_t Planner::previous_speed; float Planner::previous_nominal_speed_sqr; #if ENABLED(DISABLE_INACTIVE_EXTRUDER) - uint8_t Planner::g_uc_extruder_last_move[EXTRUDERS] = { 0 }; + last_move_t Planner::g_uc_extruder_last_move[E_STEPPERS] = { 0 }; #endif #ifdef XY_FREQUENCY_LIMIT @@ -381,7 +381,7 @@ void Planner::init() { r9 = (d >> 8) & 0xFF, r10 = (d >> 16) & 0xFF, r2,r3,r4,r5,r6,r7,r11,r12,r13,r14,r15,r16,r17,r18; - const uint8_t* ptab = inv_tab; + const uint8_t *ptab = inv_tab; __asm__ __volatile__( // %8:%7:%6 = interval @@ -418,11 +418,11 @@ void Planner::init() { L("2") A("cpi %16,0x10") // (nr & 0xF00000) == 0 ? A("brcc 3f") // No, skip this - A("swap %15") // Swap nibbles - A("swap %16") // Swap nibbles. Low nibble is 0 + A("swap %15") // Swap nybbles + A("swap %16") // Swap nybbles. Low nybble is 0 A("mov %14, %15") - A("andi %14,0x0F") // Isolate low nibble - A("andi %15,0xF0") // Keep proper nibble in %15 + A("andi %14,0x0F") // Isolate low nybble + A("andi %15,0xF0") // Keep proper nybble in %15 A("or %16, %14") // %16:%15 <<= 4 A("subi %3,-4") // idx += 4 @@ -473,10 +473,10 @@ void Planner::init() { L("9") A("sbrs %3,2") // shift by 4bits position? A("rjmp 16f") // No - A("swap %15") // Swap nibbles. lo nibble of %15 will always be 0 - A("swap %14") // Swap nibbles + A("swap %15") // Swap nybbles. lo nybble of %15 will always be 0 + A("swap %14") // Swap nybbles A("mov %12,%14") - A("andi %12,0x0F") // isolate low nibble + A("andi %12,0x0F") // isolate low nybble A("andi %14,0xF0") // and clear it A("or %15,%12") // %15:%16 <<= 4 L("16") @@ -504,11 +504,11 @@ void Planner::init() { L("11") A("sbrs %3,2") // shift by 4 bit position ? A("rjmp 12f") // No, skip it - A("swap %15") // Swap nibbles - A("andi %14, 0xF0") // Lose the lowest nibble - A("swap %14") // Swap nibbles. Upper nibble is 0 - A("or %14,%15") // Pass nibble from upper byte - A("andi %15, 0x0F") // And get rid of that nibble + A("swap %15") // Swap nybbles + A("andi %14, 0xF0") // Lose the lowest nybble + A("swap %14") // Swap nybbles. Upper nybble is 0 + A("or %14,%15") // Pass nybble from upper byte + A("andi %15, 0x0F") // And get rid of that nybble L("12") A("sbrs %3,3") // shift by 8 bit position ? A("rjmp 6f") // No, skip it @@ -775,7 +775,7 @@ block_t* Planner::get_current_block() { * is not and will not use the block while we modify it, so it is safe to * alter its values. */ -void Planner::calculate_trapezoid_for_block(block_t* const block, const float &entry_factor, const float &exit_factor) { +void Planner::calculate_trapezoid_for_block(block_t * const block, const_float_t entry_factor, const_float_t exit_factor) { uint32_t initial_rate = CEIL(block->nominal_rate * entry_factor), final_rate = CEIL(block->nominal_rate * exit_factor); // (steps per second) @@ -942,7 +942,7 @@ void Planner::calculate_trapezoid_for_block(block_t* const block, const float &e */ // The kernel called by recalculate() when scanning the plan from last to first entry. -void Planner::reverse_pass_kernel(block_t* const current, const block_t * const next) { +void Planner::reverse_pass_kernel(block_t * const current, const block_t * const next) { if (current) { // If entry speed is already at the maximum entry speed, and there was no change of speed // in the next block, there is no need to recheck. Block is cruising and there is no need to @@ -1015,8 +1015,8 @@ void Planner::reverse_pass() { // Perform the reverse pass block_t *current = &block_buffer[block_index]; - // Only consider non sync and page blocks - if (!TEST(current->flag, BLOCK_BIT_SYNC_POSITION) && !IS_PAGE(current)) { + // Only consider non sync-and-page blocks + if (!(current->flag & BLOCK_MASK_SYNC) && !IS_PAGE(current)) { reverse_pass_kernel(current, next); next = current; } @@ -1039,7 +1039,7 @@ void Planner::reverse_pass() { } // The kernel called by recalculate() when scanning the plan from first to last entry. -void Planner::forward_pass_kernel(const block_t* const previous, block_t* const current, const uint8_t block_index) { +void Planner::forward_pass_kernel(const block_t * const previous, block_t * const current, const uint8_t block_index) { if (previous) { // If the previous block is an acceleration block, too short to complete the full speed // change, adjust the entry speed accordingly. Entry speeds have already been reset, @@ -1111,7 +1111,7 @@ void Planner::forward_pass() { block = &block_buffer[block_index]; // Skip SYNC and page blocks - if (!TEST(block->flag, BLOCK_BIT_SYNC_POSITION) && !IS_PAGE(block)) { + if (!(block->flag & BLOCK_MASK_SYNC) && !IS_PAGE(block)) { // If there's no previous block or the previous block is not // BUSY (thus, modifiable) run the forward_pass_kernel. Otherwise, // the previous block became BUSY, so assume the current block's @@ -1147,7 +1147,7 @@ void Planner::recalculate_trapezoids() { block_t *prev = &block_buffer[prev_index]; // If not dealing with a sync block, we are done. The last block is not a SYNC block - if (!TEST(prev->flag, BLOCK_BIT_SYNC_POSITION)) break; + if (!(prev->flag & BLOCK_MASK_SYNC)) break; // Examine the previous block. This and all following are SYNC blocks head_block_index = prev_index; @@ -1161,7 +1161,7 @@ void Planner::recalculate_trapezoids() { next = &block_buffer[block_index]; // Skip sync and page blocks - if (!TEST(next->flag, BLOCK_BIT_SYNC_POSITION) && !IS_PAGE(next)) { + if (!(next->flag & BLOCK_MASK_SYNC) && !IS_PAGE(next)) { next_entry_speed = SQRT(next->entry_speed_sqr); if (block) { @@ -1248,42 +1248,73 @@ void Planner::recalculate() { recalculate_trapezoids(); } -#if ENABLED(AUTOTEMP) +#if HAS_FAN && DISABLED(LASER_SYNCHRONOUS_M106_M107) + #define HAS_TAIL_FAN_SPEED 1 +#endif - void Planner::getHighESpeed() { - static float oldt = 0; +/** + * Apply fan speeds + */ +#if HAS_FAN - if (!autotemp_enabled) return; - if (thermalManager.degTargetHotend(0) + 2 < autotemp_min) return; // probably temperature set to zero. + void Planner::sync_fan_speeds(uint8_t (&fan_speed)[FAN_COUNT]) { - float high = 0.0; - for (uint8_t b = block_buffer_tail; b != block_buffer_head; b = next_block_index(b)) { - block_t* block = &block_buffer[b]; - if (block->steps.x || block->steps.y || block->steps.z) { - const float se = (float)block->steps.e / block->step_event_count * SQRT(block->nominal_speed_sqr); // mm/sec; - NOLESS(high, se); + #if FAN_MIN_PWM != 0 || FAN_MAX_PWM != 255 + #define CALC_FAN_SPEED(f) (fan_speed[f] ? map(fan_speed[f], 1, 255, FAN_MIN_PWM, FAN_MAX_PWM) : FAN_OFF_PWM) + #else + #define CALC_FAN_SPEED(f) (fan_speed[f] ?: FAN_OFF_PWM) + #endif + + #if ENABLED(FAN_SOFT_PWM) + #define _FAN_SET(F) thermalManager.soft_pwm_amount_fan[F] = CALC_FAN_SPEED(F); + #elif ENABLED(FAST_PWM_FAN) + #define _FAN_SET(F) set_pwm_duty(FAN##F##_PIN, CALC_FAN_SPEED(F)); + #else + #define _FAN_SET(F) analogWrite(pin_t(FAN##F##_PIN), CALC_FAN_SPEED(F)); + #endif + #define FAN_SET(F) do{ kickstart_fan(fan_speed, ms, F); _FAN_SET(F); }while(0) + + const millis_t ms = millis(); + TERN_(HAS_FAN0, FAN_SET(0)); + TERN_(HAS_FAN1, FAN_SET(1)); + TERN_(HAS_FAN2, FAN_SET(2)); + TERN_(HAS_FAN3, FAN_SET(3)); + TERN_(HAS_FAN4, FAN_SET(4)); + TERN_(HAS_FAN5, FAN_SET(5)); + TERN_(HAS_FAN6, FAN_SET(6)); + TERN_(HAS_FAN7, FAN_SET(7)); + } + + #if FAN_KICKSTART_TIME + + void Planner::kickstart_fan(uint8_t (&fan_speed)[FAN_COUNT], const millis_t &ms, const uint8_t f) { + static millis_t fan_kick_end[FAN_COUNT] = { 0 }; + if (fan_speed[f]) { + if (fan_kick_end[f] == 0) { + fan_kick_end[f] = ms + FAN_KICKSTART_TIME; + fan_speed[f] = 255; + } + else if (PENDING(ms, fan_kick_end[f])) + fan_speed[f] = 255; } + else + fan_kick_end[f] = 0; } - float t = autotemp_min + high * autotemp_factor; - LIMIT(t, autotemp_min, autotemp_max); - if (t < oldt) t = t * (1 - float(AUTOTEMP_OLDWEIGHT)) + oldt * float(AUTOTEMP_OLDWEIGHT); - oldt = t; - thermalManager.setTargetHotend(t, 0); - } + #endif -#endif // AUTOTEMP +#endif // HAS_FAN /** * Maintain fans, paste extruder pressure, */ void Planner::check_axes_activity() { - #if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z, DISABLE_E) + #if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z , DISABLE_I , DISABLE_J , DISABLE_K, DISABLE_E) xyze_bool_t axis_active = { false }; #endif - #if HAS_FAN + #if HAS_TAIL_FAN_SPEED uint8_t tail_fan_speed[FAN_COUNT]; #endif @@ -1298,13 +1329,12 @@ void Planner::check_axes_activity() { if (has_blocks_queued()) { - #if HAS_FAN || ENABLED(BARICUDA) + #if EITHER(HAS_TAIL_FAN_SPEED, BARICUDA) block_t *block = &block_buffer[block_buffer_tail]; #endif - #if HAS_FAN - FANS_LOOP(i) - tail_fan_speed[i] = thermalManager.scaledFanSpeed(i, block->fan_speed[i]); + #if HAS_TAIL_FAN_SPEED + FANS_LOOP(i) tail_fan_speed[i] = thermalManager.scaledFanSpeed(i, block->fan_speed[i]); #endif #if ENABLED(BARICUDA) @@ -1312,13 +1342,18 @@ 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_E) + #if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z, DISABLE_I, DISABLE_J, DISABLE_K, DISABLE_E) for (uint8_t b = block_buffer_tail; b != block_buffer_head; b = next_block_index(b)) { block_t *block = &block_buffer[b]; - if (ENABLED(DISABLE_X) && block->steps.x) axis_active.x = true; - if (ENABLED(DISABLE_Y) && block->steps.y) axis_active.y = true; - if (ENABLED(DISABLE_Z) && block->steps.z) axis_active.z = true; - if (ENABLED(DISABLE_E) && block->steps.e) axis_active.e = true; + LOGICAL_AXIS_CODE( + if (TERN0(DISABLE_E, block->steps.e)) axis_active.e = true, + if (TERN0(DISABLE_X, block->steps.x)) axis_active.x = true, + if (TERN0(DISABLE_Y, block->steps.y)) axis_active.y = true, + if (TERN0(DISABLE_Z, block->steps.z)) axis_active.z = true, + if (TERN0(DISABLE_I, block->steps.i)) axis_active.i = true, + if (TERN0(DISABLE_J, block->steps.j)) axis_active.j = true, + if (TERN0(DISABLE_K, block->steps.k)) axis_active.k = true + ); } #endif } @@ -1326,9 +1361,8 @@ void Planner::check_axes_activity() { TERN_(HAS_CUTTER, cutter.refresh()); - #if HAS_FAN - FANS_LOOP(i) - tail_fan_speed[i] = thermalManager.scaledFanSpeed(i); + #if HAS_TAIL_FAN_SPEED + FANS_LOOP(i) tail_fan_speed[i] = thermalManager.scaledFanSpeed(i); #endif #if ENABLED(BARICUDA) @@ -1340,57 +1374,25 @@ void Planner::check_axes_activity() { // // Disable inactive axes // - if (TERN0(DISABLE_X, !axis_active.x)) DISABLE_AXIS_X(); - if (TERN0(DISABLE_Y, !axis_active.y)) DISABLE_AXIS_Y(); - if (TERN0(DISABLE_Z, !axis_active.z)) DISABLE_AXIS_Z(); - if (TERN0(DISABLE_E, !axis_active.e)) disable_e_steppers(); + LOGICAL_AXIS_CODE( + if (TERN0(DISABLE_E, !axis_active.e)) disable_e_steppers(), + if (TERN0(DISABLE_X, !axis_active.x)) DISABLE_AXIS_X(), + if (TERN0(DISABLE_Y, !axis_active.y)) DISABLE_AXIS_Y(), + if (TERN0(DISABLE_Z, !axis_active.z)) DISABLE_AXIS_Z(), + if (TERN0(DISABLE_I, !axis_active.i)) DISABLE_AXIS_I(), + if (TERN0(DISABLE_J, !axis_active.j)) DISABLE_AXIS_J(), + if (TERN0(DISABLE_K, !axis_active.k)) DISABLE_AXIS_K() + ); // // Update Fan speeds + // Only if synchronous M106/M107 is disabled // - #if HAS_FAN - - #if FAN_KICKSTART_TIME > 0 - static millis_t fan_kick_end[FAN_COUNT] = { 0 }; - #define KICKSTART_FAN(f) \ - if (tail_fan_speed[f]) { \ - millis_t ms = millis(); \ - if (fan_kick_end[f] == 0) { \ - fan_kick_end[f] = ms + FAN_KICKSTART_TIME; \ - tail_fan_speed[f] = 255; \ - } else if (PENDING(ms, fan_kick_end[f])) \ - tail_fan_speed[f] = 255; \ - } else fan_kick_end[f] = 0 - #else - #define KICKSTART_FAN(f) NOOP - #endif - - #if FAN_MIN_PWM != 0 || FAN_MAX_PWM != 255 - #define CALC_FAN_SPEED(f) (tail_fan_speed[f] ? map(tail_fan_speed[f], 1, 255, FAN_MIN_PWM, FAN_MAX_PWM) : FAN_OFF_PWM) - #else - #define CALC_FAN_SPEED(f) (tail_fan_speed[f] ?: FAN_OFF_PWM) - #endif - - #if ENABLED(FAN_SOFT_PWM) - #define _FAN_SET(F) thermalManager.soft_pwm_amount_fan[F] = CALC_FAN_SPEED(F); - #elif ENABLED(FAST_PWM_FAN) - #define _FAN_SET(F) set_pwm_duty(FAN##F##_PIN, CALC_FAN_SPEED(F)); - #else - #define _FAN_SET(F) analogWrite(pin_t(FAN##F##_PIN), CALC_FAN_SPEED(F)); - #endif - #define FAN_SET(F) do{ KICKSTART_FAN(F); _FAN_SET(F); }while(0) - - TERN_(HAS_FAN0, FAN_SET(0)); - TERN_(HAS_FAN1, FAN_SET(1)); - TERN_(HAS_FAN2, FAN_SET(2)); - TERN_(HAS_FAN3, FAN_SET(3)); - TERN_(HAS_FAN4, FAN_SET(4)); - TERN_(HAS_FAN5, FAN_SET(5)); - TERN_(HAS_FAN6, FAN_SET(6)); - TERN_(HAS_FAN7, FAN_SET(7)); - #endif // HAS_FAN + #if HAS_TAIL_FAN_SPEED + sync_fan_speeds(tail_fan_speed); + #endif - TERN_(AUTOTEMP, getHighESpeed()); + TERN_(AUTOTEMP, autotemp_task()); #if ENABLED(BARICUDA) TERN_(HAS_HEATER_1, analogWrite(pin_t(HEATER_1_PIN), tail_valve_pressure)); @@ -1398,6 +1400,72 @@ void Planner::check_axes_activity() { #endif } +#if ENABLED(AUTOTEMP) + + #if ENABLED(AUTOTEMP_PROPORTIONAL) + void Planner::_autotemp_update_from_hotend() { + const celsius_t target = thermalManager.degTargetHotend(active_extruder); + autotemp_min = target + AUTOTEMP_MIN_P; + autotemp_max = target + AUTOTEMP_MAX_P; + } + #endif + + /** + * Called after changing tools to: + * - Reset or re-apply the default proportional autotemp factor. + * - Enable autotemp if the factor is non-zero. + */ + void Planner::autotemp_update() { + _autotemp_update_from_hotend(); + autotemp_factor = TERN(AUTOTEMP_PROPORTIONAL, AUTOTEMP_FACTOR_P, 0); + autotemp_enabled = autotemp_factor != 0; + } + + /** + * Called by the M104/M109 commands after setting Hotend Temperature + * + */ + void Planner::autotemp_M104_M109() { + _autotemp_update_from_hotend(); + + if (parser.seenval('S')) autotemp_min = parser.value_celsius(); + if (parser.seenval('B')) autotemp_max = parser.value_celsius(); + + // When AUTOTEMP_PROPORTIONAL is enabled, F0 disables autotemp. + // Normally, leaving off F also disables autotemp. + autotemp_factor = parser.seen('F') ? parser.value_float() : TERN(AUTOTEMP_PROPORTIONAL, AUTOTEMP_FACTOR_P, 0); + autotemp_enabled = autotemp_factor != 0; + } + + /** + * Called every so often to adjust the hotend target temperature + * based on the extrusion speed, which is calculated from the blocks + * currently in the planner. + */ + void Planner::autotemp_task() { + static float oldt = 0; + + if (!autotemp_enabled) return; + if (thermalManager.degTargetHotend(active_extruder) < autotemp_min - 2) return; // Below the min? + + float high = 0.0; + for (uint8_t b = block_buffer_tail; b != block_buffer_head; b = next_block_index(b)) { + block_t *block = &block_buffer[b]; + if (LINEAR_AXIS_GANG(block->steps.x, || block->steps.y, || block->steps.z, || block->steps.i, || block->steps.j, || block->steps.k)) { + const float se = (float)block->steps.e / block->step_event_count * SQRT(block->nominal_speed_sqr); // mm/sec; + NOLESS(high, se); + } + } + + float t = autotemp_min + high * autotemp_factor; + LIMIT(t, autotemp_min, autotemp_max); + if (t < oldt) t *= (1.0f - (AUTOTEMP_OLDWEIGHT)) + oldt * (AUTOTEMP_OLDWEIGHT); + oldt = t; + thermalManager.setTargetHotend(t, active_extruder); + } + +#endif + #if DISABLED(NO_VOLUMETRICS) /** @@ -1405,7 +1473,7 @@ void Planner::check_axes_activity() { * This is the reciprocal of the circular cross-section area. * Return 1.0 with volumetric off or a diameter of 0.0. */ - inline float calculate_volumetric_multiplier(const float &diameter) { + inline float calculate_volumetric_multiplier(const_float_t diameter) { return (parser.volumetric_enabled && diameter) ? 1.0f / CIRCLE_AREA(diameter * 0.5f) : 1; } @@ -1459,6 +1527,34 @@ void Planner::check_axes_activity() { } #endif +#if ENABLED(IMPROVE_HOMING_RELIABILITY) + + void Planner::enable_stall_prevention(const bool onoff) { + static motion_state_t saved_motion_state; + if (onoff) { + saved_motion_state.acceleration.x = settings.max_acceleration_mm_per_s2[X_AXIS]; + saved_motion_state.acceleration.y = settings.max_acceleration_mm_per_s2[Y_AXIS]; + settings.max_acceleration_mm_per_s2[X_AXIS] = settings.max_acceleration_mm_per_s2[Y_AXIS] = 100; + #if ENABLED(DELTA) + saved_motion_state.acceleration.z = settings.max_acceleration_mm_per_s2[Z_AXIS]; + settings.max_acceleration_mm_per_s2[Z_AXIS] = 100; + #endif + #if HAS_CLASSIC_JERK + saved_motion_state.jerk_state = max_jerk; + max_jerk.set(0, 0 OPTARG(DELTA, 0)); + #endif + } + else { + settings.max_acceleration_mm_per_s2[X_AXIS] = saved_motion_state.acceleration.x; + settings.max_acceleration_mm_per_s2[Y_AXIS] = saved_motion_state.acceleration.y; + TERN_(DELTA, settings.max_acceleration_mm_per_s2[Z_AXIS] = saved_motion_state.acceleration.z); + TERN_(HAS_CLASSIC_JERK, max_jerk = saved_motion_state.jerk_state); + } + reset_acceleration_rates(); + } + +#endif + #if HAS_LEVELING constexpr xy_pos_t level_fulcrum = { @@ -1476,7 +1572,7 @@ void Planner::check_axes_activity() { #if ABL_PLANAR xy_pos_t d = raw - level_fulcrum; - apply_rotation_xyz(bed_level_matrix, d.x, d.y, raw.z); + bed_level_matrix.apply_rotation_xyz(d.x, d.y, raw.z); raw = d + level_fulcrum; #elif HAS_MESH @@ -1513,7 +1609,7 @@ void Planner::check_axes_activity() { matrix_3x3 inverse = matrix_3x3::transpose(bed_level_matrix); xy_pos_t d = raw - level_fulcrum; - apply_rotation_xyz(inverse, d.x, d.y, raw.z); + inverse.apply_rotation_xyz(d.x, d.y, raw.z); raw = d + level_fulcrum; #elif HAS_MESH @@ -1592,6 +1688,24 @@ void Planner::quick_stop() { stepper.quick_stop(); } +#if ENABLED(REALTIME_REPORTING_COMMANDS) + + void Planner::quick_pause() { + // Suspend until quick_resume is called + // Don't empty buffers or queues + const bool did_suspend = stepper.suspend(); + if (did_suspend) + TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_HOLD)); + } + + // Resume if suspended + void Planner::quick_resume() { + TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(grbl_state_for_marlin_state())); + stepper.wake_up(); + } + +#endif + void Planner::endstop_triggered(const AxisEnum axis) { // Record stepper position and discard the current block stepper.endstop_triggered(axis); @@ -1681,22 +1795,20 @@ void Planner::synchronize() { * Returns true if movement was properly queued, false otherwise (if cleaning) */ bool Planner::_buffer_steps(const xyze_long_t &target - #if HAS_POSITION_FLOAT - , const xyze_pos_t &target_float - #endif - #if HAS_DIST_MM_ARG - , const xyze_float_t &cart_dist_mm - #endif - , feedRate_t fr_mm_s, const uint8_t extruder, const float &millimeters + OPTARG(HAS_POSITION_FLOAT, const xyze_pos_t &target_float) + OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm) + , feedRate_t fr_mm_s, const uint8_t extruder, const_float_t millimeters ) { - // If we are cleaning, do not accept queuing of movements - if (cleaning_buffer_counter) return false; - // Wait for the next available block uint8_t next_buffer_head; block_t * const block = get_next_free_block(next_buffer_head); + // If we are cleaning, do not accept queuing of movements + // This must be after get_next_free_block() because it calls idle() + // where cleaning_buffer_counter can be changed + if (cleaning_buffer_counter) return false; + // Fill the block with the specified movement if (!_populate_block(block, false, target #if HAS_POSITION_FLOAT @@ -1745,34 +1857,39 @@ bool Planner::_buffer_steps(const xyze_long_t &target */ bool Planner::_populate_block(block_t * const block, bool split_move, const abce_long_t &target - #if HAS_POSITION_FLOAT - , const xyze_pos_t &target_float - #endif - #if HAS_DIST_MM_ARG - , const xyze_float_t &cart_dist_mm - #endif - , feedRate_t fr_mm_s, const uint8_t extruder, const float &millimeters/*=0.0*/ + OPTARG(HAS_POSITION_FLOAT, const xyze_pos_t &target_float) + OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm) + , feedRate_t fr_mm_s, const uint8_t extruder, const_float_t millimeters/*=0.0*/ ) { - - const int32_t da = target.a - position.a, - db = target.b - position.b, - dc = target.c - position.c; - - #if EXTRUDERS - int32_t de = target.e - position.e; - #else - constexpr int32_t de = 0; - #endif + int32_t LOGICAL_AXIS_LIST( + de = target.e - position.e, + da = target.a - position.a, + db = target.b - position.b, + dc = target.c - position.c, + di = target.i - position.i, + dj = target.j - position.j, + dk = target.k - position.k + ); /* <-- add a slash to enable - SERIAL_ECHOLNPAIR(" _populate_block FR:", fr_mm_s, - " A:", target.a, " (", da, " steps)" - " B:", target.b, " (", db, " steps)" - " C:", target.c, " (", dc, " steps)" - #if EXTRUDERS - " E:", target.e, " (", de, " steps)" - #endif - ); + SERIAL_ECHOLNPAIR( + " _populate_block FR:", fr_mm_s, + " A:", target.a, " (", da, " steps)" + " B:", target.b, " (", db, " steps)" + " C:", target.c, " (", dc, " steps)" + #if LINEAR_AXES >= 4 + " " AXIS4_STR ":", target.i, " (", di, " steps)" + #endif + #if LINEAR_AXES >= 5 + " " AXIS5_STR ":", target.j, " (", dj, " steps)" + #endif + #if LINEAR_AXES >= 6 + " " AXIS6_STR ":", target.k, " (", dk, " steps)" + #endif + #if HAS_EXTRUDERS + " E:", target.e, " (", de, " steps)" + #endif + ); //*/ #if EITHER(PREVENT_COLD_EXTRUSION, PREVENT_LENGTHY_EXTRUDE) @@ -1812,37 +1929,57 @@ bool Planner::_populate_block(block_t * const block, bool split_move, // Compute direction bit-mask for this block uint8_t dm = 0; #if CORE_IS_XY - if (da < 0) SBI(dm, X_HEAD); // Save the real Extruder (head) direction in X Axis + if (da < 0) SBI(dm, X_HEAD); // Save the toolhead's true direction in X if (db < 0) SBI(dm, Y_HEAD); // ...and Y if (dc < 0) SBI(dm, Z_AXIS); if (da + db < 0) SBI(dm, A_AXIS); // Motor A direction if (CORESIGN(da - db) < 0) SBI(dm, B_AXIS); // Motor B direction #elif CORE_IS_XZ - if (da < 0) SBI(dm, X_HEAD); // Save the real Extruder (head) direction in X Axis + 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 real Extruder (head) direction in Y Axis + if (db < 0) SBI(dm, Y_HEAD); // Save the toolhead's true direction in Y if (dc < 0) SBI(dm, Z_HEAD); // ...and Z if (db + dc < 0) SBI(dm, B_AXIS); // Motor B direction if (CORESIGN(db - dc) < 0) SBI(dm, C_AXIS); // Motor C direction #elif ENABLED(MARKFORGED_XY) - if (da < 0) SBI(dm, X_HEAD); // Save the real Extruder (head) direction in X Axis + if (da < 0) SBI(dm, X_HEAD); // Save the toolhead's true direction in X if (db < 0) SBI(dm, Y_HEAD); // ...and Y if (dc < 0) SBI(dm, Z_AXIS); if (da + db < 0) SBI(dm, A_AXIS); // Motor A direction if (db < 0) SBI(dm, B_AXIS); // Motor B direction #else - if (da < 0) SBI(dm, X_AXIS); - if (db < 0) SBI(dm, Y_AXIS); - if (dc < 0) SBI(dm, Z_AXIS); + LINEAR_AXIS_CODE( + if (da < 0) SBI(dm, X_AXIS), + if (db < 0) SBI(dm, Y_AXIS), + if (dc < 0) SBI(dm, Z_AXIS), + if (di < 0) SBI(dm, I_AXIS), + if (dj < 0) SBI(dm, J_AXIS), + if (dk < 0) SBI(dm, K_AXIS) + ); + #endif + + #if IS_CORE + #if LINEAR_AXES >= 4 + if (di < 0) SBI(dm, I_AXIS); + #endif + #if LINEAR_AXES >= 5 + if (dj < 0) SBI(dm, J_AXIS); + #endif + #if LINEAR_AXES >= 6 + if (dk < 0) SBI(dm, K_AXIS); + #endif #endif - if (de < 0) SBI(dm, E_AXIS); - #if EXTRUDERS + #if HAS_EXTRUDERS + if (de < 0) SBI(dm, E_AXIS); + #endif + + #if HAS_EXTRUDERS const float esteps_float = de * e_factor[extruder]; const uint32_t esteps = ABS(esteps_float) + 0.5f; #else @@ -1876,7 +2013,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, block->steps.set(ABS(da), ABS(db), ABS(dc)); #else // default non-h-bot planning - block->steps.set(ABS(da), ABS(db), ABS(dc)); + block->steps.set(LINEAR_AXIS_LIST(ABS(da), ABS(db), ABS(dc), ABS(di), ABS(dj), ABS(dk))); #endif /** @@ -1889,7 +2026,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, */ struct DistanceMM : abce_float_t { #if EITHER(IS_CORE, MARKFORGED_XY) - xyz_pos_t head; + struct { float x, y, z; } head; #endif } steps_dist_mm; #if IS_CORE @@ -1912,6 +2049,15 @@ bool Planner::_populate_block(block_t * const block, bool split_move, steps_dist_mm.b = (db + dc) * steps_to_mm[B_AXIS]; steps_dist_mm.c = CORESIGN(db - dc) * steps_to_mm[C_AXIS]; #endif + #if LINEAR_AXES >= 4 + steps_dist_mm.i = di * steps_to_mm[I_AXIS]; + #endif + #if LINEAR_AXES >= 5 + steps_dist_mm.j = dj * steps_to_mm[J_AXIS]; + #endif + #if LINEAR_AXES >= 6 + steps_dist_mm.k = dk * steps_to_mm[K_AXIS]; + #endif #elif ENABLED(MARKFORGED_XY) steps_dist_mm.head.x = da * steps_to_mm[A_AXIS]; steps_dist_mm.head.y = db * steps_to_mm[B_AXIS]; @@ -1919,41 +2065,68 @@ bool Planner::_populate_block(block_t * const block, bool split_move, steps_dist_mm.a = (da - db) * steps_to_mm[A_AXIS]; steps_dist_mm.b = db * steps_to_mm[B_AXIS]; #else - steps_dist_mm.a = da * steps_to_mm[A_AXIS]; - steps_dist_mm.b = db * steps_to_mm[B_AXIS]; - steps_dist_mm.c = dc * steps_to_mm[C_AXIS]; + LINEAR_AXIS_CODE( + steps_dist_mm.a = da * steps_to_mm[A_AXIS], + steps_dist_mm.b = db * steps_to_mm[B_AXIS], + steps_dist_mm.c = dc * steps_to_mm[C_AXIS], + steps_dist_mm.i = di * steps_to_mm[I_AXIS], + steps_dist_mm.j = dj * steps_to_mm[J_AXIS], + steps_dist_mm.k = dk * steps_to_mm[K_AXIS] + ); #endif - #if EXTRUDERS + #if HAS_EXTRUDERS steps_dist_mm.e = esteps_float * steps_to_mm[E_AXIS_N(extruder)]; - #else - steps_dist_mm.e = 0.0f; #endif TERN_(LCD_SHOW_E_TOTAL, e_move_accumulator += steps_dist_mm.e); - if (block->steps.a < MIN_STEPS_PER_SEGMENT && block->steps.b < MIN_STEPS_PER_SEGMENT && block->steps.c < MIN_STEPS_PER_SEGMENT) { - block->millimeters = (0 - #if EXTRUDERS - + ABS(steps_dist_mm.e) - #endif - ); + if (true LINEAR_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->millimeters = TERN0(HAS_EXTRUDERS, ABS(steps_dist_mm.e)); } else { if (millimeters) block->millimeters = millimeters; - else + else { block->millimeters = SQRT( #if EITHER(CORE_IS_XY, MARKFORGED_XY) - sq(steps_dist_mm.head.x) + sq(steps_dist_mm.head.y) + sq(steps_dist_mm.z) + LINEAR_AXIS_GANG( + sq(steps_dist_mm.head.x), + sq(steps_dist_mm.head.y), + sq(steps_dist_mm.z), + + sq(steps_dist_mm.i), + sq(steps_dist_mm.j), + sq(steps_dist_mm.k) + ) #elif CORE_IS_XZ - sq(steps_dist_mm.head.x) + sq(steps_dist_mm.y) + sq(steps_dist_mm.head.z) + LINEAR_AXIS_GANG( + sq(steps_dist_mm.head.x), + sq(steps_dist_mm.y), + sq(steps_dist_mm.head.z), + + sq(steps_dist_mm.i), + sq(steps_dist_mm.j), + sq(steps_dist_mm.k) + ) #elif CORE_IS_YZ - sq(steps_dist_mm.x) + sq(steps_dist_mm.head.y) + sq(steps_dist_mm.head.z) + LINEAR_AXIS_GANG( + sq(steps_dist_mm.x) + sq(steps_dist_mm.head.y) + sq(steps_dist_mm.head.z) + + sq(steps_dist_mm.i), + sq(steps_dist_mm.j), + sq(steps_dist_mm.k) + ) + #elif ENABLED(FOAMCUTTER_XYUV) + // Return the largest distance move from either X/Y or I/J plane + #if LINEAR_AXES >= 5 + _MAX(sq(steps_dist_mm.x) + sq(steps_dist_mm.y), sq(steps_dist_mm.i) + sq(steps_dist_mm.j)) + #else + sq(steps_dist_mm.x) + sq(steps_dist_mm.y) + #endif #else - sq(steps_dist_mm.x) + sq(steps_dist_mm.y) + sq(steps_dist_mm.z) + LINEAR_AXIS_GANG( + sq(steps_dist_mm.x), + sq(steps_dist_mm.y), + sq(steps_dist_mm.z), + + sq(steps_dist_mm.i), + sq(steps_dist_mm.j), + sq(steps_dist_mm.k) + ) #endif ); + } /** * At this point at least one of the axes has more steps than @@ -1967,18 +2140,16 @@ bool Planner::_populate_block(block_t * const block, bool split_move, TERN_(BACKLASH_COMPENSATION, backlash.add_correction_steps(da, db, dc, dm, block)); } - #if EXTRUDERS - block->steps.e = esteps; - #endif + TERN_(HAS_EXTRUDERS, block->steps.e = esteps); - block->step_event_count = _MAX(block->steps.a, block->steps.b, block->steps.c, 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 + )); // Bail if this is a zero-length block if (block->step_event_count < MIN_STEPS_PER_SEGMENT) return false; - #if ENABLED(MIXING_EXTRUDER) - MIXER_POPULATE_BLOCK(); - #endif + TERN_(MIXING_EXTRUDER, mixer.populate_block(block->b_color)) TERN_(HAS_CUTTER, block->cutter_power = cutter.power); @@ -1996,8 +2167,14 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #endif #if ENABLED(AUTO_POWER_CONTROL) - if (block->steps.x || block->steps.y || block->steps.z) - powerManager.power_on(); + if (LINEAR_AXIS_GANG( + block->steps.x, + || block->steps.y, + || block->steps.z, + || block->steps.i, + || block->steps.j, + || block->steps.k + )) powerManager.power_on(); #endif // Enable active axes @@ -2022,37 +2199,40 @@ bool Planner::_populate_block(block_t * const block, bool split_move, } if (block->steps.x) ENABLE_AXIS_X(); #else - if (block->steps.x) ENABLE_AXIS_X(); - if (block->steps.y) ENABLE_AXIS_Y(); - #if DISABLED(Z_LATE_ENABLE) - if (block->steps.z) ENABLE_AXIS_Z(); - #endif + LINEAR_AXIS_CODE( + if (block->steps.x) ENABLE_AXIS_X(), + if (block->steps.y) ENABLE_AXIS_Y(), + if (TERN(Z_LATE_ENABLE, 0, block->steps.z)) ENABLE_AXIS_Z(), + if (block->steps.i) ENABLE_AXIS_I(), + if (block->steps.j) ENABLE_AXIS_J(), + if (block->steps.k) ENABLE_AXIS_K() + ); #endif // Enable extruder(s) - #if EXTRUDERS + #if HAS_EXTRUDERS if (esteps) { TERN_(AUTO_POWER_CONTROL, powerManager.power_on()); #if ENABLED(DISABLE_INACTIVE_EXTRUDER) // Enable only the selected extruder - LOOP_L_N(i, EXTRUDERS) - if (g_uc_extruder_last_move[i] > 0) g_uc_extruder_last_move[i]--; + LOOP_L_N(i, E_STEPPERS) + if (g_uc_extruder_last_move[i]) g_uc_extruder_last_move[i]--; - #if HAS_DUPLICATION_MODE - if (extruder_duplication_enabled && extruder == 0) { - ENABLE_AXIS_E1(); - g_uc_extruder_last_move[1] = (BLOCK_BUFFER_SIZE) * 2; - } - #endif + #define E_STEPPER_INDEX(E) TERN(SWITCHING_EXTRUDER, (E) / 2, E) #define ENABLE_ONE_E(N) do{ \ - if (extruder == N) { \ + if (E_STEPPER_INDEX(extruder) == N) { \ ENABLE_AXIS_E##N(); \ g_uc_extruder_last_move[N] = (BLOCK_BUFFER_SIZE) * 2; \ + if ((N) == 0 && TERN0(HAS_DUPLICATION_MODE, extruder_duplication_enabled)) \ + ENABLE_AXIS_E1(); \ } \ - else if (!g_uc_extruder_last_move[N]) \ + else if (!g_uc_extruder_last_move[N]) { \ DISABLE_AXIS_E##N(); \ + if ((N) == 0 && TERN0(HAS_DUPLICATION_MODE, extruder_duplication_enabled)) \ + DISABLE_AXIS_E1(); \ + } \ }while(0); #else @@ -2061,7 +2241,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #endif - REPEAT(EXTRUDERS, ENABLE_ONE_E); // (ENABLE_ONE_E must end with semicolon) + REPEAT(E_STEPPERS, ENABLE_ONE_E); // (ENABLE_ONE_E must end with semicolon) } #endif // EXTRUDERS @@ -2126,7 +2306,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, float speed_factor = 1.0f; // factor <1 decreases speed // Linear axes first with less logic - LOOP_XYZ(i) { + LOOP_LINEAR_AXES(i) { current_speed[i] = steps_dist_mm[i] * inverse_secs; const feedRate_t cs = ABS(current_speed[i]), max_fr = settings.max_feedrate_mm_s[i]; @@ -2134,7 +2314,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, } // Limit speed on extruders, if any - #if EXTRUDERS + #if HAS_EXTRUDERS { current_speed.e = steps_dist_mm.e * inverse_secs; #if HAS_MIXER_SYNC_CHANNEL @@ -2214,23 +2394,25 @@ bool Planner::_populate_block(block_t * const block, bool split_move, // Compute and limit the acceleration rate for the trapezoid generator. const float steps_per_mm = block->step_event_count * inverse_millimeters; uint32_t accel; - if (!block->steps.a && !block->steps.b && !block->steps.c) { - // convert to: acceleration steps/sec^2 - accel = CEIL(settings.retract_acceleration * steps_per_mm); - TERN_(LIN_ADVANCE, block->use_advance_lead = false); + if (LINEAR_AXIS_GANG( + !block->steps.a, && !block->steps.b, && !block->steps.c, + && !block->steps.i, && !block->steps.j, && !block->steps.k) + ) { // Is this a retract / recover move? + accel = CEIL(settings.retract_acceleration * steps_per_mm); // Convert to: acceleration steps/sec^2 + TERN_(LIN_ADVANCE, block->use_advance_lead = false); // No linear advance for simple retract/recover } else { #define LIMIT_ACCEL_LONG(AXIS,INDX) do{ \ if (block->steps[AXIS] && max_acceleration_steps_per_s2[AXIS+INDX] < accel) { \ - const uint32_t comp = max_acceleration_steps_per_s2[AXIS+INDX] * block->step_event_count; \ - if (accel * block->steps[AXIS] > comp) accel = comp / block->steps[AXIS]; \ + const uint32_t max_possible = max_acceleration_steps_per_s2[AXIS+INDX] * block->step_event_count / block->steps[AXIS]; \ + NOMORE(accel, max_possible); \ } \ }while(0) #define LIMIT_ACCEL_FLOAT(AXIS,INDX) do{ \ if (block->steps[AXIS] && max_acceleration_steps_per_s2[AXIS+INDX] < accel) { \ - const float comp = (float)max_acceleration_steps_per_s2[AXIS+INDX] * (float)block->step_event_count; \ - if ((float)accel * (float)block->steps[AXIS] > comp) accel = comp / (float)block->steps[AXIS]; \ + const float max_possible = float(max_acceleration_steps_per_s2[AXIS+INDX]) * float(block->step_event_count) / float(block->steps[AXIS]); \ + NOMORE(accel, max_possible); \ } \ }while(0) @@ -2279,23 +2461,33 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #endif // Limit acceleration per axis - if (block->step_event_count <= cutoff_long) { - LIMIT_ACCEL_LONG(A_AXIS, 0); - LIMIT_ACCEL_LONG(B_AXIS, 0); - LIMIT_ACCEL_LONG(C_AXIS, 0); - LIMIT_ACCEL_LONG(E_AXIS, E_INDEX_N(extruder)); + if (block->step_event_count <= acceleration_long_cutoff) { + LOGICAL_AXIS_CODE( + LIMIT_ACCEL_LONG(E_AXIS, E_INDEX_N(extruder)), + LIMIT_ACCEL_LONG(A_AXIS, 0), + LIMIT_ACCEL_LONG(B_AXIS, 0), + LIMIT_ACCEL_LONG(C_AXIS, 0), + LIMIT_ACCEL_LONG(I_AXIS, 0), + LIMIT_ACCEL_LONG(J_AXIS, 0), + LIMIT_ACCEL_LONG(K_AXIS, 0) + ); } else { - LIMIT_ACCEL_FLOAT(A_AXIS, 0); - LIMIT_ACCEL_FLOAT(B_AXIS, 0); - LIMIT_ACCEL_FLOAT(C_AXIS, 0); - LIMIT_ACCEL_FLOAT(E_AXIS, E_INDEX_N(extruder)); + LOGICAL_AXIS_CODE( + LIMIT_ACCEL_FLOAT(E_AXIS, E_INDEX_N(extruder)), + LIMIT_ACCEL_FLOAT(A_AXIS, 0), + LIMIT_ACCEL_FLOAT(B_AXIS, 0), + LIMIT_ACCEL_FLOAT(C_AXIS, 0), + LIMIT_ACCEL_FLOAT(I_AXIS, 0), + LIMIT_ACCEL_FLOAT(J_AXIS, 0), + LIMIT_ACCEL_FLOAT(K_AXIS, 0) + ); } } block->acceleration_steps_per_s2 = accel; block->acceleration = accel / steps_per_mm; #if DISABLED(S_CURVE_ACCELERATION) - block->acceleration_rate = (uint32_t)(accel * (4096.0f * 4096.0f / (STEPPER_TIMER_RATE))); + block->acceleration_rate = (uint32_t)(accel * (sq(4096.0f) / (STEPPER_TIMER_RATE))); #endif #if ENABLED(LIN_ADVANCE) if (block->use_advance_lead) { @@ -2353,7 +2545,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #if HAS_DIST_MM_ARG cart_dist_mm #else - { steps_dist_mm.x, steps_dist_mm.y, steps_dist_mm.z, steps_dist_mm.e } + LOGICAL_AXIS_ARRAY(steps_dist_mm.e, steps_dist_mm.x, steps_dist_mm.y, steps_dist_mm.z, steps_dist_mm.i, steps_dist_mm.j, steps_dist_mm.k) #endif ; @@ -2372,8 +2564,15 @@ bool Planner::_populate_block(block_t * const block, bool split_move, if (moves_queued && !UNEAR_ZERO(previous_nominal_speed_sqr)) { // Compute cosine of angle between previous and current path. (prev_unit_vec is negative) // NOTE: Max junction velocity is computed without sin() or acos() by trig half angle identity. - float junction_cos_theta = (-prev_unit_vec.x * unit_vec.x) + (-prev_unit_vec.y * unit_vec.y) - + (-prev_unit_vec.z * unit_vec.z) + (-prev_unit_vec.e * unit_vec.e); + float junction_cos_theta = LOGICAL_AXIS_GANG( + + (-prev_unit_vec.e * unit_vec.e), + (-prev_unit_vec.x * unit_vec.x), + + (-prev_unit_vec.y * unit_vec.y), + + (-prev_unit_vec.z * unit_vec.z), + + (-prev_unit_vec.i * unit_vec.i), + + (-prev_unit_vec.j * unit_vec.j), + + (-prev_unit_vec.k * unit_vec.k) + ); // NOTE: Computed without any expensive trig, sin() or acos(), by trig half angle identity of cos(theta). if (junction_cos_theta > 0.999999f) { @@ -2516,10 +2715,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #ifndef TRAVEL_EXTRA_XYJERK #define TRAVEL_EXTRA_XYJERK 0 #endif - const float extra_xyjerk = (de <= 0) ? TRAVEL_EXTRA_XYJERK : 0; + const float extra_xyjerk = TERN0(HAS_EXTRUDERS, de <= 0) ? TRAVEL_EXTRA_XYJERK : 0; uint8_t limited = 0; - TERN(HAS_LINEAR_E_JERK, LOOP_XYZ, LOOP_XYZE)(i) { + TERN(HAS_LINEAR_E_JERK, LOOP_LINEAR_AXES, LOOP_LOGICAL_AXES)(i) { const float jerk = ABS(current_speed[i]), // cs : Starting from zero, change in speed for this axis maxj = (max_jerk[i] + (i == X_AXIS || i == Y_AXIS ? extra_xyjerk : 0.0f)); // mj : The max jerk setting for this axis if (jerk > maxj) { // cs > mj : New current speed too fast? @@ -2557,7 +2756,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, vmax_junction = previous_nominal_speed; // Now limit the jerk in all axes. - TERN(HAS_LINEAR_E_JERK, LOOP_XYZ, LOOP_XYZE)(axis) { + TERN(HAS_LINEAR_E_JERK, LOOP_LINEAR_AXES, LOOP_LOGICAL_AXES)(axis) { // Limit an axis. We have to differentiate: coasting, reversal of an axis, full stop. float v_exit = previous_speed[axis] * smaller_speed_factor, v_entry = current_speed[axis]; @@ -2636,9 +2835,14 @@ bool Planner::_populate_block(block_t * const block, bool split_move, /** * Planner::buffer_sync_block - * Add a block to the buffer that just updates the position + * Add a block to the buffer that just updates the position, + * or in case of LASER_SYNCHRONOUS_M106_M107 the fan PWM */ -void Planner::buffer_sync_block() { +void Planner::buffer_sync_block(TERN_(LASER_SYNCHRONOUS_M106_M107, uint8_t sync_flag)) { + #if DISABLED(LASER_SYNCHRONOUS_M106_M107) + constexpr uint8_t sync_flag = BLOCK_FLAG_SYNC_POSITION; + #endif + // Wait for the next available block uint8_t next_buffer_head; block_t * const block = get_next_free_block(next_buffer_head); @@ -2646,10 +2850,14 @@ void Planner::buffer_sync_block() { // Clear block memset(block, 0, sizeof(block_t)); - block->flag = BLOCK_FLAG_SYNC_POSITION; + block->flag = sync_flag; block->position = position; + #if BOTH(HAS_FAN, LASER_SYNCHRONOUS_M106_M107) + FANS_LOOP(i) block->fan_speed[i] = thermalManager.fan_speed[i]; + #endif + // If this is the first added movement, reload the delay, otherwise, cancel it. if (block_buffer_head == block_buffer_tail) { // If it was the first queued block, restart the 1st block delivery delay, to @@ -2679,11 +2887,9 @@ void Planner::buffer_sync_block() { * * Return 'false' if no segment was queued due to cleaning, cold extrusion, full queue, etc. */ -bool Planner::buffer_segment(const float &a, const float &b, const float &c, const float &e - #if HAS_DIST_MM_ARG - , const xyze_float_t &cart_dist_mm - #endif - , const feedRate_t &fr_mm_s, const uint8_t extruder, const float &millimeters/*=0.0*/ +bool Planner::buffer_segment(const abce_pos_t &abce + OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm) + , const_feedRate_t fr_mm_s, const uint8_t extruder/*=active_extruder*/, const_float_t millimeters/*=0.0*/ ) { // If we are cleaning, do not accept queuing of movements @@ -2700,51 +2906,71 @@ bool Planner::buffer_segment(const float &a, const float &b, const float &c, con // The target position of the tool in absolute steps // Calculate target position in absolute steps const abce_long_t target = { - int32_t(LROUND(a * settings.axis_steps_per_mm[A_AXIS])), - int32_t(LROUND(b * settings.axis_steps_per_mm[B_AXIS])), - int32_t(LROUND(c * settings.axis_steps_per_mm[C_AXIS])), - int32_t(LROUND(e * settings.axis_steps_per_mm[E_AXIS_N(extruder)])) + LOGICAL_AXIS_LIST( + int32_t(LROUND(abce.e * settings.axis_steps_per_mm[E_AXIS_N(extruder)])), + int32_t(LROUND(abce.a * settings.axis_steps_per_mm[A_AXIS])), + int32_t(LROUND(abce.b * settings.axis_steps_per_mm[B_AXIS])), + int32_t(LROUND(abce.c * settings.axis_steps_per_mm[C_AXIS])), + int32_t(LROUND(abce.i * settings.axis_steps_per_mm[I_AXIS])), + int32_t(LROUND(abce.j * settings.axis_steps_per_mm[J_AXIS])), + int32_t(LROUND(abce.k * settings.axis_steps_per_mm[K_AXIS])) + ) }; #if HAS_POSITION_FLOAT - const xyze_pos_t target_float = { a, b, c, e }; + const xyze_pos_t target_float = abce; #endif - // DRYRUN prevents E moves from taking place - if (DEBUGGING(DRYRUN) || TERN0(CANCEL_OBJECTS, cancelable.skipping)) { - position.e = target.e; - TERN_(HAS_POSITION_FLOAT, position_float.e = e); - } + #if HAS_EXTRUDERS + // DRYRUN prevents E moves from taking place + if (DEBUGGING(DRYRUN) || TERN0(CANCEL_OBJECTS, cancelable.skipping)) { + position.e = target.e; + TERN_(HAS_POSITION_FLOAT, position_float.e = abce.e); + } + #endif /* <-- add a slash to enable SERIAL_ECHOPAIR(" buffer_segment FR:", fr_mm_s); #if IS_KINEMATIC - SERIAL_ECHOPAIR(" A:", a); - SERIAL_ECHOPAIR(" (", position.a); - SERIAL_ECHOPAIR("->", target.a); - SERIAL_ECHOPAIR(") B:", b); + SERIAL_ECHOPAIR(" A:", abce.a, " (", position.a, "->", target.a, ") B:", abce.b); #else - SERIAL_ECHOPAIR_P(SP_X_LBL, a); - SERIAL_ECHOPAIR(" (", position.x); - SERIAL_ECHOPAIR("->", target.x); + SERIAL_ECHOPAIR_P(SP_X_LBL, abce.a); + SERIAL_ECHOPAIR(" (", position.x, "->", target.x); SERIAL_CHAR(')'); - SERIAL_ECHOPAIR_P(SP_Y_LBL, b); + SERIAL_ECHOPAIR_P(SP_Y_LBL, abce.b); #endif - SERIAL_ECHOPAIR(" (", position.y); - SERIAL_ECHOPAIR("->", target.y); - #if ENABLED(DELTA) - SERIAL_ECHOPAIR(") C:", c); - #else + SERIAL_ECHOPAIR(" (", position.y, "->", target.y); + #if LINEAR_AXES >= ABC + #if ENABLED(DELTA) + SERIAL_ECHOPAIR(") C:", abce.c); + #else + SERIAL_CHAR(')'); + SERIAL_ECHOPAIR_P(SP_Z_LBL, abce.c); + #endif + SERIAL_ECHOPAIR(" (", position.z, "->", target.z); + SERIAL_CHAR(')'); + #endif + #if LINEAR_AXES >= 4 + SERIAL_ECHOPAIR_P(SP_I_LBL, abce.i); + SERIAL_ECHOPAIR(" (", position.i, "->", target.i); + SERIAL_CHAR(')'); + #endif + #if LINEAR_AXES >= 5 + SERIAL_ECHOPAIR_P(SP_J_LBL, abce.j); + SERIAL_ECHOPAIR(" (", position.j, "->", target.j); + SERIAL_CHAR(')'); + #endif + #if LINEAR_AXES >= 6 + SERIAL_ECHOPAIR_P(SP_K_LBL, abce.k); + SERIAL_ECHOPAIR(" (", position.k, "->", target.k); SERIAL_CHAR(')'); - SERIAL_ECHOPAIR_P(SP_Z_LBL, c); #endif - SERIAL_ECHOPAIR(" (", position.z); - SERIAL_ECHOPAIR("->", target.z); - SERIAL_CHAR(')'); - SERIAL_ECHOPAIR_P(SP_E_LBL, e); - SERIAL_ECHOPAIR(" (", position.e); - SERIAL_ECHOPAIR("->", target.e); - SERIAL_ECHOLNPGM(")"); + #if HAS_EXTRUDERS + SERIAL_ECHOPAIR_P(SP_E_LBL, abce.e); + SERIAL_ECHOLNPAIR(" (", position.e, "->", target.e, ")"); + #else + SERIAL_EOL(); + #endif //*/ // Queue the movement. Return 'false' if the move was not queued. @@ -2767,34 +2993,34 @@ bool Planner::buffer_segment(const float &a, const float &b, const float &c, con * The target is cartesian. It's translated to * delta/scara if needed. * - * rx,ry,rz,e - target position in mm or degrees - * fr_mm_s - (target) speed of the move (mm/s) - * extruder - target extruder - * millimeters - the length of the movement, if known - * inv_duration - the reciprocal if the duration of the movement, if known (kinematic only if feeedrate scaling is enabled) + * cart - target position in mm or degrees + * fr_mm_s - (target) speed of the move (mm/s) + * extruder - target extruder + * millimeters - the length of the movement, if known + * inv_duration - the reciprocal if the duration of the movement, if known (kinematic only if feeedrate scaling is enabled) */ -bool Planner::buffer_line(const float &rx, const float &ry, const float &rz, const float &e, const feedRate_t &fr_mm_s, const uint8_t extruder, const float millimeters - #if ENABLED(SCARA_FEEDRATE_SCALING) - , const float &inv_duration - #endif +bool Planner::buffer_line(const xyze_pos_t &cart, const_feedRate_t fr_mm_s, const uint8_t extruder/*=active_extruder*/, const float millimeters/*=0.0*/ + OPTARG(SCARA_FEEDRATE_SCALING, const_float_t inv_duration/*=0.0*/) ) { - xyze_pos_t machine = { rx, ry, rz, e }; + xyze_pos_t machine = cart; TERN_(HAS_POSITION_MODIFIERS, apply_modifiers(machine)); #if IS_KINEMATIC #if HAS_JUNCTION_DEVIATION - const xyze_pos_t cart_dist_mm = { - rx - position_cart.x, ry - position_cart.y, - rz - position_cart.z, e - position_cart.e - }; + const xyze_pos_t cart_dist_mm = LOGICAL_AXIS_ARRAY( + cart.e - position_cart.e, + cart.x - position_cart.x, cart.y - position_cart.y, cart.z - position_cart.z, + cart.i - position_cart.i, cart.j - position_cart.j, cart.j - position_cart.k + ); #else - const xyz_pos_t cart_dist_mm = { rx - position_cart.x, ry - position_cart.y, rz - position_cart.z }; + const xyz_pos_t cart_dist_mm = LINEAR_AXIS_ARRAY( + cart.x - position_cart.x, cart.y - position_cart.y, cart.z - position_cart.z, + cart.i - position_cart.i, cart.j - position_cart.j, cart.j - position_cart.k + ); #endif - float mm = millimeters; - if (mm == 0.0) - mm = (cart_dist_mm.x != 0.0 || cart_dist_mm.y != 0.0) ? cart_dist_mm.magnitude() : ABS(cart_dist_mm.z); + const float mm = millimeters ?: (cart_dist_mm.x || cart_dist_mm.y) ? cart_dist_mm.magnitude() : TERN0(HAS_Z_AXIS, ABS(cart_dist_mm.z)); // Cartesian XYZ to kinematic ABC, stored in global 'delta' inverse_kinematics(machine); @@ -2808,17 +3034,12 @@ bool Planner::buffer_line(const float &rx, const float &ry, const float &rz, con #else const feedRate_t feedrate = fr_mm_s; #endif - if (buffer_segment(delta.a, delta.b, delta.c, machine.e - #if HAS_JUNCTION_DEVIATION - , cart_dist_mm - #endif - , feedrate, extruder, mm - )) { - position_cart.set(rx, ry, rz, e); + delta.e = machine.e; + if (buffer_segment(delta OPTARG(HAS_DIST_MM_ARG, cart_dist_mm), feedrate, extruder, mm)) { + position_cart = cart; return true; } - else - return false; + return false; #else return buffer_segment(machine, fr_mm_s, extruder, millimeters); #endif @@ -2837,20 +3058,16 @@ bool Planner::buffer_line(const float &rx, const float &ry, const float &rz, con block->flag = BLOCK_FLAG_IS_PAGE; - #if FAN_COUNT > 0 + #if HAS_FAN FANS_LOOP(i) block->fan_speed[i] = thermalManager.fan_speed[i]; #endif - #if HAS_MULTI_EXTRUDER - block->extruder = extruder; - #endif + TERN_(HAS_MULTI_EXTRUDER, block->extruder = extruder); block->page_idx = page_idx; block->step_event_count = num_steps; - block->initial_rate = - block->final_rate = - block->nominal_rate = last_page_step_rate; // steps/s + block->initial_rate = block->final_rate = block->nominal_rate = last_page_step_rate; // steps/s block->accelerate_until = 0; block->decelerate_after = block->step_event_count; @@ -2888,19 +3105,25 @@ bool Planner::buffer_line(const float &rx, const float &ry, const float &rz, con #endif // DIRECT_STEPPING /** - * Directly set the planner ABC position (and stepper positions) + * Directly set the planner ABCE position (and stepper positions) * converting mm (or angles for SCARA) into steps. * - * The provided ABC position is in machine units. + * The provided ABCE position is in machine units. */ - -void Planner::set_machine_position_mm(const float &a, const float &b, const float &c, const float &e) { +void Planner::set_machine_position_mm(const abce_pos_t &abce) { TERN_(DISTINCT_E_FACTORS, last_extruder = active_extruder); - TERN_(HAS_POSITION_FLOAT, position_float.set(a, b, c, e)); - position.set(LROUND(a * settings.axis_steps_per_mm[A_AXIS]), - LROUND(b * settings.axis_steps_per_mm[B_AXIS]), - LROUND(c * settings.axis_steps_per_mm[C_AXIS]), - LROUND(e * settings.axis_steps_per_mm[E_AXIS_N(active_extruder)])); + TERN_(HAS_POSITION_FLOAT, position_float = abce); + position.set( + LOGICAL_AXIS_LIST( + LROUND(abce.e * settings.axis_steps_per_mm[E_AXIS_N(active_extruder)]), + LROUND(abce.a * settings.axis_steps_per_mm[A_AXIS]), + LROUND(abce.b * settings.axis_steps_per_mm[B_AXIS]), + LROUND(abce.c * settings.axis_steps_per_mm[C_AXIS]), + LROUND(abce.i * settings.axis_steps_per_mm[I_AXIS]), + LROUND(abce.j * settings.axis_steps_per_mm[J_AXIS]), + LROUND(abce.k * settings.axis_steps_per_mm[K_AXIS]) + ) + ); if (has_blocks_queued()) { //previous_nominal_speed_sqr = 0.0; // Reset planner junction speeds. Assume start from rest. //previous_speed.reset(); @@ -2910,74 +3133,84 @@ void Planner::set_machine_position_mm(const float &a, const float &b, const floa stepper.set_position(position); } -void Planner::set_position_mm(const float &rx, const float &ry, const float &rz, const float &e) { - xyze_pos_t machine = { rx, ry, rz, e }; - #if HAS_POSITION_MODIFIERS - apply_modifiers(machine, true); - #endif +void Planner::set_position_mm(const xyze_pos_t &xyze) { + xyze_pos_t machine = xyze; + TERN_(HAS_POSITION_MODIFIERS, apply_modifiers(machine, true)); #if IS_KINEMATIC - position_cart.set(rx, ry, rz, e); + position_cart = xyze; inverse_kinematics(machine); - set_machine_position_mm(delta.a, delta.b, delta.c, machine.e); + delta.e = machine.e; + set_machine_position_mm(delta); #else set_machine_position_mm(machine); #endif } -/** - * Setters for planner position (also setting stepper position). - */ -void Planner::set_e_position_mm(const float &e) { - const uint8_t axis_index = E_AXIS_N(active_extruder); - TERN_(DISTINCT_E_FACTORS, last_extruder = active_extruder); +#if HAS_EXTRUDERS + + /** + * Setters for planner position (also setting stepper position). + */ + void Planner::set_e_position_mm(const_float_t e) { + const uint8_t axis_index = E_AXIS_N(active_extruder); + TERN_(DISTINCT_E_FACTORS, last_extruder = active_extruder); - const float e_new = e - TERN0(FWRETRACT, fwretract.current_retract[active_extruder]); - position.e = LROUND(settings.axis_steps_per_mm[axis_index] * e_new); - TERN_(HAS_POSITION_FLOAT, position_float.e = e_new); - TERN_(IS_KINEMATIC, position_cart.e = e); + const float e_new = DIFF_TERN(FWRETRACT, e, fwretract.current_retract[active_extruder]); + position.e = LROUND(settings.axis_steps_per_mm[axis_index] * e_new); + TERN_(HAS_POSITION_FLOAT, position_float.e = e_new); + TERN_(IS_KINEMATIC, TERN_(HAS_EXTRUDERS, position_cart.e = e)); - if (has_blocks_queued()) - buffer_sync_block(); - else - stepper.set_axis_position(E_AXIS, position.e); -} + if (has_blocks_queued()) + buffer_sync_block(); + else + stepper.set_axis_position(E_AXIS, position.e); + } + +#endif // Recalculate the steps/s^2 acceleration rates, based on the mm/s^2 void Planner::reset_acceleration_rates() { - #if ENABLED(DISTINCT_E_FACTORS) - #define AXIS_CONDITION (i < E_AXIS || i == E_AXIS_N(active_extruder)) - #else - #define AXIS_CONDITION true - #endif uint32_t highest_rate = 1; - LOOP_XYZE_N(i) { + LOOP_DISTINCT_AXES(i) { max_acceleration_steps_per_s2[i] = settings.max_acceleration_mm_per_s2[i] * settings.axis_steps_per_mm[i]; - if (AXIS_CONDITION) NOLESS(highest_rate, max_acceleration_steps_per_s2[i]); + if (TERN1(DISTINCT_E_FACTORS, i < E_AXIS || i == E_AXIS_N(active_extruder))) + NOLESS(highest_rate, max_acceleration_steps_per_s2[i]); } - cutoff_long = 4294967295UL / highest_rate; // 0xFFFFFFFFUL + acceleration_long_cutoff = 4294967295UL / highest_rate; // 0xFFFFFFFFUL TERN_(HAS_LINEAR_E_JERK, recalculate_max_e_jerk()); } -// Recalculate position, steps_to_mm if settings.axis_steps_per_mm changes! +/** + * Recalculate 'position' and 'steps_to_mm'. + * Must be called whenever settings.axis_steps_per_mm changes! + */ void Planner::refresh_positioning() { - LOOP_XYZE_N(i) steps_to_mm[i] = 1.0f / settings.axis_steps_per_mm[i]; + LOOP_DISTINCT_AXES(i) steps_to_mm[i] = 1.0f / settings.axis_steps_per_mm[i]; set_position_mm(current_position); reset_acceleration_rates(); } +// Apply limits to a variable and give a warning if the value was out of range inline void limit_and_warn(float &val, const uint8_t axis, PGM_P const setting_name, const xyze_float_t &max_limit) { - const uint8_t lim_axis = axis > E_AXIS ? E_AXIS : axis; + const uint8_t lim_axis = TERN_(HAS_EXTRUDERS, axis > E_AXIS ? E_AXIS :) axis; const float before = val; LIMIT(val, 0.1, max_limit[lim_axis]); if (before != val) { - SERIAL_CHAR(axis_codes[lim_axis]); + SERIAL_CHAR(AXIS_CHAR(lim_axis)); SERIAL_ECHOPGM(" Max "); - serialprintPGM(setting_name); + SERIAL_ECHOPGM_P(setting_name); SERIAL_ECHOLNPAIR(" limited to ", val); } } -void Planner::set_max_acceleration(const uint8_t axis, float targetValue) { +/** + * For the specified 'axis' set the Maximum Acceleration to the given value (mm/s^2) + * The value may be limited with warning feedback, if configured. + * Calls reset_acceleration_rates to precalculate planner terms in steps. + * + * This hard limit is applied as a block is being added to the planner queue. + */ +void Planner::set_max_acceleration(const uint8_t axis, float inMaxAccelMMS2) { #if ENABLED(LIMITED_MAX_ACCEL_EDITING) #ifdef MAX_ACCEL_EDIT_VALUES constexpr xyze_float_t max_accel_edit = MAX_ACCEL_EDIT_VALUES; @@ -2986,15 +3219,21 @@ void Planner::set_max_acceleration(const uint8_t axis, float targetValue) { constexpr xyze_float_t max_accel_edit = DEFAULT_MAX_ACCELERATION; const xyze_float_t max_acc_edit_scaled = max_accel_edit * 2; #endif - limit_and_warn(targetValue, axis, PSTR("Acceleration"), max_acc_edit_scaled); + limit_and_warn(inMaxAccelMMS2, axis, PSTR("Acceleration"), max_acc_edit_scaled); #endif - settings.max_acceleration_mm_per_s2[axis] = targetValue; + settings.max_acceleration_mm_per_s2[axis] = inMaxAccelMMS2; // Update steps per s2 to agree with the units per s2 (since they are used in the planner) reset_acceleration_rates(); } -void Planner::set_max_feedrate(const uint8_t axis, float targetValue) { +/** + * For the specified 'axis' set the Maximum Feedrate to the given value (mm/s) + * The value may be limited with warning feedback, if configured. + * + * This hard limit is applied as a block is being added to the planner queue. + */ +void Planner::set_max_feedrate(const uint8_t axis, float inMaxFeedrateMMS) { #if ENABLED(LIMITED_MAX_FR_EDITING) #ifdef MAX_FEEDRATE_EDIT_VALUES constexpr xyze_float_t max_fr_edit = MAX_FEEDRATE_EDIT_VALUES; @@ -3003,13 +3242,20 @@ void Planner::set_max_feedrate(const uint8_t axis, float targetValue) { constexpr xyze_float_t max_fr_edit = DEFAULT_MAX_FEEDRATE; const xyze_float_t max_fr_edit_scaled = max_fr_edit * 2; #endif - limit_and_warn(targetValue, axis, PSTR("Feedrate"), max_fr_edit_scaled); + limit_and_warn(inMaxFeedrateMMS, axis, PSTR("Feedrate"), max_fr_edit_scaled); #endif - settings.max_feedrate_mm_s[axis] = targetValue; + settings.max_feedrate_mm_s[axis] = inMaxFeedrateMMS; } -void Planner::set_max_jerk(const AxisEnum axis, float targetValue) { - #if HAS_CLASSIC_JERK +#if HAS_CLASSIC_JERK + + /** + * For the specified 'axis' set the Maximum Jerk (instant change) to the given value (mm/s) + * The value may be limited with warning feedback, if configured. + * + * This hard limit is applied (to the block start speed) as the block is being added to the planner queue. + */ + void Planner::set_max_jerk(const AxisEnum axis, float inMaxJerkMMS) { #if ENABLED(LIMITED_JERK_EDITING) constexpr xyze_float_t max_jerk_edit = #ifdef MAX_JERK_EDIT_VALUES @@ -3019,13 +3265,12 @@ void Planner::set_max_jerk(const AxisEnum axis, float targetValue) { (DEFAULT_ZJERK) * 2, (DEFAULT_EJERK) * 2 } #endif ; - limit_and_warn(targetValue, axis, PSTR("Jerk"), max_jerk_edit); + limit_and_warn(inMaxJerkMMS, axis, PSTR("Jerk"), max_jerk_edit); #endif - max_jerk[axis] = targetValue; - #else - UNUSED(axis); UNUSED(targetValue); - #endif -} + max_jerk[axis] = inMaxJerkMMS; + } + +#endif #if HAS_WIRED_LCD @@ -3068,33 +3313,3 @@ void Planner::set_max_jerk(const AxisEnum axis, float targetValue) { } #endif - -#if ENABLED(AUTOTEMP) - -void Planner::autotemp_update() { - #if ENABLED(AUTOTEMP_PROPORTIONAL) - const int16_t target = thermalManager.degTargetHotend(active_extruder); - autotemp_min = target + AUTOTEMP_MIN_P; - autotemp_max = target + AUTOTEMP_MAX_P; - #endif - autotemp_factor = TERN(AUTOTEMP_PROPORTIONAL, AUTOTEMP_FACTOR_P, 0); - autotemp_enabled = autotemp_factor != 0; -} - - void Planner::autotemp_M104_M109() { - - #if ENABLED(AUTOTEMP_PROPORTIONAL) - const int16_t target = thermalManager.degTargetHotend(active_extruder); - autotemp_min = target + AUTOTEMP_MIN_P; - autotemp_max = target + AUTOTEMP_MAX_P; - #endif - - if (parser.seenval('S')) autotemp_min = parser.value_celsius(); - if (parser.seenval('B')) autotemp_max = parser.value_celsius(); - - // When AUTOTEMP_PROPORTIONAL is enabled, F0 disables autotemp. - // Normally, leaving off F also disables autotemp. - autotemp_factor = parser.seen('F') ? parser.value_float() : TERN(AUTOTEMP_PROPORTIONAL, AUTOTEMP_FACTOR_P, 0); - autotemp_enabled = autotemp_factor != 0; - } -#endif diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index c4e11490b161..5e3922c8979c 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -76,7 +76,9 @@ // Feedrate for manual moves #ifdef MANUAL_FEEDRATE constexpr xyze_feedrate_t _mf = MANUAL_FEEDRATE, - manual_feedrate_mm_s { _mf.x / 60.0f, _mf.y / 60.0f, _mf.z / 60.0f, _mf.e / 60.0f }; + manual_feedrate_mm_s = LOGICAL_AXIS_ARRAY(_mf.e / 60.0f, + _mf.x / 60.0f, _mf.y / 60.0f, _mf.z / 60.0f, + _mf.i / 60.0f, _mf.j / 60.0f, _mf.k / 60.0f); #endif #if IS_KINEMATIC && HAS_JUNCTION_DEVIATION @@ -102,6 +104,11 @@ enum BlockFlagBit : char { #if ENABLED(DIRECT_STEPPING) , BLOCK_BIT_IS_PAGE #endif + + // Sync the fan speeds from the block + #if ENABLED(LASER_SYNCHRONOUS_M106_M107) + , BLOCK_BIT_SYNC_FANS + #endif }; enum BlockFlag : char { @@ -112,8 +119,13 @@ enum BlockFlag : char { #if ENABLED(DIRECT_STEPPING) , BLOCK_FLAG_IS_PAGE = _BV(BLOCK_BIT_IS_PAGE) #endif + #if ENABLED(LASER_SYNCHRONOUS_M106_M107) + , BLOCK_FLAG_SYNC_FANS = _BV(BLOCK_BIT_SYNC_FANS) + #endif }; +#define BLOCK_MASK_SYNC ( BLOCK_FLAG_SYNC_POSITION | TERN0(LASER_SYNCHRONOUS_M106_M107, BLOCK_FLAG_SYNC_FANS) ) + #if ENABLED(LASER_POWER_INLINE) typedef struct { @@ -170,7 +182,9 @@ typedef struct block_t { static constexpr uint8_t extruder = 0; #endif - TERN_(MIXING_EXTRUDER, MIXER_BLOCK_FIELD); // Normalized color for the mixing steppers + #if ENABLED(MIXING_EXTRUDER) + mixer_comp_t b_color[MIXING_STEPPERS]; // Normalized color for the mixing steppers + #endif // Settings for the trapezoid generator uint32_t accelerate_until, // The index of the step event on which to stop acceleration @@ -256,10 +270,10 @@ typedef struct block_t { #endif typedef struct { - uint32_t max_acceleration_mm_per_s2[XYZE_N], // (mm/s^2) M201 XYZE + uint32_t max_acceleration_mm_per_s2[DISTINCT_AXES], // (mm/s^2) M201 XYZE min_segment_time_us; // (µs) M205 B - float axis_steps_per_mm[XYZE_N]; // (steps) M92 XYZE - Steps per millimeter - feedRate_t max_feedrate_mm_s[XYZE_N]; // (mm/s) M203 XYZE - Max speeds + float axis_steps_per_mm[DISTINCT_AXES]; // (steps) M92 XYZE - Steps per millimeter + feedRate_t max_feedrate_mm_s[DISTINCT_AXES]; // (mm/s) M203 XYZE - Max speeds float acceleration, // (mm/s^2) M204 S - Normal acceleration. DEFAULT ACCELERATION for all printing moves. retract_acceleration, // (mm/s^2) M204 R - Retract acceleration. Filament pull-back and push-forward while standing still in the other axes travel_acceleration; // (mm/s^2) M204 T - Travel acceleration. DEFAULT ACCELERATION for all NON printing moves. @@ -267,6 +281,15 @@ typedef struct { min_travel_feedrate_mm_s; // (mm/s) M205 T - Minimum travel feedrate } planner_settings_t; +#if ENABLED(IMPROVE_HOMING_RELIABILITY) + struct motion_state_t { + TERN(DELTA, xyz_ulong_t, xy_ulong_t) acceleration; + #if HAS_CLASSIC_JERK + TERN(DELTA, xyz_float_t, xy_float_t) jerk_state; + #endif + }; +#endif + #if DISABLED(SKEW_CORRECTION) #define XY_SKEW_FACTOR 0 #define XZ_SKEW_FACTOR 0 @@ -287,6 +310,10 @@ 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; +#endif + class Planner { public: @@ -321,7 +348,7 @@ class Planner { static xyze_bool_t last_page_dir; // Last page direction given #endif - #if EXTRUDERS + #if HAS_EXTRUDERS static int16_t flow_percentage[EXTRUDERS]; // Extrusion factor for each extruder static float e_factor[EXTRUDERS]; // The flow percentage and volumetric multiplier combine to scale E movement #endif @@ -344,13 +371,13 @@ class Planner { static laser_state_t laser_inline; #endif - static uint32_t max_acceleration_steps_per_s2[XYZE_N]; // (steps/s^2) Derived from mm_per_s2 - static float steps_to_mm[XYZE_N]; // Millimeters per step + static uint32_t max_acceleration_steps_per_s2[DISTINCT_AXES]; // (steps/s^2) Derived from mm_per_s2 + static float steps_to_mm[DISTINCT_AXES]; // Millimeters per step #if HAS_JUNCTION_DEVIATION - static float junction_deviation_mm; // (mm) M205 J + static float junction_deviation_mm; // (mm) M205 J #if HAS_LINEAR_E_JERK - static float max_e_jerk[DISTINCT_E]; // Calculated from junction_deviation_mm + static float max_e_jerk[DISTINCT_E]; // Calculated from junction_deviation_mm #endif #endif @@ -427,15 +454,15 @@ class Planner { /** * Limit where 64bit math is necessary for acceleration calculation */ - static uint32_t cutoff_long; + static uint32_t acceleration_long_cutoff; #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) static float last_fade_z; #endif #if ENABLED(DISABLE_INACTIVE_EXTRUDER) - // Counters to manage disabling inactive extruders - static uint8_t g_uc_extruder_last_move[EXTRUDERS]; + // Counters to manage disabling inactive extruder steppers + static last_move_t g_uc_extruder_last_move[E_STEPPERS]; #endif #if HAS_WIRED_LCD @@ -456,14 +483,29 @@ class Planner { * Static (class) Methods */ + // Recalculate steps/s^2 accelerations based on mm/s^2 settings static void reset_acceleration_rates(); + + /** + * Recalculate 'position' and 'steps_to_mm'. + * Must be called whenever settings.axis_steps_per_mm changes! + */ static void refresh_positioning(); - static void set_max_acceleration(const uint8_t axis, float targetValue); - static void set_max_feedrate(const uint8_t axis, float targetValue); - static void set_max_jerk(const AxisEnum axis, float targetValue); + // For an axis set the Maximum Acceleration in mm/s^2 + static void set_max_acceleration(const uint8_t axis, float inMaxAccelMMS2); + + // For an axis set the Maximum Feedrate in mm/s + static void set_max_feedrate(const uint8_t axis, float inMaxFeedrateMMS); + + // For an axis set the Maximum Jerk (instant change) in mm/s + #if HAS_CLASSIC_JERK + static void set_max_jerk(const AxisEnum axis, float inMaxJerkMMS); + #else + static inline void set_max_jerk(const AxisEnum, const_float_t) {} + #endif - #if EXTRUDERS + #if HAS_EXTRUDERS FORCE_INLINE static void refresh_e_factor(const uint8_t e) { e_factor[e] = flow_percentage[e] * 0.01f * TERN(NO_VOLUMETRICS, 1.0f, volumetric_multiplier[e]); } @@ -478,6 +520,16 @@ class Planner { // Manage fans, paste pressure, etc. static void check_axes_activity(); + // Apply fan speeds + #if HAS_FAN + static void sync_fan_speeds(uint8_t (&fan_speed)[FAN_COUNT]); + #if FAN_KICKSTART_TIME + static void kickstart_fan(uint8_t (&fan_speed)[FAN_COUNT], const millis_t &ms, const uint8_t f); + #else + FORCE_INLINE static void kickstart_fan(uint8_t (&)[FAN_COUNT], const millis_t &, const uint8_t) {} + #endif + #endif + #if ENABLED(FILAMENT_WIDTH_SENSOR) void apply_filament_width_sensor(const int8_t encoded_ratio); @@ -489,6 +541,10 @@ class Planner { } #endif + #if ENABLED(IMPROVE_HOMING_RELIABILITY) + void enable_stall_prevention(const bool onoff); + #endif + #if DISABLED(NO_VOLUMETRICS) // Update multipliers based on new diameter measurements @@ -500,7 +556,7 @@ class Planner { static void calculate_volumetric_extruder_limits(); #endif - FORCE_INLINE static void set_filament_size(const uint8_t e, const float &v) { + FORCE_INLINE static void set_filament_size(const uint8_t e, const_float_t v) { 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 @@ -511,7 +567,7 @@ class Planner { #endif #if ENABLED(VOLUMETRIC_EXTRUDER_LIMIT) - FORCE_INLINE static void set_volumetric_extruder_limit(const uint8_t e, const float &v) { + FORCE_INLINE static void set_volumetric_extruder_limit(const uint8_t e, const_float_t v) { volumetric_extruder_limit[e] = v; calculate_volumetric_extruder_limit(e); } @@ -526,7 +582,7 @@ class Planner { * Returns 1.0 if planner.z_fade_height is 0.0. * Returns 0.0 if Z is past the specified 'Fade Height'. */ - static inline float fade_scaling_factor_for_z(const float &rz) { + static inline float fade_scaling_factor_for_z(const_float_t rz) { static float z_fade_factor = 1; if (!z_fade_height) return 1; if (rz >= z_fade_height) return 0; @@ -539,42 +595,42 @@ class Planner { FORCE_INLINE static void force_fade_recalc() { last_fade_z = -999.999f; } - FORCE_INLINE static void set_z_fade_height(const float &zfh) { + FORCE_INLINE static void set_z_fade_height(const_float_t zfh) { z_fade_height = zfh > 0 ? zfh : 0; inverse_z_fade_height = RECIPROCAL(z_fade_height); force_fade_recalc(); } - FORCE_INLINE static bool leveling_active_at_z(const float &rz) { + FORCE_INLINE static bool leveling_active_at_z(const_float_t rz) { return !z_fade_height || rz < z_fade_height; } #else - FORCE_INLINE static float fade_scaling_factor_for_z(const float&) { return 1; } + FORCE_INLINE static float fade_scaling_factor_for_z(const_float_t) { return 1; } - FORCE_INLINE static bool leveling_active_at_z(const float&) { return true; } + FORCE_INLINE static bool leveling_active_at_z(const_float_t) { return true; } #endif #if ENABLED(SKEW_CORRECTION) - FORCE_INLINE static void skew(float &cx, float &cy, const float &cz) { - if (WITHIN(cx, X_MIN_POS + 1, X_MAX_POS) && WITHIN(cy, Y_MIN_POS + 1, Y_MAX_POS)) { + FORCE_INLINE static void skew(float &cx, float &cy, const_float_t cz) { + if (COORDINATE_OKAY(cx, X_MIN_POS + 1, X_MAX_POS) && COORDINATE_OKAY(cy, Y_MIN_POS + 1, Y_MAX_POS)) { const float sx = cx - cy * skew_factor.xy - cz * (skew_factor.xz - (skew_factor.xy * skew_factor.yz)), sy = cy - cz * skew_factor.yz; - if (WITHIN(sx, X_MIN_POS, X_MAX_POS) && WITHIN(sy, Y_MIN_POS, Y_MAX_POS)) { + if (COORDINATE_OKAY(sx, X_MIN_POS, X_MAX_POS) && COORDINATE_OKAY(sy, Y_MIN_POS, Y_MAX_POS)) { cx = sx; cy = sy; } } } FORCE_INLINE static void skew(xyz_pos_t &raw) { skew(raw.x, raw.y, raw.z); } - FORCE_INLINE static void unskew(float &cx, float &cy, const float &cz) { - if (WITHIN(cx, X_MIN_POS, X_MAX_POS) && WITHIN(cy, Y_MIN_POS, Y_MAX_POS)) { + FORCE_INLINE static void unskew(float &cx, float &cy, const_float_t cz) { + if (COORDINATE_OKAY(cx, X_MIN_POS, X_MAX_POS) && COORDINATE_OKAY(cy, Y_MIN_POS, Y_MAX_POS)) { const float sx = cx + cy * skew_factor.xy + cz * skew_factor.xz, sy = cy + cz * skew_factor.yz; - if (WITHIN(sx, X_MIN_POS, X_MAX_POS) && WITHIN(sy, Y_MIN_POS, Y_MAX_POS)) { + if (COORDINATE_OKAY(sx, X_MIN_POS, X_MAX_POS) && COORDINATE_OKAY(sy, Y_MIN_POS, Y_MAX_POS)) { cx = sx; cy = sy; } } @@ -666,13 +722,9 @@ class Planner { * Returns true if movement was buffered, false otherwise */ static bool _buffer_steps(const xyze_long_t &target - #if HAS_POSITION_FLOAT - , const xyze_pos_t &target_float - #endif - #if HAS_DIST_MM_ARG - , const xyze_float_t &cart_dist_mm - #endif - , feedRate_t fr_mm_s, const uint8_t extruder, const float &millimeters=0.0 + OPTARG(HAS_POSITION_FLOAT, const xyze_pos_t &target_float) + OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm) + , feedRate_t fr_mm_s, const uint8_t extruder, const_float_t millimeters=0.0 ); /** @@ -687,28 +739,26 @@ class Planner { * * Returns true is movement is acceptable, false otherwise */ - static bool _populate_block(block_t * const block, bool split_move, - const xyze_long_t &target - #if HAS_POSITION_FLOAT - , const xyze_pos_t &target_float - #endif - #if HAS_DIST_MM_ARG - , const xyze_float_t &cart_dist_mm - #endif - , feedRate_t fr_mm_s, const uint8_t extruder, const float &millimeters=0.0 + static bool _populate_block(block_t * const block, bool split_move, const xyze_long_t &target + OPTARG(HAS_POSITION_FLOAT, const xyze_pos_t &target_float) + OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm) + , feedRate_t fr_mm_s, const uint8_t extruder, const_float_t millimeters=0.0 ); /** * Planner::buffer_sync_block - * Add a block to the buffer that just updates the position + * Add a block to the buffer that just updates the position or in + * case of LASER_SYNCHRONOUS_M106_M107 the fan pwm */ - static void buffer_sync_block(); + static void buffer_sync_block( + TERN_(LASER_SYNCHRONOUS_M106_M107, uint8_t sync_flag=BLOCK_FLAG_SYNC_POSITION) + ); #if IS_KINEMATIC private: // Allow do_homing_move to access internal functions, such as buffer_segment. - friend void do_homing_move(const AxisEnum, const float, const feedRate_t); + friend void do_homing_move(const AxisEnum, const float, const feedRate_t, const bool); #endif /** @@ -723,26 +773,11 @@ class Planner { * extruder - target extruder * millimeters - the length of the movement, if known */ - static bool buffer_segment(const float &a, const float &b, const float &c, const float &e - #if HAS_DIST_MM_ARG - , const xyze_float_t &cart_dist_mm - #endif - , const feedRate_t &fr_mm_s, const uint8_t extruder, const float &millimeters=0.0 + static bool buffer_segment(const abce_pos_t &abce + OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm) + , const_feedRate_t fr_mm_s, const uint8_t extruder=active_extruder, const_float_t millimeters=0.0 ); - FORCE_INLINE static bool buffer_segment(abce_pos_t &abce - #if HAS_DIST_MM_ARG - , const xyze_float_t &cart_dist_mm - #endif - , const feedRate_t &fr_mm_s, const uint8_t extruder, const float &millimeters=0.0 - ) { - return buffer_segment(abce.a, abce.b, abce.c, abce.e - #if HAS_DIST_MM_ARG - , cart_dist_mm - #endif - , fr_mm_s, extruder, millimeters); - } - public: /** @@ -750,30 +785,16 @@ class Planner { * The target is cartesian. It's translated to * delta/scara if needed. * - * rx,ry,rz,e - target position in mm or degrees + * cart - target position in mm or degrees * fr_mm_s - (target) speed of the move (mm/s) * extruder - target extruder * millimeters - the length of the movement, if known * inv_duration - the reciprocal if the duration of the movement, if known (kinematic only if feeedrate scaling is enabled) */ - static bool buffer_line(const float &rx, const float &ry, const float &rz, const float &e, const feedRate_t &fr_mm_s, const uint8_t extruder, const float millimeters=0.0 - #if ENABLED(SCARA_FEEDRATE_SCALING) - , const float &inv_duration=0.0 - #endif + static bool buffer_line(const xyze_pos_t &cart, const_feedRate_t fr_mm_s, const uint8_t extruder=active_extruder, const float millimeters=0.0 + OPTARG(SCARA_FEEDRATE_SCALING, const_float_t inv_duration=0.0) ); - FORCE_INLINE static bool buffer_line(const xyze_pos_t &cart, const feedRate_t &fr_mm_s, const uint8_t extruder, const float millimeters=0.0 - #if ENABLED(SCARA_FEEDRATE_SCALING) - , const float &inv_duration=0.0 - #endif - ) { - return buffer_line(cart.x, cart.y, cart.z, cart.e, fr_mm_s, extruder, millimeters - #if ENABLED(SCARA_FEEDRATE_SCALING) - , inv_duration - #endif - ); - } - #if ENABLED(DIRECT_STEPPING) static void buffer_page(const page_idx_t page_idx, const uint8_t extruder, const uint16_t num_steps); #endif @@ -791,9 +812,11 @@ class Planner { * * Clears previous speed values. */ - static void set_position_mm(const float &rx, const float &ry, const float &rz, const float &e); - FORCE_INLINE static void set_position_mm(const xyze_pos_t &cart) { set_position_mm(cart.x, cart.y, cart.z, cart.e); } - static void set_e_position_mm(const float &e); + static void set_position_mm(const xyze_pos_t &xyze); + + #if HAS_EXTRUDERS + static void set_e_position_mm(const_float_t e); + #endif /** * Set the planner.position and individual stepper positions. @@ -801,8 +824,7 @@ class Planner { * The supplied position is in machine space, and no additional * conversions are applied. */ - static void set_machine_position_mm(const float &a, const float &b, const float &c, const float &e); - FORCE_INLINE static void set_machine_position_mm(const abce_pos_t &abce) { set_machine_position_mm(abce.a, abce.b, abce.c, abce.e); } + static void set_machine_position_mm(const abce_pos_t &abce); /** * Get an axis position according to stepper position(s) @@ -811,12 +833,11 @@ class Planner { static float get_axis_position_mm(const AxisEnum axis); static inline abce_pos_t get_axis_positions_mm() { - const abce_pos_t out = { - get_axis_position_mm(A_AXIS), - get_axis_position_mm(B_AXIS), - get_axis_position_mm(C_AXIS), - get_axis_position_mm(E_AXIS) - }; + const abce_pos_t out = LOGICAL_AXIS_ARRAY( + get_axis_position_mm(E_AXIS), + get_axis_position_mm(A_AXIS), get_axis_position_mm(B_AXIS), get_axis_position_mm(C_AXIS), + get_axis_position_mm(I_AXIS), get_axis_position_mm(J_AXIS), get_axis_position_mm(K_AXIS) + ); return out; } @@ -829,7 +850,14 @@ class Planner { // a Full Shutdown is required, or when endstops are hit) static void quick_stop(); - // Called when an endstop is triggered. Causes the machine to stop inmediately + #if ENABLED(REALTIME_REPORTING_COMMANDS) + // Force a quick pause of the machine (e.g., when a pause is required in the middle of move). + // NOTE: Hard-stops will lose steps so encoders are highly recommended if using these! + static void quick_pause(); + static void quick_resume(); + #endif + + // Called when an endstop is triggered. Causes the machine to stop immediately static void endstop_triggered(const AxisEnum axis); // Triggered position of an axis in mm (not core-savvy) @@ -841,11 +869,9 @@ class Planner { // Wait for moves to finish and disable all steppers static void finish_and_disable(); - // Periodic tick to handle cleaning timeouts + // Periodic handler to manage the cleaning buffer counter // Called from the Temperature ISR at ~1kHz - static void tick() { - if (cleaning_buffer_counter) --cleaning_buffer_counter; - } + static void isr() { if (cleaning_buffer_counter) --cleaning_buffer_counter; } /** * Does the buffer have any blocks queued? @@ -877,11 +903,12 @@ class Planner { #endif #if ENABLED(AUTOTEMP) - static float autotemp_min, autotemp_max, autotemp_factor; + static celsius_t autotemp_min, autotemp_max; + static float autotemp_factor; static bool autotemp_enabled; - static void getHighESpeed(); - static void autotemp_M104_M109(); static void autotemp_update(); + static void autotemp_M104_M109(); + static void autotemp_task(); #endif #if HAS_LINEAR_E_JERK @@ -894,6 +921,14 @@ class Planner { private: + #if ENABLED(AUTOTEMP) + #if ENABLED(AUTOTEMP_PROPORTIONAL) + static void _autotemp_update_from_hotend(); + #else + static inline void _autotemp_update_from_hotend() {} + #endif + #endif + /** * Get the index of the next / previous block in the ring buffer */ @@ -904,7 +939,7 @@ class Planner { * Calculate the distance (not time) it takes to accelerate * from initial_rate to target_rate using the given acceleration: */ - static float estimate_acceleration_distance(const float &initial_rate, const float &target_rate, const float &accel) { + static float estimate_acceleration_distance(const_float_t initial_rate, const_float_t target_rate, const_float_t accel) { if (accel == 0) return 0; // accel was 0, set acceleration distance to 0 return (sq(target_rate) - sq(initial_rate)) / (accel * 2); } @@ -917,7 +952,7 @@ class Planner { * This is used to compute the intersection point between acceleration and deceleration * in cases where the "trapezoid" has no plateau (i.e., never reaches maximum speed) */ - static float intersection_distance(const float &initial_rate, const float &final_rate, const float &accel, const float &distance) { + static float intersection_distance(const_float_t initial_rate, const_float_t final_rate, const_float_t accel, const_float_t distance) { if (accel == 0) return 0; // accel was 0, set intersection distance to 0 return (accel * 2 * distance - sq(initial_rate) + sq(final_rate)) / (accel * 4); } @@ -927,7 +962,7 @@ class Planner { * to reach 'target_velocity_sqr' using 'acceleration' within a given * 'distance'. */ - static float max_allowable_speed_sqr(const float &accel, const float &target_velocity_sqr, const float &distance) { + static float max_allowable_speed_sqr(const_float_t accel, const_float_t target_velocity_sqr, const_float_t distance) { return target_velocity_sqr - 2 * accel * distance; } @@ -935,15 +970,15 @@ class Planner { /** * Calculate the speed reached given initial speed, acceleration and distance */ - static float final_speed(const float &initial_velocity, const float &accel, const float &distance) { + static float final_speed(const_float_t initial_velocity, const_float_t accel, const_float_t distance) { return SQRT(sq(initial_velocity) + 2 * accel * distance); } #endif - static void calculate_trapezoid_for_block(block_t* const block, const float &entry_factor, const float &exit_factor); + static void calculate_trapezoid_for_block(block_t * const block, const_float_t entry_factor, const_float_t exit_factor); - static void reverse_pass_kernel(block_t* const current, const block_t * const next); - static void forward_pass_kernel(const block_t * const previous, block_t* const current, uint8_t block_index); + static void reverse_pass_kernel(block_t * const current, const block_t * const next); + static void forward_pass_kernel(const block_t * const previous, block_t * const current, uint8_t block_index); static void reverse_pass(); static void forward_pass(); @@ -956,13 +991,13 @@ class Planner { FORCE_INLINE static void normalize_junction_vector(xyze_float_t &vector) { float magnitude_sq = 0; - LOOP_XYZE(idx) if (vector[idx]) magnitude_sq += sq(vector[idx]); + LOOP_LOGICAL_AXES(idx) if (vector[idx]) magnitude_sq += sq(vector[idx]); vector *= RSQRT(magnitude_sq); } - FORCE_INLINE static float limit_value_by_axis_maximum(const float &max_value, xyze_float_t &unit_vec) { + FORCE_INLINE static float limit_value_by_axis_maximum(const_float_t max_value, xyze_float_t &unit_vec) { float limit_value = max_value; - LOOP_XYZE(idx) { + LOOP_LOGICAL_AXES(idx) { if (unit_vec[idx]) { if (limit_value * ABS(unit_vec[idx]) > settings.max_acceleration_mm_per_s2[idx]) limit_value = ABS(settings.max_acceleration_mm_per_s2[idx] / unit_vec[idx]); @@ -974,6 +1009,6 @@ class Planner { #endif // !CLASSIC_JERK }; -#define PLANNER_XY_FEEDRATE() (_MIN(planner.settings.max_feedrate_mm_s[X_AXIS], planner.settings.max_feedrate_mm_s[Y_AXIS])) +#define PLANNER_XY_FEEDRATE() _MIN(planner.settings.max_feedrate_mm_s[X_AXIS], planner.settings.max_feedrate_mm_s[Y_AXIS]) extern Planner planner; diff --git a/Marlin/src/module/planner_bezier.cpp b/Marlin/src/module/planner_bezier.cpp index 02d878d5f51a..848906705fa2 100644 --- a/Marlin/src/module/planner_bezier.cpp +++ b/Marlin/src/module/planner_bezier.cpp @@ -43,7 +43,7 @@ #define SIGMA 0.1f // Compute the linear interpolation between two real numbers. -static inline float interp(const float &a, const float &b, const float &t) { return (1 - t) * a + t * b; } +static inline float interp(const_float_t a, const_float_t b, const_float_t t) { return (1 - t) * a + t * b; } /** * Compute a Bézier curve using the De Casteljau's algorithm (see @@ -51,7 +51,7 @@ static inline float interp(const float &a, const float &b, const float &t) { ret * easy to code and has good numerical stability (very important, * since Arudino works with limited precision real numbers). */ -static inline float eval_bezier(const float &a, const float &b, const float &c, const float &d, const float &t) { +static inline float eval_bezier(const_float_t a, const_float_t b, const_float_t c, const_float_t d, const_float_t t) { const float iab = interp(a, b, t), ibc = interp(b, c, t), icd = interp(c, d, t), @@ -64,7 +64,7 @@ static inline float eval_bezier(const float &a, const float &b, const float &c, * We approximate Euclidean distance with the sum of the coordinates * offset (so-called "norm 1"), which is quicker to compute. */ -static inline float dist1(const float &x1, const float &y1, const float &x2, const float &y2) { return ABS(x1 - x2) + ABS(y1 - y2); } +static inline float dist1(const_float_t x1, const_float_t y1, const_float_t x2, const_float_t y2) { return ABS(x1 - x2) + ABS(y1 - y2); } /** * The algorithm for computing the step is loosely based on the one in Kig @@ -109,7 +109,7 @@ void cubic_b_spline( const xyze_pos_t &position, // current position const xyze_pos_t &target, // target position const xy_pos_t (&offsets)[2], // a pair of offsets - const feedRate_t &scaled_fr_mm_s, // mm/s scaled by feedrate % + const_feedRate_t scaled_fr_mm_s, // mm/s scaled by feedrate % const uint8_t extruder ) { // Absolute first and second control points are recovered. @@ -181,11 +181,15 @@ void cubic_b_spline( t = new_t; // Compute and send new position - xyze_pos_t new_bez = { - new_pos0, new_pos1, - interp(position.z, target.z, t), // FIXME. These two are wrong, since the parameter t is - interp(position.e, target.e, t) // not linear in the distance. - }; + xyze_pos_t new_bez = LOGICAL_AXIS_ARRAY( + interp(position.e, target.e, t), // FIXME. Wrong, since t is not linear in the distance. + new_pos0, + new_pos1, + interp(position.z, target.z, t), // FIXME. Wrong, since t is not linear in the distance. + interp(position.i, target.i, t), // FIXME. Wrong, since t is not linear in the distance. + interp(position.j, target.j, t), // FIXME. Wrong, since t is not linear in the distance. + interp(position.k, target.k, t) // FIXME. Wrong, since t is not linear in the distance. + ); apply_motion_limits(new_bez); bez_target = new_bez; diff --git a/Marlin/src/module/planner_bezier.h b/Marlin/src/module/planner_bezier.h index 72048c42739a..eb48cf5e1a86 100644 --- a/Marlin/src/module/planner_bezier.h +++ b/Marlin/src/module/planner_bezier.h @@ -33,6 +33,6 @@ void cubic_b_spline( const xyze_pos_t &position, // current position const xyze_pos_t &target, // target position const xy_pos_t (&offsets)[2], // a pair of offsets - const feedRate_t &scaled_fr_mm_s, // mm/s scaled by feedrate % + const_feedRate_t scaled_fr_mm_s, // mm/s scaled by feedrate % const uint8_t extruder ); diff --git a/Marlin/src/module/printcounter.cpp b/Marlin/src/module/printcounter.cpp index 86aedf2161a9..4c5f1fc782e0 100644 --- a/Marlin/src/module/printcounter.cpp +++ b/Marlin/src/module/printcounter.cpp @@ -41,6 +41,11 @@ Stopwatch print_job_timer; // Global Print Job Timer instance #include "../libs/buzzer.h" #endif +#if PRINTCOUNTER_SYNC + #include "../module/planner.h" + #warning "To prevent step loss, motion will pause for PRINTCOUNTER auto-save." +#endif + // Service intervals #if HAS_SERVICE_INTERVALS #if SERVICE_INTERVAL_1 > 0 @@ -114,7 +119,7 @@ void PrintCounter::initStats() { inline bool _service_warn(const char * const msg) { _print_divider(); SERIAL_ECHO_START(); - serialprintPGM(msg); + SERIAL_ECHOPGM_P(msg); SERIAL_ECHOLNPGM("!"); _print_divider(); return true; @@ -160,6 +165,8 @@ void PrintCounter::saveStats() { // Refuses to save data if object is not loaded if (!isLoaded()) return; + TERN_(PRINTCOUNTER_SYNC, planner.synchronize()); + // Saves the struct to EEPROM persistentStore.access_start(); persistentStore.write_data(address + sizeof(uint8_t), (uint8_t*)&data, sizeof(printStatistics)); @@ -171,13 +178,13 @@ void PrintCounter::saveStats() { #if HAS_SERVICE_INTERVALS inline void _service_when(char buffer[], const char * const msg, const uint32_t when) { SERIAL_ECHOPGM(STR_STATS); - serialprintPGM(msg); + SERIAL_ECHOPGM_P(msg); SERIAL_ECHOLNPAIR(" in ", duration_t(when).toString(buffer)); } #endif void PrintCounter::showStats() { - char buffer[21]; + char buffer[22]; SERIAL_ECHOPGM(STR_STATS); SERIAL_ECHOLNPAIR( @@ -224,9 +231,12 @@ void PrintCounter::tick() { millis_t now = millis(); - static uint32_t update_next; // = 0 + static millis_t update_next; // = 0 if (ELAPSED(now, update_next)) { + update_next = now + updateInterval; + TERN_(DEBUG_PRINTCOUNTER, debug(PSTR("tick"))); + millis_t delta = deltaDuration(); data.printTime += delta; @@ -239,15 +249,15 @@ void PrintCounter::tick() { #if SERVICE_INTERVAL_3 > 0 data.nextService3 -= _MIN(delta, data.nextService3); #endif - - update_next = now + updateInterval * 1000; } - static uint32_t eeprom_next; // = 0 - if (ELAPSED(now, eeprom_next)) { - eeprom_next = now + saveInterval * 1000; - saveStats(); - } + #if PRINTCOUNTER_SAVE_INTERVAL > 0 + static millis_t eeprom_next; // = 0 + if (ELAPSED(now, eeprom_next)) { + eeprom_next = now + saveInterval; + saveStats(); + } + #endif } // @Override @@ -267,21 +277,20 @@ bool PrintCounter::start() { return false; } -// @Override -bool PrintCounter::stop() { +bool PrintCounter::_stop(const bool completed) { TERN_(DEBUG_PRINTCOUNTER, debug(PSTR("stop"))); - if (super::stop()) { - data.finishedPrints++; + const bool did_stop = super::stop(); + if (did_stop) { data.printTime += deltaDuration(); - - if (duration() > data.longestPrint) - data.longestPrint = duration(); - - saveStats(); - return true; + if (completed) { + data.finishedPrints++; + if (duration() > data.longestPrint) + data.longestPrint = duration(); + } } - else return false; + saveStats(); + return did_stop; } // @Override @@ -310,6 +319,7 @@ void PrintCounter::reset() { } bool PrintCounter::needsService(const int index) { + if (!loaded) loadStats(); switch (index) { #if SERVICE_INTERVAL_1 > 0 case 1: return data.nextService1 == 0; @@ -331,7 +341,7 @@ void PrintCounter::reset() { void PrintCounter::debug(const char func[]) { if (DEBUGGING(INFO)) { SERIAL_ECHOPGM("PrintCounter::"); - serialprintPGM(func); + SERIAL_ECHOPGM_P(func); SERIAL_ECHOLNPGM("()"); } } diff --git a/Marlin/src/module/printcounter.h b/Marlin/src/module/printcounter.h index 66d8cbb7b38e..4deae45a656d 100644 --- a/Marlin/src/module/printcounter.h +++ b/Marlin/src/module/printcounter.h @@ -71,19 +71,18 @@ class PrintCounter: public Stopwatch { * @brief Interval in seconds between counter updates * @details This const value defines what will be the time between each * accumulator update. This is different from the EEPROM save interval. - * - * @note The max value for this option is 60(s), otherwise integer - * overflow will happen. */ - static constexpr uint16_t updateInterval = 10; + static constexpr millis_t updateInterval = SEC_TO_MS(10); - /** - * @brief Interval in seconds between EEPROM saves - * @details This const value defines what will be the time between each - * EEPROM save cycle, the development team recommends to set this value - * no lower than 3600 secs (1 hour). - */ - static constexpr uint16_t saveInterval = 3600; + #if PRINTCOUNTER_SAVE_INTERVAL > 0 + /** + * @brief Interval in seconds between EEPROM saves + * @details This const value defines what will be the time between each + * EEPROM save cycle, the development team recommends to set this value + * no lower than 3600 secs (1 hour). + */ + static constexpr millis_t saveInterval = MIN_TO_MS(PRINTCOUNTER_SAVE_INTERVAL); + #endif /** * @brief Timestamp of the last call to deltaDuration() @@ -176,7 +175,10 @@ class PrintCounter: public Stopwatch { * The following functions are being overridden */ static bool start(); - static bool stop(); + static bool _stop(const bool completed); + static inline bool stop() { return _stop(true); } + static inline bool abort() { return _stop(false); } + static void reset(); #if HAS_SERVICE_INTERVALS diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index defc22b1fe8e..ded5d438934b 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -36,9 +36,9 @@ #include "endstops.h" #include "../gcode/gcode.h" -#include "../lcd/ultralcd.h" +#include "../lcd/marlinui.h" -#include "../MarlinCore.h" // for stop(), disable_e_steppers, wait_for_user +#include "../MarlinCore.h" // for stop(), disable_e_steppers(), wait_for_user_response() #if HAS_LEVELING #include "../feature/bedlevel/bedlevel.h" @@ -68,12 +68,12 @@ #include "servo.h" #endif -#if ENABLED(SENSORLESS_PROBING) +#if EITHER(SENSORLESS_PROBING, SENSORLESS_HOMING) #include "stepper.h" #include "../feature/tmc_util.h" #endif -#if QUIET_PROBING +#if HAS_QUIET_PROBING #include "stepper/indirection.h" #endif @@ -89,7 +89,11 @@ Probe probe; xyz_pos_t Probe::offset; // Initialized by settings.load() #if HAS_PROBE_XY_OFFSET - const xyz_pos_t &Probe::offset_xy = Probe::offset; + const xy_pos_t &Probe::offset_xy = Probe::offset; +#endif + +#if ENABLED(SENSORLESS_PROBING) + Probe::sense_bool_t Probe::test_sensitivity; #endif #if ENABLED(Z_PROBE_SLED) @@ -152,8 +156,8 @@ xyz_pos_t Probe::offset; // Initialized by settings.load() inline void run_stow_moves_script() { const xyz_pos_t oldpos = current_position; endstops.enable_z_probe(false); - do_blocking_move_to_z(TOUCH_MI_RETRACT_Z, MMM_TO_MMS(HOMING_FEEDRATE_Z)); - do_blocking_move_to(oldpos, MMM_TO_MMS(HOMING_FEEDRATE_Z)); + do_blocking_move_to_z(TOUCH_MI_RETRACT_Z, homing_feedrate(Z_AXIS)); + do_blocking_move_to(oldpos, homing_feedrate(Z_AXIS)); } #elif ENABLED(Z_PROBE_ALLEN_KEY) @@ -236,25 +240,33 @@ xyz_pos_t Probe::offset; // Initialized by settings.load() #endif // Z_PROBE_ALLEN_KEY -#if QUIET_PROBING +#if HAS_QUIET_PROBING - void Probe::set_probing_paused(const bool p) { - TERN_(PROBING_HEATERS_OFF, thermalManager.pause(p)); - TERN_(PROBING_FANS_OFF, thermalManager.set_fans_paused(p)); - #if ENABLED(PROBING_STEPPERS_OFF) - disable_e_steppers(); - #if NONE(DELTA, HOME_AFTER_DEACTIVATE) - DISABLE_AXIS_X(); DISABLE_AXIS_Y(); - #endif + #ifndef DELAY_BEFORE_PROBING + #define DELAY_BEFORE_PROBING 25 + #endif + + void Probe::set_probing_paused(const bool dopause) { + TERN_(PROBING_HEATERS_OFF, thermalManager.pause_heaters(dopause)); + TERN_(PROBING_FANS_OFF, thermalManager.set_fans_paused(dopause)); + TERN_(PROBING_ESTEPPERS_OFF, if (dopause) disable_e_steppers()); + #if ENABLED(PROBING_STEPPERS_OFF) && DISABLED(DELTA) + static uint8_t old_trusted; + if (dopause) { + old_trusted = axis_trusted; + DISABLE_AXIS_X(); + DISABLE_AXIS_Y(); + } + else { + if (TEST(old_trusted, X_AXIS)) ENABLE_AXIS_X(); + if (TEST(old_trusted, Y_AXIS)) ENABLE_AXIS_Y(); + axis_trusted = old_trusted; + } #endif - if (p) safe_delay(25 - #if DELAY_BEFORE_PROBING > 25 - - 25 + DELAY_BEFORE_PROBING - #endif - ); + if (dopause) safe_delay(_MAX(DELAY_BEFORE_PROBING, 25)); } -#endif // QUIET_PROBING +#endif // HAS_QUIET_PROBING /** * Raise Z to a minimum height to make room for a probe to move @@ -270,13 +282,7 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { #if ENABLED(PAUSE_BEFORE_DEPLOY_STOW) do { #if ENABLED(PAUSE_PROBE_DEPLOY_WHEN_TRIGGERED) - if (deploy == ( - #if HAS_CUSTOM_PROBE_PIN - READ(Z_MIN_PROBE_PIN) == Z_MIN_PROBE_ENDSTOP_INVERTING - #else - READ(Z_MIN_PIN) == Z_MIN_ENDSTOP_INVERTING - #endif - )) break; + if (deploy != PROBE_TRIGGERED()) break; #endif BUZZ(100, 659); @@ -285,8 +291,7 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { PGM_P const ds_str = deploy ? GET_TEXT(MSG_MANUAL_DEPLOY) : GET_TEXT(MSG_MANUAL_STOW); ui.return_to_status(); // To display the new status message ui.set_status_P(ds_str, 99); - serialprintPGM(ds_str); - SERIAL_EOL(); + SERIAL_ECHOLNPGM_P(ds_str); TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Stow Probe"), CONTINUE_STR)); TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("Stow Probe"))); @@ -331,6 +336,59 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { #endif } +#if EITHER(PREHEAT_BEFORE_PROBING, PREHEAT_BEFORE_LEVELING) + + #if ENABLED(PREHEAT_BEFORE_PROBING) + #ifndef PROBING_NOZZLE_TEMP + #define PROBING_NOZZLE_TEMP 0 + #endif + #ifndef PROBING_BED_TEMP + #define PROBING_BED_TEMP 0 + #endif + #endif + + /** + * Do preheating as required before leveling or probing. + * - If a preheat input is higher than the current target, raise the target temperature. + * - If a preheat input is higher than the current temperature, wait for stabilization. + */ + void Probe::preheat_for_probing(const celsius_t hotend_temp, const celsius_t bed_temp) { + #if HAS_HOTEND && (PROBING_NOZZLE_TEMP || LEVELING_NOZZLE_TEMP) + #define WAIT_FOR_NOZZLE_HEAT + #endif + #if HAS_HEATED_BED && (PROBING_BED_TEMP || LEVELING_BED_TEMP) + #define WAIT_FOR_BED_HEAT + #endif + + DEBUG_ECHOPGM("Preheating "); + + #if ENABLED(WAIT_FOR_NOZZLE_HEAT) + const celsius_t hotendPreheat = hotend_temp > thermalManager.degTargetHotend(0) ? hotend_temp : 0; + if (hotendPreheat) { + DEBUG_ECHOPAIR("hotend (", hotendPreheat, ")"); + thermalManager.setTargetHotend(hotendPreheat, 0); + } + #elif ENABLED(WAIT_FOR_BED_HEAT) + constexpr celsius_t hotendPreheat = 0; + #endif + + #if ENABLED(WAIT_FOR_BED_HEAT) + const celsius_t bedPreheat = bed_temp > thermalManager.degTargetBed() ? bed_temp : 0; + if (bedPreheat) { + if (hotendPreheat) DEBUG_ECHOPGM(" and "); + DEBUG_ECHOPAIR("bed (", bedPreheat, ")"); + thermalManager.setTargetBed(bedPreheat); + } + #endif + + DEBUG_EOL(); + + TERN_(WAIT_FOR_NOZZLE_HEAT, if (hotend_temp > thermalManager.wholeDegHotend(0) + (TEMP_WINDOW)) thermalManager.wait_for_hotend(0)); + TERN_(WAIT_FOR_BED_HEAT, if (bed_temp > thermalManager.wholeDegBed() + (TEMP_BED_WINDOW)) thermalManager.wait_for_bed_heating()); + } + +#endif + /** * Attempt to deploy or stow the probe * @@ -349,19 +407,12 @@ bool Probe::set_deployed(const bool deploy) { // 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) - const bool deploy_stow_condition = deploy; - #else - constexpr bool deploy_stow_condition = true; - #endif - - // For beds that fall when Z is powered off only raise for trusted Z - #if ENABLED(UNKNOWN_Z_NO_RAISE) - const bool unknown_condition = TEST(axis_known_position, Z_AXIS); + const bool z_raise_wanted = deploy; #else - constexpr float unknown_condition = true; + constexpr bool z_raise_wanted = true; #endif - if (deploy_stow_condition && unknown_condition) + 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) @@ -375,23 +426,15 @@ bool Probe::set_deployed(const bool deploy) { const xy_pos_t old_xy = current_position; #if ENABLED(PROBE_TRIGGERED_WHEN_STOWED_TEST) - #if HAS_CUSTOM_PROBE_PIN - #define PROBE_STOWED() (READ(Z_MIN_PROBE_PIN) != Z_MIN_PROBE_ENDSTOP_INVERTING) - #else - #define PROBE_STOWED() (READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING) - #endif - #endif - - #ifdef PROBE_STOWED // Only deploy/stow if needed - if (PROBE_STOWED() == deploy) { + if (PROBE_TRIGGERED() == deploy) { if (!deploy) endstops.enable_z_probe(false); // Switch off triggered when stowed probes early // otherwise an Allen-Key probe can't be stowed. probe_specific_action(deploy); } - if (PROBE_STOWED() == deploy) { // Unchanged after deploy/stow action? + if (PROBE_TRIGGERED() == deploy) { // Unchanged after deploy/stow action? if (IsRunning()) { SERIAL_ERROR_MSG("Z-Probe failed"); LCD_ALERTMESSAGEPGM_P(PSTR("Err: ZPROBE")); @@ -406,6 +449,9 @@ bool Probe::set_deployed(const bool deploy) { #endif + // If preheating is required before any probing... + TERN_(PREHEAT_BEFORE_PROBING, if (deploy) preheat_for_probing(PROBING_NOZZLE_TEMP, PROBING_BED_TEMP)); + do_blocking_move_to(old_xy); endstops.enable_z_probe(deploy); return false; @@ -429,29 +475,32 @@ bool Probe::set_deployed(const bool deploy) { * * @return TRUE if the probe failed to trigger. */ -bool Probe::probe_down_to_z(const float z, const feedRate_t fr_mm_s) { +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) thermalManager.wait_for_bed_heating(); #endif - #if ENABLED(BLTOUCH) && DISABLED(BLTOUCH_HS_MODE) - if (bltouch.deploy()) return true; // DEPLOY in LOW SPEED MODE on every probe action + #if BOTH(HAS_TEMP_HOTEND, WAIT_FOR_HOTEND) + thermalManager.wait_for_hotend_heating(active_extruder); #endif + if (TERN0(BLTOUCH_SLOW_MODE, bltouch.deploy())) return true; // Deploy in LOW SPEED MODE on every probe action + // Disable stealthChop if used. Enable diag1 pin on driver. #if ENABLED(SENSORLESS_PROBING) sensorless_t stealth_states { false }; #if ENABLED(DELTA) - stealth_states.x = tmc_enable_stallguard(stepperX); - stealth_states.y = tmc_enable_stallguard(stepperY); + if (probe.test_sensitivity.x) stealth_states.x = tmc_enable_stallguard(stepperX); // Delta watches all DIAG pins for a stall + if (probe.test_sensitivity.y) stealth_states.y = tmc_enable_stallguard(stepperY); #endif - stealth_states.z = tmc_enable_stallguard(stepperZ); + if (probe.test_sensitivity.z) stealth_states.z = tmc_enable_stallguard(stepperZ); // All machines will check Z-DIAG for stall endstops.enable(true); + set_homing_current(true); // The "homing" current also applies to probing #endif - TERN_(QUIET_PROBING, set_probing_paused(true)); + TERN_(HAS_QUIET_PROBING, set_probing_paused(true)); // Move down until the probe is triggered do_blocking_move_to_z(z, fr_mm_s); @@ -459,27 +508,27 @@ bool Probe::probe_down_to_z(const float z, const feedRate_t fr_mm_s) { // Check to see if the probe was triggered const bool probe_triggered = #if BOTH(DELTA, SENSORLESS_PROBING) - endstops.trigger_state() & (_BV(X_MIN) | _BV(Y_MIN) | _BV(Z_MIN)) + endstops.trigger_state() & (_BV(X_MAX) | _BV(Y_MAX) | _BV(Z_MAX)) #else - TEST(endstops.trigger_state(), TERN(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN, Z_MIN, Z_MIN_PROBE)) + TEST(endstops.trigger_state(), Z_MIN_PROBE) #endif ; - TERN_(QUIET_PROBING, set_probing_paused(false)); + TERN_(HAS_QUIET_PROBING, set_probing_paused(false)); // Re-enable stealthChop if used. Disable diag1 pin on driver. #if ENABLED(SENSORLESS_PROBING) endstops.not_homing(); #if ENABLED(DELTA) - tmc_disable_stallguard(stepperX, stealth_states.x); - tmc_disable_stallguard(stepperY, stealth_states.y); + if (probe.test_sensitivity.x) tmc_disable_stallguard(stepperX, stealth_states.x); + if (probe.test_sensitivity.y) tmc_disable_stallguard(stepperY, stealth_states.y); #endif - tmc_disable_stallguard(stepperZ, stealth_states.z); + if (probe.test_sensitivity.z) tmc_disable_stallguard(stepperZ, stealth_states.z); + set_homing_current(false); #endif - #if ENABLED(BLTOUCH) && DISABLED(BLTOUCH_HS_MODE) - if (probe_triggered && bltouch.stow()) return true; // STOW in LOW SPEED MODE on trigger on every probe action - #endif + if (probe_triggered && TERN0(BLTOUCH_SLOW_MODE, bltouch.stow())) // Stow in LOW SPEED MODE on every trigger + return true; // Clear endstop flags endstops.hit_on_purpose(); @@ -493,6 +542,43 @@ bool Probe::probe_down_to_z(const float z, const feedRate_t fr_mm_s) { return !probe_triggered; } +#if ENABLED(PROBE_TARE) + + /** + * @brief Init the tare pin + * + * @details Init tare pin to ON state for a strain gauge, otherwise OFF + */ + void Probe::tare_init() { + OUT_WRITE(PROBE_TARE_PIN, !PROBE_TARE_STATE); + } + + /** + * @brief Tare the Z probe + * + * @details Signal to the probe to tare itself + * + * @return TRUE if the tare cold not be completed + */ + bool Probe::tare() { + #if BOTH(PROBE_ACTIVATION_SWITCH, PROBE_TARE_ONLY_WHILE_INACTIVE) + if (endstops.probe_switch_activated()) { + SERIAL_ECHOLNPGM("Cannot tare an active probe"); + return true; + } + #endif + + SERIAL_ECHOLNPGM("Taring probe"); + WRITE(PROBE_TARE_PIN, PROBE_TARE_STATE); + delay(PROBE_TARE_TIME); + WRITE(PROBE_TARE_PIN, !PROBE_TARE_STATE); + delay(PROBE_TARE_DELAY); + + endstops.hit_on_purpose(); + return false; + } +#endif + /** * @brief Probe at the current XY (possibly more than once) to find the bed Z. * @@ -504,13 +590,16 @@ bool Probe::probe_down_to_z(const float z, const feedRate_t fr_mm_s) { float Probe::run_z_probe(const bool sanity_check/*=true*/) { DEBUG_SECTION(log_probe, "Probe::run_z_probe", DEBUGGING(LEVELING)); - auto try_to_probe = [&](PGM_P const plbl, const float &z_probe_low_point, const feedRate_t fr_mm_s, const bool scheck, const float clearance) { + auto try_to_probe = [&](PGM_P const plbl, const_float_t z_probe_low_point, const feedRate_t fr_mm_s, const bool scheck, const float clearance) -> bool { + // Tare the probe, if supported + if (TERN0(PROBE_TARE, tare())) return true; + // Do a first probe at the fast speed const bool probe_fail = probe_down_to_z(z_probe_low_point, fr_mm_s), // No probe trigger? early_fail = (scheck && current_position.z > -offset.z + clearance); // Probe triggered too high? #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING) && (probe_fail || early_fail)) { - DEBUG_PRINT_P(plbl); + DEBUG_ECHOPGM_P(plbl); DEBUG_ECHOPGM(" Probe fail! -"); if (probe_fail) DEBUG_ECHOPGM(" No trigger."); if (early_fail) DEBUG_ECHOPGM(" Triggered early."); @@ -524,13 +613,16 @@ float Probe::run_z_probe(const bool sanity_check/*=true*/) { // Stop the probe before it goes too low to prevent damage. // If Z isn't known then probe to -10mm. - const float z_probe_low_point = TEST(axis_known_position, Z_AXIS) ? -offset.z + Z_PROBE_LOW_POINT : -10.0; + const float z_probe_low_point = axis_is_trusted(Z_AXIS) ? -offset.z + Z_PROBE_LOW_POINT : -10.0; // Double-probing does a fast probe followed by a slow probe #if TOTAL_PROBING == 2 + // Attempt to tare the probe + if (TERN0(PROBE_TARE, tare())) return NAN; + // Do a first probe at the fast speed - if (try_to_probe(PSTR("FAST"), z_probe_low_point, MMM_TO_MMS(Z_PROBE_SPEED_FAST), + 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 = current_position.z; @@ -538,17 +630,17 @@ float Probe::run_z_probe(const bool sanity_check/*=true*/) { if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("1st Probe Z:", first_probe_z); // Raise to give the probe clearance - do_blocking_move_to_z(current_position.z + Z_CLEARANCE_MULTI_PROBE, MMM_TO_MMS(Z_PROBE_SPEED_FAST)); + do_blocking_move_to_z(current_position.z + Z_CLEARANCE_MULTI_PROBE, z_probe_fast_mm_s); - #elif Z_PROBE_SPEED_FAST != Z_PROBE_SPEED_SLOW + #elif Z_PROBE_FEEDRATE_FAST != Z_PROBE_FEEDRATE_SLOW // 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); if (current_position.z > z) { // Probe down fast. If the probe never triggered, raise for probe clearance - if (!probe_down_to_z(z, MMM_TO_MMS(Z_PROBE_SPEED_FAST))) - do_blocking_move_to_z(current_position.z + Z_CLEARANCE_BETWEEN_PROBES, MMM_TO_MMS(Z_PROBE_SPEED_FAST)); + if (!probe_down_to_z(z, z_probe_fast_mm_s)) + do_blocking_move_to_z(current_position.z + Z_CLEARANCE_BETWEEN_PROBES, z_probe_fast_mm_s); } #endif @@ -567,8 +659,11 @@ float Probe::run_z_probe(const bool sanity_check/*=true*/) { ) #endif { + // If the probe won't tare, return + if (TERN0(PROBE_TARE, tare())) return true; + // Probe downward slowly to find the bed - if (try_to_probe(PSTR("SLOW"), z_probe_low_point, MMM_TO_MMS(Z_PROBE_SPEED_SLOW), + if (try_to_probe(PSTR("SLOW"), z_probe_low_point, MMM_TO_MMS(Z_PROBE_FEEDRATE_SLOW), sanity_check, Z_CLEARANCE_MULTI_PROBE) ) return NAN; TERN_(MEASURE_BACKLASH_WHEN_PROBING, backlash.measure_with_probe()); @@ -596,7 +691,7 @@ float Probe::run_z_probe(const bool sanity_check/*=true*/) { #if EXTRA_PROBING > 0 < TOTAL_PROBING - 1 #endif - ) do_blocking_move_to_z(z + Z_CLEARANCE_MULTI_PROBE, MMM_TO_MMS(Z_PROBE_SPEED_FAST)); + ) do_blocking_move_to_z(z + Z_CLEARANCE_MULTI_PROBE, z_probe_fast_mm_s); #endif } @@ -650,14 +745,14 @@ float Probe::run_z_probe(const bool sanity_check/*=true*/) { * - Raise to the BETWEEN height * - Return the probed Z position */ -float Probe::probe_at_point(const float &rx, const float &ry, const ProbePtRaise raise_after/*=PROBE_PT_NONE*/, const uint8_t verbose_level/*=0*/, const bool probe_relative/*=true*/, const bool sanity_check/*=true*/) { +float Probe::probe_at_point(const_float_t rx, const_float_t ry, const ProbePtRaise raise_after/*=PROBE_PT_NONE*/, const uint8_t verbose_level/*=0*/, const bool probe_relative/*=true*/, const bool sanity_check/*=true*/) { DEBUG_SECTION(log_probe, "Probe::probe_at_point", DEBUGGING(LEVELING)); if (DEBUGGING(LEVELING)) { DEBUG_ECHOLNPAIR( "...(", LOGICAL_X_POSITION(rx), ", ", LOGICAL_Y_POSITION(ry), ", ", raise_after == PROBE_PT_RAISE ? "raise" : raise_after == PROBE_PT_STOW ? "stow" : "none", - ", ", int(verbose_level), + ", ", verbose_level, ", ", probe_relative ? "probe" : "nozzle", "_relative)" ); DEBUG_POS("", current_position); @@ -667,8 +762,8 @@ float Probe::probe_at_point(const float &rx, const float &ry, const ProbePtRaise if (bltouch.triggered()) bltouch._reset(); #endif - // TODO: Adapt for SCARA, where the offset rotates - xyz_pos_t npos = { rx, ry }; + // On delta keep Z below clip height or do_blocking_move_to will abort + xyz_pos_t npos = { rx, ry, _MIN(TERN(DELTA, delta_clip_start_height, current_position.z), current_position.z) }; if (probe_relative) { // The given position is in terms of the probe if (!can_reach(npos)) { if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Position Not Reachable"); @@ -678,27 +773,15 @@ float Probe::probe_at_point(const float &rx, const float &ry, const ProbePtRaise } else if (!position_is_reachable(npos)) return NAN; // The given position is in terms of the nozzle - npos.z = - #if ENABLED(DELTA) - // Move below clip height or xy move will be aborted by do_blocking_move_to - _MIN(current_position.z, delta_clip_start_height) - #else - current_position.z - #endif - ; - - const float old_feedrate_mm_s = feedrate_mm_s; - feedrate_mm_s = XY_PROBE_FEEDRATE_MM_S; - // Move the probe to the starting XYZ - do_blocking_move_to(npos); + do_blocking_move_to(npos, feedRate_t(XY_PROBE_FEEDRATE_MM_S)); float measured_z = NAN; if (!deploy()) measured_z = run_z_probe(sanity_check) + offset.z; if (!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), MMM_TO_MMS(Z_PROBE_SPEED_FAST)); + do_blocking_move_to_z(current_position.z + (big_raise ? 25 : Z_CLEARANCE_BETWEEN_PROBES), z_probe_fast_mm_s); else if (raise_after == PROBE_PT_STOW) if (stow()) measured_z = NAN; // Error on stow? @@ -706,8 +789,6 @@ float Probe::probe_at_point(const float &rx, const float &ry, const ProbePtRaise SERIAL_ECHOLNPAIR("Bed X: ", LOGICAL_X_POSITION(rx), " Y: ", LOGICAL_Y_POSITION(ry), " Z: ", measured_z); } - feedrate_mm_s = old_feedrate_mm_s; - if (isnan(measured_z)) { stow(); LCD_MESSAGEPGM(MSG_LCD_PROBING_FAILED); @@ -735,4 +816,95 @@ float Probe::probe_at_point(const float &rx, const float &ry, const ProbePtRaise #endif // HAS_Z_SERVO_PROBE +#if EITHER(SENSORLESS_PROBING, SENSORLESS_HOMING) + + sensorless_t stealth_states { false }; + + /** + * Disable stealthChop if used. Enable diag1 pin on driver. + */ + void Probe::enable_stallguard_diag1() { + #if ENABLED(SENSORLESS_PROBING) + #if ENABLED(DELTA) + stealth_states.x = tmc_enable_stallguard(stepperX); + stealth_states.y = tmc_enable_stallguard(stepperY); + #endif + stealth_states.z = tmc_enable_stallguard(stepperZ); + endstops.enable(true); + #endif + } + + /** + * Re-enable stealthChop if used. Disable diag1 pin on driver. + */ + void Probe::disable_stallguard_diag1() { + #if ENABLED(SENSORLESS_PROBING) + endstops.not_homing(); + #if ENABLED(DELTA) + tmc_disable_stallguard(stepperX, stealth_states.x); + tmc_disable_stallguard(stepperY, stealth_states.y); + #endif + tmc_disable_stallguard(stepperZ, stealth_states.z); + #endif + } + + /** + * Change the current in the TMC drivers to N##_CURRENT_HOME. And we save the current configuration of each TMC driver. + */ + void Probe::set_homing_current(const bool onoff) { + #define HAS_CURRENT_HOME(N) (defined(N##_CURRENT_HOME) && N##_CURRENT_HOME != N##_CURRENT) + #if HAS_CURRENT_HOME(X) || HAS_CURRENT_HOME(Y) || HAS_CURRENT_HOME(Z) + #if ENABLED(DELTA) + static int16_t saved_current_X, saved_current_Y; + #endif + #if HAS_CURRENT_HOME(Z) + static int16_t saved_current_Z; + #endif + #if ((ENABLED(DELTA) && (HAS_CURRENT_HOME(X) || HAS_CURRENT_HOME(Y))) || HAS_CURRENT_HOME(Z)) + auto debug_current_on = [](PGM_P const s, const int16_t a, const int16_t b) { + if (DEBUGGING(LEVELING)) { DEBUG_ECHOPGM_P(s); DEBUG_ECHOLNPAIR(" current: ", a, " -> ", b); } + }; + #endif + if (onoff) { + #if ENABLED(DELTA) + #if HAS_CURRENT_HOME(X) + saved_current_X = stepperX.getMilliamps(); + stepperX.rms_current(X_CURRENT_HOME); + debug_current_on(PSTR("X"), saved_current_X, X_CURRENT_HOME); + #endif + #if HAS_CURRENT_HOME(Y) + saved_current_Y = stepperY.getMilliamps(); + stepperY.rms_current(Y_CURRENT_HOME); + debug_current_on(PSTR("Y"), saved_current_Y, Y_CURRENT_HOME); + #endif + #endif + #if HAS_CURRENT_HOME(Z) + saved_current_Z = stepperZ.getMilliamps(); + stepperZ.rms_current(Z_CURRENT_HOME); + debug_current_on(PSTR("Z"), saved_current_Z, Z_CURRENT_HOME); + #endif + TERN_(IMPROVE_HOMING_RELIABILITY, planner.enable_stall_prevention(true)); + } + else { + #if ENABLED(DELTA) + #if HAS_CURRENT_HOME(X) + stepperX.rms_current(saved_current_X); + debug_current_on(PSTR("X"), X_CURRENT_HOME, saved_current_X); + #endif + #if HAS_CURRENT_HOME(Y) + stepperY.rms_current(saved_current_Y); + debug_current_on(PSTR("Y"), Y_CURRENT_HOME, saved_current_Y); + #endif + #endif + #if HAS_CURRENT_HOME(Z) + stepperZ.rms_current(saved_current_Z); + debug_current_on(PSTR("Z"), Z_CURRENT_HOME, saved_current_Z); + #endif + TERN_(IMPROVE_HOMING_RELIABILITY, planner.enable_stall_prevention(false)); + } + #endif + } + +#endif // SENSORLESS_PROBING + #endif // HAS_BED_PROBE diff --git a/Marlin/src/module/probe.h b/Marlin/src/module/probe.h index f0f56ec19199..ce690593f229 100644 --- a/Marlin/src/module/probe.h +++ b/Marlin/src/module/probe.h @@ -38,13 +38,37 @@ }; #endif +#if USES_Z_MIN_PROBE_PIN + #define PROBE_TRIGGERED() (READ(Z_MIN_PROBE_PIN) != Z_MIN_PROBE_ENDSTOP_INVERTING) +#else + #define PROBE_TRIGGERED() (READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING) +#endif + +#if ENABLED(PREHEAT_BEFORE_LEVELING) + #ifndef LEVELING_NOZZLE_TEMP + #define LEVELING_NOZZLE_TEMP 0 + #endif + #ifndef LEVELING_BED_TEMP + #define LEVELING_BED_TEMP 0 + #endif +#endif + class Probe { public: + #if ENABLED(SENSORLESS_PROBING) + typedef struct { bool x:1, y:1, z:1; } sense_bool_t; + static sense_bool_t test_sensitivity; + #endif + #if HAS_BED_PROBE static xyz_pos_t offset; + #if EITHER(PREHEAT_BEFORE_PROBING, PREHEAT_BEFORE_LEVELING) + static void preheat_for_probing(const celsius_t hotend_temp, const celsius_t bed_temp); + #endif + static bool set_deployed(const bool deploy); #if IS_KINEMATIC @@ -52,12 +76,12 @@ class Probe { #if HAS_PROBE_XY_OFFSET // Return true if the both nozzle and the probe can reach the given point. // Note: This won't work on SCARA since the probe offset rotates with the arm. - static inline bool can_reach(const float &rx, const float &ry) { + static bool can_reach(const_float_t rx, const_float_t ry) { return position_is_reachable(rx - offset_xy.x, ry - offset_xy.y) // The nozzle can go where it needs to go? && position_is_reachable(rx, ry, ABS(PROBING_MARGIN)); // Can the nozzle also go near there? } #else - FORCE_INLINE static bool can_reach(const float &rx, const float &ry) { + static bool can_reach(const_float_t rx, const_float_t ry) { return position_is_reachable(rx, ry, PROBING_MARGIN); } #endif @@ -71,50 +95,50 @@ class Probe { * Example: For a probe offset of -10,+10, then for the probe to reach 0,0 the * nozzle must be be able to reach +10,-10. */ - static inline bool can_reach(const float &rx, const float &ry) { + static bool can_reach(const_float_t rx, const_float_t ry) { return position_is_reachable(rx - offset_xy.x, ry - offset_xy.y) - && WITHIN(rx, min_x() - fslop, max_x() + fslop) - && WITHIN(ry, min_y() - fslop, max_y() + fslop); + && COORDINATE_OKAY(rx, min_x() - fslop, max_x() + fslop) + && COORDINATE_OKAY(ry, min_y() - fslop, max_y() + fslop); } #endif - static inline void move_z_after_probing() { + static void move_z_after_probing() { #ifdef Z_AFTER_PROBING - do_z_clearance(Z_AFTER_PROBING, true, true, true); // Move down still permitted + do_z_clearance(Z_AFTER_PROBING, true); // Move down still permitted #endif } - static float probe_at_point(const float &rx, const float &ry, const ProbePtRaise raise_after=PROBE_PT_NONE, const uint8_t verbose_level=0, const bool probe_relative=true, const bool sanity_check=true); - static inline float probe_at_point(const xy_pos_t &pos, const ProbePtRaise raise_after=PROBE_PT_NONE, const uint8_t verbose_level=0, const bool probe_relative=true, const bool sanity_check=true) { + static float probe_at_point(const_float_t rx, const_float_t ry, const ProbePtRaise raise_after=PROBE_PT_NONE, const uint8_t verbose_level=0, const bool probe_relative=true, const bool sanity_check=true); + static float probe_at_point(const xy_pos_t &pos, const ProbePtRaise raise_after=PROBE_PT_NONE, const uint8_t verbose_level=0, const bool probe_relative=true, const bool sanity_check=true) { return probe_at_point(pos.x, pos.y, raise_after, verbose_level, probe_relative, sanity_check); } #else - static constexpr xyz_pos_t offset = xyz_pos_t({ 0, 0, 0 }); // See #16767 + static constexpr xyz_pos_t offset = xyz_pos_t(LINEAR_AXIS_ARRAY(0, 0, 0, 0, 0, 0)); // See #16767 static bool set_deployed(const bool) { return false; } - FORCE_INLINE static bool can_reach(const float &rx, const float &ry) { return position_is_reachable(rx, ry); } + static bool can_reach(const_float_t rx, const_float_t ry) { return position_is_reachable(rx, ry); } #endif - static inline void move_z_after_homing() { + static void move_z_after_homing() { #ifdef Z_AFTER_HOMING - do_z_clearance(Z_AFTER_HOMING, true, true, true); - #elif BOTH(Z_AFTER_PROBING,HAS_BED_PROBE) + do_z_clearance(Z_AFTER_HOMING, true); + #elif BOTH(Z_AFTER_PROBING, HAS_BED_PROBE) move_z_after_probing(); #endif } - FORCE_INLINE static bool can_reach(const xy_pos_t &pos) { return can_reach(pos.x, pos.y); } + static bool can_reach(const xy_pos_t &pos) { return can_reach(pos.x, pos.y); } - FORCE_INLINE static bool good_bounds(const xy_pos_t &lf, const xy_pos_t &rb) { + static bool good_bounds(const xy_pos_t &lf, const xy_pos_t &rb) { return ( #if IS_KINEMATIC - can_reach(lf.x, 0) && can_reach(rb.x, 0) && can_reach(0, lf.y) && can_reach(0, rb.y) + can_reach(lf.x, 0) && can_reach(rb.x, 0) && can_reach(0, lf.y) && can_reach(0, rb.y) #else - can_reach(lf) && can_reach(rb) + can_reach(lf) && can_reach(rb) #endif ); } @@ -122,85 +146,101 @@ class Probe { // Use offset_xy for read only access // More optimal the XY offset is known to always be zero. #if HAS_PROBE_XY_OFFSET - static const xyz_pos_t &offset_xy; + static const xy_pos_t &offset_xy; #else static constexpr xy_pos_t offset_xy = xy_pos_t({ 0, 0 }); // See #16767 #endif - static inline bool deploy() { return set_deployed(true); } - static inline bool stow() { return set_deployed(false); } + static bool deploy() { return set_deployed(true); } + static bool stow() { return set_deployed(false); } #if HAS_BED_PROBE || HAS_LEVELING #if IS_KINEMATIC static constexpr float printable_radius = ( - #if ENABLED(DELTA) - DELTA_PRINTABLE_RADIUS - #elif IS_SCARA - SCARA_PRINTABLE_RADIUS - #endif + TERN_(DELTA, DELTA_PRINTABLE_RADIUS) + TERN_(IS_SCARA, SCARA_PRINTABLE_RADIUS) ); - - static inline float probe_radius() { - return printable_radius - _MAX(PROBING_MARGIN, HYPOT(offset_xy.x, offset_xy.y)); + static constexpr float probe_radius(const xy_pos_t &probe_offset_xy = offset_xy) { + return printable_radius - _MAX(PROBING_MARGIN, HYPOT(probe_offset_xy.x, probe_offset_xy.y)); } #endif - static inline float min_x() { - return ( - #if IS_KINEMATIC - (X_CENTER) - probe_radius() - #else - _MAX((X_MIN_BED) + (PROBING_MARGIN_LEFT), (X_MIN_POS) + offset_xy.x) - #endif + static constexpr float _min_x(const xy_pos_t &probe_offset_xy = offset_xy) { + return TERN(IS_KINEMATIC, + (X_CENTER) - probe_radius(probe_offset_xy), + _MAX((X_MIN_BED) + (PROBING_MARGIN_LEFT), (X_MIN_POS) + probe_offset_xy.x) ); } - static inline float max_x() { - return ( - #if IS_KINEMATIC - (X_CENTER) + probe_radius() - #else - _MIN((X_MAX_BED) - (PROBING_MARGIN_RIGHT), (X_MAX_POS) + offset_xy.x) - #endif + static constexpr float _max_x(const xy_pos_t &probe_offset_xy = offset_xy) { + return TERN(IS_KINEMATIC, + (X_CENTER) + probe_radius(probe_offset_xy), + _MIN((X_MAX_BED) - (PROBING_MARGIN_RIGHT), (X_MAX_POS) + probe_offset_xy.x) ); } - static inline float min_y() { - return ( - #if IS_KINEMATIC - (Y_CENTER) - probe_radius() - #else - _MAX((Y_MIN_BED) + (PROBING_MARGIN_FRONT), (Y_MIN_POS) + offset_xy.y) - #endif + static constexpr float _min_y(const xy_pos_t &probe_offset_xy = offset_xy) { + return TERN(IS_KINEMATIC, + (Y_CENTER) - probe_radius(probe_offset_xy), + _MAX((Y_MIN_BED) + (PROBING_MARGIN_FRONT), (Y_MIN_POS) + probe_offset_xy.y) + ); + } + static constexpr float _max_y(const xy_pos_t &probe_offset_xy = offset_xy) { + return TERN(IS_KINEMATIC, + (Y_CENTER) + probe_radius(probe_offset_xy), + _MIN((Y_MAX_BED) - (PROBING_MARGIN_BACK), (Y_MAX_POS) + probe_offset_xy.y) ); } - static inline float max_y() { - return ( + + static float min_x() { return _min_x() TERN_(NOZZLE_AS_PROBE, TERN_(HAS_HOME_OFFSET, - home_offset.x)); } + static float max_x() { return _max_x() TERN_(NOZZLE_AS_PROBE, TERN_(HAS_HOME_OFFSET, - home_offset.x)); } + static float min_y() { return _min_y() TERN_(NOZZLE_AS_PROBE, TERN_(HAS_HOME_OFFSET, - home_offset.y)); } + static float max_y() { return _max_y() TERN_(NOZZLE_AS_PROBE, TERN_(HAS_HOME_OFFSET, - home_offset.y)); } + + // constexpr helpers used in build-time static_asserts, relying on default probe offsets. + class build_time { + static constexpr xyz_pos_t default_probe_xyz_offset = + #if HAS_BED_PROBE + NOZZLE_TO_PROBE_OFFSET + #else + { 0 } + #endif + ; + static constexpr xy_pos_t default_probe_xy_offset = { default_probe_xyz_offset.x, default_probe_xyz_offset.y }; + + public: + static constexpr bool can_reach(float x, float y) { #if IS_KINEMATIC - (Y_CENTER) + probe_radius() + return HYPOT2(x, y) <= sq(probe_radius(default_probe_xy_offset)); #else - _MIN((Y_MAX_BED) - (PROBING_MARGIN_BACK), (Y_MAX_POS) + offset_xy.y) + return COORDINATE_OKAY(x, _min_x(default_probe_xy_offset) - fslop, _max_x(default_probe_xy_offset) + fslop) + && COORDINATE_OKAY(y, _min_y(default_probe_xy_offset) - fslop, _max_y(default_probe_xy_offset) + fslop); #endif - ); - } + } + + static constexpr bool can_reach(const xy_pos_t &point) { return can_reach(point.x, point.y); } + }; #if NEEDS_THREE_PROBE_POINTS // Retrieve three points to probe the bed. Any type exposing set(X,Y) may be used. template - static inline void get_three_points(T points[3]) { + static void get_three_points(T points[3]) { #if HAS_FIXED_3POINT - points[0].set(PROBE_PT_1_X, PROBE_PT_1_Y); - points[1].set(PROBE_PT_2_X, PROBE_PT_2_Y); - points[2].set(PROBE_PT_3_X, PROBE_PT_3_Y); + #define VALIDATE_PROBE_PT(N) static_assert(Probe::build_time::can_reach(xy_pos_t{PROBE_PT_##N##_X, PROBE_PT_##N##_Y}), \ + "PROBE_PT_" STRINGIFY(N) "_(X|Y) is unreachable using default NOZZLE_TO_PROBE_OFFSET and PROBING_MARGIN"); + VALIDATE_PROBE_PT(1); VALIDATE_PROBE_PT(2); VALIDATE_PROBE_PT(3); + points[0] = xy_float_t({ PROBE_PT_1_X, PROBE_PT_1_Y }); + points[1] = xy_float_t({ PROBE_PT_2_X, PROBE_PT_2_Y }); + points[2] = xy_float_t({ PROBE_PT_3_X, PROBE_PT_3_Y }); #else #if IS_KINEMATIC constexpr float SIN0 = 0.0, SIN120 = 0.866025, SIN240 = -0.866025, COS0 = 1.0, COS120 = -0.5 , COS240 = -0.5; - points[0].set((X_CENTER) + probe_radius() * COS0, (Y_CENTER) + probe_radius() * SIN0); - points[1].set((X_CENTER) + probe_radius() * COS120, (Y_CENTER) + probe_radius() * SIN120); - points[2].set((X_CENTER) + probe_radius() * COS240, (Y_CENTER) + probe_radius() * SIN240); + points[0] = xy_float_t({ (X_CENTER) + probe_radius() * COS0, (Y_CENTER) + probe_radius() * SIN0 }); + points[1] = xy_float_t({ (X_CENTER) + probe_radius() * COS120, (Y_CENTER) + probe_radius() * SIN120 }); + points[2] = xy_float_t({ (X_CENTER) + probe_radius() * COS240, (Y_CENTER) + probe_radius() * SIN240 }); #else - points[0].set(min_x(), min_y()); - points[1].set(max_x(), min_y()); - points[2].set((min_x() + max_x()) / 2, max_y()); + points[0] = xy_float_t({ min_x(), min_y() }); + points[1] = xy_float_t({ max_x(), min_y() }); + points[2] = xy_float_t({ (min_x() + max_x()) / 2, max_y() }); #endif #endif } @@ -212,12 +252,24 @@ class Probe { static void servo_probe_init(); #endif - #if QUIET_PROBING + #if HAS_QUIET_PROBING static void set_probing_paused(const bool p); #endif + #if ENABLED(PROBE_TARE) + static void tare_init(); + static bool tare(); + #endif + + // Basic functions for Sensorless Homing and Probing + #if EITHER(SENSORLESS_HOMING, SENSORLESS_PROBING) + static void enable_stallguard_diag1(); + static void disable_stallguard_diag1(); + static void set_homing_current(const bool onoff); + #endif + private: - static bool probe_down_to_z(const float z, const feedRate_t fr_mm_s); + static bool probe_down_to_z(const_float_t z, const_feedRate_t fr_mm_s); static void do_z_raise(const float z_raise); static float run_z_probe(const bool sanity_check=true); }; diff --git a/Marlin/src/module/scara.cpp b/Marlin/src/module/scara.cpp index e4b2f0b75c51..07f714a997b9 100644 --- a/Marlin/src/module/scara.cpp +++ b/Marlin/src/module/scara.cpp @@ -32,79 +32,74 @@ #include "motion.h" #include "planner.h" -float delta_segments_per_second = SCARA_SEGMENTS_PER_SECOND; - -void scara_set_axis_is_at_home(const AxisEnum axis) { - if (axis == Z_AXIS) - current_position.z = Z_HOME_POS; - else { - - /** - * SCARA homes XY at the same time - */ - xyz_pos_t homeposition; - LOOP_XYZ(i) homeposition[i] = base_home_pos((AxisEnum)i); - - #if ENABLED(MORGAN_SCARA) - // MORGAN_SCARA uses arm angles for AB home position - // SERIAL_ECHOLNPAIR("homeposition A:", homeposition.a, " B:", homeposition.b); - inverse_kinematics(homeposition); - forward_kinematics_SCARA(delta.a, delta.b); - current_position[axis] = cartes[axis]; - #else - // MP_SCARA uses a Cartesian XY home position - // SERIAL_ECHOPGM("homeposition"); - // SERIAL_ECHOLNPAIR_P(SP_X_LBL, homeposition.x, SP_Y_LBL, homeposition.y); - current_position[axis] = homeposition[axis]; - #endif +#if ENABLED(AXEL_TPARA) + #include "endstops.h" + #include "../MarlinCore.h" +#endif + +float segments_per_second = TERN(AXEL_TPARA, TPARA_SEGMENTS_PER_SECOND, SCARA_SEGMENTS_PER_SECOND); + +#if EITHER(MORGAN_SCARA, MP_SCARA) + + static constexpr xy_pos_t scara_offset = { SCARA_OFFSET_X, SCARA_OFFSET_Y }; + + /** + * Morgan SCARA Forward Kinematics. Results in 'cartes'. + * Maths and first version by QHARLEY. + * Integrated into Marlin and slightly restructured by Joachim Cerny. + */ + void forward_kinematics(const_float_t a, const_float_t b) { + const float a_sin = sin(RADIANS(a)) * L1, + a_cos = cos(RADIANS(a)) * L1, + b_sin = sin(RADIANS(SUM_TERN(MP_SCARA, b, a))) * L2, + b_cos = cos(RADIANS(SUM_TERN(MP_SCARA, b, a))) * L2; + + cartes.x = a_cos + b_cos + scara_offset.x; // theta + cartes.y = a_sin + b_sin + scara_offset.y; // phi - // SERIAL_ECHOPGM("Cartesian"); - // SERIAL_ECHOLNPAIR_P(SP_X_LBL, current_position.x, SP_Y_LBL, current_position.y); - update_software_endstops(axis); + /* + DEBUG_ECHOLNPAIR( + "SCARA FK Angle a=", a, + " b=", b, + " a_sin=", a_sin, + " a_cos=", a_cos, + " b_sin=", b_sin, + " b_cos=", b_cos + ); + DEBUG_ECHOLNPAIR(" cartes (X,Y) = "(cartes.x, ", ", cartes.y, ")"); + //*/ } -} -static constexpr xy_pos_t scara_offset = { SCARA_OFFSET_X, SCARA_OFFSET_Y }; +#endif -/** - * Morgan SCARA Forward Kinematics. Results in 'cartes'. - * Maths and first version by QHARLEY. - * Integrated into Marlin and slightly restructured by Joachim Cerny. - */ -void forward_kinematics_SCARA(const float &a, const float &b) { - - const float a_sin = sin(RADIANS(a)) * L1, - a_cos = cos(RADIANS(a)) * L1, - b_sin = sin(RADIANS(b)) * L2, - b_cos = cos(RADIANS(b)) * L2; - - cartes.set(a_cos + b_cos + scara_offset.x, // theta - a_sin + b_sin + scara_offset.y); // theta+phi - - /* - SERIAL_ECHOLNPAIR( - "SCARA FK Angle a=", a, - " b=", b, - " a_sin=", a_sin, - " a_cos=", a_cos, - " b_sin=", b_sin, - " b_cos=", b_cos - ); - SERIAL_ECHOLNPAIR(" cartes (X,Y) = "(cartes.x, ", ", cartes.y, ")"); - //*/ -} +#if ENABLED(MORGAN_SCARA) -void inverse_kinematics(const xyz_pos_t &raw) { - - #if ENABLED(MORGAN_SCARA) - /** - * Morgan SCARA Inverse Kinematics. Results in 'delta'. - * - * See https://reprap.org/forum/read.php?185,283327 - * - * Maths and first version by QHARLEY. - * Integrated into Marlin and slightly restructured by Joachim Cerny. - */ + void scara_set_axis_is_at_home(const AxisEnum axis) { + if (axis == Z_AXIS) + current_position.z = Z_HOME_POS; + else { + // MORGAN_SCARA uses a Cartesian XY home position + xyz_pos_t homeposition = { X_HOME_POS, Y_HOME_POS, Z_HOME_POS }; + //DEBUG_ECHOLNPAIR_P(PSTR("homeposition X"), homeposition.x, SP_Y_LBL, homeposition.y); + + delta = homeposition; + forward_kinematics(delta.a, delta.b); + current_position[axis] = cartes[axis]; + + //DEBUG_ECHOLNPAIR_P(PSTR("Cartesian X"), current_position.x, SP_Y_LBL, current_position.y); + update_software_endstops(axis); + } + } + + /** + * Morgan SCARA Inverse Kinematics. Results are stored in 'delta'. + * + * See https://reprap.org/forum/read.php?185,283327 + * + * Maths and first version by QHARLEY. + * Integrated into Marlin and slightly restructured by Joachim Cerny. + */ + void inverse_kinematics(const xyz_pos_t &raw) { float C2, S2, SK1, SK2, THETA, PSI; // Translate SCARA to standard XY with scaling factor @@ -116,6 +111,8 @@ void inverse_kinematics(const xyz_pos_t &raw) { else C2 = (H2 - (L1_2 + L2_2)) / (2.0f * L1 * L2); + LIMIT(C2, -1, 1); + S2 = SQRT(1.0f - sq(C2)); // Unrotated Arm1 plus rotated Arm2 gives the distance from Center to End @@ -130,16 +127,41 @@ void inverse_kinematics(const xyz_pos_t &raw) { // Angle of Arm2 PSI = ATAN2(S2, C2); - delta.set(DEGREES(THETA), DEGREES(THETA + PSI), raw.z); + delta.set(DEGREES(THETA), DEGREES(SUM_TERN(MORGAN_SCARA, PSI, THETA)), raw.z); /* DEBUG_POS("SCARA IK", raw); DEBUG_POS("SCARA IK", delta); - SERIAL_ECHOLNPAIR(" SCARA (x,y) ", sx, ",", sy, " C2=", C2, " S2=", S2, " Theta=", THETA, " Phi=", PHI); + DEBUG_ECHOLNPAIR(" SCARA (x,y) ", sx, ",", sy, " C2=", C2, " S2=", S2, " Theta=", THETA, " Psi=", PSI); //*/ + } + +#elif ENABLED(MP_SCARA) + + void scara_set_axis_is_at_home(const AxisEnum axis) { + if (axis == Z_AXIS) + current_position.z = Z_HOME_POS; + else { + // MP_SCARA uses arm angles for AB home position + #ifndef SCARA_OFFSET_THETA1 + #define SCARA_OFFSET_THETA1 12 // degrees + #endif + #ifndef SCARA_OFFSET_THETA2 + #define SCARA_OFFSET_THETA2 131 // degrees + #endif + ab_float_t homeposition = { SCARA_OFFSET_THETA1, SCARA_OFFSET_THETA2 }; + //DEBUG_ECHOLNPAIR("homeposition A:", homeposition.a, " B:", homeposition.b); + + inverse_kinematics(homeposition); + forward_kinematics(delta.a, delta.b); + current_position[axis] = cartes[axis]; - #else // MP_SCARA + //DEBUG_ECHOLNPAIR_P(PSTR("Cartesian X"), current_position.x, SP_Y_LBL, current_position.y); + update_software_endstops(axis); + } + } + void inverse_kinematics(const xyz_pos_t &raw) { const float x = raw.x, y = raw.y, c = HYPOT(x, y), THETA3 = ATAN2(y, x), THETA1 = THETA3 + ACOS((sq(c) + sq(L1) - sq(L2)) / (2.0f * c * L1)), @@ -152,12 +174,135 @@ void inverse_kinematics(const xyz_pos_t &raw) { DEBUG_POS("SCARA IK", delta); SERIAL_ECHOLNPAIR(" SCARA (x,y) ", x, ",", y," Theta1=", THETA1, " Theta2=", THETA2); //*/ + } - #endif // MP_SCARA -} +#elif ENABLED(AXEL_TPARA) + + static constexpr xyz_pos_t robot_offset = { TPARA_OFFSET_X, TPARA_OFFSET_Y, TPARA_OFFSET_Z }; + + void scara_set_axis_is_at_home(const AxisEnum axis) { + if (axis == Z_AXIS) + current_position.z = Z_HOME_POS; + else { + xyz_pos_t homeposition = { X_HOME_POS, Y_HOME_POS, Z_HOME_POS }; + //DEBUG_ECHOLNPAIR_P(PSTR("homeposition X"), homeposition.x, SP_Y_LBL, homeposition.y, SP_Z_LBL, homeposition.z); + + inverse_kinematics(homeposition); + forward_kinematics(delta.a, delta.b, delta.c); + current_position[axis] = cartes[axis]; + + //DEBUG_ECHOLNPAIR_P(PSTR("Cartesian X"), current_position.x, SP_Y_LBL, current_position.y); + update_software_endstops(axis); + } + } + + // Convert ABC inputs in degrees to XYZ outputs in mm + void forward_kinematics(const_float_t a, const_float_t b, const_float_t c) { + const float w = c - b, + r = L1 * cos(RADIANS(b)) + L2 * sin(RADIANS(w - (90 - b))), + x = r * cos(RADIANS(a)), + y = r * sin(RADIANS(a)), + rho2 = L1_2 + L2_2 - 2.0f * L1 * L2 * cos(RADIANS(w)); + + cartes = robot_offset + xyz_pos_t({ x, y, SQRT(rho2 - sq(x) - sq(y)) }); + } + + // Home YZ together, then X (or all at once). Based on quick_home_xy & home_delta + void home_TPARA() { + // Init the current position of all carriages to 0,0,0 + current_position.reset(); + destination.reset(); + sync_plan_position(); + + // Disable stealthChop if used. Enable diag1 pin on driver. + #if ENABLED(SENSORLESS_HOMING) + TERN_(X_SENSORLESS, sensorless_t stealth_states_x = start_sensorless_homing_per_axis(X_AXIS)); + TERN_(Y_SENSORLESS, sensorless_t stealth_states_y = start_sensorless_homing_per_axis(Y_AXIS)); + TERN_(Z_SENSORLESS, sensorless_t stealth_states_z = start_sensorless_homing_per_axis(Z_AXIS)); + #endif + + //const int x_axis_home_dir = TOOL_X_HOME_DIR(active_extruder); + + //const xy_pos_t pos { max_length(X_AXIS) , max_length(Y_AXIS) }; + //const float mlz = max_length(X_AXIS), + + // 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) ; + line_to_current_position(homing_feedrate(Z_AXIS)); + planner.synchronize(); + + // Re-enable stealthChop if used. Disable diag1 pin on driver. + #if ENABLED(SENSORLESS_HOMING) + TERN_(X_SENSORLESS, end_sensorless_homing_per_axis(X_AXIS, stealth_states_x)); + TERN_(Y_SENSORLESS, end_sensorless_homing_per_axis(Y_AXIS, stealth_states_y)); + TERN_(Z_SENSORLESS, end_sensorless_homing_per_axis(Z_AXIS, stealth_states_z)); + #endif + + endstops.validate_homing_move(); + + // At least one motor has reached its endstop. + // Now re-home each motor separately. + homeaxis(A_AXIS); + homeaxis(C_AXIS); + homeaxis(B_AXIS); + + // Set all carriages to their home positions + // Do this here all at once for Delta, because + // XYZ isn't ABC. Applying this per-tower would + // give the impression that they are the same. + LOOP_LINEAR_AXES(i) set_axis_is_at_home((AxisEnum)i); + + sync_plan_position(); + } + + void inverse_kinematics(const xyz_pos_t &raw) { + const xyz_pos_t spos = raw - robot_offset; + + const float RXY = SQRT(HYPOT2(spos.x, spos.y)), + RHO2 = NORMSQ(spos.x, spos.y, spos.z), + //RHO = SQRT(RHO2), + LSS = L1_2 + L2_2, + LM = 2.0f * L1 * L2, + + CG = (LSS - RHO2) / LM, + SG = SQRT(1 - POW(CG, 2)), // Method 2 + K1 = L1 - L2 * CG, + K2 = L2 * SG, + + // Angle of Body Joint + THETA = ATAN2(spos.y, spos.x), + + // Angle of Elbow Joint + //GAMMA = ACOS(CG), + GAMMA = ATAN2(SG, CG), // Method 2 + + // Angle of Shoulder Joint, elevation angle measured from horizontal (r+) + //PHI = asin(spos.z/RHO) + asin(L2 * sin(GAMMA) / RHO), + PHI = ATAN2(spos.z, RXY) + ATAN2(K2, K1), // Method 2 + + // Elbow motor angle measured from horizontal, same frame as shoulder (r+) + PSI = PHI + GAMMA; + + delta.set(DEGREES(THETA), DEGREES(PHI), DEGREES(PSI)); + + //SERIAL_ECHOLNPAIR(" SCARA (x,y,z) ", spos.x , ",", spos.y, ",", spos.z, " Rho=", RHO, " Rho2=", RHO2, " Theta=", THETA, " Phi=", PHI, " Psi=", PSI, " Gamma=", GAMMA); + } + +#endif void scara_report_positions() { - SERIAL_ECHOLNPAIR("SCARA Theta:", planner.get_axis_position_degrees(A_AXIS), " Psi+Theta:", planner.get_axis_position_degrees(B_AXIS)); + SERIAL_ECHOLNPAIR("SCARA Theta:", planner.get_axis_position_degrees(A_AXIS) + #if ENABLED(AXEL_TPARA) + , " Phi:", planner.get_axis_position_degrees(B_AXIS) + , " Psi:", planner.get_axis_position_degrees(C_AXIS) + #else + , " Psi" TERN_(MORGAN_SCARA, "+Theta") ":", planner.get_axis_position_degrees(B_AXIS) + #endif + ); SERIAL_EOL(); } diff --git a/Marlin/src/module/scara.h b/Marlin/src/module/scara.h index e2acaf30822c..8ce50e55e116 100644 --- a/Marlin/src/module/scara.h +++ b/Marlin/src/module/scara.h @@ -27,16 +27,27 @@ #include "../core/macros.h" -extern float delta_segments_per_second; +extern float segments_per_second; -// Float constants for SCARA calculations -float constexpr L1 = SCARA_LINKAGE_1, L2 = SCARA_LINKAGE_2, - L1_2 = sq(float(L1)), L1_2_2 = 2.0 * L1_2, - L2_2 = sq(float(L2)); +#if ENABLED(AXEL_TPARA) -void scara_set_axis_is_at_home(const AxisEnum axis); + float constexpr L1 = TPARA_LINKAGE_1, L2 = TPARA_LINKAGE_2, // Float constants for Robot arm calculations + L1_2 = sq(float(L1)), L1_2_2 = 2.0 * L1_2, + L2_2 = sq(float(L2)); -void inverse_kinematics(const xyz_pos_t &raw); -void forward_kinematics_SCARA(const float &a, const float &b); + void forward_kinematics(const_float_t a, const_float_t b, const_float_t c); + void home_TPARA(); + +#else + + float constexpr L1 = SCARA_LINKAGE_1, L2 = SCARA_LINKAGE_2, // Float constants for SCARA calculations + L1_2 = sq(float(L1)), L1_2_2 = 2.0 * L1_2, + L2_2 = sq(float(L2)); + void forward_kinematics(const_float_t a, const_float_t b); + +#endif + +void inverse_kinematics(const xyz_pos_t &raw); +void scara_set_axis_is_at_home(const AxisEnum axis); void scara_report_positions(); diff --git a/Marlin/src/module/servo.cpp b/Marlin/src/module/servo.cpp index 27e5a2af2e03..9b71dd390f51 100644 --- a/Marlin/src/module/servo.cpp +++ b/Marlin/src/module/servo.cpp @@ -32,7 +32,9 @@ HAL_SERVO_LIB servo[NUM_SERVOS]; -TERN_(EDITABLE_SERVO_ANGLES, uint16_t servo_angles[NUM_SERVOS][2]); +#if ENABLED(EDITABLE_SERVO_ANGLES) + uint16_t servo_angles[NUM_SERVOS][2]; +#endif void servo_init() { #if NUM_SERVOS >= 1 && HAS_SERVO_0 diff --git a/Marlin/src/module/servo.h b/Marlin/src/module/servo.h index 29bd3b8798d4..3b5a5e7e2cd2 100644 --- a/Marlin/src/module/servo.h +++ b/Marlin/src/module/servo.h @@ -112,4 +112,4 @@ #define MOVE_SERVO(I, P) servo[I].move(P) extern HAL_SERVO_LIB servo[NUM_SERVOS]; -extern void servo_init(); +void servo_init(); diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 33e5c351abc1..47c1314e2851 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -36,7 +36,7 @@ */ // Change EEPROM version if the structure changes -#define EEPROM_VERSION "V82" +#define EEPROM_VERSION "V84" #define EEPROM_OFFSET 100 // Check the integrity of data offsets. @@ -50,11 +50,7 @@ #include "stepper.h" #include "temperature.h" -#if ENABLED(DWIN_CREALITY_LCD) - #include "../lcd/dwin/e3v2/dwin.h" -#endif - -#include "../lcd/ultralcd.h" +#include "../lcd/marlinui.h" #include "../libs/vector_3.h" // for matrix_3x3 #include "../gcode/gcode.h" #include "../MarlinCore.h" @@ -134,12 +130,11 @@ #include "../feature/controllerfan.h" #if ENABLED(CONTROLLER_FAN_EDITABLE) - void M710_report(const bool forReplay); + void M710_report(const bool forReplay=true); #endif -#if ENABLED(CASE_LIGHT_ENABLE) && DISABLED(CASE_LIGHT_NO_BRIGHTNESS) +#if ENABLED(CASE_LIGHT_ENABLE) #include "../feature/caselight.h" - #define HAS_CASE_LIGHT_BRIGHTNESS 1 #endif #if ENABLED(PASSWORD_FEATURE) @@ -147,15 +142,44 @@ #endif #if ENABLED(TOUCH_SCREEN_CALIBRATION) - #include "../lcd/tft/touch.h" + #include "../lcd/tft_io/touch_calibration.h" +#endif + +#if HAS_ETHERNET + #include "../feature/ethernet.h" +#endif + +#if ENABLED(SOUND_MENU_ITEM) + #include "../libs/buzzer.h" +#endif + +#if ENABLED(DGUS_LCD_UI_MKS) + #include "../lcd/extui/dgus/DGUSScreenHandler.h" + #include "../lcd/extui/dgus/DGUSDisplayDef.h" #endif #pragma pack(push, 1) // No padding between variables -typedef struct { uint16_t X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7; } tmc_stepper_current_t; -typedef struct { uint32_t X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7; } tmc_hybrid_threshold_t; -typedef struct { int16_t X, Y, Z, X2, Y2, Z2, Z3, Z4; } tmc_sgt_t; -typedef struct { bool X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7; } tmc_stealth_enabled_t; +#if HAS_ETHERNET + void ETH0_report(); + void MAC_report(); + void M552_report(); + void M553_report(); + void M554_report(); +#endif + +#if EITHER(DELTA, HAS_EXTRA_ENDSTOPS) + void M666_report(const bool forReplay=true); +#endif + +#define _EN_ITEM(N) , E##N + +typedef struct { uint16_t LINEAR_AXIS_LIST(X, Y, Z, I, J, K), X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM); } tmc_stepper_current_t; +typedef struct { uint32_t LINEAR_AXIS_LIST(X, Y, Z, I, J, K), X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM); } tmc_hybrid_threshold_t; +typedef struct { int16_t LINEAR_AXIS_LIST(X, Y, Z, I, J, K), X2, Y2, Z2, Z3, Z4; } tmc_sgt_t; +typedef struct { bool LINEAR_AXIS_LIST(X, Y, Z, I, J, K), X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM); } tmc_stealth_enabled_t; + +#undef _EN_ITEM // Limit an index to an array size #define ALIM(I,ARR) _MIN(I, (signed)COUNT(ARR) - 1) @@ -165,8 +189,6 @@ static const uint32_t _DMA[] PROGMEM = DEFAULT_MAX_ACCELERATION; static const float _DASU[] PROGMEM = DEFAULT_AXIS_STEPS_PER_UNIT; static const feedRate_t _DMF[] PROGMEM = DEFAULT_MAX_FEEDRATE; -extern const char SP_X_STR[], SP_Y_STR[], SP_Z_STR[], SP_E_STR[]; - /** * Current EEPROM Layout * @@ -180,7 +202,7 @@ typedef struct SettingsDataStruct { // // DISTINCT_E_FACTORS // - uint8_t esteppers; // XYZE_N - XYZ + uint8_t esteppers; // DISTINCT_AXES - LINEAR_AXES planner_settings_t planner_settings; @@ -270,7 +292,7 @@ typedef struct SettingsDataStruct { abc_float_t delta_endstop_adj; // M666 X Y Z float delta_radius, // M665 R delta_diagonal_rod, // M665 L - delta_segments_per_second; // M665 S + segments_per_second; // M665 S abc_float_t delta_tower_angle_trim, // M665 X Y Z delta_diagonal_rod_trim; // M665 A B C #elif HAS_EXTRA_ENDSTOPS @@ -309,6 +331,11 @@ typedef struct SettingsDataStruct { // PID_t bedPID; // M304 PID / M303 E-1 U + // + // PIDTEMPCHAMBER + // + PID_t chamberPID; // M309 PID / M303 E-2 U + // // User-defined Thermistors // @@ -326,6 +353,11 @@ typedef struct SettingsDataStruct { // int16_t lcd_contrast; // M250 C + // + // HAS_LCD_BRIGHTNESS + // + uint8_t lcd_brightness; // M256 B + // // Controller fan settings // @@ -366,9 +398,9 @@ typedef struct SettingsDataStruct { // HAS_MOTOR_CURRENT_PWM // #ifndef MOTOR_CURRENT_COUNT - #define MOTOR_CURRENT_COUNT 3 + #define MOTOR_CURRENT_COUNT LINEAR_AXES #endif - uint32_t motor_current_setting[MOTOR_CURRENT_COUNT]; // M907 X Z E + uint32_t motor_current_setting[MOTOR_CURRENT_COUNT]; // M907 X Z E ... // // CNC_COORDINATE_SYSTEMS @@ -383,7 +415,7 @@ typedef struct SettingsDataStruct { // // ADVANCED_PAUSE_FEATURE // - #if EXTRUDERS + #if HAS_EXTRUDERS fil_change_settings_t fc_settings[EXTRUDERS]; // M603 T U L #endif @@ -410,9 +442,9 @@ typedef struct SettingsDataStruct { #endif // - // HAS_CASE_LIGHT_BRIGHTNESS + // CASELIGHT_USES_BRIGHTNESS // - #if HAS_CASE_LIGHT_BRIGHTNESS + #if CASELIGHT_USES_BRIGHTNESS uint8_t caselight_brightness; // M355 P #endif @@ -428,7 +460,37 @@ typedef struct SettingsDataStruct { // TOUCH_SCREEN_CALIBRATION // #if ENABLED(TOUCH_SCREEN_CALIBRATION) - touch_calibration_t touch_calibration; + touch_calibration_t touch_calibration_data; + #endif + + // Ethernet settings + #if HAS_ETHERNET + bool ethernet_hardware_enabled; // M552 S + uint32_t ethernet_ip, // M552 P + ethernet_dns, + ethernet_gateway, // M553 P + ethernet_subnet; // M554 P + #endif + + // + // Buzzer enable/disable + // + #if ENABLED(SOUND_MENU_ITEM) + bool buzzer_enabled; + #endif + + // + // MKS UI controller + // + #if ENABLED(DGUS_LCD_UI_MKS) + uint8_t mks_language_index; // Display Language + xy_int_t mks_corner_offsets[5]; // Bed Tramming + xyz_int_t mks_park_pos; // Custom Parking (without NOZZLE_PARK) + celsius_t mks_min_extrusion_temp; // Min E Temp (shadow M302 value) + #endif + + #if HAS_MULTI_LANGUAGE + uint8_t ui_language; // M414 S #endif } SettingsData; @@ -467,7 +529,7 @@ void MarlinSettings::postprocess() { #endif // Software endstops depend on home_offset - LOOP_XYZ(i) { + LOOP_LINEAR_AXES(i) { update_workspace_offset((AxisEnum)i); update_software_endstops((AxisEnum)i); } @@ -482,7 +544,9 @@ void MarlinSettings::postprocess() { TERN_(HAS_LINEAR_E_JERK, planner.recalculate_max_e_jerk()); - TERN_(HAS_CASE_LIGHT_BRIGHTNESS, caselight.update_brightness()); + TERN_(CASELIGHT_USES_BRIGHTNESS, caselight.update_brightness()); + + TERN_(EXTENSIBLE_UI, ExtUI::onPostprocessSettings()); // Refresh steps_to_mm with the reciprocal of axis_steps_per_mm // and init stepper.count[], planner.position[] with current_position @@ -529,24 +593,19 @@ void MarlinSettings::postprocess() { #endif // SD_FIRMWARE_UPDATE #ifdef ARCHIM2_SPI_FLASH_EEPROM_BACKUP_SIZE - static_assert( - EEPROM_OFFSET + sizeof(SettingsData) < ARCHIM2_SPI_FLASH_EEPROM_BACKUP_SIZE, - "ARCHIM2_SPI_FLASH_EEPROM_BACKUP_SIZE is insufficient to capture all EEPROM data." - ); + static_assert(EEPROM_OFFSET + sizeof(SettingsData) < ARCHIM2_SPI_FLASH_EEPROM_BACKUP_SIZE, + "ARCHIM2_SPI_FLASH_EEPROM_BACKUP_SIZE is insufficient to capture all EEPROM data."); #endif -#define DEBUG_OUT ENABLED(EEPROM_CHITCHAT) +// +// 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) #include "../core/debug_out.h" #if ENABLED(EEPROM_SETTINGS) - #define EEPROM_START() if (!persistentStore.access_start()) { SERIAL_ECHO_MSG("No EEPROM."); return false; } \ - int eeprom_index = EEPROM_OFFSET - #define EEPROM_FINISH() persistentStore.access_finish() - #define EEPROM_SKIP(VAR) (eeprom_index += sizeof(VAR)) - #define EEPROM_WRITE(VAR) do{ persistentStore.write_data(eeprom_index, (uint8_t*)&VAR, sizeof(VAR), &working_crc); }while(0) - #define EEPROM_READ(VAR) do{ persistentStore.read_data(eeprom_index, (uint8_t*)&VAR, sizeof(VAR), &working_crc, !validating); }while(0) - #define EEPROM_READ_ALWAYS(VAR) do{ persistentStore.read_data(eeprom_index, (uint8_t*)&VAR, sizeof(VAR), &working_crc); }while(0) #define EEPROM_ASSERT(TST,ERR) do{ if (!(TST)) { SERIAL_ERROR_MSG(ERR); eeprom_error = true; } }while(0) #if ENABLED(DEBUG_EEPROM_READWRITE) @@ -562,6 +621,8 @@ void MarlinSettings::postprocess() { const char version[4] = EEPROM_VERSION; bool MarlinSettings::eeprom_error, MarlinSettings::validating; + int MarlinSettings::eeprom_index; + uint16_t MarlinSettings::working_crc; bool MarlinSettings::size_error(const uint16_t size) { if (size != datasize()) { @@ -578,9 +639,7 @@ void MarlinSettings::postprocess() { float dummyf = 0; char ver[4] = "ERR"; - uint16_t working_crc = 0; - - EEPROM_START(); + if (!EEPROM_START(EEPROM_OFFSET)) return false; eeprom_error = false; @@ -591,9 +650,8 @@ void MarlinSettings::postprocess() { working_crc = 0; // clear before first "real data" + const uint8_t esteppers = COUNT(planner.settings.axis_steps_per_mm) - LINEAR_AXES; _FIELD_TEST(esteppers); - - const uint8_t esteppers = COUNT(planner.settings.axis_steps_per_mm) - XYZ; EEPROM_WRITE(esteppers); // @@ -609,7 +667,7 @@ void MarlinSettings::postprocess() { EEPROM_WRITE(dummyf); #endif #else - const xyze_pos_t planner_max_jerk = { 10, 10, 0.4, float(DEFAULT_EJERK) }; + const xyze_pos_t planner_max_jerk = LOGICAL_AXIS_ARRAY(float(DEFAULT_EJERK), 10, 10, 0.4, 0.4, 0.4, 0.4); EEPROM_WRITE(planner_max_jerk); #endif @@ -668,7 +726,7 @@ void MarlinSettings::postprocess() { // Global Leveling // { - const float zfh = TERN(ENABLE_LEVELING_FADE_HEIGHT, planner.z_fade_height, 10.0f); + const float zfh = TERN(ENABLE_LEVELING_FADE_HEIGHT, planner.z_fade_height, (DEFAULT_LEVELING_FADE_HEIGHT)); EEPROM_WRITE(zfh); } @@ -808,7 +866,7 @@ void MarlinSettings::postprocess() { EEPROM_WRITE(delta_endstop_adj); // 3 floats EEPROM_WRITE(delta_radius); // 1 float EEPROM_WRITE(delta_diagonal_rod); // 1 float - EEPROM_WRITE(delta_segments_per_second); // 1 float + EEPROM_WRITE(segments_per_second); // 1 float EEPROM_WRITE(delta_tower_angle_trim); // 3 floats EEPROM_WRITE(delta_diagonal_rod_trim); // 3 floats @@ -899,6 +957,25 @@ void MarlinSettings::postprocess() { EEPROM_WRITE(bed_pid); } + // + // PIDTEMPCHAMBER + // + { + _FIELD_TEST(chamberPID); + + const PID_t chamber_pid = { + #if DISABLED(PIDTEMPCHAMBER) + NAN, NAN, NAN + #else + // Store the unscaled PID values + thermalManager.temp_chamber.pid.Kp, + unscalePID_i(thermalManager.temp_chamber.pid.Ki), + unscalePID_d(thermalManager.temp_chamber.pid.Kd) + #endif + }; + EEPROM_WRITE(chamber_pid); + } + // // User-defined Thermistors // @@ -927,17 +1004,19 @@ void MarlinSettings::postprocess() { // { _FIELD_TEST(lcd_contrast); - - const int16_t lcd_contrast = - #if HAS_LCD_CONTRAST - ui.contrast - #else - 127 - #endif - ; + const int16_t lcd_contrast = TERN(HAS_LCD_CONTRAST, ui.contrast, 127); EEPROM_WRITE(lcd_contrast); } + // + // LCD Brightness + // + { + _FIELD_TEST(lcd_brightness); + const uint8_t lcd_brightness = TERN(HAS_LCD_BRIGHTNESS, ui.brightness, 255); + EEPROM_WRITE(lcd_brightness); + } + // // Controller Fan // @@ -1011,7 +1090,7 @@ void MarlinSettings::postprocess() { { _FIELD_TEST(tmc_stepper_current); - tmc_stepper_current_t tmc_stepper_current = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 }; + tmc_stepper_current_t tmc_stepper_current{0}; #if HAS_TRINAMIC_CONFIG #if AXIS_IS_TMC(X) @@ -1023,6 +1102,15 @@ void MarlinSettings::postprocess() { #if AXIS_IS_TMC(Z) tmc_stepper_current.Z = stepperZ.getMilliamps(); #endif + #if AXIS_IS_TMC(I) + tmc_stepper_current.I = stepperI.getMilliamps(); + #endif + #if AXIS_IS_TMC(J) + tmc_stepper_current.J = stepperJ.getMilliamps(); + #endif + #if AXIS_IS_TMC(K) + tmc_stepper_current.K = stepperK.getMilliamps(); + #endif #if AXIS_IS_TMC(X2) tmc_stepper_current.X2 = stepperX2.getMilliamps(); #endif @@ -1038,46 +1126,30 @@ void MarlinSettings::postprocess() { #if AXIS_IS_TMC(Z4) tmc_stepper_current.Z4 = stepperZ4.getMilliamps(); #endif - #if MAX_EXTRUDERS - #if AXIS_IS_TMC(E0) - tmc_stepper_current.E0 = stepperE0.getMilliamps(); - #endif - #if MAX_EXTRUDERS > 1 - #if AXIS_IS_TMC(E1) - tmc_stepper_current.E1 = stepperE1.getMilliamps(); - #endif - #if MAX_EXTRUDERS > 2 - #if AXIS_IS_TMC(E2) - tmc_stepper_current.E2 = stepperE2.getMilliamps(); - #endif - #if MAX_EXTRUDERS > 3 - #if AXIS_IS_TMC(E3) - tmc_stepper_current.E3 = stepperE3.getMilliamps(); - #endif - #if MAX_EXTRUDERS > 4 - #if AXIS_IS_TMC(E4) - tmc_stepper_current.E4 = stepperE4.getMilliamps(); - #endif - #if MAX_EXTRUDERS > 5 - #if AXIS_IS_TMC(E5) - tmc_stepper_current.E5 = stepperE5.getMilliamps(); - #endif - #if MAX_EXTRUDERS > 6 - #if AXIS_IS_TMC(E6) - tmc_stepper_current.E6 = stepperE6.getMilliamps(); - #endif - #if MAX_EXTRUDERS > 7 - #if AXIS_IS_TMC(E7) - tmc_stepper_current.E7 = stepperE7.getMilliamps(); - #endif - #endif // MAX_EXTRUDERS > 7 - #endif // MAX_EXTRUDERS > 6 - #endif // MAX_EXTRUDERS > 5 - #endif // MAX_EXTRUDERS > 4 - #endif // MAX_EXTRUDERS > 3 - #endif // MAX_EXTRUDERS > 2 - #endif // MAX_EXTRUDERS > 1 - #endif // MAX_EXTRUDERS + #if AXIS_IS_TMC(E0) + tmc_stepper_current.E0 = stepperE0.getMilliamps(); + #endif + #if AXIS_IS_TMC(E1) + tmc_stepper_current.E1 = stepperE1.getMilliamps(); + #endif + #if AXIS_IS_TMC(E2) + tmc_stepper_current.E2 = stepperE2.getMilliamps(); + #endif + #if AXIS_IS_TMC(E3) + tmc_stepper_current.E3 = stepperE3.getMilliamps(); + #endif + #if AXIS_IS_TMC(E4) + tmc_stepper_current.E4 = stepperE4.getMilliamps(); + #endif + #if AXIS_IS_TMC(E5) + tmc_stepper_current.E5 = stepperE5.getMilliamps(); + #endif + #if AXIS_IS_TMC(E6) + tmc_stepper_current.E6 = stepperE6.getMilliamps(); + #endif + #if AXIS_IS_TMC(E7) + tmc_stepper_current.E7 = stepperE7.getMilliamps(); + #endif #endif EEPROM_WRITE(tmc_stepper_current); } @@ -1089,78 +1161,34 @@ void MarlinSettings::postprocess() { _FIELD_TEST(tmc_hybrid_threshold); #if ENABLED(HYBRID_THRESHOLD) - tmc_hybrid_threshold_t tmc_hybrid_threshold = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 }; - #if AXIS_HAS_STEALTHCHOP(X) - tmc_hybrid_threshold.X = stepperX.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - tmc_hybrid_threshold.Y = stepperY.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - tmc_hybrid_threshold.Z = stepperZ.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(X2) - tmc_hybrid_threshold.X2 = stepperX2.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - tmc_hybrid_threshold.Y2 = stepperY2.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - tmc_hybrid_threshold.Z2 = stepperZ2.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(Z3) - tmc_hybrid_threshold.Z3 = stepperZ3.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(Z4) - tmc_hybrid_threshold.Z4 = stepperZ4.get_pwm_thrs(); - #endif - #if MAX_EXTRUDERS - #if AXIS_HAS_STEALTHCHOP(E0) - tmc_hybrid_threshold.E0 = stepperE0.get_pwm_thrs(); - #endif - #if MAX_EXTRUDERS > 1 - #if AXIS_HAS_STEALTHCHOP(E1) - tmc_hybrid_threshold.E1 = stepperE1.get_pwm_thrs(); - #endif - #if MAX_EXTRUDERS > 2 - #if AXIS_HAS_STEALTHCHOP(E2) - tmc_hybrid_threshold.E2 = stepperE2.get_pwm_thrs(); - #endif - #if MAX_EXTRUDERS > 3 - #if AXIS_HAS_STEALTHCHOP(E3) - tmc_hybrid_threshold.E3 = stepperE3.get_pwm_thrs(); - #endif - #if MAX_EXTRUDERS > 4 - #if AXIS_HAS_STEALTHCHOP(E4) - tmc_hybrid_threshold.E4 = stepperE4.get_pwm_thrs(); - #endif - #if MAX_EXTRUDERS > 5 - #if AXIS_HAS_STEALTHCHOP(E5) - tmc_hybrid_threshold.E5 = stepperE5.get_pwm_thrs(); - #endif - #if MAX_EXTRUDERS > 6 - #if AXIS_HAS_STEALTHCHOP(E6) - tmc_hybrid_threshold.E6 = stepperE6.get_pwm_thrs(); - #endif - #if MAX_EXTRUDERS > 7 - #if AXIS_HAS_STEALTHCHOP(E7) - tmc_hybrid_threshold.E7 = stepperE7.get_pwm_thrs(); - #endif - #endif // MAX_EXTRUDERS > 7 - #endif // MAX_EXTRUDERS > 6 - #endif // MAX_EXTRUDERS > 5 - #endif // MAX_EXTRUDERS > 4 - #endif // MAX_EXTRUDERS > 3 - #endif // MAX_EXTRUDERS > 2 - #endif // MAX_EXTRUDERS > 1 - #endif // MAX_EXTRUDERS + tmc_hybrid_threshold_t tmc_hybrid_threshold{0}; + TERN_(X_HAS_STEALTHCHOP, tmc_hybrid_threshold.X = stepperX.get_pwm_thrs()); + TERN_(Y_HAS_STEALTHCHOP, tmc_hybrid_threshold.Y = stepperY.get_pwm_thrs()); + TERN_(Z_HAS_STEALTHCHOP, tmc_hybrid_threshold.Z = stepperZ.get_pwm_thrs()); + TERN_(I_HAS_STEALTHCHOP, tmc_hybrid_threshold.I = stepperI.get_pwm_thrs()); + TERN_(J_HAS_STEALTHCHOP, tmc_hybrid_threshold.J = stepperJ.get_pwm_thrs()); + TERN_(K_HAS_STEALTHCHOP, tmc_hybrid_threshold.K = stepperK.get_pwm_thrs()); + TERN_(X2_HAS_STEALTHCHOP, tmc_hybrid_threshold.X2 = stepperX2.get_pwm_thrs()); + TERN_(Y2_HAS_STEALTHCHOP, tmc_hybrid_threshold.Y2 = stepperY2.get_pwm_thrs()); + TERN_(Z2_HAS_STEALTHCHOP, tmc_hybrid_threshold.Z2 = stepperZ2.get_pwm_thrs()); + TERN_(Z3_HAS_STEALTHCHOP, tmc_hybrid_threshold.Z3 = stepperZ3.get_pwm_thrs()); + TERN_(Z4_HAS_STEALTHCHOP, tmc_hybrid_threshold.Z4 = stepperZ4.get_pwm_thrs()); + TERN_(E0_HAS_STEALTHCHOP, tmc_hybrid_threshold.E0 = stepperE0.get_pwm_thrs()); + TERN_(E1_HAS_STEALTHCHOP, tmc_hybrid_threshold.E1 = stepperE1.get_pwm_thrs()); + TERN_(E2_HAS_STEALTHCHOP, tmc_hybrid_threshold.E2 = stepperE2.get_pwm_thrs()); + TERN_(E3_HAS_STEALTHCHOP, tmc_hybrid_threshold.E3 = stepperE3.get_pwm_thrs()); + TERN_(E4_HAS_STEALTHCHOP, tmc_hybrid_threshold.E4 = stepperE4.get_pwm_thrs()); + TERN_(E5_HAS_STEALTHCHOP, tmc_hybrid_threshold.E5 = stepperE5.get_pwm_thrs()); + TERN_(E6_HAS_STEALTHCHOP, tmc_hybrid_threshold.E6 = stepperE6.get_pwm_thrs()); + TERN_(E7_HAS_STEALTHCHOP, tmc_hybrid_threshold.E7 = stepperE7.get_pwm_thrs()); #else + #define _EN_ITEM(N) , .E##N = 30 const tmc_hybrid_threshold_t tmc_hybrid_threshold = { - .X = 100, .Y = 100, .Z = 3, - .X2 = 100, .Y2 = 100, .Z2 = 3, .Z3 = 3, .Z4 = 3, - .E0 = 30, .E1 = 30, .E2 = 30, - .E3 = 30, .E4 = 30, .E5 = 30 + LINEAR_AXIS_LIST(.X = 100, .Y = 100, .Z = 3, .I = 3, .J = 3, .K = 3), + .X2 = 100, .Y2 = 100, .Z2 = 3, .Z3 = 3, .Z4 = 3 + REPEAT(E_STEPPERS, _EN_ITEM) }; + #undef _EN_ITEM #endif EEPROM_WRITE(tmc_hybrid_threshold); } @@ -1171,11 +1199,16 @@ void MarlinSettings::postprocess() { { tmc_sgt_t tmc_sgt{0}; #if USE_SENSORLESS - TERN_(X_SENSORLESS, tmc_sgt.X = stepperX.homing_threshold()); + LINEAR_AXIS_CODE( + TERN_(X_SENSORLESS, tmc_sgt.X = stepperX.homing_threshold()), + TERN_(Y_SENSORLESS, tmc_sgt.Y = stepperY.homing_threshold()), + TERN_(Z_SENSORLESS, tmc_sgt.Z = stepperZ.homing_threshold()), + TERN_(I_SENSORLESS, tmc_sgt.I = stepperI.homing_threshold()), + TERN_(J_SENSORLESS, tmc_sgt.J = stepperJ.homing_threshold()), + TERN_(K_SENSORLESS, tmc_sgt.K = stepperK.homing_threshold()) + ); TERN_(X2_SENSORLESS, tmc_sgt.X2 = stepperX2.homing_threshold()); - TERN_(Y_SENSORLESS, tmc_sgt.Y = stepperY.homing_threshold()); TERN_(Y2_SENSORLESS, tmc_sgt.Y2 = stepperY2.homing_threshold()); - TERN_(Z_SENSORLESS, tmc_sgt.Z = stepperZ.homing_threshold()); TERN_(Z2_SENSORLESS, tmc_sgt.Z2 = stepperZ2.homing_threshold()); TERN_(Z3_SENSORLESS, tmc_sgt.Z3 = stepperZ3.homing_threshold()); TERN_(Z4_SENSORLESS, tmc_sgt.Z4 = stepperZ4.homing_threshold()); @@ -1189,74 +1222,26 @@ void MarlinSettings::postprocess() { { _FIELD_TEST(tmc_stealth_enabled); - tmc_stealth_enabled_t tmc_stealth_enabled = { false, false, false, false, false, false, false, false, false, false, false, false, false }; - - #if HAS_STEALTHCHOP - #if AXIS_HAS_STEALTHCHOP(X) - tmc_stealth_enabled.X = stepperX.get_stored_stealthChop_status(); - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - tmc_stealth_enabled.Y = stepperY.get_stored_stealthChop_status(); - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - tmc_stealth_enabled.Z = stepperZ.get_stored_stealthChop_status(); - #endif - #if AXIS_HAS_STEALTHCHOP(X2) - tmc_stealth_enabled.X2 = stepperX2.get_stored_stealthChop_status(); - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - tmc_stealth_enabled.Y2 = stepperY2.get_stored_stealthChop_status(); - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - tmc_stealth_enabled.Z2 = stepperZ2.get_stored_stealthChop_status(); - #endif - #if AXIS_HAS_STEALTHCHOP(Z3) - tmc_stealth_enabled.Z3 = stepperZ3.get_stored_stealthChop_status(); - #endif - #if AXIS_HAS_STEALTHCHOP(Z4) - tmc_stealth_enabled.Z4 = stepperZ4.get_stored_stealthChop_status(); - #endif - #if MAX_EXTRUDERS - #if AXIS_HAS_STEALTHCHOP(E0) - tmc_stealth_enabled.E0 = stepperE0.get_stored_stealthChop_status(); - #endif - #if MAX_EXTRUDERS > 1 - #if AXIS_HAS_STEALTHCHOP(E1) - tmc_stealth_enabled.E1 = stepperE1.get_stored_stealthChop_status(); - #endif - #if MAX_EXTRUDERS > 2 - #if AXIS_HAS_STEALTHCHOP(E2) - tmc_stealth_enabled.E2 = stepperE2.get_stored_stealthChop_status(); - #endif - #if MAX_EXTRUDERS > 3 - #if AXIS_HAS_STEALTHCHOP(E3) - tmc_stealth_enabled.E3 = stepperE3.get_stored_stealthChop_status(); - #endif - #if MAX_EXTRUDERS > 4 - #if AXIS_HAS_STEALTHCHOP(E4) - tmc_stealth_enabled.E4 = stepperE4.get_stored_stealthChop_status(); - #endif - #if MAX_EXTRUDERS > 5 - #if AXIS_HAS_STEALTHCHOP(E5) - tmc_stealth_enabled.E5 = stepperE5.get_stored_stealthChop_status(); - #endif - #if MAX_EXTRUDERS > 6 - #if AXIS_HAS_STEALTHCHOP(E6) - tmc_stealth_enabled.E6 = stepperE6.get_stored_stealthChop_status(); - #endif - #if MAX_EXTRUDERS > 7 - #if AXIS_HAS_STEALTHCHOP(E7) - tmc_stealth_enabled.E7 = stepperE7.get_stored_stealthChop_status(); - #endif - #endif // MAX_EXTRUDERS > 7 - #endif // MAX_EXTRUDERS > 6 - #endif // MAX_EXTRUDERS > 5 - #endif // MAX_EXTRUDERS > 4 - #endif // MAX_EXTRUDERS > 3 - #endif // MAX_EXTRUDERS > 2 - #endif // MAX_EXTRUDERS > 1 - #endif // MAX_EXTRUDERS - #endif + tmc_stealth_enabled_t tmc_stealth_enabled = { false }; + TERN_(X_HAS_STEALTHCHOP, tmc_stealth_enabled.X = stepperX.get_stored_stealthChop()); + TERN_(Y_HAS_STEALTHCHOP, tmc_stealth_enabled.Y = stepperY.get_stored_stealthChop()); + TERN_(Z_HAS_STEALTHCHOP, tmc_stealth_enabled.Z = stepperZ.get_stored_stealthChop()); + TERN_(I_HAS_STEALTHCHOP, tmc_stealth_enabled.I = stepperI.get_stored_stealthChop()); + TERN_(J_HAS_STEALTHCHOP, tmc_stealth_enabled.J = stepperJ.get_stored_stealthChop()); + TERN_(K_HAS_STEALTHCHOP, tmc_stealth_enabled.K = stepperK.get_stored_stealthChop()); + TERN_(X2_HAS_STEALTHCHOP, tmc_stealth_enabled.X2 = stepperX2.get_stored_stealthChop()); + TERN_(Y2_HAS_STEALTHCHOP, tmc_stealth_enabled.Y2 = stepperY2.get_stored_stealthChop()); + TERN_(Z2_HAS_STEALTHCHOP, tmc_stealth_enabled.Z2 = stepperZ2.get_stored_stealthChop()); + TERN_(Z3_HAS_STEALTHCHOP, tmc_stealth_enabled.Z3 = stepperZ3.get_stored_stealthChop()); + TERN_(Z4_HAS_STEALTHCHOP, tmc_stealth_enabled.Z4 = stepperZ4.get_stored_stealthChop()); + TERN_(E0_HAS_STEALTHCHOP, tmc_stealth_enabled.E0 = stepperE0.get_stored_stealthChop()); + TERN_(E1_HAS_STEALTHCHOP, tmc_stealth_enabled.E1 = stepperE1.get_stored_stealthChop()); + TERN_(E2_HAS_STEALTHCHOP, tmc_stealth_enabled.E2 = stepperE2.get_stored_stealthChop()); + TERN_(E3_HAS_STEALTHCHOP, tmc_stealth_enabled.E3 = stepperE3.get_stored_stealthChop()); + TERN_(E4_HAS_STEALTHCHOP, tmc_stealth_enabled.E4 = stepperE4.get_stored_stealthChop()); + TERN_(E5_HAS_STEALTHCHOP, tmc_stealth_enabled.E5 = stepperE5.get_stored_stealthChop()); + TERN_(E6_HAS_STEALTHCHOP, tmc_stealth_enabled.E6 = stepperE6.get_stored_stealthChop()); + TERN_(E7_HAS_STEALTHCHOP, tmc_stealth_enabled.E7 = stepperE7.get_stored_stealthChop()); EEPROM_WRITE(tmc_stealth_enabled); } @@ -1308,7 +1293,7 @@ void MarlinSettings::postprocess() { // // Advanced Pause filament load & unload lengths // - #if EXTRUDERS + #if HAS_EXTRUDERS { #if DISABLED(ADVANCED_PAUSE_FEATURE) const fil_change_settings_t fc_settings[EXTRUDERS] = { 0, 0 }; @@ -1353,18 +1338,18 @@ void MarlinSettings::postprocess() { // Extensible UI User Data // #if ENABLED(EXTENSIBLE_UI) - { - char extui_data[ExtUI::eeprom_data_size] = { 0 }; - ExtUI::onStoreSettings(extui_data); - _FIELD_TEST(extui_data); - EEPROM_WRITE(extui_data); - } + { + char extui_data[ExtUI::eeprom_data_size] = { 0 }; + ExtUI::onStoreSettings(extui_data); + _FIELD_TEST(extui_data); + EEPROM_WRITE(extui_data); + } #endif // // Case Light Brightness // - #if HAS_CASE_LIGHT_BRIGHTNESS + #if CASELIGHT_USES_BRIGHTNESS EEPROM_WRITE(caselight.brightness); #endif @@ -1380,11 +1365,54 @@ void MarlinSettings::postprocess() { // TOUCH_SCREEN_CALIBRATION // #if ENABLED(TOUCH_SCREEN_CALIBRATION) - EEPROM_WRITE(touch.calibration); + EEPROM_WRITE(touch_calibration.calibration); + #endif + + // + // Ethernet network info + // + #if HAS_ETHERNET + { + _FIELD_TEST(ethernet_hardware_enabled); + const bool ethernet_hardware_enabled = ethernet.hardware_enabled; + const uint32_t ethernet_ip = ethernet.ip, + ethernet_dns = ethernet.myDns, + ethernet_gateway = ethernet.gateway, + ethernet_subnet = ethernet.subnet; + EEPROM_WRITE(ethernet_hardware_enabled); + EEPROM_WRITE(ethernet_ip); + EEPROM_WRITE(ethernet_dns); + EEPROM_WRITE(ethernet_gateway); + EEPROM_WRITE(ethernet_subnet); + } #endif // - // Validate CRC and Data Size + // Buzzer enable/disable + // + #if ENABLED(SOUND_MENU_ITEM) + EEPROM_WRITE(ui.buzzer_enabled); + #endif + + // + // MKS UI controller + // + #if ENABLED(DGUS_LCD_UI_MKS) + EEPROM_WRITE(mks_language_index); + EEPROM_WRITE(mks_corner_offsets); + EEPROM_WRITE(mks_park_pos); + EEPROM_WRITE(mks_min_extrusion_temp); + #endif + + // + // Selected LCD language + // + #if HAS_MULTI_LANGUAGE + EEPROM_WRITE(ui.language); + #endif + + // + // Report final CRC and Data Size // if (!eeprom_error) { const uint16_t eeprom_size = eeprom_index - (EEPROM_OFFSET), @@ -1397,8 +1425,7 @@ void MarlinSettings::postprocess() { EEPROM_WRITE(final_crc); // Report storage size - DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("Settings Stored (", eeprom_size, " bytes; crc ", (uint32_t)final_crc, ")"); + DEBUG_ECHO_MSG("Settings Stored (", eeprom_size, " bytes; crc ", (uint32_t)final_crc, ")"); eeprom_error |= size_error(eeprom_size); } @@ -1423,9 +1450,7 @@ void MarlinSettings::postprocess() { * M501 - Retrieve Configuration */ bool MarlinSettings::_load() { - uint16_t working_crc = 0; - - EEPROM_START(); + if (!EEPROM_START(EEPROM_OFFSET)) return false; char stored_ver[4]; EEPROM_READ_ALWAYS(stored_ver); @@ -1439,9 +1464,8 @@ void MarlinSettings::postprocess() { stored_ver[0] = '?'; stored_ver[1] = '\0'; } - DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("EEPROM version mismatch (EEPROM=", stored_ver, " Marlin=" EEPROM_VERSION ")"); - TERN(EEPROM_AUTO_INIT,,ui.eeprom_alert_version()); + DEBUG_ECHO_MSG("EEPROM version mismatch (EEPROM=", stored_ver, " Marlin=" EEPROM_VERSION ")"); + IF_DISABLED(EEPROM_AUTO_INIT, ui.eeprom_alert_version()); eeprom_error = true; } else { @@ -1460,16 +1484,16 @@ void MarlinSettings::postprocess() { { // Get only the number of E stepper parameters previously stored // Any steppers added later are set to their defaults - uint32_t tmp1[XYZ + esteppers]; - float tmp2[XYZ + esteppers]; - feedRate_t tmp3[XYZ + esteppers]; - EEPROM_READ(tmp1); // max_acceleration_mm_per_s2 + uint32_t tmp1[LINEAR_AXES + esteppers]; + float tmp2[LINEAR_AXES + esteppers]; + feedRate_t tmp3[LINEAR_AXES + esteppers]; + EEPROM_READ((uint8_t *)tmp1, sizeof(tmp1)); // max_acceleration_mm_per_s2 EEPROM_READ(planner.settings.min_segment_time_us); - EEPROM_READ(tmp2); // axis_steps_per_mm - EEPROM_READ(tmp3); // max_feedrate_mm_s + EEPROM_READ((uint8_t *)tmp2, sizeof(tmp2)); // axis_steps_per_mm + EEPROM_READ((uint8_t *)tmp3, sizeof(tmp3)); // max_feedrate_mm_s - if (!validating) LOOP_XYZE_N(i) { - const bool in = (i < esteppers + XYZ); + if (!validating) LOOP_DISTINCT_AXES(i) { + const bool in = (i < esteppers + LINEAR_AXES); planner.settings.max_acceleration_mm_per_s2[i] = in ? tmp1[i] : pgm_read_dword(&_DMA[ALIM(i, _DMA)]); planner.settings.axis_steps_per_mm[i] = in ? tmp2[i] : pgm_read_float(&_DASU[ALIM(i, _DASU)]); planner.settings.max_feedrate_mm_s[i] = in ? tmp3[i] : pgm_read_float(&_DMF[ALIM(i, _DMF)]); @@ -1487,7 +1511,7 @@ void MarlinSettings::postprocess() { EEPROM_READ(dummyf); #endif #else - for (uint8_t q = 4; q--;) EEPROM_READ(dummyf); + for (uint8_t q = LOGICAL_AXES; q--;) EEPROM_READ(dummyf); #endif EEPROM_READ(TERN(CLASSIC_JERK, dummyf, planner.junction_deviation_mm)); @@ -1556,7 +1580,7 @@ void MarlinSettings::postprocess() { #if ENABLED(MESH_BED_LEVELING) if (!validating) mbl.z_offset = dummyf; - if (mesh_num_x == GRID_MAX_POINTS_X && mesh_num_y == GRID_MAX_POINTS_Y) { + if (mesh_num_x == (GRID_MAX_POINTS_X) && mesh_num_y == (GRID_MAX_POINTS_Y)) { // EEPROM data fits the current mesh EEPROM_READ(mbl.z_values); } @@ -1603,7 +1627,7 @@ void MarlinSettings::postprocess() { EEPROM_READ_ALWAYS(grid_max_x); // 1 byte EEPROM_READ_ALWAYS(grid_max_y); // 1 byte #if ENABLED(AUTO_BED_LEVELING_BILINEAR) - if (grid_max_x == GRID_MAX_POINTS_X && grid_max_y == GRID_MAX_POINTS_Y) { + if (grid_max_x == (GRID_MAX_POINTS_X) && grid_max_y == (GRID_MAX_POINTS_Y)) { if (!validating) set_bed_leveling_enabled(false); EEPROM_READ(bilinear_grid_spacing); // 2 ints EEPROM_READ(bilinear_start); // 2 ints @@ -1688,7 +1712,7 @@ void MarlinSettings::postprocess() { EEPROM_READ(delta_endstop_adj); // 3 floats EEPROM_READ(delta_radius); // 1 float EEPROM_READ(delta_diagonal_rod); // 1 float - EEPROM_READ(delta_segments_per_second); // 1 float + EEPROM_READ(segments_per_second); // 1 float EEPROM_READ(delta_tower_angle_trim); // 3 floats EEPROM_READ(delta_diagonal_rod_trim); // 3 floats @@ -1778,6 +1802,22 @@ void MarlinSettings::postprocess() { #endif } + // + // Heated Chamber PID + // + { + PID_t pid; + EEPROM_READ(pid); + #if ENABLED(PIDTEMPCHAMBER) + if (!validating && !isnan(pid.Kp)) { + // Scale PID values since EEPROM values are unscaled + thermalManager.temp_chamber.pid.Kp = pid.Kp; + thermalManager.temp_chamber.pid.Ki = scalePID_i(pid.Ki); + thermalManager.temp_chamber.pid.Kd = scalePID_d(pid.Kd); + } + #endif + } + // // User-defined Thermistors // @@ -1813,6 +1853,16 @@ void MarlinSettings::postprocess() { } } + // + // LCD Brightness + // + { + _FIELD_TEST(lcd_brightness); + uint8_t lcd_brightness; + EEPROM_READ(lcd_brightness); + TERN_(HAS_LCD_BRIGHTNESS, if (!validating) ui.set_brightness(lcd_brightness)); + } + // // Controller Fan // @@ -1924,6 +1974,15 @@ void MarlinSettings::postprocess() { #if AXIS_IS_TMC(Z4) SET_CURR(Z4); #endif + #if AXIS_IS_TMC(I) + SET_CURR(I); + #endif + #if AXIS_IS_TMC(J) + SET_CURR(J); + #endif + #if AXIS_IS_TMC(K) + SET_CURR(K); + #endif #if AXIS_IS_TMC(E0) SET_CURR(E0); #endif @@ -1960,54 +2019,25 @@ void MarlinSettings::postprocess() { #if ENABLED(HYBRID_THRESHOLD) if (!validating) { - #if AXIS_HAS_STEALTHCHOP(X) - stepperX.set_pwm_thrs(tmc_hybrid_threshold.X); - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - stepperY.set_pwm_thrs(tmc_hybrid_threshold.Y); - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - stepperZ.set_pwm_thrs(tmc_hybrid_threshold.Z); - #endif - #if AXIS_HAS_STEALTHCHOP(X2) - stepperX2.set_pwm_thrs(tmc_hybrid_threshold.X2); - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - stepperY2.set_pwm_thrs(tmc_hybrid_threshold.Y2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - stepperZ2.set_pwm_thrs(tmc_hybrid_threshold.Z2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z3) - stepperZ3.set_pwm_thrs(tmc_hybrid_threshold.Z3); - #endif - #if AXIS_HAS_STEALTHCHOP(Z4) - stepperZ4.set_pwm_thrs(tmc_hybrid_threshold.Z4); - #endif - #if AXIS_HAS_STEALTHCHOP(E0) - stepperE0.set_pwm_thrs(tmc_hybrid_threshold.E0); - #endif - #if AXIS_HAS_STEALTHCHOP(E1) - stepperE1.set_pwm_thrs(tmc_hybrid_threshold.E1); - #endif - #if AXIS_HAS_STEALTHCHOP(E2) - stepperE2.set_pwm_thrs(tmc_hybrid_threshold.E2); - #endif - #if AXIS_HAS_STEALTHCHOP(E3) - stepperE3.set_pwm_thrs(tmc_hybrid_threshold.E3); - #endif - #if AXIS_HAS_STEALTHCHOP(E4) - stepperE4.set_pwm_thrs(tmc_hybrid_threshold.E4); - #endif - #if AXIS_HAS_STEALTHCHOP(E5) - stepperE5.set_pwm_thrs(tmc_hybrid_threshold.E5); - #endif - #if AXIS_HAS_STEALTHCHOP(E6) - stepperE6.set_pwm_thrs(tmc_hybrid_threshold.E6); - #endif - #if AXIS_HAS_STEALTHCHOP(E7) - stepperE7.set_pwm_thrs(tmc_hybrid_threshold.E7); - #endif + TERN_(X_HAS_STEALTHCHOP, stepperX.set_pwm_thrs(tmc_hybrid_threshold.X)); + TERN_(Y_HAS_STEALTHCHOP, stepperY.set_pwm_thrs(tmc_hybrid_threshold.Y)); + TERN_(Z_HAS_STEALTHCHOP, stepperZ.set_pwm_thrs(tmc_hybrid_threshold.Z)); + TERN_(X2_HAS_STEALTHCHOP, stepperX2.set_pwm_thrs(tmc_hybrid_threshold.X2)); + TERN_(Y2_HAS_STEALTHCHOP, stepperY2.set_pwm_thrs(tmc_hybrid_threshold.Y2)); + TERN_(Z2_HAS_STEALTHCHOP, stepperZ2.set_pwm_thrs(tmc_hybrid_threshold.Z2)); + TERN_(Z3_HAS_STEALTHCHOP, stepperZ3.set_pwm_thrs(tmc_hybrid_threshold.Z3)); + TERN_(Z4_HAS_STEALTHCHOP, stepperZ4.set_pwm_thrs(tmc_hybrid_threshold.Z4)); + TERN_(I_HAS_STEALTHCHOP, stepperI.set_pwm_thrs(tmc_hybrid_threshold.I)); + TERN_(J_HAS_STEALTHCHOP, stepperJ.set_pwm_thrs(tmc_hybrid_threshold.J)); + TERN_(K_HAS_STEALTHCHOP, stepperK.set_pwm_thrs(tmc_hybrid_threshold.K)); + TERN_(E0_HAS_STEALTHCHOP, stepperE0.set_pwm_thrs(tmc_hybrid_threshold.E0)); + TERN_(E1_HAS_STEALTHCHOP, stepperE1.set_pwm_thrs(tmc_hybrid_threshold.E1)); + TERN_(E2_HAS_STEALTHCHOP, stepperE2.set_pwm_thrs(tmc_hybrid_threshold.E2)); + TERN_(E3_HAS_STEALTHCHOP, stepperE3.set_pwm_thrs(tmc_hybrid_threshold.E3)); + TERN_(E4_HAS_STEALTHCHOP, stepperE4.set_pwm_thrs(tmc_hybrid_threshold.E4)); + TERN_(E5_HAS_STEALTHCHOP, stepperE5.set_pwm_thrs(tmc_hybrid_threshold.E5)); + TERN_(E6_HAS_STEALTHCHOP, stepperE6.set_pwm_thrs(tmc_hybrid_threshold.E6)); + TERN_(E7_HAS_STEALTHCHOP, stepperE7.set_pwm_thrs(tmc_hybrid_threshold.E7)); } #endif } @@ -2021,11 +2051,16 @@ void MarlinSettings::postprocess() { EEPROM_READ(tmc_sgt); #if USE_SENSORLESS if (!validating) { - TERN_(X_SENSORLESS, stepperX.homing_threshold(tmc_sgt.X)); + LINEAR_AXIS_CODE( + TERN_(X_SENSORLESS, stepperX.homing_threshold(tmc_sgt.X)), + TERN_(Y_SENSORLESS, stepperY.homing_threshold(tmc_sgt.Y)), + TERN_(Z_SENSORLESS, stepperZ.homing_threshold(tmc_sgt.Z)), + TERN_(I_SENSORLESS, stepperI.homing_threshold(tmc_sgt.I)), + TERN_(J_SENSORLESS, stepperJ.homing_threshold(tmc_sgt.J)), + TERN_(K_SENSORLESS, stepperK.homing_threshold(tmc_sgt.K)) + ); TERN_(X2_SENSORLESS, stepperX2.homing_threshold(tmc_sgt.X2)); - TERN_(Y_SENSORLESS, stepperY.homing_threshold(tmc_sgt.Y)); TERN_(Y2_SENSORLESS, stepperY2.homing_threshold(tmc_sgt.Y2)); - TERN_(Z_SENSORLESS, stepperZ.homing_threshold(tmc_sgt.Z)); TERN_(Z2_SENSORLESS, stepperZ2.homing_threshold(tmc_sgt.Z2)); TERN_(Z3_SENSORLESS, stepperZ3.homing_threshold(tmc_sgt.Z3)); TERN_(Z4_SENSORLESS, stepperZ4.homing_threshold(tmc_sgt.Z4)); @@ -2044,54 +2079,25 @@ void MarlinSettings::postprocess() { #define SET_STEPPING_MODE(ST) stepper##ST.stored.stealthChop_enabled = tmc_stealth_enabled.ST; stepper##ST.refresh_stepping_mode(); if (!validating) { - #if AXIS_HAS_STEALTHCHOP(X) - SET_STEPPING_MODE(X); - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - SET_STEPPING_MODE(Y); - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - SET_STEPPING_MODE(Z); - #endif - #if AXIS_HAS_STEALTHCHOP(X2) - SET_STEPPING_MODE(X2); - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - SET_STEPPING_MODE(Y2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - SET_STEPPING_MODE(Z2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z3) - SET_STEPPING_MODE(Z3); - #endif - #if AXIS_HAS_STEALTHCHOP(Z4) - SET_STEPPING_MODE(Z4); - #endif - #if AXIS_HAS_STEALTHCHOP(E0) - SET_STEPPING_MODE(E0); - #endif - #if AXIS_HAS_STEALTHCHOP(E1) - SET_STEPPING_MODE(E1); - #endif - #if AXIS_HAS_STEALTHCHOP(E2) - SET_STEPPING_MODE(E2); - #endif - #if AXIS_HAS_STEALTHCHOP(E3) - SET_STEPPING_MODE(E3); - #endif - #if AXIS_HAS_STEALTHCHOP(E4) - SET_STEPPING_MODE(E4); - #endif - #if AXIS_HAS_STEALTHCHOP(E5) - SET_STEPPING_MODE(E5); - #endif - #if AXIS_HAS_STEALTHCHOP(E6) - SET_STEPPING_MODE(E6); - #endif - #if AXIS_HAS_STEALTHCHOP(E7) - SET_STEPPING_MODE(E7); - #endif + TERN_(X_HAS_STEALTHCHOP, SET_STEPPING_MODE(X)); + TERN_(Y_HAS_STEALTHCHOP, SET_STEPPING_MODE(Y)); + TERN_(Z_HAS_STEALTHCHOP, SET_STEPPING_MODE(Z)); + TERN_(I_HAS_STEALTHCHOP, SET_STEPPING_MODE(I)); + TERN_(J_HAS_STEALTHCHOP, SET_STEPPING_MODE(J)); + TERN_(K_HAS_STEALTHCHOP, SET_STEPPING_MODE(K)); + TERN_(X2_HAS_STEALTHCHOP, SET_STEPPING_MODE(X2)); + TERN_(Y2_HAS_STEALTHCHOP, SET_STEPPING_MODE(Y2)); + TERN_(Z2_HAS_STEALTHCHOP, SET_STEPPING_MODE(Z2)); + TERN_(Z3_HAS_STEALTHCHOP, SET_STEPPING_MODE(Z3)); + TERN_(Z4_HAS_STEALTHCHOP, SET_STEPPING_MODE(Z4)); + TERN_(E0_HAS_STEALTHCHOP, SET_STEPPING_MODE(E0)); + TERN_(E1_HAS_STEALTHCHOP, SET_STEPPING_MODE(E1)); + TERN_(E2_HAS_STEALTHCHOP, SET_STEPPING_MODE(E2)); + TERN_(E3_HAS_STEALTHCHOP, SET_STEPPING_MODE(E3)); + TERN_(E4_HAS_STEALTHCHOP, SET_STEPPING_MODE(E4)); + TERN_(E5_HAS_STEALTHCHOP, SET_STEPPING_MODE(E5)); + TERN_(E6_HAS_STEALTHCHOP, SET_STEPPING_MODE(E6)); + TERN_(E7_HAS_STEALTHCHOP, SET_STEPPING_MODE(E7)); } #endif } @@ -2119,9 +2125,13 @@ void MarlinSettings::postprocess() { = DIGIPOT_MOTOR_CURRENT #endif ; - DEBUG_ECHOLNPGM("DIGIPOTS Loading"); + #if HAS_MOTOR_CURRENT_SPI + DEBUG_ECHO_MSG("DIGIPOTS Loading"); + #endif EEPROM_READ(motor_current_setting); - DEBUG_ECHOLNPGM("DIGIPOTS Loaded"); + #if HAS_MOTOR_CURRENT_SPI + DEBUG_ECHO_MSG("DIGIPOTS Loaded"); + #endif #if HAS_MOTOR_CURRENT_SPI || HAS_MOTOR_CURRENT_PWM if (!validating) COPY(stepper.motor_current_setting, motor_current_setting); @@ -2163,7 +2173,7 @@ void MarlinSettings::postprocess() { // // Advanced Pause filament load & unload lengths // - #if EXTRUDERS + #if HAS_EXTRUDERS { #if DISABLED(ADVANCED_PAUSE_FEATURE) fil_change_settings_t fc_settings[EXTRUDERS]; @@ -2189,7 +2199,7 @@ void MarlinSettings::postprocess() { const xyz_float_t &backlash_distance_mm = backlash.distance_mm; const uint8_t &backlash_correction = backlash.correction; #else - float backlash_distance_mm[XYZ]; + xyz_float_t backlash_distance_mm; uint8_t backlash_correction; #endif #if ENABLED(BACKLASH_GCODE) && defined(BACKLASH_SMOOTHING_MM) @@ -2207,19 +2217,18 @@ void MarlinSettings::postprocess() { // Extensible UI User Data // #if ENABLED(EXTENSIBLE_UI) - // This is a significant hardware change; don't reserve EEPROM space when not present - { - const char extui_data[ExtUI::eeprom_data_size] = { 0 }; - _FIELD_TEST(extui_data); - EEPROM_READ(extui_data); - if (!validating) ExtUI::onLoadSettings(extui_data); - } + { // This is a significant hardware change; don't reserve EEPROM space when not present + const char extui_data[ExtUI::eeprom_data_size] = { 0 }; + _FIELD_TEST(extui_data); + EEPROM_READ(extui_data); + if (!validating) ExtUI::onLoadSettings(extui_data); + } #endif // // Case Light Brightness // - #if HAS_CASE_LIGHT_BRIGHTNESS + #if CASELIGHT_USES_BRIGHTNESS _FIELD_TEST(caselight_brightness); EEPROM_READ(caselight.brightness); #endif @@ -2237,21 +2246,66 @@ void MarlinSettings::postprocess() { // TOUCH_SCREEN_CALIBRATION // #if ENABLED(TOUCH_SCREEN_CALIBRATION) - _FIELD_TEST(touch.calibration); - EEPROM_READ(touch.calibration); + _FIELD_TEST(touch_calibration_data); + EEPROM_READ(touch_calibration.calibration); + #endif + + // + // Ethernet network info + // + #if HAS_ETHERNET + _FIELD_TEST(ethernet_hardware_enabled); + uint32_t ethernet_ip, ethernet_dns, ethernet_gateway, ethernet_subnet; + EEPROM_READ(ethernet.hardware_enabled); + EEPROM_READ(ethernet_ip); ethernet.ip = ethernet_ip; + EEPROM_READ(ethernet_dns); ethernet.myDns = ethernet_dns; + EEPROM_READ(ethernet_gateway); ethernet.gateway = ethernet_gateway; + EEPROM_READ(ethernet_subnet); ethernet.subnet = ethernet_subnet; + #endif + + // + // Buzzer enable/disable + // + #if ENABLED(SOUND_MENU_ITEM) + _FIELD_TEST(buzzer_enabled); + EEPROM_READ(ui.buzzer_enabled); #endif + // + // MKS UI controller + // + #if ENABLED(DGUS_LCD_UI_MKS) + _FIELD_TEST(mks_language_index); + EEPROM_READ(mks_language_index); + EEPROM_READ(mks_corner_offsets); + EEPROM_READ(mks_park_pos); + EEPROM_READ(mks_min_extrusion_temp); + #endif + + // + // Selected LCD language + // + #if HAS_MULTI_LANGUAGE + { + uint8_t ui_language; + EEPROM_READ(ui_language); + if (ui_language >= NUM_LANGUAGES) ui_language = 0; + ui.set_language(ui_language); + } + #endif + + // + // Validate Final Size and CRC + // eeprom_error = size_error(eeprom_index - (EEPROM_OFFSET)); if (eeprom_error) { - DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("Index: ", int(eeprom_index - (EEPROM_OFFSET)), " Size: ", datasize()); - TERN(EEPROM_AUTO_INIT,,ui.eeprom_alert_index()); + DEBUG_ECHO_MSG("Index: ", eeprom_index - (EEPROM_OFFSET), " Size: ", datasize()); + IF_DISABLED(EEPROM_AUTO_INIT, ui.eeprom_alert_index()); } else if (working_crc != stored_crc) { eeprom_error = true; - DEBUG_ERROR_START(); - DEBUG_ECHOLNPAIR("EEPROM CRC mismatch - (stored) ", stored_crc, " != ", working_crc, " (calculated)!"); - TERN(EEPROM_AUTO_INIT,,ui.eeprom_alert_crc()); + DEBUG_ERROR_MSG("EEPROM CRC mismatch - (stored) ", stored_crc, " != ", working_crc, " (calculated)!"); + IF_DISABLED(EEPROM_AUTO_INIT, ui.eeprom_alert_crc()); } else if (!validating) { DEBUG_ECHO_START(); @@ -2266,15 +2320,14 @@ void MarlinSettings::postprocess() { ubl.report_state(); if (!ubl.sanity_check()) { - SERIAL_EOL(); - #if ENABLED(EEPROM_CHITCHAT) + #if BOTH(EEPROM_CHITCHAT, DEBUG_LEVELING_FEATURE) ubl.echo_name(); DEBUG_ECHOLNPGM(" initialized.\n"); #endif } else { eeprom_error = true; - #if ENABLED(EEPROM_CHITCHAT) + #if BOTH(EEPROM_CHITCHAT, DEBUG_LEVELING_FEATURE) DEBUG_ECHOPGM("?Can't enable "); ubl.echo_name(); DEBUG_ECHOLNPGM("."); @@ -2296,7 +2349,7 @@ void MarlinSettings::postprocess() { #if ENABLED(EEPROM_CHITCHAT) && DISABLED(DISABLE_M503) // Report the EEPROM settings - if (!validating && (DISABLED(EEPROM_BOOT_SILENT) || IsRunning())) report(); + if (!validating && TERN1(EEPROM_BOOT_SILENT, IsRunning())) report(); #endif EEPROM_FINISH(); @@ -2340,13 +2393,8 @@ void MarlinSettings::postprocess() { #if ENABLED(AUTO_BED_LEVELING_UBL) inline void ubl_invalid_slot(const int s) { - #if ENABLED(EEPROM_CHITCHAT) - DEBUG_ECHOLNPGM("?Invalid slot."); - DEBUG_ECHO(s); - DEBUG_ECHOLNPGM(" mesh slots available."); - #else - UNUSED(s); - #endif + DEBUG_ECHOLNPAIR("?Invalid slot.\n", s, " mesh slots available."); + UNUSED(s); } const uint16_t MarlinSettings::meshes_end = persistentStore.capacity() - 129; // 128 (+1 because of the change to capacity rather than last valid address) @@ -2358,12 +2406,14 @@ void MarlinSettings::postprocess() { // or down a little bit without disrupting the mesh data } + #define MESH_STORE_SIZE sizeof(TERN(OPTIMIZED_MESH_STORAGE, mesh_store_t, ubl.z_values)) + uint16_t MarlinSettings::calc_num_meshes() { - return (meshes_end - meshes_start_index()) / sizeof(ubl.z_values); + return (meshes_end - meshes_start_index()) / MESH_STORE_SIZE; } int MarlinSettings::mesh_slot_offset(const int8_t slot) { - return meshes_end - (slot + 1) * sizeof(ubl.z_values); + return meshes_end - (slot + 1) * MESH_STORE_SIZE; } void MarlinSettings::store_mesh(const int8_t slot) { @@ -2380,9 +2430,17 @@ void MarlinSettings::postprocess() { int pos = mesh_slot_offset(slot); uint16_t crc = 0; + #if ENABLED(OPTIMIZED_MESH_STORAGE) + int16_t z_mesh_store[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y]; + ubl.set_store_from_mesh(ubl.z_values, z_mesh_store); + uint8_t * const src = (uint8_t*)&z_mesh_store; + #else + uint8_t * const src = (uint8_t*)&ubl.z_values; + #endif + // Write crc to MAT along with other data, or just tack on to the beginning or end persistentStore.access_start(); - const bool status = persistentStore.write_data(pos, (uint8_t *)&ubl.z_values, sizeof(ubl.z_values), &crc); + const bool status = persistentStore.write_data(pos, src, MESH_STORE_SIZE, &crc); persistentStore.access_finish(); if (status) SERIAL_ECHOLNPGM("?Unable to save mesh data."); @@ -2408,12 +2466,27 @@ void MarlinSettings::postprocess() { int pos = mesh_slot_offset(slot); uint16_t crc = 0; - uint8_t * const dest = into ? (uint8_t*)into : (uint8_t*)&ubl.z_values; + #if ENABLED(OPTIMIZED_MESH_STORAGE) + int16_t z_mesh_store[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y]; + uint8_t * const dest = (uint8_t*)&z_mesh_store; + #else + uint8_t * const dest = into ? (uint8_t*)into : (uint8_t*)&ubl.z_values; + #endif persistentStore.access_start(); - const uint16_t status = persistentStore.read_data(pos, dest, sizeof(ubl.z_values), &crc); + const uint16_t status = persistentStore.read_data(pos, dest, MESH_STORE_SIZE, &crc); persistentStore.access_finish(); + #if ENABLED(OPTIMIZED_MESH_STORAGE) + if (into) { + float z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y]; + ubl.set_mesh_from_store(z_mesh_store, z_values); + memcpy(into, z_values, sizeof(z_values)); + } + else + ubl.set_mesh_from_store(z_mesh_store, ubl.z_values); + #endif + if (status) SERIAL_ECHOLNPGM("?Unable to load mesh data."); else DEBUG_ECHOLNPAIR("Mesh loaded from slot ", slot); @@ -2444,10 +2517,10 @@ void MarlinSettings::postprocess() { * M502 - Reset Configuration */ void MarlinSettings::reset() { - LOOP_XYZE_N(i) { + LOOP_DISTINCT_AXES(i) { planner.settings.max_acceleration_mm_per_s2[i] = pgm_read_dword(&_DMA[ALIM(i, _DMA)]); - planner.settings.axis_steps_per_mm[i] = pgm_read_float(&_DASU[ALIM(i, _DASU)]); - planner.settings.max_feedrate_mm_s[i] = pgm_read_float(&_DMF[ALIM(i, _DMF)]); + planner.settings.axis_steps_per_mm[i] = pgm_read_float(&_DASU[ALIM(i, _DASU)]); + planner.settings.max_feedrate_mm_s[i] = pgm_read_float(&_DMF[ALIM(i, _DMF)]); } planner.settings.min_segment_time_us = DEFAULT_MINSEGMENTTIME; @@ -2461,14 +2534,25 @@ void MarlinSettings::reset() { #ifndef DEFAULT_XJERK #define DEFAULT_XJERK 0 #endif - #ifndef DEFAULT_YJERK + #if HAS_Y_AXIS && !defined(DEFAULT_YJERK) #define DEFAULT_YJERK 0 #endif - #ifndef DEFAULT_ZJERK + #if HAS_Z_AXIS && !defined(DEFAULT_ZJERK) #define DEFAULT_ZJERK 0 #endif - planner.max_jerk.set(DEFAULT_XJERK, DEFAULT_YJERK, DEFAULT_ZJERK); - TERN_(HAS_CLASSIC_E_JERK, planner.max_jerk.e = DEFAULT_EJERK;); + #if LINEAR_AXES >= 4 && !defined(DEFAULT_IJERK) + #define DEFAULT_IJERK 0 + #endif + #if LINEAR_AXES >= 5 && !defined(DEFAULT_JJERK) + #define DEFAULT_JJERK 0 + #endif + #if LINEAR_AXES >= 6 && !defined(DEFAULT_KJERK) + #define DEFAULT_KJERK 0 + #endif + planner.max_jerk.set( + LINEAR_AXIS_LIST(DEFAULT_XJERK, DEFAULT_YJERK, DEFAULT_ZJERK, DEFAULT_IJERK, DEFAULT_JJERK, DEFAULT_KJERK) + ); + TERN_(HAS_CLASSIC_E_JERK, planner.max_jerk.e = DEFAULT_EJERK); #endif #if HAS_JUNCTION_DEVIATION @@ -2541,12 +2625,17 @@ void MarlinSettings::reset() { // // Case Light Brightness // - TERN_(HAS_CASE_LIGHT_BRIGHTNESS, caselight.brightness = CASE_LIGHT_DEFAULT_BRIGHTNESS); + TERN_(CASELIGHT_USES_BRIGHTNESS, caselight.brightness = CASE_LIGHT_DEFAULT_BRIGHTNESS); // // TOUCH_SCREEN_CALIBRATION // - TERN_(TOUCH_SCREEN_CALIBRATION, touch.calibration_reset()); + TERN_(TOUCH_SCREEN_CALIBRATION, touch_calibration.calibration_reset()); + + // + // Buzzer enable/disable + // + TERN_(SOUND_MENU_ITEM, ui.buzzer_enabled = true); // // Magnetic Parking Extruder @@ -2556,16 +2645,16 @@ void MarlinSettings::reset() { // // Global Leveling // - TERN_(ENABLE_LEVELING_FADE_HEIGHT, new_z_fade_height = 0.0); + TERN_(ENABLE_LEVELING_FADE_HEIGHT, new_z_fade_height = (DEFAULT_LEVELING_FADE_HEIGHT)); TERN_(HAS_LEVELING, reset_bed_level()); #if HAS_BED_PROBE constexpr float dpo[] = NOZZLE_TO_PROBE_OFFSET; - static_assert(COUNT(dpo) == 3, "NOZZLE_TO_PROBE_OFFSET must contain offsets for X, Y, and Z."); + static_assert(COUNT(dpo) == LINEAR_AXES, "NOZZLE_TO_PROBE_OFFSET must contain offsets for each linear axis X, Y, Z...."); #if HAS_PROBE_XY_OFFSET - LOOP_XYZ(a) probe.offset[a] = dpo[a]; + LOOP_LINEAR_AXES(a) probe.offset[a] = dpo[a]; #else - probe.offset.set(0, 0, dpo[Z_AXIS]); + probe.offset.set(LINEAR_AXIS_LIST(0, 0, dpo[Z_AXIS], 0, 0, 0)); #endif #endif @@ -2596,7 +2685,7 @@ void MarlinSettings::reset() { delta_endstop_adj = adj; delta_radius = DELTA_RADIUS; delta_diagonal_rod = DELTA_DIAGONAL_ROD; - delta_segments_per_second = DELTA_SEGMENTS_PER_SECOND; + segments_per_second = DELTA_SEGMENTS_PER_SECOND; delta_tower_angle_trim = dta; delta_diagonal_rod_trim = ddr; #endif @@ -2638,25 +2727,20 @@ void MarlinSettings::reset() { // Preheat parameters // #if PREHEAT_COUNT + #define _PITEM(N,T) PREHEAT_##N##_##T, #if HAS_HOTEND - constexpr uint16_t hpre[] = ARRAY_N(PREHEAT_COUNT, PREHEAT_1_TEMP_HOTEND, PREHEAT_2_TEMP_HOTEND, PREHEAT_3_TEMP_HOTEND, PREHEAT_4_TEMP_HOTEND, PREHEAT_5_TEMP_HOTEND); + constexpr uint16_t hpre[] = { REPEAT2_S(1, INCREMENT(PREHEAT_COUNT), _PITEM, TEMP_HOTEND) }; #endif #if HAS_HEATED_BED - constexpr uint16_t bpre[] = ARRAY_N(PREHEAT_COUNT, PREHEAT_1_TEMP_BED, PREHEAT_2_TEMP_BED, PREHEAT_3_TEMP_BED, PREHEAT_4_TEMP_BED, PREHEAT_5_TEMP_BED); + constexpr uint16_t bpre[] = { REPEAT2_S(1, INCREMENT(PREHEAT_COUNT), _PITEM, TEMP_BED) }; #endif #if HAS_FAN - constexpr uint8_t fpre[] = ARRAY_N(PREHEAT_COUNT, PREHEAT_1_FAN_SPEED, PREHEAT_2_FAN_SPEED, PREHEAT_3_FAN_SPEED, PREHEAT_4_FAN_SPEED, PREHEAT_5_FAN_SPEED); + constexpr uint8_t fpre[] = { REPEAT2_S(1, INCREMENT(PREHEAT_COUNT), _PITEM, FAN_SPEED) }; #endif LOOP_L_N(i, PREHEAT_COUNT) { - #if HAS_HOTEND - ui.material_preset[i].hotend_temp = hpre[i]; - #endif - #if HAS_HEATED_BED - ui.material_preset[i].bed_temp = bpre[i]; - #endif - #if HAS_FAN - ui.material_preset[i].fan_speed = fpre[i]; - #endif + 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]); } #endif @@ -2736,6 +2820,16 @@ void MarlinSettings::reset() { thermalManager.temp_bed.pid.Kd = scalePID_d(DEFAULT_bedKd); #endif + // + // Heated Chamber PID + // + + #if ENABLED(PIDTEMPCHAMBER) + thermalManager.temp_chamber.pid.Kp = DEFAULT_chamberKp; + thermalManager.temp_chamber.pid.Ki = scalePID_i(DEFAULT_chamberKi); + thermalManager.temp_chamber.pid.Kd = scalePID_d(DEFAULT_chamberKd); + #endif + // // User-Defined Thermistors // @@ -2751,6 +2845,11 @@ void MarlinSettings::reset() { // TERN_(HAS_LCD_CONTRAST, ui.set_contrast(DEFAULT_LCD_CONTRAST)); + // + // LCD Brightness + // + TERN_(HAS_LCD_BRIGHTNESS, ui.set_brightness(DEFAULT_LCD_BRIGHTNESS)); + // // Controller Fan // @@ -2851,6 +2950,11 @@ void MarlinSettings::reset() { #endif #endif + // + // MKS UI controller + // + TERN_(DGUS_LCD_UI_MKS, MKS_reset_settings()); + postprocess(); DEBUG_ECHO_START(); @@ -2865,13 +2969,13 @@ void MarlinSettings::reset() { if (!repl) { SERIAL_ECHO_START(); SERIAL_ECHOPGM("; "); - serialprintPGM(pstr); + SERIAL_ECHOPGM_P(pstr); if (eol) SERIAL_EOL(); } } #define CONFIG_ECHO_START() do{ if (!forReplay) SERIAL_ECHO_START(); }while(0) - #define CONFIG_ECHO_MSG(STR) do{ CONFIG_ECHO_START(); SERIAL_ECHOLNPGM(STR); }while(0) + #define CONFIG_ECHO_MSG(V...) do{ CONFIG_ECHO_START(); SERIAL_ECHOLNPAIR(V); }while(0) #define CONFIG_ECHO_HEADING(STR) config_heading(forReplay, PSTR(STR)) #if HAS_TRINAMIC_CONFIG @@ -2882,7 +2986,7 @@ void MarlinSettings::reset() { SERIAL_ECHOPGM(" M569 S1"); if (etc) { SERIAL_CHAR(' '); - serialprintPGM(etc); + SERIAL_ECHOPGM_P(etc); } if (newLine) SERIAL_EOL(); } @@ -2900,7 +3004,7 @@ void MarlinSettings::reset() { #endif inline void say_units(const bool colon) { - serialprintPGM( + SERIAL_ECHOPGM_P( #if ENABLED(INCH_MODE_SUPPORT) parser.linear_unit_factor != 1.0 ? PSTR(" (in)") : #endif @@ -2941,7 +3045,7 @@ void MarlinSettings::reset() { SERIAL_ECHOPGM(" M149 "); SERIAL_CHAR(parser.temp_units_code()); SERIAL_ECHOPGM(" ; Units in "); - serialprintPGM(parser.temp_units_name()); + SERIAL_ECHOPGM_P(parser.temp_units_name()); #else SERIAL_ECHOLNPGM(" M149 C ; Units in Celsius"); #endif @@ -2964,26 +3068,24 @@ void MarlinSettings::reset() { } #if EXTRUDERS == 1 - CONFIG_ECHO_START(); - SERIAL_ECHOLNPAIR(" M200 S", int(parser.volumetric_enabled) - , " D", LINEAR_UNIT(planner.filament_size[0]) + CONFIG_ECHO_MSG(" M200 S", parser.volumetric_enabled + , " D", LINEAR_UNIT(planner.filament_size[0]) + #if ENABLED(VOLUMETRIC_EXTRUDER_LIMIT) + , " L", LINEAR_UNIT(planner.volumetric_extruder_limit[0]) + #endif + ); + #else + LOOP_L_N(i, EXTRUDERS) { + CONFIG_ECHO_MSG(" M200 T", i + , " D", LINEAR_UNIT(planner.filament_size[i]) #if ENABLED(VOLUMETRIC_EXTRUDER_LIMIT) - , " L", LINEAR_UNIT(planner.volumetric_extruder_limit[0]) + , " L", LINEAR_UNIT(planner.volumetric_extruder_limit[i]) #endif ); - #else - LOOP_L_N(i, EXTRUDERS) { - CONFIG_ECHO_START(); - SERIAL_ECHOLNPAIR(" M200 T", int(i) - , " D", LINEAR_UNIT(planner.filament_size[i]) - #if ENABLED(VOLUMETRIC_EXTRUDER_LIMIT) - , " L", LINEAR_UNIT(planner.volumetric_extruder_limit[i]) - #endif - ); } - CONFIG_ECHO_START(); - SERIAL_ECHOLNPAIR(" M200 S", int(parser.volumetric_enabled)); + CONFIG_ECHO_MSG(" M200 S", parser.volumetric_enabled); #endif + #endif // EXTRUDERS && !NO_VOLUMETRICS CONFIG_ECHO_HEADING("Steps per unit:"); @@ -2992,10 +3094,15 @@ void MarlinSettings::reset() { CONFIG_ECHO_HEADING("Maximum feedrates (units/s):"); CONFIG_ECHO_START(); SERIAL_ECHOLNPAIR_P( - 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]) - #if DISABLED(DISTINCT_E_FACTORS) + LIST_N(DOUBLE(LINEAR_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]) + ) + #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS) , SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_feedrate_mm_s[E_AXIS]) #endif ); @@ -3003,7 +3110,7 @@ void MarlinSettings::reset() { LOOP_L_N(i, E_STEPPERS) { CONFIG_ECHO_START(); SERIAL_ECHOLNPAIR_P( - PSTR(" M203 T"), (int)i + PSTR(" M203 T"), i , SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_feedrate_mm_s[E_AXIS_N(i)]) ); } @@ -3012,10 +3119,15 @@ void MarlinSettings::reset() { CONFIG_ECHO_HEADING("Maximum Acceleration (units/s2):"); CONFIG_ECHO_START(); SERIAL_ECHOLNPAIR_P( - 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]) - #if DISABLED(DISTINCT_E_FACTORS) + LIST_N(DOUBLE(LINEAR_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, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[I_AXIS]), + SP_J_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[J_AXIS]), + SP_K_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[K_AXIS]) + ) + #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS) , SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_acceleration_mm_per_s2[E_AXIS]) #endif ); @@ -3023,7 +3135,7 @@ void MarlinSettings::reset() { LOOP_L_N(i, E_STEPPERS) { CONFIG_ECHO_START(); SERIAL_ECHOLNPAIR_P( - PSTR(" M201 T"), (int)i + PSTR(" M201 T"), i , SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(i)]) ); } @@ -3056,9 +3168,14 @@ void MarlinSettings::reset() { , PSTR(" J"), LINEAR_UNIT(planner.junction_deviation_mm) #endif #if HAS_CLASSIC_JERK - , SP_X_STR, LINEAR_UNIT(planner.max_jerk.x) - , SP_Y_STR, LINEAR_UNIT(planner.max_jerk.y) - , SP_Z_STR, LINEAR_UNIT(planner.max_jerk.z) + , LIST_N(DOUBLE(LINEAR_AXES), + SP_X_STR, LINEAR_UNIT(planner.max_jerk.x), + SP_Y_STR, LINEAR_UNIT(planner.max_jerk.y), + SP_Z_STR, LINEAR_UNIT(planner.max_jerk.z), + SP_I_STR, LINEAR_UNIT(planner.max_jerk.i), + SP_J_STR, LINEAR_UNIT(planner.max_jerk.j), + SP_K_STR, LINEAR_UNIT(planner.max_jerk.k) + ) #if HAS_CLASSIC_E_JERK , SP_E_STR, LINEAR_UNIT(planner.max_jerk.e) #endif @@ -3070,13 +3187,17 @@ void MarlinSettings::reset() { CONFIG_ECHO_START(); SERIAL_ECHOLNPAIR_P( #if IS_CARTESIAN - PSTR(" M206 X"), LINEAR_UNIT(home_offset.x) - , SP_Y_STR, LINEAR_UNIT(home_offset.y) - , SP_Z_STR + LIST_N(DOUBLE(LINEAR_AXES), + PSTR(" M206 X"), LINEAR_UNIT(home_offset.x), + SP_Y_STR, LINEAR_UNIT(home_offset.y), + SP_Z_STR, LINEAR_UNIT(home_offset.z), + SP_I_STR, LINEAR_UNIT(home_offset.i), + SP_J_STR, LINEAR_UNIT(home_offset.j), + SP_K_STR, LINEAR_UNIT(home_offset.k) + ) #else - PSTR(" M206 Z") + PSTR(" M206 Z"), LINEAR_UNIT(home_offset.z) #endif - , LINEAR_UNIT(home_offset.z) ); #endif @@ -3085,7 +3206,7 @@ void MarlinSettings::reset() { CONFIG_ECHO_START(); LOOP_S_L_N(e, 1, HOTENDS) { SERIAL_ECHOPAIR_P( - PSTR(" M218 T"), (int)e, + PSTR(" M218 T"), e, SP_X_STR, LINEAR_UNIT(hotend_offset[e].x), SP_Y_STR, LINEAR_UNIT(hotend_offset[e].y) ); @@ -3104,7 +3225,7 @@ void MarlinSettings::reset() { #elif ENABLED(AUTO_BED_LEVELING_UBL) - config_heading(forReplay, PSTR(""), false); + config_heading(forReplay, NUL_STR, false); if (!forReplay) { ubl.echo_name(); SERIAL_CHAR(':'); @@ -3119,7 +3240,7 @@ void MarlinSettings::reset() { CONFIG_ECHO_START(); SERIAL_ECHOLNPAIR_P( - PSTR(" M420 S"), planner.leveling_active ? 1 : 0 + PSTR(" M420 S"), planner.leveling_active #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) , SP_Z_STR, LINEAR_UNIT(planner.z_fade_height) #endif @@ -3131,12 +3252,12 @@ void MarlinSettings::reset() { LOOP_L_N(py, GRID_MAX_POINTS_Y) { LOOP_L_N(px, GRID_MAX_POINTS_X) { CONFIG_ECHO_START(); - SERIAL_ECHOPAIR_P(PSTR(" G29 S3 I"), (int)px, PSTR(" J"), (int)py); + SERIAL_ECHOPAIR(" G29 S3 I", px, " J", py); SERIAL_ECHOLNPAIR_F_P(SP_Z_STR, LINEAR_UNIT(mbl.z_values[px][py]), 5); } } CONFIG_ECHO_START(); - SERIAL_ECHOLNPAIR_F_P(PSTR(" G29 S4 Z"), LINEAR_UNIT(mbl.z_offset), 5); + SERIAL_ECHOLNPAIR_F(" G29 S4 Z", LINEAR_UNIT(mbl.z_offset), 5); } #elif ENABLED(AUTO_BED_LEVELING_UBL) @@ -3144,7 +3265,6 @@ void MarlinSettings::reset() { if (!forReplay) { SERIAL_EOL(); ubl.report_state(); - SERIAL_EOL(); config_heading(false, PSTR("Active Mesh Slot: "), false); SERIAL_ECHOLN(ubl.storage_slot); config_heading(false, PSTR("EEPROM can hold "), false); @@ -3160,7 +3280,7 @@ void MarlinSettings::reset() { LOOP_L_N(py, GRID_MAX_POINTS_Y) { LOOP_L_N(px, GRID_MAX_POINTS_X) { CONFIG_ECHO_START(); - SERIAL_ECHOPAIR(" G29 W I", (int)px, " J", (int)py); + SERIAL_ECHOPAIR(" G29 W I", px, " J", py); SERIAL_ECHOLNPAIR_F_P(SP_Z_STR, LINEAR_UNIT(z_values[px][py]), 5); } } @@ -3185,8 +3305,7 @@ void MarlinSettings::reset() { #elif ENABLED(BLTOUCH) || (HAS_Z_SERVO_PROBE && defined(Z_SERVO_ANGLES)) case Z_PROBE_SERVO_NR: #endif - CONFIG_ECHO_START(); - SERIAL_ECHOLNPAIR(" M281 P", int(i), " L", servo_angles[i][0], " U", servo_angles[i][1]); + CONFIG_ECHO_MSG(" M281 P", i, " L", servo_angles[i][0], " U", servo_angles[i][1]); default: break; } } @@ -3198,7 +3317,7 @@ void MarlinSettings::reset() { CONFIG_ECHO_HEADING("SCARA settings: S P T"); CONFIG_ECHO_START(); SERIAL_ECHOLNPAIR_P( - PSTR(" M665 S"), delta_segments_per_second + PSTR(" M665 S"), segments_per_second , SP_P_STR, scara_home_offset.a , SP_T_STR, scara_home_offset.b , SP_Z_STR, LINEAR_UNIT(scara_home_offset.z) @@ -3206,21 +3325,13 @@ void MarlinSettings::reset() { #elif ENABLED(DELTA) - CONFIG_ECHO_HEADING("Endstop adjustment:"); - CONFIG_ECHO_START(); - SERIAL_ECHOLNPAIR_P( - PSTR(" M666 X"), LINEAR_UNIT(delta_endstop_adj.a) - , SP_Y_STR, LINEAR_UNIT(delta_endstop_adj.b) - , SP_Z_STR, LINEAR_UNIT(delta_endstop_adj.c) - ); - CONFIG_ECHO_HEADING("Delta settings: L R H S XYZ ABC"); CONFIG_ECHO_START(); SERIAL_ECHOLNPAIR_P( PSTR(" M665 L"), LINEAR_UNIT(delta_diagonal_rod) , PSTR(" R"), LINEAR_UNIT(delta_radius) , PSTR(" H"), LINEAR_UNIT(delta_height) - , PSTR(" S"), delta_segments_per_second + , PSTR(" S"), segments_per_second , SP_X_STR, LINEAR_UNIT(delta_tower_angle_trim.a) , SP_Y_STR, LINEAR_UNIT(delta_tower_angle_trim.b) , SP_Z_STR, LINEAR_UNIT(delta_tower_angle_trim.c) @@ -3229,32 +3340,11 @@ void MarlinSettings::reset() { , PSTR(" C"), LINEAR_UNIT(delta_diagonal_rod_trim.c) ); - #elif HAS_EXTRA_ENDSTOPS - - CONFIG_ECHO_HEADING("Endstop adjustment:"); - CONFIG_ECHO_START(); - SERIAL_ECHOPGM(" M666"); - #if ENABLED(X_DUAL_ENDSTOPS) - SERIAL_ECHOLNPAIR_P(SP_X_STR, LINEAR_UNIT(endstops.x2_endstop_adj)); - #endif - #if ENABLED(Y_DUAL_ENDSTOPS) - SERIAL_ECHOLNPAIR_P(SP_Y_STR, LINEAR_UNIT(endstops.y2_endstop_adj)); - #endif - #if ENABLED(Z_MULTI_ENDSTOPS) - #if NUM_Z_STEPPER_DRIVERS >= 3 - SERIAL_ECHOPAIR(" S2 Z", LINEAR_UNIT(endstops.z3_endstop_adj)); - CONFIG_ECHO_START(); - SERIAL_ECHOPAIR(" M666 S3 Z", LINEAR_UNIT(endstops.z3_endstop_adj)); - #if NUM_Z_STEPPER_DRIVERS >= 4 - CONFIG_ECHO_START(); - SERIAL_ECHOPAIR(" M666 S4 Z", LINEAR_UNIT(endstops.z4_endstop_adj)); - #endif - #else - SERIAL_ECHOLNPAIR_P(SP_Z_STR, LINEAR_UNIT(endstops.z2_endstop_adj)); - #endif - #endif + #endif - #endif // [XYZ]_DUAL_ENDSTOPS + #if EITHER(DELTA, HAS_EXTRA_ENDSTOPS) + M666_report(forReplay); + #endif #if PREHEAT_COUNT @@ -3262,12 +3352,12 @@ void MarlinSettings::reset() { LOOP_L_N(i, PREHEAT_COUNT) { CONFIG_ECHO_START(); SERIAL_ECHOLNPAIR_P( - PSTR(" M145 S"), (int)i + PSTR(" M145 S"), i #if HAS_HOTEND - , PSTR(" H"), TEMP_UNIT(ui.material_preset[i].hotend_temp) + , PSTR(" H"), parser.to_temp_units(ui.material_preset[i].hotend_temp) #endif #if HAS_HEATED_BED - , SP_B_STR, TEMP_UNIT(ui.material_preset[i].bed_temp) + , SP_B_STR, parser.to_temp_units(ui.material_preset[i].bed_temp) #endif #if HAS_FAN , PSTR(" F"), ui.material_preset[i].fan_speed @@ -3307,15 +3397,23 @@ void MarlinSettings::reset() { #endif // PIDTEMP #if ENABLED(PIDTEMPBED) - CONFIG_ECHO_START(); - SERIAL_ECHOLNPAIR( + CONFIG_ECHO_MSG( " M304 P", thermalManager.temp_bed.pid.Kp , " I", unscalePID_i(thermalManager.temp_bed.pid.Ki) , " D", unscalePID_d(thermalManager.temp_bed.pid.Kd) ); #endif - #endif // PIDTEMP || PIDTEMPBED + #if ENABLED(PIDTEMPCHAMBER) + CONFIG_ECHO_START(); + SERIAL_ECHOLNPAIR( + " M309 P", thermalManager.temp_chamber.pid.Kp + , " I", unscalePID_i(thermalManager.temp_chamber.pid.Ki) + , " D", unscalePID_d(thermalManager.temp_chamber.pid.Kd) + ); + #endif + + #endif // PIDTEMP || PIDTEMPBED || PIDTEMPCHAMBER #if HAS_USER_THERMISTORS CONFIG_ECHO_HEADING("User thermistors:"); @@ -3325,46 +3423,26 @@ void MarlinSettings::reset() { #if HAS_LCD_CONTRAST CONFIG_ECHO_HEADING("LCD Contrast:"); - CONFIG_ECHO_START(); - SERIAL_ECHOLNPAIR(" M250 C", ui.contrast); + CONFIG_ECHO_MSG(" M250 C", ui.contrast); + #endif + + #if HAS_LCD_BRIGHTNESS + CONFIG_ECHO_HEADING("LCD Brightness:"); + CONFIG_ECHO_MSG(" M256 B", ui.brightness); #endif TERN_(CONTROLLER_FAN_EDITABLE, M710_report(forReplay)); #if ENABLED(POWER_LOSS_RECOVERY) CONFIG_ECHO_HEADING("Power-Loss Recovery:"); - CONFIG_ECHO_START(); - SERIAL_ECHOLNPAIR(" M413 S", int(recovery.enabled)); + CONFIG_ECHO_MSG(" M413 S", recovery.enabled); #endif #if ENABLED(FWRETRACT) - - CONFIG_ECHO_HEADING("Retract: S F Z"); - CONFIG_ECHO_START(); - SERIAL_ECHOLNPAIR_P( - PSTR(" M207 S"), LINEAR_UNIT(fwretract.settings.retract_length) - , PSTR(" W"), LINEAR_UNIT(fwretract.settings.swap_retract_length) - , PSTR(" F"), LINEAR_UNIT(MMS_TO_MMM(fwretract.settings.retract_feedrate_mm_s)) - , SP_Z_STR, LINEAR_UNIT(fwretract.settings.retract_zraise) - ); - - CONFIG_ECHO_HEADING("Recover: S F"); - CONFIG_ECHO_START(); - SERIAL_ECHOLNPAIR( - " M208 S", LINEAR_UNIT(fwretract.settings.retract_recover_extra) - , " W", LINEAR_UNIT(fwretract.settings.swap_retract_recover_extra) - , " F", LINEAR_UNIT(MMS_TO_MMM(fwretract.settings.retract_recover_feedrate_mm_s)) - ); - - #if ENABLED(FWRETRACT_AUTORETRACT) - - CONFIG_ECHO_HEADING("Auto-Retract: S=0 to disable, 1 to interpret E-only moves as retract/recover"); - CONFIG_ECHO_START(); - SERIAL_ECHOLNPAIR(" M209 S", fwretract.autoretract_enabled ? 1 : 0); - - #endif // FWRETRACT_AUTORETRACT - - #endif // FWRETRACT + fwretract.M207_report(forReplay); + fwretract.M208_report(forReplay); + TERN_(FWRETRACT_AUTORETRACT, fwretract.M209_report(forReplay)); + #endif /** * Probe Offset @@ -3446,6 +3524,19 @@ void MarlinSettings::reset() { SERIAL_ECHOLNPAIR(" I3 Z", stepperZ4.getMilliamps()); #endif + #if AXIS_IS_TMC(I) + say_M906(forReplay); + SERIAL_ECHOLNPAIR_P(SP_I_STR, stepperI.getMilliamps()); + #endif + #if AXIS_IS_TMC(J) + say_M906(forReplay); + SERIAL_ECHOLNPAIR_P(SP_J_STR, stepperJ.getMilliamps()); + #endif + #if AXIS_IS_TMC(K) + say_M906(forReplay); + SERIAL_ECHOLNPAIR_P(SP_K_STR, stepperK.getMilliamps()); + #endif + #if AXIS_IS_TMC(E0) say_M906(forReplay); SERIAL_ECHOLNPAIR(" T0 E", stepperE0.getMilliamps()); @@ -3485,74 +3576,87 @@ void MarlinSettings::reset() { */ #if ENABLED(HYBRID_THRESHOLD) CONFIG_ECHO_HEADING("Hybrid Threshold:"); - #if AXIS_HAS_STEALTHCHOP(X) || AXIS_HAS_STEALTHCHOP(Y) || AXIS_HAS_STEALTHCHOP(Z) + #if X_HAS_STEALTHCHOP || Y_HAS_STEALTHCHOP || Z_HAS_STEALTHCHOP say_M913(forReplay); - #if AXIS_HAS_STEALTHCHOP(X) + #if X_HAS_STEALTHCHOP SERIAL_ECHOPAIR_P(SP_X_STR, stepperX.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(Y) + #if Y_HAS_STEALTHCHOP SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(Z) + #if Z_HAS_STEALTHCHOP SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ.get_pwm_thrs()); #endif SERIAL_EOL(); #endif - #if AXIS_HAS_STEALTHCHOP(X2) || AXIS_HAS_STEALTHCHOP(Y2) || AXIS_HAS_STEALTHCHOP(Z2) + #if X2_HAS_STEALTHCHOP || Y2_HAS_STEALTHCHOP || Z2_HAS_STEALTHCHOP say_M913(forReplay); SERIAL_ECHOPGM(" I1"); - #if AXIS_HAS_STEALTHCHOP(X2) + #if X2_HAS_STEALTHCHOP SERIAL_ECHOPAIR_P(SP_X_STR, stepperX2.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(Y2) + #if Y2_HAS_STEALTHCHOP SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY2.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(Z2) + #if Z2_HAS_STEALTHCHOP SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ2.get_pwm_thrs()); #endif SERIAL_EOL(); #endif - #if AXIS_HAS_STEALTHCHOP(Z3) + #if Z3_HAS_STEALTHCHOP say_M913(forReplay); SERIAL_ECHOLNPAIR(" I2 Z", stepperZ3.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(Z4) + #if Z4_HAS_STEALTHCHOP say_M913(forReplay); SERIAL_ECHOLNPAIR(" I3 Z", stepperZ4.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(E0) + #if I_HAS_STEALTHCHOP + say_M913(forReplay); + SERIAL_ECHOLNPAIR_P(SP_I_STR, stepperI.get_pwm_thrs()); + #endif + #if J_HAS_STEALTHCHOP + say_M913(forReplay); + SERIAL_ECHOLNPAIR_P(SP_J_STR, stepperJ.get_pwm_thrs()); + #endif + #if K_HAS_STEALTHCHOP + say_M913(forReplay); + SERIAL_ECHOLNPAIR_P(SP_K_STR, stepperK.get_pwm_thrs()); + #endif + + #if E0_HAS_STEALTHCHOP say_M913(forReplay); SERIAL_ECHOLNPAIR(" T0 E", stepperE0.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(E1) + #if E1_HAS_STEALTHCHOP say_M913(forReplay); SERIAL_ECHOLNPAIR(" T1 E", stepperE1.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(E2) + #if E2_HAS_STEALTHCHOP say_M913(forReplay); SERIAL_ECHOLNPAIR(" T2 E", stepperE2.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(E3) + #if E3_HAS_STEALTHCHOP say_M913(forReplay); SERIAL_ECHOLNPAIR(" T3 E", stepperE3.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(E4) + #if E4_HAS_STEALTHCHOP say_M913(forReplay); SERIAL_ECHOLNPAIR(" T4 E", stepperE4.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(E5) + #if E5_HAS_STEALTHCHOP say_M913(forReplay); SERIAL_ECHOLNPAIR(" T5 E", stepperE5.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(E6) + #if E6_HAS_STEALTHCHOP say_M913(forReplay); SERIAL_ECHOLNPAIR(" T6 E", stepperE6.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(E7) + #if E7_HAS_STEALTHCHOP say_M913(forReplay); SERIAL_ECHOLNPAIR(" T7 E", stepperE7.get_pwm_thrs()); #endif @@ -3607,6 +3711,22 @@ void MarlinSettings::reset() { SERIAL_ECHOLNPAIR(" I3 Z", stepperZ4.homing_threshold()); #endif + #if I_SENSORLESS + CONFIG_ECHO_START(); + say_M914(); + SERIAL_ECHOLNPAIR_P(SP_I_STR, stepperI.homing_threshold()); + #endif + #if J_SENSORLESS + CONFIG_ECHO_START(); + say_M914(); + SERIAL_ECHOLNPAIR_P(SP_J_STR, stepperJ.homing_threshold()); + #endif + #if K_SENSORLESS + CONFIG_ECHO_START(); + say_M914(); + SERIAL_ECHOLNPAIR_P(SP_K_STR, stepperK.homing_threshold()); + #endif + #endif // USE_SENSORLESS /** @@ -3614,45 +3734,29 @@ void MarlinSettings::reset() { */ #if HAS_STEALTHCHOP CONFIG_ECHO_HEADING("Driver stepping mode:"); - #if AXIS_HAS_STEALTHCHOP(X) - const bool chop_x = stepperX.get_stored_stealthChop_status(); - #else - constexpr bool chop_x = false; - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - const bool chop_y = stepperY.get_stored_stealthChop_status(); - #else - constexpr bool chop_y = false; - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - const bool chop_z = stepperZ.get_stored_stealthChop_status(); - #else - constexpr bool chop_z = false; - #endif - - if (chop_x || chop_y || chop_z) { + const bool chop_x = TERN0(X_HAS_STEALTHCHOP, stepperX.get_stored_stealthChop()), + chop_y = TERN0(Y_HAS_STEALTHCHOP, stepperY.get_stored_stealthChop()), + chop_z = TERN0(Z_HAS_STEALTHCHOP, stepperZ.get_stored_stealthChop()), + chop_i = TERN0(I_HAS_STEALTHCHOP, stepperI.get_stored_stealthChop()), + chop_j = TERN0(J_HAS_STEALTHCHOP, stepperJ.get_stored_stealthChop()), + chop_k = TERN0(K_HAS_STEALTHCHOP, stepperK.get_stored_stealthChop()); + + if (chop_x || chop_y || chop_z || chop_i || chop_j || chop_k) { say_M569(forReplay); - if (chop_x) SERIAL_ECHOPGM_P(SP_X_STR); - if (chop_y) SERIAL_ECHOPGM_P(SP_Y_STR); - if (chop_z) SERIAL_ECHOPGM_P(SP_Z_STR); + LINEAR_AXIS_CODE( + if (chop_x) SERIAL_ECHOPGM_P(SP_X_STR), + if (chop_y) SERIAL_ECHOPGM_P(SP_Y_STR), + if (chop_z) SERIAL_ECHOPGM_P(SP_Z_STR), + if (chop_i) SERIAL_ECHOPGM_P(SP_I_STR), + if (chop_j) SERIAL_ECHOPGM_P(SP_J_STR), + if (chop_k) SERIAL_ECHOPGM_P(SP_K_STR) + ); SERIAL_EOL(); } - #if AXIS_HAS_STEALTHCHOP(X2) - const bool chop_x2 = stepperX2.get_stored_stealthChop_status(); - #else - constexpr bool chop_x2 = false; - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - const bool chop_y2 = stepperY2.get_stored_stealthChop_status(); - #else - constexpr bool chop_y2 = false; - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - const bool chop_z2 = stepperZ2.get_stored_stealthChop_status(); - #else - constexpr bool chop_z2 = false; - #endif + const bool chop_x2 = TERN0(X2_HAS_STEALTHCHOP, stepperX2.get_stored_stealthChop()), + chop_y2 = TERN0(Y2_HAS_STEALTHCHOP, stepperY2.get_stored_stealthChop()), + chop_z2 = TERN0(Z2_HAS_STEALTHCHOP, stepperZ2.get_stored_stealthChop()); if (chop_x2 || chop_y2 || chop_z2) { say_M569(forReplay, PSTR("I1")); @@ -3662,38 +3766,21 @@ void MarlinSettings::reset() { SERIAL_EOL(); } - #if AXIS_HAS_STEALTHCHOP(Z3) - if (stepperZ3.get_stored_stealthChop_status()) { say_M569(forReplay, PSTR("I2 Z"), true); } - #endif + if (TERN0(Z3_HAS_STEALTHCHOP, stepperZ3.get_stored_stealthChop())) { say_M569(forReplay, PSTR("I2 Z"), true); } + if (TERN0(Z4_HAS_STEALTHCHOP, stepperZ4.get_stored_stealthChop())) { say_M569(forReplay, PSTR("I3 Z"), true); } - #if AXIS_HAS_STEALTHCHOP(Z4) - if (stepperZ4.get_stored_stealthChop_status()) { say_M569(forReplay, PSTR("I3 Z"), true); } - #endif + if (TERN0( I_HAS_STEALTHCHOP, stepperI.get_stored_stealthChop())) { say_M569(forReplay, SP_I_STR, true); } + if (TERN0( J_HAS_STEALTHCHOP, stepperJ.get_stored_stealthChop())) { say_M569(forReplay, SP_J_STR, true); } + if (TERN0( K_HAS_STEALTHCHOP, stepperK.get_stored_stealthChop())) { say_M569(forReplay, SP_K_STR, true); } - #if AXIS_HAS_STEALTHCHOP(E0) - if (stepperE0.get_stored_stealthChop_status()) { say_M569(forReplay, PSTR("T0 E"), true); } - #endif - #if AXIS_HAS_STEALTHCHOP(E1) - if (stepperE1.get_stored_stealthChop_status()) { say_M569(forReplay, PSTR("T1 E"), true); } - #endif - #if AXIS_HAS_STEALTHCHOP(E2) - if (stepperE2.get_stored_stealthChop_status()) { say_M569(forReplay, PSTR("T2 E"), true); } - #endif - #if AXIS_HAS_STEALTHCHOP(E3) - if (stepperE3.get_stored_stealthChop_status()) { say_M569(forReplay, PSTR("T3 E"), true); } - #endif - #if AXIS_HAS_STEALTHCHOP(E4) - if (stepperE4.get_stored_stealthChop_status()) { say_M569(forReplay, PSTR("T4 E"), true); } - #endif - #if AXIS_HAS_STEALTHCHOP(E5) - if (stepperE5.get_stored_stealthChop_status()) { say_M569(forReplay, PSTR("T5 E"), true); } - #endif - #if AXIS_HAS_STEALTHCHOP(E6) - if (stepperE6.get_stored_stealthChop_status()) { say_M569(forReplay, PSTR("T6 E"), true); } - #endif - #if AXIS_HAS_STEALTHCHOP(E7) - if (stepperE7.get_stored_stealthChop_status()) { say_M569(forReplay, PSTR("T7 E"), true); } - #endif + if (TERN0(E0_HAS_STEALTHCHOP, stepperE0.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T0 E"), true); } + if (TERN0(E1_HAS_STEALTHCHOP, stepperE1.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T1 E"), true); } + if (TERN0(E2_HAS_STEALTHCHOP, stepperE2.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T2 E"), true); } + if (TERN0(E3_HAS_STEALTHCHOP, stepperE3.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T3 E"), true); } + if (TERN0(E4_HAS_STEALTHCHOP, stepperE4.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T4 E"), true); } + if (TERN0(E5_HAS_STEALTHCHOP, stepperE5.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T5 E"), true); } + if (TERN0(E6_HAS_STEALTHCHOP, stepperE6.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T6 E"), true); } + if (TERN0(E7_HAS_STEALTHCHOP, stepperE7.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T7 E"), true); } #endif // HAS_STEALTHCHOP @@ -3705,33 +3792,36 @@ void MarlinSettings::reset() { #if ENABLED(LIN_ADVANCE) CONFIG_ECHO_HEADING("Linear Advance:"); #if EXTRUDERS < 2 - CONFIG_ECHO_START(); - SERIAL_ECHOLNPAIR(" M900 K", planner.extruder_advance_K[0]); + CONFIG_ECHO_MSG(" M900 K", planner.extruder_advance_K[0]); #else - LOOP_L_N(i, EXTRUDERS) { - CONFIG_ECHO_START(); - SERIAL_ECHOLNPAIR(" M900 T", int(i), " K", planner.extruder_advance_K[i]); - } + LOOP_L_N(i, EXTRUDERS) + CONFIG_ECHO_MSG(" M900 T", i, " K", planner.extruder_advance_K[i]); #endif #endif - #if HAS_MOTOR_CURRENT_SPI || HAS_MOTOR_CURRENT_PWM + #if EITHER(HAS_MOTOR_CURRENT_SPI, HAS_MOTOR_CURRENT_PWM) CONFIG_ECHO_HEADING("Stepper motor currents:"); CONFIG_ECHO_START(); #if HAS_MOTOR_CURRENT_PWM - SERIAL_ECHOLNPAIR_P( - PSTR(" M907 X"), stepper.motor_current_setting[0] - , SP_Z_STR, stepper.motor_current_setting[1] - , SP_E_STR, stepper.motor_current_setting[2] + SERIAL_ECHOLNPAIR_P( // PWM-based has 3 values: + PSTR(" M907 X"), stepper.motor_current_setting[0] // X and Y + , SP_Z_STR, stepper.motor_current_setting[1] // Z + , SP_E_STR, stepper.motor_current_setting[2] // E ); #elif HAS_MOTOR_CURRENT_SPI - SERIAL_ECHOPGM(" M907"); - LOOP_L_N(q, MOTOR_CURRENT_COUNT) { - SERIAL_CHAR(' '); - SERIAL_CHAR(axis_codes[q]); + SERIAL_ECHOPGM(" M907"); // SPI-based has 5 values: + LOOP_LOGICAL_AXES(q) { // X Y Z (I J K) E (map to X Y Z (I J K) E0 by default) + SERIAL_CHAR(' ', axis_codes[q]); SERIAL_ECHO(stepper.motor_current_setting[q]); } - #endif + SERIAL_CHAR(' ', 'B'); // B (maps to E1 by default) + SERIAL_ECHOLN(stepper.motor_current_setting[4]); + #endif + #elif HAS_MOTOR_CURRENT_I2C // i2c-based has any number of values + // Values sent over i2c are not stored. + // Indexes map directly to drivers, not axes. + #elif HAS_MOTOR_CURRENT_DAC // DAC-based has 4 values, for X Y Z (I J K) E + // Values sent over i2c are not stored. Uses indirect mapping. #endif /** @@ -3743,8 +3833,8 @@ void MarlinSettings::reset() { say_M603(forReplay); SERIAL_ECHOLNPAIR("L", LINEAR_UNIT(fc_settings[0].load_length), " U", LINEAR_UNIT(fc_settings[0].unload_length)); #else - #define _ECHO_603(N) do{ say_M603(forReplay); SERIAL_ECHOLNPAIR("T" STRINGIFY(N) " L", LINEAR_UNIT(fc_settings[N].load_length), " U", LINEAR_UNIT(fc_settings[N].unload_length)); }while(0); - REPEAT(EXTRUDERS, _ECHO_603) + auto echo_603 = [](const bool f, const uint8_t n) { say_M603(f); SERIAL_ECHOLNPAIR("T", n, " L", LINEAR_UNIT(fc_settings[n].load_length), " U", LINEAR_UNIT(fc_settings[n].unload_length)); }; + LOOP_L_N(i, EXTRUDERS) echo_603(forReplay, i); #endif #endif @@ -3759,9 +3849,14 @@ void MarlinSettings::reset() { CONFIG_ECHO_START(); SERIAL_ECHOLNPAIR_P( PSTR(" M425 F"), backlash.get_correction() - , SP_X_STR, LINEAR_UNIT(backlash.distance_mm.x) - , SP_Y_STR, LINEAR_UNIT(backlash.distance_mm.y) - , SP_Z_STR, LINEAR_UNIT(backlash.distance_mm.z) + , LIST_N(DOUBLE(LINEAR_AXES), + SP_X_STR, LINEAR_UNIT(backlash.distance_mm.x), + SP_Y_STR, LINEAR_UNIT(backlash.distance_mm.y), + SP_Z_STR, LINEAR_UNIT(backlash.distance_mm.z), + SP_I_STR, LINEAR_UNIT(backlash.distance_mm.i), + SP_J_STR, LINEAR_UNIT(backlash.distance_mm.j), + SP_K_STR, LINEAR_UNIT(backlash.distance_mm.k) + ) #ifdef BACKLASH_SMOOTHING_MM , PSTR(" S"), LINEAR_UNIT(backlash.smoothing_mm) #endif @@ -3770,14 +3865,27 @@ void MarlinSettings::reset() { #if HAS_FILAMENT_SENSOR CONFIG_ECHO_HEADING("Filament runout sensor:"); - CONFIG_ECHO_START(); - SERIAL_ECHOLNPAIR( - " M412 S", int(runout.enabled) + CONFIG_ECHO_MSG( + " M412 S", runout.enabled #if HAS_FILAMENT_RUNOUT_DISTANCE , " D", LINEAR_UNIT(runout.runout_distance()) #endif ); #endif + + #if HAS_ETHERNET + CONFIG_ECHO_HEADING("Ethernet:"); + if (!forReplay) { CONFIG_ECHO_START(); ETH0_report(); } + CONFIG_ECHO_START(); SERIAL_ECHO_SP(2); MAC_report(); + CONFIG_ECHO_START(); SERIAL_ECHO_SP(2); M552_report(); + CONFIG_ECHO_START(); SERIAL_ECHO_SP(2); M553_report(); + CONFIG_ECHO_START(); SERIAL_ECHO_SP(2); M554_report(); + #endif + + #if HAS_MULTI_LANGUAGE + CONFIG_ECHO_HEADING("UI Language:"); + CONFIG_ECHO_MSG(" M414 S", ui.language); + #endif } #endif // !DISABLE_M503 diff --git a/Marlin/src/module/settings.h b/Marlin/src/module/settings.h index b213de93a433..967d49c0738e 100644 --- a/Marlin/src/module/settings.h +++ b/Marlin/src/module/settings.h @@ -76,12 +76,15 @@ class MarlinSettings { //static void delete_mesh(); // necessary if we have a MAT //static void defrag_meshes(); // " #endif - #else + + #else // !EEPROM_SETTINGS + FORCE_INLINE static bool load() { reset(); report(); return true; } FORCE_INLINE static void first_load() { (void)load(); } - #endif + + #endif // !EEPROM_SETTINGS #if DISABLED(DISABLE_M503) static void report(const bool forReplay=false); @@ -105,7 +108,42 @@ class MarlinSettings { static bool _load(); static bool size_error(const uint16_t size); - #endif + + static int eeprom_index; + static uint16_t working_crc; + + static bool EEPROM_START(int eeprom_offset) { + if (!persistentStore.access_start()) { SERIAL_ECHO_MSG("No EEPROM."); return false; } + eeprom_index = eeprom_offset; + working_crc = 0; + return true; + } + + static void EEPROM_FINISH(void) { persistentStore.access_finish(); } + + template + static void EEPROM_SKIP(const T &VAR) { eeprom_index += sizeof(VAR); } + + template + static void EEPROM_WRITE(const T &VAR) { + persistentStore.write_data(eeprom_index, (const uint8_t *) &VAR, sizeof(VAR), &working_crc); + } + + template + static void EEPROM_READ(T &VAR) { + persistentStore.read_data(eeprom_index, (uint8_t *) &VAR, sizeof(VAR), &working_crc, !validating); + } + + static void EEPROM_READ(uint8_t *VAR, size_t sizeof_VAR) { + persistentStore.read_data(eeprom_index, VAR, sizeof_VAR, &working_crc, !validating); + } + + template + static void EEPROM_READ_ALWAYS(T &VAR) { + persistentStore.read_data(eeprom_index, (uint8_t *) &VAR, sizeof(VAR), &working_crc); + } + + #endif // EEPROM_SETTINGS }; extern MarlinSettings settings; diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 6d451f8f0240..b8fdaa5f7609 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -91,8 +91,7 @@ Stepper stepper; // Singleton #include "planner.h" #include "motion.h" -#include "temperature.h" -#include "../lcd/ultralcd.h" +#include "../lcd/marlinui.h" #include "../gcode/queue.h" #include "../sd/cardreader.h" #include "../MarlinCore.h" @@ -180,7 +179,11 @@ bool Stepper::abort_current_block; uint32_t Stepper::acceleration_time, Stepper::deceleration_time; uint8_t Stepper::steps_per_isr; -TERN(ADAPTIVE_STEP_SMOOTHING,,constexpr) uint8_t Stepper::oversampling_factor; +#if HAS_FREEZE_PIN + bool Stepper::frozen; // = false +#endif + +IF_DISABLED(ADAPTIVE_STEP_SMOOTHING, constexpr) uint8_t Stepper::oversampling_factor; xyze_long_t Stepper::delta_error{0}; @@ -256,13 +259,13 @@ xyze_int8_t Stepper::count_direction{0}; #define DUAL_ENDSTOP_APPLY_STEP(A,V) \ if (separate_multi_axis) { \ - if (A##_HOME_DIR < 0) { \ - if (!(TEST(endstops.state(), A##_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##_motor) A##_STEP_WRITE(V); \ - if (!(TEST(endstops.state(), A##2_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \ + if (ENABLED(A##_HOME_TO_MIN)) { \ + if (TERN0(HAS_##A##_MIN, !(TEST(endstops.state(), A##_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##_motor)) A##_STEP_WRITE(V); \ + if (TERN0(HAS_##A##2_MIN, !(TEST(endstops.state(), A##2_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##2_motor)) A##2_STEP_WRITE(V); \ } \ else { \ - if (!(TEST(endstops.state(), A##_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##_motor) A##_STEP_WRITE(V); \ - if (!(TEST(endstops.state(), A##2_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \ + if (TERN0(HAS_##A##_MAX, !(TEST(endstops.state(), A##_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##_motor)) A##_STEP_WRITE(V); \ + if (TERN0(HAS_##A##2_MAX, !(TEST(endstops.state(), A##2_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##2_motor)) A##2_STEP_WRITE(V); \ } \ } \ else { \ @@ -282,7 +285,7 @@ xyze_int8_t Stepper::count_direction{0}; #define TRIPLE_ENDSTOP_APPLY_STEP(A,V) \ if (separate_multi_axis) { \ - if (A##_HOME_DIR < 0) { \ + if (ENABLED(A##_HOME_TO_MIN)) { \ if (!(TEST(endstops.state(), A##_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##_motor) A##_STEP_WRITE(V); \ if (!(TEST(endstops.state(), A##2_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \ if (!(TEST(endstops.state(), A##3_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##3_motor) A##3_STEP_WRITE(V); \ @@ -311,26 +314,18 @@ xyze_int8_t Stepper::count_direction{0}; A##3_STEP_WRITE(V); \ } -#define QUAD_ENDSTOP_APPLY_STEP(A,V) \ - if (separate_multi_axis) { \ - if (A##_HOME_DIR < 0) { \ - if (!(TEST(endstops.state(), A##_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##_motor) A##_STEP_WRITE(V); \ - if (!(TEST(endstops.state(), A##2_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \ - if (!(TEST(endstops.state(), A##3_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##3_motor) A##3_STEP_WRITE(V); \ - if (!(TEST(endstops.state(), A##4_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##4_motor) A##4_STEP_WRITE(V); \ - } \ - else { \ - if (!(TEST(endstops.state(), A##_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##_motor) A##_STEP_WRITE(V); \ - if (!(TEST(endstops.state(), A##2_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \ - if (!(TEST(endstops.state(), A##3_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##3_motor) A##3_STEP_WRITE(V); \ - if (!(TEST(endstops.state(), A##4_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##4_motor) A##4_STEP_WRITE(V); \ - } \ - } \ - else { \ - A##_STEP_WRITE(V); \ - A##2_STEP_WRITE(V); \ - A##3_STEP_WRITE(V); \ - A##4_STEP_WRITE(V); \ +#define QUAD_ENDSTOP_APPLY_STEP(A,V) \ + if (separate_multi_axis) { \ + if (!(TEST(endstops.state(), (TERN(A##_HOME_TO_MIN, A##_MIN, A##_MAX))) && count_direction[_AXIS(A)] < 0) && !locked_##A##_motor) A##_STEP_WRITE(V); \ + if (!(TEST(endstops.state(), (TERN(A##_HOME_TO_MIN, A##2_MIN, A##2_MAX))) && count_direction[_AXIS(A)] < 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \ + if (!(TEST(endstops.state(), (TERN(A##_HOME_TO_MIN, A##3_MIN, A##3_MAX))) && count_direction[_AXIS(A)] < 0) && !locked_##A##3_motor) A##3_STEP_WRITE(V); \ + if (!(TEST(endstops.state(), (TERN(A##_HOME_TO_MIN, A##4_MIN, A##4_MAX))) && count_direction[_AXIS(A)] < 0) && !locked_##A##4_motor) A##4_STEP_WRITE(V); \ + } \ + else { \ + A##_STEP_WRITE(V); \ + A##2_STEP_WRITE(V); \ + A##3_STEP_WRITE(V); \ + A##4_STEP_WRITE(V); \ } #define QUAD_SEPARATE_APPLY_STEP(A,V) \ @@ -348,7 +343,7 @@ xyze_int8_t Stepper::count_direction{0}; } #if ENABLED(X_DUAL_STEPPER_DRIVERS) - #define X_APPLY_DIR(v,Q) do{ X_DIR_WRITE(v); X2_DIR_WRITE((v) != INVERT_X2_VS_X_DIR); }while(0) + #define X_APPLY_DIR(v,Q) do{ X_DIR_WRITE(v); X2_DIR_WRITE((v) ^ ENABLED(INVERT_X2_VS_X_DIR)); }while(0) #if ENABLED(X_DUAL_ENDSTOPS) #define X_APPLY_STEP(v,Q) DUAL_ENDSTOP_APPLY_STEP(X,v) #else @@ -356,7 +351,7 @@ xyze_int8_t Stepper::count_direction{0}; #endif #elif ENABLED(DUAL_X_CARRIAGE) #define X_APPLY_DIR(v,ALWAYS) do{ \ - if (extruder_duplication_enabled || ALWAYS) { X_DIR_WRITE(v); X2_DIR_WRITE(mirrored_duplication_mode ? !(v) : v); } \ + if (extruder_duplication_enabled || ALWAYS) { X_DIR_WRITE(v); X2_DIR_WRITE((v) ^ idex_mirrored_mode); } \ else if (last_moved_extruder) X2_DIR_WRITE(v); else X_DIR_WRITE(v); \ }while(0) #define X_APPLY_STEP(v,ALWAYS) do{ \ @@ -369,19 +364,22 @@ xyze_int8_t Stepper::count_direction{0}; #endif #if ENABLED(Y_DUAL_STEPPER_DRIVERS) - #define Y_APPLY_DIR(v,Q) do{ Y_DIR_WRITE(v); Y2_DIR_WRITE((v) != INVERT_Y2_VS_Y_DIR); }while(0) + #define Y_APPLY_DIR(v,Q) do{ Y_DIR_WRITE(v); Y2_DIR_WRITE((v) ^ ENABLED(INVERT_Y2_VS_Y_DIR)); }while(0) #if ENABLED(Y_DUAL_ENDSTOPS) #define Y_APPLY_STEP(v,Q) DUAL_ENDSTOP_APPLY_STEP(Y,v) #else #define Y_APPLY_STEP(v,Q) do{ Y_STEP_WRITE(v); Y2_STEP_WRITE(v); }while(0) #endif -#else +#elif HAS_Y_AXIS #define Y_APPLY_DIR(v,Q) Y_DIR_WRITE(v) #define Y_APPLY_STEP(v,Q) Y_STEP_WRITE(v) #endif #if NUM_Z_STEPPER_DRIVERS == 4 - #define Z_APPLY_DIR(v,Q) do{ Z_DIR_WRITE(v); Z2_DIR_WRITE(v); Z3_DIR_WRITE(v); Z4_DIR_WRITE(v); }while(0) + #define Z_APPLY_DIR(v,Q) do{ \ + Z_DIR_WRITE(v); Z2_DIR_WRITE((v) ^ ENABLED(INVERT_Z2_VS_Z_DIR)); \ + Z3_DIR_WRITE((v) ^ ENABLED(INVERT_Z3_VS_Z_DIR)); Z4_DIR_WRITE((v) ^ ENABLED(INVERT_Z4_VS_Z_DIR)); \ + }while(0) #if ENABLED(Z_MULTI_ENDSTOPS) #define Z_APPLY_STEP(v,Q) QUAD_ENDSTOP_APPLY_STEP(Z,v) #elif ENABLED(Z_STEPPER_AUTO_ALIGN) @@ -390,7 +388,9 @@ xyze_int8_t Stepper::count_direction{0}; #define Z_APPLY_STEP(v,Q) do{ Z_STEP_WRITE(v); Z2_STEP_WRITE(v); Z3_STEP_WRITE(v); Z4_STEP_WRITE(v); }while(0) #endif #elif NUM_Z_STEPPER_DRIVERS == 3 - #define Z_APPLY_DIR(v,Q) do{ Z_DIR_WRITE(v); Z2_DIR_WRITE(v); Z3_DIR_WRITE(v); }while(0) + #define Z_APPLY_DIR(v,Q) do{ \ + Z_DIR_WRITE(v); Z2_DIR_WRITE((v) ^ ENABLED(INVERT_Z2_VS_Z_DIR)); Z3_DIR_WRITE((v) ^ ENABLED(INVERT_Z3_VS_Z_DIR)); \ + }while(0) #if ENABLED(Z_MULTI_ENDSTOPS) #define Z_APPLY_STEP(v,Q) TRIPLE_ENDSTOP_APPLY_STEP(Z,v) #elif ENABLED(Z_STEPPER_AUTO_ALIGN) @@ -399,7 +399,7 @@ xyze_int8_t Stepper::count_direction{0}; #define Z_APPLY_STEP(v,Q) do{ Z_STEP_WRITE(v); Z2_STEP_WRITE(v); Z3_STEP_WRITE(v); }while(0) #endif #elif NUM_Z_STEPPER_DRIVERS == 2 - #define Z_APPLY_DIR(v,Q) do{ Z_DIR_WRITE(v); Z2_DIR_WRITE(v); }while(0) + #define Z_APPLY_DIR(v,Q) do{ Z_DIR_WRITE(v); Z2_DIR_WRITE((v) ^ ENABLED(INVERT_Z2_VS_Z_DIR)); }while(0) #if ENABLED(Z_MULTI_ENDSTOPS) #define Z_APPLY_STEP(v,Q) DUAL_ENDSTOP_APPLY_STEP(Z,v) #elif ENABLED(Z_STEPPER_AUTO_ALIGN) @@ -407,11 +407,24 @@ xyze_int8_t Stepper::count_direction{0}; #else #define Z_APPLY_STEP(v,Q) do{ Z_STEP_WRITE(v); Z2_STEP_WRITE(v); }while(0) #endif -#else +#elif HAS_Z_AXIS #define Z_APPLY_DIR(v,Q) Z_DIR_WRITE(v) #define Z_APPLY_STEP(v,Q) Z_STEP_WRITE(v) #endif +#if LINEAR_AXES >= 4 + #define I_APPLY_DIR(v,Q) I_DIR_WRITE(v) + #define I_APPLY_STEP(v,Q) I_STEP_WRITE(v) +#endif +#if LINEAR_AXES >= 5 + #define J_APPLY_DIR(v,Q) J_DIR_WRITE(v) + #define J_APPLY_STEP(v,Q) J_STEP_WRITE(v) +#endif +#if LINEAR_AXES >= 6 + #define K_APPLY_DIR(v,Q) K_DIR_WRITE(v) + #define K_APPLY_STEP(v,Q) K_STEP_WRITE(v) +#endif + #if DISABLED(MIXING_EXTRUDER) #define E_APPLY_STEP(v,Q) E_STEP_WRITE(stepper_extruder, v) #endif @@ -478,6 +491,18 @@ void Stepper::set_directions() { SET_STEP_DIR(Z); // C #endif + #if HAS_I_DIR + SET_STEP_DIR(I); // I + #endif + + #if HAS_J_DIR + SET_STEP_DIR(J); // J + #endif + + #if HAS_K_DIR + SET_STEP_DIR(K); // K + #endif + #if DISABLED(LIN_ADVANCE) #if ENABLED(MIXING_EXTRUDER) // Because this is valid for the whole block we don't know @@ -490,7 +515,7 @@ void Stepper::set_directions() { MIXER_STEPPER_LOOP(j) NORM_E_DIR(j); count_direction.e = 1; } - #else + #elif HAS_EXTRUDERS if (motor_direction(E_AXIS)) { REV_E_DIR(stepper_extruder); count_direction.e = -1; @@ -1527,6 +1552,9 @@ void Stepper::pulse_phase_isr() { // If there is no current block, do nothing if (!current_block) return; + // Skipping step processing causes motion to freeze + if (TERN0(HAS_FREEZE_PIN, frozen)) return; + // Count of pending loops and events for this iteration const uint32_t pending_events = step_event_count - step_events_completed; uint8_t events_to_do = _MIN(pending_events, steps_per_isr); @@ -1573,7 +1601,7 @@ void Stepper::pulse_phase_isr() { const bool is_page = IS_PAGE(current_block); #if ENABLED(DIRECT_STEPPING) - + // TODO (DerAndere): Add support for LINEAR_AXES >= 4 if (is_page) { #if STEPPER_PAGE_FORMAT == SP_4x4D_128 @@ -1605,10 +1633,9 @@ void Stepper::pulse_phase_isr() { PAGE_SEGMENT_UPDATE(Z, high >> 4); PAGE_SEGMENT_UPDATE(E, high & 0xF); - if (dm != last_direction_bits) { - last_direction_bits = dm; - set_directions(); - } + if (dm != last_direction_bits) + set_directions(dm); + } break; default: break; @@ -1617,7 +1644,7 @@ void Stepper::pulse_phase_isr() { PAGE_PULSE_PREP(X); PAGE_PULSE_PREP(Y); PAGE_PULSE_PREP(Z); - PAGE_PULSE_PREP(E); + TERN_(HAS_EXTRUDERS, PAGE_PULSE_PREP(E)); page_step_state.segment_steps++; @@ -1650,7 +1677,7 @@ void Stepper::pulse_phase_isr() { PAGE_PULSE_PREP(X); PAGE_PULSE_PREP(Y); PAGE_PULSE_PREP(Z); - PAGE_PULSE_PREP(E); + TERN_(HAS_EXTRUDERS, PAGE_PULSE_PREP(E)); page_step_state.segment_steps++; @@ -1690,16 +1717,25 @@ void Stepper::pulse_phase_isr() { #if HAS_Z_STEP PULSE_PREP(Z); #endif + #if HAS_I_STEP + PULSE_PREP(I); + #endif + #if HAS_J_STEP + PULSE_PREP(J); + #endif + #if HAS_K_STEP + PULSE_PREP(K); + #endif #if EITHER(LIN_ADVANCE, MIXING_EXTRUDER) delta_error.e += advance_dividend.e; if (delta_error.e >= 0) { - count_position.e += count_direction.e; #if ENABLED(LIN_ADVANCE) delta_error.e -= advance_divisor; // Don't step E here - But remember the number of steps to perform motor_direction(E_AXIS) ? --LA_steps : ++LA_steps; #else + count_position.e += count_direction.e; step_needed.e = true; #endif } @@ -1725,6 +1761,15 @@ void Stepper::pulse_phase_isr() { #if HAS_Z_STEP PULSE_START(Z); #endif + #if HAS_I_STEP + PULSE_START(I); + #endif + #if HAS_J_STEP + PULSE_START(J); + #endif + #if HAS_K_STEP + PULSE_START(K); + #endif #if DISABLED(LIN_ADVANCE) #if ENABLED(MIXING_EXTRUDER) @@ -1754,6 +1799,15 @@ void Stepper::pulse_phase_isr() { #if HAS_Z_STEP PULSE_STOP(Z); #endif + #if HAS_I_STEP + PULSE_STOP(I); + #endif + #if HAS_J_STEP + PULSE_STOP(J); + #endif + #if HAS_K_STEP + PULSE_STOP(K); + #endif #if DISABLED(LIN_ADVANCE) #if ENABLED(MIXING_EXTRUDER) @@ -1788,6 +1842,7 @@ uint32_t Stepper::block_phase_isr() { // If current block is finished, reset pointer and finalize state if (step_events_completed >= step_event_count) { #if ENABLED(DIRECT_STEPPING) + // TODO (DerAndere): Add support for LINEAR_AXES >= 4 #if STEPPER_PAGE_FORMAT == SP_4x4D_128 #define PAGE_SEGMENT_UPDATE_POS(AXIS) \ count_position[_AXIS(AXIS)] += page_step_state.bd[_AXIS(AXIS)] - 128 * 7; @@ -1985,9 +2040,18 @@ uint32_t Stepper::block_phase_isr() { // Anything in the buffer? if ((current_block = planner.get_current_block())) { - // Sync block? Sync the stepper counts and return - while (TEST(current_block->flag, BLOCK_BIT_SYNC_POSITION)) { - _set_position(current_block->position); + // Sync block? Sync the stepper counts or fan speeds and return + while (current_block->flag & BLOCK_MASK_SYNC) { + + #if ENABLED(LASER_SYNCHRONOUS_M106_M107) + const bool is_sync_fans = TEST(current_block->flag, BLOCK_BIT_SYNC_FANS); + if (is_sync_fans) planner.sync_fan_speeds(current_block->fan_speed); + #else + constexpr bool is_sync_fans = false; + #endif + + if (!is_sync_fans) _set_position(current_block->position); + discard_current_block(); // Try to get a new block @@ -2084,13 +2148,18 @@ uint32_t Stepper::block_phase_isr() { #endif uint8_t axis_bits = 0; - if (X_MOVE_TEST) SBI(axis_bits, A_AXIS); - if (Y_MOVE_TEST) SBI(axis_bits, B_AXIS); - if (Z_MOVE_TEST) SBI(axis_bits, C_AXIS); - //if (!!current_block->steps.e) SBI(axis_bits, E_AXIS); - //if (!!current_block->steps.a) SBI(axis_bits, X_HEAD); - //if (!!current_block->steps.b) SBI(axis_bits, Y_HEAD); - //if (!!current_block->steps.c) SBI(axis_bits, Z_HEAD); + LINEAR_AXIS_CODE( + if (X_MOVE_TEST) SBI(axis_bits, A_AXIS), + if (Y_MOVE_TEST) SBI(axis_bits, B_AXIS), + if (Z_MOVE_TEST) SBI(axis_bits, C_AXIS), + if (current_block->steps.i) SBI(axis_bits, I_AXIS), + if (current_block->steps.j) SBI(axis_bits, J_AXIS), + if (current_block->steps.k) SBI(axis_bits, K_AXIS) + ); + //if (current_block->steps.e) SBI(axis_bits, E_AXIS); + //if (current_block->steps.a) SBI(axis_bits, X_HEAD); + //if (current_block->steps.b) SBI(axis_bits, Y_HEAD); + //if (current_block->steps.c) SBI(axis_bits, Z_HEAD); axis_did_move = axis_bits; // No acceleration / deceleration time elapsed so far @@ -2127,13 +2196,9 @@ uint32_t Stepper::block_phase_isr() { accelerate_until = current_block->accelerate_until << oversampling; decelerate_after = current_block->decelerate_after << oversampling; - #if ENABLED(MIXING_EXTRUDER) - MIXER_STEPPER_SETUP(); - #endif + TERN_(MIXING_EXTRUDER, mixer.stepper_setup(current_block->b_color)) - #if HAS_MULTI_EXTRUDER - stepper_extruder = current_block->extruder; - #endif + TERN_(HAS_MULTI_EXTRUDER, stepper_extruder = current_block->extruder); // Initialize the trapezoid generator from the current block. #if ENABLED(LIN_ADVANCE) @@ -2151,17 +2216,14 @@ uint32_t Stepper::block_phase_isr() { else LA_isr_rate = LA_ADV_NEVER; #endif - if ( ENABLED(HAS_L64XX) // Always set direction for L64xx (Also enables the chips) + if ( ENABLED(HAS_L64XX) // Always set direction for L64xx (Also enables the chips) + || ENABLED(DUAL_X_CARRIAGE) // TODO: Find out why this fixes "jittery" small circles || current_block->direction_bits != last_direction_bits || TERN(MIXING_EXTRUDER, false, stepper_extruder != last_moved_extruder) ) { - last_direction_bits = current_block->direction_bits; - #if HAS_MULTI_EXTRUDER - last_moved_extruder = stepper_extruder; - #endif - + TERN_(HAS_MULTI_EXTRUDER, last_moved_extruder = stepper_extruder); TERN_(HAS_L64XX, L64XX_OK_to_power_up = true); - set_directions(); + set_directions(current_block->direction_bits); } #if ENABLED(LASER_POWER_INLINE) @@ -2278,15 +2340,23 @@ uint32_t Stepper::block_phase_isr() { #if ENABLED(MIXING_EXTRUDER) // We don't know which steppers will be stepped because LA loop follows, // with potentially multiple steps. Set all. - if (LA_steps > 0) + if (LA_steps > 0) { MIXER_STEPPER_LOOP(j) NORM_E_DIR(j); - else if (LA_steps < 0) + count_direction.e = 1; + } + else if (LA_steps < 0) { MIXER_STEPPER_LOOP(j) REV_E_DIR(j); + count_direction.e = -1; + } #else - if (LA_steps > 0) + if (LA_steps > 0) { NORM_E_DIR(stepper_extruder); - else if (LA_steps < 0) + count_direction.e = 1; + } + else if (LA_steps < 0) { REV_E_DIR(stepper_extruder); + count_direction.e = -1; + } #endif DIR_WAIT_AFTER(); @@ -2307,6 +2377,8 @@ uint32_t Stepper::block_phase_isr() { AWAIT_LOW_PULSE(); #endif + count_position.e += count_direction.e; + // Set the STEP pulse ON #if ENABLED(MIXING_EXTRUDER) E_STEP_WRITE(mixer.get_next_stepper(), !INVERT_E_STEP_PIN); @@ -2357,7 +2429,7 @@ uint32_t Stepper::block_phase_isr() { // Check if the given block is busy or not - Must not be called from ISR contexts // The current_block could change in the middle of the read by an Stepper ISR, so // we must explicitly prevent that! -bool Stepper::is_block_busy(const block_t* const block) { +bool Stepper::is_block_busy(const block_t * const block) { #ifdef __AVR__ // A SW memory barrier, to ensure GCC does not overoptimize loops #define sw_barrier() asm volatile("": : :"memory"); @@ -2367,7 +2439,7 @@ bool Stepper::is_block_busy(const block_t* const block) { // This works because stepper ISRs happen at a slower rate than // successive reads of a variable, so 2 consecutive reads with // the same value means no interrupt updated it. - block_t* vold, *vnew = current_block; + block_t *vold, *vnew = current_block; sw_barrier(); do { vold = vnew; @@ -2417,6 +2489,15 @@ void Stepper::init() { Z4_DIR_INIT(); #endif #endif + #if HAS_I_DIR + I_DIR_INIT(); + #endif + #if HAS_J_DIR + J_DIR_INIT(); + #endif + #if HAS_K_DIR + K_DIR_INIT(); + #endif #if HAS_E0_DIR E0_DIR_INIT(); #endif @@ -2475,6 +2556,18 @@ void Stepper::init() { if (!Z_ENABLE_ON) Z4_ENABLE_WRITE(HIGH); #endif #endif + #if HAS_I_ENABLE + I_ENABLE_INIT(); + if (!I_ENABLE_ON) I_ENABLE_WRITE(HIGH); + #endif + #if HAS_J_ENABLE + J_ENABLE_INIT(); + if (!J_ENABLE_ON) J_ENABLE_WRITE(HIGH); + #endif + #if HAS_K_ENABLE + K_ENABLE_INIT(); + if (!K_ENABLE_ON) K_ENABLE_WRITE(HIGH); + #endif #if HAS_E0_ENABLE E0_ENABLE_INIT(); if (!E_ENABLE_ON) E0_ENABLE_WRITE(HIGH); @@ -2551,6 +2644,15 @@ void Stepper::init() { #endif AXIS_INIT(Z, Z); #endif + #if HAS_I_STEP + AXIS_INIT(I, I); + #endif + #if HAS_J_STEP + AXIS_INIT(J, J); + #endif + #if HAS_K_STEP + AXIS_INIT(K, K); + #endif #if E_STEPPERS && HAS_E0_STEP E_AXIS_INIT(0); @@ -2584,12 +2686,16 @@ void Stepper::init() { #endif // Init direction bits for first moves - last_direction_bits = 0 - | (INVERT_X_DIR ? _BV(X_AXIS) : 0) - | (INVERT_Y_DIR ? _BV(Y_AXIS) : 0) - | (INVERT_Z_DIR ? _BV(Z_AXIS) : 0); - - set_directions(); + set_directions(0 + LINEAR_AXIS_GANG( + | TERN0(INVERT_X_DIR, _BV(X_AXIS)), + | TERN0(INVERT_Y_DIR, _BV(Y_AXIS)), + | TERN0(INVERT_Z_DIR, _BV(Z_AXIS)), + | TERN0(INVERT_I_DIR, _BV(I_AXIS)), + | TERN0(INVERT_J_DIR, _BV(J_AXIS)), + | TERN0(INVERT_K_DIR, _BV(K_AXIS)) + ) + ); #if HAS_MOTOR_CURRENT_SPI || HAS_MOTOR_CURRENT_PWM initialized = true; @@ -2600,30 +2706,32 @@ void Stepper::init() { /** * Set the stepper positions directly in steps * - * The input is based on the typical per-axis XYZ steps. + * The input is based on the typical per-axis XYZE steps. * For CORE machines XYZ needs to be translated to ABC. * * This allows get_axis_position_mm to correctly - * derive the current XYZ position later on. + * derive the current XYZE position later on. */ -void Stepper::_set_position(const int32_t &a, const int32_t &b, const int32_t &c, const int32_t &e) { - #if CORE_IS_XY - // corexy positioning - // these equations follow the form of the dA and dB equations on https://www.corexy.com/theory.html - count_position.set(a + b, CORESIGN(a - b), c); - #elif CORE_IS_XZ - // corexz planning - count_position.set(a + c, b, CORESIGN(a - c)); - #elif CORE_IS_YZ - // coreyz planning - count_position.set(a, b + c, CORESIGN(b - c)); - #elif ENABLED(MARKFORGED_XY) - count_position.set(a - b, b, c); +void Stepper::_set_position(const abce_long_t &spos) { + #if EITHER(IS_CORE, MARKFORGED_XY) + #if CORE_IS_XY + // corexy positioning + // these equations follow the form of the dA and dB equations on https://www.corexy.com/theory.html + count_position.set(spos.a + spos.b, CORESIGN(spos.a - spos.b), spos.c); + #elif CORE_IS_XZ + // corexz planning + count_position.set(spos.a + spos.c, spos.b, CORESIGN(spos.a - spos.c)); + #elif CORE_IS_YZ + // coreyz planning + count_position.set(spos.a, spos.b + spos.c, CORESIGN(spos.b - spos.c)); + #elif ENABLED(MARKFORGED_XY) + count_position.set(spos.a - spos.b, spos.b, spos.c); + #endif + TERN_(HAS_EXTRUDERS, count_position.e = spos.e); #else // default non-h-bot planning - count_position.set(a, b, c); + count_position = spos; #endif - count_position.e = e; } /** @@ -2646,10 +2754,10 @@ int32_t Stepper::position(const AxisEnum axis) { } // Set the current position in steps -void Stepper::set_position(const int32_t &a, const int32_t &b, const int32_t &c, const int32_t &e) { +void Stepper::set_position(const xyze_long_t &spos) { planner.synchronize(); const bool was_enabled = suspend(); - _set_position(a, b, c, e); + _set_position(spos); if (was_enabled) wake_up(); } @@ -2717,17 +2825,27 @@ int32_t Stepper::triggered_position(const AxisEnum axis) { return v; } +#if ANY(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY, IS_SCARA, DELTA) + #define SAYS_A 1 +#endif +#if ANY(CORE_IS_XY, CORE_IS_YZ, MARKFORGED_XY, IS_SCARA, DELTA) + #define SAYS_B 1 +#endif +#if ANY(CORE_IS_XZ, CORE_IS_YZ, DELTA) + #define SAYS_C 1 +#endif + void Stepper::report_a_position(const xyz_long_t &pos) { - #if ANY(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY, DELTA, IS_SCARA) - SERIAL_ECHOPAIR(STR_COUNT_A, pos.x, " B:", pos.y); - #else - SERIAL_ECHOPAIR_P(PSTR(STR_COUNT_X), pos.x, SP_Y_LBL, pos.y); - #endif - #if ANY(CORE_IS_XZ, CORE_IS_YZ, DELTA) - SERIAL_ECHOLNPAIR(" C:", pos.z); - #else - SERIAL_ECHOLNPAIR_P(SP_Z_LBL, pos.z); - #endif + SERIAL_ECHOLNPAIR_P( + LIST_N(DOUBLE(LINEAR_AXES), + TERN(SAYS_A, PSTR(STR_COUNT_A), PSTR(STR_COUNT_X)), pos.x, + TERN(SAYS_B, PSTR("B:"), SP_Y_LBL), pos.y, + TERN(SAYS_C, PSTR("C:"), SP_Z_LBL), pos.z, + SP_I_LBL, pos.i, + SP_J_LBL, pos.j, + SP_K_LBL, pos.k + ) + ); } void Stepper::report_positions() { @@ -2835,9 +2953,7 @@ void Stepper::report_positions() { // No other ISR should ever interrupt this! void Stepper::do_babystep(const AxisEnum axis, const bool direction) { - #if DISABLED(INTEGRATED_BABYSTEPPING) - cli(); - #endif + IF_DISABLED(INTEGRATED_BABYSTEPPING, cli()); switch (axis) { @@ -2881,35 +2997,90 @@ void Stepper::report_positions() { ENABLE_AXIS_X(); ENABLE_AXIS_Y(); ENABLE_AXIS_Z(); + ENABLE_AXIS_I(); + ENABLE_AXIS_J(); + ENABLE_AXIS_K(); DIR_WAIT_BEFORE(); - const xyz_byte_t old_dir = { X_DIR_READ(), Y_DIR_READ(), Z_DIR_READ() }; + const xyz_byte_t old_dir = LINEAR_AXIS_ARRAY(X_DIR_READ(), Y_DIR_READ(), Z_DIR_READ(), I_DIR_READ(), J_DIR_READ(), K_DIR_READ()); X_DIR_WRITE(INVERT_X_DIR ^ z_direction); - Y_DIR_WRITE(INVERT_Y_DIR ^ z_direction); - Z_DIR_WRITE(INVERT_Z_DIR ^ z_direction); + #ifdef Y_DIR_WRITE + Y_DIR_WRITE(INVERT_Y_DIR ^ z_direction); + #endif + #ifdef Z_DIR_WRITE + Z_DIR_WRITE(INVERT_Z_DIR ^ z_direction); + #endif + #ifdef I_DIR_WRITE + I_DIR_WRITE(INVERT_I_DIR ^ z_direction); + #endif + #ifdef J_DIR_WRITE + J_DIR_WRITE(INVERT_J_DIR ^ z_direction); + #endif + #ifdef K_DIR_WRITE + K_DIR_WRITE(INVERT_K_DIR ^ z_direction); + #endif DIR_WAIT_AFTER(); _SAVE_START(); X_STEP_WRITE(!INVERT_X_STEP_PIN); - Y_STEP_WRITE(!INVERT_Y_STEP_PIN); - Z_STEP_WRITE(!INVERT_Z_STEP_PIN); + #ifdef Y_STEP_WRITE + Y_STEP_WRITE(!INVERT_Y_STEP_PIN); + #endif + #ifdef Z_STEP_WRITE + Z_STEP_WRITE(!INVERT_Z_STEP_PIN); + #endif + #ifdef I_STEP_WRITE + I_STEP_WRITE(!INVERT_I_STEP_PIN); + #endif + #ifdef J_STEP_WRITE + J_STEP_WRITE(!INVERT_J_STEP_PIN); + #endif + #ifdef K_STEP_WRITE + K_STEP_WRITE(!INVERT_K_STEP_PIN); + #endif _PULSE_WAIT(); X_STEP_WRITE(INVERT_X_STEP_PIN); - Y_STEP_WRITE(INVERT_Y_STEP_PIN); - Z_STEP_WRITE(INVERT_Z_STEP_PIN); + #ifdef Y_STEP_WRITE + Y_STEP_WRITE(INVERT_Y_STEP_PIN); + #endif + #ifdef Z_STEP_WRITE + Z_STEP_WRITE(INVERT_Z_STEP_PIN); + #endif + #ifdef I_STEP_WRITE + I_STEP_WRITE(INVERT_I_STEP_PIN); + #endif + #ifdef J_STEP_WRITE + J_STEP_WRITE(INVERT_J_STEP_PIN); + #endif + #ifdef K_STEP_WRITE + K_STEP_WRITE(INVERT_K_STEP_PIN); + #endif // Restore direction bits EXTRA_DIR_WAIT_BEFORE(); X_DIR_WRITE(old_dir.x); - Y_DIR_WRITE(old_dir.y); - Z_DIR_WRITE(old_dir.z); + #ifdef Y_DIR_WRITE + Y_DIR_WRITE(old_dir.y); + #endif + #ifdef Z_DIR_WRITE + Z_DIR_WRITE(old_dir.z); + #endif + #ifdef I_DIR_WRITE + I_DIR_WRITE(old_dir.i); + #endif + #ifdef J_DIR_WRITE + J_DIR_WRITE(old_dir.j); + #endif + #ifdef K_DIR_WRITE + K_DIR_WRITE(old_dir.k); + #endif EXTRA_DIR_WAIT_AFTER(); @@ -2917,12 +3088,20 @@ void Stepper::report_positions() { } break; + #if LINEAR_AXES >= 4 + case I_AXIS: BABYSTEP_AXIS(I, 0, direction); break; + #endif + #if LINEAR_AXES >= 5 + case J_AXIS: BABYSTEP_AXIS(J, 0, direction); break; + #endif + #if LINEAR_AXES >= 6 + case K_AXIS: BABYSTEP_AXIS(K, 0, direction); break; + #endif + default: break; } - #if DISABLED(INTEGRATED_BABYSTEPPING) - sei(); - #endif + IF_DISABLED(INTEGRATED_BABYSTEPPING, sei()); } #endif // BABYSTEPPING @@ -2972,7 +3151,7 @@ void Stepper::report_positions() { #if HAS_MOTOR_CURRENT_SPI || HAS_MOTOR_CURRENT_PWM void Stepper::set_digipot_current(const uint8_t driver, const int16_t current) { - if (WITHIN(driver, 0, COUNT(motor_current_setting) - 1)) + if (WITHIN(driver, 0, MOTOR_CURRENT_COUNT - 1)) motor_current_setting[driver] = current; // update motor_current_setting if (!initialized) return; @@ -3257,6 +3436,15 @@ void Stepper::report_positions() { #if HAS_E7_MS_PINS case 10: WRITE(E7_MS1_PIN, ms1); break; #endif + #if HAS_I_MICROSTEPS + case 11: WRITE(I_MS1_PIN, ms1); break + #endif + #if HAS_J_MICROSTEPS + case 12: WRITE(J_MS1_PIN, ms1); break + #endif + #if HAS_K_MICROSTEPS + case 13: WRITE(K_MS1_PIN, ms1); break + #endif } if (ms2 >= 0) switch (driver) { #if HAS_X_MS_PINS || HAS_X2_MS_PINS @@ -3319,6 +3507,15 @@ void Stepper::report_positions() { #if HAS_E7_MS_PINS case 10: WRITE(E7_MS2_PIN, ms2); break; #endif + #if HAS_I_M_PINS + case 11: WRITE(I_MS2_PIN, ms2); break + #endif + #if HAS_J_M_PINS + case 12: WRITE(J_MS2_PIN, ms2); break + #endif + #if HAS_K_M_PINS + case 13: WRITE(K_MS2_PIN, ms2); break + #endif } if (ms3 >= 0) switch (driver) { #if HAS_X_MS_PINS || HAS_X2_MS_PINS @@ -3437,6 +3634,24 @@ void Stepper::report_positions() { PIN_CHAR(Z_MS3); #endif #endif + #if HAS_I_MS_PINS + MS_LINE(I); + #if PIN_EXISTS(I_MS3) + PIN_CHAR(I_MS3); + #endif + #endif + #if HAS_J_MS_PINS + MS_LINE(J); + #if PIN_EXISTS(J_MS3) + PIN_CHAR(J_MS3); + #endif + #endif + #if HAS_K_MS_PINS + MS_LINE(K); + #if PIN_EXISTS(K_MS3) + PIN_CHAR(K_MS3); + #endif + #endif #if HAS_E0_MS_PINS MS_LINE(E0); #if PIN_EXISTS(E0_MS3) diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index 572c3f3f9b2d..236ba5ee9847 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -133,36 +133,38 @@ #endif +// If linear advance is disabled, the loop also handles them +#if DISABLED(LIN_ADVANCE) && ENABLED(MIXING_EXTRUDER) + #define ISR_MIXING_STEPPER_CYCLES ((MIXING_STEPPERS) * (ISR_STEPPER_CYCLES)) +#else + #define ISR_MIXING_STEPPER_CYCLES 0UL +#endif + // Add time for each stepper #if HAS_X_STEP - #define ISR_X_STEPPER_CYCLES ISR_STEPPER_CYCLES -#else - #define ISR_X_STEPPER_CYCLES 0UL + #define ISR_X_STEPPER_CYCLES ISR_STEPPER_CYCLES #endif #if HAS_Y_STEP - #define ISR_Y_STEPPER_CYCLES ISR_STEPPER_CYCLES -#else - #define ISR_START_Y_STEPPER_CYCLES 0UL - #define ISR_Y_STEPPER_CYCLES 0UL + #define ISR_Y_STEPPER_CYCLES ISR_STEPPER_CYCLES #endif #if HAS_Z_STEP - #define ISR_Z_STEPPER_CYCLES ISR_STEPPER_CYCLES -#else - #define ISR_Z_STEPPER_CYCLES 0UL + #define ISR_Z_STEPPER_CYCLES ISR_STEPPER_CYCLES #endif - -// E is always interpolated, even for mixing extruders -#define ISR_E_STEPPER_CYCLES ISR_STEPPER_CYCLES - -// If linear advance is disabled, the loop also handles them -#if DISABLED(LIN_ADVANCE) && ENABLED(MIXING_EXTRUDER) - #define ISR_MIXING_STEPPER_CYCLES ((MIXING_STEPPERS) * (ISR_STEPPER_CYCLES)) -#else - #define ISR_MIXING_STEPPER_CYCLES 0UL +#if HAS_I_STEP + #define ISR_I_STEPPER_CYCLES ISR_STEPPER_CYCLES +#endif +#if HAS_J_STEP + #define ISR_J_STEPPER_CYCLES ISR_STEPPER_CYCLES +#endif +#if HAS_K_STEP + #define ISR_K_STEPPER_CYCLES ISR_STEPPER_CYCLES +#endif +#if HAS_EXTRUDERS + #define ISR_E_STEPPER_CYCLES ISR_STEPPER_CYCLES // E is always interpolated, even for mixing extruders #endif // And the total minimum loop time, not including the base -#define MIN_ISR_LOOP_CYCLES (ISR_X_STEPPER_CYCLES + ISR_Y_STEPPER_CYCLES + ISR_Z_STEPPER_CYCLES + ISR_E_STEPPER_CYCLES + ISR_MIXING_STEPPER_CYCLES) +#define MIN_ISR_LOOP_CYCLES (ISR_MIXING_STEPPER_CYCLES LOGICAL_AXIS_GANG(+ ISR_E_STEPPER_CYCLES, + ISR_X_STEPPER_CYCLES, + ISR_Y_STEPPER_CYCLES, + ISR_Z_STEPPER_CYCLES, + ISR_I_STEPPER_CYCLES, + ISR_J_STEPPER_CYCLES, + ISR_K_STEPPER_CYCLES)) // Calculate the minimum MPU cycles needed per pulse to enforce, limited to the max stepper rate #define _MIN_STEPPER_PULSE_CYCLES(N) _MAX(uint32_t((F_CPU) / (MAXIMUM_STEPPER_RATE)), ((F_CPU) / 500000UL) * (N)) @@ -250,7 +252,7 @@ class Stepper { #ifndef PWM_MOTOR_CURRENT #define PWM_MOTOR_CURRENT DEFAULT_PWM_MOTOR_CURRENT #endif - #define MOTOR_CURRENT_COUNT 3 + #define MOTOR_CURRENT_COUNT LINEAR_AXES #elif HAS_MOTOR_CURRENT_SPI static constexpr uint32_t digipot_count[] = DIGIPOT_MOTOR_CURRENT; #define MOTOR_CURRENT_COUNT COUNT(Stepper::digipot_count) @@ -266,6 +268,10 @@ class Stepper { static constexpr uint8_t last_moved_extruder = 0; #endif + #if HAS_FREEZE_PIN + static bool frozen; // Set this flag to instantly freeze motion + #endif + private: static block_t* current_block; // A pointer to the block currently being traced @@ -423,14 +429,13 @@ class Stepper { #endif // 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); + static bool is_block_busy(const block_t * const block); // Get the position of a stepper, in steps static int32_t position(const AxisEnum axis); // Set the current position in steps - static void set_position(const int32_t &a, const int32_t &b, const int32_t &c, const int32_t &e); - static inline void set_position(const xyze_long_t &abce) { set_position(abce.a, abce.b, abce.c, abce.e); } + static void set_position(const xyze_long_t &spos); static void set_axis_position(const AxisEnum a, const int32_t &v); // Report the positions of the steppers, in steps @@ -514,16 +519,21 @@ class Stepper { static void refresh_motor_power(); #endif - // Set direction bits for all steppers + // Update direction states for all steppers static void set_directions(); + // Set direction bits and update all stepper DIR states + static void set_directions(const uint8_t bits) { + last_direction_bits = bits; + set_directions(); + } + private: // Set the current position in steps - static void _set_position(const int32_t &a, const int32_t &b, const int32_t &c, const int32_t &e); - FORCE_INLINE static void _set_position(const abce_long_t &spos) { _set_position(spos.a, spos.b, spos.c, spos.e); } + static void _set_position(const abce_long_t &spos); - FORCE_INLINE static uint32_t calc_timer_interval(uint32_t step_rate, uint8_t* loops) { + FORCE_INLINE static uint32_t calc_timer_interval(uint32_t step_rate, uint8_t *loops) { uint32_t timer; // Scale the frequency, as requested by the caller diff --git a/Marlin/src/module/stepper/L64xx.cpp b/Marlin/src/module/stepper/L64xx.cpp index 3e2bf0944666..27816fb4f742 100644 --- a/Marlin/src/module/stepper/L64xx.cpp +++ b/Marlin/src/module/stepper/L64xx.cpp @@ -55,6 +55,15 @@ #if AXIS_IS_L64XX(Z4) L64XX_CLASS(Z4) stepperZ4(L6470_CHAIN_SS_PIN); #endif +#if AXIS_IS_L64XX(I) + L64XX_CLASS(I) stepperI(L6470_CHAIN_SS_PIN); +#endif +#if AXIS_IS_L64XX(J) + L64XX_CLASS(J) stepperJ(L6470_CHAIN_SS_PIN); +#endif +#if AXIS_IS_L64XX(K) + L64XX_CLASS(K) stepperK(L6470_CHAIN_SS_PIN); +#endif #if AXIS_IS_L64XX(E0) L64XX_CLASS(E0) stepperE0(L6470_CHAIN_SS_PIN); #endif @@ -196,6 +205,18 @@ void L64XX_Marlin::init_to_defaults() { #if AXIS_IS_L64XX(Z3) L6470_INIT_CHIP(Z3); #endif + #if AXIS_IS_L64XX(Z4) + L6470_INIT_CHIP(Z4); + #endif + #if AXIS_IS_L64XX(I) + L6470_INIT_CHIP(I); + #endif + #if AXIS_IS_L64XX(J) + L6470_INIT_CHIP(J); + #endif + #if AXIS_IS_L64XX(K) + L6470_INIT_CHIP(K); + #endif #if AXIS_IS_L64XX(E0) L6470_INIT_CHIP(E0); #endif diff --git a/Marlin/src/module/stepper/L64xx.h b/Marlin/src/module/stepper/L64xx.h index 9c8b0b1bddee..9f7e6623b140 100644 --- a/Marlin/src/module/stepper/L64xx.h +++ b/Marlin/src/module/stepper/L64xx.h @@ -206,6 +206,66 @@ #define DISABLE_STEPPER_Z4() stepperZ4.free() #endif +// I Stepper +#if AXIS_IS_L64XX(I) + extern L64XX_CLASS(I) stepperI; + #define I_ENABLE_INIT() NOOP + #define I_ENABLE_WRITE(STATE) (STATE ? stepperI.hardStop() : stepperI.free()) + #define I_ENABLE_READ() (stepperI.getStatus() & STATUS_HIZ) + #if AXIS_DRIVER_TYPE_I(L6474) + #define I_DIR_INIT() SET_OUTPUT(I_DIR_PIN) + #define I_DIR_WRITE(STATE) L6474_DIR_WRITE(I, STATE) + #define I_DIR_READ() READ(I_DIR_PIN) + #else + #define I_DIR_INIT() NOOP + #define I_DIR_WRITE(STATE) L64XX_DIR_WRITE(I, STATE) + #define I_DIR_READ() (stepper##I.getStatus() & STATUS_DIR); + #if AXIS_DRIVER_TYPE_I(L6470) + #define DISABLE_STEPPER_I() stepperI.free() + #endif + #endif +#endif + +// J Stepper +#if AXIS_IS_L64XX(J) + extern L64XX_CLASS(J) stepperJ; + #define J_ENABLE_INIT() NOOP + #define J_ENABLE_WRITE(STATE) (STATE ? stepperJ.hardStop() : stepperJ.free()) + #define J_ENABLE_READ() (stepperJ.getStatus() & STATUS_HIZ) + #if AXIS_DRIVER_TYPE_J(L6474) + #define J_DIR_INIT() SET_OUTPUT(J_DIR_PIN) + #define J_DIR_WRITE(STATE) L6474_DIR_WRITE(J, STATE) + #define J_DIR_READ() READ(J_DIR_PIN) + #else + #define J_DIR_INIT() NOOP + #define J_DIR_WRITE(STATE) L64XX_DIR_WRITE(J, STATE) + #define J_DIR_READ() (stepper##J.getStatus() & STATUS_DIR); + #if AXIS_DRIVER_TYPE_J(L6470) + #define DISABLE_STEPPER_J() stepperJ.free() + #endif + #endif +#endif + +// K Stepper +#if AXIS_IS_L64XX(K) + extern L64XX_CLASS(K) stepperK; + #define K_ENABLE_INIT() NOOP + #define K_ENABLE_WRITE(STATE) (STATE ? stepperK.hardStop() : stepperK.free()) + #define K_ENABLE_READ() (stepperK.getStatus() & STATUS_HIZ) + #if AXIS_DRIVER_TYPE_K(L6474) + #define K_DIR_INIT() SET_OUTPUT(K_DIR_PIN) + #define K_DIR_WRITE(STATE) L6474_DIR_WRITE(K, STATE) + #define K_DIR_READ() READ(K_DIR_PIN) + #else + #define K_DIR_INIT() NOOP + #define K_DIR_WRITE(STATE) L64XX_DIR_WRITE(K, STATE) + #define K_DIR_READ() (stepper##K.getStatus() & STATUS_DIR); + #if AXIS_DRIVER_TYPE_K(L6470) + #define DISABLE_STEPPER_K() stepperK.free() + #endif + #endif +#endif + // E0 Stepper #if AXIS_IS_L64XX(E0) extern L64XX_CLASS(E0) stepperE0; diff --git a/Marlin/src/module/stepper/TMC26X.cpp b/Marlin/src/module/stepper/TMC26X.cpp index 926f1a4e089f..26f91bfeb9da 100644 --- a/Marlin/src/module/stepper/TMC26X.cpp +++ b/Marlin/src/module/stepper/TMC26X.cpp @@ -60,6 +60,15 @@ #if AXIS_DRIVER_TYPE_Z4(TMC26X) _TMC26X_DEFINE(Z4); #endif +#if AXIS_DRIVER_TYPE_I(TMC26X) + _TMC26X_DEFINE(I); +#endif +#if AXIS_DRIVER_TYPE_J(TMC26X) + _TMC26X_DEFINE(J); +#endif +#if AXIS_DRIVER_TYPE_K(TMC26X) + _TMC26X_DEFINE(K); +#endif #if AXIS_DRIVER_TYPE_E0(TMC26X) _TMC26X_DEFINE(E0); #endif @@ -115,6 +124,15 @@ void tmc26x_init_to_defaults() { #if AXIS_DRIVER_TYPE_Z4(TMC26X) _TMC26X_INIT(Z4); #endif + #if AXIS_DRIVER_TYPE_I(TMC26X) + _TMC26X_INIT(I); + #endif + #if AXIS_DRIVER_TYPE_J(TMC26X) + _TMC26X_INIT(J); + #endif + #if AXIS_DRIVER_TYPE_K(TMC26X) + _TMC26X_INIT(K); + #endif #if AXIS_DRIVER_TYPE_E0(TMC26X) _TMC26X_INIT(E0); #endif diff --git a/Marlin/src/module/stepper/TMC26X.h b/Marlin/src/module/stepper/TMC26X.h index 8977266b47bf..988bebe0f20f 100644 --- a/Marlin/src/module/stepper/TMC26X.h +++ b/Marlin/src/module/stepper/TMC26X.h @@ -31,11 +31,7 @@ // TMC26X drivers have STEP/DIR on normal pins, but ENABLE via SPI #include -#if defined(STM32GENERIC) && defined(STM32F7) - #include "../../HAL/STM32_F4_F7/STM32F7/TMC2660.h" -#else - #include -#endif +#include void tmc26x_init_to_defaults(); @@ -103,6 +99,30 @@ void tmc26x_init_to_defaults(); #define Z4_ENABLE_READ() stepperZ4.isEnabled() #endif +// I Stepper +#if HAS_I_ENABLE && AXIS_DRIVER_TYPE_I(TMC26X) + extern TMC26XStepper stepperI; + #define I_ENABLE_INIT() NOOP + #define I_ENABLE_WRITE(STATE) stepperI.setEnabled(STATE) + #define I_ENABLE_READ() stepperI.isEnabled() +#endif + +// J Stepper +#if HAS_J_ENABLE && AXIS_DRIVER_TYPE_J(TMC26X) + extern TMC26XStepper stepperJ; + #define J_ENABLE_INIT() NOOP + #define J_ENABLE_WRITE(STATE) stepperJ.setEnabled(STATE) + #define J_ENABLE_READ() stepperJ.isEnabled() +#endif + +// K Stepper +#if HAS_K_ENABLE && AXIS_DRIVER_TYPE_K(TMC26X) + extern TMC26XStepper stepperK; + #define K_ENABLE_INIT() NOOP + #define K_ENABLE_WRITE(STATE) stepperK.setEnabled(STATE) + #define K_ENABLE_READ() stepperK.isEnabled() +#endif + // E0 Stepper #if AXIS_DRIVER_TYPE_E0(TMC26X) extern TMC26XStepper stepperE0; diff --git a/Marlin/src/module/stepper/indirection.cpp b/Marlin/src/module/stepper/indirection.cpp index 6f9ac9ba0ab1..e44496d0224c 100644 --- a/Marlin/src/module/stepper/indirection.cpp +++ b/Marlin/src/module/stepper/indirection.cpp @@ -37,9 +37,12 @@ void restore_stepper_drivers() { } void reset_stepper_drivers() { - #if HAS_DRIVER(TMC26X) - tmc26x_init_to_defaults(); - #endif + TERN_(HAS_TMC26X, tmc26x_init_to_defaults()); TERN_(HAS_L64XX, L64xxManager.init_to_defaults()); TERN_(HAS_TRINAMIC_CONFIG, reset_trinamic_drivers()); } + +#if ENABLED(SOFTWARE_DRIVER_ENABLE) + // Flags to optimize XYZ 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 ec0d63a89d97..08d0be0b3153 100644 --- a/Marlin/src/module/stepper/indirection.h +++ b/Marlin/src/module/stepper/indirection.h @@ -36,7 +36,7 @@ #include "L64xx.h" #endif -#if HAS_DRIVER(TMC26X) +#if HAS_TMC26X #include "TMC26X.h" #endif @@ -65,38 +65,42 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #define X_STEP_READ() bool(READ(X_STEP_PIN)) // Y Stepper -#ifndef Y_ENABLE_INIT - #define Y_ENABLE_INIT() SET_OUTPUT(Y_ENABLE_PIN) - #define Y_ENABLE_WRITE(STATE) WRITE(Y_ENABLE_PIN,STATE) - #define Y_ENABLE_READ() bool(READ(Y_ENABLE_PIN)) -#endif -#ifndef Y_DIR_INIT - #define Y_DIR_INIT() SET_OUTPUT(Y_DIR_PIN) - #define Y_DIR_WRITE(STATE) WRITE(Y_DIR_PIN,STATE) - #define Y_DIR_READ() bool(READ(Y_DIR_PIN)) -#endif -#define Y_STEP_INIT() SET_OUTPUT(Y_STEP_PIN) -#ifndef Y_STEP_WRITE - #define Y_STEP_WRITE(STATE) WRITE(Y_STEP_PIN,STATE) +#if HAS_Y_AXIS + #ifndef Y_ENABLE_INIT + #define Y_ENABLE_INIT() SET_OUTPUT(Y_ENABLE_PIN) + #define Y_ENABLE_WRITE(STATE) WRITE(Y_ENABLE_PIN,STATE) + #define Y_ENABLE_READ() bool(READ(Y_ENABLE_PIN)) + #endif + #ifndef Y_DIR_INIT + #define Y_DIR_INIT() SET_OUTPUT(Y_DIR_PIN) + #define Y_DIR_WRITE(STATE) WRITE(Y_DIR_PIN,STATE) + #define Y_DIR_READ() bool(READ(Y_DIR_PIN)) + #endif + #define Y_STEP_INIT() SET_OUTPUT(Y_STEP_PIN) + #ifndef Y_STEP_WRITE + #define Y_STEP_WRITE(STATE) WRITE(Y_STEP_PIN,STATE) + #endif + #define Y_STEP_READ() bool(READ(Y_STEP_PIN)) #endif -#define Y_STEP_READ() bool(READ(Y_STEP_PIN)) // Z Stepper -#ifndef Z_ENABLE_INIT - #define Z_ENABLE_INIT() SET_OUTPUT(Z_ENABLE_PIN) - #define Z_ENABLE_WRITE(STATE) WRITE(Z_ENABLE_PIN,STATE) - #define Z_ENABLE_READ() bool(READ(Z_ENABLE_PIN)) -#endif -#ifndef Z_DIR_INIT - #define Z_DIR_INIT() SET_OUTPUT(Z_DIR_PIN) - #define Z_DIR_WRITE(STATE) WRITE(Z_DIR_PIN,STATE) - #define Z_DIR_READ() bool(READ(Z_DIR_PIN)) -#endif -#define Z_STEP_INIT() SET_OUTPUT(Z_STEP_PIN) -#ifndef Z_STEP_WRITE - #define Z_STEP_WRITE(STATE) WRITE(Z_STEP_PIN,STATE) +#if HAS_Z_AXIS + #ifndef Z_ENABLE_INIT + #define Z_ENABLE_INIT() SET_OUTPUT(Z_ENABLE_PIN) + #define Z_ENABLE_WRITE(STATE) WRITE(Z_ENABLE_PIN,STATE) + #define Z_ENABLE_READ() bool(READ(Z_ENABLE_PIN)) + #endif + #ifndef Z_DIR_INIT + #define Z_DIR_INIT() SET_OUTPUT(Z_DIR_PIN) + #define Z_DIR_WRITE(STATE) WRITE(Z_DIR_PIN,STATE) + #define Z_DIR_READ() bool(READ(Z_DIR_PIN)) + #endif + #define Z_STEP_INIT() SET_OUTPUT(Z_STEP_PIN) + #ifndef Z_STEP_WRITE + #define Z_STEP_WRITE(STATE) WRITE(Z_STEP_PIN,STATE) + #endif + #define Z_STEP_READ() bool(READ(Z_STEP_PIN)) #endif -#define Z_STEP_READ() bool(READ(Z_STEP_PIN)) // X2 Stepper #if HAS_X2_ENABLE @@ -201,6 +205,63 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #define Z4_DIR_WRITE(STATE) NOOP #endif +// I Stepper +#if LINEAR_AXES >= 4 + #ifndef I_ENABLE_INIT + #define I_ENABLE_INIT() SET_OUTPUT(I_ENABLE_PIN) + #define I_ENABLE_WRITE(STATE) WRITE(I_ENABLE_PIN,STATE) + #define I_ENABLE_READ() bool(READ(I_ENABLE_PIN)) + #endif + #ifndef I_DIR_INIT + #define I_DIR_INIT() SET_OUTPUT(I_DIR_PIN) + #define I_DIR_WRITE(STATE) WRITE(I_DIR_PIN,STATE) + #define I_DIR_READ() bool(READ(I_DIR_PIN)) + #endif + #define I_STEP_INIT() SET_OUTPUT(I_STEP_PIN) + #ifndef I_STEP_WRITE + #define I_STEP_WRITE(STATE) WRITE(I_STEP_PIN,STATE) + #endif + #define I_STEP_READ() bool(READ(I_STEP_PIN)) +#endif + +// J Stepper +#if LINEAR_AXES >= 5 + #ifndef J_ENABLE_INIT + #define J_ENABLE_INIT() SET_OUTPUT(J_ENABLE_PIN) + #define J_ENABLE_WRITE(STATE) WRITE(J_ENABLE_PIN,STATE) + #define J_ENABLE_READ() bool(READ(J_ENABLE_PIN)) + #endif + #ifndef J_DIR_INIT + #define J_DIR_INIT() SET_OUTPUT(J_DIR_PIN) + #define J_DIR_WRITE(STATE) WRITE(J_DIR_PIN,STATE) + #define J_DIR_READ() bool(READ(J_DIR_PIN)) + #endif + #define J_STEP_INIT() SET_OUTPUT(J_STEP_PIN) + #ifndef J_STEP_WRITE + #define J_STEP_WRITE(STATE) WRITE(J_STEP_PIN,STATE) + #endif + #define J_STEP_READ() bool(READ(J_STEP_PIN)) +#endif + +// K Stepper +#if LINEAR_AXES >= 6 + #ifndef K_ENABLE_INIT + #define K_ENABLE_INIT() SET_OUTPUT(K_ENABLE_PIN) + #define K_ENABLE_WRITE(STATE) WRITE(K_ENABLE_PIN,STATE) + #define K_ENABLE_READ() bool(READ(K_ENABLE_PIN)) + #endif + #ifndef K_DIR_INIT + #define K_DIR_INIT() SET_OUTPUT(K_DIR_PIN) + #define K_DIR_WRITE(STATE) WRITE(K_DIR_PIN,STATE) + #define K_DIR_READ() bool(READ(K_DIR_PIN)) + #endif + #define K_STEP_INIT() SET_OUTPUT(K_STEP_PIN) + #ifndef K_STEP_WRITE + #define K_STEP_WRITE(STATE) WRITE(K_STEP_PIN,STATE) + #endif + #define K_STEP_READ() bool(READ(K_STEP_PIN)) +#endif + // E0 Stepper #ifndef E0_ENABLE_INIT #define E0_ENABLE_INIT() SET_OUTPUT(E0_ENABLE_PIN) @@ -417,12 +478,15 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #define NORM_E_DIR(E) do{ E0_DIR_WRITE(E ? INVERT_E0_DIR : !INVERT_E0_DIR); }while(0) #define REV_E_DIR(E) do{ E0_DIR_WRITE(E ? !INVERT_E0_DIR : INVERT_E0_DIR); }while(0) #endif -#elif ENABLED(PRUSA_MMU2) + +#elif HAS_PRUSA_MMU2 // One multiplexed stepper driver + #define E_STEP_WRITE(E,V) E0_STEP_WRITE(V) #define NORM_E_DIR(E) E0_DIR_WRITE(!INVERT_E0_DIR) #define REV_E_DIR(E) E0_DIR_WRITE( INVERT_E0_DIR) -#elif ENABLED(MK2_MULTIPLEXER) // One multiplexed stepper driver, reversed on odd index +#elif HAS_PRUSA_MMU1 // One multiplexed stepper driver, reversed on odd index + #define E_STEP_WRITE(E,V) E0_STEP_WRITE(V) #define NORM_E_DIR(E) do{ E0_DIR_WRITE(TEST(E, 0) ? !INVERT_E0_DIR: INVERT_E0_DIR); }while(0) #define REV_E_DIR(E) do{ E0_DIR_WRITE(TEST(E, 0) ? INVERT_E0_DIR: !INVERT_E0_DIR); }while(0) @@ -581,6 +645,11 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #endif +#elif ENABLED(E_DUAL_STEPPER_DRIVERS) + #define E_STEP_WRITE(E,V) do{ E0_STEP_WRITE(V); E1_STEP_WRITE(V); }while(0) + #define NORM_E_DIR(E) do{ E0_DIR_WRITE(!INVERT_E0_DIR); E1_DIR_WRITE(!INVERT_E0_DIR ^ ENABLED(INVERT_E1_VS_E0_DIR)); }while(0) + #define REV_E_DIR(E) do{ E0_DIR_WRITE( INVERT_E0_DIR); E1_DIR_WRITE( INVERT_E0_DIR ^ ENABLED(INVERT_E1_VS_E0_DIR)); }while(0) + #elif E_STEPPERS #define E_STEP_WRITE(E,V) E0_STEP_WRITE(V) #define NORM_E_DIR(E) E0_DIR_WRITE(!INVERT_E0_DIR) @@ -717,6 +786,51 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #endif #endif +#ifndef ENABLE_STEPPER_I + #if HAS_I_ENABLE + #define ENABLE_STEPPER_I() I_ENABLE_WRITE( I_ENABLE_ON) + #else + #define ENABLE_STEPPER_I() NOOP + #endif +#endif +#ifndef DISABLE_STEPPER_I + #if HAS_I_ENABLE + #define DISABLE_STEPPER_I() I_ENABLE_WRITE(!I_ENABLE_ON) + #else + #define DISABLE_STEPPER_I() NOOP + #endif +#endif + +#ifndef ENABLE_STEPPER_J + #if HAS_J_ENABLE + #define ENABLE_STEPPER_J() J_ENABLE_WRITE( J_ENABLE_ON) + #else + #define ENABLE_STEPPER_J() NOOP + #endif +#endif +#ifndef DISABLE_STEPPER_J + #if HAS_J_ENABLE + #define DISABLE_STEPPER_J() J_ENABLE_WRITE(!J_ENABLE_ON) + #else + #define DISABLE_STEPPER_J() NOOP + #endif +#endif + +#ifndef ENABLE_STEPPER_K + #if HAS_K_ENABLE + #define ENABLE_STEPPER_K() K_ENABLE_WRITE( K_ENABLE_ON) + #else + #define ENABLE_STEPPER_K() NOOP + #endif +#endif +#ifndef DISABLE_STEPPER_K + #if HAS_K_ENABLE + #define DISABLE_STEPPER_K() K_ENABLE_WRITE(!K_ENABLE_ON) + #else + #define DISABLE_STEPPER_K() NOOP + #endif +#endif + #ifndef ENABLE_STEPPER_E0 #if HAS_E0_ENABLE #define ENABLE_STEPPER_E0() E0_ENABLE_WRITE( E_ENABLE_ON) @@ -840,28 +954,71 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset // // Axis steppers enable / disable macros // -#define FORGET_AXIS(A) TERN(HOME_AFTER_DEACTIVATE, set_axis_never_homed(A), CBI(axis_known_position, A)) +#if ENABLED(SOFTWARE_DRIVER_ENABLE) + // Avoid expensive calls to enable / disable steppers + extern xyz_bool_t axis_sw_enabled; + #define SHOULD_ENABLE(N) !axis_sw_enabled.N + #define SHOULD_DISABLE(N) axis_sw_enabled.N + #define AFTER_CHANGE(N,TF) axis_sw_enabled.N = TF +#else + #define SHOULD_ENABLE(N) true + #define SHOULD_DISABLE(N) true + #define AFTER_CHANGE(N,TF) NOOP +#endif -#define ENABLE_AXIS_X() do{ ENABLE_STEPPER_X(); ENABLE_STEPPER_X2(); }while(0) -#define DISABLE_AXIS_X() do{ DISABLE_STEPPER_X(); DISABLE_STEPPER_X2(); FORGET_AXIS(X_AXIS); }while(0) +#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); } -#define ENABLE_AXIS_Y() do{ ENABLE_STEPPER_Y(); ENABLE_STEPPER_Y2(); }while(0) -#define DISABLE_AXIS_Y() do{ DISABLE_STEPPER_Y(); DISABLE_STEPPER_Y2(); FORGET_AXIS(Y_AXIS); }while(0) +#if HAS_Y_AXIS + #define ENABLE_AXIS_Y() if (SHOULD_ENABLE(y)) { ENABLE_STEPPER_Y(); ENABLE_STEPPER_Y2(); AFTER_CHANGE(y, true); } + #define DISABLE_AXIS_Y() if (SHOULD_DISABLE(y)) { DISABLE_STEPPER_Y(); DISABLE_STEPPER_Y2(); AFTER_CHANGE(y, false); set_axis_untrusted(Y_AXIS); } +#else + #define ENABLE_AXIS_Y() NOOP + #define DISABLE_AXIS_Y() NOOP +#endif -#define ENABLE_AXIS_Z() do{ ENABLE_STEPPER_Z(); ENABLE_STEPPER_Z2(); ENABLE_STEPPER_Z3(); ENABLE_STEPPER_Z4(); }while(0) +#if HAS_Z_AXIS + #define ENABLE_AXIS_Z() if (SHOULD_ENABLE(z)) { ENABLE_STEPPER_Z(); ENABLE_STEPPER_Z2(); ENABLE_STEPPER_Z3(); ENABLE_STEPPER_Z4(); AFTER_CHANGE(z, true); } + #define DISABLE_AXIS_Z() if (SHOULD_DISABLE(z)) { DISABLE_STEPPER_Z(); DISABLE_STEPPER_Z2(); DISABLE_STEPPER_Z3(); DISABLE_STEPPER_Z4(); AFTER_CHANGE(z, false); set_axis_untrusted(Z_AXIS); Z_RESET(); } +#else + #define ENABLE_AXIS_Z() NOOP + #define DISABLE_AXIS_Z() NOOP +#endif -#ifdef Z_AFTER_DEACTIVATE - #define Z_RESET() do{ current_position.z = Z_AFTER_DEACTIVATE; sync_plan_position(); }while(0) +#ifdef Z_IDLE_HEIGHT + #define Z_RESET() do{ current_position.z = Z_IDLE_HEIGHT; sync_plan_position(); }while(0) #else #define Z_RESET() #endif -#define DISABLE_AXIS_Z() do{ DISABLE_STEPPER_Z(); DISABLE_STEPPER_Z2(); DISABLE_STEPPER_Z3(); DISABLE_STEPPER_Z4(); FORGET_AXIS(Z_AXIS); Z_RESET(); }while(0) + +#if LINEAR_AXES >= 4 + #define ENABLE_AXIS_I() if (SHOULD_ENABLE(i)) { ENABLE_STEPPER_I(); AFTER_CHANGE(i, true); } + #define DISABLE_AXIS_I() if (SHOULD_DISABLE(i)) { DISABLE_STEPPER_I(); AFTER_CHANGE(i, false); set_axis_untrusted(I_AXIS); } +#else + #define ENABLE_AXIS_I() NOOP + #define DISABLE_AXIS_I() NOOP +#endif +#if LINEAR_AXES >= 5 + #define ENABLE_AXIS_J() if (SHOULD_ENABLE(j)) { ENABLE_STEPPER_J(); AFTER_CHANGE(j, true); } + #define DISABLE_AXIS_J() if (SHOULD_DISABLE(j)) { DISABLE_STEPPER_J(); AFTER_CHANGE(j, false); set_axis_untrusted(J_AXIS); } +#else + #define ENABLE_AXIS_J() NOOP + #define DISABLE_AXIS_J() NOOP +#endif +#if LINEAR_AXES >= 6 + #define ENABLE_AXIS_K() if (SHOULD_ENABLE(k)) { ENABLE_STEPPER_K(); AFTER_CHANGE(k, true); } + #define DISABLE_AXIS_K() if (SHOULD_DISABLE(k)) { DISABLE_STEPPER_K(); AFTER_CHANGE(k, false); set_axis_untrusted(K_AXIS); } +#else + #define ENABLE_AXIS_K() NOOP + #define DISABLE_AXIS_K() NOOP +#endif // // Extruder steppers enable / disable macros // #if ENABLED(MIXING_EXTRUDER) + /** * Mixing steppers keep all their enable (and direction) states synchronized */ @@ -869,6 +1026,12 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #define _CALL_DIS_E(N) DISABLE_STEPPER_E##N () ; #define ENABLE_AXIS_E0() { RREPEAT(MIXING_STEPPERS, _CALL_ENA_E) } #define DISABLE_AXIS_E0() { RREPEAT(MIXING_STEPPERS, _CALL_DIS_E) } + +#elif ENABLED(E_DUAL_STEPPER_DRIVERS) + + #define ENABLE_AXIS_E0() do{ ENABLE_STEPPER_E0(); ENABLE_STEPPER_E1(); }while(0) + #define DISABLE_AXIS_E0() do{ DISABLE_STEPPER_E0(); DISABLE_STEPPER_E1(); }while(0) + #endif #ifndef ENABLE_AXIS_E0 diff --git a/Marlin/src/module/stepper/trinamic.cpp b/Marlin/src/module/stepper/trinamic.cpp index d5a861d71ba0..fd630279748b 100644 --- a/Marlin/src/module/stepper/trinamic.cpp +++ b/Marlin/src/module/stepper/trinamic.cpp @@ -35,8 +35,10 @@ #include #include -enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; -#define TMC_INIT(ST, STEALTH_INDEX) tmc_init(stepper##ST, ST##_CURRENT, ST##_MICROSTEPS, ST##_HYBRID_THRESHOLD, stealthchop_by_axis[STEALTH_INDEX]) +enum StealthIndex : uint8_t { + LOGICAL_AXIS_LIST(STEALTH_AXIS_E, STEALTH_AXIS_X, STEALTH_AXIS_Y, STEALTH_AXIS_Z, STEALTH_AXIS_I, STEALTH_AXIS_J, STEALTH_AXIS_K) +}; +#define TMC_INIT(ST, STEALTH_INDEX) tmc_init(stepper##ST, ST##_CURRENT, ST##_MICROSTEPS, ST##_HYBRID_THRESHOLD, stealthchop_by_axis[STEALTH_INDEX], chopper_timing_##ST, ST##_INTERPOLATE) // IC = TMC model number // ST = Stepper object letter @@ -62,7 +64,7 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; #define _TMC_UART_DEFINE(SWHW, IC, ST, AI) TMC_UART_##SWHW##_DEFINE(IC, ST, TMC_##ST##_LABEL, AI) #define TMC_UART_DEFINE(SWHW, ST, AI) _TMC_UART_DEFINE(SWHW, ST##_DRIVER_TYPE, ST, AI##_AXIS) -#if DISTINCT_E > 1 +#if ENABLED(DISTINCT_E_FACTORS) #define TMC_SPI_DEFINE_E(AI) TMC_SPI_DEFINE(E##AI, E##AI) #define TMC_UART_DEFINE_E(SWHW, AI) TMC_UART_DEFINE(SWHW, E##AI, E##AI) #else @@ -95,6 +97,15 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; #if AXIS_HAS_SPI(Z4) TMC_SPI_DEFINE(Z4, Z); #endif +#if AXIS_HAS_SPI(I) + TMC_SPI_DEFINE(I, I); +#endif +#if AXIS_HAS_SPI(J) + TMC_SPI_DEFINE(J, J); +#endif +#if AXIS_HAS_SPI(K) + TMC_SPI_DEFINE(K, K); +#endif #if AXIS_HAS_SPI(E0) TMC_SPI_DEFINE_E(0); #endif @@ -129,17 +140,66 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; #define TMC_BAUD_RATE TERN(HAS_TMC_SW_SERIAL, 57600, 115200) #endif +#ifndef TMC_X_BAUD_RATE + #define TMC_X_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_X2_BAUD_RATE + #define TMC_X2_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_Y_BAUD_RATE + #define TMC_Y_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_Y2_BAUD_RATE + #define TMC_Y2_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_Z_BAUD_RATE + #define TMC_Z_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_Z2_BAUD_RATE + #define TMC_Z2_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_Z3_BAUD_RATE + #define TMC_Z3_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_Z4_BAUD_RATE + #define TMC_Z4_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_E0_BAUD_RATE + #define TMC_E0_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_E1_BAUD_RATE + #define TMC_E1_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_E2_BAUD_RATE + #define TMC_E2_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_E3_BAUD_RATE + #define TMC_E3_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_E4_BAUD_RATE + #define TMC_E4_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_E5_BAUD_RATE + #define TMC_E5_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_E6_BAUD_RATE + #define TMC_E6_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_E7_BAUD_RATE + #define TMC_E7_BAUD_RATE TMC_BAUD_RATE +#endif + #if HAS_DRIVER(TMC2130) template - void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth) { + void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate) { st.begin(); CHOPCONF_t chopconf{0}; - chopconf.tbl = 1; - chopconf.toff = chopper_timing.toff; - chopconf.intpol = INTERPOLATE; - chopconf.hend = chopper_timing.hend + 3; - chopconf.hstrt = chopper_timing.hstrt - 1; + chopconf.tbl = 0b01; + chopconf.toff = chop_init.toff; + chopconf.intpol = interpolate; + chopconf.hend = chop_init.hend + 3; + chopconf.hstrt = chop_init.hstrt - 1; TERN_(SQUARE_WAVE_STEPPING, chopconf.dedge = true); st.CHOPCONF(chopconf.sr); @@ -166,15 +226,15 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; #if HAS_DRIVER(TMC2160) template - void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth) { + void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate) { st.begin(); CHOPCONF_t chopconf{0}; - chopconf.tbl = 1; - chopconf.toff = chopper_timing.toff; - chopconf.intpol = INTERPOLATE; - chopconf.hend = chopper_timing.hend + 3; - chopconf.hstrt = chopper_timing.hstrt - 1; + chopconf.tbl = 0b01; + chopconf.toff = chop_init.toff; + chopconf.intpol = interpolate; + chopconf.hend = chop_init.hend + 3; + chopconf.hstrt = chop_init.hstrt - 1; TERN_(SQUARE_WAVE_STEPPING, chopconf.dedge = true); st.CHOPCONF(chopconf.sr); @@ -278,6 +338,34 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; #define Z4_HAS_SW_SERIAL 1 #endif #endif + #if AXIS_HAS_UART(I) + #ifdef I_HARDWARE_SERIAL + TMC_UART_DEFINE(HW, I, I); + #define I_HAS_HW_SERIAL 1 + #else + TMC_UART_DEFINE(SW, I, I); + #define I_HAS_SW_SERIAL 1 + #endif + #endif + #if AXIS_HAS_UART(J) + #ifdef J_HARDWARE_SERIAL + TMC_UART_DEFINE(HW, J, J); + #define J_HAS_HW_SERIAL 1 + #else + TMC_UART_DEFINE(SW, J, J); + #define J_HAS_SW_SERIAL 1 + #endif + #endif + #if AXIS_HAS_UART(K) + #ifdef K_HARDWARE_SERIAL + TMC_UART_DEFINE(HW, K, K); + #define K_HAS_HW_SERIAL 1 + #else + TMC_UART_DEFINE(SW, K, K); + #define K_HAS_SW_SERIAL 1 + #endif + #endif + #if AXIS_HAS_UART(E0) #ifdef E0_HARDWARE_SERIAL TMC_UART_DEFINE_E(HW, 0); @@ -351,7 +439,9 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; #endif #endif - enum TMCAxis : uint8_t { X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7, TOTAL }; + #define _EN_ITEM(N) , E##N + enum TMCAxis : uint8_t { LINEAR_AXIS_LIST(X, Y, Z, I, J, K), X2, Y2, Z2, Z3, Z4 REPEAT(EXTRUDERS, _EN_ITEM), TOTAL }; + #undef _EN_ITEM void tmc_serial_begin() { #if HAS_TMC_HW_SERIAL @@ -364,7 +454,7 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; } sp_helper; #define HW_SERIAL_BEGIN(A) do{ if (!sp_helper.began(TMCAxis::A, &A##_HARDWARE_SERIAL)) \ - A##_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); }while(0) + A##_HARDWARE_SERIAL.begin(TMC_##A##_BAUD_RATE); }while(0) #endif #if AXIS_HAS_UART(X) @@ -423,6 +513,27 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; stepperZ4.beginSerial(TMC_BAUD_RATE); #endif #endif + #if AXIS_HAS_UART(I) + #ifdef I_HARDWARE_SERIAL + HW_SERIAL_BEGIN(I); + #else + stepperI.beginSerial(TMC_BAUD_RATE); + #endif + #endif + #if AXIS_HAS_UART(J) + #ifdef J_HARDWARE_SERIAL + HW_SERIAL_BEGIN(J); + #else + stepperJ.beginSerial(TMC_BAUD_RATE); + #endif + #endif + #if AXIS_HAS_UART(K) + #ifdef K_HARDWARE_SERIAL + HW_SERIAL_BEGIN(K); + #else + stepperK.beginSerial(TMC_BAUD_RATE); + #endif + #endif #if AXIS_HAS_UART(E0) #ifdef E0_HARDWARE_SERIAL HW_SERIAL_BEGIN(E0); @@ -484,7 +595,7 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; #if HAS_DRIVER(TMC2208) template - void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth) { + void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate) { TMC2208_n::GCONF_t gconf{0}; gconf.pdn_disable = true; // Use UART gconf.mstep_reg_select = true; // Select microsteps with UART @@ -495,10 +606,10 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; TMC2208_n::CHOPCONF_t chopconf{0}; chopconf.tbl = 0b01; // blank_time = 24 - chopconf.toff = chopper_timing.toff; - chopconf.intpol = INTERPOLATE; - chopconf.hend = chopper_timing.hend + 3; - chopconf.hstrt = chopper_timing.hstrt - 1; + chopconf.toff = chop_init.toff; + chopconf.intpol = interpolate; + chopconf.hend = chop_init.hend + 3; + chopconf.hstrt = chop_init.hstrt - 1; TERN_(SQUARE_WAVE_STEPPING, chopconf.dedge = true); st.CHOPCONF(chopconf.sr); @@ -526,7 +637,7 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; #if HAS_DRIVER(TMC2209) template - void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth) { + void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate) { TMC2208_n::GCONF_t gconf{0}; gconf.pdn_disable = true; // Use UART gconf.mstep_reg_select = true; // Select microsteps with UART @@ -537,10 +648,10 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; TMC2208_n::CHOPCONF_t chopconf{0}; chopconf.tbl = 0b01; // blank_time = 24 - chopconf.toff = chopper_timing.toff; - chopconf.intpol = INTERPOLATE; - chopconf.hend = chopper_timing.hend + 3; - chopconf.hstrt = chopper_timing.hstrt - 1; + chopconf.toff = chop_init.toff; + chopconf.intpol = interpolate; + chopconf.hend = chop_init.hend + 3; + chopconf.hstrt = chop_init.hstrt - 1; TERN_(SQUARE_WAVE_STEPPING, chopconf.dedge = true); st.CHOPCONF(chopconf.sr); @@ -568,21 +679,21 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; #if HAS_DRIVER(TMC2660) template - void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t, const bool) { + void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t, const bool, const chopper_timing_t &chop_init, const bool interpolate) { st.begin(); TMC2660_n::CHOPCONF_t chopconf{0}; - chopconf.tbl = 1; - chopconf.toff = chopper_timing.toff; - chopconf.hend = chopper_timing.hend + 3; - chopconf.hstrt = chopper_timing.hstrt - 1; + chopconf.tbl = 0b01; + chopconf.toff = chop_init.toff; + chopconf.hend = chop_init.hend + 3; + chopconf.hstrt = chop_init.hstrt - 1; st.CHOPCONF(chopconf.sr); st.sdoff(0); st.rms_current(mA); st.microsteps(microsteps); TERN_(SQUARE_WAVE_STEPPING, st.dedge(true)); - st.intpol(INTERPOLATE); + st.intpol(interpolate); st.diss2g(true); // Disable short to ground protection. Too many false readings? TERN_(TMC_DEBUG, st.rdsel(0b01)); } @@ -590,15 +701,15 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; #if HAS_DRIVER(TMC5130) template - void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth) { + void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate) { st.begin(); CHOPCONF_t chopconf{0}; - chopconf.tbl = 1; - chopconf.toff = chopper_timing.toff; - chopconf.intpol = INTERPOLATE; - chopconf.hend = chopper_timing.hend + 3; - chopconf.hstrt = chopper_timing.hstrt - 1; + chopconf.tbl = 0b01; + chopconf.toff = chop_init.toff; + chopconf.intpol = interpolate; + chopconf.hend = chop_init.hend + 3; + chopconf.hstrt = chop_init.hstrt - 1; TERN_(SQUARE_WAVE_STEPPING, chopconf.dedge = true); st.CHOPCONF(chopconf.sr); @@ -625,15 +736,15 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; #if HAS_DRIVER(TMC5160) template - void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth) { + void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate) { st.begin(); CHOPCONF_t chopconf{0}; - chopconf.tbl = 1; - chopconf.toff = chopper_timing.toff; - chopconf.intpol = INTERPOLATE; - chopconf.hend = chopper_timing.hend + 3; - chopconf.hstrt = chopper_timing.hstrt - 1; + chopconf.tbl = 0b01; + chopconf.toff = chop_init.toff; + chopconf.intpol = interpolate; + chopconf.hend = chop_init.hend + 3; + chopconf.hstrt = chop_init.hstrt - 1; TERN_(SQUARE_WAVE_STEPPING, chopconf.dedge = true); st.CHOPCONF(chopconf.sr); @@ -655,11 +766,7 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; pwmconf.pwm_ofs = 36; st.PWMCONF(pwmconf.sr); - #if ENABLED(HYBRID_THRESHOLD) - st.set_pwm_thrs(hyb_thrs); - #else - UNUSED(hyb_thrs); - #endif + TERN(HYBRID_THRESHOLD, st.set_pwm_thrs(hyb_thrs), UNUSED(hyb_thrs)); st.GSTAT(); // Clear GSTAT } #endif // TMC5160 @@ -689,6 +796,15 @@ void restore_trinamic_drivers() { #if AXIS_IS_TMC(Z4) stepperZ4.push(); #endif + #if AXIS_IS_TMC(I) + stepperI.push(); + #endif + #if AXIS_IS_TMC(J) + stepperJ.push(); + #endif + #if AXIS_IS_TMC(K) + stepperK.push(); + #endif #if AXIS_IS_TMC(E0) stepperE0.push(); #endif @@ -716,19 +832,27 @@ void restore_trinamic_drivers() { } void reset_trinamic_drivers() { - static constexpr bool stealthchop_by_axis[] = { ENABLED(STEALTHCHOP_XY), ENABLED(STEALTHCHOP_Z), ENABLED(STEALTHCHOP_E) }; + static constexpr bool stealthchop_by_axis[] = LOGICAL_AXIS_ARRAY( + ENABLED(STEALTHCHOP_E), + ENABLED(STEALTHCHOP_XY), + ENABLED(STEALTHCHOP_XY), + ENABLED(STEALTHCHOP_Z), + ENABLED(STEALTHCHOP_I), + ENABLED(STEALTHCHOP_J), + ENABLED(STEALTHCHOP_K) + ); #if AXIS_IS_TMC(X) - TMC_INIT(X, STEALTH_AXIS_XY); + TMC_INIT(X, STEALTH_AXIS_X); #endif #if AXIS_IS_TMC(X2) - TMC_INIT(X2, STEALTH_AXIS_XY); + TMC_INIT(X2, STEALTH_AXIS_X); #endif #if AXIS_IS_TMC(Y) - TMC_INIT(Y, STEALTH_AXIS_XY); + TMC_INIT(Y, STEALTH_AXIS_Y); #endif #if AXIS_IS_TMC(Y2) - TMC_INIT(Y2, STEALTH_AXIS_XY); + TMC_INIT(Y2, STEALTH_AXIS_Y); #endif #if AXIS_IS_TMC(Z) TMC_INIT(Z, STEALTH_AXIS_Z); @@ -742,6 +866,15 @@ void reset_trinamic_drivers() { #if AXIS_IS_TMC(Z4) TMC_INIT(Z4, STEALTH_AXIS_Z); #endif + #if AXIS_IS_TMC(I) + TMC_INIT(I, STEALTH_AXIS_I); + #endif + #if AXIS_IS_TMC(J) + TMC_INIT(J, STEALTH_AXIS_J); + #endif + #if AXIS_IS_TMC(K) + TMC_INIT(K, STEALTH_AXIS_K); + #endif #if AXIS_IS_TMC(E0) TMC_INIT(E0, STEALTH_AXIS_E); #endif @@ -792,7 +925,25 @@ void reset_trinamic_drivers() { stepperZ4.homing_threshold(CAT(TERN(Z4_SENSORLESS, Z4, Z), _STALL_SENSITIVITY)); #endif #endif - #endif + #if I_SENSORLESS + stepperI.homing_threshold(I_STALL_SENSITIVITY); + #if AXIS_HAS_STALLGUARD(I) + stepperI.homing_threshold(CAT(TERN(I_SENSORLESS, I, I), _STALL_SENSITIVITY)); + #endif + #endif + #if J_SENSORLESS + stepperJ.homing_threshold(J_STALL_SENSITIVITY); + #if AXIS_HAS_STALLGUARD(J) + stepperJ.homing_threshold(CAT(TERN(J_SENSORLESS, J, J), _STALL_SENSITIVITY)); + #endif + #endif + #if K_SENSORLESS + stepperK.homing_threshold(K_STALL_SENSITIVITY); + #if AXIS_HAS_STALLGUARD(K) + stepperK.homing_threshold(CAT(TERN(K_SENSORLESS, K, K), _STALL_SENSITIVITY)); + #endif + #endif + #endif // USE SENSORLESS #ifdef TMC_ADV TMC_ADV() @@ -804,7 +955,7 @@ void reset_trinamic_drivers() { // TMC Slave Address Conflict Detection // // Conflict detection is performed in the following way. Similar methods are used for -// hardware and software serial, but the implementations are indepenent. +// hardware and software serial, but the implementations are independent. // // 1. Populate a data structure with UART parameters and addresses for all possible axis. // If an axis is not in use, populate it with recognizable placeholder data. @@ -816,11 +967,12 @@ void reset_trinamic_drivers() { // Using a fixed-length character array for the port name allows this to be constexpr compatible. struct SanityHwSerialDetails { const char port[20]; uint32_t address; }; #define TMC_HW_DETAIL_ARGS(A) TERN(A##_HAS_HW_SERIAL, STRINGIFY(A##_HARDWARE_SERIAL), ""), TERN0(A##_HAS_HW_SERIAL, A##_SLAVE_ADDRESS) - #define TMC_HW_DETAIL(A) {TMC_HW_DETAIL_ARGS(A)} + #define TMC_HW_DETAIL(A) { TMC_HW_DETAIL_ARGS(A) } constexpr SanityHwSerialDetails sanity_tmc_hw_details[] = { TMC_HW_DETAIL(X), TMC_HW_DETAIL(X2), TMC_HW_DETAIL(Y), TMC_HW_DETAIL(Y2), TMC_HW_DETAIL(Z), TMC_HW_DETAIL(Z2), TMC_HW_DETAIL(Z3), TMC_HW_DETAIL(Z4), + TMC_HW_DETAIL(I), TMC_HW_DETAIL(J), TMC_HW_DETAIL(K), TMC_HW_DETAIL(E0), TMC_HW_DETAIL(E1), TMC_HW_DETAIL(E2), TMC_HW_DETAIL(E3), TMC_HW_DETAIL(E4), TMC_HW_DETAIL(E5), TMC_HW_DETAIL(E6), TMC_HW_DETAIL(E7) }; @@ -830,20 +982,21 @@ void reset_trinamic_drivers() { } constexpr bool sc_hw_done(size_t start, size_t end) { return start == end; } - constexpr bool sc_hw_skip(const char* port_name) { return !(*port_name); } - constexpr bool sc_hw_match(const char* port_name, uint32_t address, size_t start, size_t end) { + constexpr bool sc_hw_skip(const char *port_name) { return !(*port_name); } + constexpr bool sc_hw_match(const char *port_name, uint32_t address, size_t start, size_t end) { return !sc_hw_done(start, end) && !sc_hw_skip(port_name) && (address == sanity_tmc_hw_details[start].address && str_eq_ce(port_name, sanity_tmc_hw_details[start].port)); } - constexpr int count_tmc_hw_serial_matches(const char* port_name, uint32_t address, size_t start, size_t end) { + constexpr int count_tmc_hw_serial_matches(const char *port_name, uint32_t address, size_t start, size_t end) { return sc_hw_done(start, end) ? 0 : ((sc_hw_skip(port_name) ? 0 : (sc_hw_match(port_name, address, start, end) ? 1 : 0)) + count_tmc_hw_serial_matches(port_name, address, start + 1, end)); } #define TMC_HWSERIAL_CONFLICT_MSG(A) STRINGIFY(A) "_SLAVE_ADDRESS conflicts with another driver using the same " STRINGIFY(A) "_HARDWARE_SERIAL" #define SA_NO_TMC_HW_C(A) static_assert(1 >= count_tmc_hw_serial_matches(TMC_HW_DETAIL_ARGS(A), 0, COUNT(sanity_tmc_hw_details)), TMC_HWSERIAL_CONFLICT_MSG(A)); - SA_NO_TMC_HW_C(X);SA_NO_TMC_HW_C(X2); - SA_NO_TMC_HW_C(Y);SA_NO_TMC_HW_C(Y2); - SA_NO_TMC_HW_C(Z);SA_NO_TMC_HW_C(Z2);SA_NO_TMC_HW_C(Z3);SA_NO_TMC_HW_C(Z4); - SA_NO_TMC_HW_C(E0);SA_NO_TMC_HW_C(E1);SA_NO_TMC_HW_C(E2);SA_NO_TMC_HW_C(E3);SA_NO_TMC_HW_C(E4);SA_NO_TMC_HW_C(E5);SA_NO_TMC_HW_C(E6);SA_NO_TMC_HW_C(E7); + SA_NO_TMC_HW_C(X); SA_NO_TMC_HW_C(X2); + SA_NO_TMC_HW_C(Y); SA_NO_TMC_HW_C(Y2); + SA_NO_TMC_HW_C(Z); SA_NO_TMC_HW_C(Z2); SA_NO_TMC_HW_C(Z3); SA_NO_TMC_HW_C(Z4); + SA_NO_TMC_HW_C(I); SA_NO_TMC_HW_C(J); SA_NO_TMC_HW_C(K); + SA_NO_TMC_HW_C(E0); SA_NO_TMC_HW_C(E1); SA_NO_TMC_HW_C(E2); SA_NO_TMC_HW_C(E3); SA_NO_TMC_HW_C(E4); SA_NO_TMC_HW_C(E5); SA_NO_TMC_HW_C(E6); SA_NO_TMC_HW_C(E7); #endif #if ANY_AXIS_HAS(SW_SERIAL) @@ -854,6 +1007,7 @@ void reset_trinamic_drivers() { TMC_SW_DETAIL(X), TMC_SW_DETAIL(X2), TMC_SW_DETAIL(Y), TMC_SW_DETAIL(Y2), TMC_SW_DETAIL(Z), TMC_SW_DETAIL(Z2), TMC_SW_DETAIL(Z3), TMC_SW_DETAIL(Z4), + TMC_SW_DETAIL(I), TMC_SW_DETAIL(J), TMC_SW_DETAIL(K), TMC_SW_DETAIL(E0), TMC_SW_DETAIL(E1), TMC_SW_DETAIL(E2), TMC_SW_DETAIL(E3), TMC_SW_DETAIL(E4), TMC_SW_DETAIL(E5), TMC_SW_DETAIL(E6), TMC_SW_DETAIL(E7) }; @@ -868,10 +1022,11 @@ void reset_trinamic_drivers() { #define TMC_SWSERIAL_CONFLICT_MSG(A) STRINGIFY(A) "_SLAVE_ADDRESS conflicts with another driver using the same " STRINGIFY(A) "_SERIAL_RX_PIN or " STRINGIFY(A) "_SERIAL_TX_PIN" #define SA_NO_TMC_SW_C(A) static_assert(1 >= count_tmc_sw_serial_matches(TMC_SW_DETAIL_ARGS(A), 0, COUNT(sanity_tmc_sw_details)), TMC_SWSERIAL_CONFLICT_MSG(A)); - SA_NO_TMC_SW_C(X);SA_NO_TMC_SW_C(X2); - SA_NO_TMC_SW_C(Y);SA_NO_TMC_SW_C(Y2); - SA_NO_TMC_SW_C(Z);SA_NO_TMC_SW_C(Z2);SA_NO_TMC_SW_C(Z3);SA_NO_TMC_SW_C(Z4); - SA_NO_TMC_SW_C(E0);SA_NO_TMC_SW_C(E1);SA_NO_TMC_SW_C(E2);SA_NO_TMC_SW_C(E3);SA_NO_TMC_SW_C(E4);SA_NO_TMC_SW_C(E5);SA_NO_TMC_SW_C(E6);SA_NO_TMC_SW_C(E7); + SA_NO_TMC_SW_C(X); SA_NO_TMC_SW_C(X2); + SA_NO_TMC_SW_C(Y); SA_NO_TMC_SW_C(Y2); + SA_NO_TMC_SW_C(Z); SA_NO_TMC_SW_C(Z2); SA_NO_TMC_SW_C(Z3); SA_NO_TMC_SW_C(Z4); + SA_NO_TMC_SW_C(I); SA_NO_TMC_SW_C(J); SA_NO_TMC_SW_C(K); + SA_NO_TMC_SW_C(E0); SA_NO_TMC_SW_C(E1); SA_NO_TMC_SW_C(E2); SA_NO_TMC_SW_C(E3); SA_NO_TMC_SW_C(E4); SA_NO_TMC_SW_C(E5); SA_NO_TMC_SW_C(E6); SA_NO_TMC_SW_C(E7); #endif #endif // HAS_TRINAMIC_CONFIG diff --git a/Marlin/src/module/stepper/trinamic.h b/Marlin/src/module/stepper/trinamic.h index 9cc3404cd2d7..766f8fced246 100644 --- a/Marlin/src/module/stepper/trinamic.h +++ b/Marlin/src/module/stepper/trinamic.h @@ -46,6 +46,10 @@ #define TMC_Y_LABEL 'Y', '0' #define TMC_Z_LABEL 'Z', '0' +#define TMC_I_LABEL 'I', '0' +#define TMC_J_LABEL 'J', '0' +#define TMC_K_LABEL 'K', '0' + #define TMC_X2_LABEL 'X', '2' #define TMC_Y2_LABEL 'Y', '2' #define TMC_Z2_LABEL 'Z', '2' @@ -76,7 +80,27 @@ typedef struct { uint8_t hstrt; } chopper_timing_t; -static constexpr chopper_timing_t chopper_timing = CHOPPER_TIMING; +#ifndef CHOPPER_TIMING_X + #define CHOPPER_TIMING_X CHOPPER_TIMING +#endif +#if HAS_Y_AXIS && !defined(CHOPPER_TIMING_Y) + #define CHOPPER_TIMING_Y CHOPPER_TIMING +#endif +#if HAS_Z_AXIS && !defined(CHOPPER_TIMING_Z) + #define CHOPPER_TIMING_Z CHOPPER_TIMING +#endif +#if LINEAR_AXES >= 4 && !defined(CHOPPER_TIMING_I) + #define CHOPPER_TIMING_I CHOPPER_TIMING +#endif +#if LINEAR_AXES >= 5 && !defined(CHOPPER_TIMING_J) + #define CHOPPER_TIMING_J CHOPPER_TIMING +#endif +#if LINEAR_AXES >= 6 && !defined(CHOPPER_TIMING_K) + #define CHOPPER_TIMING_K CHOPPER_TIMING +#endif +#if HAS_EXTRUDERS && !defined(CHOPPER_TIMING_E) + #define CHOPPER_TIMING_E CHOPPER_TIMING +#endif #if HAS_TMC220x void tmc_serial_begin(); @@ -90,9 +114,10 @@ void reset_trinamic_drivers(); // X Stepper #if AXIS_IS_TMC(X) extern TMC_CLASS(X, X) stepperX; + static constexpr chopper_timing_t chopper_timing_X = CHOPPER_TIMING_X; #if ENABLED(SOFTWARE_DRIVER_ENABLE) #define X_ENABLE_INIT() NOOP - #define X_ENABLE_WRITE(STATE) stepperX.toff((STATE)==X_ENABLE_ON ? chopper_timing.toff : 0) + #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) @@ -103,9 +128,10 @@ void reset_trinamic_drivers(); // Y Stepper #if AXIS_IS_TMC(Y) extern TMC_CLASS(Y, Y) stepperY; + static constexpr chopper_timing_t chopper_timing_Y = CHOPPER_TIMING_Y; #if ENABLED(SOFTWARE_DRIVER_ENABLE) #define Y_ENABLE_INIT() NOOP - #define Y_ENABLE_WRITE(STATE) stepperY.toff((STATE)==Y_ENABLE_ON ? chopper_timing.toff : 0) + #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) @@ -116,9 +142,10 @@ void reset_trinamic_drivers(); // Z Stepper #if AXIS_IS_TMC(Z) extern TMC_CLASS(Z, Z) stepperZ; + static constexpr chopper_timing_t chopper_timing_Z = CHOPPER_TIMING_Z; #if ENABLED(SOFTWARE_DRIVER_ENABLE) #define Z_ENABLE_INIT() NOOP - #define Z_ENABLE_WRITE(STATE) stepperZ.toff((STATE)==Z_ENABLE_ON ? chopper_timing.toff : 0) + #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) @@ -129,9 +156,13 @@ void reset_trinamic_drivers(); // X2 Stepper #if HAS_X2_ENABLE && AXIS_IS_TMC(X2) extern TMC_CLASS(X2, X) stepperX2; + #ifndef CHOPPER_TIMING_X2 + #define CHOPPER_TIMING_X2 CHOPPER_TIMING_X + #endif + static constexpr chopper_timing_t chopper_timing_X2 = CHOPPER_TIMING_X2; #if ENABLED(SOFTWARE_DRIVER_ENABLE) #define X2_ENABLE_INIT() NOOP - #define X2_ENABLE_WRITE(STATE) stepperX2.toff((STATE)==X_ENABLE_ON ? chopper_timing.toff : 0) + #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) @@ -142,9 +173,13 @@ void reset_trinamic_drivers(); // Y2 Stepper #if HAS_Y2_ENABLE && AXIS_IS_TMC(Y2) extern TMC_CLASS(Y2, Y) stepperY2; + #ifndef CHOPPER_TIMING_Y2 + #define CHOPPER_TIMING_Y2 CHOPPER_TIMING_Y + #endif + static constexpr chopper_timing_t chopper_timing_Y2 = CHOPPER_TIMING_Y2; #if ENABLED(SOFTWARE_DRIVER_ENABLE) #define Y2_ENABLE_INIT() NOOP - #define Y2_ENABLE_WRITE(STATE) stepperY2.toff((STATE)==Y_ENABLE_ON ? chopper_timing.toff : 0) + #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) @@ -155,9 +190,13 @@ void reset_trinamic_drivers(); // Z2 Stepper #if HAS_Z2_ENABLE && AXIS_IS_TMC(Z2) extern TMC_CLASS(Z2, Z) stepperZ2; + #ifndef CHOPPER_TIMING_Z2 + #define CHOPPER_TIMING_Z2 CHOPPER_TIMING_Z + #endif + static constexpr chopper_timing_t chopper_timing_Z2 = CHOPPER_TIMING_Z2; #if ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z2) #define Z2_ENABLE_INIT() NOOP - #define Z2_ENABLE_WRITE(STATE) stepperZ2.toff((STATE)==Z_ENABLE_ON ? chopper_timing.toff : 0) + #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) @@ -168,9 +207,13 @@ void reset_trinamic_drivers(); // Z3 Stepper #if HAS_Z3_ENABLE && AXIS_IS_TMC(Z3) extern TMC_CLASS(Z3, Z) stepperZ3; + #ifndef CHOPPER_TIMING_Z3 + #define CHOPPER_TIMING_Z3 CHOPPER_TIMING_Z + #endif + static constexpr chopper_timing_t chopper_timing_Z3 = CHOPPER_TIMING_Z3; #if ENABLED(SOFTWARE_DRIVER_ENABLE) #define Z3_ENABLE_INIT() NOOP - #define Z3_ENABLE_WRITE(STATE) stepperZ3.toff((STATE)==Z_ENABLE_ON ? chopper_timing.toff : 0) + #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) @@ -181,9 +224,13 @@ void reset_trinamic_drivers(); // Z4 Stepper #if HAS_Z4_ENABLE && AXIS_IS_TMC(Z4) extern TMC_CLASS(Z4, Z) stepperZ4; + #ifndef CHOPPER_TIMING_Z4 + #define CHOPPER_TIMING_Z4 CHOPPER_TIMING_Z + #endif + static constexpr chopper_timing_t chopper_timing_Z4 = CHOPPER_TIMING_Z4; #if ENABLED(SOFTWARE_DRIVER_ENABLE) #define Z4_ENABLE_INIT() NOOP - #define Z4_ENABLE_WRITE(STATE) stepperZ4.toff((STATE)==Z_ENABLE_ON ? chopper_timing.toff : 0) + #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) @@ -191,12 +238,58 @@ void reset_trinamic_drivers(); #endif #endif +// I Stepper +#if AXIS_IS_TMC(I) + extern TMC_CLASS(I, I) stepperI; + 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_READ() stepperI.isEnabled() + #endif + #if AXIS_HAS_SQUARE_WAVE(I) + #define I_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(I_STEP_PIN); }while(0) + #endif +#endif + +// J Stepper +#if AXIS_IS_TMC(J) + extern TMC_CLASS(J, J) stepperJ; + 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_READ() stepperJ.isEnabled() + #endif + #if AXIS_HAS_SQUARE_WAVE(J) + #define J_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(J_STEP_PIN); }while(0) + #endif +#endif + +// K Stepper +#if AXIS_IS_TMC(K) + extern TMC_CLASS(K, K) stepperK; + 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_READ() stepperK.isEnabled() + #endif + #if AXIS_HAS_SQUARE_WAVE(K) + #define K_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(K_STEP_PIN); }while(0) + #endif +#endif + // E0 Stepper #if AXIS_IS_TMC(E0) extern TMC_CLASS_E(0) stepperE0; + #ifndef CHOPPER_TIMING_E0 + #define CHOPPER_TIMING_E0 CHOPPER_TIMING_E + #endif + static constexpr chopper_timing_t chopper_timing_E0 = CHOPPER_TIMING_E0; #if ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E0) #define E0_ENABLE_INIT() NOOP - #define E0_ENABLE_WRITE(STATE) stepperE0.toff((STATE)==E_ENABLE_ON ? chopper_timing.toff : 0) + #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) @@ -207,9 +300,13 @@ void reset_trinamic_drivers(); // E1 Stepper #if AXIS_IS_TMC(E1) extern TMC_CLASS_E(1) stepperE1; + #ifndef CHOPPER_TIMING_E1 + #define CHOPPER_TIMING_E1 CHOPPER_TIMING_E + #endif + static constexpr chopper_timing_t chopper_timing_E1 = CHOPPER_TIMING_E1; #if ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E1) #define E1_ENABLE_INIT() NOOP - #define E1_ENABLE_WRITE(STATE) stepperE1.toff((STATE)==E_ENABLE_ON ? chopper_timing.toff : 0) + #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) @@ -220,9 +317,13 @@ void reset_trinamic_drivers(); // E2 Stepper #if AXIS_IS_TMC(E2) extern TMC_CLASS_E(2) stepperE2; + #ifndef CHOPPER_TIMING_E2 + #define CHOPPER_TIMING_E2 CHOPPER_TIMING_E + #endif + static constexpr chopper_timing_t chopper_timing_E2 = CHOPPER_TIMING_E2; #if ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E2) #define E2_ENABLE_INIT() NOOP - #define E2_ENABLE_WRITE(STATE) stepperE2.toff((STATE)==E_ENABLE_ON ? chopper_timing.toff : 0) + #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) @@ -233,9 +334,13 @@ void reset_trinamic_drivers(); // E3 Stepper #if AXIS_IS_TMC(E3) extern TMC_CLASS_E(3) stepperE3; + #ifndef CHOPPER_TIMING_E3 + #define CHOPPER_TIMING_E3 CHOPPER_TIMING_E + #endif + static constexpr chopper_timing_t chopper_timing_E3 = CHOPPER_TIMING_E3; #if ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E3) #define E3_ENABLE_INIT() NOOP - #define E3_ENABLE_WRITE(STATE) stepperE3.toff((STATE)==E_ENABLE_ON ? chopper_timing.toff : 0) + #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) @@ -246,9 +351,13 @@ void reset_trinamic_drivers(); // E4 Stepper #if AXIS_IS_TMC(E4) extern TMC_CLASS_E(4) stepperE4; + #ifndef CHOPPER_TIMING_E4 + #define CHOPPER_TIMING_E4 CHOPPER_TIMING_E + #endif + static constexpr chopper_timing_t chopper_timing_E4 = CHOPPER_TIMING_E4; #if ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E4) #define E4_ENABLE_INIT() NOOP - #define E4_ENABLE_WRITE(STATE) stepperE4.toff((STATE)==E_ENABLE_ON ? chopper_timing.toff : 0) + #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) @@ -259,9 +368,13 @@ void reset_trinamic_drivers(); // E5 Stepper #if AXIS_IS_TMC(E5) extern TMC_CLASS_E(5) stepperE5; + #ifndef CHOPPER_TIMING_E5 + #define CHOPPER_TIMING_E5 CHOPPER_TIMING_E + #endif + static constexpr chopper_timing_t chopper_timing_E5 = CHOPPER_TIMING_E5; #if ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E5) #define E5_ENABLE_INIT() NOOP - #define E5_ENABLE_WRITE(STATE) stepperE5.toff((STATE)==E_ENABLE_ON ? chopper_timing.toff : 0) + #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) @@ -272,9 +385,13 @@ void reset_trinamic_drivers(); // E6 Stepper #if AXIS_IS_TMC(E6) extern TMC_CLASS_E(6) stepperE6; + #ifndef CHOPPER_TIMING_E6 + #define CHOPPER_TIMING_E6 CHOPPER_TIMING_E + #endif + static constexpr chopper_timing_t chopper_timing_E6 = CHOPPER_TIMING_E6; #if ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E6) #define E6_ENABLE_INIT() NOOP - #define E6_ENABLE_WRITE(STATE) stepperE6.toff((STATE)==E_ENABLE_ON ? chopper_timing.toff : 0) + #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) @@ -285,9 +402,13 @@ void reset_trinamic_drivers(); // E7 Stepper #if AXIS_IS_TMC(E7) extern TMC_CLASS_E(7) stepperE7; + #ifndef CHOPPER_TIMING_E7 + #define CHOPPER_TIMING_E7 CHOPPER_TIMING_E + #endif + static constexpr chopper_timing_t chopper_timing_E7 = CHOPPER_TIMING_E7; #if ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E7) #define E7_ENABLE_INIT() NOOP - #define E7_ENABLE_WRITE(STATE) stepperE7.toff((STATE)==E_ENABLE_ON ? chopper_timing.toff : 0) + #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) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 3b341369a9bc..56322135a4f5 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -27,50 +27,104 @@ // Useful when debugging thermocouples //#define IGNORE_THERMOCOUPLE_ERRORS +#include "../MarlinCore.h" +#include "../HAL/shared/Delay.h" +#include "../lcd/marlinui.h" + #include "temperature.h" #include "endstops.h" - -#include "../MarlinCore.h" #include "planner.h" -#include "../HAL/shared/Delay.h" +#include "printcounter.h" -#include "../lcd/ultralcd.h" +#if EITHER(HAS_COOLER, LASER_COOLANT_FLOW_METER) + #include "../feature/cooler.h" + #include "../feature/spindle_laser.h" +#endif + +#if ENABLED(EMERGENCY_PARSER) + #include "motion.h" +#endif #if ENABLED(DWIN_CREALITY_LCD) - #include "../lcd/dwin/e3v2/dwin.h" + #include "../lcd/e3v2/creality/dwin.h" #endif #if ENABLED(EXTENSIBLE_UI) #include "../lcd/extui/ui_api.h" #endif -#if ENABLED(MAX6675_IS_MAX31865) - #include - #ifndef MAX31865_CS_PIN - #define MAX31865_CS_PIN MAX6675_SS_PIN // HW:49 SW:65 for example - #endif - #ifndef MAX31865_MOSI_PIN - #define MAX31865_MOSI_PIN MOSI_PIN // 63 - #endif - #ifndef MAX31865_MISO_PIN - #define MAX31865_MISO_PIN MAX6675_DO_PIN // 42 - #endif - #ifndef MAX31865_SCK_PIN - #define MAX31865_SCK_PIN MAX6675_SCK_PIN // 40 +#if ENABLED(HOST_PROMPT_SUPPORT) + #include "../feature/host_actions.h" +#endif + +// MAX TC related macros +#define TEMP_SENSOR_IS_MAX(n, M) (ENABLED(TEMP_SENSOR_##n##_IS_MAX##M) || (ENABLED(TEMP_SENSOR_REDUNDANT_IS_MAX##M) && TEMP_SENSOR_REDUNDANT_SOURCE == (n))) +#define TEMP_SENSOR_IS_ANY_MAX_TC(n) (ENABLED(TEMP_SENSOR_##n##_IS_MAX_TC) || (ENABLED(TEMP_SENSOR_REDUNDANT_IS_MAX_TC) && TEMP_SENSOR_REDUNDANT_SOURCE == 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. +#if HAS_MAX6675 && LIB_USR_MAX6675 + #include + #define HAS_MAX6675_LIBRARY 1 +#endif + +// LIB_MAX31855 can be added to the build_flags in platformio.ini to use a user-defined library. +// If LIB_MAX31855 is not on the build_flags then raw SPI reads will be used. +#if HAS_MAX31855 && LIB_USR_MAX31855 + #include + #define HAS_MAX31855_LIBRARY 1 + typedef Adafruit_MAX31855 MAX31855; +#endif + +#if HAS_MAX31865 + #if LIB_USR_MAX31865 + #include + typedef Adafruit_MAX31865 MAX31865; + #else + #include "../libs/MAX31865.h" #endif - Adafruit_MAX31865 max31865 = Adafruit_MAX31865(MAX31865_CS_PIN - #if MAX31865_CS_PIN != MAX6675_SS_PIN - , MAX31865_MOSI_PIN // For software SPI also set MOSI/MISO/SCK - , MAX31865_MISO_PIN - , MAX31865_SCK_PIN - #endif - ); #endif -#define MAX6675_SEPARATE_SPI (EITHER(HEATER_0_USES_MAX6675, HEATER_1_USES_MAX6675) && PINS_EXIST(MAX6675_SCK, MAX6675_DO)) +#if HAS_MAX6675_LIBRARY || HAS_MAX31855_LIBRARY || HAS_MAX31865 + #define HAS_MAXTC_LIBRARIES 1 +#endif -#if MAX6675_SEPARATE_SPI +// If we have a MAX TC with SCK and MISO pins defined, it's either on a separate/dedicated Hardware +// SPI bus, or some pins for Software SPI. Alternate Hardware SPI buses are not supported yet, so +// your SPI options are: +// +// 1. Only CS pin(s) defined: Hardware SPI on the default bus (usually the SD card SPI). +// 2. CS, MISO, and SCK pins defined: Software SPI on a separate bus, as defined by MISO, SCK. +// 3. CS, MISO, and SCK pins w/ FORCE_HW_SPI: Hardware SPI on the default bus, ignoring MISO, SCK. +// +#if TEMP_SENSOR_IS_ANY_MAX_TC(0) && TEMP_SENSOR_0_HAS_SPI_PINS && DISABLED(TEMP_SENSOR_FORCE_HW_SPI) + #define TEMP_SENSOR_0_USES_SW_SPI 1 +#endif +#if TEMP_SENSOR_IS_ANY_MAX_TC(1) && TEMP_SENSOR_1_HAS_SPI_PINS && DISABLED(TEMP_SENSOR_FORCE_HW_SPI) + #define TEMP_SENSOR_1_USES_SW_SPI 1 +#endif + +#if (TEMP_SENSOR_0_USES_SW_SPI || TEMP_SENSOR_1_USES_SW_SPI) && !HAS_MAXTC_LIBRARIES #include "../libs/private_spi.h" + #define HAS_MAXTC_SW_SPI 1 + + // Define pins for SPI-based sensors + #if TEMP_SENSOR_0_USES_SW_SPI + #define SW_SPI_SCK_PIN TEMP_0_SCK_PIN + #define SW_SPI_MISO_PIN TEMP_0_MISO_PIN + #if PIN_EXISTS(TEMP_0_MOSI) + #define SW_SPI_MOSI_PIN TEMP_0_MOSI_PIN + #endif + #else + #define SW_SPI_SCK_PIN TEMP_1_SCK_PIN + #define SW_SPI_MISO_PIN TEMP_1_MISO_PIN + #if PIN_EXISTS(TEMP_1_MOSI) + #define SW_SPI_MOSI_PIN TEMP_1_MOSI_PIN + #endif + #endif + #ifndef SW_SPI_MOSI_PIN + #define SW_SPI_MOSI_PIN SD_MOSI_PIN + #endif #endif #if ENABLED(PID_EXTRUSION_SCALING) @@ -81,8 +135,6 @@ #include "../feature/babystep.h" #endif -#include "printcounter.h" - #if ENABLED(FILAMENT_WIDTH_SENSOR) #include "../feature/filwidth.h" #endif @@ -112,18 +164,19 @@ #endif #if HAS_SERVOS - #include "./servo.h" + #include "servo.h" #endif -#if HOTEND_USES_THERMISTOR - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - static const temp_entry_t* heater_ttbl_map[2] = { HEATER_0_TEMPTABLE, HEATER_1_TEMPTABLE }; - static constexpr uint8_t heater_ttbllen_map[2] = { HEATER_0_TEMPTABLE_LEN, HEATER_1_TEMPTABLE_LEN }; - #else - #define NEXT_TEMPTABLE(N) ,HEATER_##N##_TEMPTABLE - #define NEXT_TEMPTABLE_LEN(N) ,HEATER_##N##_TEMPTABLE_LEN - static const temp_entry_t* heater_ttbl_map[HOTENDS] = ARRAY_BY_HOTENDS(HEATER_0_TEMPTABLE REPEAT_S(1, HOTENDS, NEXT_TEMPTABLE)); - static constexpr uint8_t heater_ttbllen_map[HOTENDS] = ARRAY_BY_HOTENDS(HEATER_0_TEMPTABLE_LEN REPEAT_S(1, HOTENDS, NEXT_TEMPTABLE_LEN)); - #endif + +#if ANY(TEMP_SENSOR_0_IS_THERMISTOR, TEMP_SENSOR_1_IS_THERMISTOR, TEMP_SENSOR_2_IS_THERMISTOR, TEMP_SENSOR_3_IS_THERMISTOR, \ + TEMP_SENSOR_4_IS_THERMISTOR, TEMP_SENSOR_5_IS_THERMISTOR, TEMP_SENSOR_6_IS_THERMISTOR, TEMP_SENSOR_7_IS_THERMISTOR ) + #define HAS_HOTEND_THERMISTOR 1 +#endif + +#if HAS_HOTEND_THERMISTOR + #define NEXT_TEMPTABLE(N) ,TEMPTABLE_##N + #define NEXT_TEMPTABLE_LEN(N) ,TEMPTABLE_##N##_LEN + static const temp_entry_t* heater_ttbl_map[HOTENDS] = ARRAY_BY_HOTENDS(TEMPTABLE_0 REPEAT_S(1, HOTENDS, NEXT_TEMPTABLE)); + static constexpr uint8_t heater_ttbllen_map[HOTENDS] = ARRAY_BY_HOTENDS(TEMPTABLE_0_LEN REPEAT_S(1, HOTENDS, NEXT_TEMPTABLE_LEN)); #endif Temperature thermalManager; @@ -146,18 +199,89 @@ const char str_t_thermal_runaway[] PROGMEM = STR_T_THERMAL_RUNAWAY, #else #define _CHAMBER_PSTR(h) #endif +#if HAS_COOLER + #define _COOLER_PSTR(h) (h) == H_COOLER ? GET_TEXT(MSG_COOLER) : +#else + #define _COOLER_PSTR(h) +#endif #define _E_PSTR(h,N) ((HOTENDS) > N && (h) == N) ? PSTR(LCD_STR_E##N) : -#define HEATER_PSTR(h) _BED_PSTR(h) _CHAMBER_PSTR(h) _E_PSTR(h,1) _E_PSTR(h,2) _E_PSTR(h,3) _E_PSTR(h,4) _E_PSTR(h,5) PSTR(LCD_STR_E0) +#define HEATER_PSTR(h) _BED_PSTR(h) _CHAMBER_PSTR(h) _COOLER_PSTR(h) _E_PSTR(h,1) _E_PSTR(h,2) _E_PSTR(h,3) _E_PSTR(h,4) _E_PSTR(h,5) PSTR(LCD_STR_E0) -// public: +// +// Initialize MAX TC objects/SPI +// +#if HAS_MAX_TC + + #if HAS_MAXTC_SW_SPI + // Initialize SoftSPI for non-lib Software SPI; Libraries take care of it themselves. + template + SoftSPI SPIclass::softSPI; + SPIclass max_tc_spi; + + #endif + + #define MAXTC_INIT(n, M) \ + MAX##M max##M##_##n = MAX##M( \ + TEMP_##n##_CS_PIN \ + OPTARG(_MAX31865_##n##_SW, TEMP_##n##_MOSI_PIN) \ + OPTARG(TEMP_SENSOR_##n##_USES_SW_SPI, TEMP_##n##_MISO_PIN, TEMP_##n##_SCK_PIN) \ + OPTARG(LARGE_PINMAP, HIGH) \ + ) + + #if HAS_MAX6675_LIBRARY + #if TEMP_SENSOR_IS_MAX(0, 6675) + MAXTC_INIT(0, 6675); + #endif + #if TEMP_SENSOR_IS_MAX(1, 6675) + MAXTC_INIT(1, 6675); + #endif + #endif + + #if HAS_MAX31855_LIBRARY + #if TEMP_SENSOR_IS_MAX(0, 31855) + MAXTC_INIT(0, 31855); + #endif + #if TEMP_SENSOR_IS_MAX(1, 31855) + MAXTC_INIT(1, 31855); + #endif + #endif + + // MAX31865 always uses a library, unlike '55 & 6675 + #if HAS_MAX31865 + #define _MAX31865_0_SW TEMP_SENSOR_0_USES_SW_SPI + #define _MAX31865_1_SW TEMP_SENSOR_1_USES_SW_SPI + + #if TEMP_SENSOR_IS_MAX(0, 31865) + MAXTC_INIT(0, 31865); + #endif + #if TEMP_SENSOR_IS_MAX(1, 31865) + MAXTC_INIT(1, 31865); + #endif + + #undef _MAX31865_0_SW + #undef _MAX31865_1_SW + #endif + + #undef MAXTC_INIT + +#endif + +/** + * public: + */ #if ENABLED(NO_FAN_SLOWING_IN_PID_TUNING) bool Temperature::adaptive_fan_slowing = true; #endif #if HAS_HOTEND - hotend_info_t Temperature::temp_hotend[HOTEND_TEMPS]; // = { 0 } - const uint16_t Temperature::heater_maxtemp[HOTENDS] = ARRAY_BY_HOTENDS(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP, HEATER_4_MAXTEMP, HEATER_5_MAXTEMP, HEATER_6_MAXTEMP, HEATER_7_MAXTEMP); + hotend_info_t Temperature::temp_hotend[HOTENDS]; + #define _HMT(N) HEATER_##N##_MAXTEMP, + const celsius_t Temperature::hotend_maxtemp[HOTENDS] = ARRAY_BY_HOTENDS(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP, HEATER_4_MAXTEMP, HEATER_5_MAXTEMP, HEATER_6_MAXTEMP, HEATER_7_MAXTEMP); +#endif + +#if HAS_TEMP_REDUNDANT + redundant_temp_info_t Temperature::temp_redundant; #endif #if ENABLED(AUTO_POWER_E_FANS) @@ -168,24 +292,54 @@ const char str_t_thermal_runaway[] PROGMEM = STR_T_THERMAL_RUNAWAY, uint8_t Temperature::chamberfan_speed; // = 0 #endif +#if ENABLED(AUTO_POWER_COOLER_FAN) + uint8_t Temperature::coolerfan_speed; // = 0 +#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) +#else + #define _INIT_SOFT_FAN(P) OUT_WRITE(P, FAN_INVERTING ? LOW : HIGH) +#endif +#if ENABLED(FAN_SOFT_PWM) + #define _INIT_FAN_PIN(P) _INIT_SOFT_FAN(P) +#else + #define _INIT_FAN_PIN(P) do{ if (PWM_PIN(P)) SET_PWM(P); else _INIT_SOFT_FAN(P); }while(0) +#endif +#if ENABLED(FAST_PWM_FAN) + #define SET_FAST_PWM_FREQ(P) set_pwm_frequency(P, FAST_PWM_FAN_FREQUENCY) +#else + #define SET_FAST_PWM_FREQ(P) NOOP +#endif +#define INIT_FAN_PIN(P) do{ _INIT_FAN_PIN(P); SET_FAST_PWM_FREQ(P); }while(0) + +// HAS_FAN does not include CONTROLLER_FAN #if HAS_FAN uint8_t Temperature::fan_speed[FAN_COUNT]; // = { 0 } #if ENABLED(EXTRA_FAN_SPEED) - uint8_t Temperature::old_fan_speed[FAN_COUNT], Temperature::new_fan_speed[FAN_COUNT]; - void Temperature::set_temp_fan_speed(const uint8_t fan, const uint16_t tmp_temp) { - switch (tmp_temp) { + Temperature::extra_fan_t Temperature::extra_fan_speed[FAN_COUNT]; + + /** + * Handle the M106 P T command: + * T1 = Restore fan speed saved on the last T2 + * T2 = Save the fan speed, then set to the last T<3-255> value + * T<3-255> = Set the "extra fan speed" + */ + void Temperature::set_temp_fan_speed(const uint8_t fan, const uint16_t command_or_speed) { + switch (command_or_speed) { case 1: - set_fan_speed(fan, old_fan_speed[fan]); + set_fan_speed(fan, extra_fan_speed[fan].saved); break; case 2: - old_fan_speed[fan] = fan_speed[fan]; - set_fan_speed(fan, new_fan_speed[fan]); + extra_fan_speed[fan].saved = fan_speed[fan]; + set_fan_speed(fan, extra_fan_speed[fan].speed); break; default: - new_fan_speed[fan] = _MIN(tmp_temp, 255U); + extra_fan_speed[fan].speed = _MIN(command_or_speed, 255U); break; } } @@ -198,40 +352,43 @@ const char str_t_thermal_runaway[] PROGMEM = STR_T_THERMAL_RUNAWAY, #endif #if ENABLED(ADAPTIVE_FAN_SLOWING) - uint8_t Temperature::fan_speed_scaler[FAN_COUNT] = ARRAY_N(FAN_COUNT, 128, 128, 128, 128, 128, 128, 128, 128); + uint8_t Temperature::fan_speed_scaler[FAN_COUNT] = ARRAY_N_1(FAN_COUNT, 128); #endif /** * Set the print fan speed for a target extruder */ - void Temperature::set_fan_speed(uint8_t target, uint16_t speed) { + void Temperature::set_fan_speed(uint8_t fan, uint16_t speed) { NOMORE(speed, 255U); #if ENABLED(SINGLENOZZLE_STANDBY_FAN) - if (target != active_extruder) { - if (target < EXTRUDERS) singlenozzle_fan_speed[target] = speed; + if (fan != active_extruder) { + if (fan < EXTRUDERS) singlenozzle_fan_speed[fan] = speed; return; } #endif - TERN_(SINGLENOZZLE, target = 0); // Always use fan index 0 with SINGLENOZZLE + TERN_(SINGLENOZZLE, if (fan < EXTRUDERS) fan = 0); // Always fan 0 for SINGLENOZZLE E fan - if (target >= FAN_COUNT) return; + if (fan >= FAN_COUNT) return; - fan_speed[target] = speed; + fan_speed[fan] = speed; + #if REDUNDANT_PART_COOLING_FAN + if (fan == 0) fan_speed[REDUNDANT_PART_COOLING_FAN] = speed; + #endif - TERN_(REPORT_FAN_CHANGE, report_fan_speed(target)); + TERN_(REPORT_FAN_CHANGE, report_fan_speed(fan)); } #if ENABLED(REPORT_FAN_CHANGE) /** * Report print fan speed for a target extruder */ - void Temperature::report_fan_speed(const uint8_t target) { - if (target >= FAN_COUNT) return; - PORT_REDIRECT(SERIAL_BOTH); - SERIAL_ECHOLNPAIR("M106 P", target, " S", fan_speed[target]); + void Temperature::report_fan_speed(const uint8_t fan) { + if (fan >= FAN_COUNT) return; + PORT_REDIRECT(SerialMask::All); + SERIAL_ECHOLNPAIR("M106 P", fan, " S", fan_speed[fan]); } #endif @@ -261,62 +418,61 @@ const char str_t_thermal_runaway[] PROGMEM = STR_T_THERMAL_RUNAWAY, #if HAS_HEATED_BED bed_info_t Temperature::temp_bed; // = { 0 } // Init min and max temp with extreme values to prevent false errors during startup - #ifdef BED_MINTEMP - int16_t Temperature::mintemp_raw_BED = HEATER_BED_RAW_LO_TEMP; - #endif - #ifdef BED_MAXTEMP - int16_t Temperature::maxtemp_raw_BED = HEATER_BED_RAW_HI_TEMP; - #endif + int16_t Temperature::mintemp_raw_BED = TEMP_SENSOR_BED_RAW_LO_TEMP, + Temperature::maxtemp_raw_BED = TEMP_SENSOR_BED_RAW_HI_TEMP; TERN_(WATCH_BED, bed_watch_t Temperature::watch_bed); // = { 0 } - TERN(PIDTEMPBED,, millis_t Temperature::next_bed_check_ms); -#endif // HAS_HEATED_BED + IF_DISABLED(PIDTEMPBED, millis_t Temperature::next_bed_check_ms); +#endif #if HAS_TEMP_CHAMBER chamber_info_t Temperature::temp_chamber; // = { 0 } #if HAS_HEATED_CHAMBER - int16_t fan_chamber_pwm; - bool flag_chamber_off; - bool flag_chamber_excess_heat = false; millis_t next_cool_check_ms_2 = 0; - float old_temp = 9999; - #ifdef CHAMBER_MINTEMP - int16_t Temperature::mintemp_raw_CHAMBER = HEATER_CHAMBER_RAW_LO_TEMP; - #endif - #ifdef CHAMBER_MAXTEMP - int16_t Temperature::maxtemp_raw_CHAMBER = HEATER_CHAMBER_RAW_HI_TEMP; - #endif - #if WATCH_CHAMBER - chamber_watch_t Temperature::watch_chamber{0}; + celsius_float_t old_temp = 9999; + int16_t Temperature::mintemp_raw_CHAMBER = TEMP_SENSOR_CHAMBER_RAW_LO_TEMP, + Temperature::maxtemp_raw_CHAMBER = TEMP_SENSOR_CHAMBER_RAW_HI_TEMP; + TERN_(WATCH_CHAMBER, chamber_watch_t Temperature::watch_chamber{0}); + IF_DISABLED(PIDTEMPCHAMBER, millis_t Temperature::next_chamber_check_ms); + #endif +#endif + +#if HAS_TEMP_COOLER + cooler_info_t Temperature::temp_cooler; // = { 0 } + #if HAS_COOLER + bool flag_cooler_state; + //bool flag_cooler_excess = false; + celsius_float_t previous_temp = 9999; + int16_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}; #endif - millis_t Temperature::next_chamber_check_ms; - #endif // HAS_HEATED_CHAMBER -#endif // HAS_TEMP_CHAMBER + millis_t Temperature::next_cooler_check_ms, Temperature::cooler_fan_flush_ms; + #endif +#endif #if HAS_TEMP_PROBE probe_info_t Temperature::temp_probe; // = { 0 } #endif -// Initialized by settings.load() -#if ENABLED(PIDTEMP) - //hotend_pid_t Temperature::pid[HOTENDS]; -#endif - #if ENABLED(PREVENT_COLD_EXTRUSION) bool Temperature::allow_cold_extrude = false; - int16_t Temperature::extrude_min_temp = EXTRUDE_MINTEMP; + celsius_t Temperature::extrude_min_temp = EXTRUDE_MINTEMP; #endif -// private: - -#if EARLY_WATCHDOG - bool Temperature::inited = false; +#if HAS_ADC_BUTTONS + uint32_t Temperature::current_ADCKey_raw = HAL_ADC_RANGE; + uint16_t Temperature::ADCKey_count = 0; #endif -#if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - uint16_t Temperature::redundant_temperature_raw = 0; - float Temperature::redundant_temperature = 0.0; +#if ENABLED(PID_EXTRUSION_SCALING) + int16_t Temperature::lpq_len; // Initialized in settings.cpp #endif +/** + * private: + */ + volatile bool Temperature::raw_temps_ready = false; #if ENABLED(PID_EXTRUSION_SCALING) @@ -324,27 +480,27 @@ volatile bool Temperature::raw_temps_ready = false; lpq_ptr_t Temperature::lpq_ptr = 0; #endif -#define TEMPDIR(N) ((HEATER_##N##_RAW_LO_TEMP) < (HEATER_##N##_RAW_HI_TEMP) ? 1 : -1) +#define TEMPDIR(N) ((TEMP_SENSOR_##N##_RAW_LO_TEMP) < (TEMP_SENSOR_##N##_RAW_HI_TEMP) ? 1 : -1) #if HAS_HOTEND // Init mintemp and maxtemp with extreme values to prevent false errors during startup - constexpr temp_range_t sensor_heater_0 { HEATER_0_RAW_LO_TEMP, HEATER_0_RAW_HI_TEMP, 0, 16383 }, - sensor_heater_1 { HEATER_1_RAW_LO_TEMP, HEATER_1_RAW_HI_TEMP, 0, 16383 }, - sensor_heater_2 { HEATER_2_RAW_LO_TEMP, HEATER_2_RAW_HI_TEMP, 0, 16383 }, - sensor_heater_3 { HEATER_3_RAW_LO_TEMP, HEATER_3_RAW_HI_TEMP, 0, 16383 }, - sensor_heater_4 { HEATER_4_RAW_LO_TEMP, HEATER_4_RAW_HI_TEMP, 0, 16383 }, - sensor_heater_5 { HEATER_5_RAW_LO_TEMP, HEATER_5_RAW_HI_TEMP, 0, 16383 }, - sensor_heater_6 { HEATER_6_RAW_LO_TEMP, HEATER_6_RAW_HI_TEMP, 0, 16383 }, - sensor_heater_7 { HEATER_7_RAW_LO_TEMP, HEATER_7_RAW_HI_TEMP, 0, 16383 }; + constexpr temp_range_t sensor_heater_0 { TEMP_SENSOR_0_RAW_LO_TEMP, TEMP_SENSOR_0_RAW_HI_TEMP, 0, 16383 }, + sensor_heater_1 { TEMP_SENSOR_1_RAW_LO_TEMP, TEMP_SENSOR_1_RAW_HI_TEMP, 0, 16383 }, + sensor_heater_2 { TEMP_SENSOR_2_RAW_LO_TEMP, TEMP_SENSOR_2_RAW_HI_TEMP, 0, 16383 }, + sensor_heater_3 { TEMP_SENSOR_3_RAW_LO_TEMP, TEMP_SENSOR_3_RAW_HI_TEMP, 0, 16383 }, + sensor_heater_4 { TEMP_SENSOR_4_RAW_LO_TEMP, TEMP_SENSOR_4_RAW_HI_TEMP, 0, 16383 }, + sensor_heater_5 { TEMP_SENSOR_5_RAW_LO_TEMP, TEMP_SENSOR_5_RAW_HI_TEMP, 0, 16383 }, + sensor_heater_6 { TEMP_SENSOR_6_RAW_LO_TEMP, TEMP_SENSOR_6_RAW_HI_TEMP, 0, 16383 }, + sensor_heater_7 { TEMP_SENSOR_7_RAW_LO_TEMP, TEMP_SENSOR_7_RAW_HI_TEMP, 0, 16383 }; temp_range_t Temperature::temp_range[HOTENDS] = ARRAY_BY_HOTENDS(sensor_heater_0, sensor_heater_1, sensor_heater_2, sensor_heater_3, sensor_heater_4, sensor_heater_5, sensor_heater_6, sensor_heater_7); #endif -#ifdef MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED +#if MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED > 1 uint8_t Temperature::consecutive_low_temperature_error[HOTENDS] = { 0 }; #endif -#ifdef MILLISECONDS_PREHEAT_TIME +#if MILLISECONDS_PREHEAT_TIME > 0 millis_t Temperature::preheat_end_time[HOTENDS] = { 0 }; #endif @@ -357,21 +513,22 @@ volatile bool Temperature::raw_temps_ready = false; Temperature::soft_pwm_count_fan[FAN_COUNT]; #endif -#if ENABLED(PROBING_HEATERS_OFF) - bool Temperature::paused; +#if ENABLED(SINGLENOZZLE_STANDBY_TEMP) + celsius_t Temperature::singlenozzle_temp[EXTRUDERS]; #endif - -// public: - -#if HAS_ADC_BUTTONS - uint32_t Temperature::current_ADCKey_raw = HAL_ADC_RANGE; - uint16_t Temperature::ADCKey_count = 0; +#if ENABLED(SINGLENOZZLE_STANDBY_FAN) + uint8_t Temperature::singlenozzle_fan_speed[EXTRUDERS]; #endif -#if ENABLED(PID_EXTRUSION_SCALING) - int16_t Temperature::lpq_len; // Initialized in settings.cpp +#if ENABLED(PROBING_HEATERS_OFF) + bool Temperature::paused_for_probing; #endif +/** + * public: + * Class and Instance Methods + */ + #if HAS_PID_HEATING inline void say_default_() { SERIAL_ECHOPGM("#define DEFAULT_"); } @@ -384,57 +541,62 @@ volatile bool Temperature::raw_temps_ready = false; * Needs sufficient heater power to make some overshoot at target * temperature to succeed. */ - void Temperature::PID_autotune(const float &target, const heater_id_t heater_id, const int8_t ncycles, const bool set_result/*=false*/) { - float current_temp = 0.0; + void Temperature::PID_autotune(const celsius_t target, const heater_id_t heater_id, const int8_t ncycles, const bool set_result/*=false*/) { + celsius_float_t current_temp = 0.0; int cycles = 0; bool heating = true; millis_t next_temp_ms = millis(), t1 = next_temp_ms, t2 = next_temp_ms; long t_high = 0, t_low = 0; - long bias, d; PID_t tune_pid = { 0, 0, 0 }; - float maxT = 0, minT = 10000; + celsius_float_t maxT = 0, minT = 10000; const bool isbed = (heater_id == H_BED); + const bool ischamber = (heater_id == H_CHAMBER); - #if HAS_PID_FOR_BOTH - #define GHV(B,H) (isbed ? (B) : (H)) - #define SHV(B,H) do{ if (isbed) temp_bed.soft_pwm_amount = B; else temp_hotend[heater_id].soft_pwm_amount = H; }while(0) - #define ONHEATINGSTART() (isbed ? printerEventLEDs.onBedHeatingStart() : printerEventLEDs.onHotendHeatingStart()) - #define ONHEATING(S,C,T) (isbed ? printerEventLEDs.onBedHeating(S,C,T) : printerEventLEDs.onHotendHeating(S,C,T)) - #elif ENABLED(PIDTEMPBED) - #define GHV(B,H) B - #define SHV(B,H) (temp_bed.soft_pwm_amount = B) - #define ONHEATINGSTART() printerEventLEDs.onBedHeatingStart() - #define ONHEATING(S,C,T) printerEventLEDs.onBedHeating(S,C,T) + #if ENABLED(PIDTEMPCHAMBER) + #define C_TERN(T,A,B) ((T) ? (A) : (B)) #else - #define GHV(B,H) H - #define SHV(B,H) (temp_hotend[heater_id].soft_pwm_amount = H) - #define ONHEATINGSTART() printerEventLEDs.onHotendHeatingStart() - #define ONHEATING(S,C,T) printerEventLEDs.onHotendHeating(S,C,T) + #define C_TERN(T,A,B) (B) #endif - #define WATCH_PID BOTH(WATCH_BED, PIDTEMPBED) || BOTH(WATCH_HOTENDS, PIDTEMP) + #if ENABLED(PIDTEMPBED) + #define B_TERN(T,A,B) ((T) ? (A) : (B)) + #else + #define B_TERN(T,A,B) (B) + #endif + #define GHV(C,B,H) C_TERN(ischamber, C, B_TERN(isbed, B, H)) + #define SHV(V) C_TERN(ischamber, temp_chamber.soft_pwm_amount = V, B_TERN(isbed, temp_bed.soft_pwm_amount = V, temp_hotend[heater_id].soft_pwm_amount = V)) + #define ONHEATINGSTART() C_TERN(ischamber, printerEventLEDs.onChamberHeatingStart(), B_TERN(isbed, printerEventLEDs.onBedHeatingStart(), printerEventLEDs.onHotendHeatingStart())) + #define ONHEATING(S,C,T) C_TERN(ischamber, printerEventLEDs.onChamberHeating(S,C,T), B_TERN(isbed, printerEventLEDs.onBedHeating(S,C,T), printerEventLEDs.onHotendHeating(S,C,T))) + + #define WATCH_PID BOTH(WATCH_CHAMBER, PIDTEMPCHAMBER) || BOTH(WATCH_BED, PIDTEMPBED) || BOTH(WATCH_HOTENDS, PIDTEMP) #if WATCH_PID - #if ALL(THERMAL_PROTECTION_HOTENDS, PIDTEMP, THERMAL_PROTECTION_BED, PIDTEMPBED) - #define GTV(B,H) (isbed ? (B) : (H)) - #elif BOTH(THERMAL_PROTECTION_HOTENDS, PIDTEMP) - #define GTV(B,H) (H) + #if BOTH(THERMAL_PROTECTION_CHAMBER, PIDTEMPCHAMBER) + #define C_GTV(T,A,B) ((T) ? (A) : (B)) #else - #define GTV(B,H) (B) + #define C_GTV(T,A,B) (B) #endif - const uint16_t watch_temp_period = GTV(WATCH_BED_TEMP_PERIOD, WATCH_TEMP_PERIOD); - const uint8_t watch_temp_increase = GTV(WATCH_BED_TEMP_INCREASE, WATCH_TEMP_INCREASE); - const float watch_temp_target = target - float(watch_temp_increase + GTV(TEMP_BED_HYSTERESIS, TEMP_HYSTERESIS) + 1); + #if BOTH(THERMAL_PROTECTION_BED, PIDTEMPBED) + #define B_GTV(T,A,B) ((T) ? (A) : (B)) + #else + #define B_GTV(T,A,B) (B) + #endif + #define GTV(C,B,H) C_GTV(ischamber, C, B_GTV(isbed, B, H)) + const uint16_t watch_temp_period = GTV(WATCH_CHAMBER_TEMP_PERIOD, WATCH_BED_TEMP_PERIOD, WATCH_TEMP_PERIOD); + const uint8_t watch_temp_increase = GTV(WATCH_CHAMBER_TEMP_INCREASE, WATCH_BED_TEMP_INCREASE, WATCH_TEMP_INCREASE); + const celsius_float_t watch_temp_target = celsius_float_t(target - (watch_temp_increase + GTV(TEMP_CHAMBER_HYSTERESIS, TEMP_BED_HYSTERESIS, TEMP_HYSTERESIS) + 1)); millis_t temp_change_ms = next_temp_ms + SEC_TO_MS(watch_temp_period); - float next_watch_temp = 0.0; + celsius_float_t next_watch_temp = 0.0; bool heated = false; #endif TERN_(HAS_AUTO_FAN, next_auto_fan_check_ms = next_temp_ms + 2500UL); - if (target > GHV(BED_MAX_TARGET, temp_range[heater_id].maxtemp - HOTEND_OVERSHOOT)) { + TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_STARTED)); + + if (target > GHV(CHAMBER_MAX_TARGET, BED_MAX_TARGET, temp_range[heater_id].maxtemp - (HOTEND_OVERSHOOT))) { SERIAL_ECHOLNPGM(STR_PID_TEMP_TOO_HIGH); TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_TEMP_TOO_HIGH)); return; @@ -445,10 +607,11 @@ volatile bool Temperature::raw_temps_ready = false; disable_all_heaters(); TERN_(AUTO_POWER_CONTROL, powerManager.power_on()); - SHV(bias = d = (MAX_BED_POWER) >> 1, bias = d = (PID_MAX) >> 1); + long bias = GHV(MAX_CHAMBER_POWER, MAX_BED_POWER, PID_MAX) >> 1, d = bias; + SHV(bias); #if ENABLED(PRINTER_EVENT_LEDS) - const float start_temp = GHV(temp_bed.celsius, temp_hotend[heater_id].celsius); + const celsius_float_t start_temp = GHV(degChamber(), degBed(), degHotend(heater_id)); LEDColor color = ONHEATINGSTART(); #endif @@ -460,11 +623,10 @@ volatile bool Temperature::raw_temps_ready = false; const millis_t ms = millis(); - if (raw_temps_ready) { // temp sample ready - updateTemperaturesFromRawValues(); + if (updateTemperaturesIfReady()) { // temp sample ready // Get the current temperature and constrain it - current_temp = GHV(temp_bed.celsius, temp_hotend[heater_id].celsius); + current_temp = GHV(degChamber(), degBed(), degHotend(heater_id)); NOLESS(maxT, current_temp); NOMORE(minT, current_temp); @@ -479,67 +641,46 @@ volatile bool Temperature::raw_temps_ready = false; } #endif - if (heating && current_temp > target) { - if (ELAPSED(ms, t2 + 5000UL)) { - heating = false; - SHV((bias - d) >> 1, (bias - d) >> 1); - t1 = ms; - t_high = t1 - t2; - maxT = target; - } + if (heating && current_temp > target && ELAPSED(ms, t2 + 5000UL)) { + heating = false; + SHV((bias - d) >> 1); + t1 = ms; + t_high = t1 - t2; + maxT = target; } - if (!heating && current_temp < target) { - if (ELAPSED(ms, t1 + 5000UL)) { - heating = true; - t2 = ms; - t_low = t2 - t1; - if (cycles > 0) { - const long max_pow = GHV(MAX_BED_POWER, PID_MAX); - bias += (d * (t_high - t_low)) / (t_low + t_high); - LIMIT(bias, 20, max_pow - 20); - d = (bias > max_pow >> 1) ? max_pow - 1 - bias : bias; - - SERIAL_ECHOPAIR(STR_BIAS, bias, STR_D_COLON, d, STR_T_MIN, minT, STR_T_MAX, maxT); - if (cycles > 2) { - const float Ku = (4.0f * d) / (float(M_PI) * (maxT - minT) * 0.5f), - Tu = float(t_low + t_high) * 0.001f, - pf = isbed ? 0.2f : 0.6f, - df = isbed ? 1.0f / 3.0f : 1.0f / 8.0f; - - SERIAL_ECHOPAIR(STR_KU, Ku, STR_TU, Tu); - if (isbed) { // Do not remove this otherwise PID autotune won't work right for the bed! - tune_pid.Kp = Ku * 0.2f; - tune_pid.Ki = 2 * tune_pid.Kp / Tu; - tune_pid.Kd = tune_pid.Kp * Tu / 3; - SERIAL_ECHOLNPGM("\n" " No overshoot"); // Works far better for the bed. Classic and some have bad ringing. - SERIAL_ECHOLNPAIR(STR_KP, tune_pid.Kp, STR_KI, tune_pid.Ki, STR_KD, tune_pid.Kd); - } - else { - tune_pid.Kp = Ku * pf; - tune_pid.Kd = tune_pid.Kp * Tu * df; - tune_pid.Ki = 2 * tune_pid.Kp / Tu; - SERIAL_ECHOLNPGM("\n" STR_CLASSIC_PID); - SERIAL_ECHOLNPAIR(STR_KP, tune_pid.Kp, STR_KI, tune_pid.Ki, STR_KD, tune_pid.Kd); - } - - /** - tune_pid.Kp = 0.33 * Ku; - tune_pid.Ki = tune_pid.Kp / Tu; - tune_pid.Kd = tune_pid.Kp * Tu / 3; - SERIAL_ECHOLNPGM(" Some overshoot"); - SERIAL_ECHOLNPAIR(" Kp: ", tune_pid.Kp, " Ki: ", tune_pid.Ki, " Kd: ", tune_pid.Kd, " No overshoot"); - tune_pid.Kp = 0.2 * Ku; - tune_pid.Ki = 2 * tune_pid.Kp / Tu; - tune_pid.Kd = tune_pid.Kp * Tu / 3; - SERIAL_ECHOPAIR(" Kp: ", tune_pid.Kp, " Ki: ", tune_pid.Ki, " Kd: ", tune_pid.Kd); - */ - } + if (!heating && current_temp < target && ELAPSED(ms, t1 + 5000UL)) { + heating = true; + t2 = ms; + t_low = t2 - t1; + if (cycles > 0) { + const long max_pow = GHV(MAX_CHAMBER_POWER, MAX_BED_POWER, PID_MAX); + bias += (d * (t_high - t_low)) / (t_low + t_high); + LIMIT(bias, 20, max_pow - 20); + d = (bias > max_pow >> 1) ? max_pow - 1 - bias : bias; + + SERIAL_ECHOPAIR(STR_BIAS, bias, STR_D_COLON, d, STR_T_MIN, minT, STR_T_MAX, maxT); + if (cycles > 2) { + const float Ku = (4.0f * d) / (float(M_PI) * (maxT - minT) * 0.5f), + Tu = float(t_low + t_high) * 0.001f, + pf = ischamber ? 0.2f : (isbed ? 0.2f : 0.6f), + df = ischamber ? 1.0f / 3.0f : (isbed ? 1.0f / 3.0f : 1.0f / 8.0f); + + tune_pid.Kp = Ku * pf; + tune_pid.Ki = tune_pid.Kp * 2.0f / Tu; + tune_pid.Kd = tune_pid.Kp * Tu * df; + + SERIAL_ECHOLNPAIR(STR_KU, Ku, STR_TU, Tu); + if (ischamber || isbed) + SERIAL_ECHOLNPGM(" No overshoot"); + else + SERIAL_ECHOLNPGM(STR_CLASSIC_PID); + SERIAL_ECHOLNPAIR(STR_KP, tune_pid.Kp, STR_KI, tune_pid.Ki, STR_KD, tune_pid.Kd); } - SHV((bias + d) >> 1, (bias + d) >> 1); - cycles++; - minT = target; } + SHV((bias + d) >> 1); + cycles++; + minT = target; } } @@ -556,14 +697,14 @@ volatile bool Temperature::raw_temps_ready = false; // Report heater states every 2 seconds if (ELAPSED(ms, next_temp_ms)) { #if HAS_TEMP_SENSOR - print_heater_states(isbed ? active_extruder : heater_id); + print_heater_states(ischamber ? active_extruder : (isbed ? active_extruder : heater_id)); SERIAL_EOL(); #endif next_temp_ms = ms + 2000UL; // Make sure heating is actually working #if WATCH_PID - if (BOTH(WATCH_BED, WATCH_HOTENDS) || isbed == DISABLED(WATCH_HOTENDS)) { + if (BOTH(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 @@ -593,43 +734,47 @@ volatile bool Temperature::raw_temps_ready = false; if (cycles > ncycles && cycles > 2) { SERIAL_ECHOLNPGM(STR_PID_AUTOTUNE_FINISHED); - #if HAS_PID_FOR_BOTH - const char * const estring = GHV(PSTR("bed"), NUL_STR); - say_default_(); serialprintPGM(estring); SERIAL_ECHOLNPAIR("Kp ", tune_pid.Kp); - say_default_(); serialprintPGM(estring); SERIAL_ECHOLNPAIR("Ki ", tune_pid.Ki); - say_default_(); serialprintPGM(estring); SERIAL_ECHOLNPAIR("Kd ", tune_pid.Kd); - #elif ENABLED(PIDTEMP) + #if EITHER(PIDTEMPBED, PIDTEMPCHAMBER) + PGM_P const estring = GHV(PSTR("chamber"), PSTR("bed"), NUL_STR); + say_default_(); SERIAL_ECHOPGM_P(estring); SERIAL_ECHOLNPAIR("Kp ", tune_pid.Kp); + say_default_(); SERIAL_ECHOPGM_P(estring); SERIAL_ECHOLNPAIR("Ki ", tune_pid.Ki); + say_default_(); SERIAL_ECHOPGM_P(estring); SERIAL_ECHOLNPAIR("Kd ", tune_pid.Kd); + #else say_default_(); SERIAL_ECHOLNPAIR("Kp ", tune_pid.Kp); say_default_(); SERIAL_ECHOLNPAIR("Ki ", tune_pid.Ki); say_default_(); SERIAL_ECHOLNPAIR("Kd ", tune_pid.Kd); - #else - say_default_(); SERIAL_ECHOLNPAIR("bedKp ", tune_pid.Kp); - say_default_(); SERIAL_ECHOLNPAIR("bedKi ", tune_pid.Ki); - say_default_(); SERIAL_ECHOLNPAIR("bedKd ", tune_pid.Kd); #endif - #define _SET_BED_PID() do { \ - temp_bed.pid.Kp = tune_pid.Kp; \ - temp_bed.pid.Ki = scalePID_i(tune_pid.Ki); \ - temp_bed.pid.Kd = scalePID_d(tune_pid.Kd); \ - }while(0) + auto _set_hotend_pid = [](const uint8_t e, const PID_t &in_pid) { + #if ENABLED(PIDTEMP) + PID_PARAM(Kp, e) = in_pid.Kp; + PID_PARAM(Ki, e) = scalePID_i(in_pid.Ki); + PID_PARAM(Kd, e) = scalePID_d(in_pid.Kd); + updatePID(); + #else + UNUSED(e); UNUSED(in_pid); + #endif + }; - #define _SET_EXTRUDER_PID() do { \ - PID_PARAM(Kp, heater_id) = tune_pid.Kp; \ - PID_PARAM(Ki, heater_id) = scalePID_i(tune_pid.Ki); \ - PID_PARAM(Kd, heater_id) = scalePID_d(tune_pid.Kd); \ - updatePID(); }while(0) + #if ENABLED(PIDTEMPBED) + auto _set_bed_pid = [](const PID_t &in_pid) { + temp_bed.pid.Kp = in_pid.Kp; + temp_bed.pid.Ki = scalePID_i(in_pid.Ki); + temp_bed.pid.Kd = scalePID_d(in_pid.Kd); + }; + #endif + + #if ENABLED(PIDTEMPCHAMBER) + auto _set_chamber_pid = [](const PID_t &in_pid) { + temp_chamber.pid.Kp = in_pid.Kp; + temp_chamber.pid.Ki = scalePID_i(in_pid.Ki); + temp_chamber.pid.Kd = scalePID_d(in_pid.Kd); + }; + #endif // Use the result? (As with "M303 U1") - if (set_result) { - #if HAS_PID_FOR_BOTH - if (isbed) _SET_BED_PID(); else _SET_EXTRUDER_PID(); - #elif ENABLED(PIDTEMP) - _SET_EXTRUDER_PID(); - #else - _SET_BED_PID(); - #endif - } + if (set_result) + GHV(_set_chamber_pid(tune_pid), _set_bed_pid(tune_pid), _set_hotend_pid(heater_id, tune_pid)); TERN_(PRINTER_EVENT_LEDS, printerEventLEDs.onPidTuningDone(color)); @@ -659,10 +804,6 @@ volatile bool Temperature::raw_temps_ready = false; #endif // HAS_PID_HEATING -/** - * Class and Instance Methods - */ - int16_t Temperature::getHeaterPower(const heater_id_t heater_id) { switch (heater_id) { #if HAS_HEATED_BED @@ -671,6 +812,9 @@ int16_t Temperature::getHeaterPower(const heater_id_t heater_id) { #if HAS_HEATED_CHAMBER case H_CHAMBER: return temp_chamber.soft_pwm_amount; #endif + #if HAS_COOLER + case H_COOLER: return temp_cooler.soft_pwm_amount; + #endif default: return TERN0(HAS_HOTEND, temp_hotend[heater_id].soft_pwm_amount); } @@ -679,6 +823,16 @@ int16_t Temperature::getHeaterPower(const heater_id_t heater_id) { #define _EFANOVERLAP(A,B) _FANOVERLAP(E##A,B) #if HAS_AUTO_FAN + #if EXTRUDER_AUTO_FAN_SPEED != 255 + #define INIT_E_AUTO_FAN_PIN(P) do{ if (P == FAN1_PIN || P == FAN2_PIN) { SET_PWM(P); SET_FAST_PWM_FREQ(P); } else SET_OUTPUT(P); }while(0) + #else + #define INIT_E_AUTO_FAN_PIN(P) SET_OUTPUT(P) + #endif + #if CHAMBER_AUTO_FAN_SPEED != 255 + #define INIT_CHAMBER_AUTO_FAN_PIN(P) do{ if (P == FAN1_PIN || P == FAN2_PIN) { SET_PWM(P); SET_FAST_PWM_FREQ(P); } else SET_OUTPUT(P); }while(0) + #else + #define INIT_CHAMBER_AUTO_FAN_PIN(P) SET_OUTPUT(P) + #endif #define CHAMBER_FAN_INDEX HOTENDS @@ -706,6 +860,11 @@ int16_t Temperature::getHeaterPower(const heater_id_t heater_id) { SBI(fanState, pgm_read_byte(&fanBit[CHAMBER_FAN_INDEX])); #endif + #if HAS_AUTO_COOLER_FAN + if (temp_cooler.celsius >= COOLER_AUTO_FAN_TEMPERATURE) + SBI(fanState, pgm_read_byte(&fanBit[COOLER_FAN_INDEX])); + #endif + #define _UPDATE_AUTO_FAN(P,D,A) do{ \ if (PWM_PIN(P##_AUTO_FAN_PIN) && A < 255) \ analogWrite(pin_t(P##_AUTO_FAN_PIN), D ? A : 0); \ @@ -773,9 +932,16 @@ int16_t Temperature::getHeaterPower(const heater_id_t heater_id) { inline void loud_kill(PGM_P const lcd_msg, const heater_id_t heater_id) { marlin_state = MF_KILLED; #if USE_BEEPER + thermalManager.disable_all_heaters(); for (uint8_t i = 20; i--;) { - WRITE(BEEPER_PIN, HIGH); delay(25); - WRITE(BEEPER_PIN, LOW); delay(80); + WRITE(BEEPER_PIN, HIGH); + delay(25); + watchdog_refresh(); + WRITE(BEEPER_PIN, LOW); + delay(40); + watchdog_refresh(); + delay(40); + watchdog_refresh(); } WRITE(BEEPER_PIN, HIGH); #endif @@ -788,18 +954,21 @@ void Temperature::_temp_error(const heater_id_t heater_id, PGM_P const serial_ms if (IsRunning() && TERN1(BOGUS_TEMPERATURE_GRACE_PERIOD, killed == 2)) { SERIAL_ERROR_START(); - serialprintPGM(serial_msg); + SERIAL_ECHOPGM_P(serial_msg); SERIAL_ECHOPGM(STR_STOPPED_HEATER); if (heater_id >= 0) - SERIAL_ECHO((int)heater_id); + SERIAL_ECHO(heater_id); else if (TERN0(HAS_HEATED_CHAMBER, heater_id == H_CHAMBER)) SERIAL_ECHOPGM(STR_HEATER_CHAMBER); + else if (TERN0(HAS_COOLER, heater_id == H_COOLER)) + SERIAL_ECHOPGM(STR_COOLER); else SERIAL_ECHOPGM(STR_HEATER_BED); SERIAL_EOL(); } disable_all_heaters(); // always disable (even for bogus temp) + watchdog_refresh(); #if BOGUS_TEMPERATURE_GRACE_PERIOD const millis_t ms = millis(); @@ -838,10 +1007,11 @@ void Temperature::min_temp_error(const heater_id_t heater_id) { _temp_error(heater_id, PSTR(STR_T_MINTEMP), GET_TEXT(MSG_ERR_MINTEMP)); } +#if ANY(PID_DEBUG, PID_BED_DEBUG, PID_CHAMBER_DEBUG) + bool Temperature::pid_debug_flag; // = 0 +#endif + #if HAS_HOTEND - #if ENABLED(PID_DEBUG) - extern bool pid_debug_flag; - #endif float Temperature::get_pid_output_hotend(const uint8_t E_NAME) { const uint8_t ee = HOTEND_INDEX; @@ -903,8 +1073,8 @@ void Temperature::min_temp_error(const heater_id_t heater_id) { } #endif // PID_EXTRUSION_SCALING #if ENABLED(PID_FAN_SCALING) - if (thermalManager.fan_speed[active_extruder] > PID_FAN_SCALING_MIN_SPEED) { - work_pid[ee].Kf = PID_PARAM(Kf, ee) + (PID_FAN_SCALING_LIN_FACTOR) * thermalManager.fan_speed[active_extruder]; + if (fan_speed[active_extruder] > PID_FAN_SCALING_MIN_SPEED) { + work_pid[ee].Kf = PID_PARAM(Kf, ee) + (PID_FAN_SCALING_LIN_FACTOR) * fan_speed[active_extruder]; pid_output += work_pid[ee].Kf; } //pid_output -= work_pid[ee].Ki; @@ -922,23 +1092,18 @@ void Temperature::min_temp_error(const heater_id_t heater_id) { #if ENABLED(PID_DEBUG) if (ee == active_extruder && pid_debug_flag) { - SERIAL_ECHO_START(); - SERIAL_ECHOPAIR(STR_PID_DEBUG, ee, STR_PID_DEBUG_INPUT, temp_hotend[ee].celsius, STR_PID_DEBUG_OUTPUT, pid_output); - #if DISABLED(PID_OPENLOOP) - { - SERIAL_ECHOPAIR( - STR_PID_DEBUG_PTERM, work_pid[ee].Kp, - STR_PID_DEBUG_ITERM, work_pid[ee].Ki, - STR_PID_DEBUG_DTERM, work_pid[ee].Kd + SERIAL_ECHO_MSG(STR_PID_DEBUG, ee, STR_PID_DEBUG_INPUT, temp_hotend[ee].celsius, STR_PID_DEBUG_OUTPUT, pid_output + #if DISABLED(PID_OPENLOOP) + , STR_PID_DEBUG_PTERM, work_pid[ee].Kp + , STR_PID_DEBUG_ITERM, work_pid[ee].Ki + , STR_PID_DEBUG_DTERM, work_pid[ee].Kd #if ENABLED(PID_EXTRUSION_SCALING) , STR_PID_DEBUG_CTERM, work_pid[ee].Kc #endif - ); - } - #endif - SERIAL_EOL(); + #endif + ); } - #endif // PID_DEBUG + #endif #else // No PID enabled @@ -998,14 +1163,76 @@ void Temperature::min_temp_error(const heater_id_t heater_id) { #endif // PID_OPENLOOP #if ENABLED(PID_BED_DEBUG) + if (pid_debug_flag) { + SERIAL_ECHO_MSG( + " PID_BED_DEBUG : Input ", temp_bed.celsius, " Output ", pid_output + #if DISABLED(PID_OPENLOOP) + , STR_PID_DEBUG_PTERM, work_pid.Kp + , STR_PID_DEBUG_ITERM, work_pid.Ki + , STR_PID_DEBUG_DTERM, work_pid.Kd + #endif + ); + } + #endif + + return pid_output; + } + +#endif // PIDTEMPBED + +#if ENABLED(PIDTEMPCHAMBER) + + float Temperature::get_pid_output_chamber() { + + #if DISABLED(PID_OPENLOOP) + + static PID_t work_pid{0}; + static float temp_iState = 0, temp_dState = 0; + static bool pid_reset = true; + float pid_output = 0; + const float max_power_over_i_gain = float(MAX_CHAMBER_POWER) / temp_chamber.pid.Ki - float(MIN_CHAMBER_POWER), + pid_error = temp_chamber.target - temp_chamber.celsius; + + if (!temp_chamber.target || pid_error < -(PID_FUNCTIONAL_RANGE)) { + pid_output = 0; + pid_reset = true; + } + else if (pid_error > PID_FUNCTIONAL_RANGE) { + pid_output = MAX_CHAMBER_POWER; + pid_reset = true; + } + else { + if (pid_reset) { + temp_iState = 0.0; + work_pid.Kd = 0.0; + pid_reset = false; + } + + temp_iState = constrain(temp_iState + pid_error, 0, max_power_over_i_gain); + + work_pid.Kp = temp_chamber.pid.Kp * pid_error; + work_pid.Ki = temp_chamber.pid.Ki * temp_iState; + work_pid.Kd = work_pid.Kd + PID_K2 * (temp_chamber.pid.Kd * (temp_dState - temp_chamber.celsius) - work_pid.Kd); + + temp_dState = temp_chamber.celsius; + + pid_output = constrain(work_pid.Kp + work_pid.Ki + work_pid.Kd + float(MIN_CHAMBER_POWER), 0, MAX_CHAMBER_POWER); + } + + #else // PID_OPENLOOP + + const float pid_output = constrain(temp_chamber.target, 0, MAX_CHAMBER_POWER); + + #endif // PID_OPENLOOP + + #if ENABLED(PID_CHAMBER_DEBUG) { - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR( - " PID_BED_DEBUG : Input ", temp_bed.celsius, " Output ", pid_output, + SERIAL_ECHO_MSG( + " PID_CHAMBER_DEBUG : Input ", temp_chamber.celsius, " Output ", pid_output #if DISABLED(PID_OPENLOOP) - STR_PID_DEBUG_PTERM, work_pid.Kp, - STR_PID_DEBUG_ITERM, work_pid.Ki, - STR_PID_DEBUG_DTERM, work_pid.Kd, + , STR_PID_DEBUG_PTERM, work_pid.Kp + , STR_PID_DEBUG_ITERM, work_pid.Ki + , STR_PID_DEBUG_DTERM, work_pid.Kd #endif ); } @@ -1014,7 +1241,7 @@ void Temperature::min_temp_error(const heater_id_t heater_id) { return pid_output; } -#endif // PIDTEMPBED +#endif // PIDTEMPCHAMBER /** * Manage heating activities for extruder hot-ends and a heated bed @@ -1026,27 +1253,35 @@ void Temperature::min_temp_error(const heater_id_t heater_id) { * - Update the heated bed PID output value */ void Temperature::manage_heater() { + if (marlin_state == MF_INITIALIZING) return watchdog_refresh(); // If Marlin isn't started, at least reset the watchdog! - #if EARLY_WATCHDOG - // If thermal manager is still not running, make sure to at least reset the watchdog! - if (!inited) return watchdog_refresh(); - #endif + static bool no_reentry = false; // Prevent recursion + if (no_reentry) return; + REMEMBER(mh, no_reentry, true); - if (TERN0(EMERGENCY_PARSER, emergency_parser.killed_by_M112)) - kill(M112_KILL_STR, nullptr, true); + #if ENABLED(EMERGENCY_PARSER) + if (emergency_parser.killed_by_M112) kill(M112_KILL_STR, nullptr, true); - if (!raw_temps_ready) return; + if (emergency_parser.quickstop_by_M410) { + emergency_parser.quickstop_by_M410 = false; // quickstop_stepper may call idle so clear this now! + quickstop_stepper(); + } + #endif - updateTemperaturesFromRawValues(); // also resets the watchdog + if (!updateTemperaturesIfReady()) return; // Will also reset the watchdog if temperatures are ready #if DISABLED(IGNORE_THERMOCOUPLE_ERRORS) - #if ENABLED(HEATER_0_USES_MAX6675) - if (temp_hotend[0].celsius > _MIN(HEATER_0_MAXTEMP, HEATER_0_MAX6675_TMAX - 1.0)) max_temp_error(H_E0); - if (temp_hotend[0].celsius < _MAX(HEATER_0_MINTEMP, HEATER_0_MAX6675_TMIN + .01)) min_temp_error(H_E0); + #if TEMP_SENSOR_0_IS_MAX_TC + if (degHotend(0) > _MIN(HEATER_0_MAXTEMP, TEMP_SENSOR_0_MAX_TC_TMAX - 1.0)) max_temp_error(H_E0); + if (degHotend(0) < _MAX(HEATER_0_MINTEMP, TEMP_SENSOR_0_MAX_TC_TMIN + .01)) min_temp_error(H_E0); #endif - #if ENABLED(HEATER_1_USES_MAX6675) - if (temp_hotend[1].celsius > _MIN(HEATER_1_MAXTEMP, HEATER_1_MAX6675_TMAX - 1.0)) max_temp_error(H_E1); - if (temp_hotend[1].celsius < _MAX(HEATER_1_MINTEMP, HEATER_1_MAX6675_TMIN + .01)) min_temp_error(H_E1); + #if TEMP_SENSOR_1_IS_MAX_TC + if (degHotend(1) > _MIN(HEATER_1_MAXTEMP, TEMP_SENSOR_1_MAX_TC_TMAX - 1.0)) max_temp_error(H_E1); + if (degHotend(1) < _MAX(HEATER_1_MINTEMP, TEMP_SENSOR_1_MAX_TC_TMIN + .01)) min_temp_error(H_E1); + #endif + #if TEMP_SENSOR_REDUNDANT_IS_MAX_TC + if (degRedundant() > TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX - 1.0) max_temp_error(H_REDUNDANT); + if (degRedundant() < TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN + .01) min_temp_error(H_REDUNDANT); #endif #endif @@ -1070,26 +1305,26 @@ void Temperature::manage_heater() { #if WATCH_HOTENDS // Make sure temperature is increasing - if (watch_hotend[e].next_ms && ELAPSED(ms, watch_hotend[e].next_ms)) { // Time to check this extruder? - if (degHotend(e) < watch_hotend[e].target) { // Failed to increase enough? + if (watch_hotend[e].elapsed(ms)) { // Enabled and time to check? + if (watch_hotend[e].check(degHotend(e))) // Increased enough? + start_watching_hotend(e); // If temp reached, turn off elapsed check + else { TERN_(DWIN_CREALITY_LCD, DWIN_Popup_Temperature(0)); _temp_error((heater_id_t)e, str_t_heating_failed, GET_TEXT(MSG_HEATING_FAILED_LCD)); } - else // Start again if the target is still far off - start_watching_hotend(e); } #endif - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - // Make sure measured temperatures are close together - if (ABS(temp_hotend[0].celsius - redundant_temperature) > MAX_REDUNDANT_TEMP_SENSOR_DIFF) - _temp_error(H_E0, PSTR(STR_REDUNDANCY), GET_TEXT(MSG_ERR_REDUNDANT_TEMP)); - #endif - } // HOTEND_LOOP #endif // HAS_HOTEND + #if HAS_TEMP_REDUNDANT + // Make sure measured temperatures are close together + if (ABS(degRedundantTarget() - degRedundant()) > TEMP_SENSOR_REDUNDANT_MAX_DIFF) + _temp_error((heater_id_t)TEMP_SENSOR_REDUNDANT_TARGET, PSTR(STR_REDUNDANCY), GET_TEXT(MSG_ERR_REDUNDANT_TEMP)); + #endif + #if HAS_AUTO_FAN if (ELAPSED(ms, next_auto_fan_check_ms)) { // only need to check fan state very infrequently checkExtruderAutoFans(); @@ -1113,13 +1348,13 @@ void Temperature::manage_heater() { #if WATCH_BED // Make sure temperature is increasing - if (watch_bed.elapsed(ms)) { // Time to check the bed? - if (degBed() < watch_bed.target) { // Failed to increase enough? + if (watch_bed.elapsed(ms)) { // Time to check the bed? + if (watch_bed.check(degBed())) // Increased enough? + start_watching_bed(); // If temp reached, turn off elapsed check + else { TERN_(DWIN_CREALITY_LCD, DWIN_Popup_Temperature(0)); _temp_error(H_BED, str_t_heating_failed, GET_TEXT(MSG_HEATING_FAILED_LCD)); } - else // Start again if the target is still far off - start_watching_bed(); } #endif // WATCH_BED @@ -1135,10 +1370,10 @@ void Temperature::manage_heater() { #if DISABLED(PIDTEMPBED) if (PENDING(ms, next_bed_check_ms) - && TERN1(PAUSE_CHANGE_REQD, paused == last_pause_state) + && TERN1(PAUSE_CHANGE_REQD, paused_for_probing == last_pause_state) ) break; next_bed_check_ms = ms + BED_CHECK_INTERVAL; - TERN_(PAUSE_CHANGE_REQD, last_pause_state = paused); + TERN_(PAUSE_CHANGE_REQD, last_pause_state = paused_for_probing); #endif TERN_(HEATER_IDLE_HANDLER, heater_idle[IDLE_INDEX_BED].update(ms)); @@ -1194,30 +1429,39 @@ void Temperature::manage_heater() { #if WATCH_CHAMBER // Make sure temperature is increasing - if (watch_chamber.elapsed(ms)) { // Time to check the chamber? - if (degChamber() < watch_chamber.target) // Failed to increase enough? - _temp_error(H_CHAMBER, str_t_heating_failed, GET_TEXT(MSG_HEATING_FAILED_LCD)); + if (watch_chamber.elapsed(ms)) { // Time to check the chamber? + if (watch_chamber.check(degChamber())) // Increased enough? Error below. + start_watching_chamber(); // If temp reached, turn off elapsed check. else - start_watching_chamber(); // Start again if the target is still far off + _temp_error(H_CHAMBER, str_t_heating_failed, GET_TEXT(MSG_HEATING_FAILED_LCD)); } #endif + #if EITHER(CHAMBER_FAN, CHAMBER_VENT) || DISABLED(PIDTEMPCHAMBER) + static bool flag_chamber_excess_heat; // = false; + #endif + #if EITHER(CHAMBER_FAN, CHAMBER_VENT) + static bool flag_chamber_off; // = false + if (temp_chamber.target > CHAMBER_MINTEMP) { flag_chamber_off = false; #if ENABLED(CHAMBER_FAN) + int16_t fan_chamber_pwm; #if CHAMBER_FAN_MODE == 0 - fan_chamber_pwm = CHAMBER_FAN_BASE + fan_chamber_pwm = CHAMBER_FAN_BASE; #elif CHAMBER_FAN_MODE == 1 fan_chamber_pwm = (temp_chamber.celsius > temp_chamber.target) ? (CHAMBER_FAN_BASE) + (CHAMBER_FAN_FACTOR) * (temp_chamber.celsius - temp_chamber.target) : 0; #elif CHAMBER_FAN_MODE == 2 fan_chamber_pwm = (CHAMBER_FAN_BASE) + (CHAMBER_FAN_FACTOR) * ABS(temp_chamber.celsius - temp_chamber.target); if (temp_chamber.soft_pwm_amount) fan_chamber_pwm += (CHAMBER_FAN_FACTOR) * 2; + #elif CHAMBER_FAN_MODE == 3 + fan_chamber_pwm = CHAMBER_FAN_BASE + _MAX((CHAMBER_FAN_FACTOR) * (temp_chamber.celsius - temp_chamber.target), 0); #endif NOMORE(fan_chamber_pwm, 225); - thermalManager.set_fan_speed(2, fan_chamber_pwm); // TODO: instead of fan 2, set to chamber fan + set_fan_speed(CHAMBER_FAN_INDEX, fan_chamber_pwm); // TODO: instead of fan 2, set to chamber fan #endif #if ENABLED(CHAMBER_VENT) @@ -1227,12 +1471,13 @@ void Temperature::manage_heater() { #ifndef MIN_COOLING_SLOPE_DEG_CHAMBER_VENT #define MIN_COOLING_SLOPE_DEG_CHAMBER_VENT 1.5 #endif - if( (temp_chamber.celsius - temp_chamber.target >= HIGH_EXCESS_HEAT_LIMIT) && !flag_chamber_excess_heat) { - // open vent after MIN_COOLING_SLOPE_TIME_CHAMBER_VENT seconds - // if the temperature did not drop at least MIN_COOLING_SLOPE_DEG_CHAMBER_VENT + if (!flag_chamber_excess_heat && temp_chamber.celsius - temp_chamber.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 (old_temp - temp_chamber.celsius < float(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 + 1000UL * MIN_COOLING_SLOPE_TIME_CHAMBER_VENT; + 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); old_temp = temp_chamber.celsius; } } @@ -1240,15 +1485,14 @@ void Temperature::manage_heater() { next_cool_check_ms_2 = 0; old_temp = 9999; } - if (flag_chamber_excess_heat && (temp_chamber.celsius - temp_chamber.target <= -LOW_EXCESS_HEAT_LIMIT) ) { + if (flag_chamber_excess_heat && (temp_chamber.target - temp_chamber.celsius >= LOW_EXCESS_HEAT_LIMIT)) flag_chamber_excess_heat = false; - } #endif } else if (!flag_chamber_off) { #if ENABLED(CHAMBER_FAN) flag_chamber_off = true; - thermalManager.set_fan_speed(2, 0); + set_fan_speed(CHAMBER_FAN_INDEX, 0); #endif #if ENABLED(CHAMBER_VENT) flag_chamber_excess_heat = false; @@ -1257,44 +1501,116 @@ void Temperature::manage_heater() { } #endif - if (ELAPSED(ms, next_chamber_check_ms)) { - next_chamber_check_ms = ms + CHAMBER_CHECK_INTERVAL; - - if (WITHIN(temp_chamber.celsius, CHAMBER_MINTEMP, CHAMBER_MAXTEMP)) { - if (flag_chamber_excess_heat) { + #if ENABLED(PIDTEMPCHAMBER) + // PIDTEMPCHAMBER doesn't support a CHAMBER_VENT yet. + temp_chamber.soft_pwm_amount = WITHIN(temp_chamber.celsius, CHAMBER_MINTEMP, CHAMBER_MAXTEMP) ? (int)get_pid_output_chamber() >> 1 : 0; + #else + if (ELAPSED(ms, next_chamber_check_ms)) { + next_chamber_check_ms = ms + CHAMBER_CHECK_INTERVAL; + + if (WITHIN(temp_chamber.celsius, CHAMBER_MINTEMP, CHAMBER_MAXTEMP)) { + if (flag_chamber_excess_heat) { + temp_chamber.soft_pwm_amount = 0; + #if ENABLED(CHAMBER_VENT) + if (!flag_chamber_off) MOVE_SERVO(CHAMBER_VENT_SERVO_NR, temp_chamber.celsius <= temp_chamber.target ? 0 : 90); + #endif + } + else { + #if ENABLED(CHAMBER_LIMIT_SWITCHING) + if (temp_chamber.celsius >= temp_chamber.target + TEMP_CHAMBER_HYSTERESIS) + temp_chamber.soft_pwm_amount = 0; + else if (temp_chamber.celsius <= temp_chamber.target - (TEMP_CHAMBER_HYSTERESIS)) + temp_chamber.soft_pwm_amount = (MAX_CHAMBER_POWER) >> 1; + #else + temp_chamber.soft_pwm_amount = temp_chamber.celsius < temp_chamber.target ? (MAX_CHAMBER_POWER) >> 1 : 0; + #endif + #if ENABLED(CHAMBER_VENT) + if (!flag_chamber_off) MOVE_SERVO(CHAMBER_VENT_SERVO_NR, 0); + #endif + } + } + else { temp_chamber.soft_pwm_amount = 0; - #if ENABLED(CHAMBER_VENT) - if (!flag_chamber_off) MOVE_SERVO(CHAMBER_VENT_SERVO_NR, temp_chamber.celsius <= temp_chamber.target ? 0 : 90); + WRITE_HEATER_CHAMBER(LOW); + } + } + #if ENABLED(THERMAL_PROTECTION_CHAMBER) + tr_state_machine[RUNAWAY_IND_CHAMBER].run(temp_chamber.celsius, temp_chamber.target, H_CHAMBER, THERMAL_PROTECTION_CHAMBER_PERIOD, THERMAL_PROTECTION_CHAMBER_HYSTERESIS); + #endif + #endif + + #endif // HAS_HEATED_CHAMBER + + #if HAS_COOLER + + #ifndef COOLER_CHECK_INTERVAL + #define COOLER_CHECK_INTERVAL 2000UL + #endif + + #if ENABLED(THERMAL_PROTECTION_COOLER) + if (degCooler() > COOLER_MAXTEMP) max_temp_error(H_COOLER); + #endif + + #if WATCH_COOLER + // Make sure temperature is decreasing + if (watch_cooler.elapsed(ms)) { // Time to check the cooler? + if (degCooler() > watch_cooler.target) // Failed to decrease enough? + _temp_error(H_COOLER, GET_TEXT(MSG_COOLING_FAILED), GET_TEXT(MSG_COOLING_FAILED)); + else + start_watching_cooler(); // Start again if the target is still far off + } + #endif + + static bool flag_cooler_state; // = false + + if (cooler.enabled) { + flag_cooler_state = true; // used to allow M106 fan control when cooler is disabled + if (temp_cooler.target == 0) temp_cooler.target = COOLER_MIN_TARGET; + if (ELAPSED(ms, next_cooler_check_ms)) { + next_cooler_check_ms = ms + COOLER_CHECK_INTERVAL; + if (temp_cooler.celsius > temp_cooler.target) { + temp_cooler.soft_pwm_amount = temp_cooler.celsius > temp_cooler.target ? MAX_COOLER_POWER : 0; + flag_cooler_state = temp_cooler.soft_pwm_amount > 0 ? true : false; // used to allow M106 fan control when cooler is disabled + #if ENABLED(COOLER_FAN) + int16_t fan_cooler_pwm = (COOLER_FAN_BASE) + (COOLER_FAN_FACTOR) * ABS(temp_cooler.celsius - temp_cooler.target); + NOMORE(fan_cooler_pwm, 255); + set_fan_speed(COOLER_FAN_INDEX, fan_cooler_pwm); // Set cooler fan pwm + cooler_fan_flush_ms = ms + 5000; #endif } else { - #if ENABLED(CHAMBER_LIMIT_SWITCHING) - if (temp_chamber.celsius >= temp_chamber.target + TEMP_CHAMBER_HYSTERESIS) - temp_chamber.soft_pwm_amount = 0; - else if (temp_chamber.celsius <= temp_chamber.target - (TEMP_CHAMBER_HYSTERESIS)) - temp_chamber.soft_pwm_amount = (MAX_CHAMBER_POWER) >> 1; - #else - temp_chamber.soft_pwm_amount = temp_chamber.celsius < temp_chamber.target ? (MAX_CHAMBER_POWER) >> 1 : 0; - #endif - #if ENABLED(CHAMBER_VENT) - if (!flag_chamber_off) MOVE_SERVO(CHAMBER_VENT_SERVO_NR, 0); + temp_cooler.soft_pwm_amount = 0; + #if ENABLED(COOLER_FAN) + set_fan_speed(COOLER_FAN_INDEX, temp_cooler.celsius > temp_cooler.target - 2 ? COOLER_FAN_BASE : 0); #endif + WRITE_HEATER_COOLER(LOW); } } - else { - temp_chamber.soft_pwm_amount = 0; - WRITE_HEATER_CHAMBER(LOW); + } + else { + temp_cooler.soft_pwm_amount = 0; + if (flag_cooler_state) { + flag_cooler_state = false; + thermalManager.set_fan_speed(COOLER_FAN_INDEX, 0); } - - #if ENABLED(THERMAL_PROTECTION_CHAMBER) - tr_state_machine[RUNAWAY_IND_CHAMBER].run(temp_chamber.celsius, temp_chamber.target, H_CHAMBER, THERMAL_PROTECTION_CHAMBER_PERIOD, THERMAL_PROTECTION_CHAMBER_HYSTERESIS); - #endif + WRITE_HEATER_COOLER(LOW); } - // TODO: Implement true PID pwm - //temp_bed.soft_pwm_amount = WITHIN(temp_chamber.celsius, CHAMBER_MINTEMP, CHAMBER_MAXTEMP) ? (int)get_pid_output_chamber() >> 1 : 0; + #if ENABLED(THERMAL_PROTECTION_COOLER) + tr_state_machine[RUNAWAY_IND_COOLER].run(temp_cooler.celsius, temp_cooler.target, H_COOLER, THERMAL_PROTECTION_COOLER_PERIOD, THERMAL_PROTECTION_COOLER_HYSTERESIS); + #endif - #endif // HAS_HEATED_CHAMBER + #endif // HAS_COOLER + + #if ENABLED(LASER_COOLANT_FLOW_METER) + cooler.flowmeter_task(ms); + #if ENABLED(FLOWMETER_SAFETY) + if (cutter.enabled() && cooler.check_flow_too_low()) { + cutter.disable(); + TERN_(HAS_DISPLAY, ui.flow_fault()); + } + #endif + #endif UNUSED(ms); } @@ -1306,22 +1622,22 @@ void Temperature::manage_heater() { * Bisect search for the range of the 'raw' value, then interpolate * proportionally between the under and over values. */ -#define SCAN_THERMISTOR_TABLE(TBL,LEN) do{ \ - uint8_t l = 0, r = LEN, m; \ - for (;;) { \ - m = (l + r) >> 1; \ - if (!m) return int16_t(pgm_read_word(&TBL[0].celsius)); \ - if (m == l || m == r) return int16_t(pgm_read_word(&TBL[LEN-1].celsius)); \ - int16_t v00 = pgm_read_word(&TBL[m-1].value), \ - v10 = pgm_read_word(&TBL[m-0].value); \ - if (raw < v00) r = m; \ - else if (raw > v10) l = m; \ - else { \ - const int16_t v01 = int16_t(pgm_read_word(&TBL[m-1].celsius)), \ - v11 = int16_t(pgm_read_word(&TBL[m-0].celsius)); \ - return v01 + (raw - v00) * float(v11 - v01) / float(v10 - v00); \ - } \ - } \ +#define SCAN_THERMISTOR_TABLE(TBL,LEN) do{ \ + uint8_t l = 0, r = LEN, m; \ + for (;;) { \ + m = (l + r) >> 1; \ + if (!m) return celsius_t(pgm_read_word(&TBL[0].celsius)); \ + if (m == l || m == r) return celsius_t(pgm_read_word(&TBL[LEN-1].celsius)); \ + int16_t v00 = pgm_read_word(&TBL[m-1].value), \ + v10 = pgm_read_word(&TBL[m-0].value); \ + if (raw < v00) r = m; \ + else if (raw > v10) l = m; \ + else { \ + const celsius_t v01 = celsius_t(pgm_read_word(&TBL[m-1].celsius)), \ + v11 = celsius_t(pgm_read_word(&TBL[m-0].celsius)); \ + return v01 + (raw - v00) * float(v11 - v01) / float(v10 - v00); \ + } \ + } \ }while(0) #if HAS_USER_THERMISTORS @@ -1329,39 +1645,48 @@ void Temperature::manage_heater() { user_thermistor_t Temperature::user_thermistor[USER_THERMISTORS]; // Initialized by settings.load() void Temperature::reset_user_thermistors() { - user_thermistor_t user_thermistor[USER_THERMISTORS] = { - #if ENABLED(HEATER_0_USER_THERMISTOR) + user_thermistor_t default_user_thermistor[USER_THERMISTORS] = { + #if TEMP_SENSOR_0_IS_CUSTOM { true, 0, 0, HOTEND0_PULLUP_RESISTOR_OHMS, HOTEND0_RESISTANCE_25C_OHMS, 0, 0, HOTEND0_BETA, 0 }, #endif - #if ENABLED(HEATER_1_USER_THERMISTOR) + #if TEMP_SENSOR_1_IS_CUSTOM { true, 0, 0, HOTEND1_PULLUP_RESISTOR_OHMS, HOTEND1_RESISTANCE_25C_OHMS, 0, 0, HOTEND1_BETA, 0 }, #endif - #if ENABLED(HEATER_2_USER_THERMISTOR) + #if TEMP_SENSOR_2_IS_CUSTOM { true, 0, 0, HOTEND2_PULLUP_RESISTOR_OHMS, HOTEND2_RESISTANCE_25C_OHMS, 0, 0, HOTEND2_BETA, 0 }, #endif - #if ENABLED(HEATER_3_USER_THERMISTOR) + #if TEMP_SENSOR_3_IS_CUSTOM { true, 0, 0, HOTEND3_PULLUP_RESISTOR_OHMS, HOTEND3_RESISTANCE_25C_OHMS, 0, 0, HOTEND3_BETA, 0 }, #endif - #if ENABLED(HEATER_4_USER_THERMISTOR) + #if TEMP_SENSOR_4_IS_CUSTOM { true, 0, 0, HOTEND4_PULLUP_RESISTOR_OHMS, HOTEND4_RESISTANCE_25C_OHMS, 0, 0, HOTEND4_BETA, 0 }, #endif - #if ENABLED(HEATER_5_USER_THERMISTOR) + #if TEMP_SENSOR_5_IS_CUSTOM { true, 0, 0, HOTEND5_PULLUP_RESISTOR_OHMS, HOTEND5_RESISTANCE_25C_OHMS, 0, 0, HOTEND5_BETA, 0 }, #endif - #if ENABLED(HEATER_6_USER_THERMISTOR) + #if TEMP_SENSOR_6_IS_CUSTOM { true, 0, 0, HOTEND6_PULLUP_RESISTOR_OHMS, HOTEND6_RESISTANCE_25C_OHMS, 0, 0, HOTEND6_BETA, 0 }, #endif - #if ENABLED(HEATER_7_USER_THERMISTOR) + #if TEMP_SENSOR_7_IS_CUSTOM { true, 0, 0, HOTEND7_PULLUP_RESISTOR_OHMS, HOTEND7_RESISTANCE_25C_OHMS, 0, 0, HOTEND7_BETA, 0 }, #endif - #if ENABLED(HEATER_BED_USER_THERMISTOR) + #if TEMP_SENSOR_BED_IS_CUSTOM { true, 0, 0, BED_PULLUP_RESISTOR_OHMS, BED_RESISTANCE_25C_OHMS, 0, 0, BED_BETA, 0 }, #endif - #if ENABLED(HEATER_CHAMBER_USER_THERMISTOR) - { true, 0, 0, CHAMBER_PULLUP_RESISTOR_OHMS, CHAMBER_RESISTANCE_25C_OHMS, 0, 0, CHAMBER_BETA, 0 } + #if TEMP_SENSOR_CHAMBER_IS_CUSTOM + { true, 0, 0, CHAMBER_PULLUP_RESISTOR_OHMS, CHAMBER_RESISTANCE_25C_OHMS, 0, 0, CHAMBER_BETA, 0 }, + #endif + #if TEMP_SENSOR_COOLER_IS_CUSTOM + { true, 0, 0, COOLER_PULLUP_RESISTOR_OHMS, COOLER_RESISTANCE_25C_OHMS, 0, 0, COOLER_BETA, 0 }, + #endif + #if TEMP_SENSOR_PROBE_IS_CUSTOM + { true, 0, 0, PROBE_PULLUP_RESISTOR_OHMS, PROBE_RESISTANCE_25C_OHMS, 0, 0, PROBE_BETA, 0 }, + #endif + #if TEMP_SENSOR_REDUNDANT_IS_CUSTOM + { true, 0, 0, REDUNDANT_PULLUP_RESISTOR_OHMS, REDUNDANT_RESISTANCE_25C_OHMS, 0, 0, REDUNDANT_BETA, 0 }, #endif }; - COPY(thermalManager.user_thermistor, user_thermistor); + COPY(user_thermistor, default_user_thermistor); } void Temperature::log_user_thermistor(const uint8_t t_index, const bool eprom/*=false*/) { @@ -1370,8 +1695,7 @@ void Temperature::manage_heater() { SERIAL_ECHOPGM(" M305 "); else SERIAL_ECHO_START(); - SERIAL_CHAR('P'); - SERIAL_CHAR('0' + t_index); + SERIAL_CHAR('P', '0' + t_index); const user_thermistor_t &t = user_thermistor[t_index]; @@ -1380,28 +1704,26 @@ void Temperature::manage_heater() { SERIAL_ECHOPAIR_F_P(SP_B_STR, t.beta, 1); SERIAL_ECHOPAIR_F_P(SP_C_STR, t.sh_c_coeff, 9); SERIAL_ECHOPGM(" ; "); - serialprintPGM( - TERN_(HEATER_0_USER_THERMISTOR, t_index == CTI_HOTEND_0 ? PSTR("HOTEND 0") :) - TERN_(HEATER_1_USER_THERMISTOR, t_index == CTI_HOTEND_1 ? PSTR("HOTEND 1") :) - TERN_(HEATER_2_USER_THERMISTOR, t_index == CTI_HOTEND_2 ? PSTR("HOTEND 2") :) - TERN_(HEATER_3_USER_THERMISTOR, t_index == CTI_HOTEND_3 ? PSTR("HOTEND 3") :) - TERN_(HEATER_4_USER_THERMISTOR, t_index == CTI_HOTEND_4 ? PSTR("HOTEND 4") :) - TERN_(HEATER_5_USER_THERMISTOR, t_index == CTI_HOTEND_5 ? PSTR("HOTEND 5") :) - TERN_(HEATER_6_USER_THERMISTOR, t_index == CTI_HOTEND_6 ? PSTR("HOTEND 6") :) - TERN_(HEATER_7_USER_THERMISTOR, t_index == CTI_HOTEND_7 ? PSTR("HOTEND 7") :) - TERN_(HEATER_BED_USER_THERMISTOR, t_index == CTI_BED ? PSTR("BED") :) - TERN_(HEATER_CHAMBER_USER_THERMISTOR, t_index == CTI_CHAMBER ? PSTR("CHAMBER") :) + SERIAL_ECHOPGM_P( + TERN_(TEMP_SENSOR_0_IS_CUSTOM, t_index == CTI_HOTEND_0 ? PSTR("HOTEND 0") :) + TERN_(TEMP_SENSOR_1_IS_CUSTOM, t_index == CTI_HOTEND_1 ? PSTR("HOTEND 1") :) + TERN_(TEMP_SENSOR_2_IS_CUSTOM, t_index == CTI_HOTEND_2 ? PSTR("HOTEND 2") :) + TERN_(TEMP_SENSOR_3_IS_CUSTOM, t_index == CTI_HOTEND_3 ? PSTR("HOTEND 3") :) + TERN_(TEMP_SENSOR_4_IS_CUSTOM, t_index == CTI_HOTEND_4 ? PSTR("HOTEND 4") :) + TERN_(TEMP_SENSOR_5_IS_CUSTOM, t_index == CTI_HOTEND_5 ? PSTR("HOTEND 5") :) + TERN_(TEMP_SENSOR_6_IS_CUSTOM, t_index == CTI_HOTEND_6 ? PSTR("HOTEND 6") :) + TERN_(TEMP_SENSOR_7_IS_CUSTOM, t_index == CTI_HOTEND_7 ? PSTR("HOTEND 7") :) + TERN_(TEMP_SENSOR_BED_IS_CUSTOM, t_index == CTI_BED ? PSTR("BED") :) + TERN_(TEMP_SENSOR_CHAMBER_IS_CUSTOM, t_index == CTI_CHAMBER ? PSTR("CHAMBER") :) + TERN_(TEMP_SENSOR_COOLER_IS_CUSTOM, t_index == CTI_COOLER ? PSTR("COOLER") :) + TERN_(TEMP_SENSOR_PROBE_IS_CUSTOM, t_index == CTI_PROBE ? PSTR("PROBE") :) + TERN_(TEMP_SENSOR_REDUNDANT_IS_CUSTOM, t_index == CTI_REDUNDANT ? PSTR("REDUNDANT") :) nullptr ); SERIAL_EOL(); } - float Temperature::user_thermistor_to_deg_c(const uint8_t t_index, const int raw) { - //#if (MOTHERBOARD == BOARD_RAMPS_14_EFB) - // static uint32_t clocks_total = 0; - // static uint32_t calls = 0; - // uint32_t tcnt5 = TCNT5; - //#endif + celsius_float_t Temperature::user_thermistor_to_deg_c(const uint8_t t_index, const int16_t raw) { if (!WITHIN(t_index, 0, COUNT(user_thermistor) - 1)) return 25; @@ -1429,14 +1751,6 @@ void Temperature::manage_heater() { value += t.sh_c_coeff * cu(log_resistance); value = 1.0f / value; - //#if (MOTHERBOARD == BOARD_RAMPS_14_EFB) - // int32_t clocks = TCNT5 - tcnt5; - // if (clocks >= 0) { - // clocks_total += clocks; - // calls++; - // } - //#endif - // Return degrees C (up to 999, as the LCD only displays 3 digits) return _MIN(value + THERMISTOR_ABS_ZERO_C, 999); } @@ -1445,10 +1759,10 @@ void Temperature::manage_heater() { #if HAS_HOTEND // Derived from RepRap FiveD extruder::getTemperature() // For hot end temperature measurement. - float Temperature::analog_to_celsius_hotend(const int raw, const uint8_t e) { - if (e > HOTENDS - DISABLED(TEMP_SENSOR_1_AS_REDUNDANT)) { + celsius_float_t Temperature::analog_to_celsius_hotend(const int16_t raw, const uint8_t e) { + if (e >= HOTENDS) { SERIAL_ERROR_START(); - SERIAL_ECHO((int)e); + SERIAL_ECHO(e); SERIAL_ECHOLNPGM(STR_INVALID_EXTRUDER_NUM); kill(); return 0; @@ -1456,91 +1770,99 @@ void Temperature::manage_heater() { switch (e) { case 0: - #if ENABLED(HEATER_0_USER_THERMISTOR) + #if TEMP_SENSOR_0_IS_CUSTOM return user_thermistor_to_deg_c(CTI_HOTEND_0, raw); - #elif ENABLED(HEATER_0_USES_MAX6675) - return ( - #if ENABLED(MAX6675_IS_MAX31865) - max31865.temperature(MAX31865_SENSOR_OHMS, MAX31865_CALIBRATION_OHMS) - #else - raw * 0.25 - #endif - ); - #elif ENABLED(HEATER_0_USES_AD595) + #elif TEMP_SENSOR_0_IS_MAX_TC + #if TEMP_SENSOR_0_IS_MAX31865 + return TERN(LIB_INTERNAL_MAX31865, + max31865_0.temperature((uint16_t)raw), + max31865_0.temperature(MAX31865_SENSOR_OHMS_0, MAX31865_CALIBRATION_OHMS_0) + ); + #else + return raw * 0.25; + #endif + #elif TEMP_SENSOR_0_IS_AD595 return TEMP_AD595(raw); - #elif ENABLED(HEATER_0_USES_AD8495) + #elif TEMP_SENSOR_0_IS_AD8495 return TEMP_AD8495(raw); #else break; #endif case 1: - #if ENABLED(HEATER_1_USER_THERMISTOR) + #if TEMP_SENSOR_1_IS_CUSTOM return user_thermistor_to_deg_c(CTI_HOTEND_1, raw); - #elif ENABLED(HEATER_1_USES_MAX6675) - return raw * 0.25; - #elif ENABLED(HEATER_1_USES_AD595) + #elif TEMP_SENSOR_1_IS_MAX_TC + #if TEMP_SENSOR_0_IS_MAX31865 + return TERN(LIB_INTERNAL_MAX31865, + max31865_1.temperature((uint16_t)raw), + max31865_1.temperature(MAX31865_SENSOR_OHMS_1, MAX31865_CALIBRATION_OHMS_1) + ); + #else + return raw * 0.25; + #endif + #elif TEMP_SENSOR_1_IS_AD595 return TEMP_AD595(raw); - #elif ENABLED(HEATER_1_USES_AD8495) + #elif TEMP_SENSOR_1_IS_AD8495 return TEMP_AD8495(raw); #else break; #endif case 2: - #if ENABLED(HEATER_2_USER_THERMISTOR) + #if TEMP_SENSOR_2_IS_CUSTOM return user_thermistor_to_deg_c(CTI_HOTEND_2, raw); - #elif ENABLED(HEATER_2_USES_AD595) + #elif TEMP_SENSOR_2_IS_AD595 return TEMP_AD595(raw); - #elif ENABLED(HEATER_2_USES_AD8495) + #elif TEMP_SENSOR_2_IS_AD8495 return TEMP_AD8495(raw); #else break; #endif case 3: - #if ENABLED(HEATER_3_USER_THERMISTOR) + #if TEMP_SENSOR_3_IS_CUSTOM return user_thermistor_to_deg_c(CTI_HOTEND_3, raw); - #elif ENABLED(HEATER_3_USES_AD595) + #elif TEMP_SENSOR_3_IS_AD595 return TEMP_AD595(raw); - #elif ENABLED(HEATER_3_USES_AD8495) + #elif TEMP_SENSOR_3_IS_AD8495 return TEMP_AD8495(raw); #else break; #endif case 4: - #if ENABLED(HEATER_4_USER_THERMISTOR) + #if TEMP_SENSOR_4_IS_CUSTOM return user_thermistor_to_deg_c(CTI_HOTEND_4, raw); - #elif ENABLED(HEATER_4_USES_AD595) + #elif TEMP_SENSOR_4_IS_AD595 return TEMP_AD595(raw); - #elif ENABLED(HEATER_4_USES_AD8495) + #elif TEMP_SENSOR_4_IS_AD8495 return TEMP_AD8495(raw); #else break; #endif case 5: - #if ENABLED(HEATER_5_USER_THERMISTOR) + #if TEMP_SENSOR_5_IS_CUSTOM return user_thermistor_to_deg_c(CTI_HOTEND_5, raw); - #elif ENABLED(HEATER_5_USES_AD595) + #elif TEMP_SENSOR_5_IS_AD595 return TEMP_AD595(raw); - #elif ENABLED(HEATER_5_USES_AD8495) + #elif TEMP_SENSOR_5_IS_AD8495 return TEMP_AD8495(raw); #else break; #endif case 6: - #if ENABLED(HEATER_6_USER_THERMISTOR) + #if TEMP_SENSOR_6_IS_CUSTOM return user_thermistor_to_deg_c(CTI_HOTEND_6, raw); - #elif ENABLED(HEATER_6_USES_AD595) + #elif TEMP_SENSOR_6_IS_AD595 return TEMP_AD595(raw); - #elif ENABLED(HEATER_6_USES_AD8495) + #elif TEMP_SENSOR_6_IS_AD8495 return TEMP_AD8495(raw); #else break; #endif case 7: - #if ENABLED(HEATER_7_USER_THERMISTOR) + #if TEMP_SENSOR_7_IS_CUSTOM return user_thermistor_to_deg_c(CTI_HOTEND_7, raw); - #elif ENABLED(HEATER_7_USES_AD595) + #elif TEMP_SENSOR_7_IS_AD595 return TEMP_AD595(raw); - #elif ENABLED(HEATER_7_USES_AD8495) + #elif TEMP_SENSOR_7_IS_AD8495 return TEMP_AD8495(raw); #else break; @@ -1548,7 +1870,7 @@ void Temperature::manage_heater() { default: break; } - #if HOTEND_USES_THERMISTOR + #if HAS_HOTEND_THERMISTOR // Thermistor with conversion table? const temp_entry_t(*tt)[] = (temp_entry_t(*)[])(heater_ttbl_map[e]); SCAN_THERMISTOR_TABLE((*tt), heater_ttbllen_map[e]); @@ -1559,16 +1881,15 @@ void Temperature::manage_heater() { #endif // HAS_HOTEND #if HAS_HEATED_BED - // Derived from RepRap FiveD extruder::getTemperature() // For bed temperature measurement. - float Temperature::analog_to_celsius_bed(const int raw) { - #if ENABLED(HEATER_BED_USER_THERMISTOR) + celsius_float_t Temperature::analog_to_celsius_bed(const int16_t raw) { + #if TEMP_SENSOR_BED_IS_CUSTOM return user_thermistor_to_deg_c(CTI_BED, raw); - #elif ENABLED(HEATER_BED_USES_THERMISTOR) - SCAN_THERMISTOR_TABLE(BED_TEMPTABLE, BED_TEMPTABLE_LEN); - #elif ENABLED(HEATER_BED_USES_AD595) + #elif TEMP_SENSOR_BED_IS_THERMISTOR + SCAN_THERMISTOR_TABLE(TEMPTABLE_BED, TEMPTABLE_BED_LEN); + #elif TEMP_SENSOR_BED_IS_AD595 return TEMP_AD595(raw); - #elif ENABLED(HEATER_BED_USES_AD8495) + #elif TEMP_SENSOR_BED_IS_AD8495 return TEMP_AD8495(raw); #else UNUSED(raw); @@ -1578,16 +1899,15 @@ void Temperature::manage_heater() { #endif // HAS_HEATED_BED #if HAS_TEMP_CHAMBER - // Derived from RepRap FiveD extruder::getTemperature() // For chamber temperature measurement. - float Temperature::analog_to_celsius_chamber(const int raw) { - #if ENABLED(HEATER_CHAMBER_USER_THERMISTOR) + celsius_float_t Temperature::analog_to_celsius_chamber(const int16_t raw) { + #if TEMP_SENSOR_CHAMBER_IS_CUSTOM return user_thermistor_to_deg_c(CTI_CHAMBER, raw); - #elif ENABLED(HEATER_CHAMBER_USES_THERMISTOR) - SCAN_THERMISTOR_TABLE(CHAMBER_TEMPTABLE, CHAMBER_TEMPTABLE_LEN); - #elif ENABLED(HEATER_CHAMBER_USES_AD595) + #elif TEMP_SENSOR_CHAMBER_IS_THERMISTOR + SCAN_THERMISTOR_TABLE(TEMPTABLE_CHAMBER, TEMPTABLE_CHAMBER_LEN); + #elif TEMP_SENSOR_CHAMBER_IS_AD595 return TEMP_AD595(raw); - #elif ENABLED(HEATER_CHAMBER_USES_AD8495) + #elif TEMP_SENSOR_CHAMBER_IS_AD8495 return TEMP_AD8495(raw); #else UNUSED(raw); @@ -1596,17 +1916,34 @@ void Temperature::manage_heater() { } #endif // HAS_TEMP_CHAMBER +#if HAS_TEMP_COOLER + // For cooler temperature measurement. + celsius_float_t Temperature::analog_to_celsius_cooler(const int16_t raw) { + #if TEMP_SENSOR_COOLER_IS_CUSTOM + return user_thermistor_to_deg_c(CTI_COOLER, raw); + #elif TEMP_SENSOR_COOLER_IS_THERMISTOR + SCAN_THERMISTOR_TABLE(TEMPTABLE_COOLER, TEMPTABLE_COOLER_LEN); + #elif TEMP_SENSOR_COOLER_IS_AD595 + return TEMP_AD595(raw); + #elif TEMP_SENSOR_COOLER_IS_AD8495 + return TEMP_AD8495(raw); + #else + UNUSED(raw); + return 0; + #endif + } +#endif // HAS_TEMP_COOLER + #if HAS_TEMP_PROBE - // Derived from RepRap FiveD extruder::getTemperature() // For probe temperature measurement. - float Temperature::analog_to_celsius_probe(const int raw) { - #if ENABLED(PROBE_USER_THERMISTOR) + celsius_float_t Temperature::analog_to_celsius_probe(const int16_t raw) { + #if TEMP_SENSOR_PROBE_IS_CUSTOM return user_thermistor_to_deg_c(CTI_PROBE, raw); - #elif ENABLED(PROBE_USES_THERMISTOR) - SCAN_THERMISTOR_TABLE(PROBE_TEMPTABLE, PROBE_TEMPTABLE_LEN); - #elif ENABLED(PROBE_USES_AD595) + #elif TEMP_SENSOR_PROBE_IS_THERMISTOR + SCAN_THERMISTOR_TABLE(TEMPTABLE_PROBE, TEMPTABLE_PROBE_LEN); + #elif TEMP_SENSOR_PROBE_IS_AD595 return TEMP_AD595(raw); - #elif ENABLED(PROBE_USES_AD8495) + #elif TEMP_SENSOR_PROBE_IS_AD8495 return TEMP_AD8495(raw); #else UNUSED(raw); @@ -1615,112 +1952,228 @@ void Temperature::manage_heater() { } #endif // HAS_TEMP_PROBE +#if HAS_TEMP_REDUNDANT + // For redundant temperature measurement. + celsius_float_t Temperature::analog_to_celsius_redundant(const int16_t raw) { + #if TEMP_SENSOR_REDUNDANT_IS_CUSTOM + return user_thermistor_to_deg_c(CTI_REDUNDANT, raw); + #elif TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 0 + return TERN(TEMP_SENSOR_REDUNDANT_IS_MAX31865, max31865_0.temperature((uint16_t)raw), raw * 0.25); + #elif TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 1 + return TERN(TEMP_SENSOR_REDUNDANT_IS_MAX31865, max31865_1.temperature((uint16_t)raw), raw * 0.25); + #elif TEMP_SENSOR_REDUNDANT_IS_THERMISTOR + SCAN_THERMISTOR_TABLE(TEMPTABLE_REDUNDANT, TEMPTABLE_REDUNDANT_LEN); + #elif TEMP_SENSOR_REDUNDANT_IS_AD595 + return TEMP_AD595(raw); + #elif TEMP_SENSOR_REDUNDANT_IS_AD8495 + return TEMP_AD8495(raw); + #else + UNUSED(raw); + return 0; + #endif + } +#endif // HAS_TEMP_REDUNDANT + /** - * Get the raw values into the actual temperatures. - * The raw values are created in interrupt context, - * and this function is called from normal context - * as it would block the stepper routine. + * Convert the raw sensor readings into actual Celsius temperatures and + * validate raw temperatures. Bad readings generate min/maxtemp errors. + * + * The raw values are generated entirely in interrupt context, and this + * method is called from normal context once 'raw_temps_ready' has been + * set by update_raw_temperatures(). + * + * The watchdog is dependent on this method. If 'raw_temps_ready' stops + * being set by the interrupt so that this method is not called for over + * 4 seconds then something has gone afoul and the machine will be reset. */ void Temperature::updateTemperaturesFromRawValues() { - #if ENABLED(HEATER_0_USES_MAX6675) - temp_hotend[0].raw = READ_MAX6675(0); - #endif - #if ENABLED(HEATER_1_USES_MAX6675) - temp_hotend[1].raw = READ_MAX6675(1); - #endif + + watchdog_refresh(); // Reset because raw_temps_ready was set by the interrupt + + TERN_(TEMP_SENSOR_0_IS_MAX_TC, temp_hotend[0].raw = READ_MAX_TC(0)); + TERN_(TEMP_SENSOR_1_IS_MAX_TC, temp_hotend[1].raw = READ_MAX_TC(1)); + TERN_(TEMP_SENSOR_REDUNDANT_IS_MAX_TC, temp_redundant.raw = READ_MAX_TC(TEMP_SENSOR_REDUNDANT_SOURCE)); + #if HAS_HOTEND HOTEND_LOOP() temp_hotend[e].celsius = analog_to_celsius_hotend(temp_hotend[e].raw, e); #endif - TERN_(HAS_HEATED_BED, temp_bed.celsius = analog_to_celsius_bed(temp_bed.raw)); - TERN_(HAS_TEMP_CHAMBER, temp_chamber.celsius = analog_to_celsius_chamber(temp_chamber.raw)); - TERN_(HAS_TEMP_PROBE, temp_probe.celsius = analog_to_celsius_probe(temp_probe.raw)); - TERN_(TEMP_SENSOR_1_AS_REDUNDANT, redundant_temperature = analog_to_celsius_hotend(redundant_temperature_raw, 1)); + TERN_(HAS_HEATED_BED, temp_bed.celsius = analog_to_celsius_bed(temp_bed.raw)); + TERN_(HAS_TEMP_CHAMBER, temp_chamber.celsius = analog_to_celsius_chamber(temp_chamber.raw)); + TERN_(HAS_TEMP_COOLER, temp_cooler.celsius = analog_to_celsius_cooler(temp_cooler.raw)); + TERN_(HAS_TEMP_PROBE, temp_probe.celsius = analog_to_celsius_probe(temp_probe.raw)); + TERN_(HAS_TEMP_REDUNDANT, temp_redundant.celsius = analog_to_celsius_redundant(temp_redundant.raw)); + TERN_(FILAMENT_WIDTH_SENSOR, filwidth.update_measured_mm()); - TERN_(HAS_POWER_MONITOR, power_monitor.capture_values()); + TERN_(HAS_POWER_MONITOR, power_monitor.capture_values()); - // Reset the watchdog on good temperature measurement - watchdog_refresh(); + #if HAS_HOTEND + static constexpr int8_t temp_dir[] = { + #if TEMP_SENSOR_IS_ANY_MAX_TC(0) + 0 + #else + TEMPDIR(0) + #endif + #if HAS_MULTI_HOTEND + #if TEMP_SENSOR_IS_ANY_MAX_TC(1) + , 0 + #else + , TEMPDIR(1) + #endif + #if HOTENDS > 2 + #define _TEMPDIR(N) , TEMPDIR(N) + REPEAT_S(2, HOTENDS, _TEMPDIR) + #endif + #endif + }; - raw_temps_ready = false; -} + LOOP_L_N(e, COUNT(temp_dir)) { + const int8_t tdir = temp_dir[e]; + if (tdir) { + const int16_t rawtemp = temp_hotend[e].raw * tdir; // normal direction, +rawtemp, else -rawtemp + if (rawtemp > temp_range[e].raw_max * tdir) max_temp_error((heater_id_t)e); -#if MAX6675_SEPARATE_SPI - template SoftSPI SPIclass::softSPI; - SPIclass max6675_spi; -#endif + const bool heater_on = temp_hotend[e].target > 0; + if (heater_on && rawtemp < temp_range[e].raw_min * tdir && !is_preheating(e)) { + #if MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED > 1 + if (++consecutive_low_temperature_error[e] >= MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED) + #endif + min_temp_error((heater_id_t)e); + } + #if MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED > 1 + else + consecutive_low_temperature_error[e] = 0; + #endif + } + } -// Init fans according to whether they're native PWM or Software PWM -#ifdef ALFAWISE_UX0 - #define _INIT_SOFT_FAN(P) OUT_WRITE_OD(P, FAN_INVERTING ? LOW : HIGH) -#else - #define _INIT_SOFT_FAN(P) OUT_WRITE(P, FAN_INVERTING ? LOW : HIGH) -#endif -#if ENABLED(FAN_SOFT_PWM) - #define _INIT_FAN_PIN(P) _INIT_SOFT_FAN(P) -#else - #define _INIT_FAN_PIN(P) do{ if (PWM_PIN(P)) SET_PWM(P); else _INIT_SOFT_FAN(P); }while(0) -#endif -#if ENABLED(FAST_PWM_FAN) - #define SET_FAST_PWM_FREQ(P) set_pwm_frequency(P, FAST_PWM_FAN_FREQUENCY) -#else - #define SET_FAST_PWM_FREQ(P) NOOP -#endif -#define INIT_FAN_PIN(P) do{ _INIT_FAN_PIN(P); SET_FAST_PWM_FREQ(P); }while(0) -#if EXTRUDER_AUTO_FAN_SPEED != 255 - #define INIT_E_AUTO_FAN_PIN(P) do{ if (P == FAN1_PIN || P == FAN2_PIN) { SET_PWM(P); SET_FAST_PWM_FREQ(P); } else SET_OUTPUT(P); }while(0) -#else - #define INIT_E_AUTO_FAN_PIN(P) SET_OUTPUT(P) -#endif -#if CHAMBER_AUTO_FAN_SPEED != 255 - #define INIT_CHAMBER_AUTO_FAN_PIN(P) do{ if (P == FAN1_PIN || P == FAN2_PIN) { SET_PWM(P); SET_FAST_PWM_FREQ(P); } else SET_OUTPUT(P); }while(0) -#else - #define INIT_CHAMBER_AUTO_FAN_PIN(P) SET_OUTPUT(P) -#endif + #endif // HAS_HOTEND + + #if ENABLED(THERMAL_PROTECTION_BED) + #define BEDCMP(A,B) (TEMPDIR(BED) < 0 ? ((A)<(B)) : ((A)>(B))) + if (BEDCMP(temp_bed.raw, maxtemp_raw_BED)) max_temp_error(H_BED); + if (temp_bed.target > 0 && BEDCMP(mintemp_raw_BED, temp_bed.raw)) min_temp_error(H_BED); + #endif + + #if BOTH(HAS_HEATED_CHAMBER, THERMAL_PROTECTION_CHAMBER) + #define CHAMBERCMP(A,B) (TEMPDIR(CHAMBER) < 0 ? ((A)<(B)) : ((A)>(B))) + if (CHAMBERCMP(temp_chamber.raw, maxtemp_raw_CHAMBER)) max_temp_error(H_CHAMBER); + if (temp_chamber.target > 0 && CHAMBERCMP(mintemp_raw_CHAMBER, temp_chamber.raw)) min_temp_error(H_CHAMBER); + #endif + + #if BOTH(HAS_COOLER, THERMAL_PROTECTION_COOLER) + #define COOLERCMP(A,B) (TEMPDIR(COOLER) < 0 ? ((A)<(B)) : ((A)>(B))) + if (cutter.unitPower > 0 && COOLERCMP(temp_cooler.raw, maxtemp_raw_COOLER)) max_temp_error(H_COOLER); + if (COOLERCMP(mintemp_raw_COOLER, temp_cooler.raw)) min_temp_error(H_COOLER); + #endif +} // Temperature::updateTemperaturesFromRawValues /** * Initialize the temperature manager + * * The manager is implemented by periodic calls to manage_heater() + * + * - Init (and disable) SPI thermocouples like MAX6675 and MAX31865 + * - Disable RUMBA JTAG to accommodate a thermocouple extension + * - Read-enable thermistors with a read-enable pin + * - Init HEATER and COOLER pins for OUTPUT in OFF state + * - Init the FAN pins as PWM or OUTPUT + * - Init the SPI interface for SPI thermocouples + * - Init ADC according to the HAL + * - Set thermistor pins to analog inputs according to the HAL + * - Start the Temperature ISR timer + * - Init the AUTO FAN pins as PWM or OUTPUT + * - Wait 250ms for temperatures to settle + * - Init temp_range[], used for catching min/maxtemp */ void Temperature::init() { - TERN_(MAX6675_IS_MAX31865, max31865.begin(MAX31865_2WIRE)); // MAX31865_2WIRE, MAX31865_3WIRE, MAX31865_4WIRE + TERN_(PROBING_HEATERS_OFF, paused_for_probing = false); - #if EARLY_WATCHDOG - // Flag that the thermalManager should be running - if (inited) return; - inited = true; + #if BOTH(PIDTEMP, PID_EXTRUSION_SCALING) + last_e_position = 0; + #endif + + // 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); + #endif + #if TEMP_SENSOR_IS_ANY_MAX_TC(1) && PIN_EXISTS(TEMP_1_CS) + OUT_WRITE(TEMP_1_CS_PIN, HIGH); + #endif + + // Setup objects for library-based polling of MAX TCs + #if HAS_MAXTC_LIBRARIES + #define _MAX31865_WIRES(n) MAX31865_##n##WIRE + #define MAX31865_WIRES(n) _MAX31865_WIRES(n) + + #if TEMP_SENSOR_IS_MAX(0, 6675) && HAS_MAX6675_LIBRARY + max6675_0.begin(); + #elif TEMP_SENSOR_IS_MAX(0, 31855) && HAS_MAX31855_LIBRARY + max31855_0.begin(); + #elif TEMP_SENSOR_IS_MAX(0, 31865) + max31865_0.begin( + MAX31865_WIRES(MAX31865_SENSOR_WIRES_0) // MAX31865_2WIRE, MAX31865_3WIRE, MAX31865_4WIRE + OPTARG(LIB_INTERNAL_MAX31865, MAX31865_SENSOR_OHMS_0, MAX31865_CALIBRATION_OHMS_0) + ); + #if defined(LIB_INTERNAL_MAX31865) && ENABLED(MAX31865_50HZ_FILTER) + max31865_0.enable50HzFilter(1); + #endif + #endif + + #if TEMP_SENSOR_IS_MAX(1, 6675) && HAS_MAX6675_LIBRARY + max6675_1.begin(); + #elif TEMP_SENSOR_IS_MAX(1, 31855) && HAS_MAX31855_LIBRARY + max31855_1.begin(); + #elif TEMP_SENSOR_IS_MAX(1, 31865) + max31865_1.begin( + MAX31865_WIRES(MAX31865_SENSOR_WIRES_1) // MAX31865_2WIRE, MAX31865_3WIRE, MAX31865_4WIRE + OPTARG(LIB_INTERNAL_MAX31865, MAX31865_SENSOR_OHMS_1, MAX31865_CALIBRATION_OHMS_1) + ); + #if defined(LIB_INTERNAL_MAX31865) && ENABLED(MAX31865_50HZ_FILTER) + max31865_1.enable50HzFilter(1); + #endif + #endif + #undef MAX31865_WIRES + #undef _MAX31865_WIRES #endif #if MB(RUMBA) // Disable RUMBA JTAG in case the thermocouple extension is plugged on top of JTAG connector - #define _AD(N) ANY(HEATER_##N##_USES_AD595, HEATER_##N##_USES_AD8495) - #if _AD(0) || _AD(1) || _AD(2) || _AD(BED) || _AD(CHAMBER) + #define _AD(N) (TEMP_SENSOR_##N##_IS_AD595 || TEMP_SENSOR_##N##_IS_AD8495) + #if _AD(0) || _AD(1) || _AD(2) || _AD(BED) || _AD(CHAMBER) || _AD(REDUNDANT) MCUCR = _BV(JTD); MCUCR = _BV(JTD); #endif #endif // Thermistor activation by MCU pin - #if PIN_EXISTS(TEMP_0_TR_ENABLE_PIN) - OUT_WRITE(TEMP_0_TR_ENABLE_PIN, ENABLED(HEATER_0_USES_MAX6675)); - #endif - #if PIN_EXISTS(TEMP_1_TR_ENABLE_PIN) - OUT_WRITE(TEMP_1_TR_ENABLE_PIN, ENABLED(HEATER_1_USES_MAX6675)); + #if PIN_EXISTS(TEMP_0_TR_ENABLE) + OUT_WRITE(TEMP_0_TR_ENABLE_PIN, + #if TEMP_SENSOR_IS_ANY_MAX_TC(0) + 1 + #else + 0 + #endif + ); #endif - - #if BOTH(PIDTEMP, PID_EXTRUSION_SCALING) - last_e_position = 0; + #if PIN_EXISTS(TEMP_1_TR_ENABLE) + OUT_WRITE(TEMP_1_TR_ENABLE_PIN, + #if TEMP_SENSOR_IS_ANY_MAX_TC(1) + 1 + #else + 0 + #endif + ); #endif #if HAS_HEATER_0 - #ifdef ALFAWISE_UX0 + #ifdef BOARD_OPENDRAIN_MOSFETS OUT_WRITE_OD(HEATER_0_PIN, HEATER_0_INVERTING); #else OUT_WRITE(HEATER_0_PIN, HEATER_0_INVERTING); #endif #endif - #if HAS_HEATER_1 OUT_WRITE(HEATER_1_PIN, HEATER_1_INVERTING); #endif @@ -1744,7 +2197,7 @@ void Temperature::init() { #endif #if HAS_HEATED_BED - #ifdef ALFAWISE_UX0 + #ifdef BOARD_OPENDRAIN_MOSFETS OUT_WRITE_OD(HEATER_BED_PIN, HEATER_BED_INVERTING); #else OUT_WRITE(HEATER_BED_PIN, HEATER_BED_INVERTING); @@ -1755,6 +2208,10 @@ void Temperature::init() { OUT_WRITE(HEATER_CHAMBER_PIN, HEATER_CHAMBER_INVERTING); #endif + #if HAS_COOLER + OUT_WRITE(COOLER_PIN, COOLER_INVERTING); + #endif + #if HAS_FAN0 INIT_FAN_PIN(FAN_PIN); #endif @@ -1783,21 +2240,8 @@ void Temperature::init() { INIT_FAN_PIN(CONTROLLER_FAN_PIN); #endif - #if MAX6675_SEPARATE_SPI - - OUT_WRITE(SCK_PIN, LOW); - OUT_WRITE(MOSI_PIN, HIGH); - SET_INPUT_PULLUP(MISO_PIN); - - max6675_spi.init(); - - OUT_WRITE(SS_PIN, HIGH); - OUT_WRITE(MAX6675_SS_PIN, HIGH); - - #endif - - #if ENABLED(HEATER_1_USES_MAX6675) - OUT_WRITE(MAX6675_SS2_PIN, HIGH); + #if HAS_MAXTC_SW_SPI + max_tc_spi.init(); #endif HAL_adc_init(); @@ -1838,15 +2282,21 @@ void Temperature::init() { #if HAS_JOY_ADC_EN SET_INPUT_PULLUP(JOY_EN_PIN); #endif - #if HAS_HEATED_BED + #if HAS_TEMP_ADC_BED HAL_ANALOG_SELECT(TEMP_BED_PIN); #endif - #if HAS_TEMP_CHAMBER + #if HAS_TEMP_ADC_CHAMBER HAL_ANALOG_SELECT(TEMP_CHAMBER_PIN); #endif - #if HAS_TEMP_PROBE + #if HAS_TEMP_ADC_COOLER + HAL_ANALOG_SELECT(TEMP_COOLER_PIN); + #endif + #if HAS_TEMP_ADC_PROBE HAL_ANALOG_SELECT(TEMP_PROBE_PIN); #endif + #if HAS_TEMP_ADC_REDUNDANT + HAL_ANALOG_SELECT(TEMP_REDUNDANT_PIN); + #endif #if ENABLED(FILAMENT_WIDTH_SENSOR) HAL_ANALOG_SELECT(FILWIDTH_PIN); #endif @@ -1891,25 +2341,21 @@ void Temperature::init() { INIT_CHAMBER_AUTO_FAN_PIN(CHAMBER_AUTO_FAN_PIN); #endif - // Wait for temperature measurement to settle - delay(250); - #if HAS_HOTEND - #define _TEMP_MIN_E(NR) do{ \ - const int16_t tmin = _MAX(HEATER_ ##NR## _MINTEMP, TERN(HEATER_##NR##_USER_THERMISTOR, 0, (int16_t)pgm_read_word(&HEATER_ ##NR## _TEMPTABLE[HEATER_ ##NR## _SENSOR_MINTEMP_IND].celsius))); \ + const celsius_t tmin = _MAX(HEATER_##NR##_MINTEMP, TERN(TEMP_SENSOR_##NR##_IS_CUSTOM, 0, (int)pgm_read_word(&TEMPTABLE_##NR [TEMP_SENSOR_##NR##_MINTEMP_IND].celsius))); \ temp_range[NR].mintemp = tmin; \ while (analog_to_celsius_hotend(temp_range[NR].raw_min, NR) < tmin) \ temp_range[NR].raw_min += TEMPDIR(NR) * (OVERSAMPLENR); \ }while(0) #define _TEMP_MAX_E(NR) do{ \ - const int16_t tmax = _MIN(HEATER_ ##NR## _MAXTEMP, TERN(HEATER_##NR##_USER_THERMISTOR, 2000, (int16_t)pgm_read_word(&HEATER_ ##NR## _TEMPTABLE[HEATER_ ##NR## _SENSOR_MAXTEMP_IND].celsius) - 1)); \ + const celsius_t tmax = _MIN(HEATER_##NR##_MAXTEMP, TERN(TEMP_SENSOR_##NR##_IS_CUSTOM, 2000, (int)pgm_read_word(&TEMPTABLE_##NR [TEMP_SENSOR_##NR##_MAXTEMP_IND].celsius) - 1)); \ temp_range[NR].maxtemp = tmax; \ while (analog_to_celsius_hotend(temp_range[NR].raw_max, NR) > tmax) \ temp_range[NR].raw_max -= TEMPDIR(NR) * (OVERSAMPLENR); \ }while(0) - #define _MINMAX_TEST(N,M) (HOTENDS > N && THERMISTOR_HEATER_##N && THERMISTOR_HEATER_##N != 998 && THERMISTOR_HEATER_##N != 999 && defined(HEATER_##N##_##M##TEMP)) + #define _MINMAX_TEST(N,M) (HOTENDS > N && TEMP_SENSOR_##N > 0 && TEMP_SENSOR_##N != 998 && TEMP_SENSOR_##N != 999 && defined(HEATER_##N##_##M##TEMP)) #if _MINMAX_TEST(0, MIN) _TEMP_MIN_E(0); @@ -1959,63 +2405,39 @@ void Temperature::init() { #if _MINMAX_TEST(7, MAX) _TEMP_MAX_E(7); #endif - #endif // HAS_HOTEND #if HAS_HEATED_BED - #ifdef BED_MINTEMP - while (analog_to_celsius_bed(mintemp_raw_BED) < BED_MINTEMP) mintemp_raw_BED += TEMPDIR(BED) * (OVERSAMPLENR); - #endif - #ifdef BED_MAXTEMP - while (analog_to_celsius_bed(maxtemp_raw_BED) > BED_MAXTEMP) maxtemp_raw_BED -= TEMPDIR(BED) * (OVERSAMPLENR); - #endif - #endif // HAS_HEATED_BED + while (analog_to_celsius_bed(mintemp_raw_BED) < BED_MINTEMP) mintemp_raw_BED += TEMPDIR(BED) * (OVERSAMPLENR); + while (analog_to_celsius_bed(maxtemp_raw_BED) > BED_MAXTEMP) maxtemp_raw_BED -= TEMPDIR(BED) * (OVERSAMPLENR); + #endif #if HAS_HEATED_CHAMBER - #ifdef CHAMBER_MINTEMP - while (analog_to_celsius_chamber(mintemp_raw_CHAMBER) < CHAMBER_MINTEMP) mintemp_raw_CHAMBER += TEMPDIR(CHAMBER) * (OVERSAMPLENR); - #endif - #ifdef CHAMBER_MAXTEMP - while (analog_to_celsius_chamber(maxtemp_raw_CHAMBER) > CHAMBER_MAXTEMP) maxtemp_raw_CHAMBER -= TEMPDIR(CHAMBER) * (OVERSAMPLENR); - #endif + while (analog_to_celsius_chamber(mintemp_raw_CHAMBER) < CHAMBER_MINTEMP) mintemp_raw_CHAMBER += TEMPDIR(CHAMBER) * (OVERSAMPLENR); + while (analog_to_celsius_chamber(maxtemp_raw_CHAMBER) > CHAMBER_MAXTEMP) maxtemp_raw_CHAMBER -= TEMPDIR(CHAMBER) * (OVERSAMPLENR); #endif - TERN_(PROBING_HEATERS_OFF, paused = false); -} - -#if WATCH_HOTENDS - /** - * Start Heating Sanity Check for hotends that are below - * their target temperature by a configurable margin. - * This is called when the temperature is set. (M104, M109) - */ - void Temperature::start_watching_hotend(const uint8_t E_NAME) { - const uint8_t ee = HOTEND_INDEX; - watch_hotend[ee].restart(degHotend(ee), degTargetHotend(ee)); - } -#endif - -#if WATCH_BED - /** - * Start Heating Sanity Check for hotends that are below - * their target temperature by a configurable margin. - * This is called when the temperature is set. (M140, M190) - */ - void Temperature::start_watching_bed() { - watch_bed.restart(degBed(), degTargetBed()); - } -#endif + #if HAS_COOLER + while (analog_to_celsius_cooler(mintemp_raw_COOLER) > COOLER_MINTEMP) mintemp_raw_COOLER += TEMPDIR(COOLER) * (OVERSAMPLENR); + while (analog_to_celsius_cooler(maxtemp_raw_COOLER) < COOLER_MAXTEMP) maxtemp_raw_COOLER -= TEMPDIR(COOLER) * (OVERSAMPLENR); + #endif -#if WATCH_CHAMBER - /** - * Start Heating Sanity Check for chamber that is below - * its target temperature by a configurable margin. - * This is called when the temperature is set. (M141, M191) - */ - void Temperature::start_watching_chamber() { - watch_chamber.restart(degChamber(), degTargetChamber()); - } -#endif + #if HAS_TEMP_REDUNDANT + temp_redundant.target = &( + #if TEMP_SENSOR_REDUNDANT_TARGET == -5 && HAS_TEMP_COOLER + temp_cooler + #elif TEMP_SENSOR_REDUNDANT_TARGET == -4 && HAS_TEMP_PROBE + temp_probe + #elif TEMP_SENSOR_REDUNDANT_TARGET == -2 && HAS_TEMP_CHAMBER + temp_chamber + #elif TEMP_SENSOR_REDUNDANT_TARGET == -1 && HAS_TEMP_BED + temp_bed + #else + temp_hotend[TEMP_SENSOR_REDUNDANT_TARGET] + #endif + ); + #endif +} #if HAS_THERMAL_PROTECTION @@ -2031,7 +2453,7 @@ void Temperature::init() { * * TODO: Embed the last 3 parameters during init, if not less optimal */ - void Temperature::tr_state_machine_t::run(const float ¤t, const float &target, const heater_id_t heater_id, const uint16_t period_seconds, const uint16_t hysteresis_degc) { + void Temperature::tr_state_machine_t::run(const_celsius_float_t current, const_celsius_float_t target, const heater_id_t heater_id, const uint16_t period_seconds, const celsius_t hysteresis_degc) { #if HEATER_IDLE_HANDLER // Convert the given heater_id_t to an idle array index @@ -2053,7 +2475,7 @@ void Temperature::init() { , " ; Idle Timeout:", heater_idle[idle_index].timed_out #endif ); - //*/ + */ #if HEATER_IDLE_HANDLER // If the heater idle timeout expires, restart @@ -2116,10 +2538,9 @@ void Temperature::init() { void Temperature::disable_all_heaters() { + // Disable autotemp, unpause and reset everything TERN_(AUTOTEMP, planner.autotemp_enabled = false); - - // Unpause and reset everything - TERN_(PROBING_HEATERS_OFF, pause(false)); + TERN_(PROBING_HEATERS_OFF, pause_heaters(false)); #if HAS_HOTEND HOTEND_LOOP() { @@ -2144,11 +2565,17 @@ void Temperature::disable_all_heaters() { temp_chamber.soft_pwm_amount = 0; WRITE_HEATER_CHAMBER(LOW); #endif + + #if HAS_COOLER + setTargetCooler(0); + temp_cooler.soft_pwm_amount = 0; + WRITE_HEATER_COOLER(LOW); + #endif } #if ENABLED(PRINTJOB_TIMER_AUTOSTART) - bool Temperature::over_autostart_threshold() { + bool Temperature::auto_job_over_threshold() { #if HAS_HOTEND HOTEND_LOOP() if (degTargetHotend(e) > (EXTRUDE_MINTEMP) / 2) return true; #endif @@ -2156,8 +2583,8 @@ void Temperature::disable_all_heaters() { || TERN0(HAS_HEATED_CHAMBER, degTargetChamber() > CHAMBER_MINTEMP); } - void Temperature::check_timer_autostart(const bool can_start, const bool can_stop) { - if (over_autostart_threshold()) { + void Temperature::auto_job_check_timer(const bool can_start, const bool can_stop) { + if (auto_job_over_threshold()) { if (can_start) startOrResumeJob(); } else if (can_stop) { @@ -2166,14 +2593,13 @@ void Temperature::disable_all_heaters() { } } -#endif - +#endif // PRINTJOB_TIMER_AUTOSTART #if ENABLED(PROBING_HEATERS_OFF) - void Temperature::pause(const bool p) { - if (p != paused) { - paused = p; + void Temperature::pause_heaters(const bool p) { + if (p != paused_for_probing) { + paused_for_probing = p; if (p) { HOTEND_LOOP() heater_idle[e].expire(); // Timeout immediately TERN_(HAS_HEATED_BED, heater_idle[IDLE_INDEX_BED].expire()); // Timeout immediately @@ -2187,256 +2613,255 @@ void Temperature::disable_all_heaters() { #endif // PROBING_HEATERS_OFF -#if HAS_MAX6675 +#if EITHER(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) + singlenozzle_fan_speed[old_tool] = fan_speed[0]; + fan_speed[0] = singlenozzle_fan_speed[new_tool]; + #endif + #if ENABLED(SINGLENOZZLE_STANDBY_TEMP) + singlenozzle_temp[old_tool] = temp_hotend[0].target; + if (singlenozzle_temp[new_tool] && singlenozzle_temp[new_tool] != singlenozzle_temp[old_tool]) { + setTargetHotend(singlenozzle_temp[new_tool], 0); + TERN_(AUTOTEMP, planner.autotemp_update()); + set_heating_message(0); + (void)wait_for_hotend(0, false); // Wait for heating or cooling + } + #endif + } + +#endif // SINGLENOZZLE_STANDBY_TEMP || SINGLENOZZLE_STANDBY_FAN + +#if HAS_MAX_TC #ifndef THERMOCOUPLE_MAX_ERRORS #define THERMOCOUPLE_MAX_ERRORS 15 #endif - int Temperature::read_max6675( - #if COUNT_6675 > 1 - const uint8_t hindex - #endif - ) { - #if COUNT_6675 == 1 - constexpr uint8_t hindex = 0; + /** + * @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). + * + * @param hindex the hotend we're referencing (if MULTI_MAX_TC) + * @return integer representing the board's buffer, to be converted later if needed + */ + int16_t Temperature::read_max_tc(TERN_(HAS_MULTI_MAX_TC, const uint8_t hindex/*=0*/)) { + #define MAXTC_HEAT_INTERVAL 250UL + + #if HAS_MAX31855 + #define MAX_TC_ERROR_MASK 7 // D2-0: SCV, SCG, OC + #define MAX_TC_DISCARD_BITS 18 // Data D31-18; sign bit D31 + #define MAX_TC_SPEED_BITS 3 // ~1MHz + #elif HAS_MAX31865 + #define MAX_TC_ERROR_MASK 1 // D0 Bit on fault only + #define MAX_TC_DISCARD_BITS 1 // Data is in D15-D1 + #define MAX_TC_SPEED_BITS 3 // ~1MHz + #else // MAX6675 + #define MAX_TC_ERROR_MASK 3 // D2 only; 1 = open circuit + #define MAX_TC_DISCARD_BITS 3 // Data D15-D1 + #define MAX_TC_SPEED_BITS 2 // ~2MHz + #endif + + #if HAS_MULTI_MAX_TC + // Needed to return the correct temp when this is called between readings + static int16_t max_tc_temp_previous[MAX_TC_COUNT] = { 0 }; + #define THERMO_TEMP(I) max_tc_temp_previous[I] + #define THERMO_SEL(A,B) (hindex ? (B) : (A)) + #define MAXTC_CS_WRITE(V) do{ switch (hindex) { case 1: WRITE(TEMP_1_CS_PIN, V); break; default: WRITE(TEMP_0_CS_PIN, V); } }while(0) #else - // Needed to return the correct temp when this is called too soon - static uint16_t max6675_temp_previous[COUNT_6675] = { 0 }; + // When we have only 1 max tc, THERMO_SEL will pick the appropriate sensor + // variable, and MAXTC_*() macros will be hardcoded to the correct CS pin. + constexpr uint8_t hindex = 0; + #define THERMO_TEMP(I) max_tc_temp + #if TEMP_SENSOR_IS_ANY_MAX_TC(0) + #define THERMO_SEL(A,B) A + #define MAXTC_CS_WRITE(V) WRITE(TEMP_0_CS_PIN, V) + #else + #define THERMO_SEL(A,B) B + #define MAXTC_CS_WRITE(V) WRITE(TEMP_1_CS_PIN, V) + #endif #endif - static uint8_t max6675_errors[COUNT_6675] = { 0 }; - - #define MAX6675_HEAT_INTERVAL 250UL + static TERN(HAS_MAX31855, uint32_t, uint16_t) max_tc_temp = THERMO_SEL( + TEMP_SENSOR_0_MAX_TC_TMAX, + TEMP_SENSOR_1_MAX_TC_TMAX + ); - #if ENABLED(MAX6675_IS_MAX31855) - static uint32_t max6675_temp = 2000; - #define MAX6675_ERROR_MASK 7 - #define MAX6675_DISCARD_BITS 18 - #define MAX6675_SPEED_BITS 3 // (_BV(SPR1)) // clock ÷ 64 - #else - static uint16_t max6675_temp = 2000; - #define MAX6675_ERROR_MASK 4 - #define MAX6675_DISCARD_BITS 3 - #define MAX6675_SPEED_BITS 2 // (_BV(SPR0)) // clock ÷ 16 - #endif + static uint8_t max_tc_errors[MAX_TC_COUNT] = { 0 }; + static millis_t next_max_tc_ms[MAX_TC_COUNT] = { 0 }; // Return last-read value between readings - static millis_t next_max6675_ms[COUNT_6675] = { 0 }; millis_t ms = millis(); - if (PENDING(ms, next_max6675_ms[hindex])) - return int( - #if COUNT_6675 == 1 - max6675_temp - #else - max6675_temp_previous[hindex] // Need to return the correct previous value - #endif - ); + if (PENDING(ms, next_max_tc_ms[hindex])) + return (int16_t)THERMO_TEMP(hindex); - next_max6675_ms[hindex] = ms + MAX6675_HEAT_INTERVAL; + next_max_tc_ms[hindex] = ms + MAXTC_HEAT_INTERVAL; - #if ENABLED(MAX6675_IS_MAX31865) - max6675_temp = int(max31865.temperature(MAX31865_SENSOR_OHMS, MAX31865_CALIBRATION_OHMS)); - #endif + #if !HAS_MAXTC_LIBRARIES + max_tc_temp = 0; - // - // TODO: spiBegin, spiRec and spiInit doesn't work when soft spi is used. - // - #if !MAX6675_SEPARATE_SPI - spiBegin(); - spiInit(MAX6675_SPEED_BITS); - #endif + #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(MAX_TC_SPEED_BITS); + #endif - #if COUNT_6675 > 1 - #define WRITE_MAX6675(V) do{ switch (hindex) { case 1: WRITE(MAX6675_SS2_PIN, V); break; default: WRITE(MAX6675_SS_PIN, V); } }while(0) - #define SET_OUTPUT_MAX6675() do{ switch (hindex) { case 1: SET_OUTPUT(MAX6675_SS2_PIN); break; default: SET_OUTPUT(MAX6675_SS_PIN); } }while(0) - #elif ENABLED(HEATER_1_USES_MAX6675) - #define WRITE_MAX6675(V) WRITE(MAX6675_SS2_PIN, V) - #define SET_OUTPUT_MAX6675() SET_OUTPUT(MAX6675_SS2_PIN) - #else - #define WRITE_MAX6675(V) WRITE(MAX6675_SS_PIN, V) - #define SET_OUTPUT_MAX6675() SET_OUTPUT(MAX6675_SS_PIN) - #endif + MAXTC_CS_WRITE(LOW); // enable MAXTC + DELAY_NS(100); // Ensure 100ns delay - SET_OUTPUT_MAX6675(); - WRITE_MAX6675(LOW); // enable TT_MAX6675 + // 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 + } - DELAY_NS(100); // Ensure 100ns delay + MAXTC_CS_WRITE(HIGH); // disable MAXTC + #else + #if HAS_MAX6675_LIBRARY + MAX6675 &max6675ref = THERMO_SEL(max6675_0, max6675_1); + max_tc_temp = max6675ref.readRaw16(); + #endif - // Read a big-endian temperature value - max6675_temp = 0; - for (uint8_t i = sizeof(max6675_temp); i--;) { - max6675_temp |= ( - #if MAX6675_SEPARATE_SPI - max6675_spi.receive() - #else - spiRec() - #endif - ); - if (i > 0) max6675_temp <<= 8; // shift left if not the last byte - } + #if HAS_MAX31855_LIBRARY + MAX31855 &max855ref = THERMO_SEL(max31855_0, max31855_1); + max_tc_temp = max855ref.readRaw32(); + #endif + + #if HAS_MAX31865 + MAX31865 &max865ref = THERMO_SEL(max31865_0, max31865_1); + max_tc_temp = TERN(LIB_INTERNAL_MAX31865, max865ref.readRaw(), max865ref.readRTD_with_Fault()); + #endif + #endif - WRITE_MAX6675(HIGH); // disable TT_MAX6675 + // 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 max_temp_error() + if (max_tc_temp & MAX_TC_ERROR_MASK) { + max_tc_errors[hindex]++; - if (DISABLED(IGNORE_THERMOCOUPLE_ERRORS) && (max6675_temp & MAX6675_ERROR_MASK)) { - max6675_errors[hindex] += 1; - if (max6675_errors[hindex] > THERMOCOUPLE_MAX_ERRORS) { + if (max_tc_errors[hindex] > THERMOCOUPLE_MAX_ERRORS) { SERIAL_ERROR_START(); SERIAL_ECHOPGM("Temp measurement error! "); - #if MAX6675_ERROR_MASK == 7 - SERIAL_ECHOPGM("MAX31855 "); - if (max6675_temp & 1) + #if HAS_MAX31855 + SERIAL_ECHOPAIR("MAX31855 Fault: (", max_tc_temp & 0x7, ") >> "); + if (max_tc_temp & 0x1) SERIAL_ECHOLNPGM("Open Circuit"); - else if (max6675_temp & 2) + else if (max_tc_temp & 0x2) SERIAL_ECHOLNPGM("Short to GND"); - else if (max6675_temp & 4) + else if (max_tc_temp & 0x4) SERIAL_ECHOLNPGM("Short to VCC"); - #else - SERIAL_ECHOLNPGM("MAX6675"); + #elif HAS_MAX31865 + const uint8_t fault_31865 = max865ref.readFault(); + max865ref.clearFault(); + if (fault_31865) { + SERIAL_EOL(); + SERIAL_ECHOLNPAIR("\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 - // Thermocouple open - max6675_temp = 4 * ( - #if COUNT_6675 > 1 - hindex ? HEATER_1_MAX6675_TMAX : HEATER_0_MAX6675_TMAX - #else - TERN(HEATER_1_USES_MAX6675, HEATER_1_MAX6675_TMAX, HEATER_0_MAX6675_TMAX) - #endif - ); + // Set thermocouple above max temperature (TMAX) + max_tc_temp = THERMO_SEL(TEMP_SENSOR_0_MAX_TC_TMAX, TEMP_SENSOR_1_MAX_TC_TMAX) << (MAX_TC_DISCARD_BITS + 1); } - else - max6675_temp >>= MAX6675_DISCARD_BITS; } else { - max6675_temp >>= MAX6675_DISCARD_BITS; - max6675_errors[hindex] = 0; + max_tc_errors[hindex] = 0; // No error bit, reset error count } - #if ENABLED(MAX6675_IS_MAX31855) - if (max6675_temp & 0x00002000) max6675_temp |= 0xFFFFC000; // Support negative temperature - #endif + max_tc_temp >>= MAX_TC_DISCARD_BITS; - #if COUNT_6675 > 1 - max6675_temp_previous[hindex] = max6675_temp; + #if HAS_MAX31855 + // Support negative temperature for MAX38155 + if (max_tc_temp & 0x00002000) max_tc_temp |= 0xFFFFC000; #endif - return int(max6675_temp); + THERMO_TEMP(hindex) = max_tc_temp; + + return (int16_t)max_tc_temp; } -#endif // HAS_MAX6675 +#endif // HAS_MAX_TC /** * Update raw temperatures + * + * Called by ISR => readings_ready when new temperatures have been set by updateTemperaturesFromRawValues. + * Applies all the accumulators to the current raw temperatures. */ void Temperature::update_raw_temperatures() { - #if HAS_TEMP_ADC_0 && DISABLED(HEATER_0_USES_MAX6675) + #if HAS_TEMP_ADC_0 && !TEMP_SENSOR_0_IS_MAX_TC temp_hotend[0].update(); #endif - #if HAS_TEMP_ADC_1 - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - redundant_temperature_raw = temp_hotend[1].acc; - #elif DISABLED(HEATER_1_USES_MAX6675) - temp_hotend[1].update(); - #endif + #if HAS_TEMP_ADC_1 && !TEMP_SENSOR_1_IS_MAX_TC + temp_hotend[1].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_HEATED_BED, temp_bed.update()); - TERN_(HAS_TEMP_CHAMBER, temp_chamber.update()); - TERN_(HAS_TEMP_PROBE, temp_probe.update()); + #if HAS_TEMP_ADC_REDUNDANT && !TEMP_SENSOR_REDUNDANT_IS_MAX_TC + temp_redundant.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()); TERN_(HAS_JOY_ADC_X, joystick.x.update()); TERN_(HAS_JOY_ADC_Y, joystick.y.update()); TERN_(HAS_JOY_ADC_Z, joystick.z.update()); - - raw_temps_ready = true; } +/** + * Called by the Temperature ISR when all the ADCs have been processed. + * Reset all the ADC accumulators for another round of updates. + */ void Temperature::readings_ready() { - // Update the raw values if they've been read. Else we could be updating them during reading. - if (!raw_temps_ready) update_raw_temperatures(); + // Update raw values only if they're not already set. + if (!raw_temps_ready) { + update_raw_temperatures(); + raw_temps_ready = true; + } // Filament Sensor - can be read any time since IIR filtering is used TERN_(FILAMENT_WIDTH_SENSOR, filwidth.reading_ready()); #if HAS_HOTEND HOTEND_LOOP() temp_hotend[e].reset(); - TERN_(TEMP_SENSOR_1_AS_REDUNDANT, temp_hotend[1].reset()); #endif TERN_(HAS_HEATED_BED, temp_bed.reset()); TERN_(HAS_TEMP_CHAMBER, temp_chamber.reset()); TERN_(HAS_TEMP_PROBE, temp_probe.reset()); + TERN_(HAS_TEMP_COOLER, temp_cooler.reset()); + TERN_(HAS_TEMP_REDUNDANT, temp_redundant.reset()); TERN_(HAS_JOY_ADC_X, joystick.x.reset()); TERN_(HAS_JOY_ADC_Y, joystick.y.reset()); TERN_(HAS_JOY_ADC_Z, joystick.z.reset()); - - #if HAS_HOTEND - - static constexpr int8_t temp_dir[] = { - TERN(HEATER_0_USES_MAX6675, 0, TEMPDIR(0)) - #if HAS_MULTI_HOTEND - , TERN(HEATER_1_USES_MAX6675, 0, TEMPDIR(1)) - #if HOTENDS > 2 - #define _TEMPDIR(N) , TEMPDIR(N) - REPEAT_S(2, HOTENDS, _TEMPDIR) - #endif - #endif - }; - - LOOP_L_N(e, COUNT(temp_dir)) { - const int8_t tdir = temp_dir[e]; - if (tdir) { - const int16_t rawtemp = temp_hotend[e].raw * tdir; // normal direction, +rawtemp, else -rawtemp - const bool heater_on = (temp_hotend[e].target > 0 - || TERN0(PIDTEMP, temp_hotend[e].soft_pwm_amount) > 0 - ); - if (rawtemp > temp_range[e].raw_max * tdir) max_temp_error((heater_id_t)e); - if (heater_on && rawtemp < temp_range[e].raw_min * tdir && !is_preheating(e)) { - #ifdef MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED - if (++consecutive_low_temperature_error[e] >= MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED) - #endif - min_temp_error((heater_id_t)e); - } - #ifdef MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED - else - consecutive_low_temperature_error[e] = 0; - #endif - } - } - - #endif // HAS_HOTEND - - #if HAS_HEATED_BED - #if TEMPDIR(BED) < 0 - #define BEDCMP(A,B) ((A)<(B)) - #else - #define BEDCMP(A,B) ((A)>(B)) - #endif - const bool bed_on = (temp_bed.target > 0) || TERN0(PIDTEMPBED, temp_bed.soft_pwm_amount > 0); - if (BEDCMP(temp_bed.raw, maxtemp_raw_BED)) max_temp_error(H_BED); - if (bed_on && BEDCMP(mintemp_raw_BED, temp_bed.raw)) min_temp_error(H_BED); - #endif - - #if HAS_HEATED_CHAMBER - #if TEMPDIR(CHAMBER) < 0 - #define CHAMBERCMP(A,B) ((A)<(B)) - #else - #define CHAMBERCMP(A,B) ((A)>(B)) - #endif - const bool chamber_on = (temp_chamber.target > 0); - if (CHAMBERCMP(temp_chamber.raw, maxtemp_raw_CHAMBER)) max_temp_error(H_CHAMBER); - if (chamber_on && CHAMBERCMP(mintemp_raw_CHAMBER, temp_chamber.raw)) min_temp_error(H_CHAMBER); - #endif } /** @@ -2452,12 +2877,12 @@ void Temperature::readings_ready() { * - Step the babysteps value for each axis towards 0 * - For PINS_DEBUGGING, monitor and report endstop pins * - For ENDSTOP_INTERRUPTS_FEATURE check endstops if flagged - * - Call planner.tick to count down its "ignore" time + * - Call planner.isr to count down its "ignore" time */ HAL_TEMP_TIMER_ISR() { HAL_timer_isr_prologue(TEMP_TIMER_NUM); - Temperature::tick(); + Temperature::isr(); HAL_timer_isr_epilogue(TEMP_TIMER_NUM); } @@ -2496,7 +2921,7 @@ class SoftPWM { * - Endstop polling * - Planner clean buffer */ -void Temperature::tick() { +void Temperature::isr() { static int8_t temp_count = -1; static ADCSensorState adc_sensor_state = StartupDelay; @@ -2522,9 +2947,15 @@ void Temperature::tick() { static SoftPWM soft_pwm_chamber; #endif + #if HAS_COOLER + static SoftPWM soft_pwm_cooler; + #endif + + #define WRITE_FAN(n, v) WRITE(FAN##n##_PIN, (v) ^ FAN_INVERTING) + #if DISABLED(SLOW_PWM_HEATERS) - #if ANY(HAS_HOTEND, HAS_HEATED_BED, HAS_HEATED_CHAMBER, FAN_SOFT_PWM) + #if ANY(HAS_HOTEND, HAS_HEATED_BED, HAS_HEATED_CHAMBER, HAS_COOLER, FAN_SOFT_PWM) constexpr uint8_t pwm_mask = TERN0(SOFT_PWM_DITHER, _BV(SOFT_PWM_SCALE) - 1); #define _PWM_MOD(N,S,T) do{ \ const bool on = S.add(pwm_mask, T.soft_pwm_amount); \ @@ -2551,6 +2982,10 @@ void Temperature::tick() { _PWM_MOD(CHAMBER,soft_pwm_chamber,temp_chamber); #endif + #if HAS_COOLER + _PWM_MOD(COOLER,soft_pwm_cooler,temp_cooler); + #endif + #if ENABLED(FAN_SOFT_PWM) #define _FAN_PWM(N) do{ \ uint8_t &spcf = soft_pwm_count_fan[N]; \ @@ -2598,6 +3033,10 @@ void Temperature::tick() { _PWM_LOW(CHAMBER, soft_pwm_chamber); #endif + #if HAS_COOLER + _PWM_LOW(COOLER, soft_pwm_cooler); + #endif + #if ENABLED(FAN_SOFT_PWM) #if HAS_FAN0 if (soft_pwm_count_fan[0] <= pwm_count_tmp) WRITE_FAN(0, LOW); @@ -2664,6 +3103,10 @@ void Temperature::tick() { _SLOW_PWM(CHAMBER, soft_pwm_chamber, temp_chamber); #endif + #if HAS_COOLER + _SLOW_PWM(COOLER, soft_pwm_cooler, temp_cooler); + #endif + } // slow_pwm_count == 0 #if HAS_HOTEND @@ -2679,6 +3122,10 @@ void Temperature::tick() { _PWM_OFF(CHAMBER, soft_pwm_chamber); #endif + #if HAS_COOLER + _PWM_OFF(COOLER, soft_pwm_cooler, temp_cooler); + #endif + #if ENABLED(FAN_SOFT_PWM) if (pwm_count_tmp >= 127) { pwm_count_tmp = 0; @@ -2758,6 +3205,7 @@ void Temperature::tick() { #endif TERN_(HAS_HEATED_BED, soft_pwm_bed.dec()); TERN_(HAS_HEATED_CHAMBER, soft_pwm_chamber.dec()); + TERN_(HAS_COOLER, soft_pwm_cooler.dec()); } #endif // SLOW_PWM_HEATERS @@ -2815,21 +3263,31 @@ void Temperature::tick() { case MeasureTemp_0: ACCUMULATE_ADC(temp_hotend[0]); break; #endif - #if HAS_HEATED_BED + #if HAS_TEMP_ADC_BED case PrepareTemp_BED: HAL_START_ADC(TEMP_BED_PIN); break; case MeasureTemp_BED: ACCUMULATE_ADC(temp_bed); break; #endif - #if HAS_TEMP_CHAMBER + #if HAS_TEMP_ADC_CHAMBER case PrepareTemp_CHAMBER: HAL_START_ADC(TEMP_CHAMBER_PIN); break; case MeasureTemp_CHAMBER: ACCUMULATE_ADC(temp_chamber); break; #endif - #if HAS_TEMP_PROBE + #if HAS_TEMP_ADC_COOLER + case PrepareTemp_COOLER: HAL_START_ADC(TEMP_COOLER_PIN); break; + case MeasureTemp_COOLER: ACCUMULATE_ADC(temp_cooler); break; + #endif + + #if HAS_TEMP_ADC_PROBE case PrepareTemp_PROBE: HAL_START_ADC(TEMP_PROBE_PIN); break; case MeasureTemp_PROBE: ACCUMULATE_ADC(temp_probe); break; #endif + #if HAS_TEMP_ADC_REDUNDANT + case PrepareTemp_REDUNDANT: HAL_START_ADC(TEMP_REDUNDANT_PIN); break; + case MeasureTemp_REDUNDANT: ACCUMULATE_ADC(temp_redundant); break; + #endif + #if HAS_TEMP_ADC_1 case PrepareTemp_1: HAL_START_ADC(TEMP_1_PIN); break; case MeasureTemp_1: ACCUMULATE_ADC(temp_hotend[1]); break; @@ -2952,111 +3410,93 @@ void Temperature::tick() { // Poll endstops state, if required endstops.poll(); - // Periodically call the planner timer - planner.tick(); + // Periodically call the planner timer service routine + planner.isr(); } #if HAS_TEMP_SENSOR #include "../gcode/gcode.h" - static void print_heater_state(const float &c, const float &t - #if ENABLED(SHOW_TEMP_ADC_VALUES) - , const float r - #endif - , const heater_id_t e=INDEX_NONE + /** + * Print a single heater state in the form: + * Bed: " B:nnn.nn /nnn.nn" + * Chamber: " C:nnn.nn /nnn.nn" + * Probe: " P:nnn.nn /nnn.nn" + * Cooler: " L:nnn.nn /nnn.nn" + * Redundant: " R:nnn.nn /nnn.nn" + * Extruder: " T0:nnn.nn /nnn.nn" + * With ADC: " T0:nnn.nn /nnn.nn (nnn.nn)" + */ + static void print_heater_state(const heater_id_t e, const_celsius_float_t c, const_celsius_float_t t + OPTARG(SHOW_TEMP_ADC_VALUES, const float r) ) { char k; switch (e) { + default: + #if HAS_TEMP_HOTEND + k = 'T'; break; + #endif + #if HAS_TEMP_BED + case H_BED: k = 'B'; break; + #endif #if HAS_TEMP_CHAMBER case H_CHAMBER: k = 'C'; break; #endif #if HAS_TEMP_PROBE case H_PROBE: k = 'P'; break; #endif - #if HAS_TEMP_HOTEND - default: k = 'T'; break; - #if HAS_HEATED_BED - case H_BED: k = 'B'; break; - #endif - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - case H_REDUNDANT: k = 'R'; break; - #endif - #elif HAS_HEATED_BED - default: k = 'B'; break; + #if HAS_TEMP_COOLER + case H_COOLER: k = 'L'; break; + #endif + #if HAS_TEMP_REDUNDANT + case H_REDUNDANT: k = 'R'; break; #endif } - SERIAL_CHAR(' '); - SERIAL_CHAR(k); + SERIAL_CHAR(' ', k); #if HAS_MULTI_HOTEND if (e >= 0) SERIAL_CHAR('0' + e); #endif + #ifdef SERIAL_FLOAT_PRECISION + #define SFP _MIN(SERIAL_FLOAT_PRECISION, 2) + #else + #define SFP 2 + #endif SERIAL_CHAR(':'); - SERIAL_ECHO(c); - SERIAL_ECHOPAIR(" /" , t); + SERIAL_PRINT(c, SFP); + SERIAL_ECHOPGM(" /"); + SERIAL_PRINT(t, SFP); #if ENABLED(SHOW_TEMP_ADC_VALUES) - SERIAL_ECHOPAIR(" (", r * RECIPROCAL(OVERSAMPLENR)); + // Temperature MAX SPI boards do not have an OVERSAMPLENR defined + SERIAL_ECHOPAIR(" (", TERN(HAS_MAXTC_LIBRARIES, k == 'T', false) ? r : r * RECIPROCAL(OVERSAMPLENR)); SERIAL_CHAR(')'); #endif delay(2); } void Temperature::print_heater_states(const uint8_t target_extruder - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - , const bool include_r/*=false*/ - #endif + OPTARG(HAS_TEMP_REDUNDANT, const bool include_r/*=false*/) ) { #if HAS_TEMP_HOTEND - print_heater_state(degHotend(target_extruder), degTargetHotend(target_extruder) - #if ENABLED(SHOW_TEMP_ADC_VALUES) - , rawHotendTemp(target_extruder) - #endif - ); - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - if (include_r) print_heater_state(redundant_temperature, degTargetHotend(target_extruder) - #if ENABLED(SHOW_TEMP_ADC_VALUES) - , redundant_temperature_raw - #endif - , H_REDUNDANT - ); - #endif + print_heater_state(H_NONE, degHotend(target_extruder), degTargetHotend(target_extruder) OPTARG(SHOW_TEMP_ADC_VALUES, rawHotendTemp(target_extruder))); #endif #if HAS_HEATED_BED - print_heater_state(degBed(), degTargetBed() - #if ENABLED(SHOW_TEMP_ADC_VALUES) - , rawBedTemp() - #endif - , H_BED - ); + print_heater_state(H_BED, degBed(), degTargetBed() OPTARG(SHOW_TEMP_ADC_VALUES, rawBedTemp())); #endif #if HAS_TEMP_CHAMBER - print_heater_state(degChamber() - #if HAS_HEATED_CHAMBER - , degTargetChamber() - #else - , 0 - #endif - #if ENABLED(SHOW_TEMP_ADC_VALUES) - , rawChamberTemp() - #endif - , H_CHAMBER - ); - #endif // HAS_TEMP_CHAMBER + print_heater_state(H_CHAMBER, degChamber(), TERN0(HAS_HEATED_CHAMBER, degTargetChamber()) OPTARG(SHOW_TEMP_ADC_VALUES, rawChamberTemp())); + #endif + #if HAS_TEMP_COOLER + print_heater_state(H_COOLER, degCooler(), TERN0(HAS_COOLER, degTargetCooler()) OPTARG(SHOW_TEMP_ADC_VALUES, rawCoolerTemp())); + #endif #if HAS_TEMP_PROBE - print_heater_state(degProbe(), 0 - #if ENABLED(SHOW_TEMP_ADC_VALUES) - , rawProbeTemp() - #endif - , H_PROBE - ); - #endif // HAS_TEMP_PROBE + print_heater_state(H_PROBE, degProbe(), 0 OPTARG(SHOW_TEMP_ADC_VALUES, rawProbeTemp()) ); + #endif + #if HAS_TEMP_REDUNDANT + if (include_r) print_heater_state(H_REDUNDANT, degRedundant(), degRedundantTarget() OPTARG(SHOW_TEMP_ADC_VALUES, rawRedundantTemp())); + #endif #if HAS_MULTI_HOTEND - HOTEND_LOOP() print_heater_state(degHotend(e), degTargetHotend(e) - #if ENABLED(SHOW_TEMP_ADC_VALUES) - , rawHotendTemp(e) - #endif - , (heater_id_t)e - ); + HOTEND_LOOP() print_heater_state((heater_id_t)e, degHotend(e), degTargetHotend(e) OPTARG(SHOW_TEMP_ADC_VALUES, rawHotendTemp(e))); #endif SERIAL_ECHOPAIR(" @:", getHeaterPower((heater_id_t)target_extruder)); #if HAS_HEATED_BED @@ -3065,6 +3505,9 @@ void Temperature::tick() { #if HAS_HEATED_CHAMBER SERIAL_ECHOPAIR(" C@:", getHeaterPower(H_CHAMBER)); #endif + #if HAS_COOLER + SERIAL_ECHOPAIR(" C@:", getHeaterPower(H_COOLER)); + #endif #if HAS_MULTI_HOTEND HOTEND_LOOP() { SERIAL_ECHOPAIR(" @", e); @@ -3075,22 +3518,11 @@ void Temperature::tick() { } #if ENABLED(AUTO_REPORT_TEMPERATURES) + AutoReporter Temperature::auto_reporter; + void Temperature::AutoReportTemp::report() { print_heater_states(active_extruder); SERIAL_EOL(); } + #endif - uint8_t Temperature::auto_report_temp_interval; - millis_t Temperature::next_temp_report_ms; - - void Temperature::auto_report_temperatures() { - if (auto_report_temp_interval && ELAPSED(millis(), next_temp_report_ms)) { - next_temp_report_ms = millis() + 1000UL * auto_report_temp_interval; - PORT_REDIRECT(SERIAL_BOTH); - print_heater_states(active_extruder); - SERIAL_EOL(); - } - } - - #endif // AUTO_REPORT_TEMPERATURES - - #if HAS_HOTEND && HAS_DISPLAY + #if HAS_HOTEND && HAS_STATUS_MESSAGE void Temperature::set_heating_message(const uint8_t e) { const bool heating = isHeatingHotend(e); ui.status_printf_P(0, @@ -3114,11 +3546,8 @@ void Temperature::tick() { #endif bool Temperature::wait_for_hotend(const uint8_t target_extruder, const bool no_wait_for_cooling/*=true*/ - #if G26_CLICK_CAN_CANCEL - , const bool click_to_cancel/*=false*/ - #endif + OPTARG(G26_CLICK_CAN_CANCEL, const bool click_to_cancel/*=false*/) ) { - #if ENABLED(AUTOTEMP) REMEMBER(1, planner.autotemp_enabled, false); #endif @@ -3138,12 +3567,12 @@ void Temperature::tick() { #endif #if ENABLED(PRINTER_EVENT_LEDS) - const float start_temp = degHotend(target_extruder); + const celsius_float_t start_temp = degHotend(target_extruder); printerEventLEDs.onHotendHeatingStart(); #endif bool wants_to_cool = false; - float target_temp = -1.0, old_temp = 9999.0; + celsius_float_t target_temp = -1.0, old_temp = 9999.0; millis_t now, next_temp_ms = 0, next_cool_check_ms = 0; wait_for_heatup = true; do { @@ -3173,7 +3602,7 @@ void Temperature::tick() { idle(); gcode.reset_stepper_timeout(); // Keep steppers powered - const float temp = degHotend(target_extruder); + const celsius_float_t temp = degHotend(target_extruder); #if ENABLED(PRINTER_EVENT_LEDS) // Gradually change LED strip from violet to red as nozzle heats up @@ -3182,7 +3611,7 @@ void Temperature::tick() { #if TEMP_RESIDENCY_TIME > 0 - const float temp_diff = ABS(target_temp - temp); + const celsius_float_t temp_diff = ABS(target_temp - temp); if (!residency_start_ms) { // Start the TEMP_RESIDENCY_TIME timer when we reach target temp for the first time. @@ -3204,7 +3633,7 @@ void Temperature::tick() { // if the temperature did not drop at least MIN_COOLING_SLOPE_DEG if (!next_cool_check_ms || ELAPSED(now, next_cool_check_ms)) { if (old_temp - temp < float(MIN_COOLING_SLOPE_DEG)) break; - next_cool_check_ms = now + 1000UL * MIN_COOLING_SLOPE_TIME; + next_cool_check_ms = now + SEC_TO_MS(MIN_COOLING_SLOPE_TIME); old_temp = temp; } } @@ -3212,7 +3641,7 @@ void Temperature::tick() { #if G26_CLICK_CAN_CANCEL if (click_to_cancel && ui.use_click()) { wait_for_heatup = false; - ui.quick_feedback(); + TERN_(HAS_LCD_MENU, ui.quick_feedback()); } #endif @@ -3234,6 +3663,17 @@ void Temperature::tick() { return false; } + #if ENABLED(WAIT_FOR_HOTEND) + void Temperature::wait_for_hotend_heating(const uint8_t target_extruder) { + if (isHeatingHotend(target_extruder)) { + SERIAL_ECHOLNPGM("Wait for hotend heating..."); + LCD_MESSAGEPGM(MSG_HEATING); + wait_for_hotend(target_extruder); + ui.reset_status(); + } + } + #endif + #endif // HAS_TEMP_HOTEND #if HAS_HEATED_BED @@ -3246,9 +3686,7 @@ void Temperature::tick() { #endif bool Temperature::wait_for_bed(const bool no_wait_for_cooling/*=true*/ - #if G26_CLICK_CAN_CANCEL - , const bool click_to_cancel/*=false*/ - #endif + OPTARG(G26_CLICK_CAN_CANCEL, const bool click_to_cancel/*=false*/) ) { #if TEMP_BED_RESIDENCY_TIME > 0 millis_t residency_start_ms = 0; @@ -3265,12 +3703,12 @@ void Temperature::tick() { #endif #if ENABLED(PRINTER_EVENT_LEDS) - const float start_temp = degBed(); + const celsius_float_t start_temp = degBed(); printerEventLEDs.onBedHeatingStart(); #endif bool wants_to_cool = false; - float target_temp = -1, old_temp = 9999; + celsius_float_t target_temp = -1, old_temp = 9999; millis_t now, next_temp_ms = 0, next_cool_check_ms = 0; wait_for_heatup = true; do { @@ -3300,7 +3738,7 @@ void Temperature::tick() { idle(); gcode.reset_stepper_timeout(); // Keep steppers powered - const float temp = degBed(); + const celsius_float_t temp = degBed(); #if ENABLED(PRINTER_EVENT_LEDS) // Gradually change LED strip from blue to violet as bed heats up @@ -3309,7 +3747,7 @@ void Temperature::tick() { #if TEMP_BED_RESIDENCY_TIME > 0 - const float temp_diff = ABS(target_temp - temp); + const celsius_float_t temp_diff = ABS(target_temp - temp); if (!residency_start_ms) { // Start the TEMP_BED_RESIDENCY_TIME timer when we reach target temp for the first time. @@ -3329,7 +3767,7 @@ void Temperature::tick() { // 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 (old_temp - temp < float(MIN_COOLING_SLOPE_DEG_BED)) break; - next_cool_check_ms = now + 1000UL * MIN_COOLING_SLOPE_TIME_BED; + next_cool_check_ms = now + SEC_TO_MS(MIN_COOLING_SLOPE_TIME_BED); old_temp = temp; } } @@ -3337,7 +3775,7 @@ void Temperature::tick() { #if G26_CLICK_CAN_CANCEL if (click_to_cancel && ui.use_click()) { wait_for_heatup = false; - ui.quick_feedback(); + TERN_(HAS_LCD_MENU, ui.quick_feedback()); } #endif @@ -3376,10 +3814,10 @@ void Temperature::tick() { #define MIN_DELTA_SLOPE_TIME_PROBE 600 #endif - bool Temperature::wait_for_probe(const float target_temp, bool no_wait_for_cooling/*=true*/) { + bool Temperature::wait_for_probe(const celsius_t target_temp, bool no_wait_for_cooling/*=true*/) { - const bool wants_to_cool = isProbeAboveTemp(target_temp); - const bool will_wait = !(wants_to_cool && no_wait_for_cooling); + const bool wants_to_cool = isProbeAboveTemp(target_temp), + will_wait = !(wants_to_cool && no_wait_for_cooling); if (will_wait) SERIAL_ECHOLNPAIR("Waiting for probe to ", (wants_to_cool ? PSTR("cool down") : PSTR("heat up")), " to ", target_temp, " degrees."); @@ -3413,7 +3851,7 @@ void Temperature::tick() { SERIAL_ECHOLNPGM("Timed out waiting for probe temperature."); break; } - next_delta_check_ms = now + 1000UL * MIN_DELTA_SLOPE_TIME_PROBE; + next_delta_check_ms = now + SEC_TO_MS(MIN_DELTA_SLOPE_TIME_PROBE); old_temp = temp; } @@ -3518,7 +3956,7 @@ void Temperature::tick() { // 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 (old_temp - temp < float(MIN_COOLING_SLOPE_DEG_CHAMBER)) break; - next_cool_check_ms = now + 1000UL * MIN_COOLING_SLOPE_TIME_CHAMBER; + next_cool_check_ms = now + SEC_TO_MS(MIN_COOLING_SLOPE_TIME_CHAMBER); old_temp = temp; } } @@ -3535,4 +3973,103 @@ void Temperature::tick() { #endif // HAS_HEATED_CHAMBER + #if HAS_COOLER + + #ifndef MIN_COOLING_SLOPE_DEG_COOLER + #define MIN_COOLING_SLOPE_DEG_COOLER 1.50 + #endif + #ifndef MIN_COOLING_SLOPE_TIME_COOLER + #define MIN_COOLING_SLOPE_TIME_COOLER 120 + #endif + + bool Temperature::wait_for_cooler(const bool no_wait_for_cooling/*=true*/) { + + #if TEMP_COOLER_RESIDENCY_TIME > 0 + millis_t residency_start_ms = 0; + bool first_loop = true; + // Loop until the temperature has stabilized + #define TEMP_COOLER_CONDITIONS (!residency_start_ms || PENDING(now, residency_start_ms + SEC_TO_MS(TEMP_COOLER_RESIDENCY_TIME))) + #else + // Loop until the temperature is very close target + #define TEMP_COOLER_CONDITIONS (wants_to_cool ? isLaserHeating() : isLaserCooling()) + #endif + + #if DISABLED(BUSY_WHILE_HEATING) && ENABLED(HOST_KEEPALIVE_FEATURE) + KEEPALIVE_STATE(NOT_BUSY); + #endif + + bool wants_to_cool = false; + float target_temp = -1, previous_temp = 9999; + millis_t now, next_temp_ms = 0, next_cooling_check_ms = 0; + wait_for_heatup = true; + do { + // Target temperature might be changed during the loop + if (target_temp != degTargetCooler()) { + wants_to_cool = isLaserHeating(); + target_temp = degTargetCooler(); + + // Exit if S, continue if S, R, or R + if (no_wait_for_cooling && wants_to_cool) break; + } + + now = millis(); + if (ELAPSED(now, next_temp_ms)) { // Print Temp Reading every 1 second while heating up. + next_temp_ms = now + 1000UL; + print_heater_states(active_extruder); + #if TEMP_COOLER_RESIDENCY_TIME > 0 + SERIAL_ECHOPGM(" W:"); + if (residency_start_ms) + SERIAL_ECHO(long((SEC_TO_MS(TEMP_COOLER_RESIDENCY_TIME) - (now - residency_start_ms)) / 1000UL)); + else + SERIAL_CHAR('?'); + #endif + SERIAL_EOL(); + } + + idle(); + gcode.reset_stepper_timeout(); // Keep steppers powered + + const celsius_float_t current_temp = degCooler(); + + #if TEMP_COOLER_RESIDENCY_TIME > 0 + + const celsius_float_t temp_diff = ABS(target_temp - temp); + + if (!residency_start_ms) { + // Start the TEMP_COOLER_RESIDENCY_TIME timer when we reach target temp for the first time. + if (temp_diff < TEMP_COOLER_WINDOW) + residency_start_ms = now + (first_loop ? SEC_TO_MS(TEMP_COOLER_RESIDENCY_TIME) / 3 : 0); + } + else if (temp_diff > TEMP_COOLER_HYSTERESIS) { + // Restart the timer whenever the temperature falls outside the hysteresis. + residency_start_ms = now; + } + + first_loop = false; + #endif // TEMP_COOLER_RESIDENCY_TIME > 0 + + 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_cooling_check_ms || ELAPSED(now, next_cooling_check_ms)) { + if (previous_temp - current_temp < float(MIN_COOLING_SLOPE_DEG_COOLER)) break; + next_cooling_check_ms = now + SEC_TO_MS(MIN_COOLING_SLOPE_TIME_COOLER); + previous_temp = current_temp; + } + } + + } while (wait_for_heatup && TEMP_COOLER_CONDITIONS); + + // Prevent a wait-forever situation if R is misused i.e. M191 R0 + if (wait_for_heatup) { + wait_for_heatup = false; + ui.reset_status(); + return true; + } + + return false; + } + + #endif // HAS_COOLER + #endif // HAS_TEMP_SENSOR diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index 57b0fecbcc99..c8d085133cb3 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -33,6 +33,10 @@ #include "../feature/power.h" #endif +#if ENABLED(AUTO_REPORT_TEMPERATURES) + #include "../libs/autoreport.h" +#endif + #ifndef SOFT_PWM_SCALE #define SOFT_PWM_SCALE 0 #endif @@ -40,10 +44,10 @@ #define HOTEND_INDEX TERN(HAS_MULTI_HOTEND, e, 0) #define E_NAME TERN_(HAS_MULTI_HOTEND, e) -// Heater identifiers. Positive values are hotends. Negative values are other heaters. +// Element identifiers. Positive values are hotends. Negative values are other heaters or coolers. typedef enum : int8_t { - INDEX_NONE = -5, - H_PROBE, H_REDUNDANT, H_CHAMBER, H_BED, + H_NONE = -6, + H_COOLER, H_PROBE, H_REDUNDANT, H_CHAMBER, H_BED, H_E0, H_E1, H_E2, H_E3, H_E4, H_E5, H_E6, H_E7 } heater_id_t; @@ -69,7 +73,7 @@ hotend_pid_t; typedef IF<(LPQ_MAX_LEN > 255), uint16_t, uint8_t>::type lpq_ptr_t; #endif -#define PID_PARAM(F,H) _PID_##F(TERN(PID_PARAMS_PER_HOTEND, H, 0)) +#define PID_PARAM(F,H) _PID_##F(TERN(PID_PARAMS_PER_HOTEND, H, 0 & H)) // Always use 'H' to suppress warning #define _PID_Kp(H) TERN(PIDTEMP, Temperature::temp_hotend[H].pid.Kp, NAN) #define _PID_Ki(H) TERN(PIDTEMP, Temperature::temp_hotend[H].pid.Ki, NAN) #define _PID_Kd(H) TERN(PIDTEMP, Temperature::temp_hotend[H].pid.Kd, NAN) @@ -89,15 +93,21 @@ enum ADCSensorState : char { #if HAS_TEMP_ADC_0 PrepareTemp_0, MeasureTemp_0, #endif - #if HAS_HEATED_BED + #if HAS_TEMP_ADC_BED PrepareTemp_BED, MeasureTemp_BED, #endif - #if HAS_TEMP_CHAMBER + #if HAS_TEMP_ADC_CHAMBER PrepareTemp_CHAMBER, MeasureTemp_CHAMBER, #endif - #if HAS_TEMP_PROBE + #if HAS_TEMP_ADC_COOLER + PrepareTemp_COOLER, MeasureTemp_COOLER, + #endif + #if HAS_TEMP_ADC_PROBE PrepareTemp_PROBE, MeasureTemp_PROBE, #endif + #if HAS_TEMP_ADC_REDUNDANT + PrepareTemp_REDUNDANT, MeasureTemp_REDUNDANT, + #endif #if HAS_TEMP_ADC_1 PrepareTemp_1, MeasureTemp_1, #endif @@ -164,7 +174,7 @@ enum ADCSensorState : char { #define unscalePID_d(d) ( float(d) * PID_dT ) #endif -#if BOTH(HAS_LCD_MENU, G26_MESH_VALIDATION) +#if ENABLED(G26_MESH_VALIDATION) && EITHER(HAS_LCD_MENU, EXTENSIBLE_UI) #define G26_CLICK_CAN_CANCEL 1 #endif @@ -172,15 +182,22 @@ enum ADCSensorState : char { typedef struct TempInfo { uint16_t acc; int16_t raw; - float celsius; + celsius_float_t celsius; inline void reset() { acc = 0; } inline void sample(const uint16_t s) { acc += s; } inline void update() { raw = acc; } } temp_info_t; +#if HAS_TEMP_REDUNDANT + // A redundant temperature sensor + typedef struct RedundantTempInfo : public TempInfo { + temp_info_t* target; + } redundant_temp_info_t; +#endif + // A PWM heater with temperature sensor typedef struct HeaterInfo : public TempInfo { - int16_t target; + celsius_t target; uint8_t soft_pwm_amount; } heater_info_t; @@ -206,22 +223,31 @@ struct PIDHeaterInfo : public HeaterInfo { typedef temp_info_t probe_info_t; #endif #if HAS_HEATED_CHAMBER - typedef heater_info_t chamber_info_t; + #if ENABLED(PIDTEMPCHAMBER) + typedef struct PIDHeaterInfo chamber_info_t; + #else + typedef heater_info_t chamber_info_t; + #endif #elif HAS_TEMP_CHAMBER typedef temp_info_t chamber_info_t; #endif +#if EITHER(HAS_COOLER, HAS_TEMP_COOLER) + typedef heater_info_t cooler_info_t; +#endif // Heater watch handling template struct HeaterWatch { - uint16_t target; + celsius_t target; millis_t next_ms; inline bool elapsed(const millis_t &ms) { return next_ms && ELAPSED(ms, next_ms); } inline bool elapsed() { return elapsed(millis()); } - inline void restart(const int16_t curr, const int16_t tgt) { + inline bool check(const celsius_t curr) { return curr >= target; } + + inline void restart(const celsius_t curr, const celsius_t tgt) { if (tgt) { - const int16_t newtarget = curr + INCREASE; + const celsius_t newtarget = curr + INCREASE; if (newtarget < tgt - HYSTERESIS - 1) { target = newtarget; next_ms = millis() + SEC_TO_MS(PERIOD); @@ -241,11 +267,14 @@ struct HeaterWatch { #if WATCH_CHAMBER typedef struct HeaterWatch chamber_watch_t; #endif +#if WATCH_COOLER + typedef struct HeaterWatch cooler_watch_t; +#endif // Temperature sensor read value ranges typedef struct { int16_t raw_min, raw_max; } raw_range_t; -typedef struct { int16_t mintemp, maxtemp; } celsius_range_t; -typedef struct { int16_t raw_min, raw_max, mintemp, maxtemp; } temp_range_t; +typedef struct { celsius_t mintemp, maxtemp; } celsius_range_t; +typedef struct { int16_t raw_min, raw_max; celsius_t mintemp, maxtemp; } temp_range_t; #define THERMISTOR_ABS_ZERO_C -273.15f // bbbbrrrrr cold ! #define THERMISTOR_RESISTANCE_NOMINAL_C 25.0f // mmmmm comfortable @@ -253,33 +282,39 @@ typedef struct { int16_t raw_min, raw_max, mintemp, maxtemp; } temp_range_t; #if HAS_USER_THERMISTORS enum CustomThermistorIndex : uint8_t { - #if ENABLED(HEATER_0_USER_THERMISTOR) + #if TEMP_SENSOR_0_IS_CUSTOM CTI_HOTEND_0, #endif - #if ENABLED(HEATER_1_USER_THERMISTOR) + #if TEMP_SENSOR_1_IS_CUSTOM CTI_HOTEND_1, #endif - #if ENABLED(HEATER_2_USER_THERMISTOR) + #if TEMP_SENSOR_2_IS_CUSTOM CTI_HOTEND_2, #endif - #if ENABLED(HEATER_3_USER_THERMISTOR) + #if TEMP_SENSOR_3_IS_CUSTOM CTI_HOTEND_3, #endif - #if ENABLED(HEATER_4_USER_THERMISTOR) + #if TEMP_SENSOR_4_IS_CUSTOM CTI_HOTEND_4, #endif - #if ENABLED(HEATER_5_USER_THERMISTOR) + #if TEMP_SENSOR_5_IS_CUSTOM CTI_HOTEND_5, #endif - #if ENABLED(HEATER_BED_USER_THERMISTOR) + #if TEMP_SENSOR_BED_IS_CUSTOM CTI_BED, #endif - #if ENABLED(HEATER_PROBE_USER_THERMISTOR) + #if TEMP_SENSOR_PROBE_IS_CUSTOM CTI_PROBE, #endif - #if ENABLED(HEATER_CHAMBER_USER_THERMISTOR) + #if TEMP_SENSOR_CHAMBER_IS_CUSTOM CTI_CHAMBER, #endif + #if TEMP_SENSOR_COOLER_IS_CUSTOM + CTI_COOLER, + #endif + #if TEMP_SENSOR_REDUNDANT_IS_CUSTOM + CTI_REDUNDANT, + #endif USER_THERMISTORS }; @@ -301,16 +336,35 @@ class Temperature { public: #if HAS_HOTEND - #define HOTEND_TEMPS (HOTENDS + ENABLED(TEMP_SENSOR_1_AS_REDUNDANT)) - static hotend_info_t temp_hotend[HOTEND_TEMPS]; - static const uint16_t heater_maxtemp[HOTENDS]; + static hotend_info_t temp_hotend[HOTENDS]; + static const celsius_t hotend_maxtemp[HOTENDS]; + static inline celsius_t hotend_max_target(const uint8_t e) { return hotend_maxtemp[e] - (HOTEND_OVERSHOOT); } + #endif + #if HAS_HEATED_BED + static bed_info_t temp_bed; + #endif + #if HAS_TEMP_PROBE + static probe_info_t temp_probe; + #endif + #if HAS_TEMP_CHAMBER + static chamber_info_t temp_chamber; + #endif + #if HAS_TEMP_COOLER + static cooler_info_t temp_cooler; + #endif + #if HAS_TEMP_REDUNDANT + static redundant_temp_info_t temp_redundant; #endif - TERN_(HAS_HEATED_BED, static bed_info_t temp_bed); - TERN_(HAS_TEMP_PROBE, static probe_info_t temp_probe); - TERN_(HAS_TEMP_CHAMBER, static chamber_info_t temp_chamber); - TERN_(AUTO_POWER_E_FANS, static uint8_t autofan_speed[HOTENDS]); - TERN_(AUTO_POWER_CHAMBER_FAN, static uint8_t chamberfan_speed); + #if ENABLED(AUTO_POWER_E_FANS) + static uint8_t autofan_speed[HOTENDS]; + #endif + #if ENABLED(AUTO_POWER_CHAMBER_FAN) + static uint8_t chamberfan_speed; + #endif + #if ENABLED(AUTO_POWER_COOLER_FAN) + static uint8_t coolerfan_speed; + #endif #if ENABLED(FAN_SOFT_PWM) static uint8_t soft_pwm_amount_fan[FAN_COUNT], @@ -319,21 +373,27 @@ class Temperature { #if ENABLED(PREVENT_COLD_EXTRUSION) static bool allow_cold_extrude; - static int16_t extrude_min_temp; - FORCE_INLINE static bool tooCold(const int16_t temp) { return allow_cold_extrude ? false : temp < extrude_min_temp - (TEMP_WINDOW); } - FORCE_INLINE static bool tooColdToExtrude(const uint8_t E_NAME) { - return tooCold(degHotend(HOTEND_INDEX)); - } - FORCE_INLINE static bool targetTooColdToExtrude(const uint8_t E_NAME) { - return tooCold(degTargetHotend(HOTEND_INDEX)); - } + static celsius_t extrude_min_temp; + static inline bool tooCold(const celsius_t temp) { return allow_cold_extrude ? false : temp < extrude_min_temp - (TEMP_WINDOW); } + static inline bool tooColdToExtrude(const uint8_t E_NAME) { return tooCold(wholeDegHotend(HOTEND_INDEX)); } + static inline bool targetTooColdToExtrude(const uint8_t E_NAME) { return tooCold(degTargetHotend(HOTEND_INDEX)); } #else - FORCE_INLINE static bool tooColdToExtrude(const uint8_t) { return false; } - FORCE_INLINE static bool targetTooColdToExtrude(const uint8_t) { return false; } + static inline bool tooColdToExtrude(const uint8_t) { return false; } + static inline bool targetTooColdToExtrude(const uint8_t) { return false; } #endif - FORCE_INLINE static bool hotEnoughToExtrude(const uint8_t e) { return !tooColdToExtrude(e); } - FORCE_INLINE static bool targetHotEnoughToExtrude(const uint8_t e) { return !targetTooColdToExtrude(e); } + static inline bool hotEnoughToExtrude(const uint8_t e) { return !tooColdToExtrude(e); } + static inline bool targetHotEnoughToExtrude(const uint8_t e) { return !targetTooColdToExtrude(e); } + + #if EITHER(SINGLENOZZLE_STANDBY_TEMP, SINGLENOZZLE_STANDBY_FAN) + #if ENABLED(SINGLENOZZLE_STANDBY_TEMP) + static celsius_t singlenozzle_temp[EXTRUDERS]; + #endif + #if ENABLED(SINGLENOZZLE_STANDBY_FAN) + static uint8_t singlenozzle_fan_speed[EXTRUDERS]; + #endif + static void singlenozzle_change(const uint8_t old_tool, const uint8_t new_tool); + #endif #if HEATER_IDLE_HANDLER @@ -348,39 +408,41 @@ class Temperature { } heater_idle_t; // Indices and size for the heater_idle array - #define _ENUM_FOR_E(N) IDLE_INDEX_E##N, - enum IdleIndex : uint8_t { - REPEAT(HOTENDS, _ENUM_FOR_E) - #if ENABLED(HAS_HEATED_BED) - IDLE_INDEX_BED, - #endif - NR_HEATER_IDLE + enum IdleIndex : int8_t { + _II = -1 + + #define _IDLE_INDEX_E(N) ,IDLE_INDEX_E##N + REPEAT(HOTENDS, _IDLE_INDEX_E) + #undef _IDLE_INDEX_E + + OPTARG(HAS_HEATED_BED, IDLE_INDEX_BED) + + , NR_HEATER_IDLE }; - #undef _ENUM_FOR_E // Convert the given heater_id_t to idle array index static inline IdleIndex idle_index_for_id(const int8_t heater_id) { - #if HAS_HEATED_BED - if (heater_id == H_BED) return IDLE_INDEX_BED; - #endif + TERN_(HAS_HEATED_BED, if (heater_id == H_BED) return IDLE_INDEX_BED); return (IdleIndex)_MAX(heater_id, 0); } static heater_idle_t heater_idle[NR_HEATER_IDLE]; - #endif - - private: + #endif // HEATER_IDLE_TIMER - TERN_(EARLY_WATCHDOG, static bool inited); // If temperature controller is running + #if HAS_ADC_BUTTONS + static uint32_t current_ADCKey_raw; + static uint16_t ADCKey_count; + #endif - static volatile bool raw_temps_ready; + #if ENABLED(PID_EXTRUSION_SCALING) + static int16_t lpq_len; + #endif - TERN_(WATCH_HOTENDS, static hotend_watch_t watch_hotend[HOTENDS]); + private: - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - static uint16_t redundant_temperature_raw; - static float redundant_temperature; + #if ENABLED(WATCH_HOTENDS) + static hotend_watch_t watch_hotend[HOTENDS]; #endif #if ENABLED(PID_EXTRUSION_SCALING) @@ -388,50 +450,51 @@ class Temperature { static lpq_ptr_t lpq_ptr; #endif - TERN_(HAS_HOTEND, static temp_range_t temp_range[HOTENDS]); + #if HAS_HOTEND + static temp_range_t temp_range[HOTENDS]; + #endif #if HAS_HEATED_BED - TERN_(WATCH_BED, static bed_watch_t watch_bed); - TERN(PIDTEMPBED,,static millis_t next_bed_check_ms); - #ifdef BED_MINTEMP - static int16_t mintemp_raw_BED; - #endif - #ifdef BED_MAXTEMP - static int16_t maxtemp_raw_BED; + #if ENABLED(WATCH_BED) + static bed_watch_t watch_bed; #endif + IF_DISABLED(PIDTEMPBED, static millis_t next_bed_check_ms); + static int16_t mintemp_raw_BED, maxtemp_raw_BED; #endif #if HAS_HEATED_CHAMBER - TERN_(WATCH_CHAMBER, static chamber_watch_t watch_chamber); - static millis_t next_chamber_check_ms; - #ifdef CHAMBER_MINTEMP - static int16_t mintemp_raw_CHAMBER; + #if ENABLED(WATCH_CHAMBER) + static chamber_watch_t watch_chamber; #endif - #ifdef CHAMBER_MAXTEMP - static int16_t maxtemp_raw_CHAMBER; + TERN(PIDTEMPCHAMBER,,static millis_t next_chamber_check_ms); + static int16_t mintemp_raw_CHAMBER, maxtemp_raw_CHAMBER; + #endif + + #if HAS_COOLER + #if ENABLED(WATCH_COOLER) + static cooler_watch_t watch_cooler; #endif + static millis_t next_cooler_check_ms, cooler_fan_flush_ms; + static int16_t mintemp_raw_COOLER, maxtemp_raw_COOLER; #endif - #ifdef MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED + #if MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED > 1 static uint8_t consecutive_low_temperature_error[HOTENDS]; #endif - #ifdef MILLISECONDS_PREHEAT_TIME + #if MILLISECONDS_PREHEAT_TIME > 0 static millis_t preheat_end_time[HOTENDS]; #endif - TERN_(HAS_AUTO_FAN, static millis_t next_auto_fan_check_ms); - - TERN_(PROBING_HEATERS_OFF, static bool paused); - - public: - #if HAS_ADC_BUTTONS - static uint32_t current_ADCKey_raw; - static uint16_t ADCKey_count; + #if HAS_AUTO_FAN + static millis_t next_auto_fan_check_ms; #endif - TERN_(PID_EXTRUSION_SCALING, static int16_t lpq_len); + #if ENABLED(PROBING_HEATERS_OFF) + static bool paused_for_probing; + #endif + public: /** * Instance Methods */ @@ -446,26 +509,26 @@ class Temperature { static user_thermistor_t user_thermistor[USER_THERMISTORS]; static void log_user_thermistor(const uint8_t t_index, const bool eprom=false); static void reset_user_thermistors(); - static float user_thermistor_to_deg_c(const uint8_t t_index, const int raw); - static bool set_pull_up_res(int8_t t_index, float value) { + static celsius_float_t user_thermistor_to_deg_c(const uint8_t t_index, const int16_t raw); + static inline bool set_pull_up_res(int8_t t_index, float value) { //if (!WITHIN(t_index, 0, USER_THERMISTORS - 1)) return false; if (!WITHIN(value, 1, 1000000)) return false; user_thermistor[t_index].series_res = value; return true; } - static bool set_res25(int8_t t_index, float value) { + static inline bool set_res25(int8_t t_index, float value) { if (!WITHIN(value, 1, 10000000)) return false; user_thermistor[t_index].res_25 = value; user_thermistor[t_index].pre_calc = true; return true; } - static bool set_beta(int8_t t_index, float value) { + static inline bool set_beta(int8_t t_index, float value) { if (!WITHIN(value, 1, 1000000)) return false; user_thermistor[t_index].beta = value; user_thermistor[t_index].pre_calc = true; return true; } - static bool set_sh_coeff(int8_t t_index, float value) { + static inline bool set_sh_coeff(int8_t t_index, float value) { if (!WITHIN(value, -0.01f, 0.01f)) return false; user_thermistor[t_index].sh_c_coeff = value; user_thermistor[t_index].pre_calc = true; @@ -474,17 +537,22 @@ class Temperature { #endif #if HAS_HOTEND - static float analog_to_celsius_hotend(const int raw, const uint8_t e); + static celsius_float_t analog_to_celsius_hotend(const int16_t raw, const uint8_t e); #endif - #if HAS_HEATED_BED - static float analog_to_celsius_bed(const int raw); + static celsius_float_t analog_to_celsius_bed(const int16_t raw); #endif #if HAS_TEMP_PROBE - static float analog_to_celsius_probe(const int raw); + static celsius_float_t analog_to_celsius_probe(const int16_t raw); #endif #if HAS_TEMP_CHAMBER - static float analog_to_celsius_chamber(const int raw); + static celsius_float_t analog_to_celsius_chamber(const int16_t raw); + #endif + #if HAS_TEMP_COOLER + static celsius_float_t analog_to_celsius_cooler(const int16_t raw); + #endif + #if HAS_TEMP_REDUNDANT + static celsius_float_t analog_to_celsius_redundant(const int16_t raw); #endif #if HAS_FAN @@ -492,10 +560,10 @@ class Temperature { static uint8_t fan_speed[FAN_COUNT]; #define FANS_LOOP(I) LOOP_L_N(I, FAN_COUNT) - static void set_fan_speed(const uint8_t target, const uint16_t speed); + static void set_fan_speed(const uint8_t fan, const uint16_t speed); #if ENABLED(REPORT_FAN_CHANGE) - static void report_fan_speed(const uint8_t target); + static void report_fan_speed(const uint8_t fan); #endif #if EITHER(PROBING_FANS_OFF, ADVANCED_PAUSE_FANS_PAUSE) @@ -503,22 +571,27 @@ class Temperature { static uint8_t saved_fan_speed[FAN_COUNT]; #endif - static constexpr inline uint8_t fanPercent(const uint8_t speed) { return ui8_to_percent(speed); } - - TERN_(ADAPTIVE_FAN_SLOWING, static uint8_t fan_speed_scaler[FAN_COUNT]); + #if ENABLED(ADAPTIVE_FAN_SLOWING) + static uint8_t fan_speed_scaler[FAN_COUNT]; + #endif - static inline uint8_t scaledFanSpeed(const uint8_t target, const uint8_t fs) { - UNUSED(target); // Potentially unused! - return (fs * uint16_t(TERN(ADAPTIVE_FAN_SLOWING, fan_speed_scaler[target], 128))) >> 7; + static inline uint8_t scaledFanSpeed(const uint8_t fan, const uint8_t fs) { + UNUSED(fan); // Potentially unused! + return (fs * uint16_t(TERN(ADAPTIVE_FAN_SLOWING, fan_speed_scaler[fan], 128))) >> 7; } - static inline uint8_t scaledFanSpeed(const uint8_t target) { - return scaledFanSpeed(target, fan_speed[target]); + static inline uint8_t scaledFanSpeed(const uint8_t fan) { + return scaledFanSpeed(fan, fan_speed[fan]); } + static constexpr inline uint8_t pwmToPercent(const uint8_t speed) { return ui8_to_percent(speed); } + static inline uint8_t fanSpeedPercent(const uint8_t fan) { return ui8_to_percent(fan_speed[fan]); } + static inline uint8_t scaledFanSpeedPercent(const uint8_t fan) { return ui8_to_percent(scaledFanSpeed(fan)); } + #if ENABLED(EXTRA_FAN_SPEED) - static uint8_t old_fan_speed[FAN_COUNT], new_fan_speed[FAN_COUNT]; - static void set_temp_fan_speed(const uint8_t fan, const uint16_t tmp_temp); + typedef struct { uint8_t saved, speed; } extra_fan_t; + static extra_fan_t extra_fan_speed[FAN_COUNT]; + 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) @@ -536,8 +609,8 @@ class Temperature { /** * Called from the Temperature ISR */ + static void isr(); static void readings_ready(); - static void tick(); /** * Call periodically to manage heaters @@ -547,14 +620,14 @@ class Temperature { /** * Preheating hotends */ - #ifdef MILLISECONDS_PREHEAT_TIME - static bool is_preheating(const uint8_t E_NAME) { + #if MILLISECONDS_PREHEAT_TIME > 0 + static inline bool is_preheating(const uint8_t E_NAME) { return preheat_end_time[HOTEND_INDEX] && PENDING(millis(), preheat_end_time[HOTEND_INDEX]); } - static void start_preheat_time(const uint8_t E_NAME) { + static inline void start_preheat_time(const uint8_t E_NAME) { preheat_end_time[HOTEND_INDEX] = millis() + MILLISECONDS_PREHEAT_TIME; } - static void reset_preheat_time(const uint8_t E_NAME) { + static inline void reset_preheat_time(const uint8_t E_NAME) { preheat_end_time[HOTEND_INDEX] = 0; } #else @@ -565,63 +638,71 @@ class Temperature { //inline so that there is no performance decrease. //deg=degreeCelsius - FORCE_INLINE static float degHotend(const uint8_t E_NAME) { + static inline celsius_float_t degHotend(const uint8_t E_NAME) { return TERN0(HAS_HOTEND, temp_hotend[HOTEND_INDEX].celsius); } + static inline celsius_t wholeDegHotend(const uint8_t E_NAME) { + return TERN0(HAS_HOTEND, static_cast(temp_hotend[HOTEND_INDEX].celsius + 0.5f)); + } + #if ENABLED(SHOW_TEMP_ADC_VALUES) - FORCE_INLINE static int16_t rawHotendTemp(const uint8_t E_NAME) { + static inline int16_t rawHotendTemp(const uint8_t E_NAME) { return TERN0(HAS_HOTEND, temp_hotend[HOTEND_INDEX].raw); } #endif - FORCE_INLINE static int16_t degTargetHotend(const uint8_t E_NAME) { + static inline celsius_t degTargetHotend(const uint8_t E_NAME) { return TERN0(HAS_HOTEND, temp_hotend[HOTEND_INDEX].target); } - #if WATCH_HOTENDS - static void start_watching_hotend(const uint8_t e=0); - #else - static inline void start_watching_hotend(const uint8_t=0) {} - #endif - #if HAS_HOTEND - static void setTargetHotend(const int16_t celsius, const uint8_t E_NAME) { + static void setTargetHotend(const celsius_t celsius, const uint8_t E_NAME) { const uint8_t ee = HOTEND_INDEX; - #ifdef MILLISECONDS_PREHEAT_TIME + #if MILLISECONDS_PREHEAT_TIME > 0 if (celsius == 0) reset_preheat_time(ee); else if (temp_hotend[ee].target == 0) start_preheat_time(ee); #endif TERN_(AUTO_POWER_CONTROL, if (celsius) powerManager.power_on()); - temp_hotend[ee].target = _MIN(celsius, temp_range[ee].maxtemp - HOTEND_OVERSHOOT); + temp_hotend[ee].target = _MIN(celsius, hotend_max_target(ee)); start_watching_hotend(ee); } - FORCE_INLINE static bool isHeatingHotend(const uint8_t E_NAME) { + static inline bool isHeatingHotend(const uint8_t E_NAME) { return temp_hotend[HOTEND_INDEX].target > temp_hotend[HOTEND_INDEX].celsius; } - FORCE_INLINE static bool isCoolingHotend(const uint8_t E_NAME) { + static inline bool isCoolingHotend(const uint8_t E_NAME) { return temp_hotend[HOTEND_INDEX].target < temp_hotend[HOTEND_INDEX].celsius; } #if HAS_TEMP_HOTEND static bool wait_for_hotend(const uint8_t target_extruder, const bool no_wait_for_cooling=true - #if G26_CLICK_CAN_CANCEL - , const bool click_to_cancel=false - #endif + OPTARG(G26_CLICK_CAN_CANCEL, const bool click_to_cancel=false) ); + + #if ENABLED(WAIT_FOR_HOTEND) + static void wait_for_hotend_heating(const uint8_t target_extruder); + #endif #endif - FORCE_INLINE static bool still_heating(const uint8_t e) { - return degTargetHotend(e) > TEMP_HYSTERESIS && ABS(degHotend(e) - degTargetHotend(e)) > TEMP_HYSTERESIS; + static inline bool still_heating(const uint8_t e) { + return degTargetHotend(e) > TEMP_HYSTERESIS && ABS(wholeDegHotend(e) - degTargetHotend(e)) > TEMP_HYSTERESIS; + } + + static inline bool degHotendNear(const uint8_t e, const celsius_t temp) { + return ABS(wholeDegHotend(e) - temp) < (TEMP_HYSTERESIS); } - FORCE_INLINE static bool degHotendNear(const uint8_t e, const float &temp) { - return ABS(degHotend(e) - temp) < (TEMP_HYSTERESIS); + // Start watching a Hotend to make sure it's really heating up + static inline void start_watching_hotend(const uint8_t E_NAME) { + UNUSED(HOTEND_INDEX); + #if WATCH_HOTENDS + watch_hotend[HOTEND_INDEX].restart(degHotend(HOTEND_INDEX), degTargetHotend(HOTEND_INDEX)); + #endif } #endif // HAS_HOTEND @@ -629,93 +710,102 @@ class Temperature { #if HAS_HEATED_BED #if ENABLED(SHOW_TEMP_ADC_VALUES) - FORCE_INLINE static int16_t rawBedTemp() { return temp_bed.raw; } + static inline int16_t rawBedTemp() { return temp_bed.raw; } #endif - FORCE_INLINE static float degBed() { return temp_bed.celsius; } - FORCE_INLINE static int16_t degTargetBed() { return temp_bed.target; } - FORCE_INLINE static bool isHeatingBed() { return temp_bed.target > temp_bed.celsius; } - FORCE_INLINE static bool isCoolingBed() { return temp_bed.target < temp_bed.celsius; } + static inline celsius_float_t degBed() { return temp_bed.celsius; } + static inline celsius_t wholeDegBed() { return static_cast(degBed() + 0.5f); } + static inline celsius_t degTargetBed() { return temp_bed.target; } + static inline bool isHeatingBed() { return temp_bed.target > temp_bed.celsius; } + static inline bool isCoolingBed() { return temp_bed.target < temp_bed.celsius; } - #if WATCH_BED - static void start_watching_bed(); - #else - static inline void start_watching_bed() {} - #endif + // Start watching the Bed to make sure it's really heating up + static inline void start_watching_bed() { TERN_(WATCH_BED, watch_bed.restart(degBed(), degTargetBed())); } - static void setTargetBed(const int16_t celsius) { + static void setTargetBed(const celsius_t celsius) { TERN_(AUTO_POWER_CONTROL, if (celsius) powerManager.power_on()); - temp_bed.target = - #ifdef BED_MAX_TARGET - _MIN(celsius, BED_MAX_TARGET) - #else - celsius - #endif - ; + temp_bed.target = _MIN(celsius, BED_MAX_TARGET); start_watching_bed(); } static bool wait_for_bed(const bool no_wait_for_cooling=true - #if G26_CLICK_CAN_CANCEL - , const bool click_to_cancel=false - #endif + OPTARG(G26_CLICK_CAN_CANCEL, const bool click_to_cancel=false) ); static void wait_for_bed_heating(); - FORCE_INLINE static bool degBedNear(const float &temp) { - return ABS(degBed() - temp) < (TEMP_BED_HYSTERESIS); + static inline bool degBedNear(const celsius_t temp) { + return ABS(wholeDegBed() - temp) < (TEMP_BED_HYSTERESIS); } #endif // HAS_HEATED_BED #if HAS_TEMP_PROBE #if ENABLED(SHOW_TEMP_ADC_VALUES) - FORCE_INLINE static int16_t rawProbeTemp() { return temp_probe.raw; } + static inline int16_t rawProbeTemp() { return temp_probe.raw; } #endif - FORCE_INLINE static float degProbe() { return temp_probe.celsius; } - FORCE_INLINE static bool isProbeBelowTemp(const float target_temp) { return temp_probe.celsius < target_temp; } - FORCE_INLINE static bool isProbeAboveTemp(const float target_temp) { return temp_probe.celsius > target_temp; } - static bool wait_for_probe(const float target_temp, bool no_wait_for_cooling=true); - #endif - - #if WATCH_PROBE - static void start_watching_probe(); - #else - static inline void start_watching_probe() {} + static inline celsius_float_t degProbe() { return temp_probe.celsius; } + static inline celsius_t wholeDegProbe() { return static_cast(degProbe() + 0.5f); } + static inline bool isProbeBelowTemp(const celsius_t target_temp) { return wholeDegProbe() < target_temp; } + static inline bool isProbeAboveTemp(const celsius_t target_temp) { return wholeDegProbe() > target_temp; } + static bool wait_for_probe(const celsius_t target_temp, bool no_wait_for_cooling=true); #endif #if HAS_TEMP_CHAMBER #if ENABLED(SHOW_TEMP_ADC_VALUES) - FORCE_INLINE static int16_t rawChamberTemp() { return temp_chamber.raw; } + static inline int16_t rawChamberTemp() { return temp_chamber.raw; } #endif - FORCE_INLINE static float degChamber() { return temp_chamber.celsius; } + static inline celsius_float_t degChamber() { return temp_chamber.celsius; } + static inline celsius_t wholeDegChamber() { return static_cast(degChamber() + 0.5f); } #if HAS_HEATED_CHAMBER - FORCE_INLINE static int16_t degTargetChamber() { return temp_chamber.target; } - FORCE_INLINE static bool isHeatingChamber() { return temp_chamber.target > temp_chamber.celsius; } - FORCE_INLINE static bool isCoolingChamber() { return temp_chamber.target < temp_chamber.celsius; } - + static inline celsius_t degTargetChamber() { return temp_chamber.target; } + static inline bool isHeatingChamber() { return temp_chamber.target > temp_chamber.celsius; } + static inline bool isCoolingChamber() { return temp_chamber.target < temp_chamber.celsius; } static bool wait_for_chamber(const bool no_wait_for_cooling=true); #endif - #endif // HAS_TEMP_CHAMBER - - #if WATCH_CHAMBER - static void start_watching_chamber(); - #else - static inline void start_watching_chamber() {} #endif #if HAS_HEATED_CHAMBER - static void setTargetChamber(const int16_t celsius) { - temp_chamber.target = - #ifdef CHAMBER_MAXTEMP - _MIN(celsius, CHAMBER_MAXTEMP - 10) - #else - celsius - #endif - ; + static void setTargetChamber(const celsius_t celsius) { + temp_chamber.target = _MIN(celsius, CHAMBER_MAX_TARGET); start_watching_chamber(); } - #endif // HAS_HEATED_CHAMBER + // Start watching the Chamber to make sure it's really heating up + static inline void start_watching_chamber() { TERN_(WATCH_CHAMBER, watch_chamber.restart(degChamber(), degTargetChamber())); } + #endif + + #if HAS_TEMP_COOLER + #if ENABLED(SHOW_TEMP_ADC_VALUES) + static inline int16_t rawCoolerTemp() { return temp_cooler.raw; } + #endif + static inline celsius_float_t degCooler() { return temp_cooler.celsius; } + static inline celsius_t wholeDegCooler() { return static_cast(temp_cooler.celsius + 0.5f); } + #if HAS_COOLER + static inline celsius_t degTargetCooler() { return temp_cooler.target; } + static inline bool isLaserHeating() { return temp_cooler.target > temp_cooler.celsius; } + static inline bool isLaserCooling() { return temp_cooler.target < temp_cooler.celsius; } + static bool wait_for_cooler(const bool no_wait_for_cooling=true); + #endif + #endif + + #if HAS_TEMP_REDUNDANT + #if ENABLED(SHOW_TEMP_ADC_VALUES) + static inline int16_t rawRedundantTemp() { return temp_redundant.raw; } + static inline int16_t rawRedundanTargetTemp() { return (*temp_redundant.target).raw; } + #endif + static inline celsius_float_t degRedundant() { return temp_redundant.celsius; } + static inline celsius_float_t degRedundantTarget() { return (*temp_redundant.target).celsius; } + static inline celsius_t wholeDegRedundant() { return static_cast(temp_redundant.celsius + 0.5f); } + static inline celsius_t wholeDegRedundantTarget() { return static_cast((*temp_redundant.target).celsius + 0.5f); } + #endif + + #if HAS_COOLER + static inline void setTargetCooler(const celsius_t celsius) { + temp_cooler.target = constrain(celsius, COOLER_MIN_TARGET, COOLER_MAX_TARGET); + start_watching_cooler(); + } + // Start watching the Cooler to make sure it's really cooling down + static inline void start_watching_cooler() { TERN_(WATCH_COOLER, watch_cooler.restart(degCooler(), degTargetCooler())); } + #endif /** * The software PWM power for a heater @@ -731,15 +821,20 @@ class Temperature { /** * Methods to check if heaters are enabled, indicating an active job */ - static bool over_autostart_threshold(); - static void check_timer_autostart(const bool can_start, const bool can_stop); + static bool auto_job_over_threshold(); + static void auto_job_check_timer(const bool can_start, const bool can_stop); #endif /** * Perform auto-tuning for hotend or bed in response to M303 */ #if HAS_PID_HEATING - static void PID_autotune(const float &target, const heater_id_t heater_id, const int8_t ncycles, const bool set_result=false); + + #if ANY(PID_DEBUG, PID_BED_DEBUG, PID_CHAMBER_DEBUG) + static bool pid_debug_flag; + #endif + + 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; @@ -751,7 +846,7 @@ class Temperature { * Update the temp manager when PID values change */ #if ENABLED(PIDTEMP) - FORCE_INLINE static void updatePID() { + static inline void updatePID() { TERN_(PID_EXTRUSION_SCALING, last_e_position = 0); } #endif @@ -759,19 +854,18 @@ class Temperature { #endif #if ENABLED(PROBING_HEATERS_OFF) - static void pause(const bool p); - FORCE_INLINE static bool is_paused() { return paused; } + static void pause_heaters(const bool p); #endif #if HEATER_IDLE_HANDLER - static void reset_hotend_idle_timer(const uint8_t E_NAME) { + static inline void reset_hotend_idle_timer(const uint8_t E_NAME) { heater_idle[HOTEND_INDEX].reset(); start_watching_hotend(HOTEND_INDEX); } #if HAS_HEATED_BED - static void reset_bed_idle_timer() { + static inline void reset_bed_idle_timer() { heater_idle[IDLE_INDEX_BED].reset(); start_watching_bed(); } @@ -781,87 +875,88 @@ class Temperature { #if HAS_TEMP_SENSOR static void print_heater_states(const uint8_t target_extruder - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - , const bool include_r=false - #endif + OPTARG(HAS_TEMP_REDUNDANT, const bool include_r=false) ); #if ENABLED(AUTO_REPORT_TEMPERATURES) - static uint8_t auto_report_temp_interval; - static millis_t next_temp_report_ms; - static void auto_report_temperatures(); - static inline void set_auto_report_interval(uint8_t v) { - NOMORE(v, 60); - auto_report_temp_interval = v; - next_temp_report_ms = millis() + 1000UL * v; - } + struct AutoReportTemp { static void report(); }; + static AutoReporter auto_reporter; #endif #endif - TERN_(HAS_DISPLAY, static void set_heating_message(const uint8_t e)); + #if HAS_HOTEND && HAS_STATUS_MESSAGE + static void set_heating_message(const uint8_t e); + #else + static inline void set_heating_message(const uint8_t) {} + #endif #if HAS_LCD_MENU && HAS_TEMPERATURE - static void lcd_preheat(const int16_t e, const int8_t indh, const int8_t indb); + static void lcd_preheat(const uint8_t e, const int8_t indh, const int8_t indb); #endif private: + + // Reading raw temperatures and converting to Celsius when ready + static volatile bool raw_temps_ready; static void update_raw_temperatures(); static void updateTemperaturesFromRawValues(); + static inline bool updateTemperaturesIfReady() { + if (!raw_temps_ready) return false; + updateTemperaturesFromRawValues(); + raw_temps_ready = false; + return true; + } - #define HAS_MAX6675 EITHER(HEATER_0_USES_MAX6675, HEATER_1_USES_MAX6675) - #if HAS_MAX6675 - #define COUNT_6675 1 + BOTH(HEATER_0_USES_MAX6675, HEATER_1_USES_MAX6675) - #if COUNT_6675 > 1 - #define READ_MAX6675(N) read_max6675(N) + // MAX Thermocouples + #if HAS_MAX_TC + #define MAX_TC_COUNT COUNT_ENABLED(TEMP_SENSOR_0_IS_MAX_TC, TEMP_SENSOR_1_IS_MAX_TC, TEMP_SENSOR_REDUNDANT_IS_MAX_TC) + #if MAX_TC_COUNT > 1 + #define HAS_MULTI_MAX_TC 1 + #define READ_MAX_TC(N) read_max_tc(N) #else - #define READ_MAX6675(N) read_max6675() + #define READ_MAX_TC(N) read_max_tc() #endif - static int read_max6675( - #if COUNT_6675 > 1 - const uint8_t hindex=0 - #endif - ); + static int16_t read_max_tc(TERN_(HAS_MULTI_MAX_TC, const uint8_t hindex=0)); #endif static void checkExtruderAutoFans(); - static float get_pid_output_hotend(const uint8_t e); - - TERN_(PIDTEMPBED, static float get_pid_output_bed()); - - TERN_(HAS_HEATED_CHAMBER, static float get_pid_output_chamber()); + #if HAS_HOTEND + static float get_pid_output_hotend(const uint8_t e); + #endif + #if ENABLED(PIDTEMPBED) + static float get_pid_output_bed(); + #endif + #if ENABLED(PIDTEMPCHAMBER) + static float get_pid_output_chamber(); + #endif static void _temp_error(const heater_id_t e, PGM_P const serial_msg, PGM_P const lcd_msg); static void min_temp_error(const heater_id_t e); static void max_temp_error(const heater_id_t e); - #define HAS_THERMAL_PROTECTION ANY(THERMAL_PROTECTION_HOTENDS, THERMAL_PROTECTION_CHAMBER, HAS_THERMALLY_PROTECTED_BED) + #define HAS_THERMAL_PROTECTION ANY(THERMAL_PROTECTION_HOTENDS, THERMAL_PROTECTION_CHAMBER, HAS_THERMALLY_PROTECTED_BED, THERMAL_PROTECTION_COOLER) #if HAS_THERMAL_PROTECTION // Indices and size for the tr_state_machine array. One for each protected heater. - #define _ENUM_FOR_E(N) RUNAWAY_IND_E##N, - enum RunawayIndex : uint8_t { + enum RunawayIndex : int8_t { + _RI = -1 #if ENABLED(THERMAL_PROTECTION_HOTENDS) - REPEAT(HOTENDS, _ENUM_FOR_E) - #endif - #if ENABLED(HAS_THERMALLY_PROTECTED_BED) - RUNAWAY_IND_BED, + #define _RUNAWAY_IND_E(N) ,RUNAWAY_IND_E##N + REPEAT(HOTENDS, _RUNAWAY_IND_E) + #undef _RUNAWAY_IND_E #endif - #if ENABLED(THERMAL_PROTECTION_CHAMBER) - RUNAWAY_IND_CHAMBER, - #endif - NR_HEATER_RUNAWAY + OPTARG(HAS_THERMALLY_PROTECTED_BED, RUNAWAY_IND_BED) + OPTARG(THERMAL_PROTECTION_CHAMBER, RUNAWAY_IND_CHAMBER) + OPTARG(THERMAL_PROTECTION_COOLER, RUNAWAY_IND_COOLER) + , NR_HEATER_RUNAWAY }; - #undef _ENUM_FOR_E // Convert the given heater_id_t to runaway state array index static inline RunawayIndex runaway_index_for_id(const int8_t heater_id) { - #if HAS_THERMALLY_PROTECTED_CHAMBER - if (heater_id == H_CHAMBER) return RUNAWAY_IND_CHAMBER; - #endif - #if HAS_THERMALLY_PROTECTED_BED - if (heater_id == H_BED) return RUNAWAY_IND_BED; - #endif + TERN_(HAS_THERMALLY_PROTECTED_CHAMBER, if (heater_id == H_CHAMBER) return RUNAWAY_IND_CHAMBER); + TERN_(HAS_THERMALLY_PROTECTED_CHAMBER, if (heater_id == H_COOLER) return RUNAWAY_IND_COOLER); + TERN_(HAS_THERMALLY_PROTECTED_BED, if (heater_id == H_BED) return RUNAWAY_IND_BED); return (RunawayIndex)_MAX(heater_id, 0); } @@ -871,7 +966,7 @@ class Temperature { millis_t timer = 0; TRState state = TRInactive; float running_temp; - void run(const float ¤t, const float &target, const heater_id_t heater_id, const uint16_t period_seconds, const uint16_t hysteresis_degc); + void run(const_celsius_float_t current, const_celsius_float_t target, const heater_id_t heater_id, const uint16_t period_seconds, const celsius_t hysteresis_degc); } tr_state_machine_t; static tr_state_machine_t tr_state_machine[NR_HEATER_RUNAWAY]; diff --git a/Marlin/src/module/thermistor/thermistor_1.h b/Marlin/src/module/thermistor/thermistor_1.h index fad790837571..2ebf8da550a0 100644 --- a/Marlin/src/module/thermistor/thermistor_1.h +++ b/Marlin/src/module/thermistor/thermistor_1.h @@ -22,7 +22,7 @@ #pragma once // R25 = 100 kOhm, beta25 = 4092 K, 4.7 kOhm pull-up, bed thermistor -const temp_entry_t temptable_1[] PROGMEM = { +constexpr temp_entry_t temptable_1[] PROGMEM = { { OV( 23), 300 }, { OV( 25), 295 }, { OV( 27), 290 }, diff --git a/Marlin/src/module/thermistor/thermistor_10.h b/Marlin/src/module/thermistor/thermistor_10.h index c24ad40bf483..9f2285c3fd83 100644 --- a/Marlin/src/module/thermistor/thermistor_10.h +++ b/Marlin/src/module/thermistor/thermistor_10.h @@ -22,7 +22,7 @@ #pragma once // R25 = 100 kOhm, beta25 = 3960 K, 4.7 kOhm pull-up, RS thermistor 198-961 -const temp_entry_t temptable_10[] PROGMEM = { +constexpr temp_entry_t temptable_10[] PROGMEM = { { OV( 1), 929 }, { OV( 36), 299 }, { OV( 71), 246 }, diff --git a/Marlin/src/module/thermistor/thermistor_1010.h b/Marlin/src/module/thermistor/thermistor_1010.h index 8ab5e3b364c6..6f2e3ab318f2 100644 --- a/Marlin/src/module/thermistor/thermistor_1010.h +++ b/Marlin/src/module/thermistor/thermistor_1010.h @@ -24,7 +24,7 @@ #define REVERSE_TEMP_SENSOR_RANGE_1010 1 // Pt1000 with 1k0 pullup -const temp_entry_t temptable_1010[] PROGMEM = { +constexpr temp_entry_t temptable_1010[] PROGMEM = { PtLine( 0, 1000, 1000), PtLine( 25, 1000, 1000), PtLine( 50, 1000, 1000), diff --git a/Marlin/src/module/thermistor/thermistor_1047.h b/Marlin/src/module/thermistor/thermistor_1047.h index 6e1b61f9d073..fb901d0a8d02 100644 --- a/Marlin/src/module/thermistor/thermistor_1047.h +++ b/Marlin/src/module/thermistor/thermistor_1047.h @@ -24,7 +24,7 @@ #define REVERSE_TEMP_SENSOR_RANGE_1047 1 // Pt1000 with 4k7 pullup -const temp_entry_t temptable_1047[] PROGMEM = { +constexpr temp_entry_t temptable_1047[] PROGMEM = { // only a few values are needed as the curve is very flat PtLine( 0, 1000, 4700), PtLine( 50, 1000, 4700), diff --git a/Marlin/src/module/thermistor/thermistor_11.h b/Marlin/src/module/thermistor/thermistor_11.h index 345d009a6498..52f89814e732 100644 --- a/Marlin/src/module/thermistor/thermistor_11.h +++ b/Marlin/src/module/thermistor/thermistor_11.h @@ -22,7 +22,7 @@ #pragma once // R25 = 100 kOhm, beta25 = 3950 K, 4.7 kOhm pull-up, QU-BD silicone bed QWG-104F-3950 thermistor -const temp_entry_t temptable_11[] PROGMEM = { +constexpr temp_entry_t temptable_11[] PROGMEM = { { OV( 1), 938 }, { OV( 31), 314 }, { OV( 41), 290 }, diff --git a/Marlin/src/module/thermistor/thermistor_110.h b/Marlin/src/module/thermistor/thermistor_110.h index 215495e2c6a1..5d76d1ee1bda 100644 --- a/Marlin/src/module/thermistor/thermistor_110.h +++ b/Marlin/src/module/thermistor/thermistor_110.h @@ -24,7 +24,7 @@ #define REVERSE_TEMP_SENSOR_RANGE_110 1 // Pt100 with 1k0 pullup -const temp_entry_t temptable_110[] PROGMEM = { +constexpr temp_entry_t temptable_110[] PROGMEM = { // only a few values are needed as the curve is very flat PtLine( 0, 100, 1000), PtLine( 50, 100, 1000), diff --git a/Marlin/src/module/thermistor/thermistor_12.h b/Marlin/src/module/thermistor/thermistor_12.h index d1ee23b2b7f7..c0cbd254cffc 100644 --- a/Marlin/src/module/thermistor/thermistor_12.h +++ b/Marlin/src/module/thermistor/thermistor_12.h @@ -22,7 +22,7 @@ #pragma once // R25 = 100 kOhm, beta25 = 4700 K, 4.7 kOhm pull-up, (personal calibration for Makibox hot bed) -const temp_entry_t temptable_12[] PROGMEM = { +constexpr temp_entry_t temptable_12[] PROGMEM = { { OV( 35), 180 }, // top rating 180C { OV( 211), 140 }, { OV( 233), 135 }, diff --git a/Marlin/src/module/thermistor/thermistor_13.h b/Marlin/src/module/thermistor/thermistor_13.h index bb622240c82d..7e87373948a2 100644 --- a/Marlin/src/module/thermistor/thermistor_13.h +++ b/Marlin/src/module/thermistor/thermistor_13.h @@ -22,7 +22,7 @@ #pragma once // R25 = 100 kOhm, beta25 = 4100 K, 4.7 kOhm pull-up, Hisens thermistor -const temp_entry_t temptable_13[] PROGMEM = { +constexpr temp_entry_t temptable_13[] PROGMEM = { { OV( 20.04), 300 }, { OV( 23.19), 290 }, { OV( 26.71), 280 }, diff --git a/Marlin/src/module/thermistor/thermistor_147.h b/Marlin/src/module/thermistor/thermistor_147.h index 6d846ad5bed7..542e4844ec6b 100644 --- a/Marlin/src/module/thermistor/thermistor_147.h +++ b/Marlin/src/module/thermistor/thermistor_147.h @@ -24,7 +24,7 @@ #define REVERSE_TEMP_SENSOR_RANGE_147 1 // Pt100 with 4k7 pullup -const temp_entry_t temptable_147[] PROGMEM = { +constexpr temp_entry_t temptable_147[] PROGMEM = { // only a few values are needed as the curve is very flat PtLine( 0, 100, 4700), PtLine( 50, 100, 4700), diff --git a/Marlin/src/module/thermistor/thermistor_15.h b/Marlin/src/module/thermistor/thermistor_15.h index 46dcce8c1e4f..ce9824879357 100644 --- a/Marlin/src/module/thermistor/thermistor_15.h +++ b/Marlin/src/module/thermistor/thermistor_15.h @@ -22,7 +22,7 @@ #pragma once // 100k bed thermistor in JGAurora A5. Calibrated by Sam Pinches 21st Jan 2018 using cheap k-type thermocouple inserted into heater block, using TM-902C meter. -const temp_entry_t temptable_15[] PROGMEM = { +constexpr temp_entry_t temptable_15[] PROGMEM = { { OV( 31), 275 }, { OV( 33), 270 }, { OV( 35), 260 }, diff --git a/Marlin/src/module/thermistor/thermistor_17.h b/Marlin/src/module/thermistor/thermistor_17.h new file mode 100644 index 000000000000..55d3bc39d0af --- /dev/null +++ b/Marlin/src/module/thermistor/thermistor_17.h @@ -0,0 +1,78 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +// Dagoma NTC 100k white thermistor +constexpr temp_entry_t temptable_17[] PROGMEM = { + { OV( 16), 309 }, + { OV( 18), 307 }, + { OV( 20), 300 }, + { OV( 22), 293 }, + { OV( 26), 284 }, + { OV( 29), 272 }, + { OV( 33), 266 }, + { OV( 36), 260 }, + { OV( 42), 252 }, + { OV( 46), 247 }, + { OV( 48), 244 }, + { OV( 51), 241 }, + { OV( 62), 231 }, + { OV( 73), 222 }, + { OV( 78), 219 }, + { OV( 87), 212 }, + { OV( 98), 207 }, + { OV( 109), 201 }, + { OV( 118), 197 }, + { OV( 131), 191 }, + { OV( 145), 186 }, + { OV( 160), 181 }, + { OV( 177), 175 }, + { OV( 203), 169 }, + { OV( 222), 164 }, + { OV( 256), 156 }, + { OV( 283), 151 }, + { OV( 312), 145 }, + { OV( 343), 140 }, + { OV( 377), 131 }, + { OV( 413), 125 }, + { OV( 454), 119 }, + { OV( 496), 113 }, + { OV( 537), 108 }, + { OV( 578), 102 }, + { OV( 619), 97 }, + { OV( 658), 92 }, + { OV( 695), 87 }, + { OV( 735), 81 }, + { OV( 773), 75 }, + { OV( 808), 70 }, + { OV( 844), 64 }, + { OV( 868), 59 }, + { OV( 892), 54 }, + { OV( 914), 49 }, + { OV( 935), 42 }, + { OV( 951), 38 }, + { OV( 967), 32 }, + { OV( 975), 28 }, + { OV(1000), 20 }, + { OV(1010), 10 }, + { OV(1024), -273 } // for safety +}; diff --git a/Marlin/src/module/thermistor/thermistor_18.h b/Marlin/src/module/thermistor/thermistor_18.h index 9c2d81b3e698..061cf78129e0 100644 --- a/Marlin/src/module/thermistor/thermistor_18.h +++ b/Marlin/src/module/thermistor/thermistor_18.h @@ -22,7 +22,7 @@ #pragma once // ATC Semitec 204GT-2 (4.7k pullup) Dagoma.Fr - MKS_Base_DKU001327 - version (measured/tested/approved) -const temp_entry_t temptable_18[] PROGMEM = { +constexpr temp_entry_t temptable_18[] PROGMEM = { { OV( 1), 713 }, { OV( 17), 284 }, { OV( 20), 275 }, diff --git a/Marlin/src/module/thermistor/thermistor_2.h b/Marlin/src/module/thermistor/thermistor_2.h index d0e1e4f3dfca..a899fd17ee0f 100644 --- a/Marlin/src/module/thermistor/thermistor_2.h +++ b/Marlin/src/module/thermistor/thermistor_2.h @@ -26,7 +26,7 @@ // Verified by linagee. Source: https://www.mouser.com/datasheet/2/362/semitec%20usa%20corporation_gtthermistor-1202937.pdf // Calculated using 4.7kohm pullup, voltage divider math, and manufacturer provided temp/resistance // -const temp_entry_t temptable_2[] PROGMEM = { +constexpr temp_entry_t temptable_2[] PROGMEM = { { OV( 1), 848 }, { OV( 30), 300 }, // top rating 300C { OV( 34), 290 }, diff --git a/Marlin/src/module/thermistor/thermistor_20.h b/Marlin/src/module/thermistor/thermistor_20.h index 73094f14604d..a8267e93e4a6 100644 --- a/Marlin/src/module/thermistor/thermistor_20.h +++ b/Marlin/src/module/thermistor/thermistor_20.h @@ -24,7 +24,7 @@ #define REVERSE_TEMP_SENSOR_RANGE_20 1 // Pt100 with INA826 amp on Ultimaker v2.0 electronics -const temp_entry_t temptable_20[] PROGMEM = { +constexpr temp_entry_t temptable_20[] PROGMEM = { { OV( 0), 0 }, { OV(227), 1 }, { OV(236), 10 }, diff --git a/Marlin/src/module/thermistor/thermistor_201.h b/Marlin/src/module/thermistor/thermistor_201.h index 44d52806813a..9c083a2d1bf0 100644 --- a/Marlin/src/module/thermistor/thermistor_201.h +++ b/Marlin/src/module/thermistor/thermistor_201.h @@ -24,7 +24,7 @@ #define REVERSE_TEMP_SENSOR_RANGE_201 1 // Pt100 with LMV324 amp on Overlord v1.1 electronics -const temp_entry_t temptable_201[] PROGMEM = { +constexpr temp_entry_t temptable_201[] PROGMEM = { { OV( 0), 0 }, { OV( 8), 1 }, { OV( 23), 6 }, diff --git a/Marlin/src/module/thermistor/thermistor_202.h b/Marlin/src/module/thermistor/thermistor_202.h index c5229607ae33..e1b0ee258e79 100644 --- a/Marlin/src/module/thermistor/thermistor_202.h +++ b/Marlin/src/module/thermistor/thermistor_202.h @@ -3,7 +3,7 @@ // Temptable sent from dealer technologyoutlet.co.uk // -const temp_entry_t temptable_202[] PROGMEM = { +constexpr temp_entry_t temptable_202[] PROGMEM = { { OV( 1), 864 }, { OV( 35), 300 }, { OV( 38), 295 }, diff --git a/Marlin/src/module/thermistor/thermistor_21.h b/Marlin/src/module/thermistor/thermistor_21.h index cd867df29103..f8a5de2e150d 100644 --- a/Marlin/src/module/thermistor/thermistor_21.h +++ b/Marlin/src/module/thermistor/thermistor_21.h @@ -26,8 +26,9 @@ #undef OV_SCALE #define OV_SCALE(N) (float((N) * 5) / 3.3f) -// Pt100 with INA826 amp with 3.3v excitation based on "Pt100 with INA826 amp on Ultimaker v2.0 electronics" -const temp_entry_t temptable_21[] PROGMEM = { +// Pt100 with INA826 amplifier board with 5v supply based on Thermistor 20, with 3v3 ADC reference on the mainboard. +// If the ADC reference and INA826 board supply voltage are identical, Thermistor 20 instead. +constexpr temp_entry_t temptable_21[] PROGMEM = { { OV( 0), 0 }, { OV(227), 1 }, { OV(236), 10 }, diff --git a/Marlin/src/module/thermistor/thermistor_22.h b/Marlin/src/module/thermistor/thermistor_22.h index 6f4a31050add..90e1af8c1a6c 100644 --- a/Marlin/src/module/thermistor/thermistor_22.h +++ b/Marlin/src/module/thermistor/thermistor_22.h @@ -21,7 +21,7 @@ */ // 100k hotend thermistor with 4.7k pull up to 3.3v and 220R to analog input as in GTM32 Pro vB -const temp_entry_t temptable_22[] PROGMEM = { +constexpr temp_entry_t temptable_22[] PROGMEM = { { OV( 1), 352 }, { OV( 6), 341 }, { OV( 11), 330 }, diff --git a/Marlin/src/module/thermistor/thermistor_23.h b/Marlin/src/module/thermistor/thermistor_23.h index 02ff9fb2b6c8..9b806af5b77f 100644 --- a/Marlin/src/module/thermistor/thermistor_23.h +++ b/Marlin/src/module/thermistor/thermistor_23.h @@ -21,7 +21,7 @@ */ // 100k hotbed thermistor with 4.7k pull up to 3.3v and 220R to analog input as in GTM32 Pro vB -const temp_entry_t temptable_23[] PROGMEM = { +constexpr temp_entry_t temptable_23[] PROGMEM = { { OV( 1), 938 }, { OV( 11), 423 }, { OV( 21), 351 }, diff --git a/Marlin/src/module/thermistor/thermistor_3.h b/Marlin/src/module/thermistor/thermistor_3.h index 74e00e2ba4f4..cb6d75738ed2 100644 --- a/Marlin/src/module/thermistor/thermistor_3.h +++ b/Marlin/src/module/thermistor/thermistor_3.h @@ -22,7 +22,7 @@ #pragma once // R25 = 100 kOhm, beta25 = 4120 K, 4.7 kOhm pull-up, mendel-parts -const temp_entry_t temptable_3[] PROGMEM = { +constexpr temp_entry_t temptable_3[] PROGMEM = { { OV( 1), 864 }, { OV( 21), 300 }, { OV( 25), 290 }, diff --git a/Marlin/src/module/thermistor/thermistor_30.h b/Marlin/src/module/thermistor/thermistor_30.h index bc1781b1351c..daf4d29aa761 100644 --- a/Marlin/src/module/thermistor/thermistor_30.h +++ b/Marlin/src/module/thermistor/thermistor_30.h @@ -28,7 +28,7 @@ // B Value Tolerance + / - 1% // Kis3d Silicone Heater 24V 200W/300W with 6mm Precision cast plate (EN AW 5083) // Temperature setting time 10 min to determine the 12Bit ADC value on the surface. (le3tspeak) -const temp_entry_t temptable_30[] PROGMEM = { +constexpr temp_entry_t temptable_30[] PROGMEM = { { OV( 1), 938 }, { OV( 298), 125 }, // 1193 - 125° { OV( 321), 121 }, // 1285 - 121° diff --git a/Marlin/src/module/thermistor/thermistor_331.h b/Marlin/src/module/thermistor/thermistor_331.h index ccb0f6b62d2b..847dbc30a03b 100644 --- a/Marlin/src/module/thermistor/thermistor_331.h +++ b/Marlin/src/module/thermistor/thermistor_331.h @@ -24,7 +24,7 @@ #define OVM(V) OV((V)*(0.327/0.5)) // R25 = 100 kOhm, beta25 = 4092 K, 4.7 kOhm pull-up, bed thermistor -const temp_entry_t temptable_331[] PROGMEM = { +constexpr temp_entry_t temptable_331[] PROGMEM = { { OVM( 23), 300 }, { OVM( 25), 295 }, { OVM( 27), 290 }, diff --git a/Marlin/src/module/thermistor/thermistor_332.h b/Marlin/src/module/thermistor/thermistor_332.h index 9502f1bdae9e..83a5d39f0fee 100644 --- a/Marlin/src/module/thermistor/thermistor_332.h +++ b/Marlin/src/module/thermistor/thermistor_332.h @@ -24,7 +24,7 @@ #define OVM(V) OV((V)*(0.327/0.327)) // R25 = 100 kOhm, beta25 = 4092 K, 4.7 kOhm pull-up, bed thermistor -const temp_entry_t temptable_332[] PROGMEM = { +constexpr temp_entry_t temptable_332[] PROGMEM = { { OVM( 268), 150 }, { OVM( 293), 145 }, { OVM( 320), 141 }, diff --git a/Marlin/src/module/thermistor/thermistor_4.h b/Marlin/src/module/thermistor/thermistor_4.h index 92d907249be9..98192a112454 100644 --- a/Marlin/src/module/thermistor/thermistor_4.h +++ b/Marlin/src/module/thermistor/thermistor_4.h @@ -22,7 +22,7 @@ #pragma once // R25 = 10 kOhm, beta25 = 3950 K, 4.7 kOhm pull-up, Generic 10k thermistor -const temp_entry_t temptable_4[] PROGMEM = { +constexpr temp_entry_t temptable_4[] PROGMEM = { { OV( 1), 430 }, { OV( 54), 137 }, { OV( 107), 107 }, diff --git a/Marlin/src/module/thermistor/thermistor_5.h b/Marlin/src/module/thermistor/thermistor_5.h index 1d5fa2fec739..69ef99fae1ee 100644 --- a/Marlin/src/module/thermistor/thermistor_5.h +++ b/Marlin/src/module/thermistor/thermistor_5.h @@ -26,7 +26,7 @@ // ATC Semitec 104GT-2/104NT-4-R025H42G (Used in ParCan) // Verified by linagee. Source: https://www.mouser.com/datasheet/2/362/semitec%20usa%20corporation_gtthermistor-1202937.pdf // Calculated using 4.7kohm pullup, voltage divider math, and manufacturer provided temp/resistance -const temp_entry_t temptable_5[] PROGMEM = { +constexpr temp_entry_t temptable_5[] PROGMEM = { { OV( 1), 713 }, { OV( 17), 300 }, // top rating 300C { OV( 20), 290 }, diff --git a/Marlin/src/module/thermistor/thermistor_501.h b/Marlin/src/module/thermistor/thermistor_501.h index d40e341f7e31..0e142628ec6b 100644 --- a/Marlin/src/module/thermistor/thermistor_501.h +++ b/Marlin/src/module/thermistor/thermistor_501.h @@ -22,7 +22,7 @@ #pragma once // 100k Zonestar thermistor. Adjusted By Hally -const temp_entry_t temptable_501[] PROGMEM = { +constexpr temp_entry_t temptable_501[] PROGMEM = { { OV( 1), 713 }, { OV( 14), 300 }, // Top rating 300C { OV( 16), 290 }, diff --git a/Marlin/src/module/thermistor/thermistor_502.h b/Marlin/src/module/thermistor/thermistor_502.h index 69cee2431c5f..3ddbf30d47ed 100644 --- a/Marlin/src/module/thermistor/thermistor_502.h +++ b/Marlin/src/module/thermistor/thermistor_502.h @@ -23,7 +23,7 @@ // Unknown thermistor for the Zonestar P802M hot bed. Adjusted By Nerseth // These were the shipped settings from Zonestar in original firmware: P802M_8_Repetier_V1.6_Zonestar.zip -const temp_entry_t temptable_502[] PROGMEM = { +constexpr temp_entry_t temptable_502[] PROGMEM = { { OV( 56.0 / 4), 300 }, { OV( 187.0 / 4), 250 }, { OV( 615.0 / 4), 190 }, diff --git a/Marlin/src/module/thermistor/thermistor_503.h b/Marlin/src/module/thermistor/thermistor_503.h new file mode 100644 index 000000000000..6ffe4b4a666f --- /dev/null +++ b/Marlin/src/module/thermistor/thermistor_503.h @@ -0,0 +1,57 @@ +/** + * 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 + +// Zonestar (Z8XM2) Heated Bed thermistor. Added By AvanOsch +// These are taken from the Zonestar settings in original Repetier firmware: Z8XM2_ZRIB_LCD12864_V51.zip +constexpr temp_entry_t temptable_503[] PROGMEM = { + { OV( 12), 300 }, + { OV( 27), 270 }, + { OV( 47), 250 }, + { OV( 68), 230 }, + { OV( 99), 210 }, + { OV( 120), 200 }, + { OV( 141), 190 }, + { OV( 171), 180 }, + { OV( 201), 170 }, + { OV( 261), 160 }, + { OV( 321), 150 }, + { OV( 401), 140 }, + { OV( 451), 130 }, + { OV( 551), 120 }, + { OV( 596), 110 }, + { OV( 626), 105 }, + { OV( 666), 100 }, + { OV( 697), 90 }, + { OV( 717), 85 }, + { OV( 798), 69 }, + { OV( 819), 65 }, + { OV( 870), 55 }, + { OV( 891), 51 }, + { OV( 922), 39 }, + { OV( 968), 28 }, + { OV( 980), 23 }, + { OV( 991), 17 }, + { OV( 1001), 9 }, + { OV(1021), -27 }, + { OV(1023), -200} +}; diff --git a/Marlin/src/module/thermistor/thermistor_51.h b/Marlin/src/module/thermistor/thermistor_51.h index d02dd47ba5d1..ee63a0e61bbb 100644 --- a/Marlin/src/module/thermistor/thermistor_51.h +++ b/Marlin/src/module/thermistor/thermistor_51.h @@ -26,7 +26,7 @@ // Verified by linagee. // Calculated using 1kohm pullup, voltage divider math, and manufacturer provided temp/resistance // Advantage: Twice the resolution and better linearity from 150C to 200C -const temp_entry_t temptable_51[] PROGMEM = { +constexpr temp_entry_t temptable_51[] PROGMEM = { { OV( 1), 350 }, { OV( 190), 250 }, // top rating 250C { OV( 203), 245 }, diff --git a/Marlin/src/module/thermistor/thermistor_512.h b/Marlin/src/module/thermistor/thermistor_512.h index e8021e1e48c4..e380b4a16bfd 100644 --- a/Marlin/src/module/thermistor/thermistor_512.h +++ b/Marlin/src/module/thermistor/thermistor_512.h @@ -22,7 +22,7 @@ // 100k thermistor supplied with RPW-Ultra hotend, 4.7k pullup -const temp_entry_t temptable_512[] PROGMEM = { +constexpr temp_entry_t temptable_512[] PROGMEM = { { OV(26), 300 }, { OV(28), 295 }, { OV(30), 290 }, diff --git a/Marlin/src/module/thermistor/thermistor_52.h b/Marlin/src/module/thermistor/thermistor_52.h index 5c9cb9dc4df9..f3bb75d4627f 100644 --- a/Marlin/src/module/thermistor/thermistor_52.h +++ b/Marlin/src/module/thermistor/thermistor_52.h @@ -26,7 +26,7 @@ // Verified by linagee. Source: https://www.mouser.com/datasheet/2/362/semitec%20usa%20corporation_gtthermistor-1202937.pdf // Calculated using 1kohm pullup, voltage divider math, and manufacturer provided temp/resistance // Advantage: More resolution and better linearity from 150C to 200C -const temp_entry_t temptable_52[] PROGMEM = { +constexpr temp_entry_t temptable_52[] PROGMEM = { { OV( 1), 500 }, { OV( 125), 300 }, // top rating 300C { OV( 142), 290 }, diff --git a/Marlin/src/module/thermistor/thermistor_55.h b/Marlin/src/module/thermistor/thermistor_55.h index 707b7d420a12..41004a97ef23 100644 --- a/Marlin/src/module/thermistor/thermistor_55.h +++ b/Marlin/src/module/thermistor/thermistor_55.h @@ -26,7 +26,7 @@ // Verified by linagee. Source: https://www.mouser.com/datasheet/2/362/semitec%20usa%20corporation_gtthermistor-1202937.pdf // Calculated using 1kohm pullup, voltage divider math, and manufacturer provided temp/resistance // Advantage: More resolution and better linearity from 150C to 200C -const temp_entry_t temptable_55[] PROGMEM = { +constexpr temp_entry_t temptable_55[] PROGMEM = { { OV( 1), 500 }, { OV( 76), 300 }, { OV( 87), 290 }, diff --git a/Marlin/src/module/thermistor/thermistor_6.h b/Marlin/src/module/thermistor/thermistor_6.h index 68113419e583..b5e79a9b0e72 100644 --- a/Marlin/src/module/thermistor/thermistor_6.h +++ b/Marlin/src/module/thermistor/thermistor_6.h @@ -22,7 +22,7 @@ #pragma once // R25 = 100 kOhm, beta25 = 4092 K, 8.2 kOhm pull-up, 100k Epcos (?) thermistor -const temp_entry_t temptable_6[] PROGMEM = { +constexpr temp_entry_t temptable_6[] PROGMEM = { { OV( 1), 350 }, { OV( 28), 250 }, // top rating 250C { OV( 31), 245 }, diff --git a/Marlin/src/module/thermistor/thermistor_60.h b/Marlin/src/module/thermistor/thermistor_60.h index a3fe50559fd0..a057080e45c1 100644 --- a/Marlin/src/module/thermistor/thermistor_60.h +++ b/Marlin/src/module/thermistor/thermistor_60.h @@ -31,7 +31,7 @@ // beta: 3950 // min adc: 1 at 0.0048828125 V // max adc: 1023 at 4.9951171875 V -const temp_entry_t temptable_60[] PROGMEM = { +constexpr temp_entry_t temptable_60[] PROGMEM = { { OV( 51), 272 }, { OV( 61), 258 }, { OV( 71), 247 }, diff --git a/Marlin/src/module/thermistor/thermistor_61.h b/Marlin/src/module/thermistor/thermistor_61.h index ed4c4c885956..2916bffd3bc8 100644 --- a/Marlin/src/module/thermistor/thermistor_61.h +++ b/Marlin/src/module/thermistor/thermistor_61.h @@ -30,8 +30,8 @@ // Resistance Tolerance + / -1% // B Value 3950K at 25/50 deg. C // B Value Tolerance + / - 1% -const temp_entry_t temptable_61[] PROGMEM = { - { OV( 2.00), 420 }, // Guestimate to ensure we dont lose a reading and drop temps to -50 when over +constexpr temp_entry_t temptable_61[] PROGMEM = { + { OV( 2.00), 420 }, // Guestimate to ensure we don't lose a reading and drop temps to -50 when over { OV( 12.07), 350 }, { OV( 12.79), 345 }, { OV( 13.59), 340 }, diff --git a/Marlin/src/module/thermistor/thermistor_66.h b/Marlin/src/module/thermistor/thermistor_66.h index 0ad5994ea811..3b057ac6960e 100644 --- a/Marlin/src/module/thermistor/thermistor_66.h +++ b/Marlin/src/module/thermistor/thermistor_66.h @@ -22,7 +22,7 @@ #pragma once // R25 = 2.5 MOhm, beta25 = 4500 K, 4.7 kOhm pull-up, DyzeDesign 500 °C Thermistor -const temp_entry_t temptable_66[] PROGMEM = { +constexpr temp_entry_t temptable_66[] PROGMEM = { { OV( 17.5), 850 }, { OV( 17.9), 500 }, { OV( 21.7), 480 }, diff --git a/Marlin/src/module/thermistor/thermistor_666.h b/Marlin/src/module/thermistor/thermistor_666.h index 490dbd5f3ee9..bba3e606fc06 100644 --- a/Marlin/src/module/thermistor/thermistor_666.h +++ b/Marlin/src/module/thermistor/thermistor_666.h @@ -33,7 +33,7 @@ * B: 0.00031362 * C: -2.03978e-07 */ -const temp_entry_t temptable_666[] PROGMEM = { +constexpr temp_entry_t temptable_666[] PROGMEM = { { OV( 1), 794 }, { OV( 18), 288 }, { OV( 35), 234 }, diff --git a/Marlin/src/module/thermistor/thermistor_67.h b/Marlin/src/module/thermistor/thermistor_67.h index 7d6d7f697df3..10fa9310b1cf 100644 --- a/Marlin/src/module/thermistor/thermistor_67.h +++ b/Marlin/src/module/thermistor/thermistor_67.h @@ -22,7 +22,7 @@ #pragma once // R25 = 500 KOhm, beta25 = 3800 K, 4.7 kOhm pull-up, SliceEngineering 450 °C Thermistor -const temp_entry_t temptable_67[] PROGMEM = { +constexpr temp_entry_t temptable_67[] PROGMEM = { { OV( 22 ), 500 }, { OV( 23 ), 490 }, { OV( 25 ), 480 }, diff --git a/Marlin/src/module/thermistor/thermistor_7.h b/Marlin/src/module/thermistor/thermistor_7.h index 7a737559841c..964897859e84 100644 --- a/Marlin/src/module/thermistor/thermistor_7.h +++ b/Marlin/src/module/thermistor/thermistor_7.h @@ -22,7 +22,7 @@ #pragma once // R25 = 100 kOhm, beta25 = 3974 K, 4.7 kOhm pull-up, Honeywell 135-104LAG-J01 -const temp_entry_t temptable_7[] PROGMEM = { +constexpr temp_entry_t temptable_7[] PROGMEM = { { OV( 1), 941 }, { OV( 19), 362 }, { OV( 37), 299 }, // top rating 300C diff --git a/Marlin/src/module/thermistor/thermistor_70.h b/Marlin/src/module/thermistor/thermistor_70.h index 466b9255533e..f0163dcabc9f 100644 --- a/Marlin/src/module/thermistor/thermistor_70.h +++ b/Marlin/src/module/thermistor/thermistor_70.h @@ -26,7 +26,7 @@ // ANENG AN8009 DMM with a K-type probe used for measurements. // R25 = 100 kOhm, beta25 = 4100 K, 4.7 kOhm pull-up, bqh2 stock thermistor -const temp_entry_t temptable_70[] PROGMEM = { +constexpr temp_entry_t temptable_70[] PROGMEM = { { OV( 18), 270 }, { OV( 27), 248 }, { OV( 34), 234 }, diff --git a/Marlin/src/module/thermistor/thermistor_71.h b/Marlin/src/module/thermistor/thermistor_71.h index abd7fc5b986e..c94b4d5bbc6f 100644 --- a/Marlin/src/module/thermistor/thermistor_71.h +++ b/Marlin/src/module/thermistor/thermistor_71.h @@ -27,7 +27,7 @@ // Beta = 3974 // R1 = 0 Ohm // R2 = 4700 Ohm -const temp_entry_t temptable_71[] PROGMEM = { +constexpr temp_entry_t temptable_71[] PROGMEM = { { OV( 35), 300 }, { OV( 51), 269 }, { OV( 59), 258 }, diff --git a/Marlin/src/module/thermistor/thermistor_75.h b/Marlin/src/module/thermistor/thermistor_75.h index 79800d2e4048..bb2ecce7dcf8 100644 --- a/Marlin/src/module/thermistor/thermistor_75.h +++ b/Marlin/src/module/thermistor/thermistor_75.h @@ -34,7 +34,7 @@ //#define HIGH_TEMP_RANGE_75 -const temp_entry_t temptable_75[] PROGMEM = { // Generic Silicon Heat Pad with NTC 100K MGB18-104F39050L32 thermistor +constexpr temp_entry_t temptable_75[] PROGMEM = { // Generic Silicon Heat Pad with NTC 100K MGB18-104F39050L32 thermistor { OV(111.06), 200 }, // v=0.542 r=571.747 res=0.501 degC/count #ifdef HIGH_TEMP_RANGE_75 diff --git a/Marlin/src/module/thermistor/thermistor_8.h b/Marlin/src/module/thermistor/thermistor_8.h index 9e19168fed0d..4b0f791f16be 100644 --- a/Marlin/src/module/thermistor/thermistor_8.h +++ b/Marlin/src/module/thermistor/thermistor_8.h @@ -22,7 +22,7 @@ #pragma once // R25 = 100 kOhm, beta25 = 3950 K, 10 kOhm pull-up, NTCS0603E3104FHT -const temp_entry_t temptable_8[] PROGMEM = { +constexpr temp_entry_t temptable_8[] PROGMEM = { { OV( 1), 704 }, { OV( 54), 216 }, { OV( 107), 175 }, diff --git a/Marlin/src/module/thermistor/thermistor_9.h b/Marlin/src/module/thermistor/thermistor_9.h index 29097420ec11..3830a7dfcce7 100644 --- a/Marlin/src/module/thermistor/thermistor_9.h +++ b/Marlin/src/module/thermistor/thermistor_9.h @@ -22,7 +22,7 @@ #pragma once // R25 = 100 kOhm, beta25 = 3960 K, 4.7 kOhm pull-up, GE Sensing AL03006-58.2K-97-G1 -const temp_entry_t temptable_9[] PROGMEM = { +constexpr temp_entry_t temptable_9[] PROGMEM = { { OV( 1), 936 }, { OV( 36), 300 }, { OV( 71), 246 }, diff --git a/Marlin/src/module/thermistor/thermistor_99.h b/Marlin/src/module/thermistor/thermistor_99.h index 839a511c0918..f813abae6981 100644 --- a/Marlin/src/module/thermistor/thermistor_99.h +++ b/Marlin/src/module/thermistor/thermistor_99.h @@ -24,7 +24,7 @@ // 100k bed thermistor with a 10K pull-up resistor - made by $ buildroot/share/scripts/createTemperatureLookupMarlin.py --rp=10000 -const temp_entry_t temptable_99[] PROGMEM = { +constexpr temp_entry_t temptable_99[] PROGMEM = { { OV( 5.81), 350 }, // v=0.028 r= 57.081 res=13.433 degC/count { OV( 6.54), 340 }, // v=0.032 r= 64.248 res=11.711 degC/count { OV( 7.38), 330 }, // v=0.036 r= 72.588 res=10.161 degC/count diff --git a/Marlin/src/module/thermistor/thermistor_998.h b/Marlin/src/module/thermistor/thermistor_998.h index e4cfbbaa0d2f..753cdd40bc6a 100644 --- a/Marlin/src/module/thermistor/thermistor_998.h +++ b/Marlin/src/module/thermistor/thermistor_998.h @@ -27,7 +27,7 @@ #define DUMMY_THERMISTOR_998_VALUE 25 #endif -const temp_entry_t temptable_998[] PROGMEM = { +constexpr temp_entry_t temptable_998[] PROGMEM = { { OV( 1), DUMMY_THERMISTOR_998_VALUE }, { OV(1023), DUMMY_THERMISTOR_998_VALUE } }; diff --git a/Marlin/src/module/thermistor/thermistor_999.h b/Marlin/src/module/thermistor/thermistor_999.h index 0271c47f8585..41e44ef63189 100644 --- a/Marlin/src/module/thermistor/thermistor_999.h +++ b/Marlin/src/module/thermistor/thermistor_999.h @@ -27,7 +27,7 @@ #define DUMMY_THERMISTOR_999_VALUE 25 #endif -const temp_entry_t temptable_999[] PROGMEM = { +constexpr temp_entry_t temptable_999[] PROGMEM = { { OV( 1), DUMMY_THERMISTOR_999_VALUE }, { OV(1023), DUMMY_THERMISTOR_999_VALUE } }; diff --git a/Marlin/src/module/thermistor/thermistors.h b/Marlin/src/module/thermistor/thermistors.h index 0b0419c52034..a6cd7c86dfd8 100644 --- a/Marlin/src/module/thermistor/thermistors.h +++ b/Marlin/src/module/thermistor/thermistors.h @@ -27,6 +27,8 @@ #define THERMISTOR_TABLE_SCALE (HAL_ADC_RANGE / _BV(THERMISTOR_TABLE_ADC_RESOLUTION)) #if ENABLED(HAL_ADC_FILTERED) #define OVERSAMPLENR 1 +#elif HAL_ADC_RESOLUTION > 10 + #define OVERSAMPLENR (20 - HAL_ADC_RESOLUTION) #else #define OVERSAMPLENR 16 #endif @@ -40,9 +42,18 @@ #define OV_SCALE(N) (N) #define OV(N) int16_t(OV_SCALE(N) * (OVERSAMPLENR) * (THERMISTOR_TABLE_SCALE)) -#define ANY_THERMISTOR_IS(n) (THERMISTOR_HEATER_0 == n || THERMISTOR_HEATER_1 == n || THERMISTOR_HEATER_2 == n || THERMISTOR_HEATER_3 == n || THERMISTOR_HEATER_4 == n || THERMISTOR_HEATER_5 == n || THERMISTOR_HEATER_6 == n || THERMISTOR_HEATER_7 == n || THERMISTORBED == n || THERMISTORCHAMBER == n || THERMISTORPROBE == n) +#define TEMP_SENSOR_IS(n,H) (n == TEMP_SENSOR_##H) +#define ANY_THERMISTOR_IS(n) ( TEMP_SENSOR_IS(n, 0) || TEMP_SENSOR_IS(n, 1) \ + || TEMP_SENSOR_IS(n, 2) || TEMP_SENSOR_IS(n, 3) \ + || TEMP_SENSOR_IS(n, 4) || TEMP_SENSOR_IS(n, 5) \ + || TEMP_SENSOR_IS(n, 6) || TEMP_SENSOR_IS(n, 7) \ + || TEMP_SENSOR_IS(n, BED) \ + || TEMP_SENSOR_IS(n, CHAMBER) \ + || TEMP_SENSOR_IS(n, COOLER) \ + || TEMP_SENSOR_IS(n, PROBE) \ + || TEMP_SENSOR_IS(n, REDUNDANT) ) -typedef struct { int16_t value, celsius; } temp_entry_t; +typedef struct { int16_t value; celsius_t celsius; } temp_entry_t; // Pt1000 and Pt100 handling // @@ -75,6 +86,9 @@ typedef struct { int16_t value, celsius; } temp_entry_t; #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 + #include "thermistor_503.h" +#endif #if ANY_THERMISTOR_IS(512) // 100k thermistor in RPW-Ultra hotend, Pull-up = 4.7 kOhm, "unknown model" #include "thermistor_512.h" #endif @@ -105,6 +119,9 @@ typedef struct { int16_t value, celsius; } temp_entry_t; #if ANY_THERMISTOR_IS(15) // JGAurora A5 thermistor calibration #include "thermistor_15.h" #endif +#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 #include "thermistor_18.h" #endif @@ -190,310 +207,324 @@ typedef struct { int16_t value, celsius; } temp_entry_t; #include "thermistor_999.h" #endif #if ANY_THERMISTOR_IS(1000) // Custom - const temp_entry_t temptable_1000[] PROGMEM = { { 0, 0 } }; + constexpr temp_entry_t temptable_1000[] PROGMEM = { { 0, 0 } }; #endif #define _TT_NAME(_N) temptable_ ## _N #define TT_NAME(_N) _TT_NAME(_N) +#if TEMP_SENSOR_0 > 0 + #define TEMPTABLE_0 TT_NAME(TEMP_SENSOR_0) + #define TEMPTABLE_0_LEN COUNT(TEMPTABLE_0) +#else + #define TEMPTABLE_0 nullptr + #define TEMPTABLE_0_LEN 0 +#endif + +#if TEMP_SENSOR_1 > 0 + #define TEMPTABLE_1 TT_NAME(TEMP_SENSOR_1) + #define TEMPTABLE_1_LEN COUNT(TEMPTABLE_1) +#else + #define TEMPTABLE_1 nullptr + #define TEMPTABLE_1_LEN 0 +#endif -#if THERMISTOR_HEATER_0 - #define HEATER_0_TEMPTABLE TT_NAME(THERMISTOR_HEATER_0) - #define HEATER_0_TEMPTABLE_LEN COUNT(HEATER_0_TEMPTABLE) -#elif defined(HEATER_0_USES_THERMISTOR) - #error "No heater 0 thermistor table specified" +#if TEMP_SENSOR_2 > 0 + #define TEMPTABLE_2 TT_NAME(TEMP_SENSOR_2) + #define TEMPTABLE_2_LEN COUNT(TEMPTABLE_2) #else - #define HEATER_0_TEMPTABLE nullptr - #define HEATER_0_TEMPTABLE_LEN 0 + #define TEMPTABLE_2 nullptr + #define TEMPTABLE_2_LEN 0 #endif -#if THERMISTOR_HEATER_1 - #define HEATER_1_TEMPTABLE TT_NAME(THERMISTOR_HEATER_1) - #define HEATER_1_TEMPTABLE_LEN COUNT(HEATER_1_TEMPTABLE) -#elif defined(HEATER_1_USES_THERMISTOR) - #error "No heater 1 thermistor table specified" +#if TEMP_SENSOR_3 > 0 + #define TEMPTABLE_3 TT_NAME(TEMP_SENSOR_3) + #define TEMPTABLE_3_LEN COUNT(TEMPTABLE_3) #else - #define HEATER_1_TEMPTABLE nullptr - #define HEATER_1_TEMPTABLE_LEN 0 + #define TEMPTABLE_3 nullptr + #define TEMPTABLE_3_LEN 0 #endif -#if THERMISTOR_HEATER_2 - #define HEATER_2_TEMPTABLE TT_NAME(THERMISTOR_HEATER_2) - #define HEATER_2_TEMPTABLE_LEN COUNT(HEATER_2_TEMPTABLE) -#elif defined(HEATER_2_USES_THERMISTOR) - #error "No heater 2 thermistor table specified" +#if TEMP_SENSOR_4 > 0 + #define TEMPTABLE_4 TT_NAME(TEMP_SENSOR_4) + #define TEMPTABLE_4_LEN COUNT(TEMPTABLE_4) #else - #define HEATER_2_TEMPTABLE nullptr - #define HEATER_2_TEMPTABLE_LEN 0 + #define TEMPTABLE_4 nullptr + #define TEMPTABLE_4_LEN 0 #endif -#if THERMISTOR_HEATER_3 - #define HEATER_3_TEMPTABLE TT_NAME(THERMISTOR_HEATER_3) - #define HEATER_3_TEMPTABLE_LEN COUNT(HEATER_3_TEMPTABLE) -#elif defined(HEATER_3_USES_THERMISTOR) - #error "No heater 3 thermistor table specified" +#if TEMP_SENSOR_5 > 0 + #define TEMPTABLE_5 TT_NAME(TEMP_SENSOR_5) + #define TEMPTABLE_5_LEN COUNT(TEMPTABLE_5) #else - #define HEATER_3_TEMPTABLE nullptr - #define HEATER_3_TEMPTABLE_LEN 0 + #define TEMPTABLE_5 nullptr + #define TEMPTABLE_5_LEN 0 #endif -#if THERMISTOR_HEATER_4 - #define HEATER_4_TEMPTABLE TT_NAME(THERMISTOR_HEATER_4) - #define HEATER_4_TEMPTABLE_LEN COUNT(HEATER_4_TEMPTABLE) -#elif defined(HEATER_4_USES_THERMISTOR) - #error "No heater 4 thermistor table specified" +#if TEMP_SENSOR_6 > 0 + #define TEMPTABLE_6 TT_NAME(TEMP_SENSOR_6) + #define TEMPTABLE_6_LEN COUNT(TEMPTABLE_6) #else - #define HEATER_4_TEMPTABLE nullptr - #define HEATER_4_TEMPTABLE_LEN 0 + #define TEMPTABLE_6 nullptr + #define TEMPTABLE_6_LEN 0 #endif -#if THERMISTOR_HEATER_5 - #define HEATER_5_TEMPTABLE TT_NAME(THERMISTOR_HEATER_5) - #define HEATER_5_TEMPTABLE_LEN COUNT(HEATER_5_TEMPTABLE) -#elif defined(HEATER_5_USES_THERMISTOR) - #error "No heater 5 thermistor table specified" +#if TEMP_SENSOR_7 > 0 + #define TEMPTABLE_7 TT_NAME(TEMP_SENSOR_7) + #define TEMPTABLE_7_LEN COUNT(TEMPTABLE_7) #else - #define HEATER_5_TEMPTABLE nullptr - #define HEATER_5_TEMPTABLE_LEN 0 + #define TEMPTABLE_7 nullptr + #define TEMPTABLE_7_LEN 0 #endif -#if THERMISTOR_HEATER_6 - #define HEATER_6_TEMPTABLE TT_NAME(THERMISTOR_HEATER_6) - #define HEATER_6_TEMPTABLE_LEN COUNT(HEATER_6_TEMPTABLE) -#elif defined(HEATER_6_USES_THERMISTOR) - #error "No heater 6 thermistor table specified" +#if TEMP_SENSOR_BED > 0 + #define TEMPTABLE_BED TT_NAME(TEMP_SENSOR_BED) + #define TEMPTABLE_BED_LEN COUNT(TEMPTABLE_BED) #else - #define HEATER_6_TEMPTABLE nullptr - #define HEATER_6_TEMPTABLE_LEN 0 + #define TEMPTABLE_BED_LEN 0 #endif -#if THERMISTOR_HEATER_7 - #define HEATER_7_TEMPTABLE TT_NAME(THERMISTOR_HEATER_7) - #define HEATER_7_TEMPTABLE_LEN COUNT(HEATER_7_TEMPTABLE) -#elif defined(HEATER_7_USES_THERMISTOR) - #error "No heater 7 thermistor table specified" +#if TEMP_SENSOR_CHAMBER > 0 + #define TEMPTABLE_CHAMBER TT_NAME(TEMP_SENSOR_CHAMBER) + #define TEMPTABLE_CHAMBER_LEN COUNT(TEMPTABLE_CHAMBER) #else - #define HEATER_7_TEMPTABLE nullptr - #define HEATER_7_TEMPTABLE_LEN 0 + #define TEMPTABLE_CHAMBER_LEN 0 #endif -#ifdef THERMISTORBED - #define BED_TEMPTABLE TT_NAME(THERMISTORBED) - #define BED_TEMPTABLE_LEN COUNT(BED_TEMPTABLE) -#elif defined(HEATER_BED_USES_THERMISTOR) - #error "No bed thermistor table specified" +#if TEMP_SENSOR_COOLER > 0 + #define TEMPTABLE_COOLER TT_NAME(TEMP_SENSOR_COOLER) + #define TEMPTABLE_COOLER_LEN COUNT(TEMPTABLE_COOLER) #else - #define BED_TEMPTABLE_LEN 0 + #define TEMPTABLE_COOLER_LEN 0 #endif -#ifdef THERMISTORCHAMBER - #define CHAMBER_TEMPTABLE TT_NAME(THERMISTORCHAMBER) - #define CHAMBER_TEMPTABLE_LEN COUNT(CHAMBER_TEMPTABLE) -#elif defined(HEATER_CHAMBER_USES_THERMISTOR) - #error "No chamber thermistor table specified" +#if TEMP_SENSOR_PROBE > 0 + #define TEMPTABLE_PROBE TT_NAME(TEMP_SENSOR_PROBE) + #define TEMPTABLE_PROBE_LEN COUNT(TEMPTABLE_PROBE) #else - #define CHAMBER_TEMPTABLE_LEN 0 + #define TEMPTABLE_PROBE_LEN 0 #endif -#ifdef THERMISTORPROBE - #define PROBE_TEMPTABLE TT_NAME(THERMISTORPROBE) - #define PROBE_TEMPTABLE_LEN COUNT(PROBE_TEMPTABLE) -#elif defined(HEATER_PROBE_USES_THERMISTOR) - #error "No probe thermistor table specified" +#if TEMP_SENSOR_REDUNDANT > 0 + #define TEMPTABLE_REDUNDANT TT_NAME(TEMP_SENSOR_REDUNDANT) + #define TEMPTABLE_REDUNDANT_LEN COUNT(TEMPTABLE_REDUNDANT) #else - #define PROBE_TEMPTABLE_LEN 0 + #define TEMPTABLE_REDUNDANT_LEN 0 #endif // The SCAN_THERMISTOR_TABLE macro needs alteration? -static_assert( - HEATER_0_TEMPTABLE_LEN < 256 && HEATER_1_TEMPTABLE_LEN < 256 - && HEATER_2_TEMPTABLE_LEN < 256 && HEATER_3_TEMPTABLE_LEN < 256 - && HEATER_4_TEMPTABLE_LEN < 256 && HEATER_5_TEMPTABLE_LEN < 256 - && HEATER_6_TEMPTABLE_LEN < 256 && HEATER_7_TEMPTABLE_LEN < 256 - && BED_TEMPTABLE_LEN < 256 && CHAMBER_TEMPTABLE_LEN < 256 - && PROBE_TEMPTABLE_LEN < 256, - "Temperature conversion tables over 255 entries need special consideration." +static_assert(255 > TEMPTABLE_0_LEN || 255 > TEMPTABLE_1_LEN || 255 > TEMPTABLE_2_LEN || 255 > TEMPTABLE_3_LEN + || 255 > TEMPTABLE_4_LEN || 255 > TEMPTABLE_5_LEN || 255 > TEMPTABLE_6_LEN || 255 > TEMPTABLE_7_LEN + || 255 > TEMPTABLE_BED_LEN + || 255 > TEMPTABLE_CHAMBER_LEN + || 255 > TEMPTABLE_COOLER_LEN + || 255 > TEMPTABLE_PROBE_LEN + || 255 > TEMPTABLE_REDUNDANT_LEN + , "Temperature conversion tables over 255 entries need special consideration." ); // Set the high and low raw values for the heaters // For thermistors the highest temperature results in the lowest ADC value // For thermocouples the highest temperature results in the highest ADC value -#define _TT_REV(N) REVERSE_TEMP_SENSOR_RANGE_##N -#define TT_REV(N) _TT_REV(N) +#define _TT_REV(N) REVERSE_TEMP_SENSOR_RANGE_##N +#define TT_REV(N) TERN0(TEMP_SENSOR_##N##_IS_THERMISTOR, DEFER4(_TT_REV)(TEMP_SENSOR_##N)) +#define _TT_REVRAW(N) !TEMP_SENSOR_##N##_IS_THERMISTOR +#define TT_REVRAW(N) (TT_REV(N) || _TT_REVRAW(N)) -#ifdef HEATER_0_TEMPTABLE - #if TT_REV(THERMISTOR_HEATER_0) - #define HEATER_0_SENSOR_MINTEMP_IND 0 - #define HEATER_0_SENSOR_MAXTEMP_IND HEATER_0_TEMPTABLE_LEN - 1 +#ifdef TEMPTABLE_0 + #if TT_REV(0) + #define TEMP_SENSOR_0_MINTEMP_IND 0 + #define TEMP_SENSOR_0_MAXTEMP_IND TEMPTABLE_0_LEN - 1 #else - #define HEATER_0_SENSOR_MINTEMP_IND HEATER_0_TEMPTABLE_LEN - 1 - #define HEATER_0_SENSOR_MAXTEMP_IND 0 + #define TEMP_SENSOR_0_MINTEMP_IND TEMPTABLE_0_LEN - 1 + #define TEMP_SENSOR_0_MAXTEMP_IND 0 #endif #endif -#ifdef HEATER_1_TEMPTABLE - #if TT_REV(THERMISTOR_HEATER_1) - #define HEATER_1_SENSOR_MINTEMP_IND 0 - #define HEATER_1_SENSOR_MAXTEMP_IND HEATER_1_TEMPTABLE_LEN - 1 +#ifdef TEMPTABLE_1 + #if TT_REV(1) + #define TEMP_SENSOR_1_MINTEMP_IND 0 + #define TEMP_SENSOR_1_MAXTEMP_IND TEMPTABLE_1_LEN - 1 #else - #define HEATER_1_SENSOR_MINTEMP_IND HEATER_1_TEMPTABLE_LEN - 1 - #define HEATER_1_SENSOR_MAXTEMP_IND 0 + #define TEMP_SENSOR_1_MINTEMP_IND TEMPTABLE_1_LEN - 1 + #define TEMP_SENSOR_1_MAXTEMP_IND 0 #endif #endif -#ifdef HEATER_2_TEMPTABLE - #if TT_REV(THERMISTOR_HEATER_2) - #define HEATER_2_SENSOR_MINTEMP_IND 0 - #define HEATER_2_SENSOR_MAXTEMP_IND HEATER_2_TEMPTABLE_LEN - 1 +#ifdef TEMPTABLE_2 + #if TT_REV(2) + #define TEMP_SENSOR_2_MINTEMP_IND 0 + #define TEMP_SENSOR_2_MAXTEMP_IND TEMPTABLE_2_LEN - 1 #else - #define HEATER_2_SENSOR_MINTEMP_IND HEATER_2_TEMPTABLE_LEN - 1 - #define HEATER_2_SENSOR_MAXTEMP_IND 0 + #define TEMP_SENSOR_2_MINTEMP_IND TEMPTABLE_2_LEN - 1 + #define TEMP_SENSOR_2_MAXTEMP_IND 0 #endif #endif -#ifdef HEATER_3_TEMPTABLE - #if TT_REV(THERMISTOR_HEATER_3) - #define HEATER_3_SENSOR_MINTEMP_IND 0 - #define HEATER_3_SENSOR_MAXTEMP_IND HEATER_3_TEMPTABLE_LEN - 1 +#ifdef TEMPTABLE_3 + #if TT_REV(3) + #define TEMP_SENSOR_3_MINTEMP_IND 0 + #define TEMP_SENSOR_3_MAXTEMP_IND TEMPTABLE_3_LEN - 1 #else - #define HEATER_3_SENSOR_MINTEMP_IND HEATER_3_TEMPTABLE_LEN - 1 - #define HEATER_3_SENSOR_MAXTEMP_IND 0 + #define TEMP_SENSOR_3_MINTEMP_IND TEMPTABLE_3_LEN - 1 + #define TEMP_SENSOR_3_MAXTEMP_IND 0 #endif #endif -#ifdef HEATER_4_TEMPTABLE - #if TT_REV(THERMISTOR_HEATER_4) - #define HEATER_4_SENSOR_MINTEMP_IND 0 - #define HEATER_4_SENSOR_MAXTEMP_IND HEATER_4_TEMPTABLE_LEN - 1 +#ifdef TEMPTABLE_4 + #if TT_REV(4) + #define TEMP_SENSOR_4_MINTEMP_IND 0 + #define TEMP_SENSOR_4_MAXTEMP_IND TEMPTABLE_4_LEN - 1 #else - #define HEATER_4_SENSOR_MINTEMP_IND HEATER_4_TEMPTABLE_LEN - 1 - #define HEATER_4_SENSOR_MAXTEMP_IND 0 + #define TEMP_SENSOR_4_MINTEMP_IND TEMPTABLE_4_LEN - 1 + #define TEMP_SENSOR_4_MAXTEMP_IND 0 #endif #endif -#ifdef HEATER_5_TEMPTABLE - #if TT_REV(THERMISTOR_HEATER_5) - #define HEATER_5_SENSOR_MINTEMP_IND 0 - #define HEATER_5_SENSOR_MAXTEMP_IND HEATER_5_TEMPTABLE_LEN - 1 +#ifdef TEMPTABLE_5 + #if TT_REV(5) + #define TEMP_SENSOR_5_MINTEMP_IND 0 + #define TEMP_SENSOR_5_MAXTEMP_IND TEMPTABLE_5_LEN - 1 #else - #define HEATER_5_SENSOR_MINTEMP_IND HEATER_5_TEMPTABLE_LEN - 1 - #define HEATER_5_SENSOR_MAXTEMP_IND 0 + #define TEMP_SENSOR_5_MINTEMP_IND TEMPTABLE_5_LEN - 1 + #define TEMP_SENSOR_5_MAXTEMP_IND 0 #endif #endif -#ifdef HEATER_6_TEMPTABLE - #if TT_REV(THERMISTOR_HEATER_6) - #define HEATER_6_SENSOR_MINTEMP_IND 0 - #define HEATER_6_SENSOR_MAXTEMP_IND HEATER_6_TEMPTABLE_LEN - 1 +#ifdef TEMPTABLE_6 + #if TT_REV(6) + #define TEMP_SENSOR_6_MINTEMP_IND 0 + #define TEMP_SENSOR_6_MAXTEMP_IND TEMPTABLE_6_LEN - 1 #else - #define HEATER_6_SENSOR_MINTEMP_IND HEATER_6_TEMPTABLE_LEN - 1 - #define HEATER_6_SENSOR_MAXTEMP_IND 0 + #define TEMP_SENSOR_6_MINTEMP_IND TEMPTABLE_6_LEN - 1 + #define TEMP_SENSOR_6_MAXTEMP_IND 0 #endif #endif -#ifdef HEATER_7_TEMPTABLE - #if TT_REV(THERMISTOR_HEATER_7) - #define HEATER_7_SENSOR_MINTEMP_IND 0 - #define HEATER_7_SENSOR_MAXTEMP_IND HEATER_7_TEMPTABLE_LEN - 1 +#ifdef TEMPTABLE_7 + #if TT_REV(7) + #define TEMP_SENSOR_7_MINTEMP_IND 0 + #define TEMP_SENSOR_7_MAXTEMP_IND TEMPTABLE_7_LEN - 1 #else - #define HEATER_7_SENSOR_MINTEMP_IND HEATER_7_TEMPTABLE_LEN - 1 - #define HEATER_7_SENSOR_MAXTEMP_IND 0 + #define TEMP_SENSOR_7_MINTEMP_IND TEMPTABLE_7_LEN - 1 + #define TEMP_SENSOR_7_MAXTEMP_IND 0 #endif #endif -#ifndef HEATER_0_RAW_HI_TEMP - #if TT_REV(THERMISTOR_HEATER_0) || !defined(HEATER_0_USES_THERMISTOR) - #define HEATER_0_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE - #define HEATER_0_RAW_LO_TEMP 0 +#ifndef TEMP_SENSOR_0_RAW_HI_TEMP + #if TT_REVRAW(0) + #define TEMP_SENSOR_0_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE + #define TEMP_SENSOR_0_RAW_LO_TEMP 0 + #else + #define TEMP_SENSOR_0_RAW_HI_TEMP 0 + #define TEMP_SENSOR_0_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE + #endif +#endif +#ifndef TEMP_SENSOR_1_RAW_HI_TEMP + #if TT_REVRAW(1) + #define TEMP_SENSOR_1_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE + #define TEMP_SENSOR_1_RAW_LO_TEMP 0 + #else + #define TEMP_SENSOR_1_RAW_HI_TEMP 0 + #define TEMP_SENSOR_1_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE + #endif +#endif +#ifndef TEMP_SENSOR_2_RAW_HI_TEMP + #if TT_REVRAW(2) + #define TEMP_SENSOR_2_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE + #define TEMP_SENSOR_2_RAW_LO_TEMP 0 #else - #define HEATER_0_RAW_HI_TEMP 0 - #define HEATER_0_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE + #define TEMP_SENSOR_2_RAW_HI_TEMP 0 + #define TEMP_SENSOR_2_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE #endif #endif -#ifndef HEATER_1_RAW_HI_TEMP - #if TT_REV(THERMISTOR_HEATER_1) || !defined(HEATER_1_USES_THERMISTOR) - #define HEATER_1_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE - #define HEATER_1_RAW_LO_TEMP 0 +#ifndef TEMP_SENSOR_3_RAW_HI_TEMP + #if TT_REVRAW(3) + #define TEMP_SENSOR_3_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE + #define TEMP_SENSOR_3_RAW_LO_TEMP 0 #else - #define HEATER_1_RAW_HI_TEMP 0 - #define HEATER_1_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE + #define TEMP_SENSOR_3_RAW_HI_TEMP 0 + #define TEMP_SENSOR_3_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE #endif #endif -#ifndef HEATER_2_RAW_HI_TEMP - #if TT_REV(THERMISTOR_HEATER_2) || !defined(HEATER_2_USES_THERMISTOR) - #define HEATER_2_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE - #define HEATER_2_RAW_LO_TEMP 0 +#ifndef TEMP_SENSOR_4_RAW_HI_TEMP + #if TT_REVRAW(4) + #define TEMP_SENSOR_4_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE + #define TEMP_SENSOR_4_RAW_LO_TEMP 0 #else - #define HEATER_2_RAW_HI_TEMP 0 - #define HEATER_2_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE + #define TEMP_SENSOR_4_RAW_HI_TEMP 0 + #define TEMP_SENSOR_4_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE #endif #endif -#ifndef HEATER_3_RAW_HI_TEMP - #if TT_REV(THERMISTOR_HEATER_3) || !defined(HEATER_3_USES_THERMISTOR) - #define HEATER_3_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE - #define HEATER_3_RAW_LO_TEMP 0 +#ifndef TEMP_SENSOR_5_RAW_HI_TEMP + #if TT_REVRAW(5) + #define TEMP_SENSOR_5_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE + #define TEMP_SENSOR_5_RAW_LO_TEMP 0 #else - #define HEATER_3_RAW_HI_TEMP 0 - #define HEATER_3_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE + #define TEMP_SENSOR_5_RAW_HI_TEMP 0 + #define TEMP_SENSOR_5_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE #endif #endif -#ifndef HEATER_4_RAW_HI_TEMP - #if TT_REV(THERMISTOR_HEATER_4) || !defined(HEATER_4_USES_THERMISTOR) - #define HEATER_4_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE - #define HEATER_4_RAW_LO_TEMP 0 +#ifndef TEMP_SENSOR_6_RAW_HI_TEMP + #if TT_REVRAW(6) + #define TEMP_SENSOR_6_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE + #define TEMP_SENSOR_6_RAW_LO_TEMP 0 #else - #define HEATER_4_RAW_HI_TEMP 0 - #define HEATER_4_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE + #define TEMP_SENSOR_6_RAW_HI_TEMP 0 + #define TEMP_SENSOR_6_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE #endif #endif -#ifndef HEATER_5_RAW_HI_TEMP - #if TT_REV(THERMISTOR_HEATER_5) || !defined(HEATER_5_USES_THERMISTOR) - #define HEATER_5_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE - #define HEATER_5_RAW_LO_TEMP 0 +#ifndef TEMP_SENSOR_7_RAW_HI_TEMP + #if TT_REVRAW(7) + #define TEMP_SENSOR_7_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE + #define TEMP_SENSOR_7_RAW_LO_TEMP 0 #else - #define HEATER_5_RAW_HI_TEMP 0 - #define HEATER_5_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE + #define TEMP_SENSOR_7_RAW_HI_TEMP 0 + #define TEMP_SENSOR_7_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE #endif #endif -#ifndef HEATER_6_RAW_HI_TEMP - #if TT_REV(THERMISTOR_HEATER_6) || !defined(HEATER_6_USES_THERMISTOR) - #define HEATER_6_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE - #define HEATER_6_RAW_LO_TEMP 0 +#ifndef TEMP_SENSOR_BED_RAW_HI_TEMP + #if TT_REVRAW(BED) + #define TEMP_SENSOR_BED_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE + #define TEMP_SENSOR_BED_RAW_LO_TEMP 0 #else - #define HEATER_6_RAW_HI_TEMP 0 - #define HEATER_6_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE + #define TEMP_SENSOR_BED_RAW_HI_TEMP 0 + #define TEMP_SENSOR_BED_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE #endif #endif -#ifndef HEATER_7_RAW_HI_TEMP - #if TT_REV(THERMISTOR_HEATER_7) || !defined(HEATER_7_USES_THERMISTOR) - #define HEATER_7_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE - #define HEATER_7_RAW_LO_TEMP 0 +#ifndef TEMP_SENSOR_CHAMBER_RAW_HI_TEMP + #if TT_REVRAW(CHAMBER) + #define TEMP_SENSOR_CHAMBER_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE + #define TEMP_SENSOR_CHAMBER_RAW_LO_TEMP 0 #else - #define HEATER_7_RAW_HI_TEMP 0 - #define HEATER_7_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE + #define TEMP_SENSOR_CHAMBER_RAW_HI_TEMP 0 + #define TEMP_SENSOR_CHAMBER_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE #endif #endif -#ifndef HEATER_BED_RAW_HI_TEMP - #if TT_REV(THERMISTORBED) || !defined(HEATER_BED_USES_THERMISTOR) - #define HEATER_BED_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE - #define HEATER_BED_RAW_LO_TEMP 0 +#ifndef TEMP_SENSOR_COOLER_RAW_HI_TEMP + #if TT_REVRAW(COOLER) + #define TEMP_SENSOR_COOLER_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE + #define TEMP_SENSOR_COOLER_RAW_LO_TEMP 0 #else - #define HEATER_BED_RAW_HI_TEMP 0 - #define HEATER_BED_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE + #define TEMP_SENSOR_COOLER_RAW_HI_TEMP 0 + #define TEMP_SENSOR_COOLER_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE #endif #endif -#ifndef HEATER_CHAMBER_RAW_HI_TEMP - #if TT_REV(THERMISTORCHAMBER) || !defined(HEATER_CHAMBER_USES_THERMISTOR) - #define HEATER_CHAMBER_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE - #define HEATER_CHAMBER_RAW_LO_TEMP 0 +#ifndef TEMP_SENSOR_PROBE_RAW_HI_TEMP + #if TT_REVRAW(PROBE) + #define TEMP_SENSOR_PROBE_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE + #define TEMP_SENSOR_PROBE_RAW_LO_TEMP 0 #else - #define HEATER_CHAMBER_RAW_HI_TEMP 0 - #define HEATER_CHAMBER_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE + #define TEMP_SENSOR_PROBE_RAW_HI_TEMP 0 + #define TEMP_SENSOR_PROBE_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE #endif #endif -#ifndef HEATER_PROBE_RAW_HI_TEMP - #if TT_REV(THERMISTORPROBE) || !defined(HEATER_PROBE_USES_THERMISTOR) - #define HEATER_PROBE_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE - #define HEATER_PROBE_RAW_LO_TEMP 0 +#ifndef TEMP_SENSOR_REDUNDANT_RAW_HI_TEMP + #if TT_REVRAW(REDUNDANT) + #define TEMP_SENSOR_REDUNDANT_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE + #define TEMP_SENSOR_REDUNDANT_RAW_LO_TEMP 0 #else - #define HEATER_PROBE_RAW_HI_TEMP 0 - #define HEATER_PROBE_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE + #define TEMP_SENSOR_REDUNDANT_RAW_HI_TEMP 0 + #define TEMP_SENSOR_REDUNDANT_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE #endif #endif +#undef __TT_REV #undef _TT_REV #undef TT_REV +#undef _TT_REVRAW +#undef TT_REVRAW diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index 4ab818f41d2e..6d69b8722dde 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -49,16 +49,18 @@ bool toolchange_extruder_ready[EXTRUDERS]; #endif -#if ENABLED(SINGLENOZZLE_STANDBY_TEMP) - uint16_t singlenozzle_temp[EXTRUDERS]; +#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 BOTH(HAS_FAN, SINGLENOZZLE_STANDBY_FAN) - uint8_t singlenozzle_fan_speed[EXTRUDERS]; +#if ENABLED(TOOL_SENSOR) + #include "../lcd/marlinui.h" #endif -#if ENABLED(MAGNETIC_PARKING_EXTRUDER) || defined(EVENT_GCODE_AFTER_TOOLCHANGE) || (ENABLED(PARKING_EXTRUDER) && PARKING_EXTRUDER_SOLENOIDS_DELAY > 0) - #include "../gcode/gcode.h" +#if ENABLED(DUAL_X_CARRIAGE) + #include "stepper.h" #endif #if ANY(SWITCHING_EXTRUDER, SWITCHING_NOZZLE, SWITCHING_TOOLHEAD) @@ -69,10 +71,6 @@ #include "../feature/solenoid.h" #endif -#if ENABLED(MK2_MULTIPLEXER) - #include "../feature/snmm.h" -#endif - #if ENABLED(MIXING_EXTRUDER) #include "../feature/mixing.h" #endif @@ -85,12 +83,14 @@ #include "../feature/fanmux.h" #endif -#if ENABLED(PRUSA_MMU2) - #include "../feature/mmu2/mmu2.h" +#if HAS_PRUSA_MMU1 + #include "../feature/mmu/mmu.h" +#elif HAS_PRUSA_MMU2 + #include "../feature/mmu/mmu2.h" #endif #if HAS_LCD_MENU - #include "../lcd/ultralcd.h" + #include "../lcd/marlinui.h" #endif #if ENABLED(ADVANCED_PAUSE_FEATURE) @@ -115,11 +115,8 @@ void move_extruder_servo(const uint8_t e) { planner.synchronize(); - #if EXTRUDERS & 1 - if (e < EXTRUDERS - 1) - #endif - { - MOVE_SERVO(_SERVO_NR(e), servo_angles[_SERVO_NR(e)][e]); + if ((EXTRUDERS & 1) && e < EXTRUDERS - 1) { + MOVE_SERVO(_SERVO_NR(e), servo_angles[_SERVO_NR(e)][e & 1]); safe_delay(500); } } @@ -153,11 +150,11 @@ #endif // SWITCHING_NOZZLE -inline void _line_to_current(const AxisEnum fr_axis, const float fscale=1) { +void _line_to_current(const AxisEnum fr_axis, const float fscale=1) { line_to_current_position(planner.settings.max_feedrate_mm_s[fr_axis] * fscale); } -inline void slow_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0.5f); } -inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis); } +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); } #if ENABLED(MAGNETIC_PARKING_EXTRUDER) @@ -192,7 +189,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a current_position.x = mpe_settings.parking_xpos[new_tool] + offsetcompensation; - DEBUG_ECHOPAIR("(1) Move extruder ", int(new_tool)); + DEBUG_ECHOPAIR("(1) Move extruder ", new_tool); DEBUG_POS(" to new extruder ParkPos", current_position); planner.buffer_line(current_position, mpe_settings.fast_feedrate, new_tool); @@ -202,7 +199,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a current_position.x = grabpos + offsetcompensation; - DEBUG_ECHOPAIR("(2) Couple extruder ", int(new_tool)); + DEBUG_ECHOPAIR("(2) Couple extruder ", new_tool); DEBUG_POS(" to new extruder GrabPos", current_position); planner.buffer_line(current_position, mpe_settings.slow_feedrate, new_tool); @@ -215,7 +212,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a current_position.x = mpe_settings.parking_xpos[new_tool] + offsetcompensation; - DEBUG_ECHOPAIR("(3) Move extruder ", int(new_tool)); + DEBUG_ECHOPAIR("(3) Move extruder ", new_tool); DEBUG_POS(" back to new extruder ParkPos", current_position); planner.buffer_line(current_position, mpe_settings.slow_feedrate, new_tool); @@ -225,7 +222,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a current_position.x = mpe_settings.parking_xpos[active_extruder] + (active_extruder == 0 ? MPE_TRAVEL_DISTANCE : -MPE_TRAVEL_DISTANCE) + offsetcompensation; - DEBUG_ECHOPAIR("(4) Move extruder ", int(new_tool)); + DEBUG_ECHOPAIR("(4) Move extruder ", new_tool); DEBUG_POS(" close to old extruder ParkPos", current_position); planner.buffer_line(current_position, mpe_settings.fast_feedrate, new_tool); @@ -235,7 +232,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a current_position.x = mpe_settings.parking_xpos[active_extruder] + offsetcompensation; - DEBUG_ECHOPAIR("(5) Park extruder ", int(new_tool)); + DEBUG_ECHOPAIR("(5) Park extruder ", new_tool); DEBUG_POS(" at old extruder ParkPos", current_position); planner.buffer_line(current_position, mpe_settings.slow_feedrate, new_tool); @@ -245,7 +242,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a current_position.x = oldx; - DEBUG_ECHOPAIR("(6) Move extruder ", int(new_tool)); + DEBUG_ECHOPAIR("(6) Move extruder ", new_tool); DEBUG_POS(" to starting position", current_position); planner.buffer_line(current_position, mpe_settings.fast_feedrate, new_tool); @@ -257,15 +254,10 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a #elif ENABLED(PARKING_EXTRUDER) void pe_solenoid_init() { - LOOP_LE_N(n, 1) - #if ENABLED(PARKING_EXTRUDER_SOLENOIDS_INVERT) - pe_activate_solenoid(n); - #else - pe_deactivate_solenoid(n); - #endif + LOOP_LE_N(n, 1) pe_solenoid_set_pin_state(n, !PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE); } - void pe_set_solenoid(const uint8_t extruder_num, const uint8_t state) { + void pe_solenoid_set_pin_state(const uint8_t extruder_num, const uint8_t state) { switch (extruder_num) { case 1: OUT_WRITE(SOL1_PIN, state); break; default: OUT_WRITE(SOL0_PIN, state); break; @@ -275,6 +267,26 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a #endif } + bool extruder_parked = true, do_solenoid_activation = true; + + // Modifies tool_change() behavior based on homing side + bool parking_extruder_unpark_after_homing(const uint8_t final_tool, bool homed_towards_final_tool) { + do_solenoid_activation = false; // Tell parking_extruder_tool_change to skip solenoid activation + + if (!extruder_parked) return false; // nothing to do + + if (homed_towards_final_tool) { + pe_solenoid_magnet_off(1 - final_tool); + DEBUG_ECHOLNPAIR("Disengage magnet", 1 - final_tool); + pe_solenoid_magnet_on(final_tool); + DEBUG_ECHOLNPAIR("Engage magnet", final_tool); + parking_extruder_set_parked(false); + return false; + } + + return true; + } + inline void parking_extruder_tool_change(const uint8_t new_tool, bool no_move) { if (!no_move) { @@ -302,27 +314,30 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a DEBUG_POS("Start PE Tool-Change", current_position); - current_position.x = parkingposx[active_extruder] + x_offset; + // Don't park the active_extruder unless unparked + if (!extruder_parked) { + current_position.x = parkingposx[active_extruder] + x_offset; - DEBUG_ECHOLNPAIR("(1) Park extruder ", int(active_extruder)); - DEBUG_POS("Moving ParkPos", current_position); + DEBUG_ECHOLNPAIR("(1) Park extruder ", active_extruder); + DEBUG_POS("Moving ParkPos", current_position); - fast_line_to_current(X_AXIS); + fast_line_to_current(X_AXIS); - // STEP 2 + // STEP 2 - planner.synchronize(); - DEBUG_ECHOLNPGM("(2) Disengage magnet"); - pe_deactivate_solenoid(active_extruder); + planner.synchronize(); + DEBUG_ECHOLNPGM("(2) Disengage magnet"); + pe_solenoid_magnet_off(active_extruder); - // STEP 3 + // STEP 3 - current_position.x += active_extruder ? -10 : 10; // move 10mm away from parked extruder + current_position.x += active_extruder ? -10 : 10; // move 10mm away from parked extruder - DEBUG_ECHOLNPGM("(3) Move near new extruder"); - DEBUG_POS("Move away from parked extruder", current_position); + DEBUG_ECHOLNPGM("(3) Move near new extruder"); + DEBUG_POS("Move away from parked extruder", current_position); - fast_line_to_current(X_AXIS); + fast_line_to_current(X_AXIS); + } // STEP 4 @@ -330,8 +345,8 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a DEBUG_ECHOLNPGM("(4) Engage magnetic field"); // Just save power for inverted magnets - TERN_(PARKING_EXTRUDER_SOLENOIDS_INVERT, pe_activate_solenoid(active_extruder)); - pe_activate_solenoid(new_tool); + TERN_(PARKING_EXTRUDER_SOLENOIDS_INVERT, pe_solenoid_magnet_on(active_extruder)); + pe_solenoid_magnet_on(new_tool); // STEP 5 @@ -347,7 +362,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a // STEP 6 - current_position.x = midpos - TERN0(HAS_HOTEND_OFFSET, hotend_offset[new_tool].x); + current_position.x = DIFF_TERN(HAS_HOTEND_OFFSET, midpos, hotend_offset[new_tool].x); DEBUG_SYNCHRONIZE(); DEBUG_POS("(6) Move midway between hotends", current_position); @@ -356,25 +371,133 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a planner.synchronize(); // Always sync the final move DEBUG_POS("PE Tool-Change done.", current_position); + parking_extruder_set_parked(false); } - else { // nomove == true - // Only engage magnetic field for new extruder - pe_activate_solenoid(new_tool); - // Just save power for inverted magnets - TERN_(PARKING_EXTRUDER_SOLENOIDS_INVERT, pe_activate_solenoid(active_extruder)); + else if (do_solenoid_activation) { + // Deactivate current extruder solenoid + pe_solenoid_set_pin_state(active_extruder, !PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE); + // Engage new extruder magnetic field + pe_solenoid_set_pin_state(new_tool, PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE); } + + do_solenoid_activation = true; // Activate solenoid for subsequent tool_change() } #endif // PARKING_EXTRUDER #if ENABLED(SWITCHING_TOOLHEAD) - inline void swt_lock(const bool locked=true) { - const uint16_t swt_angles[2] = SWITCHING_TOOLHEAD_SERVO_ANGLES; - MOVE_SERVO(SWITCHING_TOOLHEAD_SERVO_NR, swt_angles[locked ? 0 : 1]); + // Return a bitmask of tool sensor states + inline uint8_t poll_tool_sensor_pins() { + return (0 + #if ENABLED(TOOL_SENSOR) + #if PIN_EXISTS(TOOL_SENSOR1) + | (READ(TOOL_SENSOR1_PIN) << 0) + #endif + #if PIN_EXISTS(TOOL_SENSOR2) + | (READ(TOOL_SENSOR2_PIN) << 1) + #endif + #if PIN_EXISTS(TOOL_SENSOR3) + | (READ(TOOL_SENSOR3_PIN) << 2) + #endif + #if PIN_EXISTS(TOOL_SENSOR4) + | (READ(TOOL_SENSOR4_PIN) << 3) + #endif + #if PIN_EXISTS(TOOL_SENSOR5) + | (READ(TOOL_SENSOR5_PIN) << 4) + #endif + #if PIN_EXISTS(TOOL_SENSOR6) + | (READ(TOOL_SENSOR6_PIN) << 5) + #endif + #if PIN_EXISTS(TOOL_SENSOR7) + | (READ(TOOL_SENSOR7_PIN) << 6) + #endif + #if PIN_EXISTS(TOOL_SENSOR8) + | (READ(TOOL_SENSOR8_PIN) << 7) + #endif + #endif + ); } - void swt_init() { swt_lock(); } + #if ENABLED(TOOL_SENSOR) + + bool tool_sensor_disabled; // = false + + uint8_t check_tool_sensor_stats(const uint8_t tool_index, const bool kill_on_error/*=false*/, const bool disable/*=false*/) { + static uint8_t sensor_tries; // = 0 + for (;;) { + if (poll_tool_sensor_pins() == _BV(tool_index)) { + sensor_tries = 0; + return tool_index; + } + else if (kill_on_error && (!tool_sensor_disabled || disable)) { + sensor_tries++; + if (sensor_tries > 10) kill(PSTR("Tool Sensor error")); + safe_delay(5); + } + else { + sensor_tries++; + if (sensor_tries > 10) return -1; + safe_delay(5); + } + } + } + + #endif + + inline void switching_toolhead_lock(const bool locked) { + #ifdef SWITCHING_TOOLHEAD_SERVO_ANGLES + const uint16_t swt_angles[2] = SWITCHING_TOOLHEAD_SERVO_ANGLES; + MOVE_SERVO(SWITCHING_TOOLHEAD_SERVO_NR, swt_angles[locked ? 0 : 1]); + #elif PIN_EXISTS(SWT_SOLENOID) + OUT_WRITE(SWT_SOLENOID_PIN, locked); + gcode.dwell(10); + #else + #error "No toolhead locking mechanism configured." + #endif + } + + #include + + void swt_init() { + switching_toolhead_lock(true); + + #if ENABLED(TOOL_SENSOR) + // Init tool sensors + #if PIN_EXISTS(TOOL_SENSOR1) + SET_INPUT_PULLUP(TOOL_SENSOR1_PIN); + #endif + #if PIN_EXISTS(TOOL_SENSOR2) + SET_INPUT_PULLUP(TOOL_SENSOR2_PIN); + #endif + #if PIN_EXISTS(TOOL_SENSOR3) + SET_INPUT_PULLUP(TOOL_SENSOR3_PIN); + #endif + #if PIN_EXISTS(TOOL_SENSOR4) + SET_INPUT_PULLUP(TOOL_SENSOR4_PIN); + #endif + #if PIN_EXISTS(TOOL_SENSOR5) + SET_INPUT_PULLUP(TOOL_SENSOR5_PIN); + #endif + #if PIN_EXISTS(TOOL_SENSOR6) + SET_INPUT_PULLUP(TOOL_SENSOR6_PIN); + #endif + #if PIN_EXISTS(TOOL_SENSOR7) + SET_INPUT_PULLUP(TOOL_SENSOR7_PIN); + #endif + #if PIN_EXISTS(TOOL_SENSOR8) + SET_INPUT_PULLUP(TOOL_SENSOR8_PIN); + #endif + + if (check_tool_sensor_stats(0)) { + ui.set_status_P("TC error"); + switching_toolhead_lock(false); + while (check_tool_sensor_stats(0)) { /* nada */ } + switching_toolhead_lock(true); + } + ui.set_status_P("TC Success"); + #endif + } inline void switching_toolhead_tool_change(const uint8_t new_tool, bool no_move/*=false*/) { if (no_move) return; @@ -383,6 +506,8 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a const float placexpos = toolheadposx[active_extruder], grabxpos = toolheadposx[new_tool]; + (void)check_tool_sensor_stats(active_extruder, true); + /** * 1. Move to switch position of current toolhead * 2. Unlock tool and drop it in the dock @@ -396,7 +521,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a current_position.x = placexpos; - DEBUG_ECHOLNPAIR("(1) Place old tool ", int(active_extruder)); + DEBUG_ECHOLNPAIR("(1) Place old tool ", active_extruder); DEBUG_POS("Move X SwitchPos", current_position); fast_line_to_current(X_AXIS); @@ -406,13 +531,14 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a DEBUG_SYNCHRONIZE(); DEBUG_POS("Move Y SwitchPos + Security", current_position); - fast_line_to_current(Y_AXIS); + slow_line_to_current(Y_AXIS); // 2. Unlock tool and drop it in the dock + TERN_(TOOL_SENSOR, tool_sensor_disabled = true); planner.synchronize(); DEBUG_ECHOLNPGM("(2) Unlock and Place Toolhead"); - swt_lock(false); + switching_toolhead_lock(false); safe_delay(500); current_position.y = SWITCHING_TOOLHEAD_Y_POS; @@ -425,7 +551,9 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a current_position.y -= SWITCHING_TOOLHEAD_Y_CLEAR; DEBUG_POS("Move back Y clear", current_position); - fast_line_to_current(Y_AXIS); // move away from docked toolhead + slow_line_to_current(Y_AXIS); // move away from docked toolhead + + (void)check_tool_sensor_stats(active_extruder); // 3. Move to the new toolhead @@ -442,7 +570,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a DEBUG_SYNCHRONIZE(); DEBUG_POS("Move Y SwitchPos + Security", current_position); - fast_line_to_current(Y_AXIS); + slow_line_to_current(Y_AXIS); // 4. Grab and lock the new toolhead @@ -457,14 +585,19 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a // Wait for move to finish, pause 0.2s, move servo, pause 0.5s planner.synchronize(); safe_delay(200); - swt_lock(); + + (void)check_tool_sensor_stats(new_tool, true, true); + + switching_toolhead_lock(true); safe_delay(500); current_position.y -= SWITCHING_TOOLHEAD_Y_CLEAR; DEBUG_POS("Move back Y clear", current_position); - fast_line_to_current(Y_AXIS); // Move away from docked toolhead + slow_line_to_current(Y_AXIS); // Move away from docked toolhead planner.synchronize(); // Always sync the final move + (void)check_tool_sensor_stats(new_tool, true, true); + DEBUG_POS("ST Tool-Change done.", current_position); } @@ -494,7 +627,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a current_position.y = SWITCHING_TOOLHEAD_Y_POS + SWITCHING_TOOLHEAD_Y_CLEAR; - SERIAL_ECHOLNPAIR("(1) Place old tool ", int(active_extruder)); + SERIAL_ECHOLNPAIR("(1) Place old tool ", active_extruder); DEBUG_POS("Move Y SwitchPos + Security", current_position); fast_line_to_current(Y_AXIS); @@ -691,16 +824,23 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a #endif // ELECTROMAGNETIC_SWITCHING_TOOLHEAD -#if EXTRUDERS +#if HAS_EXTRUDERS inline void invalid_extruder_error(const uint8_t e) { SERIAL_ECHO_START(); - SERIAL_CHAR('T'); SERIAL_ECHO(int(e)); + SERIAL_CHAR('T'); SERIAL_ECHO(e); SERIAL_CHAR(' '); SERIAL_ECHOLNPGM(STR_INVALID_EXTRUDER); } #endif #if ENABLED(DUAL_X_CARRIAGE) + /** + * @brief Dual X Tool Change + * @details Change tools, with extra behavior based on current mode + * + * @param new_tool Tool index to activate + * @param no_move Flag indicating no moves should take place + */ inline void dualx_tool_change(const uint8_t new_tool, bool &no_move) { DEBUG_ECHOPGM("Dual X Carriage Mode "); @@ -711,17 +851,16 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a case DXC_MIRRORED_MODE: DEBUG_ECHOLNPGM("MIRRORED"); break; } + // Get the home position of the currently-active tool const float xhome = x_home_pos(active_extruder); - if (dual_x_carriage_mode == DXC_AUTO_PARK_MODE - && IsRunning() && !no_move - && (delayed_move_time || current_position.x != xhome) - ) { + if (dual_x_carriage_mode == DXC_AUTO_PARK_MODE // If Auto-Park mode is enabled + && IsRunning() && !no_move // ...and movement is permitted + && (delayed_move_time || current_position.x != xhome) // ...and delayed_move_time is set OR not "already parked"... + ) { DEBUG_ECHOLNPAIR("MoveX to ", xhome); - - // Park old head current_position.x = xhome; - line_to_current_position(planner.settings.max_feedrate_mm_s[X_AXIS]); + line_to_current_position(planner.settings.max_feedrate_mm_s[X_AXIS]); // Park the current head planner.synchronize(); } @@ -736,20 +875,21 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a switch (dual_x_carriage_mode) { case DXC_FULL_CONTROL_MODE: // New current position is the position of the activated extruder - current_position.x = inactive_extruder_x_pos; + current_position.x = inactive_extruder_x; // Save the inactive extruder's position (from the old current_position) - inactive_extruder_x_pos = destination.x; + inactive_extruder_x = destination.x; + DEBUG_ECHOLNPAIR("DXC Full Control curr.x=", current_position.x, " dest.x=", destination.x); break; case DXC_AUTO_PARK_MODE: - // record current raised toolhead position for use by unpark - raised_parked_position = current_position; - active_extruder_parked = true; - delayed_move_time = 0; + idex_set_parked(); break; default: break; } + // Ensure X axis DIR pertains to the correct carriage + stepper.set_directions(); + DEBUG_ECHOLNPAIR("Active extruder parked: ", active_extruder_parked ? "yes" : "no"); DEBUG_POS("New extruder (parked)", current_position); } @@ -761,75 +901,77 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a */ #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) -void tool_change_prime() { - if (toolchange_settings.extra_prime > 0 - && TERN(PREVENT_COLD_EXTRUSION, !thermalManager.targetTooColdToExtrude(active_extruder), 1) - ) { - destination = current_position; // Remember the old position - - const bool ok = TERN1(TOOLCHANGE_PARK, all_axes_homed() && toolchange_settings.enable_park); + void tool_change_prime() { + if (toolchange_settings.extra_prime > 0 + && TERN(PREVENT_COLD_EXTRUSION, !thermalManager.targetTooColdToExtrude(active_extruder), 1) + ) { + destination = current_position; // Remember the old position - #if HAS_FAN && TOOLCHANGE_FS_FAN >= 0 - // Store and stop fan. Restored on any exit. - REMEMBER(fan, thermalManager.fan_speed[TOOLCHANGE_FS_FAN], 0); - #endif + const bool ok = TERN1(TOOLCHANGE_PARK, all_axes_homed() && toolchange_settings.enable_park); - // Z raise - if (ok) { - // Do a small lift to avoid the workpiece in the move back (below) - current_position.z += toolchange_settings.z_raise; - #if HAS_SOFTWARE_ENDSTOPS - NOMORE(current_position.z, soft_endstop.max.z); + #if HAS_FAN && TOOLCHANGE_FS_FAN >= 0 + // Store and stop fan. Restored on any exit. + REMEMBER(fan, thermalManager.fan_speed[TOOLCHANGE_FS_FAN], 0); #endif - fast_line_to_current(Z_AXIS); - planner.synchronize(); - } - // Park - #if ENABLED(TOOLCHANGE_PARK) + // Z raise if (ok) { - TERN(TOOLCHANGE_PARK_Y_ONLY,,current_position.x = toolchange_settings.change_point.x); - TERN(TOOLCHANGE_PARK_X_ONLY,,current_position.y = toolchange_settings.change_point.y); - planner.buffer_line(current_position, MMM_TO_MMS(TOOLCHANGE_PARK_XY_FEEDRATE), active_extruder); + // Do a small lift to avoid the workpiece in the move back (below) + current_position.z += toolchange_settings.z_raise; + #if HAS_SOFTWARE_ENDSTOPS + NOMORE(current_position.z, soft_endstop.max.z); + #endif + fast_line_to_current(Z_AXIS); planner.synchronize(); } - #endif - // Prime (All distances are added and slowed down to ensure secure priming in all circumstances) - unscaled_e_move(toolchange_settings.swap_length + toolchange_settings.extra_prime, MMM_TO_MMS(toolchange_settings.prime_speed)); + // Park + #if ENABLED(TOOLCHANGE_PARK) + if (ok) { + IF_DISABLED(TOOLCHANGE_PARK_Y_ONLY, current_position.x = toolchange_settings.change_point.x); + IF_DISABLED(TOOLCHANGE_PARK_X_ONLY, current_position.y = toolchange_settings.change_point.y); + planner.buffer_line(current_position, MMM_TO_MMS(TOOLCHANGE_PARK_XY_FEEDRATE), active_extruder); + planner.synchronize(); + } + #endif - // Cutting retraction - #if TOOLCHANGE_FS_WIPE_RETRACT - unscaled_e_move(-(TOOLCHANGE_FS_WIPE_RETRACT), MMM_TO_MMS(toolchange_settings.retract_speed)); - #endif + // Prime (All distances are added and slowed down to ensure secure priming in all circumstances) + unscaled_e_move(toolchange_settings.swap_length + toolchange_settings.extra_prime, MMM_TO_MMS(toolchange_settings.prime_speed)); - // Cool down with fan - #if HAS_FAN && TOOLCHANGE_FS_FAN >= 0 - thermalManager.fan_speed[TOOLCHANGE_FS_FAN] = toolchange_settings.fan_speed; - gcode.dwell(toolchange_settings.fan_time * 1000); - thermalManager.fan_speed[TOOLCHANGE_FS_FAN] = 0; - #endif + // Cutting retraction + #if TOOLCHANGE_FS_WIPE_RETRACT + unscaled_e_move(-(TOOLCHANGE_FS_WIPE_RETRACT), MMM_TO_MMS(toolchange_settings.retract_speed)); + #endif - // Move back - #if ENABLED(TOOLCHANGE_PARK) - if (ok) { - #if ENABLED(TOOLCHANGE_NO_RETURN) - do_blocking_move_to_z(destination.z, planner.settings.max_feedrate_mm_s[Z_AXIS]); - #else - do_blocking_move_to(destination, MMM_TO_MMS(TOOLCHANGE_PARK_XY_FEEDRATE)); - #endif - } - #endif + // Cool down with fan + #if HAS_FAN && TOOLCHANGE_FS_FAN >= 0 + thermalManager.fan_speed[TOOLCHANGE_FS_FAN] = toolchange_settings.fan_speed; + gcode.dwell(SEC_TO_MS(toolchange_settings.fan_time)); + thermalManager.fan_speed[TOOLCHANGE_FS_FAN] = 0; + #endif - // Cutting recover - unscaled_e_move(toolchange_settings.extra_resume + TOOLCHANGE_FS_WIPE_RETRACT, MMM_TO_MMS(toolchange_settings.unretract_speed)); + // Move back + #if ENABLED(TOOLCHANGE_PARK) + if (ok) { + #if ENABLED(TOOLCHANGE_NO_RETURN) + const float temp = destination.z; + destination = current_position; + destination.z = temp.z; + #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))); + } + #endif - planner.synchronize(); - current_position.e = destination.e; - sync_plan_position_e(); // Resume at the old E position + // Cutting recover + unscaled_e_move(toolchange_settings.extra_resume + TOOLCHANGE_FS_WIPE_RETRACT, MMM_TO_MMS(toolchange_settings.unretract_speed)); + + // Resume at the old E position + current_position.e = destination.e; + sync_plan_position_e(); + } } -} -#endif + +#endif // TOOLCHANGE_FILAMENT_SWAP /** * Perform a tool-change, which may result in moving the @@ -852,7 +994,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { mixer.T(new_tool); #endif - #elif ENABLED(PRUSA_MMU2) + #elif HAS_PRUSA_MMU2 UNUSED(no_move); @@ -875,7 +1017,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { planner.synchronize(); #if ENABLED(DUAL_X_CARRIAGE) // Only T0 allowed if the Printer is in DXC_DUPLICATION_MODE or DXC_MIRRORED_MODE - if (new_tool != 0 && dxc_is_duplicating()) + if (new_tool != 0 && idex_is_duplicating()) return invalid_extruder_error(new_tool); #endif @@ -887,7 +1029,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { DEBUG_ECHOLNPGM("No move (not homed)"); } - TERN_(HAS_LCD_MENU, if (!no_move) ui.return_to_status()); + TERN_(HAS_LCD_MENU, if (!no_move) ui.update()); #if ENABLED(DUAL_X_CARRIAGE) const bool idex_full_control = dual_x_carriage_mode == DXC_FULL_CONTROL_MODE; @@ -904,16 +1046,16 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { #endif // First tool priming. To prime again, reboot the machine. - #if BOTH(TOOLCHANGE_FILAMENT_SWAP, TOOLCHANGE_FS_PRIME_FIRST_USED) + #if ENABLED(TOOLCHANGE_FS_PRIME_FIRST_USED) static bool first_tool_is_primed = false; if (new_tool == old_tool && !first_tool_is_primed && enable_first_prime) { tool_change_prime(); first_tool_is_primed = true; - toolchange_extruder_ready[old_tool] = true; // Primed and initialized + TERN_(TOOLCHANGE_FS_INIT_BEFORE_SWAP, toolchange_extruder_ready[old_tool] = true); // Primed and initialized } #endif - if (new_tool != old_tool) { + 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 @@ -946,12 +1088,10 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { if (ENABLED(SINGLENOZZLE)) { active_extruder = new_tool; return; } } else { - #if ENABLED(TOOLCHANGE_FS_PRIME_FIRST_USED) - // For first new tool, change without unloading the old. 'Just prime/init the new' - if (first_tool_is_primed) - unscaled_e_move(-toolchange_settings.swap_length, MMM_TO_MMS(toolchange_settings.retract_speed)); - first_tool_is_primed = true; // The first new tool will be primed by toolchanging - #endif + // For first new tool, change without unloading the old. 'Just prime/init the new' + if (TERN1(TOOLCHANGE_FS_PRIME_FIRST_USED, first_tool_is_primed)) + unscaled_e_move(-toolchange_settings.swap_length, MMM_TO_MMS(toolchange_settings.retract_speed)); + TERN_(TOOLCHANGE_FS_PRIME_FIRST_USED, first_tool_is_primed = true); // The first new tool will be primed by toolchanging } } #endif @@ -987,8 +1127,8 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { // Toolchange park #if ENABLED(TOOLCHANGE_PARK) && DISABLED(SWITCHING_NOZZLE) if (can_move_away && toolchange_settings.enable_park) { - TERN(TOOLCHANGE_PARK_Y_ONLY,,current_position.x = toolchange_settings.change_point.x); - TERN(TOOLCHANGE_PARK_X_ONLY,,current_position.y = toolchange_settings.change_point.y); + IF_DISABLED(TOOLCHANGE_PARK_Y_ONLY, current_position.x = toolchange_settings.change_point.x); + IF_DISABLED(TOOLCHANGE_PARK_X_ONLY, current_position.y = toolchange_settings.change_point.y); planner.buffer_line(current_position, MMM_TO_MMS(TOOLCHANGE_PARK_XY_FEEDRATE), old_tool); planner.synchronize(); } @@ -1029,8 +1169,11 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { move_nozzle_servo(new_tool); #endif - // Set the new active extruder - if (DISABLED(DUAL_X_CARRIAGE)) active_extruder = new_tool; + IF_DISABLED(DUAL_X_CARRIAGE, active_extruder = new_tool); // Set the new active extruder + + TERN_(TOOL_SENSOR, tool_sensor_disabled = false); + + (void)check_tool_sensor_stats(active_extruder, true); // The newly-selected extruder XYZ is actually at... DEBUG_ECHOLNPAIR("Offset Tool XYZ by { ", diff.x, ", ", diff.y, ", ", diff.z, " }"); @@ -1040,7 +1183,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { sync_plan_position(); #if ENABLED(DELTA) - //LOOP_XYZ(i) update_software_endstops(i); // or modify the constrain function + //LOOP_LINEAR_AXES(i) update_software_endstops(i); // or modify the constrain function const bool safe_to_move = current_position.z < delta_clip_start_height - 1; #else constexpr bool safe_to_move = true; @@ -1050,19 +1193,8 @@ 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 BOTH(HAS_FAN, SINGLENOZZLE_STANDBY_FAN) - singlenozzle_fan_speed[old_tool] = thermalManager.fan_speed[0]; - thermalManager.fan_speed[0] = singlenozzle_fan_speed[new_tool]; - #endif - - #if ENABLED(SINGLENOZZLE_STANDBY_TEMP) - singlenozzle_temp[old_tool] = thermalManager.temp_hotend[0].target; - if (singlenozzle_temp[new_tool] && singlenozzle_temp[new_tool] != singlenozzle_temp[old_tool]) { - thermalManager.setTargetHotend(singlenozzle_temp[new_tool], 0); - TERN_(AUTOTEMP, planner.autotemp_update()); - TERN_(HAS_DISPLAY, thermalManager.set_heating_message(0)); - (void)thermalManager.wait_for_hotend(0, false); // Wait for heating or cooling - } + #if EITHER(SINGLENOZZLE_STANDBY_TEMP, SINGLENOZZLE_STANDBY_FAN) + thermalManager.singlenozzle_change(old_tool, new_tool); #endif #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) @@ -1092,7 +1224,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { // Cool down with fan #if HAS_FAN && TOOLCHANGE_FS_FAN >= 0 thermalManager.fan_speed[TOOLCHANGE_FS_FAN] = toolchange_settings.fan_speed; - gcode.dwell(toolchange_settings.fan_time * 1000); + gcode.dwell(SEC_TO_MS(toolchange_settings.fan_time)); thermalManager.fan_speed[TOOLCHANGE_FS_FAN] = 0; #endif } @@ -1102,7 +1234,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { #if ENABLED(MAGNETIC_SWITCHING_TOOLHEAD) // If the original position is within tool store area, go to X origin at once if (destination.y < SWITCHING_TOOLHEAD_Y_POS + SWITCHING_TOOLHEAD_Y_CLEAR) { - current_position.x = 0; + current_position.x = X_MIN_POS; planner.buffer_line(current_position, planner.settings.max_feedrate_mm_s[X_AXIS], new_tool); planner.synchronize(); } @@ -1116,10 +1248,8 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { // Just move back down DEBUG_ECHOLNPGM("Move back Z only"); - #if ENABLED(TOOLCHANGE_PARK) - if (toolchange_settings.enable_park) - #endif - do_blocking_move_to_z(destination.z, planner.settings.max_feedrate_mm_s[Z_AXIS]); + if (TERN1(TOOLCHANGE_PARK, toolchange_settings.enable_park)) + do_blocking_move_to_z(destination.z, planner.settings.max_feedrate_mm_s[Z_AXIS]); #else // Move back to the original (or adjusted) position @@ -1151,7 +1281,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { } #endif - TERN_(DUAL_X_CARRIAGE, active_extruder_parked = false); + TERN_(DUAL_X_CARRIAGE, idex_set_parked(false)); } #if ENABLED(SWITCHING_NOZZLE) @@ -1160,8 +1290,6 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { do_blocking_move_to_z(destination.z, planner.settings.max_feedrate_mm_s[Z_AXIS]); #endif - TERN_(PRUSA_MMU2, mmu2.tool_change(new_tool)); - TERN_(SWITCHING_NOZZLE_TWO_SERVOS, lower_nozzle(new_tool)); } // (new_tool != old_tool) @@ -1173,7 +1301,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { enable_solenoid_on_active_extruder(); #endif - #if ENABLED(MK2_MULTIPLEXER) + #if HAS_PRUSA_MMU1 if (new_tool >= E_STEPPERS) return invalid_extruder_error(new_tool); select_multiplexed_stepper(new_tool); #endif @@ -1185,38 +1313,46 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { TERN_(HAS_FANMUX, fanmux_switch(active_extruder)); - #ifdef EVENT_GCODE_AFTER_TOOLCHANGE - if (!no_move && TERN1(DUAL_X_CARRIAGE, dual_x_carriage_mode == DXC_AUTO_PARK_MODE)) - gcode.process_subcommands_now_P(PSTR(EVENT_GCODE_AFTER_TOOLCHANGE)); - #endif + if (!no_move) { + #ifdef EVENT_GCODE_TOOLCHANGE_T0 + if (new_tool == 0) + gcode.process_subcommands_now_P(PSTR(EVENT_GCODE_TOOLCHANGE_T0)); + #endif - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR(STR_ACTIVE_EXTRUDER, int(active_extruder)); + #ifdef EVENT_GCODE_TOOLCHANGE_T1 + if (new_tool == 1) + gcode.process_subcommands_now_P(PSTR(EVENT_GCODE_TOOLCHANGE_T1)); + #endif + + #ifdef EVENT_GCODE_AFTER_TOOLCHANGE + if (TERN1(DUAL_X_CARRIAGE, dual_x_carriage_mode == DXC_AUTO_PARK_MODE)) + gcode.process_subcommands_now_P(PSTR(EVENT_GCODE_AFTER_TOOLCHANGE)); + #endif + } + + SERIAL_ECHO_MSG(STR_ACTIVE_EXTRUDER, active_extruder); #endif // HAS_MULTI_EXTRUDER } #if ENABLED(TOOLCHANGE_MIGRATION_FEATURE) + #define DEBUG_OUT ENABLED(DEBUG_TOOLCHANGE_MIGRATION_FEATURE) + #include "../core/debug_out.h" + bool extruder_migration() { #if ENABLED(PREVENT_COLD_EXTRUSION) if (thermalManager.targetTooColdToExtrude(active_extruder)) { - #if ENABLED(DEBUG_TOOLCHANGE_MIGRATION_FEATURE) - SERIAL_ECHOLN("Migration Source Too Cold"); - #endif + DEBUG_ECHOLNPGM("Migration Source Too Cold"); return false; } #endif // No auto-migration or specified target? if (!migration.target && active_extruder >= migration.last) { - #if ENABLED(DEBUG_TOOLCHANGE_MIGRATION_FEATURE) - SERIAL_ECHO_MSG("No Migration Target"); - SERIAL_ECHO_MSG("Target: ", migration.target, - " Last: ", migration.last, - " Active: ", active_extruder); - #endif + DEBUG_ECHO_MSG("No Migration Target"); + DEBUG_ECHO_MSG("Target: ", migration.target, " Last: ", migration.last, " Active: ", active_extruder); migration.automode = false; return false; } @@ -1226,9 +1362,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { uint8_t migration_extruder = active_extruder; if (migration.target) { - #if ENABLED(DEBUG_TOOLCHANGE_MIGRATION_FEATURE) - SERIAL_ECHOLN("Migration using fixed target"); - #endif + DEBUG_ECHOLNPGM("Migration using fixed target"); // Specified target ok? const int16_t t = migration.target - 1; if (t != active_extruder) migration_extruder = t; @@ -1237,16 +1371,12 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { migration_extruder++; if (migration_extruder == active_extruder) { - #if ENABLED(DEBUG_TOOLCHANGE_MIGRATION_FEATURE) - SERIAL_ECHOLN("Migration source matches active"); - #endif + DEBUG_ECHOLNPGM("Migration source matches active"); return false; } // Migration begins - #if ENABLED(DEBUG_TOOLCHANGE_MIGRATION_FEATURE) - SERIAL_ECHOLN("Beginning migration"); - #endif + DEBUG_ECHOLNPGM("Beginning migration"); migration.in_progress = true; // Prevent runout script planner.synchronize(); @@ -1264,9 +1394,9 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { // Migrate the temperature to the new hotend #if HAS_MULTI_HOTEND - thermalManager.setTargetHotend(thermalManager.temp_hotend[active_extruder].target, migration_extruder); + thermalManager.setTargetHotend(thermalManager.degTargetHotend(active_extruder), migration_extruder); TERN_(AUTOTEMP, planner.autotemp_update()); - TERN_(HAS_DISPLAY, thermalManager.set_heating_message(0)); + thermalManager.set_heating_message(0); thermalManager.wait_for_hotend(active_extruder); #endif @@ -1292,9 +1422,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 - #if ENABLED(DEBUG_TOOLCHANGE_MIGRATION_FEATURE) - SERIAL_ECHOLN("Migration Complete"); - #endif + DEBUG_ECHOLNPGM("Migration Complete"); return true; } diff --git a/Marlin/src/module/tool_change.h b/Marlin/src/module/tool_change.h index 38347191d390..bbdc0b686278 100644 --- a/Marlin/src/module/tool_change.h +++ b/Marlin/src/module/tool_change.h @@ -21,8 +21,9 @@ */ #pragma once -#include "../inc/MarlinConfigPre.h" -#include "../core/types.h" +#include "../inc/MarlinConfig.h" + +//#define DEBUG_TOOLCHANGE_MIGRATION_FEATURE #if HAS_MULTI_EXTRUDER @@ -41,7 +42,7 @@ extern toolchange_settings_t toolchange_settings; #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) - extern void tool_change_prime(); + void tool_change_prime(); #endif #if ENABLED(TOOLCHANGE_FS_PRIME_FIRST_USED) @@ -78,19 +79,18 @@ #if ENABLED(PARKING_EXTRUDER) - #if ENABLED(PARKING_EXTRUDER_SOLENOIDS_INVERT) - #define PE_MAGNET_ON_STATE !PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE - #else - #define PE_MAGNET_ON_STATE PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE - #endif - - void pe_set_solenoid(const uint8_t extruder_num, const uint8_t state); + void pe_solenoid_set_pin_state(const uint8_t extruder_num, const uint8_t state); - inline void pe_activate_solenoid(const uint8_t extruder_num) { pe_set_solenoid(extruder_num, PE_MAGNET_ON_STATE); } - inline void pe_deactivate_solenoid(const uint8_t extruder_num) { pe_set_solenoid(extruder_num, !PE_MAGNET_ON_STATE); } + #define PE_MAGNET_ON_STATE TERN_(PARKING_EXTRUDER_SOLENOIDS_INVERT, !)PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE + inline void pe_solenoid_magnet_on(const uint8_t extruder_num) { pe_solenoid_set_pin_state(extruder_num, PE_MAGNET_ON_STATE); } + inline void pe_solenoid_magnet_off(const uint8_t extruder_num) { pe_solenoid_set_pin_state(extruder_num, !PE_MAGNET_ON_STATE); } void pe_solenoid_init(); + extern bool extruder_parked; + inline void parking_extruder_set_parked(const bool parked) { extruder_parked = parked; } + bool parking_extruder_unpark_after_homing(const uint8_t final_tool, bool homed_towards_final_tool); + #elif ENABLED(MAGNETIC_PARKING_EXTRUDER) typedef struct MPESettings { @@ -108,18 +108,18 @@ #endif -#if ENABLED(SINGLENOZZLE_STANDBY_TEMP) - extern uint16_t singlenozzle_temp[EXTRUDERS]; +#if ENABLED(ELECTROMAGNETIC_SWITCHING_TOOLHEAD) + void est_init(); +#elif ENABLED(SWITCHING_TOOLHEAD) + void swt_init(); #endif -#if BOTH(HAS_FAN, SINGLENOZZLE_STANDBY_FAN) - extern uint8_t singlenozzle_fan_speed[EXTRUDERS]; +#if ENABLED(TOOL_SENSOR) + uint8_t check_tool_sensor_stats(const uint8_t active_tool, const bool kill_on_error=false, const bool disable=false); +#else + inline uint8_t check_tool_sensor_stats(const uint8_t, const bool=false, const bool=false) { return 0; } #endif -TERN_(ELECTROMAGNETIC_SWITCHING_TOOLHEAD, void est_init()); - -TERN_(SWITCHING_TOOLHEAD, void swt_init()); - /** * Perform a tool-change, which may result in moving the * previous tool out of the way and the new tool into place. diff --git a/Marlin/src/pins/esp32/env_validate.h b/Marlin/src/pins/esp32/env_validate.h new file mode 100644 index 000000000000..ce14c33414ad --- /dev/null +++ b/Marlin/src/pins/esp32/env_validate.h @@ -0,0 +1,26 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#if NOT_TARGET(ARDUINO_ARCH_ESP32) + #error "Oops! Select an ESP32 board in 'Tools > Board.'" +#endif diff --git a/Marlin/src/pins/esp32/pins_E4D.h b/Marlin/src/pins/esp32/pins_E4D.h index 7b5595444cf1..9e28af2190ab 100644 --- a/Marlin/src/pins/esp32/pins_E4D.h +++ b/Marlin/src/pins/esp32/pins_E4D.h @@ -27,45 +27,60 @@ * for more info check https://atbox.tech/ and join to Facebook page E4d@box. */ -#if NOT_TARGET(ARDUINO_ARCH_ESP32) - #error "Oops! Select an ESP32 board in 'Tools > Board.'" -#elif EXTRUDERS > 1 || E_STEPPERS > 1 +#include "env_validate.h" + +#if EXTRUDERS > 1 || E_STEPPERS > 1 #error "E4d@box only supports one E Stepper. Comment out this line to continue." -#elif HOTENDS > 2 - #error "E4d@box currently supports only one hotend. Comment out this line to continue." +#elif HOTENDS > 1 + #error "E4d@box only supports one hotend / E-stepper. Comment out this line to continue." #endif #define BOARD_INFO_NAME "E4D@BOX" #define BOARD_WEBSITE_URL "github.com/Exilaus/E4d@box" #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME +// +// Disable I2S stepper stream +// +#undef I2S_STEPPER_STREAM + +// +// Redefine I2S for ESP32 +// +#undef I2S_WS +#define I2S_WS 23 +#undef I2S_BCK +#define I2S_BCK 22 +#undef I2S_DATA +#define I2S_DATA 21 + // // Limit Switches // -#define X_MIN_PIN 34 -#define Y_MIN_PIN 35 -#define Z_MIN_PIN 16 // 15 +#define X_STOP_PIN 34 +#define Y_STOP_PIN 35 +#define Z_STOP_PIN 16 // // Steppers // -#define X_STEP_PIN 12 // 34//27 -#define X_DIR_PIN 13 // 35//26 -#define X_ENABLE_PIN 17 // 0//17//25 // used free pin +#define X_STEP_PIN 12 +#define X_DIR_PIN 13 +#define X_ENABLE_PIN 17 //#define X_CS_PIN 0 -#define Y_STEP_PIN 32 // 33 -#define Y_DIR_PIN 33 // 32 +#define Y_STEP_PIN 32 +#define Y_DIR_PIN 33 #define Y_ENABLE_PIN X_ENABLE_PIN //#define Y_CS_PIN 13 -#define Z_STEP_PIN 25 // 14 -#define Z_DIR_PIN 26 // 12 +#define Z_STEP_PIN 25 +#define Z_DIR_PIN 26 #define Z_ENABLE_PIN X_ENABLE_PIN //#define Z_CS_PIN 5 // SS_PIN -#define E0_STEP_PIN 27 // 16 -#define E0_DIR_PIN 14 // 17 +#define E0_STEP_PIN 27 +#define E0_DIR_PIN 14 #define E0_ENABLE_PIN X_ENABLE_PIN //#define E0_CS_PIN 21 @@ -78,13 +93,15 @@ // // Heaters / Fans // -#define HEATER_0_PIN 2 // 4//2//(D8) -#define FAN_PIN 0 // 2//15//13 (D9) -#define HEATER_BED_PIN 15 // 15//0 //(D10) +#define HEATER_0_PIN 2 +#define FAN_PIN 0 +#define HEATER_BED_PIN 15 -// SPI +// +// MicroSD card on SPI +// +#define SD_MOSI_PIN 23 +#define SD_MISO_PIN 19 +#define SD_SCK_PIN 18 #define SDSS 5 -#define I2S_STEPPER_STREAM -#define I2S_WS 23 -#define I2S_BCK 22 -#define I2S_DATA 21 +#define USES_SHARED_SPI // SPI is shared by SD card with TMC SPI drivers diff --git a/Marlin/src/pins/esp32/pins_ESP32.h b/Marlin/src/pins/esp32/pins_ESP32.h index d54a92b9c4e5..6578770ba0e2 100644 --- a/Marlin/src/pins/esp32/pins_ESP32.h +++ b/Marlin/src/pins/esp32/pins_ESP32.h @@ -25,9 +25,7 @@ * Espressif ESP32 (Tensilica Xtensa LX6) pin assignments */ -#if NOT_TARGET(ARDUINO_ARCH_ESP32) - "Oops! Select an ESP32 board in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "Espressif ESP32" diff --git a/Marlin/src/pins/esp32/pins_FYSETC_E4.h b/Marlin/src/pins/esp32/pins_FYSETC_E4.h new file mode 100644 index 000000000000..7dd7f94ae567 --- /dev/null +++ b/Marlin/src/pins/esp32/pins_FYSETC_E4.h @@ -0,0 +1,126 @@ +/** + * 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 + +/** + * FYSETC E4 pin assignments + * FYSETC E4 is a 3D printer control board based on the ESP32 microcontroller. + * Supports 4 stepper drivers, heated bed, single hotend. + */ + +#include "env_validate.h" + +#if EXTRUDERS > 1 || E_STEPPERS > 1 + #error "FYSETC E4 only supports one E Stepper. Comment out this line to continue." +#elif HOTENDS > 1 + #error "FYSETC E4 only supports one hotend / E-stepper. Comment out this line to continue." +#endif + +#define BOARD_INFO_NAME "FYSETC_E4" +#define DEFAULT_MACHINE_NAME BOARD_INFO_NAME + +// +// Disable I2S stepper stream +// +#undef I2S_STEPPER_STREAM +#define I2S_WS -1 +#define I2S_BCK -1 +#define I2S_DATA -1 + +// +// Limit Switches +// +#define X_STOP_PIN 34 +#define Y_STOP_PIN 35 +#define Z_STOP_PIN 15 + +// +// Steppers +// +#define X_STEP_PIN 27 +#define X_DIR_PIN 26 +#define X_ENABLE_PIN 25 + +#define Y_STEP_PIN 33 +#define Y_DIR_PIN 32 +#define Y_ENABLE_PIN X_ENABLE_PIN + +#define Z_STEP_PIN 14 +#define Z_DIR_PIN 12 +#define Z_ENABLE_PIN X_ENABLE_PIN + +#define E0_STEP_PIN 16 +#define E0_DIR_PIN 17 +#define E0_ENABLE_PIN X_ENABLE_PIN + +#if HAS_TMC_UART + // + // TMC2209 stepper drivers + // + + // + // Hardware serial 1 + // + #define X_HARDWARE_SERIAL Serial1 + #define Y_HARDWARE_SERIAL Serial1 + #define Z_HARDWARE_SERIAL Serial1 + #define E0_HARDWARE_SERIAL Serial1 + + #define TMC_BAUD_RATE 115200 +#endif + +// +// Temperature Sensors +// +#define TEMP_0_PIN 36 // Analog Input +#define TEMP_BED_PIN 39 // Analog Input + +// +// Heaters / Fans +// +#define HEATER_0_PIN 2 +#define FAN_PIN 13 +#define HEATER_BED_PIN 4 + +// +// MicroSD card +// +#define SD_MOSI_PIN 23 +#define SD_MISO_PIN 19 +#define SD_SCK_PIN 18 +#define SDSS 5 +#define USES_SHARED_SPI // SPI is shared by SD card with TMC SPI drivers + +/** + * Hardware serial pins + * + * Override these pins in Configuration.h or Configuration_adv.h if needed. + * + * Note: Serial2 can be defined using HARDWARE_SERIAL2_RX and HARDWARE_SERIAL2_TX + * but MRR ESPA does not have enough spare pins for such reassignment. + */ +#ifndef HARDWARE_SERIAL1_RX + #define HARDWARE_SERIAL1_RX 21 +#endif +#ifndef HARDWARE_SERIAL1_TX + #define HARDWARE_SERIAL1_TX 22 +#endif diff --git a/Marlin/src/pins/esp32/pins_MRR_ESPA.h b/Marlin/src/pins/esp32/pins_MRR_ESPA.h index 0457b0afca53..38f43b53d329 100644 --- a/Marlin/src/pins/esp32/pins_MRR_ESPA.h +++ b/Marlin/src/pins/esp32/pins_MRR_ESPA.h @@ -27,12 +27,12 @@ * Supports 4 stepper drivers, heated bed, single hotend. */ -#if NOT_TARGET(ARDUINO_ARCH_ESP32) - #error "Oops! Select an ESP32 board in 'Tools > Board.'" -#elif EXTRUDERS > 1 || E_STEPPERS > 1 +#include "env_validate.h" + +#if EXTRUDERS > 1 || E_STEPPERS > 1 #error "MRR ESPA only supports one E Stepper. Comment out this line to continue." #elif HOTENDS > 1 - #error "MRR ESPA currently supports only one hotend. Comment out this line to continue." + #error "MRR ESPA only supports one hotend / E-stepper. Comment out this line to continue." #endif #define BOARD_INFO_NAME "MRR ESPA" @@ -42,12 +42,10 @@ // // Disable I2S stepper stream // -#ifdef I2S_STEPPER_STREAM - #undef I2S_STEPPER_STREAM -#endif -#define I2S_WS -1 -#define I2S_BCK -1 -#define I2S_DATA -1 +#undef I2S_STEPPER_STREAM +#undef I2S_WS +#undef I2S_BCK +#undef I2S_DATA // // Limit Switches @@ -95,9 +93,9 @@ // // MicroSD card // -#define MOSI_PIN 23 -#define MISO_PIN 19 -#define SCK_PIN 18 +#define SD_MOSI_PIN 23 +#define SD_MISO_PIN 19 +#define SD_SCK_PIN 18 #define SDSS 5 #define USES_SHARED_SPI // SPI is shared by SD card with TMC SPI drivers diff --git a/Marlin/src/pins/esp32/pins_MRR_ESPE.h b/Marlin/src/pins/esp32/pins_MRR_ESPE.h index 95f761f26ad9..f156efd2e8a9 100644 --- a/Marlin/src/pins/esp32/pins_MRR_ESPE.h +++ b/Marlin/src/pins/esp32/pins_MRR_ESPE.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. - * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm + * 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 @@ -28,12 +28,12 @@ * single hotend, and LCD controller. */ -#if NOT_TARGET(ARDUINO_ARCH_ESP32) - #error "Oops! Select an ESP32 board in 'Tools > Board.'" -#elif EXTRUDERS > 2 || E_STEPPERS > 2 +#include "env_validate.h" + +#if EXTRUDERS > 2 || E_STEPPERS > 2 #error "MRR ESPE only supports two E Steppers. Comment out this line to continue." #elif HOTENDS > 1 - #error "MRR ESPE currently supports only one hotend. Comment out this line to continue." + #error "MRR ESPE only supports one hotend / E-stepper. Comment out this line to continue." #endif #define BOARD_INFO_NAME "MRR ESPE" @@ -52,12 +52,10 @@ // #undef I2S_STEPPER_STREAM #define I2S_STEPPER_STREAM - -#undef LIN_ADVANCE // Currently, I2S stream does not work with linear advance - #define I2S_WS 26 #define I2S_BCK 25 #define I2S_DATA 27 +#undef LIN_ADVANCE // Currently, I2S stream does not work with linear advance // // Steppers @@ -114,9 +112,9 @@ // // MicroSD card // -#define MOSI_PIN 23 -#define MISO_PIN 19 -#define SCK_PIN 18 +#define SD_MOSI_PIN 23 +#define SD_MISO_PIN 19 +#define SD_SCK_PIN 18 #define SDSS 5 #define USES_SHARED_SPI // SPI is shared by SD card with TMC SPI drivers @@ -134,7 +132,7 @@ #define BEEPER_PIN 151 - #elif ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #elif IS_RRD_FG_SC #define BEEPER_PIN 151 diff --git a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h index 002d2ebd9c62..a0f8c1648c1e 100644 --- a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h +++ b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h @@ -49,6 +49,10 @@ #define BOARD_INFO_NAME "RAMPS 1.4" #endif +#ifndef DEFAULT_MACHINE_NAME + #define DEFAULT_MACHINE_NAME "SimRap 1.4" +#endif + #ifndef MARLIN_EEPROM_SIZE #define MARLIN_EEPROM_SIZE 0x1000 // 4KB #endif @@ -133,11 +137,11 @@ #define TEMP_1_PIN 1 // Analog Input #define TEMP_BED_PIN 2 // Analog Input -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 66 // Don't use 53 if using Display/SD card + #define TEMP_0_CS_PIN 66 // Don't use 53 if using Display/SD card #else - #define MAX6675_SS_PIN 66 // Don't use 49 (SD_DETECT_PIN) + #define TEMP_0_CS_PIN 66 // Don't use 49 (SD_DETECT_PIN) #endif // @@ -192,7 +196,7 @@ #else // Non-specific are "EFB" (i.e., "EFBF" or "EFBE") #define FAN_PIN RAMPS_D9_PIN #define HEATER_BED_PIN RAMPS_D8_PIN - #if HOTENDS == 1 + #if HOTENDS == 1 && DISABLED(HEATERS_PARALLEL) #define FAN1_PIN MOSFET_D_PIN #else #define HEATER_1_PIN MOSFET_D_PIN @@ -208,6 +212,7 @@ // #define SDSS 53 #define LED_PIN 13 +#define NEOPIXEL_PIN 71 #ifndef FILWIDTH_PIN #define FILWIDTH_PIN 5 // Analog Input on AUX2 @@ -215,7 +220,7 @@ // define digital pin 4 for the filament runout sensor. Use the RAMPS 1.4 digital input 4 on the servos connector #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 4 + #define FIL_RUNOUT_PIN 21 #endif #ifndef PS_ON_PIN @@ -389,7 +394,54 @@ // LCDs and Controllers // ////////////////////////// -#if HAS_WIRED_LCD +#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_SCK_PIN SD_SCK_PIN + #define TFT_MOSI_PIN SD_MOSI_PIN + #define TFT_MISO_PIN SD_MISO_PIN + #define LCD_USE_DMA_SPI + + #define BTN_EN1 40 + #define BTN_EN2 63 + #define BTN_ENC 59 + #define BEEPER_PIN 42 + + #define TOUCH_CS_PIN 33 + #define SD_DETECT_PIN 41 + + #define HAS_SPI_FLASH 1 + #if HAS_SPI_FLASH + #define SPI_DEVICE 1 + #define SPI_FLASH_SIZE 0x1000000 // 16MB + #define W25QXX_CS_PIN 31 + #define W25QXX_MOSI_PIN SD_MOSI_PIN + #define W25QXX_MISO_PIN SD_MISO_PIN + #define W25QXX_SCK_PIN SD_SCK_PIN + #endif + + #define TFT_BUFFER_SIZE 0xFFFF + #ifndef TFT_DRIVER + #define TFT_DRIVER ST7796 + #endif + #ifndef XPT2046_X_CALIBRATION + #define XPT2046_X_CALIBRATION 63934 + #endif + #ifndef XPT2046_Y_CALIBRATION + #define XPT2046_Y_CALIBRATION 63598 + #endif + #ifndef XPT2046_X_OFFSET + #define XPT2046_X_OFFSET -1 + #endif + #ifndef XPT2046_Y_OFFSET + #define XPT2046_Y_OFFSET -20 + #endif + + #define BTN_BACK 70 + +#elif HAS_WIRED_LCD // // LCD Display output pins @@ -400,7 +452,7 @@ #define LCD_PINS_ENABLE 51 // SID (MOSI) #define LCD_PINS_D4 52 // SCK (CLK) clock - #elif BOTH(NEWPANEL, PANEL_ONE) + #elif BOTH(IS_NEWPANEL, PANEL_ONE) #define LCD_PINS_RS 40 #define LCD_PINS_ENABLE 42 @@ -417,7 +469,7 @@ #define LCD_PINS_ENABLE 29 #define LCD_PINS_D4 25 - #if DISABLED(NEWPANEL) + #if !IS_NEWPANEL #define BEEPER_PIN 37 #endif @@ -450,19 +502,19 @@ #define LCD_PINS_D7 29 - #if DISABLED(NEWPANEL) + #if !IS_NEWPANEL #define BEEPER_PIN 33 #endif #endif - #if DISABLED(NEWPANEL) + #if !IS_NEWPANEL // Buttons attached to a shift register // Not wired yet - //#define SHIFT_CLK 38 - //#define SHIFT_LD 42 - //#define SHIFT_OUT 40 - //#define SHIFT_EN 17 + //#define SHIFT_CLK_PIN 38 + //#define SHIFT_LD_PIN 42 + //#define SHIFT_OUT_PIN 40 + //#define SHIFT_EN_PIN 17 #endif #endif @@ -470,7 +522,7 @@ // // LCD Display input pins // - #if ENABLED(NEWPANEL) + #if IS_NEWPANEL #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) @@ -607,10 +659,10 @@ #define BEEPER_PIN 33 // Buttons are directly attached to AUX-2 - #if ENABLED(REPRAPWORLD_KEYPAD) - #define SHIFT_OUT 40 - #define SHIFT_CLK 44 - #define SHIFT_LD 42 + #if IS_RRW_KEYPAD + #define SHIFT_OUT_PIN 40 + #define SHIFT_CLK_PIN 44 + #define SHIFT_LD_PIN 42 #define BTN_EN1 64 #define BTN_EN2 59 #define BTN_ENC 63 @@ -622,14 +674,18 @@ #define BTN_EN1 37 #define BTN_EN2 35 #define BTN_ENC 31 + #define SD_DETECT_PIN 41 #endif #if ENABLED(G3D_PANEL) #define SD_DETECT_PIN 49 #define KILL_PIN 41 #endif - #endif - #endif // NEWPANEL + + // CUSTOM SIMULATOR INPUTS + #define BTN_BACK 70 + + #endif // IS_NEWPANEL #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/lpc1768/env_validate.h b/Marlin/src/pins/lpc1768/env_validate.h new file mode 100644 index 000000000000..adb3ea938dc2 --- /dev/null +++ b/Marlin/src/pins/lpc1768/env_validate.h @@ -0,0 +1,30 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#if ENABLED(REQUIRE_LPC1769) && NOT_TARGET(MCU_LPC1769) + #error "Oops! Make sure you have the LPC1769 environment selected in your IDE." +#elif DISABLED(REQUIRE_LPC1769) && NOT_TARGET(MCU_LPC1768) + #error "Oops! Make sure you have the LPC1768 environment selected in your IDE." +#endif + +#undef REQUIRE_LPC1769 diff --git a/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h b/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h index 78e742667497..5131069f6bea 100644 --- a/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h +++ b/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h @@ -25,9 +25,7 @@ * AZSMZ MINI pin assignments */ -#if NOT_TARGET(MCU_LPC1768) - #error "Oops! Make sure you have the LPC1768 environment selected in your IDE." -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "AZSMZ MINI" @@ -39,8 +37,8 @@ // // Limit Switches // -#define X_MIN_PIN P1_24 -#define Y_MIN_PIN P1_26 +#define X_STOP_PIN P1_24 +#define Y_STOP_PIN P1_26 #define Z_MIN_PIN P1_28 #define Z_MAX_PIN P1_29 @@ -102,16 +100,16 @@ #endif #if SD_CONNECTION_IS(LCD) - #define SCK_PIN P0_15 - #define MISO_PIN P0_17 - #define MOSI_PIN P0_18 - #define SS_PIN LCD_SDSS + #define SD_SCK_PIN P0_15 + #define SD_MISO_PIN P0_17 + #define SD_MOSI_PIN P0_18 + #define SD_SS_PIN LCD_SDSS #define SD_DETECT_PIN P3_25 #elif SD_CONNECTION_IS(ONBOARD) - #define SCK_PIN P0_07 - #define MISO_PIN P0_08 - #define MOSI_PIN P0_09 - #define SS_PIN ONBOARD_SD_CS_PIN + #define SD_SCK_PIN P0_07 + #define SD_MISO_PIN P0_08 + #define SD_MOSI_PIN P0_09 + #define SD_SS_PIN ONBOARD_SD_CS_PIN #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "No custom SD drive cable defined for this board." #endif 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 df182049f994..10a610ff95f7 100644 --- a/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h +++ b/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h @@ -29,9 +29,7 @@ * BOARD_BIQU_BQ111_A4 (Hotend, Fan, Bed) */ -#if NOT_TARGET(MCU_LPC1768) - #error "Oops! Make sure you have the LPC1768 environment selected in your IDE." -#endif +#include "env_validate.h" #ifndef BOARD_INFO_NAME #define BOARD_INFO_NAME "BIQU Thunder B300 V1.0" @@ -138,8 +136,8 @@ #define LCD_PINS_ENABLE P0_18 // (MOSI) EXP1-3 #define LCD_PINS_D4 P0_15 // (SCK) EXP1-5 - #if BOTH(HAS_MARLINUI_HD44780, REPRAP_DISCOUNT_SMART_CONTROLLER) - #error "REPRAP_DISCOUNT_SMART_CONTROLLER is not supported by the BIQU B300 v1.0" + #if BOTH(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) @@ -155,11 +153,11 @@ * Hardware SPI can't be used because P0_17 (MISO) is not brought out on this board. */ #if ENABLED(SDSUPPORT) - #define SCK_PIN P0_15 // EXP1-5 - #define MISO_PIN P0_16 // EXP1-4 - #define MOSI_PIN P0_18 // EXP1-3 - #define SS_PIN P1_30 // EXP1-2 - #define SDSS SS_PIN + #define SD_SCK_PIN P0_15 // EXP1-5 + #define SD_MISO_PIN P0_16 // EXP1-4 + #define SD_MOSI_PIN P0_18 // EXP1-3 + #define SD_SS_PIN P1_30 // EXP1-2 + #define SDSS SD_SS_PIN #endif /** diff --git a/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h b/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h index bcff04eb85e8..f94381e13a47 100644 --- a/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h +++ b/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h @@ -29,9 +29,7 @@ * BOARD_BIQU_BQ111_A4 (Hotend, Fan, Bed) */ -#if NOT_TARGET(MCU_LPC1768) - #error "Oops! Make sure you have the LPC1768 environment selected in your IDE." -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "BIQU BQ111-A4" @@ -109,8 +107,8 @@ #define LCD_PINS_ENABLE P0_18 // (MOSI) EXP1-3 #define LCD_PINS_D4 P0_15 // (SCK) EXP1-5 - #if BOTH(HAS_MARLINUI_HD44780, REPRAP_DISCOUNT_SMART_CONTROLLER) - #error "REPRAP_DISCOUNT_SMART_CONTROLLER is not supported by the BIQU BQ111-A4" + #if BOTH(HAS_MARLINUI_HD44780, IS_RRD_SC) + #error "REPRAP_DISCOUNT_SMART_CONTROLLER displays aren't supported by the BIQU BQ111-A4" #endif #if ENABLED(SDSUPPORT) @@ -127,11 +125,11 @@ */ #if ENABLED(SDSUPPORT) - #define SCK_PIN P0_15 // EXP1-5 - #define MISO_PIN P0_16 // EXP1-4 - #define MOSI_PIN P0_18 // EXP1-3 - #define SS_PIN P1_30 // EXP1-2 - #define SDSS SS_PIN + #define SD_SCK_PIN P0_15 // EXP1-5 + #define SD_MISO_PIN P0_16 // EXP1-4 + #define SD_MOSI_PIN P0_18 // EXP1-3 + #define SD_SS_PIN P1_30 // EXP1-2 + #define SDSS SD_SS_PIN #endif // SDSUPPORT 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 0701e45992eb..c6a44123a02b 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h @@ -52,6 +52,37 @@ #define E0_DIR_PIN P2_13 #define E0_ENABLE_PIN P2_12 + +/** + * ______ ______ + * NC | 1 2 | GND 5V | 1 2 | GND + * RESET | 3 4 | 1.31 NC | 3 4 | NC + * 0.18 | 5 6 3.25 NC | 5 6 0.15 + * 1.23 | 7 8 | 3.26 0.16 | 7 8 | 0.18 + * 0.15 | 9 10 | 0.17 2.11 | 9 10 | 1.30 + * ------ ------ + * EXP2 EXP1 + */ + +#define EXP1_03_PIN -1 +#define EXP1_04_PIN -1 +#define EXP1_05_PIN -1 +#define EXP1_06_PIN P0_15 +#define EXP1_07_PIN P0_16 +#define EXP1_08_PIN P0_18 +#define EXP1_09_PIN P2_11 +#define EXP1_10_PIN P1_30 + +#define EXP2_03_PIN -1 +#define EXP2_04_PIN P1_31 +#define EXP2_05_PIN P0_18 +#define EXP2_06_PIN P3_25 +#define EXP2_07_PIN P1_23 +#define EXP2_08_PIN P3_26 +#define EXP2_09_PIN P0_15 +#define EXP2_10_PIN P0_17 + + /** * LCD / Controller * @@ -68,26 +99,23 @@ #if IS_TFTGLCD_PANEL #if ENABLED(TFTGLCD_PANEL_SPI) - #define TFTGLCD_CS P3_26 + #define TFTGLCD_CS EXP2_08_PIN #endif - #define SD_DETECT_PIN P1_31 - #elif HAS_WIRED_LCD - #define BTN_EN1 P3_26 - #define BTN_EN2 P3_25 - #define BTN_ENC P2_11 + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN + #define BTN_ENC EXP1_09_PIN - #define SD_DETECT_PIN P1_31 - #define LCD_SDSS P1_23 - #define LCD_PINS_RS P0_16 - #define LCD_PINS_ENABLE P0_18 - #define LCD_PINS_D4 P0_15 + #define LCD_SDSS EXP2_07_PIN + #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_ENABLE EXP2_05_PIN + #define LCD_PINS_D4 EXP2_09_PIN #if ENABLED(MKS_MINI_12864) #define DOGLCD_CS P2_06 - #define DOGLCD_A0 P0_16 + #define DOGLCD_A0 EXP1_07_PIN #endif #endif // HAS_WIRED_LCD @@ -106,17 +134,13 @@ #endif #endif -#if SD_CONNECTION_IS(LCD) - #define SS_PIN P1_23 -#endif - // Trinamic driver support #if HAS_TRINAMIC_CONFIG // Using TMC devices in intelligent mode requires extra connections to each device. Unfortunately // the SKR does not have many free pins (especially if a display is in use). The SPI-based devices // will require 3 connections (clock, mosi, miso), plus a chip select line (CS) for each driver. - // The UART-based devices require 2 pis per deriver (one of which must be interrupt capable). + // The UART-based devices require 2 pis per driver (one of which must be interrupt capable). // The same SPI pins can be shared with the display/SD card reader, meaning SPI-based devices are // probably a good choice for this board. // @@ -140,10 +164,10 @@ // 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 P0_18 - #define TMC_SW_MISO P0_17 + #define TMC_SW_MOSI EXP2_05_PIN + #define TMC_SW_MISO EXP2_10_PIN // To minimize pin usage use the same clock pin as the display/SD card reader. (May generate LCD noise.) - #define TMC_SW_SCK P0_15 + #define TMC_SW_SCK EXP2_09_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 @@ -186,14 +210,11 @@ // SDCARD_CONNECTION must not be 'LCD'. Nothing should be connected to EXP1/EXP2. //#define SKR_USE_LCD_PINS_FOR_CS #if ENABLED(SKR_USE_LCD_PINS_FOR_CS) - #if SD_CONNECTION_IS(LCD) - #error "SDCARD_CONNECTION must not be 'LCD' with SKR_USE_LCD_PINS_FOR_CS." - #endif - #define X_CS_PIN P1_23 - #define Y_CS_PIN P3_26 - #define Z_CS_PIN P2_11 - #define E0_CS_PIN P3_25 - #define E1_CS_PIN P1_31 + #define X_CS_PIN EXP2_07_PIN + #define Y_CS_PIN EXP2_08_PIN + #define Z_CS_PIN EXP1_09_PIN + #define E0_CS_PIN EXP2_06_PIN + #define E1_CS_PIN EXP2_04_PIN #endif // Example 2: A REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER @@ -201,19 +222,16 @@ // the pins will be in use. So SDCARD_CONNECTION must not be 'LCD'. //#define SKR_USE_LCD_SD_CARD_PINS_FOR_CS #if ENABLED(SKR_USE_LCD_SD_CARD_PINS_FOR_CS) - #if SD_CONNECTION_IS(LCD) - #error "SDCARD_CONNECTION must not be 'LCD' with SKR_USE_LCD_SD_CARD_PINS_FOR_CS." - #endif #define X_CS_PIN P0_02 #define Y_CS_PIN P0_03 #define Z_CS_PIN P2_06 // We use SD_DETECT_PIN for E0 #undef SD_DETECT_PIN - #define E0_CS_PIN P1_31 + #define E0_CS_PIN EXP2_04_PIN // We use LCD_SDSS pin for E1 #undef LCD_SDSS #define LCD_SDSS -1 - #define E1_CS_PIN P1_23 + #define E1_CS_PIN EXP2_07_PIN #endif // Example 3: Use the driver enable pins for chip-select. 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 31373fedff66..42c6f4d0299b 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -22,6 +22,7 @@ #pragma once #define BOARD_INFO_NAME "BTT SKR V1.3" +#define LPC1768_IS_SKRV1_3 1 // // Trinamic Stallguard pins @@ -37,7 +38,7 @@ // #ifdef X_STALL_SENSITIVITY #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_DIR < 0 + #if X_HOME_TO_MIN #define X_MAX_PIN P1_28 // X+ #else #define X_MIN_PIN P1_28 // X+ @@ -49,7 +50,7 @@ #ifdef Y_STALL_SENSITIVITY #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_DIR < 0 + #if Y_HOME_TO_MIN #define Y_MAX_PIN P1_26 // Y+ #else #define Y_MIN_PIN P1_26 // Y+ @@ -61,7 +62,7 @@ #ifdef Z_STALL_SENSITIVITY #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_DIR < 0 + #if Z_HOME_TO_MIN #define Z_MAX_PIN P1_24 // Z+ #else #define Z_MIN_PIN P1_24 // Z+ @@ -186,38 +187,39 @@ #endif /** - * _____ _____ - * NC | 1 2 | GND 5V | 1 2 | GND - * RESET | 3 4 | 1.31 (SD_DETECT) (LCD_D7) 1.23 | 3 4 | 1.22 (LCD_D6) - * (MOSI) 0.18 | 5 6 3.25 (BTN_EN2) (LCD_D5) 1.21 | 5 6 1.20 (LCD_D4) - * (SD_SS) 0.16 | 7 8 | 3.26 (BTN_EN1) (LCD_RS) 1.19 | 7 8 | 1.18 (LCD_EN) - * (SCK) 0.15 | 9 10| 0.17 (MISO) (BTN_ENC) 0.28 | 9 10| 1.30 (BEEPER) - * ----- ----- + * ______ ______ + * NC | 1 2 | GND 5V | 1 2 | GND + * RESET | 3 4 | 1.31 (SD_DETECT) (LCD_D7) 1.23 | 3 4 | 1.22 (LCD_D6) + * (MOSI) 0.18 | 5 6 3.25 (BTN_EN2) (LCD_D5) 1.21 | 5 6 1.20 (LCD_D4) + * (SD_SS) 0.16 | 7 8 | 3.26 (BTN_EN1) (LCD_RS) 1.19 | 7 8 | 1.18 (LCD_EN) + * (SCK) 0.15 | 9 10 | 0.17 (MISO) (BTN_ENC) 0.28 | 9 10 | 1.30 (BEEPER) + * ------ ------ * EXP2 EXP1 */ -#define EXPA1_03_PIN P1_23 -#define EXPA1_04_PIN P1_22 -#define EXPA1_05_PIN P1_21 -#define EXPA1_06_PIN P1_20 -#define EXPA1_07_PIN P1_19 -#define EXPA1_08_PIN P1_18 -#define EXPA1_09_PIN P0_28 -#define EXPA1_10_PIN P1_30 - -#define EXPA2_03_PIN -1 -#define EXPA2_04_PIN P1_31 -#define EXPA2_05_PIN P0_18 -#define EXPA2_06_PIN P3_25 -#define EXPA2_07_PIN P0_16 -#define EXPA2_08_PIN P3_26 -#define EXPA2_09_PIN P0_15 -#define EXPA2_10_PIN P0_17 +#define EXP1_03_PIN P1_23 +#define EXP1_04_PIN P1_22 +#define EXP1_05_PIN P1_21 +#define EXP1_06_PIN P1_20 +#define EXP1_07_PIN P1_19 +#define EXP1_08_PIN P1_18 +#define EXP1_09_PIN P0_28 +#define EXP1_10_PIN P1_30 + +#define EXP2_03_PIN -1 +#define EXP2_04_PIN P1_31 +#define EXP2_05_PIN P0_18 +#define EXP2_06_PIN P3_25 +#define EXP2_07_PIN P0_16 +#define EXP2_08_PIN P3_26 +#define EXP2_09_PIN P0_15 +#define EXP2_10_PIN P0_17 #if HAS_WIRED_LCD + #if ENABLED(ANET_FULL_GRAPHICS_LCD_ALT_WIRING) + #error "ANET_FULL_GRAPHICS_LCD_ALT_WIRING only applies to the ANET 1.0 board." - #if ENABLED(ANET_FULL_GRAPHICS_LCD) - + #elif ENABLED(ANET_FULL_GRAPHICS_LCD) #error "CAUTION! ANET_FULL_GRAPHICS_LCD requires wiring modifications. See 'pins_BTT_SKR_V1_3.h' for details. Comment out this line to continue." /** @@ -231,97 +233,157 @@ * The ANET_FULL_GRAPHICS_LCD connector plug: * * BEFORE AFTER - * _____ _____ - * GND 1 | 1 2 | 2 5V 5V 1 | 1 2 | 2 GND - * CS 3 | 3 4 | 4 BTN_EN2 CS 3 | 3 4 | 4 BTN_EN2 - * SID 5 | 5 6 6 BTN_EN1 SID 5 | 5 6 6 BTN_EN1 - * open 7 | 7 8 | 8 BTN_ENC CLK 7 | 7 8 | 8 BTN_ENC - * CLK 9 | 9 10| 10 Beeper open 9 | 9 10| 10 Beeper - * ----- ----- + * ______ ______ + * GND 1 | 1 2 | 2 5V 5V 1 | 1 2 | 2 GND + * CS 3 | 3 4 | 4 BTN_EN2 CS 3 | 3 4 | 4 BTN_EN2 + * SID 5 | 5 6 6 BTN_EN1 SID 5 | 5 6 6 BTN_EN1 + * open 7 | 7 8 | 8 BTN_ENC CLK 7 | 7 8 | 8 BTN_ENC + * CLK 9 | 9 10 | 10 Beeper open 9 | 9 10 | 10 Beeper + * ------ ------ * LCD LCD */ - #define LCD_PINS_RS EXPA1_03_PIN + #define LCD_PINS_RS EXP1_03_PIN - #define BTN_EN1 EXPA1_06_PIN - #define BTN_EN2 EXPA1_04_PIN - #define BTN_ENC EXPA1_08_PIN + #define BTN_EN1 EXP1_06_PIN + #define BTN_EN2 EXP1_04_PIN + #define BTN_ENC EXP1_08_PIN - #define LCD_PINS_ENABLE EXPA1_05_PIN - #define LCD_PINS_D4 EXPA1_07_PIN + #define LCD_PINS_ENABLE EXP1_05_PIN + #define LCD_PINS_D4 EXP1_07_PIN #elif ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS EXPA1_04_PIN + #define LCD_PINS_RS EXP1_04_PIN - #define BTN_EN1 EXPA1_08_PIN - #define BTN_EN2 EXPA1_06_PIN - #define BTN_ENC EXPA1_09_PIN // (58) open-drain + #define BTN_EN1 EXP1_08_PIN + #define BTN_EN2 EXP1_06_PIN + #define BTN_ENC EXP1_09_PIN // (58) open-drain - #define LCD_PINS_ENABLE EXPA1_03_PIN - #define LCD_PINS_D4 EXPA1_05_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN #elif HAS_ADC_BUTTONS - #error "ADC BUTTONS do not work unmodifed on SKR 1.3, The ADC ports cannot take more than 3.3v." + #error "ADC BUTTONS do not work unmodified on SKR 1.3, The ADC ports cannot take more than 3.3v." - #elif IS_TFTGLCD_PANEL + #elif HAS_SPI_TFT // Config for Classic UI (emulated DOGM) and Color UI + + #define TFT_A0_PIN EXP1_03_PIN + #define TFT_DC_PIN EXP1_03_PIN + #define TFT_CS_PIN EXP1_04_PIN + #define TFT_RESET_PIN EXP1_07_PIN + #define TFT_BACKLIGHT_PIN EXP1_08_PIN + + #define TFT_RST_PIN EXP2_04_PIN + #define TFT_MOSI_PIN EXP2_05_PIN + #define TFT_SCK_PIN EXP2_09_PIN + #define TFT_MISO_PIN EXP2_10_PIN + + #define BTN_EN2 EXP2_06_PIN + #define BTN_EN1 EXP2_08_PIN + #define BTN_ENC EXP1_09_PIN + + #define TOUCH_BUTTONS_HW_SPI + #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 + + #define TFT_BUFFER_SIZE 2400 + + #ifndef TFT_WIDTH + #define TFT_WIDTH 480 + #endif + #ifndef TFT_HEIGHT + #define TFT_HEIGHT 320 + #endif + + #define LCD_READ_ID 0xD3 + #define LCD_USE_DMA_SPI + + #if ENABLED(TFT_CLASSIC_UI) + #ifndef TOUCH_CALIBRATION_X + #define TOUCH_CALIBRATION_X -11386 + #endif + #ifndef TOUCH_CALIBRATION_Y + #define TOUCH_CALIBRATION_Y 8684 + #endif + #ifndef TOUCH_OFFSET_X + #define TOUCH_OFFSET_X 689 + #endif + #ifndef TOUCH_OFFSET_Y + #define TOUCH_OFFSET_Y -273 + #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_SIZE 2400 + #endif + #elif IS_TFTGLCD_PANEL #if ENABLED(TFTGLCD_PANEL_SPI) - #define TFTGLCD_CS EXPA2_08_PIN + #define TFTGLCD_CS EXP2_08_PIN #endif - #define SD_DETECT_PIN EXPA2_04_PIN + #define SD_DETECT_PIN EXP2_04_PIN #else // !CR10_STOCKDISPLAY - #define LCD_PINS_RS EXPA1_07_PIN + #define LCD_PINS_RS EXP1_07_PIN - #define BTN_EN1 EXPA2_08_PIN // (31) J3-2 & AUX-4 - #define BTN_EN2 EXPA2_06_PIN // (33) J3-4 & AUX-4 - #define BTN_ENC EXPA1_09_PIN // (58) open-drain + #define BTN_EN1 EXP2_08_PIN // (31) J3-2 & AUX-4 + #define BTN_EN2 EXP2_06_PIN // (33) J3-4 & AUX-4 + #define BTN_ENC EXP1_09_PIN // (58) open-drain - #define LCD_PINS_ENABLE EXPA1_08_PIN - #define LCD_PINS_D4 EXPA1_06_PIN + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN - #define LCD_SDSS EXPA2_07_PIN // (16) J3-7 & AUX-4 - #define SD_DETECT_PIN EXPA2_04_PIN // (49) (NOT 5V tolerant) + #define LCD_SDSS EXP2_07_PIN // (16) J3-7 & AUX-4 + #define SD_DETECT_PIN EXP2_04_PIN // (49) (NOT 5V tolerant) #if ENABLED(FYSETC_MINI_12864) - #define DOGLCD_CS EXPA1_08_PIN - #define DOGLCD_A0 EXPA1_07_PIN - #define DOGLCD_SCK EXPA2_09_PIN - #define DOGLCD_MOSI EXPA2_05_PIN + #define DOGLCD_CS EXP1_08_PIN + #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_SCK EXP2_09_PIN + #define DOGLCD_MOSI EXP2_05_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 EXPA1_06_PIN // Must be high or open for LCD to operate normally. + #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) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN EXPA1_05_PIN + #define RGB_LED_R_PIN EXP1_05_PIN #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN EXPA1_04_PIN + #define RGB_LED_G_PIN EXP1_04_PIN #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN EXPA1_03_PIN + #define RGB_LED_B_PIN EXP1_03_PIN #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN EXPA1_05_PIN + #define NEOPIXEL_PIN EXP1_05_PIN #endif #else // !FYSETC_MINI_12864 #if ENABLED(MKS_MINI_12864) - #define DOGLCD_CS EXPA1_05_PIN - #define DOGLCD_A0 EXPA1_04_PIN - #define DOGLCD_SCK EXPA2_09_PIN - #define DOGLCD_MOSI EXPA2_05_PIN + #define DOGLCD_CS EXP1_05_PIN + #define DOGLCD_A0 EXP1_04_PIN + #define DOGLCD_SCK EXP2_09_PIN + #define DOGLCD_MOSI EXP2_05_PIN #elif ENABLED(ENDER2_STOCKDISPLAY) @@ -337,21 +399,26 @@ * EXP1 */ - #define BTN_EN1 EXPA1_08_PIN - #define BTN_EN2 EXPA1_06_PIN - #define BTN_ENC EXPA1_09_PIN - #define DOGLCD_CS EXPA1_04_PIN - #define DOGLCD_A0 EXPA1_05_PIN - #define DOGLCD_SCK EXPA1_10_PIN - #define DOGLCD_MOSI EXPA1_03_PIN + #define BTN_EN1 EXP1_08_PIN + #define BTN_EN2 EXP1_06_PIN + #define BTN_ENC EXP1_09_PIN + #define DOGLCD_CS EXP1_04_PIN + #define DOGLCD_A0 EXP1_05_PIN + #define DOGLCD_SCK EXP1_10_PIN + #define DOGLCD_MOSI EXP1_03_PIN #define FORCE_SOFT_SPI #define LCD_BACKLIGHT_PIN -1 #endif - #if ENABLED(ULTIPANEL) - #define LCD_PINS_D5 EXPA1_05_PIN - #define LCD_PINS_D6 EXPA1_04_PIN - #define LCD_PINS_D7 EXPA1_03_PIN + #if IS_ULTIPANEL + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_04_PIN + #define LCD_PINS_D7 EXP1_03_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 @@ -360,16 +427,12 @@ #endif // HAS_WIRED_LCD -// -// SD Support -// - -#ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION LCD -#endif - -#if SD_CONNECTION_IS(LCD) - #define SS_PIN EXPA2_07_PIN +#if NEED_TOUCH_PINS + #define TOUCH_CS_PIN EXP1_06_PIN + #define TOUCH_SCK_PIN EXP2_09_PIN + #define TOUCH_MOSI_PIN EXP2_05_PIN + #define TOUCH_MISO_PIN EXP2_10_PIN + #define TOUCH_INT_PIN EXP1_05_PIN #endif /** diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h index 4686e984b088..43e954a4f1b0 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -21,6 +21,8 @@ */ #pragma once +#include "env_validate.h" + #ifndef BOARD_INFO_NAME #define BOARD_INFO_NAME "BTT SKR V1.4" #endif @@ -30,10 +32,17 @@ #endif // -// SD Connection +// EEPROM // -#ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION LCD +#if NO_EEPROM_SELECTED + //#define I2C_EEPROM // EEPROM on I2C-0 + //#define SDCARD_EEPROM_EMULATION +#endif + +#if ENABLED(I2C_EEPROM) + #define MARLIN_EEPROM_SIZE 0x8000 // 32Kb +#elif ENABLED(SDCARD_EEPROM_EMULATION) + #define MARLIN_EEPROM_SIZE 0x800 // 2Kb #endif // @@ -55,33 +64,54 @@ // #ifdef X_STALL_SENSITIVITY #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_DIR < 0 + #if X_HOME_TO_MIN #define X_MAX_PIN P1_26 // E0DET #else #define X_MIN_PIN P1_26 // E0DET #endif +#elif ENABLED(X_DUAL_ENDSTOPS) + #ifndef X_MIN_PIN + #define X_MIN_PIN P1_29 // X-STOP + #endif + #ifndef X_MAX_PIN + #define X_MAX_PIN P1_26 // E0DET + #endif #else #define X_STOP_PIN P1_29 // X-STOP #endif #ifdef Y_STALL_SENSITIVITY #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_DIR < 0 + #if Y_HOME_TO_MIN #define Y_MAX_PIN P1_25 // E1DET #else #define Y_MIN_PIN P1_25 // E1DET #endif +#elif ENABLED(Y_DUAL_ENDSTOPS) + #ifndef Y_MIN_PIN + #define Y_MIN_PIN P1_28 // Y-STOP + #endif + #ifndef Y_MAX_PIN + #define Y_MAX_PIN P1_25 // E1DET + #endif #else #define Y_STOP_PIN P1_28 // Y-STOP #endif #ifdef Z_STALL_SENSITIVITY #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_DIR < 0 + #if Z_HOME_TO_MIN #define Z_MAX_PIN P1_00 // PWRDET #else #define Z_MIN_PIN P1_00 // PWRDET #endif +#elif ENABLED(Z_MULTI_ENDSTOPS) + #ifndef Z_MIN_PIN + #define Z_MIN_PIN P1_27 // Z-STOP + #endif + #ifndef Z_MAX_PIN + #define Z_MAX_PIN P1_00 // PWRDET + #endif #else #ifndef Z_STOP_PIN #define Z_STOP_PIN P1_27 // Z-STOP @@ -208,200 +238,253 @@ #define E1_SERIAL_TX_PIN P1_01 #define E1_SERIAL_RX_PIN P1_01 - #define Z2_SERIAL_TX_PIN P1_01 - #define Z2_SERIAL_RX_PIN P1_01 - // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 #endif -// -// SD Connection -// -#if SD_CONNECTION_IS(LCD) - #define SS_PIN P0_16 -#endif +/* _____ _____ + * NC | 1 2 | GND 5V | 1 2 | GND + * RESET | 3 4 | 1.31 1.23 | 3 4 | 1.22 + * 0.18 | 5 6 3.25 1.21 | 5 6 1.20 + * 0.16 | 7 8 | 3.26 1.19 | 7 8 | 1.18 + * 0.15 | 9 10| 0.17 0.28 | 9 10| 1.30 + * ----- ----- + * EXP2 EXP1 + */ + +#define EXP1_03_PIN P1_23 +#define EXP1_04_PIN P1_22 +#define EXP1_05_PIN P1_21 +#define EXP1_06_PIN P1_20 +#define EXP1_07_PIN P1_19 +#define EXP1_08_PIN P1_18 +#define EXP1_09_PIN P0_28 +#define EXP1_10_PIN P1_30 + +#define EXP2_03_PIN -1 +#define EXP2_04_PIN P1_31 +#define EXP2_05_PIN P0_18 +#define EXP2_06_PIN P3_25 +#define EXP2_07_PIN P0_16 +#define EXP2_08_PIN P3_26 +#define EXP2_09_PIN P0_15 +#define EXP2_10_PIN P0_17 /** * _____ _____ * NC | · · | GND 5V | · · | GND * RESET | · · | 1.31 (SD_DETECT) (LCD_D7) 1.23 | · · | 1.22 (LCD_D6) - * (MOSI) 0.18 | · · | 3.25 (BTN_EN2) (LCD_D5) 1.21 | · · | 1.20 (LCD_D4) + * (MOSI) 0.18 | · · 3.25 (BTN_EN2) (LCD_D5) 1.21 | · · 1.20 (LCD_D4) * (SD_SS) 0.16 | · · | 3.26 (BTN_EN1) (LCD_RS) 1.19 | · · | 1.18 (LCD_EN) * (SCK) 0.15 | · · | 0.17 (MISO) (BTN_ENC) 0.28 | · · | 1.30 (BEEPER) * ----- ----- * EXP2 EXP1 */ -#if HAS_WIRED_LCD - #if ENABLED(ANET_FULL_GRAPHICS_LCD) - #define LCD_PINS_RS P1_23 +#if ENABLED(DWIN_CREALITY_LCD) - #define BTN_EN1 P1_20 - #define BTN_EN2 P1_22 - #define BTN_ENC P1_18 + // RET6 DWIN ENCODER LCD + #define BTN_ENC P1_20 + #define BTN_EN1 P1_23 + #define BTN_EN2 P1_22 - #define LCD_PINS_ENABLE P1_21 - #define LCD_PINS_D4 P1_19 + #ifndef BEEPER_PIN + #define BEEPER_PIN P1_21 + #undef SPEAKER + #endif + +#elif HAS_WIRED_LCD && !BTT_MOTOR_EXPANSION + + #if ENABLED(ANET_FULL_GRAPHICS_LCD_ALT_WIRING) + #error "CAUTION! ANET_FULL_GRAPHICS_LCD_ALT_WIRING requires wiring modifications. See 'pins_BTT_SKR_V1_4.h' for details. Comment out this line to continue." + + /** + * 1. Cut the tab off the LCD connector so it can be plugged into the "EXP1" connector the other way. + * 2. Swap the LCD's +5V (Pin2) and GND (Pin1) wires. (This is the critical part!) + * + * !!! If you are unsure, ask for help! Your motherboard may be damaged in some circumstances !!! + * + * The ANET_FULL_GRAPHICS_LCD_ALT_WIRING connector plug: + * + * BEFORE AFTER + * _____ _____ + * GND | 1 2 | 5V 5V | 1 2 | GND + * CS | 3 4 | BTN_EN2 CS | 3 4 | BTN_EN2 + * SID | 5 6 BTN_EN1 SID | 5 6 BTN_EN1 + * open | 7 8 | BTN_ENC open | 7 8 | BTN_ENC + * CLK | 9 10| Beeper CLK | 9 10| Beeper + * ----- ----- + * LCD LCD + */ + + #define LCD_PINS_RS EXP1_07_PIN + + #define BTN_EN1 EXP1_05_PIN + #define BTN_EN2 EXP1_04_PIN + #define BTN_ENC EXP1_10_PIN + + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN + #define BEEPER_PIN EXP1_03_PIN + + #elif ENABLED(ANET_FULL_GRAPHICS_LCD) + #error "CAUTION! ANET_FULL_GRAPHICS_LCD requires wiring modifications. See 'pins_BTT_SKR_V1_4.h' for details. Comment out this line to continue." + + /** + * 1. Cut the tab off the LCD connector so it can be plugged into the "EXP1" connector the other way. + * 2. Swap the LCD's +5V (Pin2) and GND (Pin1) wires. (This is the critical part!) + * 3. Rewire the CLK Signal (LCD Pin9) to LCD Pin7. (LCD Pin9 remains open because this pin is open drain.) + * 4. A wire is needed to connect the Reset switch at J3 (LCD Pin7) to EXP2 (Pin3) on the board. + * + * !!! If you are unsure, ask for help! Your motherboard may be damaged in some circumstances !!! + * + * The ANET_FULL_GRAPHICS_LCD connector plug: + * + * BEFORE AFTER + * ______ ______ + * GND | 1 2 | 5V 5V | 1 2 | GND + * CS | 3 4 | BTN_EN2 CS | 3 4 | BTN_EN2 + * SID | 5 6 BTN_EN1 SID | 5 6 BTN_EN1 + * open | 7 8 | BTN_ENC CLK | 7 8 | BTN_ENC + * CLK | 9 10 | Beeper open | 9 10 | Beeper + * ------ ------ + * LCD LCD + */ + + #define LCD_PINS_RS EXP1_03_PIN + + #define BTN_EN1 EXP1_06_PIN + #define BTN_EN2 EXP1_04_PIN + #define BTN_ENC EXP1_08_PIN + + #define LCD_PINS_ENABLE EXP1_05_PIN + #define LCD_PINS_D4 EXP1_07_PIN + + #define BEEPER_PIN EXP1_10_PIN #elif ENABLED(CR10_STOCKDISPLAY) - #define BTN_ENC P0_28 // (58) open-drain - #define LCD_PINS_RS P1_22 + #define BTN_ENC EXP1_09_PIN // (58) open-drain + #define LCD_PINS_RS EXP1_04_PIN - #define BTN_EN1 P1_18 - #define BTN_EN2 P1_20 + #define BTN_EN1 EXP1_08_PIN + #define BTN_EN2 EXP1_06_PIN - #define LCD_PINS_ENABLE P1_23 - #define LCD_PINS_D4 P1_21 + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN #elif ENABLED(ENDER2_STOCKDISPLAY) /** Creality Ender-2 display pinout - * _____ - * 5V | 1 2 | GND - * (MOSI) 1.23 | 3 4 | 1.22 (LCD_RS) - * (LCD_A0) 1.21 | 5 6 | 1.20 (BTN_EN2) - * RESET 1.19 | 7 8 | 1.18 (BTN_EN1) - * (BTN_ENC) 0.28 | 9 10| 1.30 (SCK) - * ----- + * ______ + * 5V | 1 2 | GND + * (MOSI) 1.23 | 3 4 | 1.22 (LCD_RS) + * (LCD_A0) 1.21 | 5 6 1.20 (BTN_EN2) + * RESET 1.19 | 7 8 | 1.18 (BTN_EN1) + * (BTN_ENC) 0.28 | 9 10 | 1.30 (SCK) + * ------ * EXP1 */ - #define BTN_EN1 P1_18 - #define BTN_EN2 P1_20 - #define BTN_ENC P0_28 + #define BTN_EN1 EXP1_08_PIN + #define BTN_EN2 EXP1_06_PIN + #define BTN_ENC EXP1_09_PIN - #define DOGLCD_CS P1_22 - #define DOGLCD_A0 P1_21 - #define DOGLCD_SCK P1_30 - #define DOGLCD_MOSI P1_23 + #define DOGLCD_CS EXP1_04_PIN + #define DOGLCD_A0 EXP1_05_PIN + #define DOGLCD_SCK EXP1_10_PIN + #define DOGLCD_MOSI EXP1_03_PIN #define FORCE_SOFT_SPI #define LCD_BACKLIGHT_PIN -1 #elif HAS_SPI_TFT // Config for Classic UI (emulated DOGM) and Color UI - #define TFT_CS_PIN P1_22 - #define TFT_A0_PIN P1_23 - #define TFT_DC_PIN P1_23 - #define TFT_MISO_PIN P0_17 - #define TFT_BACKLIGHT_PIN P1_18 - #define TFT_RESET_PIN P1_19 + #define TFT_CS_PIN EXP1_04_PIN + #define TFT_A0_PIN EXP1_03_PIN + #define TFT_DC_PIN EXP1_03_PIN + #define TFT_MISO_PIN EXP2_10_PIN + #define TFT_BACKLIGHT_PIN EXP1_08_PIN + #define TFT_RESET_PIN EXP1_07_PIN #define LCD_USE_DMA_SPI - #define TOUCH_INT_PIN P1_21 - #define TOUCH_CS_PIN P1_20 + #define TOUCH_INT_PIN EXP1_05_PIN + #define TOUCH_CS_PIN EXP1_06_PIN #define TOUCH_BUTTONS_HW_SPI #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 - #ifndef GRAPHICAL_TFT_UPSCALE - #define GRAPHICAL_TFT_UPSCALE 3 - #endif // SPI 1 - #define SCK_PIN P0_15 - #define MISO_PIN P0_17 - #define MOSI_PIN P0_18 - - // Disable any LCD related PINs config - #define LCD_PINS_ENABLE -1 - #define LCD_PINS_RS -1 - - // XPT2046 Touch Screen calibration - #if ENABLED(TFT_CLASSIC_UI) - #ifndef XPT2046_X_CALIBRATION - #define XPT2046_X_CALIBRATION -11245 - #endif - #ifndef XPT2046_Y_CALIBRATION - #define XPT2046_Y_CALIBRATION 8629 - #endif - #ifndef XPT2046_X_OFFSET - #define XPT2046_X_OFFSET 685 - #endif - #ifndef XPT2046_Y_OFFSET - #define XPT2046_Y_OFFSET -285 - #endif - #elif ENABLED(TFT_480x320_SPI) - #ifndef XPT2046_X_CALIBRATION - #define XPT2046_X_CALIBRATION -17232 - #endif - #ifndef XPT2046_Y_CALIBRATION - #define XPT2046_Y_CALIBRATION 11196 - #endif - #ifndef XPT2046_X_OFFSET - #define XPT2046_X_OFFSET 1047 - #endif - #ifndef XPT2046_Y_OFFSET - #define XPT2046_Y_OFFSET -358 - #endif + #define SD_SCK_PIN EXP2_09_PIN + #define SD_MISO_PIN EXP2_10_PIN + #define SD_MOSI_PIN EXP2_05_PIN - #define TFT_BUFFER_SIZE 2400 - #endif + #define TFT_BUFFER_SIZE 2400 #elif IS_TFTGLCD_PANEL #if ENABLED(TFTGLCD_PANEL_SPI) - #define TFTGLCD_CS P3_26 + #define TFTGLCD_CS EXP2_08_PIN #endif - #define SD_DETECT_PIN P1_31 + #define SD_DETECT_PIN EXP2_04_PIN #else - #define BTN_ENC P0_28 // (58) open-drain - #define LCD_PINS_RS P1_19 + #define BTN_ENC EXP1_09_PIN // (58) open-drain + #define LCD_PINS_RS EXP1_07_PIN - #define BTN_EN1 P3_26 // (31) J3-2 & AUX-4 - #define BTN_EN2 P3_25 // (33) J3-4 & AUX-4 + #define BTN_EN1 EXP2_08_PIN // (31) J3-2 & AUX-4 + #define BTN_EN2 EXP2_06_PIN // (33) J3-4 & AUX-4 - #define LCD_PINS_ENABLE P1_18 - #define LCD_PINS_D4 P1_20 + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN - #define LCD_SDSS P0_16 // (16) J3-7 & AUX-4 - - #if SD_CONNECTION_IS(LCD) - #define SD_DETECT_PIN P1_31 // (49) (NOT 5V tolerant) - #endif + #define LCD_SDSS EXP2_07_PIN // (16) J3-7 & AUX-4 #if ENABLED(FYSETC_MINI_12864) - #define DOGLCD_CS P1_18 - #define DOGLCD_A0 P1_19 - #define DOGLCD_SCK P0_15 - #define DOGLCD_MOSI P0_18 + #define DOGLCD_CS EXP1_08_PIN + #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_SCK EXP2_09_PIN + #define DOGLCD_MOSI EXP2_05_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 P1_20 // Must be high or open for LCD to operate normally. + #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) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN P1_21 + #define RGB_LED_R_PIN EXP1_05_PIN #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN P1_22 + #define RGB_LED_G_PIN EXP1_04_PIN #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN P1_23 + #define RGB_LED_B_PIN EXP1_03_PIN #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN P1_21 + #define NEOPIXEL_PIN EXP1_05_PIN #endif #else // !FYSETC_MINI_12864 #if ENABLED(MKS_MINI_12864) - #define DOGLCD_CS P1_21 - #define DOGLCD_A0 P1_22 - #define DOGLCD_SCK P0_15 - #define DOGLCD_MOSI P0_18 + #define DOGLCD_CS EXP1_05_PIN + #define DOGLCD_A0 EXP1_04_PIN + #define DOGLCD_SCK EXP2_09_PIN + #define DOGLCD_MOSI EXP2_05_PIN #define FORCE_SOFT_SPI #endif - #if ENABLED(ULTIPANEL) - #define LCD_PINS_D5 P1_21 - #define LCD_PINS_D6 P1_22 - #define LCD_PINS_D7 P1_23 + #if IS_ULTIPANEL + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_04_PIN + #define LCD_PINS_D7 EXP1_03_PIN + + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN EXP1_03_PIN // Detect the presence of the encoder + #endif + #endif #endif // !FYSETC_MINI_12864 @@ -411,7 +494,7 @@ #endif // HAS_WIRED_LCD #if HAS_ADC_BUTTONS - #error "ADC BUTTONS do not work unmodifed on SKR 1.4, The ADC ports cannot take more than 3.3v." + #error "ADC BUTTONS do not work unmodified on SKR 1.4, The ADC ports cannot take more than 3.3v." #endif // diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h index 820c35a01cb9..9f33c7c3f84c 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h @@ -21,12 +21,18 @@ */ #pragma once -#ifdef SKR_HAS_LPC1769 - #if NOT_TARGET(MCU_LPC1769) - #error "Oops! Make sure you have the LPC1769 environment selected in your IDE." +#include "env_validate.h" + +// 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) + #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." #endif -#elif NOT_TARGET(MCU_LPC1768) - #error "Oops! Make sure you have the LPC1768 environment selected in your IDE." #endif // Ignore temp readings during development. @@ -59,7 +65,7 @@ #define TEMP_BED_PIN P0_23_A0 // A0 (T0) - (67) - TEMP_BED_PIN #endif -#if HOTENDS == 1 +#if HOTENDS == 1 && TEMP_SENSOR_REDUNDANT_SOURCE != 1 #if TEMP_SENSOR_PROBE #define TEMP_PROBE_PIN TEMP_1_PIN #elif TEMP_SENSOR_CHAMBER @@ -67,13 +73,26 @@ #endif #endif +// CS, MISO, MOSI, and SCK for MAX Thermocouple SPI +#if HAS_MAX_TC + //#define TEMP_0_CS_PIN P... + //#define TEMP_0_MISO_PIN P... + //#define TEMP_0_MOSI_PIN P... + //#define TEMP_0_SCK_PIN P... + + //#define TEMP_1_CS_PIN P... + //#define TEMP_1_MISO_PIN P... + //#define TEMP_1_MOSI_PIN P... + //#define TEMP_1_SCK_PIN P... +#endif + // // Heaters / Fans // #ifndef HEATER_0_PIN #define HEATER_0_PIN P2_07 #endif -#if HOTENDS == 1 +#if HOTENDS == 1 && DISABLED(HEATERS_PARALLEL) #ifndef FAN1_PIN #define FAN1_PIN P2_04 #endif @@ -92,26 +111,99 @@ // // LCD / Controller // -#if HAS_WIRED_LCD && DISABLED(LCD_USE_I2C_BUZZER) +#if !defined(BEEPER_PIN) && HAS_WIRED_LCD && DISABLED(LCD_USE_I2C_BUZZER) #define BEEPER_PIN P1_30 // (37) not 5V tolerant #endif // // SD Support // +#ifndef SDCARD_CONNECTION + #if HAS_WIRED_LCD + #define SDCARD_CONNECTION LCD + #else + #define SDCARD_CONNECTION ONBOARD + #endif +#endif + #define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card +#if SD_CONNECTION_IS(LCD) && ENABLED(SKR_USE_LCD_SD_CARD_PINS_FOR_CS) + #error "SDCARD_CONNECTION must not be 'LCD' with SKR_USE_LCD_SD_CARD_PINS_FOR_CS." +#endif + #if SD_CONNECTION_IS(LCD) - #define SCK_PIN P0_15 - #define MISO_PIN P0_17 - #define MOSI_PIN P0_18 + #define SD_SCK_PIN P0_15 + #define SD_MISO_PIN P0_17 + #define SD_MOSI_PIN P0_18 + #define SD_SS_PIN EXP2_07_PIN + #define SD_DETECT_PIN EXP2_04_PIN + #elif SD_CONNECTION_IS(ONBOARD) #undef SD_DETECT_PIN #define SD_DETECT_PIN P0_27 - #define SCK_PIN P0_07 - #define MISO_PIN P0_08 - #define MOSI_PIN P0_09 - #define SS_PIN ONBOARD_SD_CS_PIN + #define SD_SCK_PIN P0_07 + #define SD_MISO_PIN P0_08 + #define SD_MOSI_PIN P0_09 + #define SD_SS_PIN ONBOARD_SD_CS_PIN #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "No custom SD drive cable defined for this board." #endif + +#if ENABLED(BTT_MOTOR_EXPANSION) + /** ______ ______ + * NC | 1 2 | GND NC | 1 2 | GND + * NC | 3 4 | M1EN M2EN | 3 4 | M3EN + * M1STP | 5 6 M1DIR M1RX | 5 6 M1DIAG + * M2DIR | 7 8 | M2STP M2RX | 7 8 | M2DIAG + * M3DIR | 9 10 | M3STP M3RX | 9 10 | M3DIAG + * ------ ------ + * EXP2 EXP1 + * + * NB In EXP_MOT_USE_EXP2_ONLY mode EXP1 is not used and M2EN and M3EN need to be jumpered to M1EN + */ + + // M1 on Driver Expansion Module + #define E2_STEP_PIN EXP2_05_PIN + #define E2_DIR_PIN EXP2_06_PIN + #define E2_ENABLE_PIN EXP2_04_PIN + #if !EXP_MOT_USE_EXP2_ONLY + #define E2_DIAG_PIN EXP1_06_PIN + #define E2_CS_PIN EXP1_05_PIN + #if HAS_TMC_UART + #define E2_SERIAL_TX_PIN EXP1_05_PIN + #define E2_SERIAL_RX_PIN EXP1_05_PIN + #endif + #endif + + // M2 on Driver Expansion Module + #define E3_STEP_PIN EXP2_08_PIN + #define E3_DIR_PIN EXP2_07_PIN + #if !EXP_MOT_USE_EXP2_ONLY + #define E3_ENABLE_PIN EXP1_03_PIN + #define E3_DIAG_PIN EXP1_08_PIN + #define E3_CS_PIN EXP1_07_PIN + #if HAS_TMC_UART + #define E3_SERIAL_TX_PIN EXP1_07_PIN + #define E3_SERIAL_RX_PIN EXP1_07_PIN + #endif + #else + #define E3_ENABLE_PIN EXP2_04_PIN + #endif + + // M3 on Driver Expansion Module + #define E4_STEP_PIN EXP2_10_PIN + #define E4_DIR_PIN EXP2_09_PIN + #if !EXP_MOT_USE_EXP2_ONLY + #define E4_ENABLE_PIN EXP1_04_PIN + #define E4_DIAG_PIN EXP1_10_PIN + #define E4_CS_PIN EXP1_09_PIN + #if HAS_TMC_UART + #define E4_SERIAL_TX_PIN EXP1_09_PIN + #define E4_SERIAL_RX_PIN EXP1_09_PIN + #endif + #else + #define E4_ENABLE_PIN EXP2_04_PIN + #endif + +#endif // BTT_MOTOR_EXPANSION diff --git a/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h b/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h index 5132081a5591..1ec1131b45ff 100644 --- a/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h +++ b/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h @@ -21,13 +21,11 @@ */ #pragma once -#if NOT_TARGET(MCU_LPC1768) - #error "Oops! Make sure you have the LPC1768 environment selected in your IDE." -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "GMARSH X6 REV1" -// Ignore temp readings during develpment. +// Ignore temp readings during development. //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 // @@ -121,11 +119,12 @@ // Misc. Functions // #define LED_PIN P1_31 +#define POWER_MONITOR_VOLTAGE_PIN P0_25_A2 // // LCD // -#if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) +#if IS_RRD_SC #define BEEPER_PIN P0_19 #define BTN_EN1 P1_23 #define BTN_EN2 P1_24 @@ -136,6 +135,11 @@ #define LCD_PINS_D5 P0_22 #define LCD_PINS_D6 P1_29 #define LCD_PINS_D7 P1_28 + + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif + #endif // @@ -149,15 +153,14 @@ #define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card #if SD_CONNECTION_IS(LCD) - #define SCK_PIN P0_15 - #define MISO_PIN P0_17 - #define MOSI_PIN P0_18 - #define SS_PIN P0_16 + #define SD_SCK_PIN P0_15 + #define SD_MISO_PIN P0_17 + #define SD_MOSI_PIN P0_18 + #define SD_SS_PIN P0_16 + #define SD_DETECT_PIN P1_22 #elif SD_CONNECTION_IS(ONBOARD) - #undef SD_DETECT_PIN - #define SD_DETECT_PIN P0_27 - #define SCK_PIN P0_07 - #define MISO_PIN P0_08 - #define MOSI_PIN P0_09 - #define SS_PIN ONBOARD_SD_CS_PIN + #define SD_SCK_PIN P0_07 + #define SD_MISO_PIN P0_08 + #define SD_MOSI_PIN P0_09 + #define SD_SS_PIN ONBOARD_SD_CS_PIN #endif diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h index 6c6a9ea306ec..4c2b606929f4 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h @@ -25,11 +25,7 @@ * MKS SBASE pin assignments */ -#if defined(MKS_HAS_LPC1769) && NOT_TARGET(MCU_LPC1769) - #error "Oops! Make sure you have the LPC1769 environment selected in your IDE." -#elif NOT_TARGET(MKS_HAS_LPC1769, MCU_LPC1768) - #error "Oops! Make sure you have the LPC1768 environment selected in your IDE." -#endif +#include "env_validate.h" #ifndef BOARD_INFO_NAME #define BOARD_INFO_NAME "MKS SBASE" @@ -131,23 +127,31 @@ #define PIN_P2_11 P2_11 // Interrupt Capable // -// Průša i3 MK2 Multi Material Multiplexer Support +// Průša i3 MMU1 (Multi Material Multiplexer) Support // -#if ENABLED(MK2_MULTIPLEXER) +#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 #endif // -// Misc. Functions +// Power Supply Control // -#define PS_ON_PIN P0_25 // TH3 Connector +#if ENABLED(PSU_CONTROL) // MKSPWC + #ifndef PS_ON_PIN + #define PS_ON_PIN P0_25 // SERVO + #endif + #ifndef KILL_PIN + #define KILL_PIN P1_29 // Z+ + #define KILL_PIN_STATE HIGH + #endif +#endif // // Ethernet pins // -#ifndef ULTIPANEL +#if !IS_ULTIPANEL #define ENET_MDIO P1_17 // J12-4 #define ENET_RX_ER P1_14 // J12-6 #define ENET_RXD1 P1_10 // J12-8 @@ -182,26 +186,25 @@ * SD_DETECT_PIN entirely and remove that wire from the the custom cable. */ #define SD_DETECT_PIN P2_11 // J8-5 (moved from EXP2 P0.27) - #define SCK_PIN P1_22 // J8-2 (moved from EXP2 P0.7) - #define MISO_PIN P1_23 // J8-3 (moved from EXP2 P0.8) - #define MOSI_PIN P2_12 // J8-4 (moved from EXP2 P0.9) - #define SS_PIN P0_28 + #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_SS_PIN P0_28 #define LPC_SOFTWARE_SPI // With a custom cable we need software SPI because the // selected pins are not on a hardware SPI controller -#elif SD_CONNECTION_IS(LCD) - // use standard cable and header, SPI and SD detect sre shared with on-board SD card - // hardware SPI is used for both SD cards. The detect pin is shred between the - // LCD and onboard SD readers so we disable it. - #define SCK_PIN P0_07 - #define MISO_PIN P0_08 - #define MOSI_PIN P0_09 - #define SS_PIN P0_28 -#elif SD_CONNECTION_IS(ONBOARD) - #define SD_DETECT_PIN P0_27 - #define SCK_PIN P0_07 - #define MISO_PIN P0_08 - #define MOSI_PIN P0_09 - #define SS_PIN ONBOARD_SD_CS_PIN +#elif SD_CONNECTION_IS(LCD) || SD_CONNECTION_IS(ONBOARD) + #define SD_SCK_PIN P0_07 + #define SD_MISO_PIN P0_08 + #define SD_MOSI_PIN P0_09 + #if SD_CONNECTION_IS(LCD) + // Use standard cable and header, SPI and SD detect are shared with onboard SD card. + // Hardware SPI is used for both SD cards. The detect pin is shared between the + // LCD and onboard SD readers so we disable it. + #define SD_SS_PIN P0_28 + #else + #define SD_DETECT_PIN P0_27 + #define SD_SS_PIN ONBOARD_SD_CS_PIN + #endif #endif /** @@ -238,8 +241,8 @@ #define LCD_PINS_ENABLE P0_18 // EXP1.3 #define LCD_PINS_D4 P0_15 // EXP1.5 #if ANY(VIKI2, miniVIKI) - #define DOGLCD_SCK SCK_PIN - #define DOGLCD_MOSI MOSI_PIN + #define DOGLCD_SCK SD_SCK_PIN + #define DOGLCD_MOSI SD_MOSI_PIN #endif #if ENABLED(FYSETC_MINI_12864) diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h index d269ecbdc90d..0c3f44ceb721 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h @@ -25,9 +25,7 @@ * MKS SGEN-L pin assignments */ -#if NOT_TARGET(MCU_LPC1768) - #error "Oops! Make sure you have the LPC1768 environment selected in your IDE." -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "MKS SGen-L" #define BOARD_WEBSITE_URL "github.com/makerbase-mks/MKS-SGEN_L" @@ -52,7 +50,7 @@ // #ifdef X_STALL_SENSITIVITY #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_DIR < 0 + #if X_HOME_TO_MIN #define X_MAX_PIN P1_28 // X+ #else #define X_MIN_PIN P1_28 // X+ @@ -64,7 +62,7 @@ #ifdef Y_STALL_SENSITIVITY #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_DIR < 0 + #if Y_HOME_TO_MIN #define Y_MAX_PIN P1_26 // Y+ #else #define Y_MIN_PIN P1_26 // Y+ @@ -76,7 +74,7 @@ #ifdef Z_STALL_SENSITIVITY #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_DIR < 0 + #if Z_HOME_TO_MIN #define Z_MAX_PIN P1_24 // Z+ #else #define Z_MIN_PIN P1_24 // Z+ @@ -189,7 +187,7 @@ // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 -#endif // TMC2208 || TMC2209 +#endif // HAS_TMC_UART // // Temperature Sensors @@ -204,7 +202,7 @@ // #define HEATER_BED_PIN P2_05 #define HEATER_0_PIN P2_07 -#if HOTENDS == 1 +#if HOTENDS == 1 && DISABLED(HEATERS_PARALLEL) #ifndef FAN1_PIN #define FAN1_PIN P2_06 #endif @@ -217,6 +215,19 @@ #define FAN_PIN P2_04 #endif +// +// Power Supply Control +// +#if ENABLED(PSU_CONTROL) // MKSPWC + #ifndef PS_ON_PIN + #define PS_ON_PIN P2_00 // SERVO + #endif + #ifndef KILL_PIN + #define KILL_PIN P1_24 // Z+ + #define KILL_PIN_STATE HIGH + #endif +#endif + // // Misc. Functions // @@ -229,7 +240,7 @@ * _____ _____ * (BEEPER) 1.31 | · · | 1.30 (BTN_ENC) (MISO) 0.8 | · · | 0.7 (SD_SCK) * (LCD_EN) 0.18 | · · | 0.16 (LCD_RS) (BTN_EN1) 3.25 | · · | 0.28 (SD_CS2) - * (LCD_D4) 0.15 | · · | 0.17 (LCD_D5) (BTN_EN2) 3.26 | · · | 0.9 (SD_MOSI) + * (LCD_D4) 0.15 | · · 0.17 (LCD_D5) (BTN_EN2) 3.26 | · · 0.9 (SD_MOSI) * (LCD_D6) 1.0 | · · | 1.22 (LCD_D7) (SD_DETECT) 0.27 | · · | RST * GND | · · | 5V GND | · · | NC * ----- ----- @@ -249,6 +260,35 @@ #define LCD_PINS_ENABLE P1_22 #define LCD_PINS_D4 P0_17 + #elif HAS_SPI_TFT // Config for Classic UI (emulated DOGM) and Color UI + #define TFT_CS_PIN P1_00 + #define TFT_A0_PIN P1_22 + #define TFT_DC_PIN P1_22 + #define TFT_MISO_PIN P0_08 + #define TFT_BACKLIGHT_PIN P0_18 + #define TFT_RESET_PIN P0_16 + + #define LCD_USE_DMA_SPI + + #define TOUCH_INT_PIN P0_17 + #define TOUCH_CS_PIN P0_15 + #define TOUCH_BUTTONS_HW_SPI + #define TOUCH_BUTTONS_HW_SPI_DEVICE 2 + + // Disable any LCD related PINs config + #define LCD_PINS_ENABLE -1 + #define LCD_PINS_RS -1 + + #ifndef TFT_BUFFER_SIZE + #define TFT_BUFFER_SIZE 1200 + #endif + #ifndef TFT_QUEUE_SIZE + #define TFT_QUEUE_SIZE 6144 + #endif + + #define BTN_EN1 P3_25 + #define BTN_EN2 P3_26 + #elif IS_TFTGLCD_PANEL #undef BEEPER_PIN @@ -319,10 +359,15 @@ #define DOGLCD_A0 P1_00 #endif - #if ENABLED(ULTIPANEL) + #if IS_ULTIPANEL #define LCD_PINS_D5 P0_17 #define LCD_PINS_D6 P1_00 #define LCD_PINS_D7 P1_22 + + #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 @@ -341,13 +386,13 @@ #if SD_CONNECTION_IS(LCD) || SD_CONNECTION_IS(ONBOARD) #define SD_DETECT_PIN P0_27 - #define SCK_PIN P0_07 - #define MISO_PIN P0_08 - #define MOSI_PIN P0_09 + #define SD_SCK_PIN P0_07 + #define SD_MISO_PIN P0_08 + #define SD_MOSI_PIN P0_09 #if SD_CONNECTION_IS(ONBOARD) - #define SS_PIN ONBOARD_SD_CS_PIN + #define SD_SS_PIN ONBOARD_SD_CS_PIN #else - #define SS_PIN P0_28 + #define SD_SS_PIN P0_28 #endif #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "No custom SD drive cable defined for this board." diff --git a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h index 294e7527a875..fe7daa8cdafd 100644 --- a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h +++ b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h @@ -35,9 +35,7 @@ // Numbers in parentheses () are the corresponding mega2560 pin numbers -#if NOT_TARGET(MCU_LPC1768) - #error "Oops! Make sure you have the LPC1768 environment selected in your IDE." -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "Re-ARM RAMPS 1.4" @@ -219,7 +217,7 @@ #define FAN1_PIN RAMPS_D8_PIN #elif DISABLED(IS_RAMPS_SF) // Not Spindle, Fan (i.e., "EFBF" or "EFBE") #define HEATER_BED_PIN RAMPS_D8_PIN - #if HOTENDS == 1 + #if HOTENDS == 1 && DISABLED(HEATERS_PARALLEL) #define FAN1_PIN MOSFET_D_PIN #else #define HEATER_1_PIN MOSFET_D_PIN @@ -250,8 +248,8 @@ #define PS_ON_PIN P2_12 // (12) -#if !defined(MAX6675_SS_PIN) && DISABLED(USE_ZMAX_PLUG) - #define MAX6675_SS_PIN P1_28 +#if !defined(TEMP_0_CS_PIN) && DISABLED(USE_ZMAX_PLUG) + #define TEMP_0_CS_PIN P1_28 #endif #if ENABLED(CASE_LIGHT_ENABLE) && !PIN_EXISTS(CASE_LIGHT) && !defined(SPINDLE_LASER_ENA_PIN) @@ -325,6 +323,10 @@ #define LCD_PINS_ENABLE P0_18 // J3-10 & AUX-3 (SID, MOSI) #define LCD_PINS_D4 P2_06 // J3-8 & AUX-3 (SCK, CLK) +#elif ENABLED(ZONESTAR_LCD) + + #error "CAUTION! ZONESTAR_LCD on REARM requires wiring modifications. NB. ADCs are not 5V tolerant. Comment out this line to continue." + #elif IS_TFTGLCD_PANEL #if ENABLED(TFTGLCD_PANEL_SPI) @@ -336,11 +338,6 @@ #elif HAS_WIRED_LCD - //#define SCK_PIN P0_15 // (52) system defined J3-9 & AUX-3 - //#define MISO_PIN P0_17 // (50) system defined J3-10 & AUX-3 - //#define MOSI_PIN P0_18 // (51) system defined J3-10 & AUX-3 - //#define SS_PIN P1_23 // (53) system defined J3-5 & AUX-3 (Sometimes called SDSS) - #if ENABLED(FYSETC_MINI_12864) #define BEEPER_PIN P1_01 #define BTN_ENC P1_04 @@ -357,17 +354,17 @@ #define LCD_PINS_RS P0_16 // (16) J3-7 & AUX-4 #define LCD_SDSS P1_23 // (53) J3-5 & AUX-3 - #if ENABLED(NEWPANEL) - #if ENABLED(REPRAPWORLD_KEYPAD) - #define SHIFT_OUT P0_18 // (51) (MOSI) J3-10 & AUX-3 - #define SHIFT_CLK P0_15 // (52) (SCK) J3-9 & AUX-3 - #define SHIFT_LD P1_31 // (49) J3-1 & AUX-3 (NOT 5V tolerant) + #if IS_NEWPANEL + #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) J3-1 & AUX-3 (NOT 5V tolerant) #endif #else - //#define SHIFT_CLK P3_26 // (31) J3-2 & AUX-4 - //#define SHIFT_LD P3_25 // (33) J3-4 & AUX-4 - //#define SHIFT_OUT P2_11 // (35) J3-3 & AUX-4 - //#define SHIFT_EN P1_22 // (41) J5-4 & 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_OUT_PIN P2_11 // (35) J3-3 & AUX-4 + //#define SHIFT_EN_PIN P1_22 // (41) J5-4 & AUX-4 #endif #if ANY(VIKI2, miniVIKI) @@ -375,8 +372,8 @@ #define DOGLCD_CS P0_16 // (16) #define DOGLCD_A0 P2_06 // (59) J3-8 & AUX-2 - #define DOGLCD_SCK SCK_PIN - #define DOGLCD_MOSI MOSI_PIN + #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 @@ -416,10 +413,15 @@ #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 - #if ENABLED(ULTIPANEL) + #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 @@ -436,7 +438,7 @@ // // Ethernet pins // -#if DISABLED(ULTIPANEL) +#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 @@ -459,16 +461,16 @@ #define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card #if SD_CONNECTION_IS(LCD) - #define SCK_PIN P0_15 // (52) system defined J3-9 & AUX-3 - #define MISO_PIN P0_17 // (50) system defined J3-10 & AUX-3 - #define MOSI_PIN P0_18 // (51) system defined J3-10 & AUX-3 - #define 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 (Sometimes called SDSS) - CS used by Marlin #elif SD_CONNECTION_IS(ONBOARD) #undef SD_DETECT_PIN - #define SCK_PIN P0_07 - #define MISO_PIN P0_08 - #define MOSI_PIN P0_09 - #define SS_PIN ONBOARD_SD_CS_PIN + #define SD_SCK_PIN P0_07 + #define SD_MISO_PIN P0_08 + #define SD_MOSI_PIN P0_09 + #define SD_SS_PIN ONBOARD_SD_CS_PIN #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "No custom SD drive cable defined for this board." #endif diff --git a/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h b/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h index f9b9db918d55..2972ac756079 100644 --- a/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h +++ b/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h @@ -25,9 +25,7 @@ * Selena Compact pin assignments */ -#if NOT_TARGET(MCU_LPC1768) - #error "Oops! Make sure you have the LPC1768 environment selected in your IDE." -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "Selena Compact" #define BOARD_WEBSITE_URL "github.com/Ales2-k/Selena" @@ -42,11 +40,11 @@ // #define X_MIN_PIN P1_28 #define X_MAX_PIN P1_25 -#define Y_MIN_PIN P2_11 -#define Y_MAX_PIN -1 -#define Z_MIN_PIN P1_27 -#define Z_MAX_PIN -1 -#define Z_PROBE P1_22 +#define Y_STOP_PIN P2_11 +#define Z_STOP_PIN P1_27 +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN P1_22 +#endif // // Steppers @@ -96,18 +94,23 @@ // Display // -#if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) - #define LCD_PINS_RS P0_16 - #define LCD_PINS_ENABLE P0_18 - #define LCD_PINS_D4 P0_15 - #define LCD_PINS_D5 P1_00 - #define LCD_PINS_D6 P1_01 - #define LCD_PINS_D7 P1_04 - #define BEEPER_PIN P1_31 - - #define BTN_EN1 P3_25 - #define BTN_EN2 P3_26 - #define BTN_ENC P1_30 - - #define SD_DETECT_PIN -1 -#endif // REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER +#if IS_RRD_FG_SC + #define LCD_PINS_RS P0_16 + #define LCD_PINS_ENABLE P0_18 + #define LCD_PINS_D4 P0_15 + #define LCD_PINS_D5 P1_00 + #define LCD_PINS_D6 P1_01 + #define LCD_PINS_D7 P1_04 + #define BEEPER_PIN P1_31 + + #define BTN_EN1 P3_25 + #define BTN_EN2 P3_26 + #define BTN_ENC P1_30 + + #define SD_DETECT_PIN -1 + + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif + +#endif // IS_RRD_FG_SC diff --git a/Marlin/src/pins/lpc1769/env_validate.h b/Marlin/src/pins/lpc1769/env_validate.h new file mode 100644 index 000000000000..2e2b63d5203f --- /dev/null +++ b/Marlin/src/pins/lpc1769/env_validate.h @@ -0,0 +1,26 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#if NOT_TARGET(MCU_LPC1769) + #error "Oops! Make sure you have the LPC1769 environment selected in your IDE." +#endif diff --git a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h index adf9085262a0..7ce78ad2832d 100644 --- a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h +++ b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h @@ -25,9 +25,7 @@ * Azteeg X5 GT pin assignments */ -#if NOT_TARGET(MCU_LPC1769) - #error "Oops! Make sure you have the LPC1769 environment selected in your IDE." -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "Azteeg X5 GT" #define BOARD_WEBSITE_URL "tinyurl.com/yx8tdqa3" diff --git a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h index 6331d6aa7c0a..80a91d2cbc4b 100644 --- a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h +++ b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h @@ -24,10 +24,7 @@ /** * Azteeg X5 MINI pin assignments */ - -#if NOT_TARGET(MCU_LPC1769) - #error "Oops! Make sure you have the LPC1769 environment selected in your IDE." -#endif +#include "env_validate.h" #ifndef BOARD_INFO_NAME #define BOARD_INFO_NAME "Azteeg X5 MINI" @@ -38,6 +35,9 @@ // LED // #define LED_PIN P1_18 +#define LED2_PIN P1_20 +#define LED3_PIN P1_19 +#define LED4_PIN P1_21 // // Servos @@ -79,14 +79,13 @@ #define E0_ENABLE_PIN P0_04 // -// DIGIPOT slave addresses +// DIGIPOT slave addresses (7-bit unshifted) // #ifndef DIGIPOT_I2C_ADDRESS_A - #define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for first DIGIPOT + #define DIGIPOT_I2C_ADDRESS_A 0x2C #endif - #ifndef DIGIPOT_I2C_ADDRESS_B - #define DIGIPOT_I2C_ADDRESS_B 0x2E // unshifted slave address for second DIGIPOT + #define DIGIPOT_I2C_ADDRESS_B 0x2E #endif // @@ -144,15 +143,15 @@ #define DOGLCD_A0 P2_06 // (59) J3-8 & AUX-2 - #if ENABLED(REPRAPWORLD_KEYPAD) - #define SHIFT_OUT P0_18 // (51) (MOSI) J3-10 & AUX-3 - #define SHIFT_CLK P0_15 // (52) (SCK) J3-9 & AUX-3 - #define SHIFT_LD P1_31 // (49) not 5V tolerant J3-1 & AUX-3 - #elif DISABLED(NEWPANEL) - //#define SHIFT_OUT P2_11 // (35) J3-3 & AUX-4 - //#define SHIFT_CLK P3_26 // (31) J3-2 & AUX-4 - //#define SHIFT_LD P3_25 // (33) J3-4 & AUX-4 - //#define SHIFT_EN P1_22 // (41) J5-4 & AUX-4 + #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 + #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 #endif #if ANY(VIKI2, miniVIKI) @@ -160,19 +159,24 @@ #define BEEPER_PIN P1_30 // (37) may change if cable changes #define DOGLCD_CS P0_26 // (63) J5-3 & AUX-2 - #define DOGLCD_SCK SCK_PIN - #define DOGLCD_MOSI MOSI_PIN + #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 #else - #if ENABLED(ULTIPANEL) + #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 #endif #define BEEPER_PIN P1_30 // (37) not 5V tolerant #define DOGLCD_CS P0_16 // (16) + + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif + #endif #if ENABLED(MINIPANEL) @@ -197,16 +201,16 @@ #define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card #if SD_CONNECTION_IS(LCD) - #define SCK_PIN P0_15 - #define MISO_PIN P0_17 - #define MOSI_PIN P0_18 - #define SS_PIN P1_23 + #define SD_SCK_PIN P0_15 + #define SD_MISO_PIN P0_17 + #define SD_MOSI_PIN P0_18 + #define SD_SS_PIN P1_23 #elif SD_CONNECTION_IS(ONBOARD) #undef SD_DETECT_PIN - #define SCK_PIN P0_07 - #define MISO_PIN P0_08 - #define MOSI_PIN P0_09 - #define SS_PIN ONBOARD_SD_CS_PIN + #define SD_SCK_PIN P0_07 + #define SD_MISO_PIN P0_08 + #define SD_MOSI_PIN P0_09 + #define SD_SS_PIN ONBOARD_SD_CS_PIN #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "No custom SD drive cable defined for this board." #endif diff --git a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI_WIFI.h b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI_WIFI.h index 99ff0fd25a14..086bacbac0f6 100644 --- a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI_WIFI.h +++ b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI_WIFI.h @@ -22,12 +22,10 @@ #pragma once /** - * Azteeg X5 MINI pin assignments + * Azteeg X5 MINI WIFI pin assignments */ -#if NOT_TARGET(MCU_LPC1769) - #error "Oops! Make sure you have the LPC1769 environment selected in your IDE." -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "Azteeg X5 MINI WIFI" 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 6d6d7557f57d..8c3c2aedaced 100644 --- a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h +++ b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h @@ -21,6 +21,8 @@ */ #pragma once +#include "env_validate.h" + #ifndef BOARD_INFO_NAME #define BOARD_INFO_NAME "BTT SKR E3 Turbo" #endif @@ -70,7 +72,9 @@ #endif // LED driving pin -#define NEOPIXEL_PIN P1_24 +#ifndef NEOPIXEL_PIN + #define NEOPIXEL_PIN P1_24 +#endif // // Power Loss Detection @@ -173,62 +177,85 @@ #define FAN_PIN P2_01 #define FAN1_PIN P2_02 +#ifndef CONTROLLER_FAN_PIN + #define CONTROLLER_FAN_PIN FAN1_PIN +#endif + /** - * _____ - * 5V | 1 2 | GND - * (LCD_EN) P0_18 | 3 4 | P0_17 (LCD_RS) - * (LCD_D4) P0_15 | 5 6 P0_20 (BTN_EN2) - * RESET | 7 8 | P0_19 (BTN_EN1) - * (BTN_ENC) P0_16 | 9 10| P2_08 (BEEPER) - * ----- + * ______ + * 5V | 1 2 | GND + * (LCD_EN) P0_18 | 3 4 | P0_17 (LCD_RS) + * (LCD_D4) P0_15 | 5 6 P0_20 (BTN_EN2) + * RESET | 7 8 | P0_19 (BTN_EN1) + * (BTN_ENC) P0_16 | 9 10 | P2_08 (BEEPER) + * ------ * EXP */ -#define EXPA1_03_PIN P0_18 -#define EXPA1_04_PIN P0_17 -#define EXPA1_05_PIN P0_15 -#define EXPA1_06_PIN P0_20 -#define EXPA1_07_PIN -1 -#define EXPA1_08_PIN P0_19 -#define EXPA1_09_PIN P0_16 -#define EXPA1_10_PIN P2_08 - -#if HAS_WIRED_LCD +#define EXP1_03_PIN P0_18 +#define EXP1_04_PIN P0_17 +#define EXP1_05_PIN P0_15 +#define EXP1_06_PIN P0_20 +#define EXP1_07_PIN -1 +#define EXP1_08_PIN P0_19 +#define EXP1_09_PIN P0_16 +#define EXP1_10_PIN P2_08 + +#if ENABLED(DWIN_CREALITY_LCD) + #error "DWIN_CREALITY_LCD requires a custom cable with TX = P0_15, RX = P0_16. Comment out this line to continue." + + /** + * Ender 3 V2 display SKR E3 Turbo (EXP1) Ender 3 V2 display --> SKR E3 Turbo + * ______ ______ RX 8 --> 5 P0_15 + * 5V | 1 2 | GND 5V | 1 2 | GND TX 7 --> 9 P0_16 + * (BTN_E1) A | 3 4 | B (BTN_E2) (LCD_EN) P0_18 | 3 4 | P0_17 (LCD_RS) BEEPER 5 --> 10 P2_08 + * BEEPER | 5 6 ENT (BTN_ENC) (LCD_D4) P0_15 | 5 6 P0_20 (BTN_EN2) + * (SKR_RX1) TX | 7 8 | RX (SKR_TX1) Reset | 7 8 | P0_19 (BTN_EN1) + * NC | 9 10 | NC (BTN_ENC) P0_16 | 9 10 | P2_08 (BEEPER) + * ------ ------ + */ + + #define BEEPER_PIN EXP1_10_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_04_PIN + #define BTN_ENC EXP1_06_PIN + +#elif HAS_WIRED_LCD #if ENABLED(CR10_STOCKDISPLAY) - #define BEEPER_PIN EXPA1_10_PIN + #define BEEPER_PIN EXP1_10_PIN - #define BTN_EN1 EXPA1_08_PIN - #define BTN_EN2 EXPA1_06_PIN - #define BTN_ENC EXPA1_09_PIN + #define BTN_EN1 EXP1_08_PIN + #define BTN_EN2 EXP1_06_PIN + #define BTN_ENC EXP1_09_PIN - #define LCD_PINS_RS EXPA1_04_PIN - #define LCD_PINS_ENABLE EXPA1_03_PIN - #define LCD_PINS_D4 EXPA1_05_PIN + #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_ENABLE 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! #error "CAUTION! ZONESTAR_LCD requires wiring modifications. See 'pins_BTT_SKR_E3_TURBO.h' for details. Comment out this line to continue." - #define LCD_PINS_RS EXPA1_05_PIN - #define LCD_PINS_ENABLE EXPA1_09_PIN - #define LCD_PINS_D4 EXPA1_04_PIN - #define LCD_PINS_D5 EXPA1_06_PIN - #define LCD_PINS_D6 EXPA1_08_PIN - #define LCD_PINS_D7 EXPA1_10_PIN + #define LCD_PINS_RS EXP1_05_PIN + #define LCD_PINS_ENABLE EXP1_09_PIN + #define LCD_PINS_D4 EXP1_04_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_08_PIN + #define LCD_PINS_D7 EXP1_10_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) - #define BTN_EN1 EXPA1_08_PIN - #define BTN_EN2 EXPA1_06_PIN - #define BTN_ENC EXPA1_09_PIN + #define BTN_EN1 EXP1_08_PIN + #define BTN_EN2 EXP1_06_PIN + #define BTN_ENC EXP1_09_PIN - #define DOGLCD_CS EXPA1_04_PIN - #define DOGLCD_A0 EXPA1_05_PIN - #define DOGLCD_SCK EXPA1_10_PIN - #define DOGLCD_MOSI EXPA1_03_PIN + #define DOGLCD_CS EXP1_04_PIN + #define DOGLCD_A0 EXP1_05_PIN + #define DOGLCD_SCK EXP1_10_PIN + #define DOGLCD_MOSI EXP1_03_PIN #define FORCE_SOFT_SPI #define LCD_BACKLIGHT_PIN -1 @@ -249,12 +276,10 @@ #if SD_CONNECTION_IS(ONBOARD) #define SD_DETECT_PIN P2_00 - #define SCK_PIN P0_07 - #define MISO_PIN P0_08 - #define MOSI_PIN P0_09 - #define SS_PIN P0_06 + #define SD_SCK_PIN P0_07 + #define SD_MISO_PIN P0_08 + #define SD_MOSI_PIN P0_09 + #define SD_SS_PIN P0_06 #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "SD CUSTOM_CABLE is not compatible with SKR E3 Turbo." #endif - -#define ON_BOARD_SPI_DEVICE 1 // SPI1 diff --git a/Marlin/src/pins/lpc1769/pins_BTT_SKR_V1_4_TURBO.h b/Marlin/src/pins/lpc1769/pins_BTT_SKR_V1_4_TURBO.h index a751286e3a81..5af1dfec3f61 100644 --- a/Marlin/src/pins/lpc1769/pins_BTT_SKR_V1_4_TURBO.h +++ b/Marlin/src/pins/lpc1769/pins_BTT_SKR_V1_4_TURBO.h @@ -22,9 +22,9 @@ #pragma once #define BOARD_INFO_NAME "BTT SKR V1.4 TURBO" -#define SKR_HAS_LPC1769 // // Include SKR 1.4 pins // +#define REQUIRE_LPC1769 #include "../lpc1768/pins_BTT_SKR_V1_4.h" diff --git a/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h b/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h index d66ffbe4e5d3..237dfaec36fb 100644 --- a/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h +++ b/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h @@ -25,9 +25,7 @@ * Cohesion3D Mini pin assignments */ -#if NOT_TARGET(MCU_LPC1769) - #error "Oops! Make sure you have the LPC1769 environment selected in your IDE." -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "Cohesion3D Mini" diff --git a/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h b/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h index 66604ef6359f..57b45214535b 100644 --- a/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h +++ b/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h @@ -25,9 +25,7 @@ * Cohesion3D ReMix pin assignments */ -#if NOT_TARGET(MCU_LPC1769) - #error "Oops! Make sure you have the LPC1769 environment selected in your IDE." -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "Cohesion3D ReMix" @@ -233,17 +231,16 @@ #define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card -#if SD_CONNECTION_IS(LCD) - #define SCK_PIN P0_07 // (52) system defined J3-9 & AUX-3 - #define MISO_PIN P0_08 // (50) system defined J3-10 & AUX-3 - #define MOSI_PIN P0_09 // (51) system defined J3-10 & AUX-3 - #define SS_PIN P1_23 // (53) system defined J3-5 & AUX-3 (Sometimes called SDSS) - CS used by Marlin -#elif SD_CONNECTION_IS(ONBOARD) - #undef SD_DETECT_PIN - #define SCK_PIN P0_07 - #define MISO_PIN P0_08 - #define MOSI_PIN P0_09 - #define SS_PIN ONBOARD_SD_CS_PIN +#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 + #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 + #else + #undef SD_DETECT_PIN + #define SD_SS_PIN ONBOARD_SD_CS_PIN + #endif #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "No custom SD drive cable defined for this board." #endif diff --git a/Marlin/src/pins/lpc1769/pins_FLY_CDY.h b/Marlin/src/pins/lpc1769/pins_FLY_CDY.h new file mode 100644 index 000000000000..b90443403ccb --- /dev/null +++ b/Marlin/src/pins/lpc1769/pins_FLY_CDY.h @@ -0,0 +1,179 @@ +/** + * 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 + +#include "env_validate.h" + +#define BOARD_INFO_NAME "FLY-CDY" +#define BOARD_WEBSITE_URL "github.com/FLYmaker/FLY-CDY" + +// +// Servos +// +#define SERVO0_PIN P1_26 + +// +// Limit Switches +// + +#define X_MIN_PIN P1_29 // X- +#define X_MAX_PIN P1_28 // X+ +#define Y_MIN_PIN P1_27 // Y- +#define Y_MAX_PIN P1_25 // Y+ +#define Z_MIN_PIN P1_22 // Z- +#define Z_MAX_PIN P0_27 // Z+ + +// +// Steppers +// +#define X_STEP_PIN P2_00 +#define X_DIR_PIN P1_01 +#define X_ENABLE_PIN P1_00 +#ifndef X_CS_PIN + #define X_CS_PIN P1_04 +#endif + +#define Y_STEP_PIN P2_01 +#define Y_DIR_PIN P1_09 +#define Y_ENABLE_PIN P1_08 +#ifndef Y_CS_PIN + #define Y_CS_PIN P1_10 +#endif + +#define Z_STEP_PIN P2_02 +#define Z_DIR_PIN P1_15 +#define Z_ENABLE_PIN P1_14 +#ifndef Z_CS_PIN + #define Z_CS_PIN P1_16 +#endif + +#define E0_STEP_PIN P2_03 +#define E0_DIR_PIN P4_29 +#define E0_ENABLE_PIN P1_17 +#ifndef E0_CS_PIN + #define E0_CS_PIN P4_28 +#endif + +#define E1_STEP_PIN P2_04 +#define E1_DIR_PIN P2_11 +#define E1_ENABLE_PIN P0_04 +#ifndef E1_CS_PIN + #define E1_CS_PIN P2_12 +#endif + +#define E2_STEP_PIN P2_05 +#define E2_DIR_PIN P0_11 +#define E2_ENABLE_PIN P2_13 +#ifndef E2_CS_PIN + #define E2_CS_PIN P0_10 +#endif + +// +// Software SPI pins for TMC2130 stepper drivers +// +#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 +#endif + +#if HAS_TMC_UART + #define X_SERIAL_TX_PIN P1_04 + #define X_SERIAL_RX_PIN P1_04 + + #define Y_SERIAL_TX_PIN P1_10 + #define Y_SERIAL_RX_PIN P1_10 + + #define Z_SERIAL_TX_PIN P1_16 + #define Z_SERIAL_RX_PIN P1_16 + + #define E0_SERIAL_TX_PIN P4_28 + #define E0_SERIAL_RX_PIN P4_28 + + #define E1_SERIAL_TX_PIN P2_12 + #define E1_SERIAL_RX_PIN P2_12 + + #define E2_SERIAL_TX_PIN P0_10 + #define E2_SERIAL_RX_PIN P0_10 + + // Reduce baud rate to improve software serial reliability + #define TMC_BAUD_RATE 19200 +#endif + +// +// Temperature Sensors +// +#define TEMP_0_PIN P0_26_A3 // (T4) +#define TEMP_1_PIN P0_25_A2 // (T3) +#define TEMP_2_PIN P0_24_A1 // (T2) +#define TEMP_BED_PIN P0_23_A0 // (T1) + +// +// Heaters / Fans +// +#define HEATER_BED_PIN P3_26 +#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 +#endif +#define FAN1_PIN P1_21 +#define FAN2_PIN P1_24 + +// +// LCD / Controller +// +#define BEEPER_PIN P2_07 +#define LCD_PINS_RS P2_10 +#define LCD_PINS_ENABLE P0_22 +#define LCD_PINS_D4 P1_19 +#define LCD_PINS_D5 P2_08 +#define LCD_PINS_D6 P1_30 +#define LCD_PINS_D7 P1_31 +#define BTN_EN1 P0_00 +#define BTN_EN2 P0_01 +#define BTN_ENC P0_28 + +#ifndef SDCARD_CONNECTION + #define SDCARD_CONNECTION ONBOARD +#endif + +#if SD_CONNECTION_IS(ONBOARD) + #define SD_SS_PIN P0_06 + #define SD_SCK_PIN P0_07 + #define SD_MISO_PIN P0_08 + #define SD_MOSI_PIN P0_09 + #define SD_DETECT_PIN P0_05 +#elif 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 P0_16 + #define SD_DETECT_PIN P2_06 +#endif diff --git a/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h b/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h index d67549997be5..ddfee63cd080 100644 --- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h +++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h @@ -28,14 +28,10 @@ * https://github.com/makerbase-mks/MKS-SGen/blob/master/Hardware/MKS%20SGEN%20V1.0_001/MKS%20SGEN%20V1.0_001%20PIN.pdf */ -#if NOT_TARGET(MCU_LPC1769) - #error "Oops! Make sure you have the LPC1769 environment selected in your IDE." -#endif - #define BOARD_INFO_NAME "MKS SGen" #define BOARD_WEBSITE_URL "github.com/makerbase-mks/MKS-SGEN" -#define MKS_HAS_LPC1769 +#define REQUIRE_LPC1769 #include "../lpc1768/pins_MKS_SBASE.h" #if 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 62660935f5bd..4020ac23c637 100644 --- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h +++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h @@ -25,9 +25,7 @@ * MKS SGen pin assignments */ -#if NOT_TARGET(MCU_LPC1769) - #error "Oops! Make sure you have the LPC1769 environment selected in your IDE." -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "MKS SGEN_L V2" #define BOARD_WEBSITE_URL "github.com/makerbase-mks" @@ -62,7 +60,7 @@ // #if X_STALL_SENSITIVITY #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_DIR < 0 + #if X_HOME_TO_MIN #define X_MAX_PIN P1_28 // X+ #else #define X_MIN_PIN P1_28 // X+ @@ -74,7 +72,7 @@ #if Y_STALL_SENSITIVITY #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_DIR < 0 + #if Y_HOME_TO_MIN #define Y_MAX_PIN P1_26 // Y+ #else #define Y_MIN_PIN P1_26 // Y+ @@ -86,7 +84,7 @@ #if Z_STALL_SENSITIVITY #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_DIR < 0 + #if Z_HOME_TO_MIN #define Z_MAX_PIN P1_24 // Z+ #else #define Z_MIN_PIN P1_24 // Z+ @@ -227,15 +225,44 @@ // Misc. Functions // #define LED_PIN P1_18 // Used as a status indicator -#define LED2_PIN P1_19 -#define LED3_PIN P1_20 -#define LED4_PIN P1_21 + +// +// Power Supply Control +// +#if ENABLED(PSU_CONTROL) // MKSPWC + #ifndef PS_ON_PIN + #define PS_ON_PIN P2_00 // Suggestion (SERVO) + #endif + #ifndef KILL_PIN + #define KILL_PIN P1_24 // Suggestion (Z+) + #define KILL_PIN_STATE HIGH + #endif +#endif + +// +// RGB LED +// +#if ENABLED(RGB_LED) + #ifndef RGB_LED_R_PIN + #define RGB_LED_R_PIN P1_19 + #endif + #ifndef RGB_LED_G_PIN + #define RGB_LED_G_PIN P1_20 + #endif + #ifndef RGB_LED_B_PIN + #define RGB_LED_B_PIN P1_21 + #endif +#else + #define LED2_PIN P1_19 // Initialized by HAL/LPC1768/main.cpp + #define LED3_PIN P1_20 + #define LED4_PIN P1_21 +#endif /** * _____ _____ - * (BEEPER) 1.31 | · · | 1.30 (BTN_ENC) (MISO) 0.8 | · · | 0.7 (SD_SCK) - * (LCD_EN) 0.18 | · · | 0.16 (LCD_RS) (BTN_EN1) 3.25 | · · | 0.28 (SD_CS2) - * (LCD_D4) 0.15 | · ·| 0.17 (LCD_D5) (BTN_EN2) 3.26 | · ·| 0.9 (SD_MOSI) + * (BEEPER) 1.31 | · · | 1.30 (BTN_ENC) (MISO) 0.8 | · · | 0.7 (SD_SCK) + * (LCD_EN) 0.18 | · · | 0.16 (LCD_RS) (BTN_EN1) 3.25 | · · | 0.28 (SD_CS2) + * (LCD_D4) 0.15 | · · | 0.17 (LCD_D5) (BTN_EN2) 3.26 | · · | 0.9 (SD_MOSI) * (LCD_D6) 1.0 | · · | 1.22 (LCD_D7) (SD_DETECT) 0.27 | · · | RST * GND | · · | 5V GND | · · | NC * ----- ----- @@ -283,6 +310,32 @@ #define LCD_PINS_D7 P1_22 #define KILL_PIN -1 // NC + #elif HAS_SPI_TFT // Config for Classic UI (emulated DOGM) and Color UI + #define TFT_CS_PIN P1_00 + #define TFT_A0_PIN P1_22 + #define TFT_DC_PIN P1_22 + #define TFT_MISO_PIN P0_08 + #define TFT_BACKLIGHT_PIN P0_18 + #define TFT_RESET_PIN P0_16 + + #define LCD_USE_DMA_SPI + + #define TOUCH_INT_PIN P0_17 + #define TOUCH_CS_PIN P0_15 + #define TOUCH_BUTTONS_HW_SPI + #define TOUCH_BUTTONS_HW_SPI_DEVICE 2 + + // Disable any LCD related PINs config + #define LCD_PINS_ENABLE -1 + #define LCD_PINS_RS -1 + + #ifndef TFT_BUFFER_SIZE + #define TFT_BUFFER_SIZE 1200 + #endif + #ifndef TFT_QUEUE_SIZE + #define TFT_QUEUE_SIZE 6144 + #endif + #else // !MKS_12864OLED_SSD1306 #define LCD_PINS_RS P0_16 @@ -295,7 +348,7 @@ #define DOGLCD_CS P0_18 #define DOGLCD_A0 P0_16 #define DOGLCD_SCK P0_07 - #define DOGLCD_MOSI P1_20 + #define DOGLCD_MOSI P0_09 #define LCD_BACKLIGHT_PIN -1 @@ -325,10 +378,15 @@ #define DOGLCD_A0 P1_00 #endif - #if ENABLED(ULTIPANEL) + #if IS_ULTIPANEL #define LCD_PINS_D5 P0_17 #define LCD_PINS_D6 P1_00 #define LCD_PINS_D7 P1_22 + + #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 @@ -347,13 +405,13 @@ #if SD_CONNECTION_IS(LCD) || SD_CONNECTION_IS(ONBOARD) #define SD_DETECT_PIN P0_27 - #define SCK_PIN P0_07 - #define MISO_PIN P0_08 - #define MOSI_PIN P0_09 + #define SD_SCK_PIN P0_07 + #define SD_MISO_PIN P0_08 + #define SD_MOSI_PIN P0_09 #if SD_CONNECTION_IS(ONBOARD) - #define SS_PIN ONBOARD_SD_CS_PIN + #define SD_SS_PIN ONBOARD_SD_CS_PIN #else - #define SS_PIN P0_28 + #define SD_SS_PIN P0_28 #endif #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "No custom SD drive cable defined for this board." diff --git a/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h b/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h index f2811b14abdc..f7bc9602d793 100644 --- a/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h +++ b/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h @@ -25,9 +25,7 @@ * Smoothieboard pin assignments */ -#if NOT_TARGET(MCU_LPC1769) - #error "Oops! Make sure you have the LPC1769 environment selected in your IDE." -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "Smoothieboard" #define BOARD_WEBSITE_URL "smoothieware.org/smoothieboard" @@ -124,10 +122,10 @@ */ #define SD_DETECT_PIN P0_27 // EXP2 Pin 7 (SD_CD, SD_DET) - #define MISO_PIN P0_08 // EXP2 Pin 1 (PB3, SD_MISO) - #define SCK_PIN P0_07 // EXP2 Pin 2 (SD_SCK) - #define SS_PIN P0_28 // EXP2 Pin 4 (SD_CSEL, SD_CS) - #define MOSI_PIN P0_09 // EXP2 Pin 6 (PB2, SD_MOSI) + #define SD_MISO_PIN P0_08 // EXP2 Pin 1 (PB3, SD_MISO) + #define SD_SCK_PIN P0_07 // EXP2 Pin 2 (SD_SCK) + #define SD_SS_PIN P0_28 // EXP2 Pin 4 (SD_CSEL, SD_CS) + #define SD_MOSI_PIN P0_09 // EXP2 Pin 6 (PB2, SD_MOSI) /** * The Smoothieboard supports the REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER with either @@ -138,7 +136,7 @@ * http://chibidibidiwah.wdfiles.com/local--files/panel/smoothieboard2sd.jpg * http://smoothieware.org/panel */ - #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #if IS_RRD_FG_SC // EXP1 Pins #define BEEPER_PIN P1_31 // EXP1 Pin 1 #define BTN_ENC P1_30 // EXP1 Pin 2 @@ -169,7 +167,7 @@ * Set from 0 - 127 with stop bit. * (Ex. 3F << 1 | 1) */ -#define DIGIPOTS_I2C_SCL P0_0 +#define DIGIPOTS_I2C_SCL P0_00 #define DIGIPOTS_I2C_SDA_X P0_04 #define DIGIPOTS_I2C_SDA_Y P0_10 #define DIGIPOTS_I2C_SDA_Z P0_19 diff --git a/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h b/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h index a0174f260298..4d725bc7d16a 100644 --- a/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h +++ b/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h @@ -25,9 +25,7 @@ * TH3D EZBoard pin assignments */ -#if NOT_TARGET(MCU_LPC1769) - #error "Oops! Make sure you have the LPC1769 environment selected in your IDE." -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "TH3D EZBoard" #define BOARD_WEBSITE_URL "th3dstudio.com" @@ -141,11 +139,11 @@ #define SDCARD_CONNECTION ONBOARD -#define SCK_PIN P0_07 -#define MISO_PIN P0_08 -#define MOSI_PIN P0_09 +#define SD_SCK_PIN P0_07 +#define SD_MISO_PIN P0_08 +#define SD_MOSI_PIN P0_09 #define ONBOARD_SD_CS_PIN P0_06 -#define SS_PIN ONBOARD_SD_CS_PIN +#define SD_SS_PIN ONBOARD_SD_CS_PIN // // LCD / Controller @@ -155,7 +153,7 @@ * _____ * 5V | · · | GND * (LCD_EN) P0_18 | · · | P0_16 (LCD_RS) - * (LCD_D4) P0_15 | · · | P3_25 (BTN_EN2) + * (LCD_D4) P0_15 | · · P3_25 (BTN_EN2) * (RESET) P2_11 | · · | P3_26 (BTN_EN1) * (BTN_ENC) P1_30 | · · | P1_31 (BEEPER) * ----- diff --git a/Marlin/src/pins/mega/env_validate.h b/Marlin/src/pins/mega/env_validate.h new file mode 100644 index 000000000000..97c52d4e5e05 --- /dev/null +++ b/Marlin/src/pins/mega/env_validate.h @@ -0,0 +1,32 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#if NOT_TARGET(__AVR_ATmega2560__) + #if DISABLED(ALLOW_MEGA1280) + #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" + #elif NOT_TARGET(__AVR_ATmega1280__) + #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560 or 1280' in 'Tools > Board.'" + #endif +#endif + +#undef ALLOW_MEGA1280 diff --git a/Marlin/src/pins/mega/pins_CHEAPTRONIC.h b/Marlin/src/pins/mega/pins_CHEAPTRONIC.h index 98427d9e592a..8bcb263bc1fd 100644 --- a/Marlin/src/pins/mega/pins_CHEAPTRONIC.h +++ b/Marlin/src/pins/mega/pins_CHEAPTRONIC.h @@ -25,9 +25,7 @@ * Cheaptronic v1.0 pin assignments */ -#if NOT_TARGET(__AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "Cheaptronic v1.0" // diff --git a/Marlin/src/pins/mega/pins_CHEAPTRONICv2.h b/Marlin/src/pins/mega/pins_CHEAPTRONICv2.h index 3a84f4395f3a..01438975b979 100644 --- a/Marlin/src/pins/mega/pins_CHEAPTRONICv2.h +++ b/Marlin/src/pins/mega/pins_CHEAPTRONICv2.h @@ -27,9 +27,7 @@ * www.reprapobchod.cz */ -#if NOT_TARGET(__AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "Cheaptronic v2.0" @@ -119,6 +117,10 @@ #define LCD_PINS_D6 41 #define LCD_PINS_D7 40 +#if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder +#endif + // // Beeper, SD Card, Encoder // @@ -129,7 +131,7 @@ #define SD_DETECT_PIN 49 #endif -#if ENABLED(NEWPANEL) +#if IS_NEWPANEL #define BTN_EN1 11 #define BTN_EN2 12 #define BTN_ENC 43 diff --git a/Marlin/src/pins/mega/pins_CNCONTROLS_11.h b/Marlin/src/pins/mega/pins_CNCONTROLS_11.h index 675d4b7262f8..6f9e5e8e6c47 100644 --- a/Marlin/src/pins/mega/pins_CNCONTROLS_11.h +++ b/Marlin/src/pins/mega/pins_CNCONTROLS_11.h @@ -25,9 +25,8 @@ * CartesioV11 pin assignments */ -#if NOT_TARGET(__AVR_ATmega1280__, __AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#endif +#define ALLOW_MEGA1280 +#include "env_validate.h" #define BOARD_INFO_NAME "CN Controls V11" @@ -141,7 +140,7 @@ // Pins for DOGM SPI LCD Support #define DOGLCD_A0 26 #define DOGLCD_CS 24 -#define DOGLCD_MOSI -1 +#define DOGLCD_MOSI -1 // Prevent auto-define by Conditionals_post.h #define DOGLCD_SCK -1 #define BTN_EN1 23 @@ -149,9 +148,9 @@ #define BTN_ENC 27 // Hardware buttons for manual movement of XYZ -#define SHIFT_OUT 19 -#define SHIFT_LD 18 -#define SHIFT_CLK 17 +#define SHIFT_OUT_PIN 19 +#define SHIFT_LD_PIN 18 +#define SHIFT_CLK_PIN 17 //#define UI1 31 //#define UI2 22 diff --git a/Marlin/src/pins/mega/pins_CNCONTROLS_12.h b/Marlin/src/pins/mega/pins_CNCONTROLS_12.h index 35426a453139..f1200e09018a 100644 --- a/Marlin/src/pins/mega/pins_CNCONTROLS_12.h +++ b/Marlin/src/pins/mega/pins_CNCONTROLS_12.h @@ -25,9 +25,8 @@ * CartesioV12 pin assignments */ -#if NOT_TARGET(__AVR_ATmega1280__, __AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#endif +#define ALLOW_MEGA1280 +#include "env_validate.h" #define BOARD_INFO_NAME "CN Controls V12" @@ -156,9 +155,9 @@ #define BTN_ENC 38 // Hardware buttons for manual movement of XYZ -#define SHIFT_OUT 42 -#define SHIFT_LD 41 -#define SHIFT_CLK 40 +#define SHIFT_OUT_PIN 42 +#define SHIFT_LD_PIN 41 +#define SHIFT_CLK_PIN 40 //#define UI1 43 //#define UI2 37 diff --git a/Marlin/src/pins/mega/pins_CNCONTROLS_15.h b/Marlin/src/pins/mega/pins_CNCONTROLS_15.h index 8bafbdf00058..6de3b7172eb0 100644 --- a/Marlin/src/pins/mega/pins_CNCONTROLS_15.h +++ b/Marlin/src/pins/mega/pins_CNCONTROLS_15.h @@ -25,9 +25,8 @@ * CNControls V15 for HMS434 pin assignments */ -#if NOT_TARGET(__AVR_ATmega1280__, __AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#endif +#define ALLOW_MEGA1280 +#include "env_validate.h" #define BOARD_INFO_NAME "CN Controls V15" diff --git a/Marlin/src/pins/mega/pins_EINSTART-S.h b/Marlin/src/pins/mega/pins_EINSTART-S.h index 40d65c353e8c..d42efe73617f 100644 --- a/Marlin/src/pins/mega/pins_EINSTART-S.h +++ b/Marlin/src/pins/mega/pins_EINSTART-S.h @@ -26,9 +26,8 @@ * PCB Silkscreen: 3DPrinterCon_v3.5 */ -#if NOT_TARGET(__AVR_ATmega1280__, __AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#endif +#define ALLOW_MEGA1280 +#include "env_validate.h" #define BOARD_INFO_NAME "Einstart-S" diff --git a/Marlin/src/pins/mega/pins_ELEFU_3.h b/Marlin/src/pins/mega/pins_ELEFU_3.h index af93c408a25a..f5e146cff99c 100644 --- a/Marlin/src/pins/mega/pins_ELEFU_3.h +++ b/Marlin/src/pins/mega/pins_ELEFU_3.h @@ -25,9 +25,7 @@ * Elefu RA Board Pin Assignments */ -#if NOT_TARGET(__AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "Elefu Ra v3" diff --git a/Marlin/src/pins/mega/pins_GT2560_REV_A.h b/Marlin/src/pins/mega/pins_GT2560_REV_A.h index 2fe9a43ba136..1adf8d3079f4 100644 --- a/Marlin/src/pins/mega/pins_GT2560_REV_A.h +++ b/Marlin/src/pins/mega/pins_GT2560_REV_A.h @@ -27,9 +27,8 @@ * Richard Smith */ -#if NOT_TARGET(__AVR_ATmega1280__, __AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#endif +#define ALLOW_MEGA1280 +#include "env_validate.h" #ifndef BOARD_INFO_NAME #define BOARD_INFO_NAME "GT2560 Rev.A" @@ -48,10 +47,11 @@ #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 - #define Z_MAX_PIN -1 #else #define Z_MAX_PIN 32 #endif @@ -109,13 +109,27 @@ #define BEEPER_PIN 18 - #if ENABLED(NEWPANEL) + #if IS_NEWPANEL #if ENABLED(MKS_MINI_12864) #define DOGLCD_A0 5 #define DOGLCD_CS 21 #define BTN_EN1 40 #define BTN_EN2 42 + #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 NEOPIXEL_PIN 21 + #define BTN_EN1 42 + #define BTN_EN2 40 + + #define LCD_RESET_PIN 16 + + #define DEFAULT_LCD_CONTRAST 220 + + #define LCD_BACKLIGHT_PIN -1 #else #define LCD_PINS_RS 20 #define LCD_PINS_ENABLE 17 @@ -130,12 +144,12 @@ #define BTN_ENC 19 #define SD_DETECT_PIN 38 - #else // !NEWPANEL + #else // !IS_NEWPANEL - #define SHIFT_CLK 38 - #define SHIFT_LD 42 - #define SHIFT_OUT 40 - #define SHIFT_EN 17 + #define SHIFT_CLK_PIN 38 + #define SHIFT_LD_PIN 42 + #define SHIFT_OUT_PIN 40 + #define SHIFT_EN_PIN 17 #define LCD_PINS_RS 16 #define LCD_PINS_ENABLE 5 @@ -144,8 +158,12 @@ #define LCD_PINS_D6 20 #define LCD_PINS_D7 19 + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif + #define SD_DETECT_PIN -1 - #endif // !NEWPANEL + #endif // !IS_NEWPANEL #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/mega/pins_GT2560_REV_B.h b/Marlin/src/pins/mega/pins_GT2560_REV_B.h new file mode 100644 index 000000000000..be71ec4902dc --- /dev/null +++ b/Marlin/src/pins/mega/pins_GT2560_REV_B.h @@ -0,0 +1,30 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * Geeetech GT2560 Rev B Pins + */ + +#define BOARD_INFO_NAME "GT2560 Rev B" + +#include "pins_GT2560_V3.h" diff --git a/Marlin/src/pins/mega/pins_GT2560_V3.h b/Marlin/src/pins/mega/pins_GT2560_V3.h index d71a19541914..46b4ebf4287e 100644 --- a/Marlin/src/pins/mega/pins_GT2560_V3.h +++ b/Marlin/src/pins/mega/pins_GT2560_V3.h @@ -22,21 +22,22 @@ #pragma once /** - * GT2560 RevB + GT2560 V3.0 + GT2560 V3.1 + GT2560 V4.0 pin assignment + * Geeetech GT2560 3.0/3.1 pin assignments + * + * Also GT2560 RevB and GT2560 4.0/4.1 */ -#if NOT_TARGET(__AVR_ATmega1280__, __AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#endif +#define ALLOW_MEGA1280 +#include "env_validate.h" #ifndef BOARD_INFO_NAME - #define BOARD_INFO_NAME "GT2560 V3.0" + #define BOARD_INFO_NAME "GT2560 3.x" #endif // // Servos // -#define SERVO0_PIN 11 //13 untested 3Dtouch +#define SERVO0_PIN 11 // 13 untested 3Dtouch // // Limit Switches @@ -82,6 +83,9 @@ #ifndef FIL_RUNOUT2_PIN #define FIL_RUNOUT2_PIN 67 #endif +#ifndef FIL_RUNOUT3_PIN + #define FIL_RUNOUT3_PIN 54 +#endif // // Power Recovery @@ -142,7 +146,10 @@ #define SDSS 53 #define LED_PIN 13 // Use 6 (case light) for external LED. 13 is internal (yellow) LED. #define PS_ON_PIN 12 -#define SUICIDE_PIN 54 // This pin must be enabled at boot to keep power flowing + +#if NUM_RUNOUT_SENSORS < 3 + #define SUICIDE_PIN 54 // This pin must be enabled at boot to keep power flowing +#endif #ifndef CASE_LIGHT_PIN #define CASE_LIGHT_PIN 6 // 21 @@ -153,26 +160,51 @@ // #define BEEPER_PIN 18 -#ifndef LCD_PINS_RS - #define LCD_PINS_RS 20 -#endif -#ifndef LCD_PINS_ENABLE - #define LCD_PINS_ENABLE 17 -#endif -#ifndef LCD_PINS_D4 - #define LCD_PINS_D4 16 -#endif -#ifndef LCD_PINS_D5 - #define LCD_PINS_D5 21 -#endif -#ifndef LCD_PINS_D6 - #define LCD_PINS_D6 5 -#endif -#ifndef LCD_PINS_D7 - #define LCD_PINS_D7 36 +#if ENABLED(YHCB2004) + #ifndef YHCB2004_CLK + #define YHCB2004_CLK 5 + #define DIO52 YHCB2004_CLK + #endif + #ifndef YHCB2004_MOSI + #define YHCB2004_MOSI 21 + #define DIO50 YHCB2004_MOSI + #endif + #ifndef YHCB2004_MISO + #define YHCB2004_MISO 36 + #define DIO51 YHCB2004_MISO + #endif +#elif HAS_WIRED_LCD + #ifndef LCD_PINS_RS + #define LCD_PINS_RS 20 + #endif + #ifndef LCD_PINS_ENABLE + #define LCD_PINS_ENABLE 17 + #endif + #ifndef LCD_PINS_D4 + #define LCD_PINS_D4 16 + #endif + #ifndef LCD_PINS_D5 + #define LCD_PINS_D5 21 + #endif + #ifndef LCD_PINS_D6 + #define LCD_PINS_D6 5 + #endif + #ifndef LCD_PINS_D7 + #define LCD_PINS_D7 36 + #endif #endif -#if ENABLED(NEWPANEL) +#if ENABLED(YHCB2004) + #ifndef BTN_EN1 + #define BTN_EN1 16 + #endif + #ifndef BTN_EN2 + #define BTN_EN2 17 + #endif + #ifndef BTN_ENC + #define BTN_ENC 19 + #endif +#elif IS_NEWPANEL #ifndef BTN_EN1 #define BTN_EN1 42 #endif diff --git a/Marlin/src/pins/mega/pins_GT2560_V3_A20.h b/Marlin/src/pins/mega/pins_GT2560_V3_A20.h index e1956488c6c7..986dd1cb04bb 100644 --- a/Marlin/src/pins/mega/pins_GT2560_V3_A20.h +++ b/Marlin/src/pins/mega/pins_GT2560_V3_A20.h @@ -22,20 +22,20 @@ #pragma once /** - * Geeetech A20M pin assignment + * Geeetech A20M board pin assignments */ -#define LCD_PINS_RS 5 -#define LCD_PINS_ENABLE 36 -#define LCD_PINS_D4 21 -#define LCD_PINS_D7 6 +#define LCD_PINS_RS 5 +#define LCD_PINS_ENABLE 36 +#define LCD_PINS_D4 21 +#define LCD_PINS_D7 6 -#define SPEAKER // The speaker can produce tones +#define SPEAKER // The speaker can produce tones -#if ENABLED(NEWPANEL) - #define BTN_EN1 16 - #define BTN_EN2 17 - #define BTN_ENC 19 +#if IS_NEWPANEL + #define BTN_EN1 16 + #define BTN_EN2 17 + #define BTN_ENC 19 #endif #include "pins_GT2560_V3.h" diff --git a/Marlin/src/pins/mega/pins_GT2560_V3_MC2.h b/Marlin/src/pins/mega/pins_GT2560_V3_MC2.h index 26721df3641e..6b22b4139b6d 100644 --- a/Marlin/src/pins/mega/pins_GT2560_V3_MC2.h +++ b/Marlin/src/pins/mega/pins_GT2560_V3_MC2.h @@ -21,9 +21,9 @@ */ #pragma once -/***************************************************************** - * GT2560 V3.0 pin assignment (for Mecreator 2) - *****************************************************************/ +/** + * Geeetech GT2560 V 3.0 board pin assignments (for Mecreator 2) + */ #define BOARD_INFO_NAME "GT2560 V3.0 (MC2)" diff --git a/Marlin/src/pins/mega/pins_GT2560_V4.h b/Marlin/src/pins/mega/pins_GT2560_V4.h new file mode 100644 index 000000000000..6ac07b70bfce --- /dev/null +++ b/Marlin/src/pins/mega/pins_GT2560_V4.h @@ -0,0 +1,30 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * Geeetech GT2560 V4.X Pins + */ + +#define BOARD_INFO_NAME "GT2560 4.x" + +#include "pins_GT2560_V3.h" diff --git a/Marlin/src/pins/mega/pins_HJC2560C_REV2.h b/Marlin/src/pins/mega/pins_HJC2560C_REV2.h index e30a65b90e1b..27ec9988918d 100644 --- a/Marlin/src/pins/mega/pins_HJC2560C_REV2.h +++ b/Marlin/src/pins/mega/pins_HJC2560C_REV2.h @@ -22,12 +22,10 @@ #pragma once /** - * HJC2560-C Rev2.x pin assignments + * Geeetech HJC2560-C Rev 2.x board pin assignments */ -#if NOT_TARGET(__AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#endif +#include "env_validate.h" #define DEFAULT_MACHINE_NAME "ADIMLab Gantry v2" #define BOARD_INFO_NAME "HJC2560-C" @@ -127,7 +125,7 @@ #define BEEPER_PIN 18 - #if ENABLED(NEWPANEL) + #if IS_NEWPANEL #define LCD_PINS_RS 20 // LCD_CS #define LCD_PINS_ENABLE 15 // LCD_SDA @@ -156,10 +154,10 @@ #else // Buttons attached to a shift register - #define SHIFT_CLK 38 - #define SHIFT_LD 42 - #define SHIFT_OUT 40 - #define SHIFT_EN 17 + #define SHIFT_CLK_PIN 38 + #define SHIFT_LD_PIN 42 + #define SHIFT_OUT_PIN 40 + #define SHIFT_EN_PIN 17 #define LCD_PINS_RS 16 #define LCD_PINS_ENABLE 5 @@ -168,6 +166,6 @@ #define LCD_PINS_D6 20 #define LCD_PINS_D7 19 - #endif // !NEWPANEL + #endif // !IS_NEWPANEL #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/mega/pins_INTAMSYS40.h b/Marlin/src/pins/mega/pins_INTAMSYS40.h index be5f461dda38..2e2a9b85db14 100644 --- a/Marlin/src/pins/mega/pins_INTAMSYS40.h +++ b/Marlin/src/pins/mega/pins_INTAMSYS40.h @@ -27,9 +27,7 @@ * 2208 version exists and may or may not work */ -#if NOT_TARGET(__AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "Intamsys 4.0" diff --git a/Marlin/src/pins/mega/pins_LEAPFROG.h b/Marlin/src/pins/mega/pins_LEAPFROG.h index 9e6802b24bd7..4700fd6729bd 100644 --- a/Marlin/src/pins/mega/pins_LEAPFROG.h +++ b/Marlin/src/pins/mega/pins_LEAPFROG.h @@ -25,9 +25,8 @@ * Leapfrog Driver board pin assignments */ -#if NOT_TARGET(__AVR_ATmega1280__, __AVR_ATmega2560__) - #error "Oops! Select 'Mega 1280' or 'Mega 2560' in 'Tools > Board.'" -#endif +#define ALLOW_MEGA1280 +#include "env_validate.h" #define BOARD_INFO_NAME "Leapfrog" diff --git a/Marlin/src/pins/mega/pins_LEAPFROG_XEED2015.h b/Marlin/src/pins/mega/pins_LEAPFROG_XEED2015.h index 9c316aa75951..af5cfd6a2eef 100644 --- a/Marlin/src/pins/mega/pins_LEAPFROG_XEED2015.h +++ b/Marlin/src/pins/mega/pins_LEAPFROG_XEED2015.h @@ -29,9 +29,7 @@ * printer models. As such this file is currently specific to the Xeed. */ -#if NOT_TARGET(__AVR_ATmega2560__) - #error "Oops! Select 'Mega 2560' in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "Leapfrog Xeed 2015" diff --git a/Marlin/src/pins/mega/pins_MALYAN_M180.h b/Marlin/src/pins/mega/pins_MALYAN_M180.h new file mode 100644 index 000000000000..19095a53799f --- /dev/null +++ b/Marlin/src/pins/mega/pins_MALYAN_M180.h @@ -0,0 +1,100 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * Malyan M180 pin assignments + * Contributed by Timo Birnschein (timo.birnschein@microforge.de) + */ + +#include "env_validate.h" + +#define BOARD_INFO_NAME "Malyan M180 v.2" +// +// Limit Switches +// +#define X_STOP_PIN 48 +#define Y_STOP_PIN 46 +#define Z_STOP_PIN 42 + +// +// Z Probe (when not Z_MIN_PIN) +// +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN -1 +#endif + +// +// Steppers +// +#define X_STEP_PIN 55 +#define X_DIR_PIN 54 +#define X_ENABLE_PIN 56 + +#define Y_STEP_PIN 59 +#define Y_DIR_PIN 58 +#define Y_ENABLE_PIN 60 + +#define Z_STEP_PIN 63 +#define Z_DIR_PIN 62 +#define Z_ENABLE_PIN 64 + +#define E0_STEP_PIN 25 +#define E0_DIR_PIN 24 +#define E0_ENABLE_PIN 26 + +#define E1_STEP_PIN 29 +#define E1_DIR_PIN 28 +#define E1_ENABLE_PIN 39 + +// +// Temperature Sensors +// +#define TEMP_BED_PIN 15 // Analog Input + +// Extruder thermocouples 0 and 1 are read out by two separate ICs using +// SPI for MAX Thermocouple +// Uses a separate SPI bus +#define TEMP_0_CS_PIN 5 // E3 - CS0 +#define TEMP_0_SCK_PIN 78 // E2 - SCK +#define TEMP_0_MISO_PIN 3 // E5 - MISO +//#define TEMP_0_MOSI_PIN ... // For MAX31865 + +#define TEMP_1_CS_PIN 2 // E4 - CS1 +#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 +// +#define HEATER_0_PIN 6 +#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. +#endif + +#ifndef FAN_PIN1 + #define FAN_PIN1 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 938ad82eff03..69c60b29ec54 100644 --- a/Marlin/src/pins/mega/pins_MEGACONTROLLER.h +++ b/Marlin/src/pins/mega/pins_MEGACONTROLLER.h @@ -25,12 +25,12 @@ * Mega controller pin assignments */ -#if NOT_TARGET(__AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#elif HOTENDS > 2 || E_STEPPERS > 2 +#if HOTENDS > 2 || E_STEPPERS > 2 #error "Mega Controller supports up to 2 hotends / E-steppers. Comment out this line to continue." #endif +#include "env_validate.h" + #define BOARD_INFO_NAME "Mega Controller" // diff --git a/Marlin/src/pins/mega/pins_MEGATRONICS.h b/Marlin/src/pins/mega/pins_MEGATRONICS.h index 1c37b21ab707..0308175b2a3f 100644 --- a/Marlin/src/pins/mega/pins_MEGATRONICS.h +++ b/Marlin/src/pins/mega/pins_MEGATRONICS.h @@ -25,9 +25,7 @@ * MegaTronics pin assignments */ -#if NOT_TARGET(__AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "Megatronics" // @@ -108,7 +106,7 @@ // #define BEEPER_PIN 33 -#if BOTH(ULTRA_LCD, NEWPANEL) +#if IS_ULTRA_LCD && IS_NEWPANEL #define LCD_PINS_RS 16 #define LCD_PINS_ENABLE 17 @@ -124,7 +122,7 @@ #define SD_DETECT_PIN -1 // RAMPS doesn't use this -#endif // ULTRA_LCD && NEWPANEL +#endif // IS_ULTRA_LCD && IS_NEWPANEL // // M3/M4/M5 - Spindle/Laser Control diff --git a/Marlin/src/pins/mega/pins_MEGATRONICS_2.h b/Marlin/src/pins/mega/pins_MEGATRONICS_2.h index ff7cf1571465..e52703591063 100644 --- a/Marlin/src/pins/mega/pins_MEGATRONICS_2.h +++ b/Marlin/src/pins/mega/pins_MEGATRONICS_2.h @@ -25,9 +25,7 @@ * MegaTronics v2.0 pin assignments */ -#if NOT_TARGET(__AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "Megatronics v2.0" // @@ -139,17 +137,17 @@ #define LCD_PINS_D6 32 #define LCD_PINS_D7 33 - #if ENABLED(NEWPANEL) + #if IS_NEWPANEL // Buttons are directly attached using keypad #define BTN_EN1 61 #define BTN_EN2 59 #define BTN_ENC 43 #else // Buttons attached to shift register of reprapworld keypad v1.1 - #define SHIFT_CLK 63 - #define SHIFT_LD 42 - #define SHIFT_OUT 17 - #define SHIFT_EN 17 + #define SHIFT_CLK_PIN 63 + #define SHIFT_LD_PIN 42 + #define SHIFT_OUT_PIN 17 + #define SHIFT_EN_PIN 17 #endif #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/mega/pins_MEGATRONICS_3.h b/Marlin/src/pins/mega/pins_MEGATRONICS_3.h index 45ebd163a79f..5dea438d704a 100644 --- a/Marlin/src/pins/mega/pins_MEGATRONICS_3.h +++ b/Marlin/src/pins/mega/pins_MEGATRONICS_3.h @@ -25,9 +25,7 @@ * MegaTronics v3.0 / v3.1 / v3.2 pin assignments */ -#if NOT_TARGET(__AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#endif +#include "env_validate.h" #if MB(MEGATRONICS_32) #define BOARD_INFO_NAME "Megatronics v3.2" @@ -162,10 +160,10 @@ #define LCD_PINS_D6 39 #define LCD_PINS_D7 15 - #define SHIFT_CLK 43 - #define SHIFT_LD 35 - #define SHIFT_OUT 34 - #define SHIFT_EN 44 + #define SHIFT_CLK_PIN 43 + #define SHIFT_LD_PIN 35 + #define SHIFT_OUT_PIN 34 + #define SHIFT_EN_PIN 44 #if MB(MEGATRONICS_31, MEGATRONICS_32) #define SD_DETECT_PIN 56 diff --git a/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h b/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h index 963911ec5d70..aea05134a87c 100644 --- a/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h +++ b/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h @@ -37,9 +37,8 @@ * number (B5) agrees with the schematic but B5 is assigned to logical pin 11. */ -#if NOT_TARGET(__AVR_ATmega1280__, __AVR_ATmega2560__) - #error "Oops! Select 'Mega 1280' or 'Mega 2560' in 'Tools > Board.'" -#endif +#define ALLOW_MEGA1280 +#include "env_validate.h" #define BOARD_INFO_NAME "Mightyboard" #define DEFAULT_MACHINE_NAME "MB Replicator" @@ -118,6 +117,7 @@ #ifndef DIGIPOT_I2C_ADDRESS_A #define DIGIPOT_I2C_ADDRESS_A 0x2F // unshifted slave address (5E <- 2F << 1) #endif +#define DIGIPOT_ENABLE_I2C_PULLUPS // MightyBoard doesn't have hardware I2C pin pull-ups. // // Temperature Sensors @@ -125,7 +125,7 @@ // K7 - 69 / ADC15 - 15 #define TEMP_BED_PIN 15 -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple // Uses a separate SPI bus // // 3 E5 DO (SO) @@ -133,15 +133,15 @@ // 2 E4 CS2 // 78 E2 SCK // -#define THERMO_SCK_PIN 78 // E2 -#define THERMO_DO_PIN 3 // E5 -#define THERMO_CS1_PIN 5 // E3 -#define THERMO_CS2_PIN 2 // E4 +#define TEMP_0_CS_PIN 5 // E3 +#define TEMP_0_SCK_PIN 78 // E2 +#define TEMP_0_MISO_PIN 3 // E5 +//#define TEMP_0_MOSI_PIN ... // For MAX31865 -#define MAX6675_SS_PIN THERMO_CS1_PIN -#define MAX6675_SS2_PIN THERMO_CS2_PIN -#define MAX6675_SCK_PIN THERMO_SCK_PIN -#define MAX6675_DO_PIN THERMO_DO_PIN +#define TEMP_1_CS_PIN 2 // E4 +#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 // // Augmentation for auto-assigning plugs @@ -214,7 +214,7 @@ // #if HAS_WIRED_LCD - #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #if IS_RRD_FG_SC #define LCD_PINS_RS 33 // C4: LCD-STROBE #define LCD_PINS_ENABLE 72 // J2: LEFT diff --git a/Marlin/src/pins/mega/pins_OVERLORD.h b/Marlin/src/pins/mega/pins_OVERLORD.h index 045c1bc0fa6c..161820b67a8e 100644 --- a/Marlin/src/pins/mega/pins_OVERLORD.h +++ b/Marlin/src/pins/mega/pins_OVERLORD.h @@ -25,12 +25,12 @@ * Dreammaker Overlord v1.1 pin assignments */ -#if NOT_TARGET(__AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#elif HOTENDS > 2 || E_STEPPERS > 2 +#if HOTENDS > 2 || E_STEPPERS > 2 #error "Overlord Controller supports up to 2 hotends / E-steppers. Comment out this line to continue." #endif +#include "env_validate.h" + #define BOARD_INFO_NAME "OVERLORD" #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME @@ -132,7 +132,7 @@ #endif #endif -#if ENABLED(NEWPANEL) +#if IS_NEWPANEL #define BTN_ENC 16 // Enter Pin #define BTN_UP 19 // Button UP Pin #define BTN_DWN 17 // Button DOWN Pin diff --git a/Marlin/src/pins/mega/pins_PICA.h b/Marlin/src/pins/mega/pins_PICA.h index ff4d3e834d05..47c101711c4f 100644 --- a/Marlin/src/pins/mega/pins_PICA.h +++ b/Marlin/src/pins/mega/pins_PICA.h @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#pragma once /** * Arduino Mega with PICA pin assignments @@ -29,6 +30,8 @@ * Applies to PICA, PICA_REVB */ +#include "env_validate.h" + #ifndef BOARD_INFO_NAME #define BOARD_INFO_NAME "PICA" #endif @@ -42,10 +45,6 @@ AD12 = 66; AD13 = 67; AD14 = 68; AD15 = 69; */ -#if NOT_TARGET(__AVR_ATmega1280__, __AVR_ATmega2560__) - #error "Oops! Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu." -#endif - // // Servos // @@ -119,11 +118,11 @@ #define SSR_PIN 6 -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 66 // Don't use 53 if using Display/SD card + #define TEMP_0_CS_PIN 66 // Don't use 53 if using Display/SD card #else - #define MAX6675_SS_PIN 66 // Don't use 49 (SD_DETECT_PIN) + #define TEMP_0_CS_PIN 66 // Don't use 49 (SD_DETECT_PIN) #endif // diff --git a/Marlin/src/pins/mega/pins_PICAOLD.h b/Marlin/src/pins/mega/pins_PICAOLD.h index f53a4cdcd258..e19ea744e5eb 100644 --- a/Marlin/src/pins/mega/pins_PICAOLD.h +++ b/Marlin/src/pins/mega/pins_PICAOLD.h @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#pragma once #define HEATER_0_PIN 9 // E0 #define HEATER_1_PIN 10 // E1 diff --git a/Marlin/src/pins/mega/pins_WANHAO_ONEPLUS.h b/Marlin/src/pins/mega/pins_WANHAO_ONEPLUS.h index 52e757c53408..503dd9ec8148 100644 --- a/Marlin/src/pins/mega/pins_WANHAO_ONEPLUS.h +++ b/Marlin/src/pins/mega/pins_WANHAO_ONEPLUS.h @@ -25,13 +25,11 @@ * Wanhao 0ne+ pin assignments */ -#if NOT_TARGET(__AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "Wanhao i3 Mini 0ne+" #define DEFAULT_MACHINE_NAME "i3 Mini" -#define BOARD_WEBSITE_URL "https://tinyurl.com/yyxw7se7" +#define BOARD_WEBSITE_URL "tinyurl.com/yyxw7se7" // // Limit Switches @@ -82,7 +80,7 @@ // // SD Card // -#define SD_DETECT_PIN -1 +#define SD_DETECT_PIN 83 #define SDSS 53 // diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index c5dbd2087627..28c7ed007170 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -21,9 +21,9 @@ */ #pragma once -#include "../core/boards.h" - /** + * File: pins/pins.h + * * Include pins definitions * * Pins numbering schemes: @@ -35,7 +35,7 @@ * These numbers are the same in any pin mapping. */ -#define MAX_EXTRUDERS 8 +#define MAX_E_STEPPERS 8 #if MB(RAMPS_13_EFB, RAMPS_14_EFB, RAMPS_PLUS_EFB, RAMPS_14_RE_ARM_EFB, RAMPS_SMART_EFB, RAMPS_DUO_EFB, RAMPS4DUE_EFB) #define IS_RAMPS_EFB @@ -49,7 +49,9 @@ #define IS_RAMPS_SF #endif -#define HAS_FREE_AUX2_PINS !(BOTH(ULTRA_LCD, NEWPANEL) && ANY(PANEL_ONE, VIKI2, miniVIKI, MINIPANEL, REPRAPWORLD_KEYPAD)) +#if !(BOTH(IS_ULTRA_LCD, IS_NEWPANEL) && ANY(PANEL_ONE, VIKI2, miniVIKI, MINIPANEL, REPRAPWORLD_KEYPAD)) + #define HAS_FREE_AUX2_PINS 1 +#endif // Test the target within the included pins file #ifdef __MARLIN_DEPS__ @@ -63,56 +65,32 @@ // #if MB(RAMPS_OLD) - #include "ramps/pins_RAMPS_OLD.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 -#elif MB(RAMPS_13_EFB) - #include "ramps/pins_RAMPS_13.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 -#elif MB(RAMPS_13_EEB) - #include "ramps/pins_RAMPS_13.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 -#elif MB(RAMPS_13_EFF) - #include "ramps/pins_RAMPS_13.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 -#elif MB(RAMPS_13_EEF) - #include "ramps/pins_RAMPS_13.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 -#elif MB(RAMPS_13_SF) - #include "ramps/pins_RAMPS_13.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 -#elif MB(RAMPS_14_EFB) - #include "ramps/pins_RAMPS.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 -#elif MB(RAMPS_14_EEB) - #include "ramps/pins_RAMPS.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 -#elif MB(RAMPS_14_EFF) - #include "ramps/pins_RAMPS.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 -#elif MB(RAMPS_14_EEF) - #include "ramps/pins_RAMPS.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 -#elif MB(RAMPS_14_SF) - #include "ramps/pins_RAMPS.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 -#elif MB(RAMPS_PLUS_EFB) - #include "ramps/pins_RAMPS_PLUS.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 -#elif MB(RAMPS_PLUS_EEB) - #include "ramps/pins_RAMPS_PLUS.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 -#elif MB(RAMPS_PLUS_EFF) - #include "ramps/pins_RAMPS_PLUS.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 -#elif MB(RAMPS_PLUS_EEF) - #include "ramps/pins_RAMPS_PLUS.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 -#elif MB(RAMPS_PLUS_SF) - #include "ramps/pins_RAMPS_PLUS.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 + #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 +#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 +#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 // // RAMPS Derivatives - ATmega1280, ATmega2560 // #elif MB(3DRAG) - #include "ramps/pins_3DRAG.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 + #include "ramps/pins_3DRAG.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(K8200) - #include "ramps/pins_K8200.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 (3DRAG) + #include "ramps/pins_K8200.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(K8400) - #include "ramps/pins_K8400.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 (3DRAG) + #include "ramps/pins_K8400.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(K8600) - #include "ramps/pins_K8600.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 + #include "ramps/pins_K8600.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(K8800) - #include "ramps/pins_K8800.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 (3DRAG) + #include "ramps/pins_K8800.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(BAM_DICE) - #include "ramps/pins_RAMPS.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 + #include "ramps/pins_RAMPS.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(BAM_DICE_DUE) - #include "ramps/pins_BAM_DICE_DUE.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 + #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 #elif MB(MKS_BASE_14) @@ -124,25 +102,27 @@ #elif MB(MKS_BASE_HEROIC) #include "ramps/pins_MKS_BASE_HEROIC.h" // ATmega2560 env:mega2560 #elif MB(MKS_GEN_13) - #include "ramps/pins_MKS_GEN_13.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 + #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" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 + #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 #elif MB(ZRIB_V20) - #include "ramps/pins_ZRIB_V20.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 (MKS_GEN_13) + #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 #elif MB(FELIX2) - #include "ramps/pins_FELIX2.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 + #include "ramps/pins_FELIX2.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(RIGIDBOARD) - #include "ramps/pins_RIGIDBOARD.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 + #include "ramps/pins_RIGIDBOARD.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(RIGIDBOARD_V2) - #include "ramps/pins_RIGIDBOARD_V2.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 + #include "ramps/pins_RIGIDBOARD_V2.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(SAINSMART_2IN1) - #include "ramps/pins_SAINSMART_2IN1.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 + #include "ramps/pins_SAINSMART_2IN1.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(ULTIMAKER) - #include "ramps/pins_ULTIMAKER.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 + #include "ramps/pins_ULTIMAKER.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(ULTIMAKER_OLD) - #include "ramps/pins_ULTIMAKER_OLD.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 + #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 #elif MB(AZTEEG_X3_PRO) @@ -169,20 +149,18 @@ #include "ramps/pins_MAKEBOARD_MINI.h" // ATmega2560 env:mega2560 #elif MB(TRIGORILLA_13) #include "ramps/pins_TRIGORILLA_13.h" // ATmega2560 env:mega2560 -#elif MB(TRIGORILLA_14) - #include "ramps/pins_TRIGORILLA_14.h" // ATmega2560 env:mega2560 -#elif MB(TRIGORILLA_14_11) +#elif MB(TRIGORILLA_14, TRIGORILLA_14_11) #include "ramps/pins_TRIGORILLA_14.h" // ATmega2560 env:mega2560 #elif MB(RAMPS_ENDER_4) #include "ramps/pins_RAMPS_ENDER_4.h" // ATmega2560 env:mega2560 #elif MB(RAMPS_CREALITY) #include "ramps/pins_RAMPS_CREALITY.h" // ATmega2560 env:mega2560 -#elif MB(RAMPS_DAGOMA) - #include "ramps/pins_RAMPS_DAGOMA.h" // ATmega2560 env:mega2560 +#elif MB(DAGOMA_F5) + #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_13 + #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_14 + #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 #elif MB(VORON) @@ -205,6 +183,10 @@ #include "ramps/pins_TENLOG_D3_HERO.h" // ATmega2560 env:mega2560 #elif MB(MKS_GEN_L_V21) #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 +#elif MB(LONGER3D_LK1_PRO, LONGER3D_LKx_PRO) + #include "ramps/pins_LONGER3D_LKx_PRO.h" // ATmega2560 env:mega2560 // // RAMBo and derivatives @@ -220,19 +202,21 @@ #include "rambo/pins_EINSY_RETRO.h" // ATmega2560 env:rambo #elif MB(SCOOVO_X9H) #include "rambo/pins_SCOOVO_X9H.h" // ATmega2560 env:rambo +#elif MB(RAMBO_THINKERV2) + #include "rambo/pins_RAMBO_THINKERV2.h" // ATmega2560 env:rambo // // Other ATmega1280, ATmega2560 // #elif MB(CNCONTROLS_11) - #include "mega/pins_CNCONTROLS_11.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 + #include "mega/pins_CNCONTROLS_11.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(CNCONTROLS_12) - #include "mega/pins_CNCONTROLS_12.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 + #include "mega/pins_CNCONTROLS_12.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(CNCONTROLS_15) - #include "mega/pins_CNCONTROLS_15.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 + #include "mega/pins_CNCONTROLS_15.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(MIGHTYBOARD_REVE) - #include "mega/pins_MIGHTYBOARD_REVE.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560ext + #include "mega/pins_MIGHTYBOARD_REVE.h" // ATmega2560, ATmega1280 env:mega2560ext env:mega1280 env:MightyBoard1280 env:MightyBoard2560 #elif MB(CHEAPTRONIC) #include "mega/pins_CHEAPTRONIC.h" // ATmega2560 env:mega2560 #elif MB(CHEAPTRONIC_V2) @@ -246,25 +230,31 @@ #elif MB(ELEFU_3) #include "mega/pins_ELEFU_3.h" // ATmega2560 env:mega2560 #elif MB(LEAPFROG) - #include "mega/pins_LEAPFROG.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 + #include "mega/pins_LEAPFROG.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(MEGACONTROLLER) #include "mega/pins_MEGACONTROLLER.h" // ATmega2560 env:mega2560 #elif MB(GT2560_REV_A) - #include "mega/pins_GT2560_REV_A.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 + #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" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 + #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 +#elif MB(GT2560_REV_B) + #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_V3_MC2) #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 #elif MB(EINSTART_S) - #include "mega/pins_EINSTART-S.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560ext + #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 #elif MB(OVERLORD) #include "mega/pins_OVERLORD.h" // ATmega2560 env:mega2560 +#elif MB(HJC2560C_REV1) + #include "mega/pins_HJC2560C_REV2.h" // ATmega2560 env:mega2560 #elif MB(HJC2560C_REV2) #include "mega/pins_HJC2560C_REV2.h" // ATmega2560 env:mega2560 #elif MB(LEAPFROG_XEED2015) @@ -275,6 +265,8 @@ #include "mega/pins_PICAOLD.h" // ATmega2560 env:mega2560 #elif MB(INTAMSYS40) #include "mega/pins_INTAMSYS40.h" // ATmega2560 env:mega2560 +#elif MB(MALYAN_M180) + #include "mega/pins_MALYAN_M180.h" // ATmega2560 env:mega2560 // // ATmega1281, ATmega2561 @@ -290,27 +282,27 @@ // #elif MB(SANGUINOLOLU_11) - #include "sanguino/pins_SANGUINOLOLU_11.h" // ATmega644P, ATmega1284P env:sanguino644p env:sanguino1284p + #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:sanguino644p env:sanguino1284p + #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:sanguino644p env:sanguino1284p + #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:sanguino644p env:sanguino1284p + #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:sanguino644p env:sanguino1284p + #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 env:melzi_optimized env:melzi_optiboot + #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:sanguino644p env:sanguino1284p + #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:sanguino644p env:sanguino1284p + #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:sanguino644p env:sanguino1284p + #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:sanguino644p env:sanguino1284p + #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:sanguino_atmega644p env:sanguino_atmega1284p + #include "sanguino/pins_ZMIB_V2.h" // ATmega644P, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p // // Other ATmega644P, ATmega644, ATmega1284P @@ -319,27 +311,27 @@ #elif MB(GEN3_MONOLITHIC) #include "sanguino/pins_GEN3_MONOLITHIC.h" // ATmega644P env:sanguino644p #elif MB(GEN3_PLUS) - #include "sanguino/pins_GEN3_PLUS.h" // ATmega644P, ATmega1284P env:sanguino644p env:sanguino1284p + #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:sanguino644p env:sanguino1284p + #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:sanguino644p env:sanguino1284p + #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:sanguino644p env:sanguino1284p + #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:sanguino644p env:sanguino1284p + #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:sanguino644p env:sanguino1284p + #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:sanguino644p env:sanguino1284p + #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 #elif MB(OMCA) #include "sanguino/pins_OMCA.h" // ATmega644P, ATmega644 env:sanguino644p #elif MB(ANET_10) - #include "sanguino/pins_ANET_10.h" // ATmega1284P env:sanguino1284p + #include "sanguino/pins_ANET_10.h" // ATmega1284P env:sanguino1284p env:sanguino1284p_optimized #elif MB(SETHI) - #include "sanguino/pins_SETHI.h" // ATmega644P, ATmega644, ATmega1284P env:sanguino644p env:sanguino1284p + #include "sanguino/pins_SETHI.h" // ATmega644P, ATmega644, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p // // Teensyduino - AT90USB1286, AT90USB1286P @@ -366,15 +358,7 @@ // LPC1768 ARM Cortex M3 // -#elif MB(RAMPS_14_RE_ARM_EFB) - #include "lpc1768/pins_RAMPS_RE_ARM.h" // LPC1768 env:LPC1768 -#elif MB(RAMPS_14_RE_ARM_EEB) - #include "lpc1768/pins_RAMPS_RE_ARM.h" // LPC1768 env:LPC1768 -#elif MB(RAMPS_14_RE_ARM_EFF) - #include "lpc1768/pins_RAMPS_RE_ARM.h" // LPC1768 env:LPC1768 -#elif MB(RAMPS_14_RE_ARM_EEF) - #include "lpc1768/pins_RAMPS_RE_ARM.h" // LPC1768 env:LPC1768 -#elif MB(RAMPS_14_RE_ARM_SF) +#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 #elif MB(MKS_SBASE) #include "lpc1768/pins_MKS_SBASE.h" // LPC1768 env:LPC1768 @@ -423,6 +407,8 @@ #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 +#elif MB(FLY_CDY) + #include "lpc1769/pins_FLY_CDY.h" // LPC1769 env:LPC1769 // // Due (ATSAM) boards @@ -442,40 +428,16 @@ #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 -#elif MB(RAMPS_SMART_EFB) +#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 -#elif MB(RAMPS_SMART_EEB) - #include "sam/pins_RAMPS_SMART.h" // SAM3X8E env:DUE env:DUE_USB env:DUE_debug -#elif MB(RAMPS_SMART_EFF) - #include "sam/pins_RAMPS_SMART.h" // SAM3X8E env:DUE env:DUE_USB env:DUE_debug -#elif MB(RAMPS_SMART_EEF) - #include "sam/pins_RAMPS_SMART.h" // SAM3X8E env:DUE env:DUE_USB env:DUE_debug -#elif MB(RAMPS_SMART_SF) - #include "sam/pins_RAMPS_SMART.h" // SAM3X8E env:DUE env:DUE_USB env:DUE_debug -#elif MB(RAMPS_DUO_EFB) - #include "sam/pins_RAMPS_DUO.h" // SAM3X8E env:DUE env:DUE_USB env:DUE_debug -#elif MB(RAMPS_DUO_EEB) +#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 -#elif MB(RAMPS_DUO_EFF) - #include "sam/pins_RAMPS_DUO.h" // SAM3X8E env:DUE env:DUE_USB env:DUE_debug -#elif MB(RAMPS_DUO_EEF) - #include "sam/pins_RAMPS_DUO.h" // SAM3X8E env:DUE env:DUE_USB env:DUE_debug -#elif MB(RAMPS_DUO_SF) - #include "sam/pins_RAMPS_DUO.h" // SAM3X8E env:DUE env:DUE_USB env:DUE_debug -#elif MB(RAMPS4DUE_EFB) - #include "sam/pins_RAMPS4DUE.h" // SAM3X8E env:DUE env:DUE_USB env:DUE_debug -#elif MB(RAMPS4DUE_EEB) - #include "sam/pins_RAMPS4DUE.h" // SAM3X8E env:DUE env:DUE_USB env:DUE_debug -#elif MB(RAMPS4DUE_EFF) - #include "sam/pins_RAMPS4DUE.h" // SAM3X8E env:DUE env:DUE_USB env:DUE_debug -#elif MB(RAMPS4DUE_EEF) - #include "sam/pins_RAMPS4DUE.h" // SAM3X8E env:DUE env:DUE_USB env:DUE_debug -#elif MB(RAMPS4DUE_SF) +#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 #elif MB(ULTRATRONICS_PRO) #include "sam/pins_ULTRATRONICS_PRO.h" // SAM3X8E env:DUE env:DUE_debug #elif MB(ARCHIM1) - #include "sam/pins_ARCHIM1.h" // SAM3X8E env:DUE env:DUE_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 #elif MB(ALLIGATOR) @@ -486,6 +448,8 @@ #include "sam/pins_PRINTRBOARD_G2.h" // SAM3X8C env:DUE_USB #elif MB(CNCONTROLS_15D) #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 // // STM32 ARM Cortex-M0 @@ -500,77 +464,109 @@ // #elif MB(STM32F103RE) - #include "stm32f1/pins_STM32F1R.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_STM32F1R.h" // STM32F103RE env:STM32F103RE env:STM32F103RE_maple #elif MB(MALYAN_M200) - #include "stm32f1/pins_MALYAN_M200.h" // STM32F1 env:STM32F103CB_malyan + #include "stm32f1/pins_MALYAN_M200.h" // STM32F103CB env:STM32F103CB_malyan env:STM32F103CB_malyan_maple #elif MB(STM3R_MINI) - #include "stm32f1/pins_STM3R_MINI.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_STM3R_MINI.h" // STM32F103VE? env:STM32F103VE env:STM32F103RE_maple #elif MB(GTM32_PRO_VB) - #include "stm32f1/pins_GTM32_PRO_VB.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_GTM32_PRO_VB.h" // STM32F103VE env:STM32F103VE env:STM32F103RE_maple +#elif MB(GTM32_PRO_VD) + #include "stm32f1/pins_GTM32_PRO_VD.h" // STM32F103VE env:STM32F103VE env:STM32F103RE_maple #elif MB(GTM32_MINI) - #include "stm32f1/pins_GTM32_MINI.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_GTM32_MINI.h" // STM32F103VE env:STM32F103VE env:STM32F103RE_maple #elif MB(GTM32_MINI_A30) - #include "stm32f1/pins_GTM32_MINI_A30.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_GTM32_MINI_A30.h" // STM32F103VE env:STM32F103VE env:STM32F103RE_maple #elif MB(GTM32_REV_B) - #include "stm32f1/pins_GTM32_REV_B.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_GTM32_REV_B.h" // STM32F103VE env:STM32F103VE env:STM32F103RE_maple #elif MB(MORPHEUS) - #include "stm32f1/pins_MORPHEUS.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_MORPHEUS.h" // STM32F103RE env:STM32F103RE env:STM32F103RE_maple #elif MB(CHITU3D) - #include "stm32f1/pins_CHITU3D.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_CHITU3D.h" // STM32F103ZE env:STM32F103ZE env:STM32F103RE_maple #elif MB(MKS_ROBIN) - #include "stm32f1/pins_MKS_ROBIN.h" // STM32F1 env:mks_robin env:mks_robin_stm32 + #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 + #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_nano35 + #include "stm32f1/pins_MKS_ROBIN_NANO.h" // STM32F1 env:mks_robin_nano35 env:mks_robin_nano35_maple #elif MB(MKS_ROBIN_NANO_V2) - #include "stm32f1/pins_MKS_ROBIN_NANO_V2.h" // STM32F1 env:mks_robin_nano35 + #include "stm32f1/pins_MKS_ROBIN_NANO_V2.h" // STM32F1 env:mks_robin_nano35 env:mks_robin_nano35_maple #elif MB(MKS_ROBIN_LITE) - #include "stm32f1/pins_MKS_ROBIN_LITE.h" // STM32F1 env:mks_robin_lite + #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 + #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 + #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 + #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 #elif MB(MKS_ROBIN_E3D) #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 #elif MB(MKS_ROBIN_E3P) - #include "stm32f1/pins_MKS_ROBIN_E3P.h" // STM32F1 env:mks_robin_e3p + #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_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB + #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_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB + #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_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB + #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_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB + #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 #elif MB(BTT_SKR_E3_DIP) - #include "stm32f1/pins_BTT_SKR_E3_DIP.h" // STM32F1 env:STM32F103RE_btt env:STM32F103RE_btt_USB env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB + #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 #elif MB(JGAURORA_A5S_A1) - #include "stm32f1/pins_JGAURORA_A5S_A1.h" // STM32F1 env:jgaurora_a5s_a1 + #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 + #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 + #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 + #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 + #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 #elif MB(CHITU3D_V5) - #include "stm32f1/pins_CHITU3D_V5.h" // STM32F1 env:chitu_f103 env:chitu_v5_gpio_init + #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 + #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 #elif MB(CREALITY_V4) - #include "stm32f1/pins_CREALITY_V4.h" // STM32F1 env:STM32F103RET6_creality + #include "stm32f1/pins_CREALITY_V4.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple +#elif MB(CREALITY_V4210) + #include "stm32f1/pins_CREALITY_V4210.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple #elif MB(CREALITY_V427) - #include "stm32f1/pins_CREALITY_V427.h" // STM32F1 env:STM32F103RET6_creality + #include "stm32f1/pins_CREALITY_V427.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple +#elif MB(CREALITY_V431) + #include "stm32f1/pins_CREALITY_V431.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple +#elif MB(CREALITY_V452) + #include "stm32f1/pins_CREALITY_V452.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple +#elif MB(CREALITY_V453) + #include "stm32f1/pins_CREALITY_V453.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple #elif MB(TRIGORILLA_PRO) - #include "stm32f1/pins_TRIGORILLA_PRO.h" // STM32F1 env:trigorilla_pro + #include "stm32f1/pins_TRIGORILLA_PRO.h" // STM32F1 env:trigorilla_pro env:trigorilla_pro_maple #elif MB(FLY_MINI) - #include "stm32f1/pins_FLY_MINI.h" // STM32F1 env:FLY_MINI + #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 +#elif MB(BEAST) + #include "stm32f1/pins_BEAST.h" // STM32F103VE? 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 +#elif MB(ZONESTAR_ZM3E2) + #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 +#elif MB(ZONESTAR_ZM3E4V2) + #include "stm32f1/pins_ZM3E4_V2_0.h" // STM32F1 env:STM32F103VE_ZM3E4V2_USB env:STM32F103VE_ZM3E4V2_USB_maple // // ARM Cortex-M4F @@ -579,21 +575,15 @@ #elif MB(TEENSY31_32) #include "teensy3/pins_TEENSY31_32.h" // TEENSY31_32 env:teensy31 #elif MB(TEENSY35_36) - #include "teensy3/pins_TEENSY35_36.h" // TEENSY35_36 env:teensy35 + #include "teensy3/pins_TEENSY35_36.h" // TEENSY35_36 env:teensy35 env:teensy36 // // STM32 ARM Cortex-M4F // -#elif MB(BEAST) - #include "stm32f4/pins_BEAST.h" // STM32F4 env:STM32F4 -#elif MB(GENERIC_STM32F4) - #include "stm32f4/pins_GENERIC_STM32F4.h" // STM32F4 env:STM32F4 #elif MB(ARMED) #include "stm32f4/pins_ARMED.h" // STM32F4 env:ARMED -#elif MB(RUMBA32_V1_0) - #include "stm32f4/pins_RUMBA32_AUS3D.h" // STM32F4 env:rumba32 -#elif MB(RUMBA32_V1_1) +#elif MB(RUMBA32_V1_0, RUMBA32_V1_1) #include "stm32f4/pins_RUMBA32_AUS3D.h" // STM32F4 env:rumba32 #elif MB(RUMBA32_MKS) #include "stm32f4/pins_RUMBA32_MKS.h" // STM32F4 env:rumba32 @@ -602,40 +592,64 @@ #elif MB(STEVAL_3DP001V1) #include "stm32f4/pins_STEVAL_3DP001V1.h" // STM32F4 env:STM32F401VE_STEVAL #elif MB(BTT_SKR_PRO_V1_1) - #include "stm32f4/pins_BTT_SKR_PRO_V1_1.h" // STM32F4 env:BIGTREE_SKR_PRO + #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 + #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 + #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 +#elif MB(BTT_E3_RRF) + #include "stm32f4/pins_BTT_E3_RRF.h" // STM32F4 env:BIGTREE_E3_RRF +#elif MB(BTT_SKR_V2_0_REV_A) + #include "stm32f4/pins_BTT_SKR_V2_0_REV_A.h" // STM32F4 env:BIGTREE_SKR_2 env:BIGTREE_SKR_2_USB +#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 +#elif MB(BTT_OCTOPUS_V1_0) + #include "stm32f4/pins_BTT_OCTOPUS_V1_0.h" // STM32F4 env:BIGTREE_OCTOPUS_V1 env:BIGTREE_OCTOPUS_V1_USB +#elif MB(BTT_OCTOPUS_V1_1) + #include "stm32f4/pins_BTT_OCTOPUS_V1_1.h" // STM32F4 env:BIGTREE_OCTOPUS_V1 env:BIGTREE_OCTOPUS_V1_USB #elif MB(LERDGE_K) - #include "stm32f4/pins_LERDGE_K.h" // STM32F4 env:STM32F4 + #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:LERDGE_S + #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: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 env:STM32F4 + #include "stm32f4/pins_VAKE403D.h" // STM32F4 #elif MB(FYSETC_S6) - #include "stm32f4/pins_FYSETC_S6.h" // STM32F4 env:FYSETC_S6 + #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 +#elif MB(FYSETC_SPIDER) + #include "stm32f4/pins_FYSETC_SPIDER.h" // STM32F4 env:FYSETC_S6 env:FYSETC_S6_8000 #elif MB(FLYF407ZG) #include "stm32f4/pins_FLYF407ZG.h" // STM32F4 env:FLYF407ZG #elif MB(MKS_ROBIN2) #include "stm32f4/pins_MKS_ROBIN2.h" // STM32F4 env:MKS_ROBIN2 -#elif MB(FYSETC_S6_V2_0) - #include "stm32f4/pins_FYSETC_S6_V2_0.h" // STM32F4 env:FYSETC_S6 +#elif MB(MKS_ROBIN_PRO_V2) + #include "stm32f4/pins_MKS_ROBIN_PRO_V2.h" // STM32F4 env:mks_robin_pro2 +#elif MB(MKS_ROBIN_NANO_V3) + #include "stm32f4/pins_MKS_ROBIN_NANO_V3.h" // STM32F4 env:mks_robin_nano_v3 env:mks_robin_nano_v3_usb_flash_drive env:mks_robin_nano_v3_usb_flash_drive_msc +#elif MB(ANET_ET4) + #include "stm32f4/pins_ANET_ET4.h" // STM32F4 env:Anet_ET4_OpenBLT +#elif MB(ANET_ET4P) + #include "stm32f4/pins_ANET_ET4P.h" // STM32F4 env:Anet_ET4_OpenBLT +#elif MB(FYSETC_CHEETAH_V20) + #include "stm32f4/pins_FYSETC_CHEETAH_V20.h" // STM32F4 env:FYSETC_CHEETAH_V20 +#elif MB(MKS_MONSTER8) + #include "stm32f4/pins_MKS_MONSTER8.h" // STM32F4 env:mks_monster8 env:mks_monster8_usb_flash_drive env:mks_monster8_usb_flash_drive_msc // // ARM Cortex M7 // -#elif MB(THE_BORG) - #include "stm32f7/pins_THE_BORG.h" // STM32F7 env:STM32F7 #elif MB(REMRAM_V1) - #include "stm32f7/pins_REMRAM_V1.h" // STM32F7 env:STM32F7 + #include "stm32f7/pins_REMRAM_V1.h" // STM32F7 env:REMRAM_V1 #elif MB(NUCLEO_F767ZI) #include "stm32f7/pins_NUCLEO_F767ZI.h" // STM32F7 env:NUCLEO_F767ZI +#elif MB(BTT_SKR_SE_BX) + #include "stm32h7/pins_BTT_SKR_SE_BX.h" // STM32H7 env:BTT_SKR_SE_BX #elif MB(TEENSY41) #include "teensy4/pins_TEENSY41.h" // Teensy-4.x env:teensy41 #elif MB(T41U5XBB) @@ -653,6 +667,8 @@ #include "esp32/pins_MRR_ESPE.h" // ESP32 env:esp32 #elif MB(E4D_BOX) #include "esp32/pins_E4D.h" // ESP32 env:esp32 +#elif MB(FYSETC_E4) + #include "esp32/pins_FYSETC_E4.h" // ESP32 env:FYSETC_E4 // // Adafruit Grand Central M4 (SAMD51 ARM Cortex-M4) @@ -664,6 +680,7 @@ // // Custom board (with custom PIO env) // + #elif MB(CUSTOM) #include "pins_custom.h" // env:custom @@ -672,7 +689,7 @@ // #elif MB(LINUX_RAMPS) - #include "linux/pins_RAMPS_LINUX.h" // Linux env:linux_native + #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 @@ -700,6 +717,9 @@ #define BOARD_BIGTREE_SKR_E3_DIP -1017 #define BOARD_RUMBA32 -1018 #define BOARD_RUMBA32_AUS3D -1019 + #define BOARD_RAMPS_DAGOMA -1020 + #define BOARD_RAMPS_LONGER3D_LK4PRO -1021 + #define BOARD_BTT_SKR_V2_0 -1022 #if MB(MKS_13) #error "BOARD_MKS_13 has been renamed BOARD_MKS_GEN_13. Please update your configuration." @@ -713,7 +733,7 @@ #error "BOARD_BIQU_SKR_V1_1 has been renamed 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." - #elif MB(BIGTREE_SKR_V2_2) + #elif MB(BIGTREE_SKR_V1_2) #error "BOARD_BIGTREE_SKR_V1_2 has been renamed 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." @@ -743,8 +763,16 @@ #error "BOARD_RUMBA32 is now BOARD_RUMBA32_MKS or BOARD_RUMBA32_V1_0. Please update your configuration." #elif MB(RUMBA32_AUS3D) #error "BOARD_RUMBA32_AUS3D is now BOARD_RUMBA32_V1_0. Please update your configuration." + #elif MB(RAMPS_DAGOMA) + #error "BOARD_RAMPS_DAGOMA is now BOARD_DAGOMA_F5. Please update your configuration." + #elif MB(RAMPS_LONGER3D_LK4PRO) + #error "BOARD_RAMPS_LONGER3D_LK4PRO is now BOARD_LONGER3D_LKx_PRO. Please update your configuration." + #elif MB(BTT_SKR_V2_0) + #error "BTT_SKR_V2_0 is now BTT_SKR_V2_0_REV_A or BTT_SKR_V2_0_REV_B. See https://bit.ly/3t5d9JQ for more information. Please update your configuration." + #elif defined(MOTHERBOARD) + #error "Unknown MOTHERBOARD value set in Configuration.h." #else - #error "Unknown MOTHERBOARD value set in Configuration.h" + #error "MOTHERBOARD not defined! Use '#define MOTHERBOARD BOARD_...' in Configuration.h." #endif #undef BOARD_MKS_13 @@ -767,855 +795,13 @@ #undef BOARD_BIGTREE_SKR_E3_DIP #undef BOARD_RUMBA32 #undef BOARD_RUMBA32_AUS3D + #undef BOARD_RAMPS_DAGOMA + #undef BOARD_RAMPS_LONGER3D_LK4PRO + #undef BOARD_BTT_SKR_V2_0 #endif -// Define certain undefined pins -#ifndef X_MS1_PIN - #define X_MS1_PIN -1 -#endif -#ifndef X_MS2_PIN - #define X_MS2_PIN -1 -#endif -#ifndef X_MS3_PIN - #define X_MS3_PIN -1 -#endif -#ifndef Y_MS1_PIN - #define Y_MS1_PIN -1 -#endif -#ifndef Y_MS2_PIN - #define Y_MS2_PIN -1 -#endif -#ifndef Y_MS3_PIN - #define Y_MS3_PIN -1 -#endif -#ifndef Z_MS1_PIN - #define Z_MS1_PIN -1 -#endif -#ifndef Z_MS2_PIN - #define Z_MS2_PIN -1 -#endif -#ifndef Z_MS3_PIN - #define Z_MS3_PIN -1 -#endif -#ifndef E0_MS1_PIN - #define E0_MS1_PIN -1 -#endif -#ifndef E0_MS2_PIN - #define E0_MS2_PIN -1 -#endif -#ifndef E0_MS3_PIN - #define E0_MS3_PIN -1 -#endif -#ifndef E1_MS1_PIN - #define E1_MS1_PIN -1 -#endif -#ifndef E1_MS2_PIN - #define E1_MS2_PIN -1 -#endif -#ifndef E1_MS3_PIN - #define E1_MS3_PIN -1 -#endif -#ifndef E2_MS1_PIN - #define E2_MS1_PIN -1 -#endif -#ifndef E2_MS2_PIN - #define E2_MS2_PIN -1 -#endif -#ifndef E2_MS3_PIN - #define E2_MS3_PIN -1 -#endif -#ifndef E3_MS1_PIN - #define E3_MS1_PIN -1 -#endif -#ifndef E3_MS2_PIN - #define E3_MS2_PIN -1 -#endif -#ifndef E3_MS3_PIN - #define E3_MS3_PIN -1 -#endif -#ifndef E4_MS1_PIN - #define E4_MS1_PIN -1 -#endif -#ifndef E4_MS2_PIN - #define E4_MS2_PIN -1 -#endif -#ifndef E4_MS3_PIN - #define E4_MS3_PIN -1 -#endif -#ifndef E5_MS1_PIN - #define E5_MS1_PIN -1 -#endif -#ifndef E5_MS2_PIN - #define E5_MS2_PIN -1 -#endif -#ifndef E5_MS3_PIN - #define E5_MS3_PIN -1 -#endif -#ifndef E6_MS1_PIN - #define E6_MS1_PIN -1 -#endif -#ifndef E6_MS2_PIN - #define E6_MS2_PIN -1 -#endif -#ifndef E6_MS3_PIN - #define E6_MS3_PIN -1 -#endif -#ifndef E7_MS1_PIN - #define E7_MS1_PIN -1 -#endif -#ifndef E7_MS2_PIN - #define E7_MS2_PIN -1 -#endif -#ifndef E7_MS3_PIN - #define E7_MS3_PIN -1 -#endif - -#ifndef E0_STEP_PIN - #define E0_STEP_PIN -1 -#endif -#ifndef E0_DIR_PIN - #define E0_DIR_PIN -1 -#endif -#ifndef E0_ENABLE_PIN - #define E0_ENABLE_PIN -1 -#endif -#ifndef E1_STEP_PIN - #define E1_STEP_PIN -1 -#endif -#ifndef E1_DIR_PIN - #define E1_DIR_PIN -1 -#endif -#ifndef E1_ENABLE_PIN - #define E1_ENABLE_PIN -1 -#endif -#ifndef E2_STEP_PIN - #define E2_STEP_PIN -1 -#endif -#ifndef E2_DIR_PIN - #define E2_DIR_PIN -1 -#endif -#ifndef E2_ENABLE_PIN - #define E2_ENABLE_PIN -1 -#endif -#ifndef E3_STEP_PIN - #define E3_STEP_PIN -1 -#endif -#ifndef E3_DIR_PIN - #define E3_DIR_PIN -1 -#endif -#ifndef E3_ENABLE_PIN - #define E3_ENABLE_PIN -1 -#endif -#ifndef E4_STEP_PIN - #define E4_STEP_PIN -1 -#endif -#ifndef E4_DIR_PIN - #define E4_DIR_PIN -1 -#endif -#ifndef E4_ENABLE_PIN - #define E4_ENABLE_PIN -1 -#endif -#ifndef E5_STEP_PIN - #define E5_STEP_PIN -1 -#endif -#ifndef E5_DIR_PIN - #define E5_DIR_PIN -1 -#endif -#ifndef E5_ENABLE_PIN - #define E5_ENABLE_PIN -1 -#endif -#ifndef E6_STEP_PIN - #define E6_STEP_PIN -1 -#endif -#ifndef E6_DIR_PIN - #define E6_DIR_PIN -1 -#endif -#ifndef E6_ENABLE_PIN - #define E6_ENABLE_PIN -1 -#endif -#ifndef E7_STEP_PIN - #define E7_STEP_PIN -1 -#endif -#ifndef E7_DIR_PIN - #define E7_DIR_PIN -1 -#endif -#ifndef E7_ENABLE_PIN - #define E7_ENABLE_PIN -1 -#endif - -// -// Destroy unused CS pins -// -#if !AXIS_HAS_SPI(X) - #undef X_CS_PIN -#endif -#if !AXIS_HAS_SPI(Y) - #undef Y_CS_PIN -#endif -#if !AXIS_HAS_SPI(Z) - #undef Z_CS_PIN -#endif -#if E_STEPPERS && !AXIS_HAS_SPI(E0) - #undef E0_CS_PIN -#endif -#if E_STEPPERS > 1 && !AXIS_HAS_SPI(E1) - #undef E1_CS_PIN -#endif -#if E_STEPPERS > 2 && !AXIS_HAS_SPI(E2) - #undef E2_CS_PIN -#endif -#if E_STEPPERS > 3 && !AXIS_HAS_SPI(E3) - #undef E3_CS_PIN -#endif -#if E_STEPPERS > 4 && !AXIS_HAS_SPI(E4) - #undef E4_CS_PIN -#endif -#if E_STEPPERS > 5 && !AXIS_HAS_SPI(E5) - #undef E5_CS_PIN -#endif -#if E_STEPPERS > 6 && !AXIS_HAS_SPI(E6) - #undef E6_CS_PIN -#endif -#if E_STEPPERS > 7 && !AXIS_HAS_SPI(E7) - #undef E7_CS_PIN -#endif - -#ifndef X_CS_PIN - #define X_CS_PIN -1 -#endif -#ifndef Y_CS_PIN - #define Y_CS_PIN -1 -#endif -#ifndef Z_CS_PIN - #define Z_CS_PIN -1 -#endif -#ifndef E0_CS_PIN - #define E0_CS_PIN -1 -#endif -#ifndef E1_CS_PIN - #define E1_CS_PIN -1 -#endif -#ifndef E2_CS_PIN - #define E2_CS_PIN -1 -#endif -#ifndef E3_CS_PIN - #define E3_CS_PIN -1 -#endif -#ifndef E4_CS_PIN - #define E4_CS_PIN -1 -#endif -#ifndef E5_CS_PIN - #define E5_CS_PIN -1 -#endif -#ifndef E6_CS_PIN - #define E6_CS_PIN -1 -#endif -#ifndef E7_CS_PIN - #define E7_CS_PIN -1 -#endif - -#ifndef FAN_PIN - #define FAN_PIN -1 -#endif -#define FAN0_PIN FAN_PIN -#ifndef FAN1_PIN - #define FAN1_PIN -1 -#endif -#ifndef FAN2_PIN - #define FAN2_PIN -1 -#endif -#ifndef CONTROLLER_FAN_PIN - #define CONTROLLER_FAN_PIN -1 -#endif - -#ifndef FANMUX0_PIN - #define FANMUX0_PIN -1 -#endif -#ifndef FANMUX1_PIN - #define FANMUX1_PIN -1 -#endif -#ifndef FANMUX2_PIN - #define FANMUX2_PIN -1 -#endif - -#ifndef HEATER_0_PIN - #define HEATER_0_PIN -1 -#endif -#ifndef HEATER_1_PIN - #define HEATER_1_PIN -1 -#endif -#ifndef HEATER_2_PIN - #define HEATER_2_PIN -1 -#endif -#ifndef HEATER_3_PIN - #define HEATER_3_PIN -1 -#endif -#ifndef HEATER_4_PIN - #define HEATER_4_PIN -1 -#endif -#ifndef HEATER_5_PIN - #define HEATER_5_PIN -1 -#endif -#ifndef HEATER_6_PIN - #define HEATER_6_PIN -1 -#endif -#ifndef HEATER_7_PIN - #define HEATER_7_PIN -1 -#endif -#ifndef HEATER_BED_PIN - #define HEATER_BED_PIN -1 -#endif - -#ifndef TEMP_0_PIN - #define TEMP_0_PIN -1 -#endif -#ifndef TEMP_1_PIN - #define TEMP_1_PIN -1 -#endif -#ifndef TEMP_2_PIN - #define TEMP_2_PIN -1 -#endif -#ifndef TEMP_3_PIN - #define TEMP_3_PIN -1 -#endif -#ifndef TEMP_4_PIN - #define TEMP_4_PIN -1 -#endif -#ifndef TEMP_5_PIN - #define TEMP_5_PIN -1 -#endif -#ifndef TEMP_6_PIN - #define TEMP_6_PIN -1 -#endif -#ifndef TEMP_7_PIN - #define TEMP_7_PIN -1 -#endif -#ifndef TEMP_BED_PIN - #define TEMP_BED_PIN -1 -#endif - -#ifndef SD_DETECT_PIN - #define SD_DETECT_PIN -1 -#endif -#ifndef SDPOWER_PIN - #define SDPOWER_PIN -1 -#endif -#ifndef SDSS - #define SDSS -1 -#endif -#ifndef LED_PIN - #define LED_PIN -1 -#endif -#if DISABLED(PSU_CONTROL) || !defined(PS_ON_PIN) - #undef PS_ON_PIN - #define PS_ON_PIN -1 -#endif -#ifndef KILL_PIN - #define KILL_PIN -1 -#endif -#ifndef SUICIDE_PIN - #define SUICIDE_PIN -1 -#endif -#ifndef SUICIDE_PIN_INVERTING - #define SUICIDE_PIN_INVERTING false -#endif - -#ifndef NUM_SERVO_PLUGS - #define NUM_SERVO_PLUGS 4 -#endif - -// -// Assign endstop pins for boards with only 3 connectors -// -#ifdef X_STOP_PIN - #if X_HOME_DIR < 0 - #define X_MIN_PIN X_STOP_PIN - #ifndef X_MAX_PIN - #define X_MAX_PIN -1 - #endif - #else - #define X_MAX_PIN X_STOP_PIN - #ifndef X_MIN_PIN - #define X_MIN_PIN -1 - #endif - #endif -#elif X_HOME_DIR < 0 - #define X_STOP_PIN X_MIN_PIN -#else - #define X_STOP_PIN X_MAX_PIN -#endif - -#ifdef Y_STOP_PIN - #if Y_HOME_DIR < 0 - #define Y_MIN_PIN Y_STOP_PIN - #ifndef Y_MAX_PIN - #define Y_MAX_PIN -1 - #endif - #else - #define Y_MAX_PIN Y_STOP_PIN - #ifndef Y_MIN_PIN - #define Y_MIN_PIN -1 - #endif - #endif -#elif Y_HOME_DIR < 0 - #define Y_STOP_PIN Y_MIN_PIN -#else - #define Y_STOP_PIN Y_MAX_PIN -#endif - -#ifdef Z_STOP_PIN - #if Z_HOME_DIR < 0 - #define Z_MIN_PIN Z_STOP_PIN - #ifndef Z_MAX_PIN - #define Z_MAX_PIN -1 - #endif - #else - #define Z_MAX_PIN Z_STOP_PIN - #ifndef Z_MIN_PIN - #define Z_MIN_PIN -1 - #endif - #endif -#elif Z_HOME_DIR < 0 - #define Z_STOP_PIN Z_MIN_PIN -#else - #define Z_STOP_PIN Z_MAX_PIN -#endif - // -// Disable unused endstop / probe pins +// Post-process pins according to configured settings // -#if !HAS_CUSTOM_PROBE_PIN - #undef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN -1 -#endif - -#if DISABLED(USE_XMAX_PLUG) - #undef X_MAX_PIN - #define X_MAX_PIN -1 -#endif - -#if DISABLED(USE_YMAX_PLUG) - #undef Y_MAX_PIN - #define Y_MAX_PIN -1 -#endif - -#if DISABLED(USE_ZMAX_PLUG) - #undef Z_MAX_PIN - #define Z_MAX_PIN -1 -#endif - -#if DISABLED(USE_XMIN_PLUG) - #undef X_MIN_PIN - #define X_MIN_PIN -1 -#endif - -#if DISABLED(USE_YMIN_PLUG) - #undef Y_MIN_PIN - #define Y_MIN_PIN -1 -#endif - -#if DISABLED(USE_ZMIN_PLUG) - #undef Z_MIN_PIN - #define Z_MIN_PIN -1 -#endif - -#if HAS_FILAMENT_SENSOR - #define FIL_RUNOUT1_PIN FIL_RUNOUT_PIN -#else - #undef FIL_RUNOUT_PIN - #undef FIL_RUNOUT1_PIN -#endif - -#ifndef LCD_PINS_D4 - #define LCD_PINS_D4 -1 -#endif - -#if HAS_MARLINUI_HD44780 || TOUCH_UI_ULTIPANEL - #ifndef LCD_PINS_D5 - #define LCD_PINS_D5 -1 - #endif - #ifndef LCD_PINS_D6 - #define LCD_PINS_D6 -1 - #endif - #ifndef LCD_PINS_D7 - #define LCD_PINS_D7 -1 - #endif -#endif - -/** - * Auto-Assignment for Dual X, Dual Y, Multi-Z Steppers - * - * By default X2 is assigned to the next open E plug - * on the board, then in order, Y2, Z2, Z3. These can be - * overridden in Configuration.h or Configuration_adv.h. - */ - -#define __PEXI(p,q) PIN_EXISTS(E##p##_##q) -#define _PEXI(p,q) __PEXI(p,q) -#define __EPIN(p,q) E##p##_##q##_PIN -#define _EPIN(p,q) __EPIN(p,q) -#define DIAG_REMAPPED(p,q) (PIN_EXISTS(q) && _EPIN(p##_E_INDEX, DIAG) == q##_PIN) - -// The X2 axis, if any, should be the next open extruder port -#define X2_E_INDEX E_STEPPERS - -#if EITHER(DUAL_X_CARRIAGE, X_DUAL_STEPPER_DRIVERS) - #ifndef X2_STEP_PIN - #define X2_STEP_PIN _EPIN(X2_E_INDEX, STEP) - #define X2_DIR_PIN _EPIN(X2_E_INDEX, DIR) - #define X2_ENABLE_PIN _EPIN(X2_E_INDEX, ENABLE) - #if X2_E_INDEX >= MAX_EXTRUDERS || !PIN_EXISTS(X2_STEP) - #error "No E stepper plug left for X2!" - #endif - #endif - #ifndef X2_MS1_PIN - #define X2_MS1_PIN _EPIN(X2_E_INDEX, MS1) - #endif - #ifndef X2_MS2_PIN - #define X2_MS2_PIN _EPIN(X2_E_INDEX, MS2) - #endif - #ifndef X2_MS3_PIN - #define X2_MS3_PIN _EPIN(X2_E_INDEX, MS3) - #endif - #if AXIS_HAS_SPI(X2) && !defined(X2_CS_PIN) - #define X2_CS_PIN _EPIN(X2_E_INDEX, CS) - #endif - #if AXIS_HAS_UART(X2) - #ifndef X2_SERIAL_TX_PIN - #define X2_SERIAL_TX_PIN _EPIN(X2_E_INDEX, SERIAL_TX) - #endif - #ifndef X2_SERIAL_RX_PIN - #define X2_SERIAL_RX_PIN _EPIN(X2_E_INDEX, SERIAL_RX) - #endif - #endif - - // - // Auto-assign pins for stallGuard sensorless homing - // - #if defined(X2_STALL_SENSITIVITY) && ENABLED(X_DUAL_ENDSTOPS) && _PEXI(X2_E_INDEX, DIAG) - #define X2_DIAG_PIN _EPIN(X2_E_INDEX, DIAG) - #if DIAG_REMAPPED(X2, X_MIN) // If already remapped in the pins file... - #define X2_USE_ENDSTOP _XMIN_ - #elif DIAG_REMAPPED(X2, Y_MIN) - #define X2_USE_ENDSTOP _YMIN_ - #elif DIAG_REMAPPED(X2, Z_MIN) - #define X2_USE_ENDSTOP _ZMIN_ - #elif DIAG_REMAPPED(X2, X_MAX) - #define X2_USE_ENDSTOP _XMAX_ - #elif DIAG_REMAPPED(X2, Y_MAX) - #define X2_USE_ENDSTOP _YMAX_ - #elif DIAG_REMAPPED(X2, Z_MAX) - #define X2_USE_ENDSTOP _ZMAX_ - #else // Otherwise use the driver DIAG_PIN directly - #define _X2_USE_ENDSTOP(P) _E##P##_DIAG_ - #define X2_USE_ENDSTOP _X2_USE_ENDSTOP(X2_E_INDEX) - #endif - #undef X2_DIAG_PIN - #endif - - #define Y2_E_INDEX INCREMENT(X2_E_INDEX) -#else - #define Y2_E_INDEX X2_E_INDEX -#endif - -#ifndef X2_CS_PIN - #define X2_CS_PIN -1 -#endif -#ifndef X2_MS1_PIN - #define X2_MS1_PIN -1 -#endif -#ifndef X2_MS2_PIN - #define X2_MS2_PIN -1 -#endif -#ifndef X2_MS3_PIN - #define X2_MS3_PIN -1 -#endif - -// The Y2 axis, if any, should be the next open extruder port -#if ENABLED(Y_DUAL_STEPPER_DRIVERS) - #ifndef Y2_STEP_PIN - #define Y2_STEP_PIN _EPIN(Y2_E_INDEX, STEP) - #define Y2_DIR_PIN _EPIN(Y2_E_INDEX, DIR) - #define Y2_ENABLE_PIN _EPIN(Y2_E_INDEX, ENABLE) - #if Y2_E_INDEX >= MAX_EXTRUDERS || !PIN_EXISTS(Y2_STEP) - #error "No E stepper plug left for Y2!" - #endif - #endif - #ifndef Y2_MS1_PIN - #define Y2_MS1_PIN _EPIN(Y2_E_INDEX, MS1) - #endif - #ifndef Y2_MS2_PIN - #define Y2_MS2_PIN _EPIN(Y2_E_INDEX, MS2) - #endif - #ifndef Y2_MS3_PIN - #define Y2_MS3_PIN _EPIN(Y2_E_INDEX, MS3) - #endif - #if AXIS_HAS_SPI(Y2) && !defined(Y2_CS_PIN) - #define Y2_CS_PIN _EPIN(Y2_E_INDEX, CS) - #endif - #if AXIS_HAS_UART(Y2) - #ifndef Y2_SERIAL_TX_PIN - #define Y2_SERIAL_TX_PIN _EPIN(Y2_E_INDEX, SERIAL_TX) - #endif - #ifndef Y2_SERIAL_RX_PIN - #define Y2_SERIAL_RX_PIN _EPIN(Y2_E_INDEX, SERIAL_RX) - #endif - #endif - #if defined(Y2_STALL_SENSITIVITY) && ENABLED(Y_DUAL_ENDSTOPS) && _PEXI(Y2_E_INDEX, DIAG) - #define Y2_DIAG_PIN _EPIN(Y2_E_INDEX, DIAG) - #if DIAG_REMAPPED(Y2, X_MIN) - #define Y2_USE_ENDSTOP _XMIN_ - #elif DIAG_REMAPPED(Y2, Y_MIN) - #define Y2_USE_ENDSTOP _YMIN_ - #elif DIAG_REMAPPED(Y2, Z_MIN) - #define Y2_USE_ENDSTOP _ZMIN_ - #elif DIAG_REMAPPED(Y2, X_MAX) - #define Y2_USE_ENDSTOP _XMAX_ - #elif DIAG_REMAPPED(Y2, Y_MAX) - #define Y2_USE_ENDSTOP _YMAX_ - #elif DIAG_REMAPPED(Y2, Z_MAX) - #define Y2_USE_ENDSTOP _ZMAX_ - #else - #define _Y2_USE_ENDSTOP(P) _E##P##_DIAG_ - #define Y2_USE_ENDSTOP _Y2_USE_ENDSTOP(Y2_E_INDEX) - #endif - #undef Y2_DIAG_PIN - #endif - #define Z2_E_INDEX INCREMENT(Y2_E_INDEX) -#else - #define Z2_E_INDEX Y2_E_INDEX -#endif - -#ifndef Y2_CS_PIN - #define Y2_CS_PIN -1 -#endif -#ifndef Y2_MS1_PIN - #define Y2_MS1_PIN -1 -#endif -#ifndef Y2_MS2_PIN - #define Y2_MS2_PIN -1 -#endif -#ifndef Y2_MS3_PIN - #define Y2_MS3_PIN -1 -#endif - -// The Z2 axis, if any, should be the next open extruder port -#if NUM_Z_STEPPER_DRIVERS >= 2 - #ifndef Z2_STEP_PIN - #define Z2_STEP_PIN _EPIN(Z2_E_INDEX, STEP) - #define Z2_DIR_PIN _EPIN(Z2_E_INDEX, DIR) - #define Z2_ENABLE_PIN _EPIN(Z2_E_INDEX, ENABLE) - #if Z2_E_INDEX >= MAX_EXTRUDERS || !PIN_EXISTS(Z2_STEP) - #error "No E stepper plug left for Z2!" - #endif - #endif - #ifndef Z2_MS1_PIN - #define Z2_MS1_PIN _EPIN(Z2_E_INDEX, MS1) - #endif - #ifndef Z2_MS2_PIN - #define Z2_MS2_PIN _EPIN(Z2_E_INDEX, MS2) - #endif - #ifndef Z2_MS3_PIN - #define Z2_MS3_PIN _EPIN(Z2_E_INDEX, MS3) - #endif - #if AXIS_HAS_SPI(Z2) && !defined(Z2_CS_PIN) - #define Z2_CS_PIN _EPIN(Z2_E_INDEX, CS) - #endif - #if AXIS_HAS_UART(Z2) - #ifndef Z2_SERIAL_TX_PIN - #define Z2_SERIAL_TX_PIN _EPIN(Z2_E_INDEX, SERIAL_TX) - #endif - #ifndef Z2_SERIAL_RX_PIN - #define Z2_SERIAL_RX_PIN _EPIN(Z2_E_INDEX, SERIAL_RX) - #endif - #endif - #if defined(Z2_STALL_SENSITIVITY) && ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 2 && _PEXI(Z2_E_INDEX, DIAG) - #define Z2_DIAG_PIN _EPIN(Z2_E_INDEX, DIAG) - #if DIAG_REMAPPED(Z2, X_MIN) - #define Z2_USE_ENDSTOP _XMIN_ - #elif DIAG_REMAPPED(Z2, Y_MIN) - #define Z2_USE_ENDSTOP _YMIN_ - #elif DIAG_REMAPPED(Z2, Z_MIN) - #define Z2_USE_ENDSTOP _ZMIN_ - #elif DIAG_REMAPPED(Z2, X_MAX) - #define Z2_USE_ENDSTOP _XMAX_ - #elif DIAG_REMAPPED(Z2, Y_MAX) - #define Z2_USE_ENDSTOP _YMAX_ - #elif DIAG_REMAPPED(Z2, Z_MAX) - #define Z2_USE_ENDSTOP _ZMAX_ - #else - #define _Z2_USE_ENDSTOP(P) _E##P##_DIAG_ - #define Z2_USE_ENDSTOP _Z2_USE_ENDSTOP(Z2_E_INDEX) - #endif - #undef Z2_DIAG_PIN - #endif - #define Z3_E_INDEX INCREMENT(Z2_E_INDEX) -#else - #define Z3_E_INDEX Z2_E_INDEX -#endif - -#ifndef Z2_CS_PIN - #define Z2_CS_PIN -1 -#endif -#ifndef Z2_MS1_PIN - #define Z2_MS1_PIN -1 -#endif -#ifndef Z2_MS2_PIN - #define Z2_MS2_PIN -1 -#endif -#ifndef Z2_MS3_PIN - #define Z2_MS3_PIN -1 -#endif - -#if NUM_Z_STEPPER_DRIVERS >= 3 - #ifndef Z3_STEP_PIN - #define Z3_STEP_PIN _EPIN(Z3_E_INDEX, STEP) - #define Z3_DIR_PIN _EPIN(Z3_E_INDEX, DIR) - #define Z3_ENABLE_PIN _EPIN(Z3_E_INDEX, ENABLE) - #if Z3_E_INDEX >= MAX_EXTRUDERS || !PIN_EXISTS(Z3_STEP) - #error "No E stepper plug left for Z3!" - #endif - #endif - #if AXIS_HAS_SPI(Z3) - #ifndef Z3_CS_PIN - #define Z3_CS_PIN _EPIN(Z3_E_INDEX, CS) - #endif - #endif - #ifndef Z3_MS1_PIN - #define Z3_MS1_PIN _EPIN(Z3_E_INDEX, MS1) - #endif - #ifndef Z3_MS2_PIN - #define Z3_MS2_PIN _EPIN(Z3_E_INDEX, MS2) - #endif - #ifndef Z3_MS3_PIN - #define Z3_MS3_PIN _EPIN(Z3_E_INDEX, MS3) - #endif - #if AXIS_HAS_UART(Z3) - #ifndef Z3_SERIAL_TX_PIN - #define Z3_SERIAL_TX_PIN _EPIN(Z3_E_INDEX, SERIAL_TX) - #endif - #ifndef Z3_SERIAL_RX_PIN - #define Z3_SERIAL_RX_PIN _EPIN(Z3_E_INDEX, SERIAL_RX) - #endif - #endif - #if defined(Z3_STALL_SENSITIVITY) && ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 3 && _PEXI(Z3_E_INDEX, DIAG) - #define Z3_DIAG_PIN _EPIN(Z3_E_INDEX, DIAG) - #if DIAG_REMAPPED(Z3, X_MIN) - #define Z3_USE_ENDSTOP _XMIN_ - #elif DIAG_REMAPPED(Z3, Y_MIN) - #define Z3_USE_ENDSTOP _YMIN_ - #elif DIAG_REMAPPED(Z3, Z_MIN) - #define Z3_USE_ENDSTOP _ZMIN_ - #elif DIAG_REMAPPED(Z3, X_MAX) - #define Z3_USE_ENDSTOP _XMAX_ - #elif DIAG_REMAPPED(Z3, Y_MAX) - #define Z3_USE_ENDSTOP _YMAX_ - #elif DIAG_REMAPPED(Z3, Z_MAX) - #define Z3_USE_ENDSTOP _ZMAX_ - #else - #define _Z3_USE_ENDSTOP(P) _E##P##_DIAG_ - #define Z3_USE_ENDSTOP _Z3_USE_ENDSTOP(Z3_E_INDEX) - #endif - #undef Z3_DIAG_PIN - #endif - #define Z4_E_INDEX INCREMENT(Z3_E_INDEX) -#endif - -#ifndef Z3_CS_PIN - #define Z3_CS_PIN -1 -#endif -#ifndef Z3_MS1_PIN - #define Z3_MS1_PIN -1 -#endif -#ifndef Z3_MS2_PIN - #define Z3_MS2_PIN -1 -#endif -#ifndef Z3_MS3_PIN - #define Z3_MS3_PIN -1 -#endif - -#if NUM_Z_STEPPER_DRIVERS >= 4 - #ifndef Z4_STEP_PIN - #define Z4_STEP_PIN _EPIN(Z4_E_INDEX, STEP) - #define Z4_DIR_PIN _EPIN(Z4_E_INDEX, DIR) - #define Z4_ENABLE_PIN _EPIN(Z4_E_INDEX, ENABLE) - #if Z4_E_INDEX >= MAX_EXTRUDERS || !PIN_EXISTS(Z4_STEP) - #error "No E stepper plug left for Z4!" - #endif - #endif - #if AXIS_HAS_SPI(Z4) - #ifndef Z4_CS_PIN - #define Z4_CS_PIN _EPIN(Z4_E_INDEX, CS) - #endif - #endif - #ifndef Z4_MS1_PIN - #define Z4_MS1_PIN _EPIN(Z4_E_INDEX, MS1) - #endif - #ifndef Z4_MS2_PIN - #define Z4_MS2_PIN _EPIN(Z4_E_INDEX, MS2) - #endif - #ifndef Z4_MS3_PIN - #define Z4_MS3_PIN _EPIN(Z4_E_INDEX, MS3) - #endif - #if AXIS_HAS_UART(Z4) - #ifndef Z4_SERIAL_TX_PIN - #define Z4_SERIAL_TX_PIN _EPIN(Z4_E_INDEX, SERIAL_TX) - #endif - #ifndef Z4_SERIAL_RX_PIN - #define Z4_SERIAL_RX_PIN _EPIN(Z4_E_INDEX, SERIAL_RX) - #endif - #endif - #if defined(Z4_STALL_SENSITIVITY) && ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4 && _PEXI(Z4_E_INDEX, DIAG) - #define Z4_DIAG_PIN _EPIN(Z4_E_INDEX, DIAG) - #if DIAG_REMAPPED(Z4, X_MIN) - #define Z4_USE_ENDSTOP _XMIN_ - #elif DIAG_REMAPPED(Z4, Y_MIN) - #define Z4_USE_ENDSTOP _YMIN_ - #elif DIAG_REMAPPED(Z4, Z_MIN) - #define Z4_USE_ENDSTOP _ZMIN_ - #elif DIAG_REMAPPED(Z4, X_MAX) - #define Z4_USE_ENDSTOP _XMAX_ - #elif DIAG_REMAPPED(Z4, Y_MAX) - #define Z4_USE_ENDSTOP _YMAX_ - #elif DIAG_REMAPPED(Z4, Z_MAX) - #define Z4_USE_ENDSTOP _ZMAX_ - #else - #define _Z4_USE_ENDSTOP(P) _E##P##_DIAG_ - #define Z4_USE_ENDSTOP _Z4_USE_ENDSTOP(Z4_E_INDEX) - #endif - #undef Z4_DIAG_PIN - #endif -#endif - -#ifndef Z4_CS_PIN - #define Z4_CS_PIN -1 -#endif -#ifndef Z4_MS1_PIN - #define Z4_MS1_PIN -1 -#endif -#ifndef Z4_MS2_PIN - #define Z4_MS2_PIN -1 -#endif -#ifndef Z4_MS3_PIN - #define Z4_MS3_PIN -1 -#endif - -#if HAS_MARLINUI_U8GLIB - #if !defined(ST7920_DELAY_1) && defined(BOARD_ST7920_DELAY_1) - #define ST7920_DELAY_1 BOARD_ST7920_DELAY_1 - #endif - #if !defined(ST7920_DELAY_2) && defined(BOARD_ST7920_DELAY_2) - #define ST7920_DELAY_2 BOARD_ST7920_DELAY_2 - #endif - #if !defined(ST7920_DELAY_3) && defined(BOARD_ST7920_DELAY_3) - #define ST7920_DELAY_3 BOARD_ST7920_DELAY_3 - #endif -#else - #undef ST7920_DELAY_1 - #undef ST7920_DELAY_2 - #undef ST7920_DELAY_3 -#endif - -#undef HAS_FREE_AUX2_PINS -#undef DIAG_REMAPPED +#include "pins_postprocess.h" diff --git a/Marlin/src/pins/pinsDebug.h b/Marlin/src/pins/pinsDebug.h index 5f153cfa2b0f..0c5523296976 100644 --- a/Marlin/src/pins/pinsDebug.h +++ b/Marlin/src/pins/pinsDebug.h @@ -41,38 +41,26 @@ #define REPORT_NAME_ANALOG(COUNTER, NAME) _ADD_PIN(#NAME, COUNTER) #include "pinsDebug_list.h" -#line 46 +#line 45 // manually add pins that have names that are macros which don't play well with these macros #if ANY(AVR_ATmega2560_FAMILY, AVR_ATmega1284_FAMILY, ARDUINO_ARCH_SAM, TARGET_LPC1768) - #if SERIAL_PORT == 0 + #if CONF_SERIAL_IS(0) static const char RXD_NAME_0[] PROGMEM = { "RXD0" }; static const char TXD_NAME_0[] PROGMEM = { "TXD0" }; - #elif SERIAL_PORT == 1 + #endif + #if CONF_SERIAL_IS(1) static const char RXD_NAME_1[] PROGMEM = { "RXD1" }; static const char TXD_NAME_1[] PROGMEM = { "TXD1" }; - #elif SERIAL_PORT == 2 + #endif + #if CONF_SERIAL_IS(2) static const char RXD_NAME_2[] PROGMEM = { "RXD2" }; static const char TXD_NAME_2[] PROGMEM = { "TXD2" }; - #elif SERIAL_PORT == 3 + #endif + #if CONF_SERIAL_IS(3) static const char RXD_NAME_3[] PROGMEM = { "RXD3" }; static const char TXD_NAME_3[] PROGMEM = { "TXD3" }; #endif - #ifdef SERIAL_PORT_2 - #if SERIAL_PORT_2 == 0 - static const char RXD_NAME_0[] PROGMEM = { "RXD0" }; - static const char TXD_NAME_0[] PROGMEM = { "TXD0" }; - #elif SERIAL_PORT_2 == 1 - static const char RXD_NAME_1[] PROGMEM = { "RXD1" }; - static const char TXD_NAME_1[] PROGMEM = { "TXD1" }; - #elif SERIAL_PORT_2 == 2 - static const char RXD_NAME_2[] PROGMEM = { "RXD2" }; - static const char TXD_NAME_2[] PROGMEM = { "TXD2" }; - #elif SERIAL_PORT_2 == 3 - static const char RXD_NAME_3[] PROGMEM = { "RXD3" }; - static const char TXD_NAME_3[] PROGMEM = { "TXD3" }; - #endif - #endif #endif ///////////////////////////////////////////////////////////////////////////// @@ -103,12 +91,11 @@ const PinInfo pin_array[] PROGMEM = { * Each entry takes up 6 bytes in FLASH: * 2 byte pointer to location of the name string * 2 bytes containing the pin number - * analog pin numbers were convereted to digital when the array was created + * analog pin numbers were converted to digital when the array was created * 2 bytes containing the digital/analog bool flag */ - // manually add pins ... - #if SERIAL_PORT == 0 + #if CONF_SERIAL_IS(0) #if EITHER(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) { RXD_NAME_0, 0, true }, { TXD_NAME_0, 1, true }, @@ -119,7 +106,9 @@ const PinInfo pin_array[] PROGMEM = { { RXD_NAME_0, 3, true }, { TXD_NAME_0, 2, true }, #endif - #elif SERIAL_PORT == 1 + #endif + + #if CONF_SERIAL_IS(1) #if EITHER(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) { RXD_NAME_1, 19, true }, { TXD_NAME_1, 18, true }, @@ -135,7 +124,9 @@ const PinInfo pin_array[] PROGMEM = { { TXD_NAME_1, 15, true }, #endif #endif - #elif SERIAL_PORT == 2 + #endif + + #if CONF_SERIAL_IS(2) #if EITHER(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) { RXD_NAME_2, 17, true }, { TXD_NAME_2, 16, true }, @@ -148,7 +139,9 @@ const PinInfo pin_array[] PROGMEM = { { TXD_NAME_2, 10, true }, #endif #endif - #elif SERIAL_PORT == 3 + #endif + + #if CONF_SERIAL_IS(3) #if EITHER(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) { RXD_NAME_3, 15, true }, { TXD_NAME_3, 14, true }, @@ -166,68 +159,8 @@ const PinInfo pin_array[] PROGMEM = { #endif #endif - #ifdef SERIAL_PORT_2 - #if SERIAL_PORT_2 == 0 - #if EITHER(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) - { RXD_NAME_0, 0, true }, - { TXD_NAME_0, 1, true }, - #elif AVR_ATmega1284_FAMILY - { RXD_NAME_0, 8, true }, - { TXD_NAME_0, 9, true }, - #elif defined(TARGET_LPC1768) // TX P0_02 RX P0_03 - { RXD_NAME_0, 3, true }, - { TXD_NAME_0, 2, true }, - #endif - #elif SERIAL_PORT_2 == 1 - #if EITHER(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) - { RXD_NAME_1, 19, true }, - { TXD_NAME_1, 18, true }, - #elif AVR_ATmega1284_FAMILY - { RXD_NAME_1, 10, true }, - { TXD_NAME_1, 11, true }, - #elif defined(TARGET_LPC1768) - #ifdef LPC_PINCFG_UART1_P2_00 // TX P2_00 RX P2_01 - { RXD_NAME_1, 0x41, true }, - { TXD_NAME_1, 0x40, true }, - #else // TX P0_15 RX P0_16 - { RXD_NAME_1, 16, true }, - { TXD_NAME_1, 15, true }, - #endif - #endif - #elif SERIAL_PORT_2 == 2 - #if EITHER(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) - { RXD_NAME_2, 17, true }, - { TXD_NAME_2, 16, true }, - #elif defined(TARGET_LPC1768) - #ifdef LPC_PINCFG_UART2_P2_08 // TX P2_08 RX P2_09 - { RXD_NAME_2, 0x49, true }, - { TXD_NAME_2, 0x48, true }, - #else // TX P0_10 RX P0_11 - { RXD_NAME_2, 11, true }, - { TXD_NAME_2, 10, true }, - #endif - #endif - #elif SERIAL_PORT_2 == 3 - #if EITHER(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) - { RXD_NAME_3, 15, true }, - { TXD_NAME_3, 14, true }, - #elif defined(TARGET_LPC1768) - #ifdef LPC_PINCFG_UART3_P0_25 // TX P0_25 RX P0_26 - { RXD_NAME_3, 0x1A, true }, - { TXD_NAME_3, 0x19, true }, - #elif defined(LPC_PINCFG_UART3_P4_28) // TX P4_28 RX P4_29 - { RXD_NAME_3, 0x9D, true }, - { TXD_NAME_3, 0x9C, true }, - #else // TX P0_00 RX P0_01 - { RXD_NAME_3, 1, true }, - { TXD_NAME_3, 0, true }, - #endif - #endif - #endif - #endif - #include "pinsDebug_list.h" - #line 172 + #line 164 }; @@ -238,7 +171,7 @@ const PinInfo pin_array[] PROGMEM = { #endif static void print_input_or_output(const bool isout) { - serialprintPGM(isout ? PSTR("Output = ") : PSTR("Input = ")); + SERIAL_ECHOPGM_P(isout ? PSTR("Output = ") : PSTR("Input = ")); } // pretty report with PWM info @@ -266,8 +199,8 @@ inline void report_pin_state_extended(pin_t pin, const bool ignore, const bool e LOOP_L_N(x, COUNT(pin_array)) { // 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) serialprintPGM(start_string); - serialprintPGM(PSTR("PIN: ")); + if (start_string) SERIAL_ECHOPGM_P(start_string); + SERIAL_ECHOPGM("PIN: "); PRINT_PIN(pin); PRINT_PORT(pin); if (int8_t(DIGITAL_PIN_TO_ANALOG_PIN(pin)) >= 0) { @@ -317,8 +250,8 @@ inline void report_pin_state_extended(pin_t pin, const bool ignore, const bool e } // end of for loop if (!found) { - if (start_string) serialprintPGM(start_string); - serialprintPGM(PSTR("PIN: ")); + if (start_string) SERIAL_ECHOPGM_P(start_string); + SERIAL_ECHOPGM("PIN: "); PRINT_PIN(pin); PRINT_PORT(pin); if (int8_t(DIGITAL_PIN_TO_ANALOG_PIN(pin)) >= 0) { diff --git a/Marlin/src/pins/pinsDebug_list.h b/Marlin/src/pins/pinsDebug_list.h index 704f2a487fb1..8b1cad3a7c97 100644 --- a/Marlin/src/pins/pinsDebug_list.h +++ b/Marlin/src/pins/pinsDebug_list.h @@ -91,6 +91,9 @@ #if PIN_EXISTS(TEMP_CHAMBER) && ANALOG_OK(TEMP_CHAMBER_PIN) REPORT_NAME_ANALOG(__LINE__, TEMP_CHAMBER_PIN) #endif +#if PIN_EXISTS(TEMP_COOLER) && ANALOG_OK(TEMP_COOLER_PIN) + REPORT_NAME_ANALOG(__LINE__, TEMP_COOLER_PIN) +#endif #if PIN_EXISTS(ADC_KEYPAD) && ANALOG_OK(ADC_KEYPAD_PIN) REPORT_NAME_ANALOG(__LINE__, ADC_KEYPAD_PIN) #endif @@ -147,6 +150,9 @@ #if defined(BTN_EN2) && BTN_EN2 >= 0 REPORT_NAME_DIGITAL(__LINE__, BTN_EN2) #endif +#if defined(BTN_ENC_EN) && BTN_ENC_EN >= 0 + REPORT_NAME_DIGITAL(__LINE__, BTN_ENC_EN) +#endif #if defined(BTN_ENC) && BTN_ENC >= 0 REPORT_NAME_DIGITAL(__LINE__, BTN_ENC) #endif @@ -180,6 +186,81 @@ #if PIN_EXISTS(JOY_EN) REPORT_NAME_DIGITAL(__LINE__, JOY_EN_PIN) #endif +#if PIN_EXISTS(BUTTON1) + REPORT_NAME_DIGITAL(__LINE__, BUTTON1_PIN) +#endif +#if PIN_EXISTS(BUTTON2) + REPORT_NAME_DIGITAL(__LINE__, BUTTON2_PIN) +#endif +#if PIN_EXISTS(BUTTON3) + REPORT_NAME_DIGITAL(__LINE__, BUTTON3_PIN) +#endif +#if PIN_EXISTS(BUTTON4) + REPORT_NAME_DIGITAL(__LINE__, BUTTON4_PIN) +#endif +#if PIN_EXISTS(BUTTON5) + REPORT_NAME_DIGITAL(__LINE__, BUTTON5_PIN) +#endif +#if PIN_EXISTS(BUTTON6) + REPORT_NAME_DIGITAL(__LINE__, BUTTON6_PIN) +#endif +#if PIN_EXISTS(BUTTON7) + REPORT_NAME_DIGITAL(__LINE__, BUTTON7_PIN) +#endif +#if PIN_EXISTS(BUTTON8) + REPORT_NAME_DIGITAL(__LINE__, BUTTON8_PIN) +#endif +#if PIN_EXISTS(BUTTON9) + REPORT_NAME_DIGITAL(__LINE__, BUTTON9_PIN) +#endif +#if PIN_EXISTS(BUTTON10) + REPORT_NAME_DIGITAL(__LINE__, BUTTON10_PIN) +#endif +#if PIN_EXISTS(BUTTON11) + REPORT_NAME_DIGITAL(__LINE__, BUTTON11_PIN) +#endif +#if PIN_EXISTS(BUTTON12) + REPORT_NAME_DIGITAL(__LINE__, BUTTON12_PIN) +#endif +#if PIN_EXISTS(BUTTON13) + REPORT_NAME_DIGITAL(__LINE__, BUTTON13_PIN) +#endif +#if PIN_EXISTS(BUTTON14) + REPORT_NAME_DIGITAL(__LINE__, BUTTON14_PIN) +#endif +#if PIN_EXISTS(BUTTON15) + REPORT_NAME_DIGITAL(__LINE__, BUTTON15_PIN) +#endif +#if PIN_EXISTS(BUTTON16) + REPORT_NAME_DIGITAL(__LINE__, BUTTON16_PIN) +#endif +#if PIN_EXISTS(BUTTON17) + REPORT_NAME_DIGITAL(__LINE__, BUTTON17_PIN) +#endif +#if PIN_EXISTS(BUTTON18) + REPORT_NAME_DIGITAL(__LINE__, BUTTON18_PIN) +#endif +#if PIN_EXISTS(BUTTON19) + REPORT_NAME_DIGITAL(__LINE__, BUTTON19_PIN) +#endif +#if PIN_EXISTS(BUTTON20) + REPORT_NAME_DIGITAL(__LINE__, BUTTON20_PIN) +#endif +#if PIN_EXISTS(BUTTON21) + REPORT_NAME_DIGITAL(__LINE__, BUTTON21_PIN) +#endif +#if PIN_EXISTS(BUTTON22) + REPORT_NAME_DIGITAL(__LINE__, BUTTON22_PIN) +#endif +#if PIN_EXISTS(BUTTON23) + REPORT_NAME_DIGITAL(__LINE__, BUTTON23_PIN) +#endif +#if PIN_EXISTS(BUTTON24) + REPORT_NAME_DIGITAL(__LINE__, BUTTON24_PIN) +#endif +#if PIN_EXISTS(BUTTON25) + REPORT_NAME_DIGITAL(__LINE__, BUTTON25_PIN) +#endif #if PIN_EXISTS(CASE_LIGHT) REPORT_NAME_DIGITAL(__LINE__, CASE_LIGHT_PIN) #endif @@ -628,6 +709,9 @@ #if PIN_EXISTS(HEATER_CHAMBER) REPORT_NAME_DIGITAL(__LINE__, HEATER_CHAMBER_PIN) #endif +#if PIN_EXISTS(COOLER) + REPORT_NAME_DIGITAL(__LINE__, COOLER_PIN) +#endif #if PIN_EXISTS(HOME) REPORT_NAME_DIGITAL(__LINE__, HOME_PIN) #endif @@ -637,9 +721,12 @@ #if PIN_EXISTS(I2C_SDA) REPORT_NAME_DIGITAL(__LINE__, I2C_SDA_PIN) #endif -#if PIN_EXISTS(KILL) +#if HAS_KILL REPORT_NAME_DIGITAL(__LINE__, KILL_PIN) #endif +#if HAS_FREEZE_PIN + REPORT_NAME_DIGITAL(__LINE__, FREEZE_PIN) +#endif #if PIN_EXISTS(LCD_BACKLIGHT) REPORT_NAME_DIGITAL(__LINE__, LCD_BACKLIGHT_PIN) #endif @@ -673,17 +760,29 @@ #if PIN_EXISTS(LED_RED) REPORT_NAME_DIGITAL(__LINE__, LED_RED_PIN) #endif -#if PIN_EXISTS(MAX6675_DO) - REPORT_NAME_DIGITAL(__LINE__, MAX6675_DO_PIN) +#if PIN_EXISTS(TEMP_0_CS) + REPORT_NAME_DIGITAL(__LINE__, TEMP_0_CS_PIN) +#endif +#if PIN_EXISTS(TEMP_0_SCK) + REPORT_NAME_DIGITAL(__LINE__, TEMP_0_SCK_PIN) +#endif +#if PIN_EXISTS(TEMP_0_MOSI) + REPORT_NAME_DIGITAL(__LINE__, TEMP_0_MOSI_PIN) #endif -#if PIN_EXISTS(MAX6675_SCK) - REPORT_NAME_DIGITAL(__LINE__, MAX6675_SCK_PIN) +#if PIN_EXISTS(TEMP_0_MISO) + REPORT_NAME_DIGITAL(__LINE__, TEMP_0_MISO_PIN) #endif -#if PIN_EXISTS(MAX6675_SS) - REPORT_NAME_DIGITAL(__LINE__, MAX6675_SS_PIN) +#if PIN_EXISTS(TEMP_1_CS) + REPORT_NAME_DIGITAL(__LINE__, TEMP_1_CS_PIN) #endif -#if PIN_EXISTS(MAX6675_SS2) - REPORT_NAME_DIGITAL(__LINE__, MAX6675_SS2_PIN) +#if PIN_EXISTS(TEMP_1_SCK) + REPORT_NAME_DIGITAL(__LINE__, TEMP_1_SCK_PIN) +#endif +#if PIN_EXISTS(TEMP_1_MOSI) + REPORT_NAME_DIGITAL(__LINE__, TEMP_1_MOSI_PIN) +#endif +#if PIN_EXISTS(TEMP_1_MISO) + REPORT_NAME_DIGITAL(__LINE__, TEMP_1_MISO_PIN) #endif #if PIN_EXISTS(MAX7219_CLK) REPORT_NAME_DIGITAL(__LINE__, MAX7219_CLK_PIN) @@ -699,7 +798,7 @@ // REPORT_NAME_DIGITAL(__LINE__, MISO) // #endif #if PIN_EXISTS(MISO) - REPORT_NAME_DIGITAL(__LINE__, MISO_PIN) + REPORT_NAME_DIGITAL(__LINE__, SD_MISO_PIN) #endif #if PIN_EXISTS(MOSFET_A) REPORT_NAME_DIGITAL(__LINE__, MOSFET_A_PIN) @@ -717,7 +816,7 @@ // REPORT_NAME_DIGITAL(__LINE__, MOSI) // #endif #if PIN_EXISTS(MOSI) - REPORT_NAME_DIGITAL(__LINE__, MOSI_PIN) + REPORT_NAME_DIGITAL(__LINE__, SD_MOSI_PIN) #endif #if PIN_EXISTS(MOTOR_CURRENT_PWM_E) REPORT_NAME_DIGITAL(__LINE__, MOTOR_CURRENT_PWM_E_PIN) @@ -798,7 +897,7 @@ // REPORT_NAME_DIGITAL(__LINE__, SCK) // #endif #if PIN_EXISTS(SCK) - REPORT_NAME_DIGITAL(__LINE__, SCK_PIN) + REPORT_NAME_DIGITAL(__LINE__, SD_SCK_PIN) #endif // #if defined(SCL) && SCL >= 0 // REPORT_NAME_DIGITAL(__LINE__, SCL) @@ -830,17 +929,17 @@ #if PIN_EXISTS(SERVO3) REPORT_NAME_DIGITAL(__LINE__, SERVO3_PIN) #endif -#if defined(SHIFT_CLK) && SHIFT_CLK >= 0 - REPORT_NAME_DIGITAL(__LINE__, SHIFT_CLK) +#if PIN_EXISTS(SHIFT_CLK) + REPORT_NAME_DIGITAL(__LINE__, SHIFT_CLK_PIN) #endif -#if defined(SHIFT_EN) && SHIFT_EN >= 0 - REPORT_NAME_DIGITAL(__LINE__, SHIFT_EN) +#if PIN_EXISTS(SHIFT_EN) + REPORT_NAME_DIGITAL(__LINE__, SHIFT_EN_PIN) #endif -#if defined(SHIFT_LD) && SHIFT_LD >= 0 - REPORT_NAME_DIGITAL(__LINE__, SHIFT_LD) +#if PIN_EXISTS(SHIFT_LD) + REPORT_NAME_DIGITAL(__LINE__, SHIFT_LD_PIN) #endif -#if defined(SHIFT_OUT) && SHIFT_OUT >= 0 - REPORT_NAME_DIGITAL(__LINE__, SHIFT_OUT) +#if PIN_EXISTS(SHIFT_OUT) + REPORT_NAME_DIGITAL(__LINE__, SHIFT_OUT_PIN) #endif #if PIN_EXISTS(SLED) REPORT_NAME_DIGITAL(__LINE__, SLED_PIN) @@ -906,7 +1005,7 @@ REPORT_NAME_DIGITAL(__LINE__, SR_STROBE_PIN) #endif #if PIN_EXISTS(SS) - REPORT_NAME_DIGITAL(__LINE__, SS_PIN) + REPORT_NAME_DIGITAL(__LINE__, SD_SS_PIN) #endif #if PIN_EXISTS(STAT_LED_BLUE) REPORT_NAME_DIGITAL(__LINE__, STAT_LED_BLUE_PIN) @@ -923,18 +1022,6 @@ #if PIN_EXISTS(SUICIDE) REPORT_NAME_DIGITAL(__LINE__, SUICIDE_PIN) #endif -#if PIN_EXISTS(THERMO_CS1) - REPORT_NAME_DIGITAL(__LINE__, THERMO_CS1_PIN) -#endif -#if PIN_EXISTS(THERMO_CS2) - REPORT_NAME_DIGITAL(__LINE__, THERMO_CS2_PIN) -#endif -#if PIN_EXISTS(THERMO_DO) - REPORT_NAME_DIGITAL(__LINE__, THERMO_DO_PIN) -#endif -#if PIN_EXISTS(THERMO_SCK) - REPORT_NAME_DIGITAL(__LINE__, THERMO_SCK_PIN) -#endif #if PIN_EXISTS(TLC_BLANK) REPORT_NAME_DIGITAL(__LINE__, TLC_BLANK_PIN) #endif @@ -1232,6 +1319,105 @@ #if PIN_EXISTS(Z_MIN_PROBE) REPORT_NAME_DIGITAL(__LINE__, Z_MIN_PROBE_PIN) #endif +#if PIN_EXISTS(I_ATT) + REPORT_NAME_DIGITAL(__LINE__, I_ATT_PIN) +#endif +#if PIN_EXISTS(I_CS) + REPORT_NAME_DIGITAL(__LINE__, I_CS_PIN) +#endif +#if PIN_EXISTS(I_DIR) + REPORT_NAME_DIGITAL(__LINE__, I_DIR_PIN) +#endif +#if PIN_EXISTS(I_ENABLE) + REPORT_NAME_DIGITAL(__LINE__, I_ENABLE_PIN) +#endif +#if PIN_EXISTS(I_MAX) + REPORT_NAME_DIGITAL(__LINE__, I_MAX_PIN) +#endif +#if PIN_EXISTS(I_MIN) + REPORT_NAME_DIGITAL(__LINE__, I_MIN_PIN) +#endif +#if PIN_EXISTS(I_MS1) + REPORT_NAME_DIGITAL(__LINE__, I_MS1_PIN) +#endif +#if PIN_EXISTS(I_MS2) + REPORT_NAME_DIGITAL(__LINE__, I_MS2_PIN) +#endif +#if PIN_EXISTS(I_MS3) + REPORT_NAME_DIGITAL(__LINE__, I_MS3_PIN) +#endif +#if PIN_EXISTS(I_STEP) + REPORT_NAME_DIGITAL(__LINE__, I_STEP_PIN) +#endif +#if PIN_EXISTS(I_STOP) + REPORT_NAME_DIGITAL(__LINE__, I_STOP_PIN) +#endif +#if PIN_EXISTS(J_ATT) + REPORT_NAME_DIGITAL(__LINE__, J_ATT_PIN) +#endif +#if PIN_EXISTS(J_CS) + REPORT_NAME_DIGITAL(__LINE__, J_CS_PIN) +#endif +#if PIN_EXISTS(J_DIR) + REPORT_NAME_DIGITAL(__LINE__, J_DIR_PIN) +#endif +#if PIN_EXISTS(J_ENABLE) + REPORT_NAME_DIGITAL(__LINE__, J_ENABLE_PIN) +#endif +#if PIN_EXISTS(J_MAX) + REPORT_NAME_DIGITAL(__LINE__, J_MAX_PIN) +#endif +#if PIN_EXISTS(J_MIN) + REPORT_NAME_DIGITAL(__LINE__, J_MIN_PIN) +#endif +#if PIN_EXISTS(J_MS1) + REPORT_NAME_DIGITAL(__LINE__, J_MS1_PIN) +#endif +#if PIN_EXISTS(J_MS2) + REPORT_NAME_DIGITAL(__LINE__, J_MS2_PIN) +#endif +#if PIN_EXISTS(J_MS3) + REPORT_NAME_DIGITAL(__LINE__, J_MS3_PIN) +#endif +#if PIN_EXISTS(J_STEP) + REPORT_NAME_DIGITAL(__LINE__, J_STEP_PIN) +#endif +#if PIN_EXISTS(J_STOP) + REPORT_NAME_DIGITAL(__LINE__, J_STOP_PIN) +#endif +#if PIN_EXISTS(K_ATT) + REPORT_NAME_DIGITAL(__LINE__, K_ATT_PIN) +#endif +#if PIN_EXISTS(K_CS) + REPORT_NAME_DIGITAL(__LINE__, K_CS_PIN) +#endif +#if PIN_EXISTS(K_DIR) + REPORT_NAME_DIGITAL(__LINE__, K_DIR_PIN) +#endif +#if PIN_EXISTS(K_ENABLE) + REPORT_NAME_DIGITAL(__LINE__, K_ENABLE_PIN) +#endif +#if PIN_EXISTS(K_MAX) + REPORT_NAME_DIGITAL(__LINE__, K_MAX_PIN) +#endif +#if PIN_EXISTS(K_MIN) + REPORT_NAME_DIGITAL(__LINE__, K_MIN_PIN) +#endif +#if PIN_EXISTS(K_MS1) + REPORT_NAME_DIGITAL(__LINE__, K_MS1_PIN) +#endif +#if PIN_EXISTS(K_MS2) + REPORT_NAME_DIGITAL(__LINE__, K_MS2_PIN) +#endif +#if PIN_EXISTS(K_MS3) + REPORT_NAME_DIGITAL(__LINE__, K_MS3_PIN) +#endif +#if PIN_EXISTS(K_STEP) + REPORT_NAME_DIGITAL(__LINE__, K_STEP_PIN) +#endif +#if PIN_EXISTS(K_STOP) + REPORT_NAME_DIGITAL(__LINE__, K_STOP_PIN) +#endif #if PIN_EXISTS(ZRIB_V20_D6) REPORT_NAME_DIGITAL(__LINE__, ZRIB_V20_D6_PIN) #endif diff --git a/Marlin/src/pins/pins_postprocess.h b/Marlin/src/pins/pins_postprocess.h new file mode 100644 index 000000000000..f7152770e5b5 --- /dev/null +++ b/Marlin/src/pins/pins_postprocess.h @@ -0,0 +1,1248 @@ +/** + * 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 + +// +// File: pins/pins_postprocess.h +// Post-process pins according to configured settings +// + +// Define certain undefined pins +#ifndef X_MS1_PIN + #define X_MS1_PIN -1 +#endif +#ifndef X_MS2_PIN + #define X_MS2_PIN -1 +#endif +#ifndef X_MS3_PIN + #define X_MS3_PIN -1 +#endif +#ifndef Y_MS1_PIN + #define Y_MS1_PIN -1 +#endif +#ifndef Y_MS2_PIN + #define Y_MS2_PIN -1 +#endif +#ifndef Y_MS3_PIN + #define Y_MS3_PIN -1 +#endif +#ifndef Z_MS1_PIN + #define Z_MS1_PIN -1 +#endif +#ifndef Z_MS2_PIN + #define Z_MS2_PIN -1 +#endif +#ifndef Z_MS3_PIN + #define Z_MS3_PIN -1 +#endif +#ifndef E0_MS1_PIN + #define E0_MS1_PIN -1 +#endif +#ifndef E0_MS2_PIN + #define E0_MS2_PIN -1 +#endif +#ifndef E0_MS3_PIN + #define E0_MS3_PIN -1 +#endif +#ifndef E1_MS1_PIN + #define E1_MS1_PIN -1 +#endif +#ifndef E1_MS2_PIN + #define E1_MS2_PIN -1 +#endif +#ifndef E1_MS3_PIN + #define E1_MS3_PIN -1 +#endif +#ifndef E2_MS1_PIN + #define E2_MS1_PIN -1 +#endif +#ifndef E2_MS2_PIN + #define E2_MS2_PIN -1 +#endif +#ifndef E2_MS3_PIN + #define E2_MS3_PIN -1 +#endif +#ifndef E3_MS1_PIN + #define E3_MS1_PIN -1 +#endif +#ifndef E3_MS2_PIN + #define E3_MS2_PIN -1 +#endif +#ifndef E3_MS3_PIN + #define E3_MS3_PIN -1 +#endif +#ifndef E4_MS1_PIN + #define E4_MS1_PIN -1 +#endif +#ifndef E4_MS2_PIN + #define E4_MS2_PIN -1 +#endif +#ifndef E4_MS3_PIN + #define E4_MS3_PIN -1 +#endif +#ifndef E5_MS1_PIN + #define E5_MS1_PIN -1 +#endif +#ifndef E5_MS2_PIN + #define E5_MS2_PIN -1 +#endif +#ifndef E5_MS3_PIN + #define E5_MS3_PIN -1 +#endif +#ifndef E6_MS1_PIN + #define E6_MS1_PIN -1 +#endif +#ifndef E6_MS2_PIN + #define E6_MS2_PIN -1 +#endif +#ifndef E6_MS3_PIN + #define E6_MS3_PIN -1 +#endif +#ifndef E7_MS1_PIN + #define E7_MS1_PIN -1 +#endif +#ifndef E7_MS2_PIN + #define E7_MS2_PIN -1 +#endif +#ifndef E7_MS3_PIN + #define E7_MS3_PIN -1 +#endif + +#ifndef E0_STEP_PIN + #define E0_STEP_PIN -1 +#endif +#ifndef E0_DIR_PIN + #define E0_DIR_PIN -1 +#endif +#ifndef E0_ENABLE_PIN + #define E0_ENABLE_PIN -1 +#endif +#ifndef E1_STEP_PIN + #define E1_STEP_PIN -1 +#endif +#ifndef E1_DIR_PIN + #define E1_DIR_PIN -1 +#endif +#ifndef E1_ENABLE_PIN + #define E1_ENABLE_PIN -1 +#endif +#ifndef E2_STEP_PIN + #define E2_STEP_PIN -1 +#endif +#ifndef E2_DIR_PIN + #define E2_DIR_PIN -1 +#endif +#ifndef E2_ENABLE_PIN + #define E2_ENABLE_PIN -1 +#endif +#ifndef E3_STEP_PIN + #define E3_STEP_PIN -1 +#endif +#ifndef E3_DIR_PIN + #define E3_DIR_PIN -1 +#endif +#ifndef E3_ENABLE_PIN + #define E3_ENABLE_PIN -1 +#endif +#ifndef E4_STEP_PIN + #define E4_STEP_PIN -1 +#endif +#ifndef E4_DIR_PIN + #define E4_DIR_PIN -1 +#endif +#ifndef E4_ENABLE_PIN + #define E4_ENABLE_PIN -1 +#endif +#ifndef E5_STEP_PIN + #define E5_STEP_PIN -1 +#endif +#ifndef E5_DIR_PIN + #define E5_DIR_PIN -1 +#endif +#ifndef E5_ENABLE_PIN + #define E5_ENABLE_PIN -1 +#endif +#ifndef E6_STEP_PIN + #define E6_STEP_PIN -1 +#endif +#ifndef E6_DIR_PIN + #define E6_DIR_PIN -1 +#endif +#ifndef E6_ENABLE_PIN + #define E6_ENABLE_PIN -1 +#endif +#ifndef E7_STEP_PIN + #define E7_STEP_PIN -1 +#endif +#ifndef E7_DIR_PIN + #define E7_DIR_PIN -1 +#endif +#ifndef E7_ENABLE_PIN + #define E7_ENABLE_PIN -1 +#endif + +// +// Destroy unused CS pins +// +#if !AXIS_HAS_SPI(X) + #undef X_CS_PIN +#endif +#if !AXIS_HAS_SPI(Y) + #undef Y_CS_PIN +#endif +#if !AXIS_HAS_SPI(Z) + #undef Z_CS_PIN +#endif +#if !AXIS_HAS_SPI(I) + #undef I_CS_PIN +#endif +#if !AXIS_HAS_SPI(J) + #undef J_CS_PIN +#endif +#if !AXIS_HAS_SPI(K) + #undef K_CS_PIN +#endif +#if E_STEPPERS && !AXIS_HAS_SPI(E0) + #undef E0_CS_PIN +#endif +#if E_STEPPERS > 1 && !AXIS_HAS_SPI(E1) + #undef E1_CS_PIN +#endif +#if E_STEPPERS > 2 && !AXIS_HAS_SPI(E2) + #undef E2_CS_PIN +#endif +#if E_STEPPERS > 3 && !AXIS_HAS_SPI(E3) + #undef E3_CS_PIN +#endif +#if E_STEPPERS > 4 && !AXIS_HAS_SPI(E4) + #undef E4_CS_PIN +#endif +#if E_STEPPERS > 5 && !AXIS_HAS_SPI(E5) + #undef E5_CS_PIN +#endif +#if E_STEPPERS > 6 && !AXIS_HAS_SPI(E6) + #undef E6_CS_PIN +#endif +#if E_STEPPERS > 7 && !AXIS_HAS_SPI(E7) + #undef E7_CS_PIN +#endif + +#ifndef X_CS_PIN + #define X_CS_PIN -1 +#endif +#ifndef Y_CS_PIN + #define Y_CS_PIN -1 +#endif +#ifndef Z_CS_PIN + #define Z_CS_PIN -1 +#endif +#ifndef I_CS_PIN + #define I_CS_PIN -1 +#endif +#ifndef J_CS_PIN + #define J_CS_PIN -1 +#endif +#ifndef K_CS_PIN + #define K_CS_PIN -1 +#endif +#ifndef E0_CS_PIN + #define E0_CS_PIN -1 +#endif +#ifndef E1_CS_PIN + #define E1_CS_PIN -1 +#endif +#ifndef E2_CS_PIN + #define E2_CS_PIN -1 +#endif +#ifndef E3_CS_PIN + #define E3_CS_PIN -1 +#endif +#ifndef E4_CS_PIN + #define E4_CS_PIN -1 +#endif +#ifndef E5_CS_PIN + #define E5_CS_PIN -1 +#endif +#ifndef E6_CS_PIN + #define E6_CS_PIN -1 +#endif +#ifndef E7_CS_PIN + #define E7_CS_PIN -1 +#endif + +#ifndef FAN_PIN + #define FAN_PIN -1 +#endif +#define FAN0_PIN FAN_PIN +#ifndef FAN1_PIN + #define FAN1_PIN -1 +#endif +#ifndef FAN2_PIN + #define FAN2_PIN -1 +#endif +#ifndef CONTROLLER_FAN_PIN + #define CONTROLLER_FAN_PIN -1 +#endif + +#ifndef FANMUX0_PIN + #define FANMUX0_PIN -1 +#endif +#ifndef FANMUX1_PIN + #define FANMUX1_PIN -1 +#endif +#ifndef FANMUX2_PIN + #define FANMUX2_PIN -1 +#endif + +#ifndef HEATER_0_PIN + #define HEATER_0_PIN -1 +#endif +#ifndef HEATER_1_PIN + #define HEATER_1_PIN -1 +#endif +#ifndef HEATER_2_PIN + #define HEATER_2_PIN -1 +#endif +#ifndef HEATER_3_PIN + #define HEATER_3_PIN -1 +#endif +#ifndef HEATER_4_PIN + #define HEATER_4_PIN -1 +#endif +#ifndef HEATER_5_PIN + #define HEATER_5_PIN -1 +#endif +#ifndef HEATER_6_PIN + #define HEATER_6_PIN -1 +#endif +#ifndef HEATER_7_PIN + #define HEATER_7_PIN -1 +#endif +#ifndef HEATER_BED_PIN + #define HEATER_BED_PIN -1 +#endif + +#ifndef TEMP_0_PIN + #define TEMP_0_PIN -1 +#endif +#ifndef TEMP_1_PIN + #define TEMP_1_PIN -1 +#endif +#ifndef TEMP_2_PIN + #define TEMP_2_PIN -1 +#endif +#ifndef TEMP_3_PIN + #define TEMP_3_PIN -1 +#endif +#ifndef TEMP_4_PIN + #define TEMP_4_PIN -1 +#endif +#ifndef TEMP_5_PIN + #define TEMP_5_PIN -1 +#endif +#ifndef TEMP_6_PIN + #define TEMP_6_PIN -1 +#endif +#ifndef TEMP_7_PIN + #define TEMP_7_PIN -1 +#endif +#ifndef TEMP_BED_PIN + #define TEMP_BED_PIN -1 +#endif + +#ifndef SD_DETECT_PIN + #define SD_DETECT_PIN -1 +#endif +#ifndef SDPOWER_PIN + #define SDPOWER_PIN -1 +#endif +#ifndef SDSS + #define SDSS -1 +#endif +#ifndef LED_PIN + #define LED_PIN -1 +#endif +#if DISABLED(PSU_CONTROL) || !defined(PS_ON_PIN) + #undef PS_ON_PIN + #define PS_ON_PIN -1 +#endif +#ifndef KILL_PIN + #define KILL_PIN -1 +#endif +#ifndef SUICIDE_PIN + #define SUICIDE_PIN -1 +#endif +#ifndef SUICIDE_PIN_INVERTING + #define SUICIDE_PIN_INVERTING false +#endif + +#ifndef NUM_SERVO_PLUGS + #define NUM_SERVO_PLUGS 4 +#endif + +// +// Assign endstop pins for boards with only 3 connectors +// +#ifdef X_STOP_PIN + #if X_HOME_TO_MIN + #define X_MIN_PIN X_STOP_PIN + #ifndef X_MAX_PIN + #define X_MAX_PIN -1 + #endif + #else + #define X_MAX_PIN X_STOP_PIN + #ifndef X_MIN_PIN + #define X_MIN_PIN -1 + #endif + #endif +#elif X_HOME_TO_MIN + #define X_STOP_PIN X_MIN_PIN +#else + #define X_STOP_PIN X_MAX_PIN +#endif + +#if HAS_Y_AXIS + #ifdef Y_STOP_PIN + #if Y_HOME_TO_MIN + #define Y_MIN_PIN Y_STOP_PIN + #ifndef Y_MAX_PIN + #define Y_MAX_PIN -1 + #endif + #else + #define Y_MAX_PIN Y_STOP_PIN + #ifndef Y_MIN_PIN + #define Y_MIN_PIN -1 + #endif + #endif + #elif Y_HOME_TO_MIN + #define Y_STOP_PIN Y_MIN_PIN + #else + #define Y_STOP_PIN Y_MAX_PIN + #endif +#endif + +#if HAS_Z_AXIS + #ifdef Z_STOP_PIN + #if Z_HOME_TO_MIN + #define Z_MIN_PIN Z_STOP_PIN + #ifndef Z_MAX_PIN + #define Z_MAX_PIN -1 + #endif + #else + #define Z_MAX_PIN Z_STOP_PIN + #ifndef Z_MIN_PIN + #define Z_MIN_PIN -1 + #endif + #endif + #elif Z_HOME_TO_MIN + #define Z_STOP_PIN Z_MIN_PIN + #else + #define Z_STOP_PIN Z_MAX_PIN + #endif +#endif + +#if LINEAR_AXES >= 4 + #ifdef I_STOP_PIN + #if I_HOME_TO_MIN + #define I_MIN_PIN I_STOP_PIN + #define I_MAX_PIN -1 + #else + #define I_MIN_PIN -1 + #define I_MAX_PIN I_STOP_PIN + #endif + #endif +#else + #undef I_MIN_PIN + #undef I_MAX_PIN +#endif + +#if LINEAR_AXES >= 5 + #ifdef J_STOP_PIN + #if J_HOME_TO_MIN + #define J_MIN_PIN J_STOP_PIN + #define J_MAX_PIN -1 + #else + #define J_MIN_PIN -1 + #define J_MAX_PIN J_STOP_PIN + #endif + #endif +#else + #undef J_MIN_PIN + #undef J_MAX_PIN +#endif + +#if LINEAR_AXES >= 6 + #ifdef K_STOP_PIN + #if K_HOME_TO_MIN + #define K_MIN_PIN K_STOP_PIN + #define K_MAX_PIN -1 + #else + #define K_MIN_PIN -1 + #define K_MAX_PIN K_STOP_PIN + #endif + #endif +#else + #undef K_MIN_PIN + #undef K_MAX_PIN +#endif + +// Filament Sensor first pin alias +#if HAS_FILAMENT_SENSOR + #define FIL_RUNOUT1_PIN FIL_RUNOUT_PIN +#else + #undef FIL_RUNOUT_PIN + #undef FIL_RUNOUT1_PIN +#endif + +#ifndef LCD_PINS_D4 + #define LCD_PINS_D4 -1 +#endif + +#if HAS_MARLINUI_HD44780 || TOUCH_UI_ULTIPANEL + #ifndef LCD_PINS_D5 + #define LCD_PINS_D5 -1 + #endif + #ifndef LCD_PINS_D6 + #define LCD_PINS_D6 -1 + #endif + #ifndef LCD_PINS_D7 + #define LCD_PINS_D7 -1 + #endif +#endif + +/** + * Auto-Assignment for Dual X, Dual Y, Multi-Z Steppers + * + * By default X2 is assigned to the next open E plug + * on the board, then in order, Y2, Z2, Z3. These can be + * overridden in Configuration.h or Configuration_adv.h. + */ + +#define __PEXI(p,q) PIN_EXISTS(E##p##_##q) +#define _PEXI(p,q) __PEXI(p,q) +#define __EPIN(p,q) E##p##_##q##_PIN +#define _EPIN(p,q) __EPIN(p,q) +#define DIAG_REMAPPED(p,q) (PIN_EXISTS(q) && _EPIN(p##_E_INDEX, DIAG) == q##_PIN) + +// The E0/E1 steppers are always used for Dual E +#if ENABLED(E_DUAL_STEPPER_DRIVERS) + #ifndef E1_STEP_PIN + #error "No E1 stepper available for E_DUAL_STEPPER_DRIVERS!" + #endif + #define X2_E_INDEX INCREMENT(E_STEPPERS) +#else + #define X2_E_INDEX E_STEPPERS +#endif + +// The X2 axis, if any, should be the next open extruder port +#if EITHER(DUAL_X_CARRIAGE, X_DUAL_STEPPER_DRIVERS) + #ifndef X2_STEP_PIN + #define X2_STEP_PIN _EPIN(X2_E_INDEX, STEP) + #define X2_DIR_PIN _EPIN(X2_E_INDEX, DIR) + #define X2_ENABLE_PIN _EPIN(X2_E_INDEX, ENABLE) + #if X2_E_INDEX >= MAX_E_STEPPERS || !PIN_EXISTS(X2_STEP) + #error "No E stepper plug left for X2!" + #endif + #endif + #ifndef X2_MS1_PIN + #define X2_MS1_PIN _EPIN(X2_E_INDEX, MS1) + #endif + #ifndef X2_MS2_PIN + #define X2_MS2_PIN _EPIN(X2_E_INDEX, MS2) + #endif + #ifndef X2_MS3_PIN + #define X2_MS3_PIN _EPIN(X2_E_INDEX, MS3) + #endif + #if AXIS_HAS_SPI(X2) && !defined(X2_CS_PIN) + #define X2_CS_PIN _EPIN(X2_E_INDEX, CS) + #endif + #if AXIS_HAS_UART(X2) + #ifndef X2_SERIAL_TX_PIN + #define X2_SERIAL_TX_PIN _EPIN(X2_E_INDEX, SERIAL_TX) + #endif + #ifndef X2_SERIAL_RX_PIN + #define X2_SERIAL_RX_PIN _EPIN(X2_E_INDEX, SERIAL_RX) + #endif + #endif + + // + // Auto-assign pins for stallGuard sensorless homing + // + #if !defined(X2_USE_ENDSTOP) && defined(X2_STALL_SENSITIVITY) && ENABLED(X_DUAL_ENDSTOPS) && _PEXI(X2_E_INDEX, DIAG) + #define X2_DIAG_PIN _EPIN(X2_E_INDEX, DIAG) + #if DIAG_REMAPPED(X2, X_MIN) // If already remapped in the pins file... + #define X2_USE_ENDSTOP _XMIN_ + #elif DIAG_REMAPPED(X2, Y_MIN) + #define X2_USE_ENDSTOP _YMIN_ + #elif DIAG_REMAPPED(X2, Z_MIN) + #define X2_USE_ENDSTOP _ZMIN_ + #elif DIAG_REMAPPED(X2, X_MAX) + #define X2_USE_ENDSTOP _XMAX_ + #elif DIAG_REMAPPED(X2, Y_MAX) + #define X2_USE_ENDSTOP _YMAX_ + #elif DIAG_REMAPPED(X2, Z_MAX) + #define X2_USE_ENDSTOP _ZMAX_ + #else // Otherwise use the driver DIAG_PIN directly + #define _X2_USE_ENDSTOP(P) _E##P##_DIAG_ + #define X2_USE_ENDSTOP _X2_USE_ENDSTOP(X2_E_INDEX) + #endif + #undef X2_DIAG_PIN + #endif + + #define Y2_E_INDEX INCREMENT(X2_E_INDEX) +#else + #define Y2_E_INDEX X2_E_INDEX +#endif + +#ifndef X2_CS_PIN + #define X2_CS_PIN -1 +#endif +#ifndef X2_MS1_PIN + #define X2_MS1_PIN -1 +#endif +#ifndef X2_MS2_PIN + #define X2_MS2_PIN -1 +#endif +#ifndef X2_MS3_PIN + #define X2_MS3_PIN -1 +#endif + +// The Y2 axis, if any, should be the next open extruder port +#if ENABLED(Y_DUAL_STEPPER_DRIVERS) + #ifndef Y2_STEP_PIN + #define Y2_STEP_PIN _EPIN(Y2_E_INDEX, STEP) + #define Y2_DIR_PIN _EPIN(Y2_E_INDEX, DIR) + #define Y2_ENABLE_PIN _EPIN(Y2_E_INDEX, ENABLE) + #if Y2_E_INDEX >= MAX_E_STEPPERS || !PIN_EXISTS(Y2_STEP) + #error "No E stepper plug left for Y2!" + #endif + #endif + #ifndef Y2_MS1_PIN + #define Y2_MS1_PIN _EPIN(Y2_E_INDEX, MS1) + #endif + #ifndef Y2_MS2_PIN + #define Y2_MS2_PIN _EPIN(Y2_E_INDEX, MS2) + #endif + #ifndef Y2_MS3_PIN + #define Y2_MS3_PIN _EPIN(Y2_E_INDEX, MS3) + #endif + #if AXIS_HAS_SPI(Y2) && !defined(Y2_CS_PIN) + #define Y2_CS_PIN _EPIN(Y2_E_INDEX, CS) + #endif + #if AXIS_HAS_UART(Y2) + #ifndef Y2_SERIAL_TX_PIN + #define Y2_SERIAL_TX_PIN _EPIN(Y2_E_INDEX, SERIAL_TX) + #endif + #ifndef Y2_SERIAL_RX_PIN + #define Y2_SERIAL_RX_PIN _EPIN(Y2_E_INDEX, SERIAL_RX) + #endif + #endif + // Auto-assign pins for stallGuard sensorless homing + #if !defined(Y2_USE_ENDSTOP) && defined(Y2_STALL_SENSITIVITY) && ENABLED(Y_DUAL_ENDSTOPS) && _PEXI(Y2_E_INDEX, DIAG) + #define Y2_DIAG_PIN _EPIN(Y2_E_INDEX, DIAG) + #if DIAG_REMAPPED(Y2, X_MIN) + #define Y2_USE_ENDSTOP _XMIN_ + #elif DIAG_REMAPPED(Y2, Y_MIN) + #define Y2_USE_ENDSTOP _YMIN_ + #elif DIAG_REMAPPED(Y2, Z_MIN) + #define Y2_USE_ENDSTOP _ZMIN_ + #elif DIAG_REMAPPED(Y2, X_MAX) + #define Y2_USE_ENDSTOP _XMAX_ + #elif DIAG_REMAPPED(Y2, Y_MAX) + #define Y2_USE_ENDSTOP _YMAX_ + #elif DIAG_REMAPPED(Y2, Z_MAX) + #define Y2_USE_ENDSTOP _ZMAX_ + #else + #define _Y2_USE_ENDSTOP(P) _E##P##_DIAG_ + #define Y2_USE_ENDSTOP _Y2_USE_ENDSTOP(Y2_E_INDEX) + #endif + #undef Y2_DIAG_PIN + #endif + #define Z2_E_INDEX INCREMENT(Y2_E_INDEX) +#else + #define Z2_E_INDEX Y2_E_INDEX +#endif + +#ifndef Y2_CS_PIN + #define Y2_CS_PIN -1 +#endif +#ifndef Y2_MS1_PIN + #define Y2_MS1_PIN -1 +#endif +#ifndef Y2_MS2_PIN + #define Y2_MS2_PIN -1 +#endif +#ifndef Y2_MS3_PIN + #define Y2_MS3_PIN -1 +#endif + +// The Z2 axis, if any, should be the next open extruder port +#if NUM_Z_STEPPER_DRIVERS >= 2 + #ifndef Z2_STEP_PIN + #define Z2_STEP_PIN _EPIN(Z2_E_INDEX, STEP) + #define Z2_DIR_PIN _EPIN(Z2_E_INDEX, DIR) + #define Z2_ENABLE_PIN _EPIN(Z2_E_INDEX, ENABLE) + #if Z2_E_INDEX >= MAX_E_STEPPERS || !PIN_EXISTS(Z2_STEP) + #error "No E stepper plug left for Z2!" + #endif + #endif + #ifndef Z2_MS1_PIN + #define Z2_MS1_PIN _EPIN(Z2_E_INDEX, MS1) + #endif + #ifndef Z2_MS2_PIN + #define Z2_MS2_PIN _EPIN(Z2_E_INDEX, MS2) + #endif + #ifndef Z2_MS3_PIN + #define Z2_MS3_PIN _EPIN(Z2_E_INDEX, MS3) + #endif + #if AXIS_HAS_SPI(Z2) && !defined(Z2_CS_PIN) + #define Z2_CS_PIN _EPIN(Z2_E_INDEX, CS) + #endif + #if AXIS_HAS_UART(Z2) + #ifndef Z2_SERIAL_TX_PIN + #define Z2_SERIAL_TX_PIN _EPIN(Z2_E_INDEX, SERIAL_TX) + #endif + #ifndef Z2_SERIAL_RX_PIN + #define Z2_SERIAL_RX_PIN _EPIN(Z2_E_INDEX, SERIAL_RX) + #endif + #endif + // Auto-assign pins for stallGuard sensorless homing + #if !defined(Z2_USE_ENDSTOP) && defined(Z2_STALL_SENSITIVITY) && ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 2 && _PEXI(Z2_E_INDEX, DIAG) + #define Z2_DIAG_PIN _EPIN(Z2_E_INDEX, DIAG) + #if DIAG_REMAPPED(Z2, X_MIN) + #define Z2_USE_ENDSTOP _XMIN_ + #elif DIAG_REMAPPED(Z2, Y_MIN) + #define Z2_USE_ENDSTOP _YMIN_ + #elif DIAG_REMAPPED(Z2, Z_MIN) + #define Z2_USE_ENDSTOP _ZMIN_ + #elif DIAG_REMAPPED(Z2, X_MAX) + #define Z2_USE_ENDSTOP _XMAX_ + #elif DIAG_REMAPPED(Z2, Y_MAX) + #define Z2_USE_ENDSTOP _YMAX_ + #elif DIAG_REMAPPED(Z2, Z_MAX) + #define Z2_USE_ENDSTOP _ZMAX_ + #else + #define _Z2_USE_ENDSTOP(P) _E##P##_DIAG_ + #define Z2_USE_ENDSTOP _Z2_USE_ENDSTOP(Z2_E_INDEX) + #endif + #undef Z2_DIAG_PIN + #endif + #define Z3_E_INDEX INCREMENT(Z2_E_INDEX) +#else + #define Z3_E_INDEX Z2_E_INDEX +#endif + +#ifndef Z2_CS_PIN + #define Z2_CS_PIN -1 +#endif +#ifndef Z2_MS1_PIN + #define Z2_MS1_PIN -1 +#endif +#ifndef Z2_MS2_PIN + #define Z2_MS2_PIN -1 +#endif +#ifndef Z2_MS3_PIN + #define Z2_MS3_PIN -1 +#endif + +#if NUM_Z_STEPPER_DRIVERS >= 3 + #ifndef Z3_STEP_PIN + #define Z3_STEP_PIN _EPIN(Z3_E_INDEX, STEP) + #define Z3_DIR_PIN _EPIN(Z3_E_INDEX, DIR) + #define Z3_ENABLE_PIN _EPIN(Z3_E_INDEX, ENABLE) + #if Z3_E_INDEX >= MAX_E_STEPPERS || !PIN_EXISTS(Z3_STEP) + #error "No E stepper plug left for Z3!" + #endif + #endif + #if AXIS_HAS_SPI(Z3) + #ifndef Z3_CS_PIN + #define Z3_CS_PIN _EPIN(Z3_E_INDEX, CS) + #endif + #endif + #ifndef Z3_MS1_PIN + #define Z3_MS1_PIN _EPIN(Z3_E_INDEX, MS1) + #endif + #ifndef Z3_MS2_PIN + #define Z3_MS2_PIN _EPIN(Z3_E_INDEX, MS2) + #endif + #ifndef Z3_MS3_PIN + #define Z3_MS3_PIN _EPIN(Z3_E_INDEX, MS3) + #endif + #if AXIS_HAS_UART(Z3) + #ifndef Z3_SERIAL_TX_PIN + #define Z3_SERIAL_TX_PIN _EPIN(Z3_E_INDEX, SERIAL_TX) + #endif + #ifndef Z3_SERIAL_RX_PIN + #define Z3_SERIAL_RX_PIN _EPIN(Z3_E_INDEX, SERIAL_RX) + #endif + #endif + // Auto-assign pins for stallGuard sensorless homing + #if !defined(Z3_USE_ENDSTOP) && defined(Z3_STALL_SENSITIVITY) && ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 3 && _PEXI(Z3_E_INDEX, DIAG) + #define Z3_DIAG_PIN _EPIN(Z3_E_INDEX, DIAG) + #if DIAG_REMAPPED(Z3, X_MIN) + #define Z3_USE_ENDSTOP _XMIN_ + #elif DIAG_REMAPPED(Z3, Y_MIN) + #define Z3_USE_ENDSTOP _YMIN_ + #elif DIAG_REMAPPED(Z3, Z_MIN) + #define Z3_USE_ENDSTOP _ZMIN_ + #elif DIAG_REMAPPED(Z3, X_MAX) + #define Z3_USE_ENDSTOP _XMAX_ + #elif DIAG_REMAPPED(Z3, Y_MAX) + #define Z3_USE_ENDSTOP _YMAX_ + #elif DIAG_REMAPPED(Z3, Z_MAX) + #define Z3_USE_ENDSTOP _ZMAX_ + #else + #define _Z3_USE_ENDSTOP(P) _E##P##_DIAG_ + #define Z3_USE_ENDSTOP _Z3_USE_ENDSTOP(Z3_E_INDEX) + #endif + #undef Z3_DIAG_PIN + #endif + #define Z4_E_INDEX INCREMENT(Z3_E_INDEX) +#else + #define Z4_E_INDEX Z3_E_INDEX +#endif + +#ifndef Z3_CS_PIN + #define Z3_CS_PIN -1 +#endif +#ifndef Z3_MS1_PIN + #define Z3_MS1_PIN -1 +#endif +#ifndef Z3_MS2_PIN + #define Z3_MS2_PIN -1 +#endif +#ifndef Z3_MS3_PIN + #define Z3_MS3_PIN -1 +#endif + +#if NUM_Z_STEPPER_DRIVERS >= 4 + #ifndef Z4_STEP_PIN + #define Z4_STEP_PIN _EPIN(Z4_E_INDEX, STEP) + #define Z4_DIR_PIN _EPIN(Z4_E_INDEX, DIR) + #define Z4_ENABLE_PIN _EPIN(Z4_E_INDEX, ENABLE) + #if Z4_E_INDEX >= MAX_E_STEPPERS || !PIN_EXISTS(Z4_STEP) + #error "No E stepper plug left for Z4!" + #endif + #endif + #if AXIS_HAS_SPI(Z4) + #ifndef Z4_CS_PIN + #define Z4_CS_PIN _EPIN(Z4_E_INDEX, CS) + #endif + #endif + #ifndef Z4_MS1_PIN + #define Z4_MS1_PIN _EPIN(Z4_E_INDEX, MS1) + #endif + #ifndef Z4_MS2_PIN + #define Z4_MS2_PIN _EPIN(Z4_E_INDEX, MS2) + #endif + #ifndef Z4_MS3_PIN + #define Z4_MS3_PIN _EPIN(Z4_E_INDEX, MS3) + #endif + #if AXIS_HAS_UART(Z4) + #ifndef Z4_SERIAL_TX_PIN + #define Z4_SERIAL_TX_PIN _EPIN(Z4_E_INDEX, SERIAL_TX) + #endif + #ifndef Z4_SERIAL_RX_PIN + #define Z4_SERIAL_RX_PIN _EPIN(Z4_E_INDEX, SERIAL_RX) + #endif + #endif + // Auto-assign pins for stallGuard sensorless homing + #if !defined(Z4_USE_ENDSTOP) && defined(Z4_STALL_SENSITIVITY) && ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4 && _PEXI(Z4_E_INDEX, DIAG) + #define Z4_DIAG_PIN _EPIN(Z4_E_INDEX, DIAG) + #if DIAG_REMAPPED(Z4, X_MIN) + #define Z4_USE_ENDSTOP _XMIN_ + #elif DIAG_REMAPPED(Z4, Y_MIN) + #define Z4_USE_ENDSTOP _YMIN_ + #elif DIAG_REMAPPED(Z4, Z_MIN) + #define Z4_USE_ENDSTOP _ZMIN_ + #elif DIAG_REMAPPED(Z4, X_MAX) + #define Z4_USE_ENDSTOP _XMAX_ + #elif DIAG_REMAPPED(Z4, Y_MAX) + #define Z4_USE_ENDSTOP _YMAX_ + #elif DIAG_REMAPPED(Z4, Z_MAX) + #define Z4_USE_ENDSTOP _ZMAX_ + #else + #define _Z4_USE_ENDSTOP(P) _E##P##_DIAG_ + #define Z4_USE_ENDSTOP _Z4_USE_ENDSTOP(Z4_E_INDEX) + #endif + #undef Z4_DIAG_PIN + #endif + #define I_E_INDEX INCREMENT(Z4_E_INDEX) +#else + #define I_E_INDEX Z4_E_INDEX +#endif + +#ifndef Z4_CS_PIN + #define Z4_CS_PIN -1 +#endif +#ifndef Z4_MS1_PIN + #define Z4_MS1_PIN -1 +#endif +#ifndef Z4_MS2_PIN + #define Z4_MS2_PIN -1 +#endif +#ifndef Z4_MS3_PIN + #define Z4_MS3_PIN -1 +#endif + +#if LINEAR_AXES >= 4 + #ifndef I_STEP_PIN + #define I_STEP_PIN _EPIN(I_E_INDEX, STEP) + #define I_DIR_PIN _EPIN(I_E_INDEX, DIR) + #define I_ENABLE_PIN _EPIN(I_E_INDEX, ENABLE) + #if I_E_INDEX >= MAX_E_STEPPERS || !PIN_EXISTS(I_STEP) + #error "No E stepper plug left for I!" + #endif + #endif + #if AXIS_HAS_SPI(I) + #ifndef I_CS_PIN + #define I_CS_PIN _EPIN(I_E_INDEX, CS) + #endif + #endif + #ifndef I_MS1_PIN + #define I_MS1_PIN _EPIN(I_E_INDEX, MS1) + #endif + #ifndef I_MS2_PIN + #define I_MS2_PIN _EPIN(I_E_INDEX, MS2) + #endif + #ifndef I_MS3_PIN + #define I_MS3_PIN _EPIN(I_E_INDEX, MS3) + #endif + #if AXIS_HAS_UART(I) + #ifndef I_SERIAL_TX_PIN + #define I_SERIAL_TX_PIN _EPIN(I_E_INDEX, SERIAL_TX) + #endif + #ifndef I_SERIAL_RX_PIN + #define I_SERIAL_RX_PIN _EPIN(I_E_INDEX, SERIAL_RX) + #endif + #endif + // Auto-assign pins for stallGuard sensorless homing + #if !defined(I_USE_ENDSTOP) && defined(I_STALL_SENSITIVITY) && _PEXI(I_E_INDEX, DIAG) + #define I_DIAG_PIN _EPIN(I_E_INDEX, DIAG) + #if DIAG_REMAPPED(I, X_MIN) + #define I_USE_ENDSTOP _XMIN_ + #elif DIAG_REMAPPED(I, Y_MIN) + #define I_USE_ENDSTOP _YMIN_ + #elif DIAG_REMAPPED(I, Z_MIN) + #define I_USE_ENDSTOP _ZMIN_ + #elif DIAG_REMAPPED(I, X_MAX) + #define I_USE_ENDSTOP _XMAX_ + #elif DIAG_REMAPPED(I, Y_MAX) + #define I_USE_ENDSTOP _YMAX_ + #elif DIAG_REMAPPED(I, Z_MAX) + #define I_USE_ENDSTOP _ZMAX_ + #else + #define _I_USE_ENDSTOP(P) _E##P##_DIAG_ + #define I_USE_ENDSTOP _I_USE_ENDSTOP(I_E_INDEX) + #endif + #undef I_DIAG_PIN + #endif + #define J_E_INDEX INCREMENT(I_E_INDEX) +#else + #define J_E_INDEX I_E_INDEX +#endif + +#ifndef I_CS_PIN + #define I_CS_PIN -1 +#endif +#ifndef I_MS1_PIN + #define I_MS1_PIN -1 +#endif +#ifndef I_MS2_PIN + #define I_MS2_PIN -1 +#endif +#ifndef I_MS3_PIN + #define I_MS3_PIN -1 +#endif + +#if LINEAR_AXES >= 5 + #ifndef J_STEP_PIN + #define J_STEP_PIN _EPIN(J_E_INDEX, STEP) + #define J_DIR_PIN _EPIN(J_E_INDEX, DIR) + #define J_ENABLE_PIN _EPIN(J_E_INDEX, ENABLE) + #if I_E_INDEX >= MAX_E_STEPPERS || !PIN_EXISTS(J_STEP) + #error "No E stepper plug left for J!" + #endif + #endif + #if AXIS_HAS_SPI(J) + #ifndef J_CS_PIN + #define J_CS_PIN _EPIN(J_E_INDEX, CS) + #endif + #endif + #ifndef J_MS1_PIN + #define J_MS1_PIN _EPIN(J_E_INDEX, MS1) + #endif + #ifndef J_MS2_PIN + #define J_MS2_PIN _EPIN(J_E_INDEX, MS2) + #endif + #ifndef J_MS3_PIN + #define J_MS3_PIN _EPIN(J_E_INDEX, MS3) + #endif + #if AXIS_HAS_UART(J) + #ifndef J_SERIAL_TX_PIN + #define J_SERIAL_TX_PIN _EPIN(J_E_INDEX, SERIAL_TX) + #endif + #ifndef J_SERIAL_RX_PIN + #define J_SERIAL_RX_PIN _EPIN(J_E_INDEX, SERIAL_RX) + #endif + #endif + // Auto-assign pins for stallGuard sensorless homing + #if !defined(J_USE_ENDSTOP) && defined(J_STALL_SENSITIVITY) && _PEXI(J_E_INDEX, DIAG) + #define J_DIAG_PIN _EPIN(J_E_INDEX, DIAG) + #if DIAG_REMAPPED(J, X_MIN) + #define J_USE_ENDSTOP _XMIN_ + #elif DIAG_REMAPPED(J, Y_MIN) + #define J_USE_ENDSTOP _YMIN_ + #elif DIAG_REMAPPED(J, Z_MIN) + #define J_USE_ENDSTOP _ZMIN_ + #elif DIAG_REMAPPED(J, X_MAX) + #define J_USE_ENDSTOP _XMAX_ + #elif DIAG_REMAPPED(J, Y_MAX) + #define J_USE_ENDSTOP _YMAX_ + #elif DIAG_REMAPPED(I, Z_MAX) + #define J_USE_ENDSTOP _ZMAX_ + #else + #define _J_USE_ENDSTOP(P) _E##P##_DIAG_ + #define J_USE_ENDSTOP _J_USE_ENDSTOP(J_E_INDEX) + #endif + #undef J_DIAG_PIN + #endif + #define K_E_INDEX INCREMENT(J_E_INDEX) +#else + #define K_E_INDEX J_E_INDEX +#endif + +#ifndef J_CS_PIN + #define J_CS_PIN -1 +#endif +#ifndef J_MS1_PIN + #define J_MS1_PIN -1 +#endif +#ifndef J_MS2_PIN + #define J_MS2_PIN -1 +#endif +#ifndef J_MS3_PIN + #define J_MS3_PIN -1 +#endif + +#if LINEAR_AXES >= 6 + #ifndef K_STEP_PIN + #define K_STEP_PIN _EPIN(K_E_INDEX, STEP) + #define K_DIR_PIN _EPIN(K_E_INDEX, DIR) + #define K_ENABLE_PIN _EPIN(K_E_INDEX, ENABLE) + #if K_E_INDEX >= MAX_E_STEPPERS || !PIN_EXISTS(K_STEP) + #error "No E stepper plug left for K!" + #endif + #endif + #if AXIS_HAS_SPI(K) + #ifndef K_CS_PIN + #define K_CS_PIN _EPIN(K_E_INDEX, CS) + #endif + #endif + #ifndef K_MS1_PIN + #define K_MS1_PIN _EPIN(K_E_INDEX, MS1) + #endif + #ifndef K_MS2_PIN + #define K_MS2_PIN _EPIN(K_E_INDEX, MS2) + #endif + #ifndef K_MS3_PIN + #define K_MS3_PIN _EPIN(K_E_INDEX, MS3) + #endif + #if AXIS_HAS_UART(K) + #ifndef K_SERIAL_TX_PIN + #define K_SERIAL_TX_PIN _EPIN(K_E_INDEX, SERIAL_TX) + #endif + #ifndef K_SERIAL_RX_PIN + #define K_SERIAL_RX_PIN _EPIN(K_E_INDEX, SERIAL_RX) + #endif + #endif + // Auto-assign pins for stallGuard sensorless homing + #if !defined(K_USE_ENDSTOP) && defined(K_STALL_SENSITIVITY) && _PEXI(K_E_INDEX, DIAG) + #define K_DIAG_PIN _EPIN(K_E_INDEX, DIAG) + #if DIAG_REMAPPED(K, X_MIN) + #define K_USE_ENDSTOP _XMIN_ + #elif DIAG_REMAPPED(K, Y_MIN) + #define K_USE_ENDSTOP _YMIN_ + #elif DIAG_REMAPPED(K, Z_MIN) + #define K_USE_ENDSTOP _ZMIN_ + #elif DIAG_REMAPPED(K, X_MAX) + #define K_USE_ENDSTOP _XMAX_ + #elif DIAG_REMAPPED(K, Y_MAX) + #define K_USE_ENDSTOP _YMAX_ + #elif DIAG_REMAPPED(K, Z_MAX) + #define K_USE_ENDSTOP _ZMAX_ + #else + #define _K_USE_ENDSTOP(P) _E##P##_DIAG_ + #define K_USE_ENDSTOP _K_USE_ENDSTOP(K_E_INDEX) + #endif + #undef K_DIAG_PIN + #endif +#endif + +#ifndef K_CS_PIN + #define K_CS_PIN -1 +#endif +#ifndef K_MS1_PIN + #define K_MS1_PIN -1 +#endif +#ifndef K_MS2_PIN + #define K_MS2_PIN -1 +#endif +#ifndef K_MS3_PIN + #define K_MS3_PIN -1 +#endif + +// +// Disable unused endstop / probe pins +// +#define _STOP_IN_USE(N) (X2_USE_ENDSTOP == N || Y2_USE_ENDSTOP == N || Z2_USE_ENDSTOP == N || Z3_USE_ENDSTOP == N || Z4_USE_ENDSTOP == N) +#if _STOP_IN_USE(_XMAX_) + #define USE_XMAX_PLUG +#endif +#if _STOP_IN_USE(_YMAX_) + #define USE_YMAX_PLUG +#endif +#if _STOP_IN_USE(_ZMAX_) + #define USE_ZMAX_PLUG +#endif +#if _STOP_IN_USE(_XMIN_) + #define USE_XMIN_PLUG +#endif +#if _STOP_IN_USE(_YMIN_) + #define USE_YMIN_PLUG +#endif +#if _STOP_IN_USE(_ZMIN_) + #define USE_ZMIN_PLUG +#endif +#undef _STOP_IN_USE +#if !USES_Z_MIN_PROBE_PIN + #undef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN -1 +#endif +#if DISABLED(USE_XMIN_PLUG) + #undef X_MIN_PIN + #define X_MIN_PIN -1 +#endif +#if DISABLED(USE_XMAX_PLUG) + #undef X_MAX_PIN + #define X_MAX_PIN -1 +#endif +#if DISABLED(USE_YMIN_PLUG) + #undef Y_MIN_PIN + #define Y_MIN_PIN -1 +#endif +#if DISABLED(USE_YMAX_PLUG) + #undef Y_MAX_PIN + #define Y_MAX_PIN -1 +#endif +#if DISABLED(USE_ZMIN_PLUG) + #undef Z_MIN_PIN + #define Z_MIN_PIN -1 +#endif +#if DISABLED(USE_ZMAX_PLUG) + #undef Z_MAX_PIN + #define Z_MAX_PIN -1 +#endif +#if DISABLED(USE_IMIN_PLUG) + #undef I_MIN_PIN + #define I_MIN_PIN -1 +#endif +#if DISABLED(USE_IMAX_PLUG) + #undef I_MAX_PIN + #define I_MAX_PIN -1 +#endif +#if DISABLED(USE_JMIN_PLUG) + #undef J_MIN_PIN + #define J_MIN_PIN -1 +#endif +#if DISABLED(USE_JMAX_PLUG) + #undef J_MAX_PIN + #define J_MAX_PIN -1 +#endif +#if DISABLED(USE_KMIN_PLUG) + #undef K_MIN_PIN + #define K_MIN_PIN -1 +#endif +#if DISABLED(USE_KMAX_PLUG) + #undef K_MAX_PIN + #define K_MAX_PIN -1 +#endif + +#if DISABLED(X_DUAL_ENDSTOPS) || X_HOME_TO_MAX + #undef X2_MIN_PIN +#endif +#if DISABLED(X_DUAL_ENDSTOPS) || X_HOME_TO_MIN + #undef X2_MAX_PIN +#endif +#if DISABLED(Y_DUAL_ENDSTOPS) || Y_HOME_TO_MAX + #undef Y2_MIN_PIN +#endif +#if DISABLED(Y_DUAL_ENDSTOPS) || Y_HOME_TO_MIN + #undef Y2_MAX_PIN +#endif +#if DISABLED(Z_MULTI_ENDSTOPS) || Z_HOME_TO_MAX + #undef Z2_MIN_PIN +#endif +#if DISABLED(Z_MULTI_ENDSTOPS) || Z_HOME_TO_MIN + #undef Z2_MAX_PIN +#endif +#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 3 || Z_HOME_TO_MAX + #undef Z3_MIN_PIN +#endif +#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 3 || Z_HOME_TO_MIN + #undef Z3_MAX_PIN +#endif +#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 4 || Z_HOME_TO_MAX + #undef Z4_MIN_PIN +#endif +#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 4 || Z_HOME_TO_MIN + #undef Z4_MAX_PIN +#endif + +// +// Default DOGLCD SPI delays +// +#if HAS_MARLINUI_U8GLIB + #if !defined(ST7920_DELAY_1) && defined(BOARD_ST7920_DELAY_1) + #define ST7920_DELAY_1 BOARD_ST7920_DELAY_1 + #endif + #if !defined(ST7920_DELAY_2) && defined(BOARD_ST7920_DELAY_2) + #define ST7920_DELAY_2 BOARD_ST7920_DELAY_2 + #endif + #if !defined(ST7920_DELAY_3) && defined(BOARD_ST7920_DELAY_3) + #define ST7920_DELAY_3 BOARD_ST7920_DELAY_3 + #endif +#else + #undef ST7920_DELAY_1 + #undef ST7920_DELAY_2 + #undef ST7920_DELAY_3 + #undef BOARD_ST7920_DELAY_1 + #undef BOARD_ST7920_DELAY_2 + #undef BOARD_ST7920_DELAY_3 +#endif + +#if !NEED_CASE_LIGHT_PIN + #undef CASE_LIGHT_PIN +#endif + +#undef HAS_FREE_AUX2_PINS +#undef DIAG_REMAPPED diff --git a/Marlin/src/pins/rambo/env_validate.h b/Marlin/src/pins/rambo/env_validate.h new file mode 100644 index 000000000000..84cf8392cdfc --- /dev/null +++ b/Marlin/src/pins/rambo/env_validate.h @@ -0,0 +1,26 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#if NOT_TARGET(__AVR_ATmega2560__) + #error "Oops! Select 'Arduino Mega 2560 or Rambo' in 'Tools > Board.'" +#endif diff --git a/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h b/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h index 2ea15c97d332..de50657b7419 100644 --- a/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h +++ b/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h @@ -25,11 +25,12 @@ * Einsy-Rambo pin assignments */ -#if NOT_TARGET(__AVR_ATmega2560__) - #error "Oops! Select 'Arduino Mega 2560 or Rambo' in 'Tools > Board.'" -#endif +#include "env_validate.h" + +#define BOARD_INFO_NAME "Einsy Rambo" +#define DEFAULT_MACHINE_NAME "Prusa MK3" -#define BOARD_INFO_NAME "Einsy Rambo" +//#define MK3_FAN_PINS // // TMC2130 Configuration_adv defaults for EinsyRambo @@ -125,11 +126,19 @@ #define HEATER_BED_PIN 4 #ifndef FAN_PIN - #define FAN_PIN 8 + #ifdef MK3_FAN_PINS + #define FAN_PIN 6 + #else + #define FAN_PIN 8 + #endif #endif #ifndef FAN1_PIN - #define FAN1_PIN 6 + #ifdef MK3_FAN_PINS + #define FAN1_PIN -1 + #else + #define FAN1_PIN 6 + #endif #endif // @@ -164,7 +173,7 @@ #define KILL_PIN 32 - #if ENABLED(ULTIPANEL) || TOUCH_UI_ULTIPANEL + #if IS_ULTIPANEL || TOUCH_UI_ULTIPANEL #if ENABLED(CR10_STOCKDISPLAY) #define LCD_PINS_RS 85 @@ -181,11 +190,18 @@ #define LCD_PINS_D7 71 #define BTN_EN1 14 #define BTN_EN2 72 + + #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_ENC 9 // AUX-2 #define BEEPER_PIN 84 // AUX-4 #define SD_DETECT_PIN 15 - #endif // ULTIPANEL || TOUCH_UI_ULTIPANEL + #endif // IS_ULTIPANEL || TOUCH_UI_ULTIPANEL #endif // HAS_WIRED_LCD + +#undef MK3_FAN_PINS diff --git a/Marlin/src/pins/rambo/pins_EINSY_RETRO.h b/Marlin/src/pins/rambo/pins_EINSY_RETRO.h index 4a1bf70b6eaa..0c072745d57b 100644 --- a/Marlin/src/pins/rambo/pins_EINSY_RETRO.h +++ b/Marlin/src/pins/rambo/pins_EINSY_RETRO.h @@ -25,9 +25,7 @@ * Einsy-Retro pin assignments */ -#if NOT_TARGET(__AVR_ATmega2560__) - #error "Oops! Select 'Arduino Mega 2560 or Rambo' in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "Einsy Retro" @@ -63,7 +61,7 @@ #else - #if X_HOME_DIR < 0 + #if X_HOME_TO_MIN #define X_MIN_PIN X_DIAG_PIN #define X_MAX_PIN 81 // X+ #else @@ -71,7 +69,7 @@ #define X_MAX_PIN X_DIAG_PIN #endif - #if Y_HOME_DIR < 0 + #if Y_HOME_TO_MIN #define Y_MIN_PIN Y_DIAG_PIN #define Y_MAX_PIN 57 // Y+ #else @@ -170,7 +168,7 @@ #define KILL_PIN 32 - #if ANY(ULTIPANEL, TOUCH_UI_ULTIPANEL, TOUCH_UI_FTDI_EVE) + #if ANY(IS_ULTIPANEL, TOUCH_UI_ULTIPANEL, TOUCH_UI_FTDI_EVE) #if ENABLED(CR10_STOCKDISPLAY) #define LCD_PINS_RS 85 @@ -194,6 +192,10 @@ #define SD_DETECT_PIN 15 - #endif // ULTIPANEL || TOUCH_UI_ULTIPANEL || TOUCH_UI_FTDI_EVE + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif + + #endif // IS_ULTIPANEL || TOUCH_UI_ULTIPANEL || TOUCH_UI_FTDI_EVE #endif // HAS_WIRED_LCD || TOUCH_UI_ULTIPANEL || TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/pins/rambo/pins_MINIRAMBO.h b/Marlin/src/pins/rambo/pins_MINIRAMBO.h index 6314bc07b8c0..ec44cc3b3661 100644 --- a/Marlin/src/pins/rambo/pins_MINIRAMBO.h +++ b/Marlin/src/pins/rambo/pins_MINIRAMBO.h @@ -25,9 +25,7 @@ * Mini-RAMBo pin assignments */ -#if NOT_TARGET(__AVR_ATmega2560__) - #error "Oops! Select 'RAMBo' in 'Tools > Board' or the Mega2560 environment in PlatformIO." -#endif +#include "env_validate.h" #if MB(MINIRAMBO_10A) #define BOARD_INFO_NAME "Mini RAMBo 1.0a" @@ -147,7 +145,7 @@ #define KILL_PIN 32 #endif - #if ENABLED(ULTIPANEL) || TOUCH_UI_ULTIPANEL + #if IS_ULTIPANEL || TOUCH_UI_ULTIPANEL #if MB(MINIRAMBO_10A) @@ -187,6 +185,10 @@ #endif // !MINIRAMBO_10A - #endif // ULTIPANEL || TOUCH_UI_ULTIPANEL + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif + + #endif // IS_ULTIPANEL || TOUCH_UI_ULTIPANEL #endif // HAS_WIRED_LCD || TOUCH_UI_ULTIPANEL diff --git a/Marlin/src/pins/rambo/pins_RAMBO.h b/Marlin/src/pins/rambo/pins_RAMBO.h index 735852b2ff79..f2d34dc00d79 100644 --- a/Marlin/src/pins/rambo/pins_RAMBO.h +++ b/Marlin/src/pins/rambo/pins_RAMBO.h @@ -41,18 +41,22 @@ * Rambo pin assignments */ -#if NOT_TARGET(__AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#endif +#include "env_validate.h" -#define BOARD_INFO_NAME "Rambo" +#ifndef BOARD_INFO_NAME + #define BOARD_INFO_NAME "Rambo" +#endif // // Servos // -#define SERVO0_PIN 22 // Motor header MX1 +#ifndef SERVO0_PIN + #define SERVO0_PIN 22 // Motor header MX1 +#endif #define SERVO1_PIN 23 // Motor header MX2 -#define SERVO2_PIN 24 // Motor header MX3 +#ifndef SERVO2_PIN + #define SERVO2_PIN 24 // Motor header MX3 +#endif #define SERVO3_PIN 5 // PWM header pin 5 // @@ -62,7 +66,9 @@ #define X_MAX_PIN 24 #define Y_MIN_PIN 11 #define Y_MAX_PIN 23 -#define Z_MIN_PIN 10 +#ifndef Z_MIN_PIN + #define Z_MIN_PIN 10 +#endif #define Z_MAX_PIN 30 // @@ -112,7 +118,7 @@ #define E1_MS2_PIN 64 #define DIGIPOTSS_PIN 38 -#define DIGIPOT_CHANNELS { 4,5,3,0,1 } // X Y Z E0 E1 digipot channels to stepper driver mapping +#define DIGIPOT_CHANNELS { 4, 5, 3, 0, 1 } // X Y Z E0 E1 digipot channels to stepper driver mapping #ifndef DIGIPOT_MOTOR_CURRENT #define DIGIPOT_MOTOR_CURRENT { 135,135,135,135,135 } // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A) #endif @@ -135,8 +141,12 @@ #ifndef FAN_PIN #define FAN_PIN 8 #endif -#define FAN1_PIN 6 -#define FAN2_PIN 2 +#ifndef FAN1_PIN + #define FAN1_PIN 6 +#endif +#ifndef FAN2_PIN + #define FAN2_PIN 2 +#endif // // Misc. Functions @@ -161,10 +171,10 @@ #define SPINDLE_DIR_PIN 32 // -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple // -#ifndef MAX6675_SS_PIN - #define MAX6675_SS_PIN 32 // SPINDLE_DIR_PIN / STAT_LED_BLUE_PIN +#ifndef TEMP_0_CS_PIN + #define TEMP_0_CS_PIN 32 // SPINDLE_DIR_PIN / STAT_LED_BLUE_PIN #endif // @@ -187,7 +197,7 @@ #define KILL_PIN 80 - #if ENABLED(ULTIPANEL) || TOUCH_UI_ULTIPANEL + #if IS_ULTIPANEL || TOUCH_UI_ULTIPANEL #define LCD_PINS_RS 70 #define LCD_PINS_ENABLE 71 @@ -220,25 +230,33 @@ #define BEEPER_PIN 79 // AUX-4 // AUX-2 - #define BTN_EN1 76 - #define BTN_EN2 77 + #ifndef BTN_EN1 + #define BTN_EN1 76 + #endif + #ifndef BTN_EN2 + #define BTN_EN2 77 + #endif #define BTN_ENC 78 #define SD_DETECT_PIN 81 #endif // !VIKI2 && !miniVIKI - #else // !NEWPANEL - old style panel with shift register + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif + + #else // !IS_NEWPANEL - old style panel with shift register // No Beeper added #define BEEPER_PIN 33 // Buttons attached to a shift register // Not wired yet - //#define SHIFT_CLK 38 - //#define SHIFT_LD 42 - //#define SHIFT_OUT 40 - //#define SHIFT_EN 17 + //#define SHIFT_CLK_PIN 38 + //#define SHIFT_LD_PIN 42 + //#define SHIFT_OUT_PIN 40 + //#define SHIFT_EN_PIN 17 #define LCD_PINS_RS 75 #define LCD_PINS_ENABLE 17 @@ -247,6 +265,6 @@ #define LCD_PINS_D6 27 #define LCD_PINS_D7 29 - #endif // !NEWPANEL + #endif // !IS_NEWPANEL #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/rambo/pins_RAMBO_THINKERV2.h b/Marlin/src/pins/rambo/pins_RAMBO_THINKERV2.h new file mode 100755 index 000000000000..278a5bf0b45a --- /dev/null +++ b/Marlin/src/pins/rambo/pins_RAMBO_THINKERV2.h @@ -0,0 +1,60 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * Rambo ThinkerV2 pin assignments + */ + +#define BOARD_INFO_NAME "Rambo ThinkerV2" + +#define SERVO0_PIN 4 // Motor header MX1 +#define SERVO2_PIN -1 // Motor header MX3 + +#ifndef FIL_RUNOUT_PIN + #define FIL_RUNOUT_PIN 10 +#endif + +// Support BLTouch and fixed probes +#if ENABLED(BLTOUCH) + #if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) + #define Z_MIN_PIN 22 + #elif !defined(Z_MIN_PROBE_PIN) + #define Z_MIN_PROBE_PIN 22 + #endif +#elif ENABLED(FIX_MOUNTED_PROBE) + #if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) + #define Z_MIN_PIN 4 + #elif !defined(Z_MIN_PROBE_PIN) + #define Z_MIN_PROBE_PIN 4 + #endif +#endif + +// Eryone has the fan pins reversed +#define FAN1_PIN 2 +#define FAN2_PIN 6 + +// Encoder +#define BTN_EN1 64 +#define BTN_EN2 63 + +#include "pins_RAMBO.h" diff --git a/Marlin/src/pins/rambo/pins_SCOOVO_X9H.h b/Marlin/src/pins/rambo/pins_SCOOVO_X9H.h index 4af38e1de36b..c2a691a3b73b 100644 --- a/Marlin/src/pins/rambo/pins_SCOOVO_X9H.h +++ b/Marlin/src/pins/rambo/pins_SCOOVO_X9H.h @@ -25,9 +25,7 @@ * Rambo pin assignments MODIFIED FOR Scoovo X9H ************************************************/ -#if NOT_TARGET(__AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#endif +#include "env_target.h" #define BOARD_INFO_NAME "Scoovo X9H" @@ -92,7 +90,7 @@ #define E1_MS2_PIN 64 #define DIGIPOTSS_PIN 38 -#define DIGIPOT_CHANNELS {4,5,3,0,1} // X Y Z E0 E1 digipot channels to stepper driver mapping +#define DIGIPOT_CHANNELS { 4, 5, 3, 0, 1 } // X Y Z E0 E1 digipot channels to stepper driver mapping // // Temperature Sensors diff --git a/Marlin/src/pins/ramps/env_validate.h b/Marlin/src/pins/ramps/env_validate.h new file mode 100644 index 000000000000..6006a78f013c --- /dev/null +++ b/Marlin/src/pins/ramps/env_validate.h @@ -0,0 +1,35 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#if ENABLED(ALLOW_SAM3X8E) + #if NOT_TARGET(__SAM3X8E__, __AVR_ATmega2560__) + #error "Oops! Select 'Arduino Due' or 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" + #endif +#elif ENABLED(REQUIRE_MEGA2560) && NOT_TARGET(__AVR_ATmega2560__) + #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" +#elif DISABLED(REQUIRE_MEGA2560) && NOT_TARGET(__AVR_ATmega1280__, __AVR_ATmega2560__) + #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560 or 1280' in 'Tools > Board.'" +#endif + +#undef ALLOW_SAM3X8E +#undef REQUIRE_MEGA2560 diff --git a/Marlin/src/pins/ramps/pins_3DRAG.h b/Marlin/src/pins/ramps/pins_3DRAG.h index f0057e1fc980..e78f7683f607 100644 --- a/Marlin/src/pins/ramps/pins_3DRAG.h +++ b/Marlin/src/pins/ramps/pins_3DRAG.h @@ -34,7 +34,7 @@ #endif #ifndef DEFAULT_SOURCE_CODE_URL - #define DEFAULT_SOURCE_CODE_URL "https://3dprint.elettronicain.it/" + #define DEFAULT_SOURCE_CODE_URL "3dprint.elettronicain.it" #endif // @@ -44,6 +44,11 @@ #define RAMPS_D9_PIN 8 #define MOSFET_D_PIN 12 +// +// Misc. Functions +// +#define SDSS 25 + #ifndef CASE_LIGHT_PIN #define CASE_LIGHT_PIN -1 // Hardware PWM but one is not available on expansion header #endif @@ -66,19 +71,13 @@ // #define HEATER_2_PIN 6 -// -// Misc. Functions -// -#undef SDSS -#define SDSS 25 - #undef SD_DETECT_PIN #define SD_DETECT_PIN 53 // // LCD / Controller // -#if BOTH(ULTRA_LCD, NEWPANEL) +#if IS_ULTRA_LCD && IS_NEWPANEL #undef BEEPER_PIN #undef LCD_PINS_RS @@ -106,7 +105,7 @@ #define BEEPER_PIN 33 -#endif // ULTRA_LCD && NEWPANEL +#endif // IS_ULTRA_LCD && IS_NEWPANEL /** * M3/M4/M5 - Spindle/Laser Control @@ -144,7 +143,7 @@ #undef SPINDLE_DIR_PIN #if HAS_CUTTER - #if !EXTRUDERS + #if !HAS_EXTRUDERS #undef E0_DIR_PIN #undef E0_ENABLE_PIN #undef E0_STEP_PIN @@ -157,7 +156,7 @@ #define SPINDLE_LASER_PWM_PIN 46 // Hardware PWM #define SPINDLE_LASER_ENA_PIN 62 // Pullup! #define SPINDLE_DIR_PIN 48 - #elif !BOTH(ULTRA_LCD, NEWPANEL) // use expansion header if no LCD in use + #elif !BOTH(IS_ULTRA_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 #endif diff --git a/Marlin/src/pins/ramps/pins_AZTEEG_X3.h b/Marlin/src/pins/ramps/pins_AZTEEG_X3.h index e919b30cf982..07af61e69381 100644 --- a/Marlin/src/pins/ramps/pins_AZTEEG_X3.h +++ b/Marlin/src/pins/ramps/pins_AZTEEG_X3.h @@ -25,9 +25,10 @@ * AZTEEG_X3 Arduino Mega with RAMPS v1.4 pin assignments */ -#if NOT_TARGET(__AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#elif HOTENDS > 2 || E_STEPPERS > 2 +#define REQUIRE_MEGA2560 +#include "env_validate.h" + +#if HOTENDS > 2 || E_STEPPERS > 2 #error "Azteeg X3 supports up to 2 hotends / E-steppers. Comment out this line to continue." #endif @@ -72,7 +73,7 @@ // // Misc // -#if ENABLED(CASE_LIGHT_ENABLE) && PIN_EXISTS(CASE_LIGHT, STAT_LED_RED) && STAT_LED_RED_PIN == CASE_LIGHT_PIN +#if ENABLED(CASE_LIGHT_ENABLE) && PINS_EXIST(CASE_LIGHT, STAT_LED_RED) && STAT_LED_RED_PIN == CASE_LIGHT_PIN #undef STAT_LED_RED_PIN #endif diff --git a/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h b/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h index 9ba6a0c1ac45..c2896146e64f 100644 --- a/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h +++ b/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h @@ -25,9 +25,10 @@ * AZTEEG_X3_PRO (Arduino Mega) pin assignments */ -#if NOT_TARGET(__AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#elif HOTENDS > 5 || E_STEPPERS > 5 +#define REQUIRE_MEGA2560 +#include "env_validate.h" + +#if HOTENDS > 5 || E_STEPPERS > 5 #error "Azteeg X3 Pro supports up to 5 hotends / E-steppers. Comment out this line to continue." #endif diff --git a/Marlin/src/pins/ramps/pins_BAM_DICE_DUE.h b/Marlin/src/pins/ramps/pins_BAM_DICE_DUE.h index af1adabbbcd2..97ef1b4fd869 100644 --- a/Marlin/src/pins/ramps/pins_BAM_DICE_DUE.h +++ b/Marlin/src/pins/ramps/pins_BAM_DICE_DUE.h @@ -34,9 +34,9 @@ // // 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 +#define SPINDLE_LASER_ENA_PIN 66 // Pullup or pulldown! +#define SPINDLE_DIR_PIN 67 +#define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM #include "pins_RAMPS.h" @@ -45,5 +45,5 @@ // #undef TEMP_0_PIN #undef TEMP_1_PIN -#define TEMP_0_PIN 9 // Analog Input -#define TEMP_1_PIN 11 // Analog Input +#define TEMP_0_PIN 9 // Analog Input +#define TEMP_1_PIN 11 // Analog Input 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 967fec7b47de..99cf484de7f0 100644 --- a/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h +++ b/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h @@ -25,9 +25,8 @@ * bq ZUM Mega 3D board definition */ -#if NOT_TARGET(__AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#endif +#define REQUIRE_MEGA2560 +#include "env_validate.h" #define BOARD_INFO_NAME "ZUM Mega 3D" @@ -85,7 +84,7 @@ // Steppers // #define DIGIPOTSS_PIN 22 -#define DIGIPOT_CHANNELS { 4, 5, 3, 0, 1 } +#define DIGIPOT_CHANNELS { 4, 5, 3, 0, 1 } // // Temperature Sensors diff --git a/Marlin/src/pins/ramps/pins_COPYMASTER_3D.h b/Marlin/src/pins/ramps/pins_COPYMASTER_3D.h index b9eee6bd5329..020941027aaf 100644 --- a/Marlin/src/pins/ramps/pins_COPYMASTER_3D.h +++ b/Marlin/src/pins/ramps/pins_COPYMASTER_3D.h @@ -23,10 +23,10 @@ #define BOARD_INFO_NAME "Copymaster 3D RAMPS" -#define Z_STEP_PIN 47 -#define Y_MAX_PIN 14 -#define FIL_RUNOUT_PIN 15 -#define SD_DETECT_PIN 66 +#define Z_STEP_PIN 47 +#define Y_MAX_PIN 14 +#define FIL_RUNOUT_PIN 15 +#define SD_DETECT_PIN 66 // // Import RAMPS 1.4 pins diff --git a/Marlin/src/pins/ramps/pins_DAGOMA_F5.h b/Marlin/src/pins/ramps/pins_DAGOMA_F5.h new file mode 100644 index 000000000000..8dc93c833b3b --- /dev/null +++ b/Marlin/src/pins/ramps/pins_DAGOMA_F5.h @@ -0,0 +1,68 @@ +/** + * 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 + +#if HOTENDS > 2 || E_STEPPERS > 2 + #error "Dagoma3D F5 supports only 2 hotends / E-steppers. Comment out this line to continue." +#endif + +#define BOARD_INFO_NAME "Dagoma3D F5" + +// +// Endstops +// +#define X_STOP_PIN 2 +#define Y_STOP_PIN 3 +#define Z_STOP_PIN 15 + +#define FIL_RUNOUT_PIN 39 +#if EXTRUDERS > 1 + #define FIL_RUNOUT2_PIN 14 +#endif + +// +// LCD delays +// +#if HAS_MARLINUI_U8GLIB + #define BOARD_ST7920_DELAY_1 DELAY_NS(0) + #define BOARD_ST7920_DELAY_2 DELAY_NS(250) + #define BOARD_ST7920_DELAY_3 DELAY_NS(250) +#endif + +// +// DAC steppers +// +#define HAS_MOTOR_CURRENT_DAC 1 + +#define DAC_STEPPER_ORDER { 0, 1, 2, 3 } + +#define DAC_STEPPER_SENSE 0.11 +#define DAC_STEPPER_ADDRESS 0 +#define DAC_STEPPER_MAX 4096 +#define DAC_STEPPER_VREF 1 +#define DAC_STEPPER_GAIN 0 +#define DAC_OR_ADDRESS 0x00 + +// +// Import default RAMPS 1.4 pins +// +#include "pins_RAMPS.h" diff --git a/Marlin/src/pins/ramps/pins_DUPLICATOR_I3_PLUS.h b/Marlin/src/pins/ramps/pins_DUPLICATOR_I3_PLUS.h index 87d24890c99c..1a4b83f02dce 100644 --- a/Marlin/src/pins/ramps/pins_DUPLICATOR_I3_PLUS.h +++ b/Marlin/src/pins/ramps/pins_DUPLICATOR_I3_PLUS.h @@ -25,9 +25,8 @@ * Wanhao Duplicator i3 Plus pin assignments */ -#if NOT_TARGET(__AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#endif +#define REQUIRE_MEGA2560 +#include "env_validate.h" #define BOARD_INFO_NAME "Duplicator i3 Plus" @@ -80,9 +79,9 @@ #define SDSS 53 // PB0 / SS #define LED_PIN 13 // PB7 / PWM13 -#define MISO_PIN 50 // PB3 -#define MOSI_PIN 51 // PB2 -#define SCK_PIN 52 // PB1 +#define SD_MISO_PIN 50 // PB3 +#define SD_MOSI_PIN 51 // PB2 +#define SD_SCK_PIN 52 // PB1 // // LCDs and Controllers diff --git a/Marlin/src/pins/ramps/pins_FELIX2.h b/Marlin/src/pins/ramps/pins_FELIX2.h index 6cc6997adc56..e572d3f2866c 100644 --- a/Marlin/src/pins/ramps/pins_FELIX2.h +++ b/Marlin/src/pins/ramps/pins_FELIX2.h @@ -49,11 +49,11 @@ // // LCD / Controller // -#if BOTH(ULTRA_LCD, NEWPANEL) +#if IS_ULTRA_LCD && IS_NEWPANEL #define SD_DETECT_PIN 6 -#endif // NEWPANEL && ULTRA_LCD +#endif // // M3/M4/M5 - Spindle/Laser Control diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h b/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h index 0877d168d60f..34a4ceb27d16 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h @@ -25,9 +25,10 @@ * Formbot Raptor pin assignments */ -#if NOT_TARGET(__AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#elif HOTENDS > 3 || E_STEPPERS > 3 +#define REQUIRE_MEGA2560 +#include "env_validate.h" + +#if HOTENDS > 3 || E_STEPPERS > 3 #error "Formbot supports up to 3 hotends / E-steppers. Comment out this line to continue." #endif @@ -113,11 +114,11 @@ #define TEMP_1_PIN 15 // Analog Input #define TEMP_BED_PIN 14 // Analog Input -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 66 // Don't use 53 if using Display/SD card + #define TEMP_0_CS_PIN 66 // Don't use 53 if using Display/SD card #else - #define MAX6675_SS_PIN 66 // Don't use 49 (SD_DETECT_PIN) + #define TEMP_0_CS_PIN 66 // Don't use 49 (SD_DETECT_PIN) #endif // @@ -181,7 +182,7 @@ // // Formbot only supports REPRAP_DISCOUNT_SMART_CONTROLLER // -#if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) +#if IS_RRD_SC #define BEEPER_PIN 37 #define BTN_EN1 31 #define BTN_EN2 33 diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h b/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h index 75a219c177de..5f645e5d957a 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h @@ -25,9 +25,10 @@ * Formbot pin assignments */ -#if NOT_TARGET(__AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#elif HOTENDS > 2 || E_STEPPERS > 2 +#define REQUIRE_MEGA2560 +#include "env_validate.h" + +#if HOTENDS > 2 || E_STEPPERS > 2 #error "Formbot supports up to 2 hotends / E-steppers. Comment out this line to continue." #endif @@ -110,11 +111,11 @@ #define TEMP_1_PIN 15 // Analog Input #define TEMP_BED_PIN 3 // Analog Input -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 66 // Don't use 53 if using Display/SD card + #define TEMP_0_CS_PIN 66 // Don't use 53 if using Display/SD card #else - #define MAX6675_SS_PIN 66 // Don't use 49 (SD_DETECT_PIN) + #define TEMP_0_CS_PIN 66 // Don't use 49 (SD_DETECT_PIN) #endif // @@ -175,7 +176,7 @@ // // Formbot only supports REPRAP_DISCOUNT_SMART_CONTROLLER // -#if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) +#if IS_RRD_SC #ifndef BEEPER_PIN #define BEEPER_PIN 37 #endif diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h b/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h index 0470fc47e98b..c953cff3d066 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h @@ -25,9 +25,10 @@ * Formbot pin assignments */ -#if NOT_TARGET(__AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#elif HOTENDS > 2 || E_STEPPERS > 2 +#define REQUIRE_MEGA2560 +#include "env_validate.h" + +#if HOTENDS > 2 || E_STEPPERS > 2 #error "Formbot supports up to 2 hotends / E-steppers. Comment out this line to continue." #endif @@ -110,11 +111,11 @@ #define TEMP_1_PIN 15 // Analog Input #define TEMP_BED_PIN 14 // Analog Input -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 66 // Don't use 53 if using Display/SD card + #define TEMP_0_CS_PIN 66 // Don't use 53 if using Display/SD card #else - #define MAX6675_SS_PIN 66 // Don't use 49 (SD_DETECT_PIN) + #define TEMP_0_CS_PIN 66 // Don't use 49 (SD_DETECT_PIN) #endif // @@ -155,7 +156,7 @@ // // Formbot only supports REPRAP_DISCOUNT_SMART_CONTROLLER // -#if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) +#if IS_RRD_SC #define LCD_PINS_RS 16 #define LCD_PINS_ENABLE 17 #define LCD_PINS_D4 23 diff --git a/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h b/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h index 3fa3cc9e8c9c..6133a6417e01 100644 --- a/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h +++ b/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h @@ -201,7 +201,7 @@ * ----- ----- * 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) + * (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) * ----- ----- @@ -226,7 +226,7 @@ #define DOGLCD_SCK 17 #define DOGLCD_A0 LCD_PINS_DC - #define KILL_PIN -1 // NC + #undef KILL_PIN #define NEOPIXEL_PIN 27 #else @@ -243,7 +243,6 @@ #define LCD_BACKLIGHT_PIN 27 #endif - #define KILL_PIN 41 #define LCD_RESET_PIN 23 // Must be high or open for LCD to operate normally. // Seems to work best if left open. @@ -261,7 +260,7 @@ #define NEOPIXEL_PIN 25 #endif - #elif HAS_MARLINUI_U8GLIB + #elif HAS_MARLINUI_U8GLIB || HAS_MARLINUI_HD44780 #define LCD_PINS_RS 16 #define LCD_PINS_ENABLE 17 @@ -275,9 +274,13 @@ #define DOGLCD_A0 27 #endif + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif + #endif - #if ENABLED(NEWPANEL) + #if IS_NEWPANEL #define BTN_EN1 31 #define BTN_EN2 33 #define BTN_ENC 35 diff --git a/Marlin/src/pins/ramps/pins_K8200.h b/Marlin/src/pins/ramps/pins_K8200.h index 5d4d2d7022a5..df685e0f0c20 100644 --- a/Marlin/src/pins/ramps/pins_K8200.h +++ b/Marlin/src/pins/ramps/pins_K8200.h @@ -28,6 +28,6 @@ #define BOARD_INFO_NAME "Velleman K8200" #define DEFAULT_MACHINE_NAME "K8200" -#define DEFAULT_SOURCE_CODE_URL "https://github.com/CONSULitAS/Marlin-K8200" +#define DEFAULT_SOURCE_CODE_URL "github.com/CONSULitAS/Marlin-K8200" #include "pins_3DRAG.h" diff --git a/Marlin/src/pins/ramps/pins_K8400.h b/Marlin/src/pins/ramps/pins_K8400.h index c36e291598eb..af687927f420 100644 --- a/Marlin/src/pins/ramps/pins_K8400.h +++ b/Marlin/src/pins/ramps/pins_K8400.h @@ -40,8 +40,8 @@ // // Limit Switches // -#define X_STOP_PIN 3 -#define Y_STOP_PIN 14 +#define X_STOP_PIN 3 +#define Y_STOP_PIN 14 #undef X_MIN_PIN #undef X_MAX_PIN @@ -52,13 +52,13 @@ // Steppers // #undef E1_STEP_PIN -#define E1_STEP_PIN 32 +#define E1_STEP_PIN 32 // // Heaters / Fans // #undef HEATER_1_PIN -#define HEATER_1_PIN 11 +#define HEATER_1_PIN 11 // // Misc. Functions @@ -69,5 +69,5 @@ #if Z_STEP_PIN == 26 #undef Z_STEP_PIN - #define Z_STEP_PIN 32 + #define Z_STEP_PIN 32 #endif diff --git a/Marlin/src/pins/ramps/pins_K8600.h b/Marlin/src/pins/ramps/pins_K8600.h index 0de01927528c..47b52e75e80d 100644 --- a/Marlin/src/pins/ramps/pins_K8600.h +++ b/Marlin/src/pins/ramps/pins_K8600.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. - * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm + * 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 @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#pragma once /** * VERTEX NANO Arduino Mega with RAMPS EFB v1.4 pin assignments. @@ -47,6 +48,7 @@ // // Misc. Functions // +#define SDSS 25 #define CASE_LIGHT_PIN 7 // @@ -87,16 +89,10 @@ // #undef HEATER_BED_PIN -// -// Misc. Functions -// -#undef SDSS -#define SDSS 25 // 53 - // // LCD / Controller // -#if BOTH(ULTRA_LCD, NEWPANEL) +#if IS_ULTRA_LCD && IS_NEWPANEL #undef BEEPER_PIN #undef LCD_PINS_RS diff --git a/Marlin/src/pins/ramps/pins_K8800.h b/Marlin/src/pins/ramps/pins_K8800.h index 7e8c245a4158..9bc74943b47a 100644 --- a/Marlin/src/pins/ramps/pins_K8800.h +++ b/Marlin/src/pins/ramps/pins_K8800.h @@ -25,9 +25,7 @@ * Velleman K8800 (Vertex) */ -#if NOT_TARGET(__AVR_ATmega1280__, __AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "K8800" #define DEFAULT_MACHINE_NAME "Vertex Delta" @@ -113,7 +111,7 @@ #define LCD_CONTRAST_MAX 100 #define DEFAULT_LCD_CONTRAST 30 - #if ENABLED(NEWPANEL) + #if IS_NEWPANEL #define BTN_EN1 17 #define BTN_EN2 16 #define BTN_ENC 23 diff --git a/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h b/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h new file mode 100644 index 000000000000..5ff3b366be1a --- /dev/null +++ b/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h @@ -0,0 +1,119 @@ +/** + * 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 + +/** + * Longer3D LK1/LK4/LK5 Pro board pin assignments + */ + +#define REQUIRE_MEGA2560 +#include "env_validate.h" + +#if HOTENDS > 1 || E_STEPPERS > 1 + #error "Longer3D LGT KIT V1.0 board only supports one hotend / E-stepper. Comment out this line to continue." +#endif + +#if SERIAL_PORT == 1 || SERIAL_PORT_2 == 1 + #warning "Serial 1 is originally reserved to DGUS LCD." +#endif +#if SERIAL_PORT == 2 || SERIAL_PORT_2 == 2 + #warning "Serial 2 has no connector. Hardware changes may be required to use it." +#endif +#if SERIAL_PORT == 3 || SERIAL_PORT_2 == 3 + #define CHANGE_Y_LIMIT_PINS + #warning "Serial 3 is originally reserved to Y limit switches. Hardware changes are required to use it." +#endif + +// Custom flags and defines for the build +//#define BOARD_CUSTOM_BUILD_FLAGS -D__FOO__ + +#define BOARD_INFO_NAME "LGT KIT V1.0" + +// +// Servos +// +#if !MB(LONGER3D_LK1_PRO) + #define SERVO0_PIN 7 +#endif +#define SERVO1_PIN -1 +#define SERVO2_PIN -1 +#define SERVO3_PIN -1 + +// +// Limit Switches +// +#define X_STOP_PIN 3 + +#ifdef CHANGE_Y_LIMIT_PINS + #define Y_STOP_PIN 37 +#else + #define Y_MIN_PIN 14 + #define Y_MAX_PIN 15 +#endif + +#if !MB(LONGER3D_LK1_PRO) + #ifdef CHANGE_Y_LIMIT_PINS + #define Z_STOP_PIN 35 + #else + #define Z_MIN_PIN 35 + #define Z_MAX_PIN 37 + #endif +#else + #define Z_MIN_PIN 11 + #define Z_MAX_PIN 37 +#endif + +// +// Z Probe (when not Z_MIN_PIN) +// +#define Z_MIN_PROBE_PIN -1 + +// +// Misc. Functions +// +#define SD_DETECT_PIN 49 +#define FIL_RUNOUT_PIN 2 + +// +// Other RAMPS 1.3 pins +// +#define IS_RAMPS_EFB // Override autodetection. Bed will be undefined. +#include "pins_RAMPS_13.h" + +// +// Steppers +// +#undef E1_STEP_PIN +#undef E1_DIR_PIN +#undef E1_ENABLE_PIN +#undef E1_CS_PIN + +// +// Temperature Sensors +// +#undef TEMP_1_PIN + +// +// Průša i3 MK2 Multiplexer Support +// +#undef E_MUX2_PIN +#undef CHANGE_Y_LIMIT_PINS diff --git a/Marlin/src/pins/ramps/pins_MKS_BASE_16.h b/Marlin/src/pins/ramps/pins_MKS_BASE_16.h index 42796acf8b6a..a4dfca21b465 100644 --- a/Marlin/src/pins/ramps/pins_MKS_BASE_16.h +++ b/Marlin/src/pins/ramps/pins_MKS_BASE_16.h @@ -30,30 +30,30 @@ #endif #define BOARD_INFO_NAME "MKS BASE 1.6" -#define MKS_BASE_VERSION 16 +#define MKS_BASE_VERSION 16 // // Servos // -#define SERVO1_PIN 12 // Digital 12 / Pin 25 +#define SERVO1_PIN 12 // Digital 12 / Pin 25 // // Omitted RAMPS pins // #ifndef SERVO2_PIN - #define SERVO2_PIN -1 + #define SERVO2_PIN -1 #endif #ifndef SERVO3_PIN - #define SERVO3_PIN -1 + #define SERVO3_PIN -1 #endif #ifndef FILWIDTH_PIN - #define FILWIDTH_PIN -1 + #define FILWIDTH_PIN -1 #endif #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN -1 + #define FIL_RUNOUT_PIN -1 #endif #ifndef PS_ON_PIN - #define PS_ON_PIN -1 + #define PS_ON_PIN -1 #endif #include "pins_MKS_BASE_common.h" diff --git a/Marlin/src/pins/ramps/pins_ORTUR_4.h b/Marlin/src/pins/ramps/pins_ORTUR_4.h index cef01bf62a46..e79973e06f07 100644 --- a/Marlin/src/pins/ramps/pins_ORTUR_4.h +++ b/Marlin/src/pins/ramps/pins_ORTUR_4.h @@ -91,7 +91,7 @@ // // LCD / Controller // -#if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) +#if IS_RRD_FG_SC #undef BEEPER_PIN #define BEEPER_PIN 35 diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index de56d2b59d9b..2c271408b0c3 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -45,15 +45,11 @@ * 7 | 11 */ -#ifdef TARGET_LPC1768 - #error "Oops! Set MOTHERBOARD to an LPC1768-based board when building for LPC1768." -#elif defined(__STM32F1__) - #error "Oops! Set MOTHERBOARD to an STM32F1-based board when building for STM32F1." +#if ENABLED(AZSMZ_12864) && DISABLED(ALLOW_SAM3X8E) + #error "No pins defined for RAMPS with AZSMZ_12864." #endif -#if NOT_TARGET(IS_RAMPS_SMART, IS_RAMPS_DUO, IS_RAMPS4DUE, TARGET_LPC1768, __AVR_ATmega1280__, __AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#endif +#include "env_validate.h" // Custom flags and defines for the build //#define BOARD_CUSTOM_BUILD_FLAGS -D__FOO__ @@ -124,14 +120,14 @@ #define X_DIR_PIN 55 #define X_ENABLE_PIN 38 #ifndef X_CS_PIN - #define X_CS_PIN 53 + #define X_CS_PIN EXP2_07_PIN #endif #define Y_STEP_PIN 60 #define Y_DIR_PIN 61 #define Y_ENABLE_PIN 56 #ifndef Y_CS_PIN - #define Y_CS_PIN 49 + #define Y_CS_PIN EXP2_04_PIN #endif #ifndef Z_STEP_PIN @@ -171,10 +167,10 @@ #endif // -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple // -#ifndef MAX6675_SS_PIN - #define MAX6675_SS_PIN 66 // Don't use 53 if using Display/SD card (SDSS) or 49 (SD_DETECT_PIN) +#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) #endif // @@ -223,7 +219,7 @@ #define FAN1_PIN RAMPS_D8_PIN #elif DISABLED(IS_RAMPS_SF) // Not Spindle, Fan (i.e., "EFBF" or "EFBE") #define HEATER_BED_PIN RAMPS_D8_PIN - #if HOTENDS == 1 + #if HOTENDS == 1 && DISABLED(HEATERS_PARALLEL) #define FAN1_PIN MOSFET_D_PIN #else #define HEATER_1_PIN MOSFET_D_PIN @@ -245,7 +241,9 @@ // // Misc. Functions // -#define SDSS 53 +#ifndef SDSS + #define SDSS EXP2_07_PIN +#endif #define LED_PIN 13 #ifndef FILWIDTH_PIN @@ -307,6 +305,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 */ //#define X_HARDWARE_SERIAL Serial1 //#define X2_HARDWARE_SERIAL Serial1 @@ -426,10 +427,57 @@ #define E_MUX2_PIN 44 // E1_CS_PIN #endif +// +// Aux 3 GND D52 D50 5V +// NC D53 D51 D49 + +// +// Aux 4 D16 D17 D23 D25 D27 D29 D31 D33 D35 D37 D39 D41 D43 D45 D47 D32 GND 5V +// + +/** + * LCD adapter. Please note: These comes in two variants. The socket keys can be + * on either side, and may be backwards on some boards / displays. + * _____ _____ + * D37 |10 9 | D35 (MISO) D50 |10 9 | D52 (SCK) + * D17 | 8 7 | D16 D31 | 8 7 | D53 + * D23 6 5 D25 D33 6 5 D51 (MOSI) + * D27 | 4 3 | D29 D49 | 4 3 | D41 + * GND | 2 1 | 5V GND | 2 1 | NC + * ----- ----- + * EXP1 EXP2 + */ + +#ifndef EXP1_03_PIN + #define EXP1_03_PIN 29 + #define EXP1_04_PIN 27 + #define EXP1_05_PIN 25 + #define EXP1_06_PIN 23 + #define EXP1_07_PIN 16 + #define EXP1_08_PIN 17 + #define EXP1_09_PIN 35 + #define EXP1_10_PIN 37 + + #define EXP2_03_PIN 41 + #define EXP2_04_PIN 49 + #define EXP2_05_PIN 51 + #define EXP2_06_PIN 33 + #define EXP2_07_PIN 53 + #define EXP2_08_PIN 31 + #define EXP2_09_PIN 52 + #define EXP2_10_PIN 50 +#endif + ////////////////////////// // LCDs and Controllers // ////////////////////////// +// GLCD features +// Uncomment screen orientation +//#define LCD_SCREEN_ROT_90 +//#define LCD_SCREEN_ROT_180 +//#define LCD_SCREEN_ROT_270 + #if HAS_WIRED_LCD // @@ -437,11 +485,11 @@ // #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_04_PIN // CS chip select /SS chip slave select + #define LCD_PINS_ENABLE EXP2_05_PIN // SID (MOSI) + #define LCD_PINS_D4 EXP2_09_PIN // SCK (CLK) clock - #elif BOTH(NEWPANEL, PANEL_ONE) + #elif BOTH(IS_NEWPANEL, PANEL_ONE) #define LCD_PINS_RS 40 #define LCD_PINS_ENABLE 42 @@ -452,22 +500,23 @@ #elif ENABLED(TFTGLCD_PANEL_SPI) - #define TFTGLCD_CS 33 + #define TFTGLCD_CS EXP2_06_PIN #else #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS 27 - #define LCD_PINS_ENABLE 29 - #define LCD_PINS_D4 25 + #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN - #if DISABLED(NEWPANEL) - #define BEEPER_PIN 37 + #if !IS_NEWPANEL + #define BEEPER_PIN EXP1_10_PIN #endif #elif ENABLED(ZONESTAR_LCD) + #error "CAUTION! ZONESTAR_LCD on RAMPS requires wiring modifications. It plugs into AUX2 but GND and 5V need to be swapped. Comment out this line to continue." #define LCD_PINS_RS 64 #define LCD_PINS_ENABLE 44 #define LCD_PINS_D4 63 @@ -478,63 +527,67 @@ #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 + #define LCD_PINS_DC EXP1_05_PIN // Set as output on init + #define LCD_PINS_RS EXP1_04_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_CS EXP1_07_PIN + #define DOGLCD_MOSI EXP1_08_PIN + #define DOGLCD_SCK EXP1_06_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_07_PIN + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_04_PIN #endif - #define LCD_PINS_D7 29 + #define LCD_PINS_D7 EXP1_03_PIN - #if DISABLED(NEWPANEL) - #define BEEPER_PIN 33 + #if !IS_NEWPANEL + #define BEEPER_PIN EXP2_06_PIN #endif #endif - #if DISABLED(NEWPANEL) + #if !IS_NEWPANEL // Buttons attached to a shift register // Not wired yet - //#define SHIFT_CLK 38 - //#define SHIFT_LD 42 - //#define SHIFT_OUT 40 - //#define SHIFT_EN 17 + //#define SHIFT_CLK_PIN 38 + //#define SHIFT_LD_PIN 42 + //#define SHIFT_OUT_PIN 40 + //#define SHIFT_EN_PIN EXP1_08_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 // - #if ENABLED(NEWPANEL) + #if IS_NEWPANEL - #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) + #if IS_RRD_SC - #define BEEPER_PIN 37 + #define BEEPER_PIN EXP1_10_PIN #if ENABLED(CR10_STOCKDISPLAY) - #define BTN_EN1 17 - #define BTN_EN2 23 + #define BTN_EN1 EXP1_08_PIN + #define BTN_EN2 EXP1_06_PIN #else - #define BTN_EN1 31 - #define BTN_EN2 33 + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN #endif - #define BTN_ENC 35 + #define BTN_ENC EXP1_09_PIN #ifndef SD_DETECT_PIN - #define SD_DETECT_PIN 49 + #define SD_DETECT_PIN EXP2_04_PIN #endif #ifndef KILL_PIN - #define KILL_PIN 41 + #define KILL_PIN EXP2_03_PIN #endif #if ENABLED(BQ_LCD_SMART_CONTROLLER) @@ -554,7 +607,7 @@ #define BTN_EN2 43 #define BTN_ENC 32 #define LCD_SDSS SDSS - #define KILL_PIN 41 + #define KILL_PIN EXP2_03_PIN #elif ENABLED(LCD_I2C_VIKI) @@ -563,7 +616,7 @@ #define BTN_ENC -1 #define LCD_SDSS SDSS - #define SD_DETECT_PIN 49 + #define SD_DETECT_PIN EXP2_04_PIN #elif ANY(VIKI2, miniVIKI) @@ -571,87 +624,83 @@ #define DOGLCD_A0 44 #define LCD_SCREEN_ROT_180 - #define BEEPER_PIN 33 + #define BEEPER_PIN EXP2_06_PIN #define STAT_LED_RED_PIN 32 - #define STAT_LED_BLUE_PIN 35 + #define STAT_LED_BLUE_PIN EXP1_09_PIN #define BTN_EN1 22 #define BTN_EN2 7 #define BTN_ENC 39 #define SD_DETECT_PIN -1 // Pin 49 for display SD interface, 72 for easy adapter board - #define KILL_PIN 31 + #define KILL_PIN EXP2_08_PIN #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) - #define DOGLCD_CS 29 - #define DOGLCD_A0 27 + #define DOGLCD_CS EXP1_03_PIN + #define DOGLCD_A0 EXP1_04_PIN - #define BEEPER_PIN 23 - #define LCD_BACKLIGHT_PIN 33 + #define BEEPER_PIN EXP1_06_PIN + #define LCD_BACKLIGHT_PIN EXP2_06_PIN - #define BTN_EN1 35 - #define BTN_EN2 37 - #define BTN_ENC 31 + #define BTN_EN1 EXP1_09_PIN + #define BTN_EN2 EXP1_10_PIN + #define BTN_ENC EXP2_08_PIN #define LCD_SDSS SDSS - #define SD_DETECT_PIN 49 - #define KILL_PIN 41 + #define SD_DETECT_PIN EXP2_04_PIN + #define KILL_PIN EXP2_03_PIN #elif EITHER(MKS_MINI_12864, FYSETC_MINI_12864) - #define BEEPER_PIN 37 - #define BTN_ENC 35 - #define SD_DETECT_PIN 49 + #define BEEPER_PIN EXP1_10_PIN + #define BTN_ENC EXP1_09_PIN + #ifndef SD_DETECT_PIN + #define SD_DETECT_PIN EXP2_04_PIN + #endif #ifndef KILL_PIN - #define KILL_PIN 41 + #define KILL_PIN EXP2_03_PIN #endif #if ENABLED(MKS_MINI_12864) - #define DOGLCD_A0 27 - #define DOGLCD_CS 25 - - // GLCD features - // Uncomment screen orientation - //#define LCD_SCREEN_ROT_90 - //#define LCD_SCREEN_ROT_180 - //#define LCD_SCREEN_ROT_270 + #define DOGLCD_A0 EXP1_04_PIN + #define DOGLCD_CS EXP1_05_PIN // not connected to a pin #define LCD_BACKLIGHT_PIN -1 // 65 (MKS mini12864 can't adjust backlight by software!) - #define BTN_EN1 31 - #define BTN_EN2 33 + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN #elif ENABLED(FYSETC_MINI_12864) // From https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8 - #define DOGLCD_A0 16 - #define DOGLCD_CS 17 + #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_CS EXP1_08_PIN - #define BTN_EN1 33 - #define BTN_EN2 31 + #define BTN_EN1 EXP2_06_PIN + #define BTN_EN2 EXP2_08_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_06_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 25 + #define RGB_LED_R_PIN EXP1_05_PIN #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN 27 + #define RGB_LED_G_PIN EXP1_04_PIN #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN 29 + #define RGB_LED_B_PIN EXP1_03_PIN #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN 25 + #define NEOPIXEL_PIN EXP1_05_PIN #endif #endif @@ -665,17 +714,11 @@ #define DOGLCD_A0 44 #define DOGLCD_CS 66 - // GLCD features - // Uncomment screen orientation - //#define LCD_SCREEN_ROT_90 - //#define LCD_SCREEN_ROT_180 - //#define LCD_SCREEN_ROT_270 - #define BTN_EN1 40 #define BTN_EN2 63 #define BTN_ENC 59 - #define SD_DETECT_PIN 49 + #define SD_DETECT_PIN EXP2_04_PIN #define KILL_PIN 64 #elif ENABLED(ZONESTAR_LCD) @@ -688,38 +731,38 @@ #elif IS_TFTGLCD_PANEL - #define SD_DETECT_PIN 49 + #define SD_DETECT_PIN EXP2_04_PIN #else // Beeper on AUX-4 - #define BEEPER_PIN 33 + #define BEEPER_PIN EXP2_06_PIN // Buttons are directly attached to AUX-2 #if ENABLED(PANEL_ONE) #define BTN_EN1 59 // AUX2 PIN 3 #define BTN_EN2 63 // AUX2 PIN 4 - #define BTN_ENC 49 // AUX3 PIN 7 + #define BTN_ENC EXP2_04_PIN #else - #define BTN_EN1 37 - #define BTN_EN2 35 - #define BTN_ENC 31 + #define BTN_EN1 EXP1_10_PIN + #define BTN_EN2 EXP1_09_PIN + #define BTN_ENC EXP2_08_PIN #endif #if ENABLED(G3D_PANEL) - #define SD_DETECT_PIN 49 - #define KILL_PIN 41 + #define SD_DETECT_PIN EXP2_04_PIN + #define KILL_PIN EXP2_03_PIN #endif #endif - #endif // NEWPANEL + #endif // IS_NEWPANEL #endif // HAS_WIRED_LCD -#if ENABLED(REPRAPWORLD_KEYPAD) && DISABLED(ADC_KEYPAD) - #define SHIFT_OUT 40 - #define SHIFT_CLK 44 - #define SHIFT_LD 42 +#if IS_RRW_KEYPAD && !HAS_ADC_BUTTONS + #define SHIFT_OUT_PIN 40 + #define SHIFT_CLK_PIN 44 + #define SHIFT_LD_PIN 42 #ifndef BTN_EN1 #define BTN_EN1 64 #endif @@ -735,7 +778,8 @@ #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_RAMPS.h' for details. Comment out this line to continue." - /** FYSETC TFT TFT81050 display pinout + /** + * FYSETC TFT-81050 display pinout * * Board Display * _____ _____ @@ -760,16 +804,16 @@ * EXP2-7 ----------- EXP1-4 * EXP2-8 ----------- EXP1-3 * EXP2-1 ----------- EXP1-2 - * EXP1-10 ----------- EXP1-1 + * EXP1-10 ---------- EXP1-1 * * NOTE: The MISO pin should not get a 5V signal. * To fix, insert a 1N4148 diode in the MISO line. */ - #define BEEPER_PIN 37 + #define BEEPER_PIN EXP1_10_PIN - #define SD_DETECT_PIN 49 + #define SD_DETECT_PIN EXP2_04_PIN - #define CLCD_MOD_RESET 31 - #define CLCD_SPI_CS 33 + #define CLCD_MOD_RESET EXP2_08_PIN + #define CLCD_SPI_CS EXP2_06_PIN #endif // TOUCH_UI_FTDI_EVE && LCD_FYSETC_TFT81050 diff --git a/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h b/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h index 1dc898e6ca9a..05de208ca1e9 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h @@ -35,7 +35,7 @@ #define MOSFET_D_PIN 7 #define FIL_RUNOUT_PIN 2 -#if NUM_RUNOUT_SENSORS > 1 +#if NUM_RUNOUT_SENSORS >= 2 #define FIL_RUNOUT2_PIN 15 // Creality CR-X can use dual runout sensors #endif diff --git a/Marlin/src/pins/ramps/pins_RAMPS_DAGOMA.h b/Marlin/src/pins/ramps/pins_RAMPS_DAGOMA.h deleted file mode 100644 index ad56b7f9d1e9..000000000000 --- a/Marlin/src/pins/ramps/pins_RAMPS_DAGOMA.h +++ /dev/null @@ -1,42 +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 - -#if HOTENDS > 2 || E_STEPPERS > 2 - #error "Dagoma3D F5 RAMPS supports only 2 hotends / E-steppers. Comment out this line to continue." -#endif - -#define BOARD_INFO_NAME "Dagoma3D F5 RAMPS" - -#define X_STOP_PIN 2 -#define Y_STOP_PIN 3 -#define Z_STOP_PIN 15 -#define FIL_RUNOUT_PIN 39 - -#ifndef E0_AUTO_FAN_PIN - #define E0_AUTO_FAN_PIN 7 -#endif - -// -// Import RAMPS 1.4 pins -// -#include "pins_RAMPS.h" diff --git a/Marlin/src/pins/ramps/pins_RAMPS_ENDER_4.h b/Marlin/src/pins/ramps/pins_RAMPS_ENDER_4.h index 513c7fe8d5d6..d9964242dd58 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_ENDER_4.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_ENDER_4.h @@ -22,7 +22,7 @@ #pragma once #if HOTENDS > 1 || E_STEPPERS > 1 - #error "Ender-4 supports only 1 hotend / E-stepper. Comment out this line to continue." + #error "Ender-4 only supports one hotend / E-stepper. Comment out this line to continue." #endif #define BOARD_INFO_NAME "Ender-4" diff --git a/Marlin/src/pins/ramps/pins_RAMPS_OLD.h b/Marlin/src/pins/ramps/pins_RAMPS_OLD.h index 6d2dad231491..974766623594 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_OLD.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_OLD.h @@ -25,9 +25,7 @@ * Arduino Mega with RAMPS v1.0, v1.1, v1.2 pin assignments */ -#if NOT_TARGET(__AVR_ATmega1280__, __AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "RAMPS <1.2" @@ -76,11 +74,11 @@ #define TEMP_0_PIN 2 // Analog Input #define TEMP_BED_PIN 1 // Analog Input -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 66 // Don't use 53 if using Display/SD card + #define TEMP_0_CS_PIN 66 // Don't use 53 if using Display/SD card #else - #define MAX6675_SS_PIN 66 // Don't use 49 (SD_DETECT_PIN) + #define TEMP_0_CS_PIN 66 // Don't use 49 (SD_DETECT_PIN) #endif // diff --git a/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h b/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h index 9908d9494f34..43a769b34db7 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h @@ -37,9 +37,7 @@ * RAMPS_PLUS_SF (Spindle, Controller Fan) */ -#if NOT_TARGET(__AVR_ATmega1280__, __AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "RAMPS 1.4 Plus" @@ -73,7 +71,7 @@ #undef E0_CS_PIN #undef E1_CS_PIN -#if ENABLED(ULTRA_LCD) && NONE(REPRAPWORLD_GRAPHICAL_LCD, CR10_STOCKDISPLAY) && !BOTH(NEWPANEL, PANEL_ONE) +#if IS_ULTRA_LCD && NONE(REPRAPWORLD_GRAPHICAL_LCD, CR10_STOCKDISPLAY) && !BOTH(IS_NEWPANEL, PANEL_ONE) #if DISABLED(MKS_12864OLED) || ENABLED(MKS_12864OLED_SSD1306) #undef LCD_PINS_RS #define LCD_PINS_RS 42 // 3DYMY boards pin 16 -> 42 diff --git a/Marlin/src/pins/ramps/pins_RAMPS_S_12.h b/Marlin/src/pins/ramps/pins_RAMPS_S_12.h new file mode 100644 index 000000000000..e1ba91cde8f0 --- /dev/null +++ b/Marlin/src/pins/ramps/pins_RAMPS_S_12.h @@ -0,0 +1,278 @@ +/** + * 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 + +/** + * Arduino Mega with RAMPS-S v1.2 by Sakul.cz pin assignments + * Written by Michal Rábek + * + * Applies to the following boards: + * + * BOARD_RAMPS_S_12_EEFB Ramps S 1.2 (Hotend0, Hotend1, Fan, Bed) + * BOARD_RAMPS_S_12_EEEB Ramps S 1.2 (Hotend0, Hotend1, Hotend2, Bed) + * BOARD_RAMPS_S_12_EFFB Ramps S 1.2 (Hotend, Fan0, Fan1, Bed) + * + * Other pins_MYBOARD.h files may override these defaults + */ + +#include "env_validate.h" + +// Custom flags and defines for the build +//#define BOARD_CUSTOM_BUILD_FLAGS -D__FOO__ + +#ifndef BOARD_INFO_NAME + #define BOARD_INFO_NAME "RAMPS S 1.2" +#endif + +// +// Servos +// +#ifndef SERVO0_PIN + #define SERVO0_PIN 10 +#endif +#ifndef SERVO1_PIN + #define SERVO1_PIN 11 +#endif +#ifndef SERVO2_PIN + #define SERVO2_PIN 12 +#endif +#ifndef SERVO3_PIN + #define SERVO3_PIN 44 +#endif + +// +// Limit Switches +// +#ifndef X_STOP_PIN + #ifndef X_MIN_PIN + #define X_MIN_PIN 37 + #endif + #ifndef X_MAX_PIN + #define X_MAX_PIN 36 + #endif +#endif +#ifndef Y_STOP_PIN + #ifndef Y_MIN_PIN + #define Y_MIN_PIN 35 + #endif + #ifndef Y_MAX_PIN + #define Y_MAX_PIN 34 + #endif +#endif +#ifndef Z_STOP_PIN + #ifndef Z_MIN_PIN + #define Z_MIN_PIN 33 + #endif + #ifndef Z_MAX_PIN + #define Z_MAX_PIN 32 + #endif +#endif + +// +// Z Probe (when not Z_MIN_PIN) +// +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN 5 +#endif + +// +// Filament Runout Sensor +// +#ifndef FIL_RUNOUT_PIN + #define FIL_RUNOUT_PIN 44 // RAMPS_S S3 on the servos connector +#endif + +// +// Steppers +// +#define X_STEP_PIN 17 +#define X_DIR_PIN 16 +#define X_ENABLE_PIN 48 + +#define Y_STEP_PIN 54 +#define Y_DIR_PIN 47 +#define Y_ENABLE_PIN 55 + +#ifndef Z_STEP_PIN + #define Z_STEP_PIN 57 +#endif +#define Z_DIR_PIN 56 +#define Z_ENABLE_PIN 62 + +#define E0_STEP_PIN 23 +#define E0_DIR_PIN 22 +#define E0_ENABLE_PIN 24 + +#define E1_STEP_PIN 26 +#define E1_DIR_PIN 25 +#define E1_ENABLE_PIN 27 + +#define E2_STEP_PIN 29 +#define E2_DIR_PIN 28 +#define E2_ENABLE_PIN 39 + +// +// Temperature Sensors +// +#ifndef TEMP_0_PIN + #define TEMP_0_PIN 15 // Analog Input +#endif +#ifndef TEMP_1_PIN + #define TEMP_1_PIN 14 // Analog Input +#endif +#ifndef TEMP_2_PIN + #define TEMP_2_PIN 13 // Analog Input +#endif +#ifndef TEMP_3_PIN + #define TEMP_3_PIN 12 // Analog Input +#endif +#ifndef TEMP_BED_PIN + #define TEMP_BED_PIN 11 // Analog Input +#endif + +// +// Heaters / Fans +// +#ifndef MOSFET_D_PIN + #define MOSFET_D_PIN -1 +#endif +#ifndef RAMPS_S_HE_0 + #define RAMPS_S_HE_0 2 +#endif +#ifndef RAMPS_S_HE_1 + #define RAMPS_S_HE_1 3 +#endif +#ifndef RAMPS_S_HE_2 + #define RAMPS_S_HE_2 6 +#endif + +#define HEATER_BED_PIN 9 + +#define HEATER_0_PIN RAMPS_S_HE_0 + +#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 +#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 FAN1_PIN RAMPS_S_HE_2 +#endif + +// +// Misc. Functions +// +#define SDSS 53 +#define LED_PIN 13 + +#ifndef KILL_PIN + #define KILL_PIN 46 +#endif + +#ifndef FILWIDTH_PIN + #define FILWIDTH_PIN 60 // Analog Input on EXTEND +#endif + +#ifndef PS_ON_PIN + #define PS_ON_PIN 12 // RAMPS_S S2 on the servos connector +#endif + +#if ENABLED(CASE_LIGHT_ENABLE) && !defined(CASE_LIGHT_PIN) && !defined(SPINDLE_LASER_ENA_PIN) + #if NUM_SERVOS <= 1 // Prefer the servo connector + #define CASE_LIGHT_PIN 12 // Hardware PWM (RAMPS_S S1 on the servos connector) + #elif HAS_FREE_AUX2_PINS + #define CASE_LIGHT_PIN 44 // Hardware PWM + #endif +#endif + +// +// 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_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 +#endif + +// +// Průša i3 MK2 Multiplexer Support +// +#ifndef E_MUX0_PIN + #define E_MUX0_PIN 29 // E2_STEP_PIN +#endif +#ifndef E_MUX1_PIN + #define E_MUX1_PIN 28 // E2_DIR_PIN +#endif +#ifndef E_MUX2_PIN + #define E_MUX2_PIN 39 // E2_ENABLE_PIN +#endif + +////////////////////////// +// LCDs and Controllers // +////////////////////////// + +// +// LCD Display output pins +// +#if HAS_WIRED_LCD + #define BEEPER_PIN 45 + #define LCD_PINS_RS 19 + #define LCD_PINS_ENABLE 49 + #define LCD_PINS_D4 18 + #define LCD_PINS_D5 30 + #define LCD_PINS_D6 41 + #define LCD_PINS_D7 31 + #ifndef SD_DETECT_PIN + #define SD_DETECT_PIN 38 + #endif + + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif + +#endif + +// +// LCD Display input pins +// +#if IS_NEWPANEL + #define BTN_EN1 40 + #define BTN_EN2 42 + #define BTN_ENC 43 +#endif diff --git a/Marlin/src/pins/ramps/pins_RIGIDBOARD.h b/Marlin/src/pins/ramps/pins_RIGIDBOARD.h index c43d786aa2e2..203af5e08180 100644 --- a/Marlin/src/pins/ramps/pins_RIGIDBOARD.h +++ b/Marlin/src/pins/ramps/pins_RIGIDBOARD.h @@ -75,12 +75,12 @@ #define TEMP_1_PIN 13 // Analog Input #define TEMP_BED_PIN 15 // Analog Input -// SPI for Max6675 or Max31855 Thermocouple -#undef MAX6675_SS_PIN +// SPI for MAX Thermocouple +#undef TEMP_0_CS_PIN #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 53 // Don't use pin 53 if there is even the remote possibility of using Display/SD card + #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 MAX6675_SS_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 + #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 #endif // @@ -124,7 +124,7 @@ #undef SD_DETECT_PIN #define SD_DETECT_PIN 22 -#elif ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) +#elif IS_RRD_SC #undef SD_DETECT_PIN #define SD_DETECT_PIN 22 diff --git a/Marlin/src/pins/ramps/pins_RIGIDBOARD_V2.h b/Marlin/src/pins/ramps/pins_RIGIDBOARD_V2.h index 1428de31a22b..5a6bba3c0842 100644 --- a/Marlin/src/pins/ramps/pins_RIGIDBOARD_V2.h +++ b/Marlin/src/pins/ramps/pins_RIGIDBOARD_V2.h @@ -34,7 +34,7 @@ // // I2C based DAC like on the Printrboard REVF -#define HAS_MOTOR_CURRENT_DAC +#define HAS_MOTOR_CURRENT_DAC 1 // Channels available for DAC, For Rigidboard there are 4 #define DAC_STEPPER_ORDER { 0, 1, 2, 3 } diff --git a/Marlin/src/pins/ramps/pins_RL200.h b/Marlin/src/pins/ramps/pins_RL200.h index 3fccb90276f4..047ad160bed1 100644 --- a/Marlin/src/pins/ramps/pins_RL200.h +++ b/Marlin/src/pins/ramps/pins_RL200.h @@ -37,16 +37,16 @@ #error "You must set ([XYZ]|Z2|E0)_DRIVER_TYPE to DRV8825 in Configuration.h for RL200." #endif -#define E0_STEP_PIN 26 // (RUMBA E1 pins) -#define E0_DIR_PIN 25 -#define E0_ENABLE_PIN 27 +#define E0_STEP_PIN 26 // (RUMBA E1 pins) +#define E0_DIR_PIN 25 +#define E0_ENABLE_PIN 27 -#define E1_STEP_PIN 29 // (RUMBA E2 pins) -#define E1_DIR_PIN 28 -#define E1_ENABLE_PIN 39 +#define E1_STEP_PIN 29 // (RUMBA E2 pins) +#define E1_DIR_PIN 28 +#define E1_ENABLE_PIN 39 -#define Z2_STEP_PIN 23 // (RUMBA E0 pins) -#define Z2_DIR_PIN 22 -#define Z2_ENABLE_PIN 24 +#define Z2_STEP_PIN 23 // (RUMBA E0 pins) +#define Z2_DIR_PIN 22 +#define Z2_ENABLE_PIN 24 #include "pins_RUMBA.h" diff --git a/Marlin/src/pins/ramps/pins_RUMBA.h b/Marlin/src/pins/ramps/pins_RUMBA.h index 5be2896e18c0..942afafd7a64 100644 --- a/Marlin/src/pins/ramps/pins_RUMBA.h +++ b/Marlin/src/pins/ramps/pins_RUMBA.h @@ -25,9 +25,10 @@ * RUMBA pin assignments */ -#if NOT_TARGET(__AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#elif HOTENDS > 3 || E_STEPPERS > 3 +#define REQUIRE_MEGA2560 +#include "env_validate.h" + +#if HOTENDS > 3 || E_STEPPERS > 3 #error "RUMBA supports up to 3 hotends / E-steppers. Comment out this line to continue." #endif @@ -227,7 +228,7 @@ #define SD_DETECT_PIN 49 #endif -#if ENABLED(NEWPANEL) +#if IS_NEWPANEL #define BTN_EN1 11 #define BTN_EN2 12 #define BTN_ENC 43 diff --git a/Marlin/src/pins/ramps/pins_TANGO.h b/Marlin/src/pins/ramps/pins_TANGO.h index 715444cee216..451d2f874d7f 100644 --- a/Marlin/src/pins/ramps/pins_TANGO.h +++ b/Marlin/src/pins/ramps/pins_TANGO.h @@ -27,26 +27,26 @@ #define BOARD_INFO_NAME "Tango" -#define FAN_PIN 8 -#define FAN1_PIN -1 +#define FAN_PIN 8 +#define FAN1_PIN -1 #ifndef E0_AUTO_FAN_PIN - #define E0_AUTO_FAN_PIN 7 + #define E0_AUTO_FAN_PIN 7 #endif #ifndef TEMP_0_PIN #if TEMP_SENSOR_0 == -1 - #define TEMP_0_PIN 10 // Analog Input (connector *K1* on Tango thermocouple ADD ON is used) + #define TEMP_0_PIN 10 // Analog Input (connector *K1* on Tango thermocouple ADD ON is used) #else - #define TEMP_0_PIN 15 // Analog Input (default connector for thermistor *T0* on rumba board is used) + #define TEMP_0_PIN 15 // Analog Input (default connector for thermistor *T0* on rumba board is used) #endif #endif #ifndef TEMP_1_PIN #if TEMP_SENSOR_1 == -1 - #define TEMP_1_PIN 9 // Analog Input (connector *K2* on Tango thermocouple ADD ON is used) + #define TEMP_1_PIN 9 // Analog Input (connector *K2* on Tango thermocouple ADD ON is used) #else - #define TEMP_1_PIN 14 // Analog Input (default connector for thermistor *T1* on rumba board is used) + #define TEMP_1_PIN 14 // Analog Input (default connector for thermistor *T1* on rumba board is used) #endif #endif diff --git a/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h b/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h index e7a59a69dffe..b884fcbfc7c1 100644 --- a/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h +++ b/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h @@ -25,9 +25,10 @@ * Tenlog pin assignments */ -#if NOT_TARGET(__AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#elif HOTENDS > 2 || E_STEPPERS > 2 +#define REQUIRE_MEGA2560 +#include "env_validate.h" + +#if HOTENDS > 2 || E_STEPPERS > 2 #error "Tenlog supports up to 2 hotends / E-steppers. Comment out this line to continue." #endif @@ -122,11 +123,11 @@ #define TEMP_1_PIN 15 // Analog Input #define TEMP_BED_PIN 14 // Analog Input -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN -1 // Don't use 53 if using Display/SD card + #define TEMP_0_CS_PIN -1 // Don't use 53 if using Display/SD card #else - #define MAX6675_SS_PIN -1 // Don't use 49 (SD_DETECT_PIN) + #define TEMP_0_CS_PIN -1 // Don't use 49 (SD_DETECT_PIN) #endif // @@ -137,7 +138,7 @@ #define HEATER_BED_PIN 8 #define FAN_PIN 9 -#define FAN1_PIN 5 // Normall this would be a servo pin +#define FAN1_PIN 5 // Normally this would be a servo pin // XXX Runout support unknown? //#define NUM_RUNOUT_SENSORS 0 @@ -163,7 +164,7 @@ // LCD / Controller // -//#if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) +//#if IS_RRD_SC #define LCD_PINS_RS -1 #define LCD_PINS_ENABLE -1 @@ -182,4 +183,4 @@ #define BEEPER_PIN -1 //#endif -//#endif // REPRAP_DISCOUNT_SMART_CONTROLLER +//#endif // IS_RRD_SC diff --git a/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h b/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h index 1c2cb609579e..54d91cee6a81 100644 --- a/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h +++ b/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h @@ -131,13 +131,13 @@ #if 0 && HAS_WIRED_LCD // LCD Display output pins - #if BOTH(NEWPANEL, PANEL_ONE) + #if BOTH(IS_NEWPANEL, PANEL_ONE) #undef LCD_PINS_D6 #define LCD_PINS_D6 57 #endif // LCD Display input pins - #if ENABLED(NEWPANEL) + #if IS_NEWPANEL #if ANY(VIKI2, miniVIKI) #undef DOGLCD_A0 #define DOGLCD_A0 23 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 f342eff8aa6c..ffe6d56eb8b1 100644 --- a/Marlin/src/pins/ramps/pins_TRONXY_V3_1_0.h +++ b/Marlin/src/pins/ramps/pins_TRONXY_V3_1_0.h @@ -25,9 +25,10 @@ * Arduino Mega for Tronxy X5S-2E, etc. */ -#if NOT_TARGET(__AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#elif HOTENDS > 2 || E_STEPPERS > 2 +#define REQUIRE_MEGA2560 +#include "env_validate.h" + +#if HOTENDS > 2 || E_STEPPERS > 2 #error "TRONXY-V3-1.0 supports only 2 hotends/E-steppers. Comment out this line to continue." #endif diff --git a/Marlin/src/pins/ramps/pins_TT_OSCAR.h b/Marlin/src/pins/ramps/pins_TT_OSCAR.h index 1568288e69bc..57a9a560d35b 100644 --- a/Marlin/src/pins/ramps/pins_TT_OSCAR.h +++ b/Marlin/src/pins/ramps/pins_TT_OSCAR.h @@ -19,10 +19,9 @@ * along with this program. If not, see . * */ +#pragma once -#if NOT_TARGET(__AVR_ATmega1280__, __AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#endif +#include "env_validate.h" #if HOTENDS > 5 || E_STEPPERS > 5 #error "TTOSCAR supports up to 5 hotends / E-steppers. Comment out this line to continue." @@ -182,11 +181,11 @@ #define TEMP_4_PIN 12 #endif -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple //#if DISABLED(SDSUPPORT) -// #define MAX6675_SS_PIN 66 // Don't use 53 if using Display/SD card +// #define TEMP_0_CS_PIN 66 // Don't use 53 if using Display/SD card //#else -// #define MAX6675_SS_PIN 66 // Don't use 49 (SD_DETECT_PIN) +// #define TEMP_0_CS_PIN 66 // Don't use 49 (SD_DETECT_PIN) //#endif // @@ -282,7 +281,7 @@ #define LCD_PINS_ENABLE 51 // SID (MOSI) #define LCD_PINS_D4 52 // SCK (CLK) clock - #elif BOTH(NEWPANEL, PANEL_ONE) + #elif BOTH(IS_NEWPANEL, PANEL_ONE) #define LCD_PINS_RS 40 #define LCD_PINS_ENABLE 42 @@ -309,7 +308,7 @@ #define LCD_PINS_ENABLE 29 #define LCD_PINS_D4 25 - #if DISABLED(NEWPANEL) + #if !IS_NEWPANEL #define BEEPER_PIN 37 #endif @@ -333,29 +332,33 @@ #define LCD_PINS_D7 29 - #if DISABLED(NEWPANEL) + #if !IS_NEWPANEL #define BEEPER_PIN 33 #endif #endif - #if DISABLED(NEWPANEL) + #if !IS_NEWPANEL // Buttons attached to a shift register // Not wired yet - //#define SHIFT_CLK 38 - //#define SHIFT_LD 42 - //#define SHIFT_OUT 40 - //#define SHIFT_EN 17 + //#define SHIFT_CLK_PIN 38 + //#define SHIFT_LD_PIN 42 + //#define SHIFT_OUT_PIN 40 + //#define SHIFT_EN_PIN 17 #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 // - #if ENABLED(NEWPANEL) + #if IS_NEWPANEL - #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) + #if IS_RRD_SC #define BEEPER_PIN 37 @@ -486,10 +489,10 @@ #define BEEPER_PIN 33 // Buttons are directly attached to AUX-2 - #if ENABLED(REPRAPWORLD_KEYPAD) - #define SHIFT_OUT 40 - #define SHIFT_CLK 44 - #define SHIFT_LD 42 + #if IS_RRW_KEYPAD + #define SHIFT_OUT_PIN 40 + #define SHIFT_CLK_PIN 44 + #define SHIFT_LD_PIN 42 #define BTN_EN1 64 #define BTN_EN2 59 #define BTN_ENC 63 @@ -510,6 +513,6 @@ #endif - #endif // NEWPANEL + #endif // IS_NEWPANEL #endif diff --git a/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h b/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h index c6251ae8175c..128f1974e0e6 100644 --- a/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h +++ b/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h @@ -33,13 +33,12 @@ * case light */ -#if NOT_TARGET(__AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#endif +#define REQUIRE_MEGA2560 +#include "env_validate.h" #define BOARD_INFO_NAME "Ultimaker 2.x" #define DEFAULT_MACHINE_NAME "Ultimaker" -#define DEFAULT_SOURCE_CODE_URL "https://github.com/Ultimaker/Marlin" +#define DEFAULT_SOURCE_CODE_URL "github.com/Ultimaker/Marlin" // // Limit Switches diff --git a/Marlin/src/pins/ramps/pins_ULTIMAKER.h b/Marlin/src/pins/ramps/pins_ULTIMAKER.h index 597a37bdbc8b..0bc04d962aaf 100644 --- a/Marlin/src/pins/ramps/pins_ULTIMAKER.h +++ b/Marlin/src/pins/ramps/pins_ULTIMAKER.h @@ -33,13 +33,11 @@ * case light */ -#if NOT_TARGET(__AVR_ATmega1280__, __AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "Ultimaker" #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME -#define DEFAULT_SOURCE_CODE_URL "https://github.com/Ultimaker/Marlin" +#define DEFAULT_SOURCE_CODE_URL "github.com/Ultimaker/Marlin" // // Servos @@ -123,7 +121,7 @@ #define BEEPER_PIN 18 - #if ENABLED(NEWPANEL) + #if IS_NEWPANEL #define LCD_PINS_RS 20 #define LCD_PINS_ENABLE 17 @@ -139,13 +137,13 @@ #define SD_DETECT_PIN 38 - #else // !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 38 - #define SHIFT_LD 42 - #define SHIFT_OUT 40 - #define SHIFT_EN 17 + #define SHIFT_CLK_PIN 38 + #define SHIFT_LD_PIN 42 + #define SHIFT_OUT_PIN 40 + #define SHIFT_EN_PIN 17 #define LCD_PINS_RS 16 #define LCD_PINS_ENABLE 5 @@ -156,7 +154,7 @@ #define SD_DETECT_PIN -1 - #endif // !NEWPANEL + #endif // !IS_NEWPANEL #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h b/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h index c5bbd02bf5a9..091356a11f82 100644 --- a/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h +++ b/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h @@ -60,9 +60,7 @@ //#define BOARD_REV_1_0 //#define BOARD_REV_1_5 -#if NOT_TARGET(__AVR_ATmega1280__, __AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#endif +#include "env_validate.h" #ifdef BOARD_REV_1_1_TO_1_3 #define BOARD_INFO_NAME "Ultimaker 1.1-1.3" @@ -74,7 +72,7 @@ #define BOARD_INFO_NAME "Ultimaker 1.5.4+" #endif #define DEFAULT_MACHINE_NAME "Ultimaker" -#define DEFAULT_SOURCE_CODE_URL "https://github.com/Ultimaker/Marlin" +#define DEFAULT_SOURCE_CODE_URL "github.com/Ultimaker/Marlin" // // Limit Switches @@ -174,11 +172,11 @@ #define LCD_PINS_D6 32 #define LCD_PINS_D7 30 -#elif BOTH(BOARD_REV_1_5, ULTRA_LCD) +#elif BOTH(BOARD_REV_1_5, IS_ULTRA_LCD) #define BEEPER_PIN 18 - #if ENABLED(NEWPANEL) + #if IS_NEWPANEL #define LCD_PINS_RS 20 #define LCD_PINS_ENABLE 17 @@ -194,13 +192,13 @@ #define SD_DETECT_PIN 38 - #else // !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 38 - #define SHIFT_LD 42 - #define SHIFT_OUT 40 - #define SHIFT_EN 17 + #define SHIFT_CLK_PIN 38 + #define SHIFT_LD_PIN 42 + #define SHIFT_OUT_PIN 40 + #define SHIFT_EN_PIN 17 #define LCD_PINS_RS 16 #define LCD_PINS_ENABLE 5 @@ -209,7 +207,7 @@ #define LCD_PINS_D6 20 #define LCD_PINS_D7 19 - #endif // !NEWPANEL + #endif // !IS_NEWPANEL #endif diff --git a/Marlin/src/pins/ramps/pins_VORON.h b/Marlin/src/pins/ramps/pins_VORON.h index 40ec71b6f0fb..9ab657346814 100644 --- a/Marlin/src/pins/ramps/pins_VORON.h +++ b/Marlin/src/pins/ramps/pins_VORON.h @@ -28,7 +28,7 @@ #define BOARD_INFO_NAME "VORON Design v2" -#define RAMPS_D8_PIN 11 +#define RAMPS_D8_PIN 11 #include "pins_RAMPS.h" @@ -36,17 +36,17 @@ // Heaters / Fans // #undef FAN_PIN -#define FAN_PIN 5 // Using the pin for the controller fan since controller fan is always on. -#define CONTROLLER_FAN_PIN 8 +#define FAN_PIN 5 // Using the pin for the controller fan since controller fan is always on. +#define CONTROLLER_FAN_PIN 8 // // Auto fans // #ifndef E0_AUTO_FAN_PIN - #define E0_AUTO_FAN_PIN 6 // Servo pin 6 for E3D Fan + #define E0_AUTO_FAN_PIN 6 // Servo pin 6 for E3D Fan #endif #ifndef E1_AUTO_FAN_PIN - #define E1_AUTO_FAN_PIN 6 // Servo pin 6 for E3D Fan (same pin for both extruders since it's the same fan) + #define E1_AUTO_FAN_PIN 6 // Servo pin 6 for E3D Fan (same pin for both extruders since it's the same fan) #endif // diff --git a/Marlin/src/pins/ramps/pins_ZRIB_V20.h b/Marlin/src/pins/ramps/pins_ZRIB_V20.h index 90433c62d751..6c4b28d0b874 100644 --- a/Marlin/src/pins/ramps/pins_ZRIB_V20.h +++ b/Marlin/src/pins/ramps/pins_ZRIB_V20.h @@ -69,9 +69,9 @@ #undef ADC_KEYPAD_PIN #undef BEEPER_PIN - #undef SHIFT_OUT - #undef SHIFT_CLK - #undef SHIFT_LD + #undef SHIFT_OUT_PIN + #undef SHIFT_CLK_PIN + #undef SHIFT_LD_PIN #undef BTN_EN1 #undef BTN_EN2 #undef BTN_ENC diff --git a/Marlin/src/pins/ramps/pins_ZRIB_V52.h b/Marlin/src/pins/ramps/pins_ZRIB_V52.h new file mode 100644 index 000000000000..f4db07ef8d4e --- /dev/null +++ b/Marlin/src/pins/ramps/pins_ZRIB_V52.h @@ -0,0 +1,160 @@ +/** + * 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 + +/** + * ZRIB V5.2 Based on MKS BASE v1.4 with A4982 stepper drivers and digital micro-stepping + */ + +#if HOTENDS > 2 || E_STEPPERS > 2 + #error "ZRIB V5.2 only supports up to 2 hotends / E-steppers. Comment out this line to continue." +#endif + +#define BOARD_INFO_NAME "ZRIB V5.2" + +#define MKS_BASE_VERSION 14 +#define IS_RAMPS_EFB + +// +// Heaters / Fans +// +#define FAN_PIN 9 // PH6 ** Pin18 ** PWM9 +#define FAN1_PIN 6 + +// +// Extra Extruder / Stepper for V5.2 +// +#define E2_STEP_PIN 4 +#define E2_DIR_PIN 5 +#define E2_ENABLE_PIN 22 +#define HEATER_1_PIN 7 + +#include "pins_MKS_BASE_common.h" + +/* + Available connectors on MKS BASE v1.4 (Basically same as ZRIB V5.2) + + ======= + | GND | + |-----| E0 + | 10 | (10) PB4 ** Pin23 ** PWM10 + |-----| + | GND | + |-----| E1 + | 7 | ( 7) PH4 ** Pin16 ** PWM7 + |-----| + | GND | + |-----| FAN + | 9 | ( 9) PH6 ** Pin18 ** PWM9 + ======= + + ======= + | GND | + |-----| Heated Bed + | 8 | ( 8) PH5 ** Pin17 ** PWM8 + ======= + + ========== + | 12-24V | + |--------| Power + | GND | + ========== + + XS3 Connector + ================= + | 65 | GND | 5V | (65) PK3 ** Pin86 ** A11 + |----|-----|----| + | 66 | GND | 5V | (66) PK4 ** Pin85 ** A12 + ================= + + Servos Connector + ================= + | 11 | GND | 5V | (11) PB5 ** Pin24 ** PWM11 + |----|-----|----| + | 12 | GND | 5V | (12) PB6 ** Pin25 ** PWM12 + ================= + + ICSP + ================= + | 5V | 51 | GND | (51) PB2 ** Pin21 ** SPI_MOSI + |----|----|-----| + | 50 | 52 | RST | (50) PB3 ** Pin22 ** SPI_MISO + ================= (52) PB1 ** Pin20 ** SPI_SCK + + XS6/AUX-1 Connector + ====================== + | 5V | GND | NC | 20 | (20) PD1 ** Pin44 ** I2C_SDA + |----|-----|----|----| + | 50 | 51 | 52 | 21 | (50) PB3 ** Pin22 ** SPI_MISO + ====================== (51) PB2 ** Pin21 ** SPI_MOSI + (52) PB1 ** Pin20 ** SPI_SCK + (21) PD0 ** Pin43 ** I2C_SCL + + Temperature + ================================== + | GND | 69 | GND | 68 | GND | 67 | + ================================== + (69) PK7 ** Pin82 ** A15 + (68) PK6 ** Pin83 ** A14 + (67) PK5 ** Pin84 ** A13 + + Limit Switches + ============ + | 2 | GND | X+ ( 2) PE4 ** Pin6 ** PWM2 + |----|-----| + | 3 | GND | X- ( 3) PE5 ** Pin7 ** PWM3 + |----|-----| + | 15 | GND | Y+ (15) PJ0 ** Pin63 ** USART3_RX + |----|-----| + | 14 | GND | Y- (14) PJ1 ** Pin64 ** USART3_TX + |----|-----| + | 19 | GND | Z+ (19) PD2 ** Pin45 ** USART1_RX + |----|-----| + | 18 | GND | Z- (18) PD3 ** Pin46 ** USART1_TX + ============ + + EXP1 + ============ + | 37 | 35 | (37) PC0 ** Pin53 ** D37 + |-----|----| (35) PC2 ** Pin55 ** D35 + | 17 | 16 | (17) PH0 ** Pin12 ** USART2_RX + |-----|----| (16) PH1 ** Pin13 ** USART2_TX + | 23 | 25 | (23) PA1 ** Pin77 ** D23 + |-----|----| (25) PA3 ** Pin75 ** D25 + | 27 | 29 | (27) PA5 ** Pin73 ** D27 + |-----|----| (29) PA7 ** Pin71 ** D29 + | GND | 5V | + ============ + + EXP2 + ============ + | 50 | 52 | (50) PB3 ** Pin22 ** SPI_MISO + |-----|----| (52) PB1 ** Pin20 ** SPI_SCK + | 31 | 53 | (31) PC6 ** Pin59 ** D31 + |-----|----| (53) PB0 ** Pin19 ** SPI_SS + | 33 | 51 | (33) PC4 ** Pin57 ** D33 + |-----|----| (51) PB2 ** Pin21 ** SPI_MOSI + | 49 | 41 | (49) PL0 ** Pin35 ** D49 + |-----|----| (41) PG0 ** Pin51 ** D41 + | GND | NC | + ============ +*/ 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 096d970871f2..26ad5fd6580a 100644 --- a/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h +++ b/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h @@ -25,9 +25,10 @@ * Z-Bolt X Series board – based on Arduino Mega2560 */ -#if NOT_TARGET(__AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#elif HOTENDS > 4 || E_STEPPERS > 4 +#define REQUIRE_MEGA2560 +#include "env_validate.h" + +#if HOTENDS > 4 || E_STEPPERS > 4 #error "Z-Bolt X Series board supports up to 4 hotends / E-steppers." #endif diff --git a/Marlin/src/pins/sam/env_validate.h b/Marlin/src/pins/sam/env_validate.h new file mode 100644 index 000000000000..09bcd1364921 --- /dev/null +++ b/Marlin/src/pins/sam/env_validate.h @@ -0,0 +1,33 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#if BOTH(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.'" +#elif ENABLED(ALLOW_MEGA1280) && NOT_TARGET(__SAM3X8E__, __AVR_ATmega1280__) + #error "Oops! Select 'Arduino Due' in 'Tools > Board.'" +#endif + +#undef ALLOW_MEGA1280 +#undef ALLOW_MEGA2560 diff --git a/Marlin/src/pins/sam/pins_ADSK.h b/Marlin/src/pins/sam/pins_ADSK.h index b0e171cf1716..425d6d45afb3 100644 --- a/Marlin/src/pins/sam/pins_ADSK.h +++ b/Marlin/src/pins/sam/pins_ADSK.h @@ -27,9 +27,9 @@ #define BOARD_INFO_NAME "ADSK" -#if NOT_TARGET(__SAM3X8E__, __AVR_ATmega1280__, __AVR_ATmega2560__) - #error "Oops! Select 'Arduino Due or Mega' in 'Tools > Board.'" -#endif +#define ALLOW_MEGA1280 +#define ALLOW_MEGA2560 +#include "env_validate.h" /* CNC shield modifications: FROM THE BOTTOM CUT THE 5V PIN THAT GOES TO ARDUINO!!! @@ -47,10 +47,10 @@ A stepper for E0 extruder Vcc (now "5V" on the board but actual 3.3V because of jumper)) (Hold)&(GND) - Bed thermistor (also require pullup resistor 4.7K between "Hold" and Vcc (now "5V" on the board but actual 3.3V because of jumper)) -(CoolEn) - 3.3v signal to controll extruder heater MOSFET +(CoolEn) - 3.3v signal to control extruder heater MOSFET (Resume) - 3.3v signal to control heatbed MOSFET -(SDA) - 3.3v signal to controll extruder fan -(SCL) - 3.3v signal to controll extruder cooling fan +(SDA) - 3.3v signal to control extruder fan +(SCL) - 3.3v signal to control extruder cooling fan */ /* CNC Shield pinout @@ -86,9 +86,9 @@ A stepper for E0 extruder // // Limit Switches // -#define X_MIN_PIN 9 -#define Y_MIN_PIN 10 -#define Z_MIN_PIN 11 +#define X_STOP_PIN 9 +#define Y_STOP_PIN 10 +#define Z_STOP_PIN 11 #define Z_MIN_PROBE_PIN 62 // Analog pin 8, Digital pin 62 @@ -137,7 +137,7 @@ A stepper for E0 extruder * The 2004 LCD should be powered with 5V. * The next LCD pins RS,D4,D5,D6,D7 have internal pull-ups to 5V and as result the 5V will be on these pins. * Luckily these internal pull-ups have really high resistance and adding 33K pull-down resistors will create - * simple voltage divider that will bring the voltage down just slightly bellow 3.3V. + * simple voltage divider that will bring the voltage down just slightly below 3.3V. * * This LCD also has buttons that connected to the same ADC pin with different voltage divider combinations. * On the LCD panel there is internal pull-up resistor of the 4.7K connected to 5V. @@ -175,7 +175,7 @@ A stepper for E0 extruder #define ADC_BUTTONS_VALUE_SCALE (5.0/AREF_VOLTS) // The LCD module pullup voltage is 5.0V but ADC reference voltage is 3.3V - #define ADC_BUTTONS_R_PULLDOWN 4.7 // Moves voltage down to be bellow 3.3V instead of 5V + #define ADC_BUTTONS_R_PULLDOWN 4.7 // Moves voltage down to be below 3.3V instead of 5V // the resistors values will be scaled because of 4.7K pulldown parallel resistor #define _ADC_BUTTONS_R_SCALED(R) ((R) * (ADC_BUTTONS_R_PULLDOWN) / ((R) + ADC_BUTTONS_R_PULLDOWN)) diff --git a/Marlin/src/pins/sam/pins_ALLIGATOR_R2.h b/Marlin/src/pins/sam/pins_ALLIGATOR_R2.h index 8d6906117dd1..c273edfc6b4d 100644 --- a/Marlin/src/pins/sam/pins_ALLIGATOR_R2.h +++ b/Marlin/src/pins/sam/pins_ALLIGATOR_R2.h @@ -26,9 +26,7 @@ * https://reprap.org/wiki/Alligator_Board */ -#if NOT_TARGET(__SAM3X8E__) - #error "Oops! Select 'Arduino Due' in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "Alligator Board R2" @@ -143,7 +141,7 @@ // // LCD / Controller // -#if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) +#if IS_RRD_FG_SC #define LCD_PINS_RS 18 #define LCD_PINS_ENABLE 15 #define LCD_PINS_D4 19 @@ -152,7 +150,7 @@ #define UI_VOLTAGE_LEVEL 1 #endif -#if ENABLED(NEWPANEL) +#if IS_NEWPANEL #define BTN_EN1 14 #define BTN_EN2 16 #define BTN_ENC 17 diff --git a/Marlin/src/pins/sam/pins_ARCHIM1.h b/Marlin/src/pins/sam/pins_ARCHIM1.h index 6e3768c663bc..57bbeb62a280 100644 --- a/Marlin/src/pins/sam/pins_ARCHIM1.h +++ b/Marlin/src/pins/sam/pins_ARCHIM1.h @@ -170,9 +170,9 @@ #define INT_SDSS 55 // D55 PA24/MCDA3 // External SD card reader on SC2 -#define SCK_PIN 76 // D76 PA27 -#define MISO_PIN 74 // D74 PA25 -#define MOSI_PIN 75 // D75 PA26 +#define SD_SCK_PIN 76 // D76 PA27 +#define SD_MISO_PIN 74 // D74 PA25 +#define SD_MOSI_PIN 75 // D75 PA26 #define SDSS 87 // D87 PA29 // 2MB SPI Flash @@ -192,10 +192,15 @@ #define SD_DETECT_PIN 2 // D2 PB25_TIOA0 - #if ENABLED(NEWPANEL) + #if IS_NEWPANEL // Buttons on AUX-2 #define BTN_EN1 60 // D60 PA3_TIOB1 #define BTN_EN2 13 // D13 PB27_TIOB0 #define BTN_ENC 16 // D16 PA13_TXD1 - #endif // NEWPANEL + #endif // IS_NEWPANEL + + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif + #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/sam/pins_ARCHIM2.h b/Marlin/src/pins/sam/pins_ARCHIM2.h index 5a3fe0e4d5c7..ecff888ff05e 100644 --- a/Marlin/src/pins/sam/pins_ARCHIM2.h +++ b/Marlin/src/pins/sam/pins_ARCHIM2.h @@ -71,7 +71,7 @@ #define E0_DIAG_PIN 78 // PB23 #define E1_DIAG_PIN 25 // PD0 - #if X_HOME_DIR < 0 + #if X_HOME_TO_MIN #define X_MIN_PIN X_DIAG_PIN #define X_MAX_PIN 32 #else @@ -79,7 +79,7 @@ #define X_MAX_PIN X_DIAG_PIN #endif - #if Y_HOME_DIR < 0 + #if Y_HOME_TO_MIN #define Y_MIN_PIN Y_DIAG_PIN #define Y_MAX_PIN 15 #else @@ -192,9 +192,9 @@ #define INT_SDSS 55 // D55 PA24/MCDA3 // External SD card reader on SC2 -#define SCK_PIN 76 // D76 PA27 -#define MISO_PIN 74 // D74 PA25 -#define MOSI_PIN 75 // D75 PA26 +#define SD_SCK_PIN 76 // D76 PA27 +#define SD_MISO_PIN 74 // D74 PA25 +#define SD_MOSI_PIN 75 // D75 PA26 #define SDSS 87 // D87 PA29 // Unused Digital GPIO J20 Pins @@ -247,11 +247,11 @@ #define LCD_PINS_D7 34 // D34 PC2_PWML0 #define SD_DETECT_PIN 2 // D2 PB25_TIOA0 +#endif - #if ANY(ULTIPANEL, TOUCH_UI_ULTIPANEL, TOUCH_UI_FTDI_EVE) - // Buttons on AUX-2 - #define BTN_EN1 60 // D60 PA3_TIOB1 - #define BTN_EN2 13 // D13 PB27_TIOB0 - #define BTN_ENC 16 // D16 PA13_TXD1 // the click - #endif +#if ANY(IS_ULTIPANEL, TOUCH_UI_ULTIPANEL, TOUCH_UI_FTDI_EVE) + // Buttons on AUX-2 + #define BTN_EN1 60 // D60 PA3_TIOB1 + #define BTN_EN2 13 // D13 PB27_TIOB0 + #define BTN_ENC 16 // D16 PA13_TXD1 // the click #endif diff --git a/Marlin/src/pins/sam/pins_CNCONTROLS_15D.h b/Marlin/src/pins/sam/pins_CNCONTROLS_15D.h index fcd2bb4c67bf..d44f6490da63 100644 --- a/Marlin/src/pins/sam/pins_CNCONTROLS_15D.h +++ b/Marlin/src/pins/sam/pins_CNCONTROLS_15D.h @@ -19,14 +19,13 @@ * along with this program. If not, see . * */ +#pragma once /** * CNControls V15 for HMS434 with DUE pin assignments */ -#if NOT_TARGET(__SAM3X8E__) - #error "Oops! Select 'Arduino Due' in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "CN Controls V15D" @@ -117,9 +116,9 @@ // // SD card // -#define SCK_PIN 76 -#define MISO_PIN 74 -#define MOSI_PIN 75 +#define SD_SCK_PIN 76 +#define SD_MISO_PIN 74 +#define SD_MOSI_PIN 75 #define SDSS 53 #define SD_DETECT_PIN 40 diff --git a/Marlin/src/pins/sam/pins_DUE3DOM.h b/Marlin/src/pins/sam/pins_DUE3DOM.h index cd4033aa6f1f..81eca3e4b14a 100644 --- a/Marlin/src/pins/sam/pins_DUE3DOM.h +++ b/Marlin/src/pins/sam/pins_DUE3DOM.h @@ -25,9 +25,7 @@ * DUE3DOM pin assignments */ -#if NOT_TARGET(__SAM3X8E__) - #error "Oops! Select 'Arduino Due' in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "DUE3DOM" @@ -84,11 +82,11 @@ #define TEMP_2_PIN 5 // Analog Input (unused) #define TEMP_BED_PIN 1 // Analog Input (BED thermistor) -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN -1 + #define TEMP_0_CS_PIN -1 #else - #define MAX6675_SS_PIN -1 + #define TEMP_0_CS_PIN -1 #endif // @@ -122,7 +120,7 @@ #define LCD_PINS_D6 46 #define LCD_PINS_D7 47 - #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) + #if IS_RRD_SC #define BEEPER_PIN 41 @@ -130,7 +128,6 @@ #define BTN_EN2 52 #define BTN_ENC 48 - #define SDSS 4 #define SD_DETECT_PIN 14 #elif ENABLED(RADDS_DISPLAY) @@ -143,8 +140,6 @@ #define BTN_BACK 71 - #undef SDSS - #define SDSS 4 #define SD_DETECT_PIN 14 #elif HAS_U8GLIB_I2C_OLED @@ -168,4 +163,9 @@ #define BEEPER_PIN -1 #endif // SPARK_FULL_GRAPHICS + + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif + #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/sam/pins_DUE3DOM_MINI.h b/Marlin/src/pins/sam/pins_DUE3DOM_MINI.h index 5f9ad48a08c4..bc0d29b00a02 100644 --- a/Marlin/src/pins/sam/pins_DUE3DOM_MINI.h +++ b/Marlin/src/pins/sam/pins_DUE3DOM_MINI.h @@ -25,9 +25,7 @@ * DUE3DOM MINI pin assignments */ -#if NOT_TARGET(__SAM3X8E__) - #error "Oops! Select 'Arduino Due' in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "DUE3DOM MINI" @@ -42,12 +40,9 @@ // // Limit Switches // -#define X_MIN_PIN 38 -#define X_MAX_PIN -1 -#define Y_MIN_PIN 34 -#define Y_MAX_PIN -1 -#define Z_MIN_PIN 30 -#define Z_MAX_PIN -1 +#define X_STOP_PIN 38 +#define Y_STOP_PIN 34 +#define Z_STOP_PIN 30 // // Steppers @@ -76,11 +71,11 @@ #define TEMP_2_PIN 5 // Analog Input (OnBoard thermistor beta 3950) #define TEMP_BED_PIN 1 // Analog Input (BED thermistor) -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 53 + #define TEMP_0_CS_PIN 53 #else - #define MAX6675_SS_PIN 53 + #define TEMP_0_CS_PIN 53 #endif // @@ -114,7 +109,7 @@ #define LCD_PINS_D6 46 #define LCD_PINS_D7 47 - #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) + #if IS_RRD_SC #define BEEPER_PIN 41 @@ -122,7 +117,10 @@ #define BTN_EN2 52 #define BTN_ENC 48 - #define SDSS 4 + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif + #define SD_DETECT_PIN 14 #elif ENABLED(RADDS_DISPLAY) @@ -135,8 +133,6 @@ #define BTN_BACK 71 - #undef SDSS - #define SDSS 4 #define SD_DETECT_PIN 14 #elif HAS_U8GLIB_I2C_OLED @@ -145,7 +141,7 @@ #define BTN_EN2 52 #define BTN_ENC 48 #define BEEPER_PIN 41 - #define LCD_SDSS 4 + #define LCD_SDSS SDSS #define SD_DETECT_PIN 14 #elif ENABLED(SPARK_FULL_GRAPHICS) @@ -160,15 +156,17 @@ #define BEEPER_PIN -1 - #elif ENABLED(MINIPANEL) + #elif ENABLED(MINIPANEL) + #define BTN_EN1 52 #define BTN_EN2 50 #define BTN_ENC 48 - #define LCD_SDSS 4 + #define LCD_SDSS SDSS #define SD_DETECT_PIN 14 #define BEEPER_PIN 41 #define DOGLCD_A0 46 #define DOGLCD_CS 45 - #endif // SPARK_FULL_GRAPHICS + #endif + #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/sam/pins_KRATOS32.h b/Marlin/src/pins/sam/pins_KRATOS32.h new file mode 100644 index 000000000000..f429e5634706 --- /dev/null +++ b/Marlin/src/pins/sam/pins_KRATOS32.h @@ -0,0 +1,179 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * KRATOS32 + */ + +#include "env_validate.h" + +#define BOARD_INFO_NAME "K.3D KRATOS32" + +// +// EEPROM +// +#if EITHER(NO_EEPROM_SELECTED, I2C_EEPROM) + #define I2C_EEPROM + #define MARLIN_EEPROM_SIZE 0x1F400 // 16KB +#endif + +// +// Servos +// +#define SERVO0_PIN 6 +#define SERVO1_PIN 5 +#define SERVO2_PIN 39 +#define SERVO3_PIN 40 // CAMERA_PIN (extended to the top of the LCD module) +#define SERVO4_PIN 45 // FIL_RUNOUT_PIN + +// +// Limit Switches +// +#define X_MIN_PIN 28 +#define X_MAX_PIN 34 +#define Y_MIN_PIN 30 +#define Y_MAX_PIN 36 +#define Z_MIN_PIN 32 +#define Z_MAX_PIN 38 + +// +// Steppers +// +#define X_STEP_PIN 24 +#define X_DIR_PIN 23 +#define X_ENABLE_PIN 26 +#ifndef X_CS_PIN + #define X_CS_PIN 25 +#endif + +#define Y_STEP_PIN 17 +#define Y_DIR_PIN 16 +#define Y_ENABLE_PIN 22 +#ifndef Y_CS_PIN + #define Y_CS_PIN 27 +#endif + +#define Z_STEP_PIN 2 +#define Z_DIR_PIN 3 +#define Z_ENABLE_PIN 15 +#ifndef Z_CS_PIN + #define Z_CS_PIN 29 +#endif + +#define E0_STEP_PIN 61 +#define E0_DIR_PIN 60 +#define E0_ENABLE_PIN 62 +#ifndef E0_CS_PIN + #define E0_CS_PIN 31 +#endif + +#define E1_STEP_PIN 64 +#define E1_DIR_PIN 63 +#define E1_ENABLE_PIN 65 +#ifndef E1_CS_PIN + #define E1_CS_PIN 37 +#endif + +#define E2_STEP_PIN 68 +#define E2_DIR_PIN 67 +#define E2_ENABLE_PIN 69 +#ifndef E2_CS_PIN + #define E2_CS_PIN 35 +#endif + +#define E3_STEP_PIN 51 +#define E3_DIR_PIN 53 +#define E3_ENABLE_PIN 49 +#ifndef E3_CS_PIN + #define E3_CS_PIN 33 +#endif + +// +// Temperature Sensors +// +#define TEMP_0_PIN 0 // Analog Input +#define TEMP_1_PIN 1 // Analog Input +#define TEMP_2_PIN 2 // Analog Input +#define TEMP_3_PIN 3 // Analog Input +#define TEMP_BED_PIN 4 // Analog Input + +// +// Heaters / Fans +// +#define HEATER_0_PIN 13 +#define HEATER_1_PIN 12 +#define HEATER_2_PIN 11 +#define HEATER_3_PIN 10 +#define HEATER_BED_PIN 7 // BED + +#ifndef FAN_PIN + #define FAN_PIN 9 +#endif +#define FAN1_PIN 8 + +// +// Misc. Functions +// +#ifndef FIL_RUNOUT_PIN + #define FIL_RUNOUT_PIN 45 // SERVO4_PIN +#endif + +#ifndef PS_ON_PIN + #define PS_ON_PIN 59 +#endif + +// +// LCD / Controller +// +#if HAS_WIRED_LCD + + #define BTN_EN1 48 + #define BTN_EN2 50 + #define BTN_ENC 46 + + #define SDSS 4 + #define SD_DETECT_PIN 14 + + #define BEEPER_PIN 41 + #define KILL_PIN 66 + + #if IS_RRD_FG_SC + + #define LCD_PINS_RS 42 + #define LCD_PINS_ENABLE 43 + #define LCD_PINS_D4 44 + + #define BTN_BACK 52 + + #elif ENABLED(K3D_242_OLED_CONTROLLER) + + #define LCD_PINS_DC 44 + #define LCD_PINS_RS 42 + #define DOGLCD_CS 52 + #define DOGLCD_MOSI 43 + #define DOGLCD_SCK 47 + #define DOGLCD_A0 LCD_PINS_DC + + #endif + +#endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/sam/pins_PRINTRBOARD_G2.h b/Marlin/src/pins/sam/pins_PRINTRBOARD_G2.h index 22edb7021302..aa01a9227fb3 100644 --- a/Marlin/src/pins/sam/pins_PRINTRBOARD_G2.h +++ b/Marlin/src/pins/sam/pins_PRINTRBOARD_G2.h @@ -25,12 +25,10 @@ * PRINTRBOARD_G2 */ -#if NOT_TARGET(__SAM3X8E__) - #error "Oops! Select 'Arduino Due' in 'Tools > Board.'" -#endif +#include "env_validate.h" #ifndef BOARD_INFO_NAME - #define BOARD_INFO_NAME "PRINTRBOARD_G2" + #define BOARD_INFO_NAME "Printrboard G2" #endif // @@ -42,9 +40,9 @@ // // Limit Switches // -#define X_MIN_PIN 22 // PB26 -#define Y_MAX_PIN 18 // PA11 -#define Z_MIN_PIN 19 // PA10 +#define X_STOP_PIN 22 // PB26 +#define Y_STOP_PIN 18 // PA11 +#define Z_STOP_PIN 19 // PA10 // // Z Probe (when not Z_MIN_PIN) @@ -151,9 +149,9 @@ ///////////////////////////////////////////////////////// -#define MISO_PIN 68 // set to unused pins for now -#define MOSI_PIN 69 // set to unused pins for now -#define SCK_PIN 70 // set to unused pins for now +#define SD_MISO_PIN 68 // set to unused pins for now +#define SD_MOSI_PIN 69 // set to unused pins for now +#define SD_SCK_PIN 70 // set to unused pins for now #define SDSS 71 // set to unused pins for now /** diff --git a/Marlin/src/pins/sam/pins_RADDS.h b/Marlin/src/pins/sam/pins_RADDS.h index 60fe3512378e..7a865b4ad870 100644 --- a/Marlin/src/pins/sam/pins_RADDS.h +++ b/Marlin/src/pins/sam/pins_RADDS.h @@ -25,9 +25,7 @@ * RADDS */ -#if NOT_TARGET(__SAM3X8E__) - #error "Oops! Select 'Arduino Due' in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "RADDS" @@ -181,11 +179,11 @@ #define TEMP_4_PIN 5 // dummy so will compile when PINS_DEBUGGING is enabled #define TEMP_BED_PIN 4 // Analog Input -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 53 + #define TEMP_0_CS_PIN 53 #else - #define MAX6675_SS_PIN 49 + #define TEMP_0_CS_PIN 49 #endif // @@ -248,7 +246,7 @@ #define SDSS 10 #define SD_DETECT_PIN 14 - #elif ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #elif IS_RRD_FG_SC // The REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER requires // an adapter such as https://www.thingiverse.com/thing:1740725 @@ -287,6 +285,10 @@ #endif // SPARK_FULL_GRAPHICS + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif + #endif // HAS_WIRED_LCD #ifndef SDSS diff --git a/Marlin/src/pins/sam/pins_RAMPS4DUE.h b/Marlin/src/pins/sam/pins_RAMPS4DUE.h index 54548333b5fd..6d9d06a17561 100644 --- a/Marlin/src/pins/sam/pins_RAMPS4DUE.h +++ b/Marlin/src/pins/sam/pins_RAMPS4DUE.h @@ -39,14 +39,9 @@ * A15 | NC */ -#if NOT_TARGET(__SAM3X8E__, __AVR_ATmega2560__) - #error "Oops! Select 'Arduino Due' or 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#endif - +#define ALLOW_SAM3X8E #define BOARD_INFO_NAME "RAMPS4DUE" -#define IS_RAMPS4DUE - // // Temperature Sensors // diff --git a/Marlin/src/pins/sam/pins_RAMPS_DUO.h b/Marlin/src/pins/sam/pins_RAMPS_DUO.h index bfc3968ffac2..5b2b2f0b6615 100644 --- a/Marlin/src/pins/sam/pins_RAMPS_DUO.h +++ b/Marlin/src/pins/sam/pins_RAMPS_DUO.h @@ -43,14 +43,9 @@ * A15 | A11 */ -#if NOT_TARGET(__SAM3X8E__, __AVR_ATmega2560__) - #error "Oops! Select 'Arduino Due' or 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" -#endif - #define BOARD_INFO_NAME "RAMPS Duo" -#define IS_RAMPS_DUO - +#define ALLOW_SAM3X8E #include "../ramps/pins_RAMPS.h" // @@ -65,12 +60,12 @@ #undef TEMP_BED_PIN #define TEMP_BED_PIN 10 // Analog Input -// SPI for Max6675 or Max31855 Thermocouple -#undef MAX6675_SS_PIN +// SPI for MAX Thermocouple +#undef TEMP_0_CS_PIN #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 69 // Don't use 53 if using Display/SD card + #define TEMP_0_CS_PIN 69 // Don't use 53 if using Display/SD card #else - #define MAX6675_SS_PIN 69 // Don't use 49 (SD_DETECT_PIN) + #define TEMP_0_CS_PIN 69 // Don't use 49 (SD_DETECT_PIN) #endif // @@ -78,7 +73,7 @@ // #if HAS_WIRED_LCD - #if BOTH(NEWPANEL, PANEL_ONE) + #if BOTH(IS_NEWPANEL, PANEL_ONE) #undef LCD_PINS_D4 #define LCD_PINS_D4 68 @@ -89,7 +84,7 @@ #define LCD_PINS_D7 67 #endif - #if ENABLED(NEWPANEL) + #if IS_NEWPANEL #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) @@ -115,7 +110,7 @@ #else - #if ENABLED(REPRAPWORLD_KEYPAD) + #if IS_RRW_KEYPAD #undef BTN_EN1 #define BTN_EN1 67 // encoder @@ -127,6 +122,10 @@ #endif #endif - #endif // NEWPANEL + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif + + #endif // IS_NEWPANEL #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h b/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h index ee525eefaa56..30f209ad3713 100644 --- a/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h +++ b/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h @@ -28,9 +28,7 @@ * Use 4k7 thermistor tables */ -#if NOT_TARGET(__SAM3X8E__) - #error "Oops! Select 'Arduino Due' in 'Tools > Board.'" -#endif +#include "env_validate.h" #ifndef BOARD_INFO_NAME #define BOARD_INFO_NAME "RAMPS-FD v1" @@ -111,11 +109,11 @@ #define TEMP_2_PIN 3 // Analog Input #define TEMP_BED_PIN 0 // Analog Input -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 53 + #define TEMP_0_CS_PIN 53 #else - #define MAX6675_SS_PIN 49 + #define TEMP_0_CS_PIN 49 #endif // @@ -148,7 +146,7 @@ #define BTN_ENC 35 #define SD_DETECT_PIN 49 - #if ENABLED(NEWPANEL) + #if IS_NEWPANEL #define LCD_PINS_RS 16 #define LCD_PINS_ENABLE 17 #endif @@ -178,7 +176,7 @@ #define NEOPIXEL_PIN 25 #endif - #elif ENABLED(NEWPANEL) + #elif IS_NEWPANEL #define LCD_PINS_D4 23 #define LCD_PINS_D5 25 @@ -203,6 +201,10 @@ #define DOGLCD_MISO 74 // MISO_PIN #endif + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif + #endif // HAS_WIRED_LCD #if HAS_TMC_UART diff --git a/Marlin/src/pins/sam/pins_RAMPS_SMART.h b/Marlin/src/pins/sam/pins_RAMPS_SMART.h index 9b76ee290b96..96d0c9e1cc9a 100644 --- a/Marlin/src/pins/sam/pins_RAMPS_SMART.h +++ b/Marlin/src/pins/sam/pins_RAMPS_SMART.h @@ -60,18 +60,26 @@ * (Search the web for "Arduino DUE Board Pinout" to see the correct header.) */ -#if NOT_TARGET(__SAM3X8E__) - #error "Oops! Select 'Arduino Due' in 'Tools > Board.'" -#endif - #define BOARD_INFO_NAME "RAMPS-SMART" -#define IS_RAMPS_SMART +#define ALLOW_SAM3X8E #include "../ramps/pins_RAMPS.h" // I2C EEPROM with 4K of space #define I2C_EEPROM #define MARLIN_EEPROM_SIZE 0x1000 +#define SDA_PIN 20 +#define SCL_PIN 21 + +// See EEPROM device datasheet for the following values. These are for 24xx256 +#define EEPROM_SERIAL_ADDR 0x50 // 7 bit i2c address (without R/W bit) +#define EEPROM_PAGE_SIZE 64 // page write buffer size +#define EEPROM_PAGE_WRITE_TIME 7 // page write time in milliseconds (docs say 5ms but that is too short) + +#define TWI_CLOCK_FREQ 400000 +#define EEPROM_ADDRSZ_BYTES TWI_MMR_IADRSZ_2_BYTE // TWI_MMR_IADRSZ_1_BYTE for 1 byte, or TWI_MMR_IADRSZ_2_BYTE for 2 byte +#define EEPROM_AVAILABLE EEPROM_I2C + #define RESET_PIN 42 // Resets the board if the jumper is attached // @@ -86,17 +94,18 @@ #undef TEMP_BED_PIN #define TEMP_BED_PIN 11 // Analog Input -// SPI for Max6675 or Max31855 Thermocouple -#undef MAX6675_SS_PIN +// SPI for MAX Thermocouple +#undef TEMP_0_CS_PIN #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 67 // Don't use 53 if using Display/SD card + #define TEMP_0_CS_PIN 67 // Don't use 53 if using Display/SD card #else - #define MAX6675_SS_PIN 67 // Don't use 49 (SD_DETECT_PIN) + #define TEMP_0_CS_PIN 67 // Don't use 49 (SD_DETECT_PIN) #endif // // LCD / Controller // + // Support for AZSMZ 12864 LCD with SD Card 3D printer smart controller control panel #if ENABLED(AZSMZ_12864) #define BEEPER_PIN 66 // Smart RAMPS 1.42 pinout diagram on RepRap WIKI erroneously says this should be pin 65 diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_11.h b/Marlin/src/pins/sam/pins_RURAMPS4D_11.h index b9e61fb27c53..b5569c810d90 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_11.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_11.h @@ -20,6 +20,7 @@ * * Ported sys0724 & Vynt */ +#pragma once /** * Arduino Mega? or Due with RuRAMPS4DUE pin assignments @@ -32,9 +33,7 @@ * | */ -#if NOT_TARGET(__SAM3X8E__) - #error "Oops! Select 'Arduino Due' in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "RuRAMPS4Due v1.1" @@ -118,7 +117,7 @@ //#define E3_MS2_PIN ? //#define E3_MS3_PIN ? -#if HAS_CUSTOM_PROBE_PIN +#if USES_Z_MIN_PROBE_PIN #define Z_MIN_PROBE_PIN 49 #endif @@ -157,12 +156,12 @@ #define TEMP_5_PIN 6 // A6 (Marlin 2.0 not support) #endif -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple /* #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 53 + #define TEMP_0_CS_PIN 53 #else - #define MAX6675_SS_PIN 49 + #define TEMP_0_CS_PIN 49 #endif */ @@ -202,7 +201,7 @@ // #if HAS_WIRED_LCD - #if ANY(RADDS_DISPLAY, REPRAP_DISCOUNT_SMART_CONTROLLER, REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #if ANY(RADDS_DISPLAY, IS_RRD_SC, IS_RRD_FG_SC) #define BEEPER_PIN 62 #define LCD_PINS_D4 48 #define LCD_PINS_D5 50 @@ -211,12 +210,12 @@ #define SD_DETECT_PIN 51 #endif - #if EITHER(RADDS_DISPLAY, REPRAP_DISCOUNT_SMART_CONTROLLER) + #if EITHER(RADDS_DISPLAY, IS_RRD_SC) #define LCD_PINS_RS 63 #define LCD_PINS_ENABLE 64 - #elif ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #elif IS_RRD_FG_SC #define LCD_PINS_RS 52 #define LCD_PINS_ENABLE 53 @@ -265,10 +264,14 @@ #endif // SPARK_FULL_GRAPHICS - #if ENABLED(NEWPANEL) + #if IS_NEWPANEL #define BTN_EN1 44 #define BTN_EN2 42 #define BTN_ENC 40 #endif + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif + #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h index dc0c1279954b..b06de1bc696b 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h @@ -20,6 +20,7 @@ * * Ported sys0724 & Vynt */ +#pragma once /** * Arduino Mega? or Due with RuRAMPS4DUE pin assignments @@ -32,9 +33,7 @@ * | */ -#if NOT_TARGET(__SAM3X8E__) - #error "Oops! Select 'Arduino Due' in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "RuRAMPS4Due v1.3" @@ -106,7 +105,7 @@ #define E2_CS_PIN 61 #endif -#if HAS_CUSTOM_PROBE_PIN +#if USES_Z_MIN_PROBE_PIN #define Z_MIN_PROBE_PIN 49 #endif @@ -143,12 +142,12 @@ #define TEMP_5_PIN 6 // A6 (Marlin 2.0 not support) #endif -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple /* #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 53 + #define TEMP_0_CS_PIN 53 #else - #define MAX6675_SS_PIN 49 + #define TEMP_0_CS_PIN 49 #endif */ @@ -188,7 +187,7 @@ // #if HAS_WIRED_LCD - #if ANY(RADDS_DISPLAY, REPRAP_DISCOUNT_SMART_CONTROLLER, REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #if ANY(RADDS_DISPLAY, IS_RRD_SC, IS_RRD_FG_SC) #define BEEPER_PIN 62 #define LCD_PINS_D4 48 #define LCD_PINS_D5 50 @@ -197,12 +196,12 @@ #define SD_DETECT_PIN 51 #endif - #if EITHER(RADDS_DISPLAY, REPRAP_DISCOUNT_SMART_CONTROLLER) + #if EITHER(RADDS_DISPLAY, IS_RRD_SC) #define LCD_PINS_RS 63 #define LCD_PINS_ENABLE 64 - #elif ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #elif IS_RRD_FG_SC #define LCD_PINS_RS 52 #define LCD_PINS_ENABLE 53 @@ -247,10 +246,14 @@ #endif - #if ENABLED(NEWPANEL) + #if IS_NEWPANEL #define BTN_EN1 44 #define BTN_EN2 42 #define BTN_ENC 40 #endif + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif + #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/sam/pins_ULTRATRONICS_PRO.h b/Marlin/src/pins/sam/pins_ULTRATRONICS_PRO.h index 0b91ba61d6df..a655d0121c84 100644 --- a/Marlin/src/pins/sam/pins_ULTRATRONICS_PRO.h +++ b/Marlin/src/pins/sam/pins_ULTRATRONICS_PRO.h @@ -26,9 +26,7 @@ * https://reprapworld.com/documentation/datasheet_ultratronics10_05.pdf */ -#if NOT_TARGET(ARDUINO_ARCH_SAM) - #error "Oops! Select 'Arduino Due' in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "Ultratronics v1.0" @@ -147,16 +145,15 @@ #define SPI_EEPROM2_CS -1 #define SPI_FLASH_CS -1 -#define SCK_PIN 76 -#define MISO_PIN 74 -#define MOSI_PIN 75 +#define SD_SCK_PIN 76 +#define SD_MISO_PIN 74 +#define SD_MOSI_PIN 75 -// SPI for Max6675 or Max31855 Thermocouple -#define MAX6675_SS_PIN 65 -#define MAX31855_SS0 65 -#define MAX31855_SS1 52 -#define MAX31855_SS2 50 -#define MAX31855_SS3 51 +// SPI for MAX Thermocouple +#define TEMP_0_CS_PIN 65 +#define TEMP_1_CS_PIN 52 +#define TEMP_2_CS_PIN 50 +#define TEMP_3_CS_PIN 51 #define ENC424_SS 61 diff --git a/Marlin/src/pins/samd/pins_RAMPS_144.h b/Marlin/src/pins/samd/pins_RAMPS_144.h index 6076be07e9d4..fbd9d7c86412 100644 --- a/Marlin/src/pins/samd/pins_RAMPS_144.h +++ b/Marlin/src/pins/samd/pins_RAMPS_144.h @@ -89,13 +89,6 @@ #define Z_CS_PIN 32 #endif -#define Z2_STEP_PIN 36 -#define Z2_DIR_PIN 34 -#define Z2_ENABLE_PIN 30 -#ifndef Z2_CS_PIN - #define Z2_CS_PIN 22 -#endif - #define E0_STEP_PIN 26 #define E0_DIR_PIN 28 #define E0_ENABLE_PIN 24 @@ -103,18 +96,33 @@ #define E0_CS_PIN 43 #endif +#define E1_STEP_PIN 36 +#define E1_DIR_PIN 34 +#define E1_ENABLE_PIN 30 +#ifndef E1_CS_PIN + #define E1_CS_PIN 22 +#endif + // // Temperature Sensors // #define TEMP_0_PIN 13 -#define TEMP_BED_PIN 14 +#if TEMP_SENSOR_BED + #define TEMP_BED_PIN 14 +#else + #define TEMP_1_PIN 14 +#endif #define TEMP_CHAMBER_PIN 15 // // Heaters / Fans // #define HEATER_0_PIN 10 -#define HEATER_BED_PIN 8 +#if TEMP_SENSOR_BED + #define HEATER_BED_PIN 8 +#else + #define HEATER_1_PIN 8 +#endif #define FAN_PIN 9 #define FAN1_PIN 7 #define FAN2_PIN 12 @@ -122,7 +130,6 @@ // // Misc. Functions // -#define SDSS 53 #define LED_PIN 13 #ifndef FILWIDTH_PIN @@ -186,9 +193,6 @@ //#define Z2_HARDWARE_SERIAL Serial1 //#define E0_HARDWARE_SERIAL Serial1 //#define E1_HARDWARE_SERIAL Serial1 - //#define E2_HARDWARE_SERIAL Serial1 - //#define E3_HARDWARE_SERIAL Serial1 - //#define E4_HARDWARE_SERIAL Serial1 // // Software serial @@ -245,42 +249,21 @@ #ifndef E1_SERIAL_RX_PIN #define E1_SERIAL_RX_PIN -1 #endif - #ifndef E2_SERIAL_TX_PIN - #define E2_SERIAL_TX_PIN -1 - #endif - #ifndef E2_SERIAL_RX_PIN - #define E2_SERIAL_RX_PIN -1 - #endif - #ifndef E3_SERIAL_TX_PIN - #define E3_SERIAL_TX_PIN -1 - #endif - #ifndef E3_SERIAL_RX_PIN - #define E3_SERIAL_RX_PIN -1 - #endif - #ifndef E4_SERIAL_TX_PIN - #define E4_SERIAL_TX_PIN -1 - #endif - #ifndef E4_SERIAL_RX_PIN - #define E4_SERIAL_RX_PIN -1 - #endif - #ifndef E5_SERIAL_TX_PIN - #define E5_SERIAL_TX_PIN -1 - #endif - #ifndef E5_SERIAL_RX_PIN - #define E5_SERIAL_RX_PIN -1 - #endif - #ifndef E6_SERIAL_TX_PIN - #define E6_SERIAL_TX_PIN -1 - #endif - #ifndef E6_SERIAL_RX_PIN - #define E6_SERIAL_RX_PIN -1 - #endif - #ifndef E7_SERIAL_TX_PIN - #define E7_SERIAL_TX_PIN -1 - #endif - #ifndef E7_SERIAL_RX_PIN - #define E7_SERIAL_RX_PIN -1 - #endif +#endif + +// +// SD Support +// +#ifndef SDCARD_CONNECTION + #define SDCARD_CONNECTION ONBOARD +#endif + +#if SD_CONNECTION_IS(ONBOARD) + #define SDSS 83 + #undef SD_DETECT_PIN + #define SD_DETECT_PIN 95 +#else + #define SDSS 53 #endif ////////////////////////// @@ -299,7 +282,7 @@ //#define LCD_PINS_ENABLE 51 // SID (MOSI) //#define LCD_PINS_D4 52 // SCK (CLK) clock - #elif BOTH(NEWPANEL, PANEL_ONE) + #elif BOTH(IS_NEWPANEL, PANEL_ONE) // TO TEST //#define LCD_PINS_RS 40 @@ -318,7 +301,7 @@ //#define LCD_PINS_ENABLE 29 //#define LCD_PINS_D4 25 - #if DISABLED(NEWPANEL) + #if !IS_NEWPANEL // TO TEST //#define BEEPER_PIN 37 #endif @@ -354,19 +337,19 @@ #define LCD_PINS_D7 29 - #if DISABLED(NEWPANEL) + #if !IS_NEWPANEL #define BEEPER_PIN 33 #endif #endif - #if DISABLED(NEWPANEL) + #if !IS_NEWPANEL // Buttons attached to a shift register // Not wired yet - //#define SHIFT_CLK 38 - //#define SHIFT_LD 42 - //#define SHIFT_OUT 40 - //#define SHIFT_EN 17 + //#define SHIFT_CLK_PIN 38 + //#define SHIFT_LD_PIN 42 + //#define SHIFT_OUT_PIN 40 + //#define SHIFT_EN_PIN 17 #endif #endif @@ -374,9 +357,9 @@ // // LCD Display input pins // - #if ENABLED(NEWPANEL) + #if IS_NEWPANEL - #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) + #if IS_RRD_SC #define BEEPER_PIN 37 @@ -387,6 +370,9 @@ #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 #endif #define BTN_ENC 35 @@ -396,8 +382,7 @@ #define KILL_PIN 41 #if ENABLED(BQ_LCD_SMART_CONTROLLER) - // TO TEST - //#define LCD_BACKLIGHT_PIN 39 + //#define LCD_BACKLIGHT_PIN 39 // TO TEST #endif #elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD) @@ -565,11 +550,11 @@ //#define BEEPER_PIN 33 // Buttons are directly attached to AUX-2 - #if ENABLED(REPRAPWORLD_KEYPAD) + #if IS_RRW_KEYPAD // TO TEST - //#define SHIFT_OUT 40 - //#define SHIFT_CLK 44 - //#define SHIFT_LD 42 + //#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 @@ -592,20 +577,6 @@ #endif #endif - #endif // NEWPANEL + #endif // IS_NEWPANEL #endif // HAS_WIRED_LCD - -// -// SD Support -// -#ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION ONBOARD -#endif - -#if SD_CONNECTION_IS(ONBOARD) - #undef SDSS - #define SDSS 83 - #undef SD_DETECT_PIN - #define SD_DETECT_PIN 95 -#endif diff --git a/Marlin/src/pins/sanguino/env_validate.h b/Marlin/src/pins/sanguino/env_validate.h new file mode 100644 index 000000000000..d229b6f102e4 --- /dev/null +++ b/Marlin/src/pins/sanguino/env_validate.h @@ -0,0 +1,42 @@ + /** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#if ENABLED(ALLOW_MEGA644) + #if NOT_TARGET(__AVR_ATmega644__, __AVR_ATmega644P__, __AVR_ATmega1284P__) + #error "Oops! Select 'Sanguino' in 'Tools > Boards' and 'ATmega644', 'ATmega644P', or 'ATmega1284P' in 'Tools > Processor.'" + #endif +#elif ENABLED(ALLOW_MEGA644P) + #if NOT_TARGET(__AVR_ATmega644P__, __AVR_ATmega1284P__) + #error "Oops! Select 'Sanguino' in 'Tools > Boards' and 'ATmega644P' or 'ATmega1284P' in 'Tools > Processor.'" + #endif +#elif ENABLED(REQUIRE_MEGA644P) + #if NOT_TARGET(__AVR_ATmega644P__) + #error "Oops! Select 'Sanguino' in 'Tools > Board' and 'ATmega644P' in 'Tools > Processor.'" + #endif +#elif NOT_TARGET(__AVR_ATmega1284P__) + #error "Oops! Select 'Sanguino' in 'Tools > Board' and 'ATmega1284P' in 'Tools > Processor.' (For PlatformIO, use 'melzi' or 'melzi_optiboot.')" +#endif + +#undef ALLOW_MEGA644 +#undef ALLOW_MEGA644P +#undef REQUIRE_MEGA644P diff --git a/Marlin/src/pins/sanguino/pins_ANET_10.h b/Marlin/src/pins/sanguino/pins_ANET_10.h index 74692a21a390..ac8fa80eb892 100644 --- a/Marlin/src/pins/sanguino/pins_ANET_10.h +++ b/Marlin/src/pins/sanguino/pins_ANET_10.h @@ -145,13 +145,16 @@ * * Only the following displays are supported: * ZONESTAR_LCD - * ANET_FULL_GRAPHICS_LCD + * ANET_FULL_GRAPHICS_LCD(_ALT_WIRING)? * REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER */ #if HAS_WIRED_LCD + #define LCD_SDSS 28 - #if ENABLED(ADC_KEYPAD) + + #if HAS_ADC_BUTTONS + #define SERVO0_PIN 27 // free for BLTouch/3D-Touch #define LCD_PINS_RS 28 #define LCD_PINS_ENABLE 29 @@ -160,28 +163,49 @@ #define LCD_PINS_D6 16 #define LCD_PINS_D7 17 #define ADC_KEYPAD_PIN 1 - #elif ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + + #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 // See below for alternative pin definitions for use with https://www.thingiverse.com/thing:2103748 - #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 - #define BOARD_ST7920_DELAY_1 DELAY_NS(0) - #define BOARD_ST7920_DELAY_2 DELAY_NS(63) - #define BOARD_ST7920_DELAY_3 DELAY_NS(125) - #define STD_ENCODER_PULSES_PER_STEP 4 - #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 + + #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 + #define BOARD_ST7920_DELAY_1 DELAY_NS(250) + #define BOARD_ST7920_DELAY_2 DELAY_NS(250) + #define BOARD_ST7920_DELAY_3 DELAY_NS(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 + #define BOARD_ST7920_DELAY_1 DELAY_NS(125) + #define BOARD_ST7920_DELAY_2 DELAY_NS(63) + #define BOARD_ST7920_DELAY_3 DELAY_NS(125) + #endif + #endif + #else #define SERVO0_PIN 27 #endif +#ifndef FIL_RUNOUT_PIN + #define FIL_RUNOUT_PIN SERVO0_PIN +#endif + /** * ==================================================================== * =============== Alternative RepRapDiscount Wiring ================== diff --git a/Marlin/src/pins/sanguino/pins_GEN3_MONOLITHIC.h b/Marlin/src/pins/sanguino/pins_GEN3_MONOLITHIC.h index 29905c108954..1343739a119e 100644 --- a/Marlin/src/pins/sanguino/pins_GEN3_MONOLITHIC.h +++ b/Marlin/src/pins/sanguino/pins_GEN3_MONOLITHIC.h @@ -48,9 +48,8 @@ * Once installed select the Sanguino board and then select the CPU. */ -#if NOT_TARGET(__AVR_ATmega644P__) - #error "Oops! Select 'Sanguino' in 'Tools > Board.'" -#endif +#define REQUIRE_MEGA644P +#include "env_validate.h" #define BOARD_INFO_NAME "Gen3 Monolithic" #define DEBUG_PIN 0 diff --git a/Marlin/src/pins/sanguino/pins_GEN3_PLUS.h b/Marlin/src/pins/sanguino/pins_GEN3_PLUS.h index 33fc233f7ab1..7cab1bd762c5 100644 --- a/Marlin/src/pins/sanguino/pins_GEN3_PLUS.h +++ b/Marlin/src/pins/sanguino/pins_GEN3_PLUS.h @@ -48,9 +48,8 @@ * Once installed select the SANGUINO board and then select the CPU. */ -#if NOT_TARGET(__AVR_ATmega644P__, __AVR_ATmega1284P__) - #error "Oops! Select 'Sanguino' in 'Tools > Boards' and 'ATmega644P' or 'ATmega1284P' in 'Tools > Processor.'" -#endif +#define ALLOW_MEGA644P +#include "env_validate.h" #define BOARD_INFO_NAME "Gen3+" diff --git a/Marlin/src/pins/sanguino/pins_GEN6.h b/Marlin/src/pins/sanguino/pins_GEN6.h index bfca8e90d9cc..51e8200b9570 100644 --- a/Marlin/src/pins/sanguino/pins_GEN6.h +++ b/Marlin/src/pins/sanguino/pins_GEN6.h @@ -50,9 +50,8 @@ * Once installed select the Sanguino board and then select the CPU. */ -#if NOT_TARGET(__AVR_ATmega644P__, __AVR_ATmega1284P__) - #error "Oops! Select 'Sanguino' in 'Tools > Boards' and 'ATmega644P' or 'ATmega1284P' in 'Tools > Processor.'" -#endif +#define ALLOW_MEGA644P +#include "env_validate.h" #ifndef BOARD_INFO_NAME #define BOARD_INFO_NAME "Gen6" diff --git a/Marlin/src/pins/sanguino/pins_GEN7_12.h b/Marlin/src/pins/sanguino/pins_GEN7_12.h index 9db7d7214a5b..0834da78c45c 100644 --- a/Marlin/src/pins/sanguino/pins_GEN7_12.h +++ b/Marlin/src/pins/sanguino/pins_GEN7_12.h @@ -50,9 +50,8 @@ * Once installed select the Sanguino board and then select the CPU. */ -#if NOT_TARGET(__AVR_ATmega644P__, __AVR_ATmega644__, __AVR_ATmega1284P__) - #error "Oops! Select 'Sanguino' in 'Tools > Boards' and 'ATmega644', 'ATmega644P', or 'ATmega1284P' in 'Tools > Processor.'" -#endif +#define ALLOW_MEGA644 +#include "env_validate.h" #ifndef BOARD_INFO_NAME #define BOARD_INFO_NAME "Gen7 v1.1 / 1.2" diff --git a/Marlin/src/pins/sanguino/pins_GEN7_14.h b/Marlin/src/pins/sanguino/pins_GEN7_14.h index 66dba533e988..97bfdd28a727 100644 --- a/Marlin/src/pins/sanguino/pins_GEN7_14.h +++ b/Marlin/src/pins/sanguino/pins_GEN7_14.h @@ -50,9 +50,8 @@ * Once installed select the Sanguino board and then select the CPU. */ -#if NOT_TARGET(__AVR_ATmega644P__, __AVR_ATmega644__, __AVR_ATmega1284P__) - #error "Oops! Select 'Sanguino' in 'Tools > Boards' and 'ATmega644', 'ATmega644P', or 'ATmega1284P' in 'Tools > Processor.'" -#endif +#define ALLOW_MEGA644 +#include "env_validate.h" #define BOARD_INFO_NAME "Gen7 v1.4" diff --git a/Marlin/src/pins/sanguino/pins_GEN7_CUSTOM.h b/Marlin/src/pins/sanguino/pins_GEN7_CUSTOM.h index 0c4871fb27d5..6d7678e6e3d2 100644 --- a/Marlin/src/pins/sanguino/pins_GEN7_CUSTOM.h +++ b/Marlin/src/pins/sanguino/pins_GEN7_CUSTOM.h @@ -53,9 +53,8 @@ * Once installed select the Sanguino board and then select the CPU. */ -#if NOT_TARGET(__AVR_ATmega644P__, __AVR_ATmega644__, __AVR_ATmega1284P__) - #error "Oops! Select 'Sanguino' in 'Tools > Boards' and 'ATmega644', 'ATmega644P', or 'ATmega1284P' in 'Tools > Processor.'" -#endif +#define ALLOW_MEGA644 +#include "env_validate.h" #define BOARD_INFO_NAME "Gen7 Custom" diff --git a/Marlin/src/pins/sanguino/pins_MELZI.h b/Marlin/src/pins/sanguino/pins_MELZI.h index 887aae18584a..de4dd1b01d10 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI.h +++ b/Marlin/src/pins/sanguino/pins_MELZI.h @@ -29,4 +29,6 @@ #define BOARD_INFO_NAME "Melzi" #endif +#define IS_MELZI 1 + #include "pins_SANGUINOLOLU_12.h" diff --git a/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h b/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h index 9f406c1f7856..225392de1bb4 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h @@ -62,17 +62,21 @@ #undef LCD_PINS_D6 #undef LCD_PINS_D7 -#define LCD_SDSS 31 // Smart Controller SD card reader (rather than the Melzi) -#define LCD_PINS_RS 28 // ST9720 CS -#define LCD_PINS_ENABLE 17 // ST9720 DAT -#define LCD_PINS_D4 30 // ST9720 CLK +#define LCD_SDSS 31 // Smart Controller SD card reader (rather than the Melzi) +#define LCD_PINS_RS 28 // ST9720 CS +#define LCD_PINS_ENABLE 17 // ST9720 DAT +#define LCD_PINS_D4 30 // ST9720 CLK #if ENABLED(BLTOUCH) - #define SERVO0_PIN 27 - #undef BEEPER_PIN + #ifndef SERVO0_PIN + #define SERVO0_PIN 27 + #endif + #if SERVO0_PIN == BEEPER_PIN + #undef BEEPER_PIN + #endif #elif ENABLED(FILAMENT_RUNOUT_SENSOR) #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 27 + #define FIL_RUNOUT_PIN 27 #endif #if FIL_RUNOUT_PIN == BEEPER_PIN #undef BEEPER_PIN @@ -81,7 +85,7 @@ #if ENABLED(MINIPANEL) #undef DOGLCD_CS - #define DOGLCD_CS LCD_PINS_RS + #define DOGLCD_CS LCD_PINS_RS #endif /** @@ -91,13 +95,13 @@ PIN: 3 Port: B3 Z_STEP_PIN protected PIN: 4 Port: B4 AVR_SS_PIN protected . FAN_PIN protected - . SS_PIN protected + . SD_SS_PIN protected PIN: 5 Port: B5 AVR_MOSI_PIN Output = 1 - . 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 - . MISO_PIN Input = 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 - . SCK_PIN Output = 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 diff --git a/Marlin/src/pins/sanguino/pins_MELZI_MALYAN.h b/Marlin/src/pins/sanguino/pins_MELZI_MALYAN.h index 5014620c6b81..8b4faeeaf909 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_MALYAN.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_MALYAN.h @@ -50,9 +50,9 @@ #undef BTN_EN2 #undef BTN_ENC -#define LCD_PINS_RS 17 // ST9720 CS -#define LCD_PINS_ENABLE 16 // ST9720 DAT -#define LCD_PINS_D4 11 // ST9720 CLK -#define BTN_EN1 30 -#define BTN_EN2 29 -#define BTN_ENC 28 +#define LCD_PINS_RS 17 // ST9720 CS +#define LCD_PINS_ENABLE 16 // ST9720 DAT +#define LCD_PINS_D4 11 // ST9720 CLK +#define BTN_EN1 30 +#define BTN_EN2 29 +#define BTN_ENC 28 diff --git a/Marlin/src/pins/sanguino/pins_MELZI_V2.h b/Marlin/src/pins/sanguino/pins_MELZI_V2.h index 275498d55813..e0369923c7d5 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_V2.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_V2.h @@ -29,7 +29,7 @@ #define BOARD_ST7920_DELAY_1 DELAY_NS(0) #endif #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(188) + #define BOARD_ST7920_DELAY_2 DELAY_NS(400) #endif #ifndef BOARD_ST7920_DELAY_3 #define BOARD_ST7920_DELAY_3 DELAY_NS(0) diff --git a/Marlin/src/pins/sanguino/pins_OMCA_A.h b/Marlin/src/pins/sanguino/pins_OMCA_A.h index 770732051900..a3ceb76a0de9 100644 --- a/Marlin/src/pins/sanguino/pins_OMCA_A.h +++ b/Marlin/src/pins/sanguino/pins_OMCA_A.h @@ -74,7 +74,7 @@ */ #if NOT_TARGET(__AVR_ATmega644__) - #error "Oops! Select 'Sanguino' in 'Tools > Board' and ATmega644 in 'Tools > Processor.'" + #error "Oops! Select 'Sanguino' in 'Tools > Board' and 'ATmega644' in 'Tools > Processor.'" #endif #define BOARD_INFO_NAME "Alpha OMCA" diff --git a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h index 438d49d615c8..d79ad7a3dda8 100644 --- a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h +++ b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h @@ -50,9 +50,8 @@ * Once installed select the Sanguino board and then select the CPU. */ -#if NOT_TARGET(__AVR_ATmega644P__, __AVR_ATmega1284P__) - #error "Oops! Select 'Sanguino' in 'Tools > Boards' and 'ATmega644P' or 'ATmega1284P' in 'Tools > Processor.'" -#endif +#define ALLOW_MEGA644P +#include "env_validate.h" #ifndef BOARD_INFO_NAME #define BOARD_INFO_NAME "Sanguinololu <1.2" @@ -106,10 +105,10 @@ #else #define HEATER_BED_PIN 14 // (bed) - #define X_ENABLE_PIN -1 - #define Y_ENABLE_PIN -1 - #define Z_ENABLE_PIN -1 - #define E0_ENABLE_PIN -1 + #define X_ENABLE_PIN 4 + #define Y_ENABLE_PIN 4 + #define Z_ENABLE_PIN 4 + #define E0_ENABLE_PIN 4 #endif @@ -136,7 +135,7 @@ #define LCD_BACKLIGHT_PIN 17 // LCD backlight LED #endif -#if NONE(SPINDLE_FEATURE, LASER_FEATURE) && ENABLED(SANGUINOLOLU_V_1_2) && !BOTH(ULTRA_LCD, NEWPANEL)// try to use IO Header +#if NONE(SPINDLE_FEATURE, LASER_FEATURE) && ENABLED(SANGUINOLOLU_V_1_2) && !BOTH(IS_ULTRA_LCD, IS_NEWPANEL) // try to use IO Header #define CASE_LIGHT_PIN 4 // Hardware PWM - see if IO Header is available #endif @@ -163,6 +162,8 @@ #define LCD_PINS_RS 17 #define LCD_PINS_ENABLE 16 #define LCD_PINS_D4 11 + #define KILL_PIN 10 + #define BEEPER_PIN 27 #ifndef BOARD_ST7920_DELAY_1 #define BOARD_ST7920_DELAY_1 DELAY_NS(0) @@ -185,7 +186,7 @@ // with M42 instead of BEEPER_PIN. #define BEEPER_PIN 27 - #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #if IS_RRD_FG_SC #ifndef BOARD_ST7920_DELAY_1 #define BOARD_ST7920_DELAY_1 DELAY_NS(0) #endif @@ -283,7 +284,7 @@ #endif - #if ENABLED(NEWPANEL) && !defined(BTN_EN1) + #if IS_NEWPANEL && !defined(BTN_EN1) #define BTN_EN1 11 #define BTN_EN2 10 #endif @@ -294,7 +295,7 @@ // M3/M4/M5 - Spindle/Laser Control // #if HAS_CUTTER - #if !MB(AZTEEG_X1) && ENABLED(SANGUINOLOLU_V_1_2) && !BOTH(ULTRA_LCD, NEWPANEL)// try to use IO Header + #if !MB(AZTEEG_X1) && ENABLED(SANGUINOLOLU_V_1_2) && !BOTH(IS_ULTRA_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 diff --git a/Marlin/src/pins/sanguino/pins_SETHI.h b/Marlin/src/pins/sanguino/pins_SETHI.h index dc2133e441dc..a2240b385b2b 100644 --- a/Marlin/src/pins/sanguino/pins_SETHI.h +++ b/Marlin/src/pins/sanguino/pins_SETHI.h @@ -49,9 +49,8 @@ * Once installed select the Sanguino board and then select the CPU. */ -#if NOT_TARGET(__AVR_ATmega644P__, __AVR_ATmega644__, __AVR_ATmega1284P__) - #error "Oops! Select 'Sanguino' in 'Tools > Boards' and 'ATmega644', 'ATmega644P', or 'ATmega1284P' in 'Tools > Processor.'" -#endif +#define ALLOW_MEGA644 +#include "env_validate.h" #define BOARD_INFO_NAME "Sethi 3D_1" diff --git a/Marlin/src/pins/sanguino/pins_ZMIB_V2.h b/Marlin/src/pins/sanguino/pins_ZMIB_V2.h index 838ffe38aa9a..0265ae0a64f5 100644 --- a/Marlin/src/pins/sanguino/pins_ZMIB_V2.h +++ b/Marlin/src/pins/sanguino/pins_ZMIB_V2.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. - * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm + * 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 @@ -21,12 +21,11 @@ */ #pragma once -#if NOT_TARGET(__AVR_ATmega644P__, __AVR_ATmega1284P__) - #error "Oops! Select 'Sanguino' in 'Tools > Boards' and 'ATmega644P' or 'ATmega1284P' in 'Tools > Processor.'" -#endif +#define ALLOW_MEGA644P +#include "env_validate.h" #define BOARD_INFO_NAME "Zonestar ZMIB_V2" -#define BOARD_WEBSITE_URL "https://www.aliexpress.com/item/32957490744.html" +#define BOARD_WEBSITE_URL "www.aliexpress.com/item/32957490744.html" #define IS_ZMIB_V2 @@ -49,11 +48,11 @@ * PIN: 4 Port: B4 SDSS * PIN: 4 Port: B4 V1: EXP1_6 * PIN: 5 Port: B5 AVR_MOSI_PIN - * . MOSI_PIN + * . SD_MOSI_PIN * PIN: 6 Port: B6 AVR_MISO_PIN - * . EXP1_9(MISO_PIN) + * . EXP1_9(SD_MISO_PIN) * PIN: 7 Port: B7 AVR_SCK_PIN - * . EXP1_10(SCK_PIN) + * . EXP1_10(SD_SCK_PIN) * PIN: 8 Port: D0 RXD * PIN: 9 Port: D1 TXD * PIN: 10 Port: D2 EXP1_8 @@ -225,7 +224,7 @@ // // All the above are also RRDSC with rotary encoder // -#if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) +#if IS_RRD_SC #define BTN_EN1 2 #define BTN_EN2 12 #define BTN_ENC 29 diff --git a/Marlin/src/pins/sensitive_pins.h b/Marlin/src/pins/sensitive_pins.h index d7eb1872458f..7ccb0339b27e 100644 --- a/Marlin/src/pins/sensitive_pins.h +++ b/Marlin/src/pins/sensitive_pins.h @@ -55,74 +55,243 @@ #else #define _X_MS3 #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(Y_MIN) - #define _Y_MIN Y_MIN_PIN, -#else - #define _Y_MIN -#endif -#if PIN_EXISTS(Y_MAX) - #define _Y_MAX Y_MAX_PIN, -#else - #define _Y_MAX -#endif -#if PIN_EXISTS(Y_CS) && AXIS_HAS_SPI(Y) - #define _Y_CS Y_CS_PIN, -#else - #define _Y_CS -#endif -#if PIN_EXISTS(Y_MS1) - #define _Y_MS1 Y_MS1_PIN, +#if PIN_EXISTS(X_ENABLE) + #define _X_ENABLE_PIN X_ENABLE_PIN, #else - #define _Y_MS1 -#endif -#if PIN_EXISTS(Y_MS2) - #define _Y_MS2 Y_MS2_PIN, -#else - #define _Y_MS2 -#endif -#if PIN_EXISTS(Y_MS3) - #define _Y_MS3 Y_MS3_PIN, -#else - #define _Y_MS3 + #define _X_ENABLE_PIN #endif -#define _Y_PINS Y_STEP_PIN, Y_DIR_PIN, Y_ENABLE_PIN, _Y_MIN _Y_MAX _Y_MS1 _Y_MS2 _Y_MS3 _Y_CS +#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 HAS_Y_AXIS + + #if PIN_EXISTS(Y_MIN) + #define _Y_MIN Y_MIN_PIN, + #else + #define _Y_MIN + #endif + #if PIN_EXISTS(Y_MAX) + #define _Y_MAX Y_MAX_PIN, + #else + #define _Y_MAX + #endif + #if PIN_EXISTS(Y_CS) && AXIS_HAS_SPI(Y) + #define _Y_CS Y_CS_PIN, + #else + #define _Y_CS + #endif + #if PIN_EXISTS(Y_MS1) + #define _Y_MS1 Y_MS1_PIN, + #else + #define _Y_MS1 + #endif + #if PIN_EXISTS(Y_MS2) + #define _Y_MS2 Y_MS2_PIN, + #else + #define _Y_MS2 + #endif + #if PIN_EXISTS(Y_MS3) + #define _Y_MS3 Y_MS3_PIN, + #else + #define _Y_MS3 + #endif + #if PIN_EXISTS(Y_ENABLE) + #define _Y_ENABLE_PIN Y_ENABLE_PIN, + #else + #define _Y_ENABLE_PIN + #endif + + #define _Y_PINS Y_STEP_PIN, Y_DIR_PIN, _Y_ENABLE_PIN _Y_MIN _Y_MAX _Y_MS1 _Y_MS2 _Y_MS3 _Y_CS -#if PIN_EXISTS(Z_MIN) - #define _Z_MIN Z_MIN_PIN, -#else - #define _Z_MIN -#endif -#if PIN_EXISTS(Z_MAX) - #define _Z_MAX Z_MAX_PIN, #else - #define _Z_MAX + + #define _Y_PINS + #endif -#if PIN_EXISTS(Z_CS) && AXIS_HAS_SPI(Z) - #define _Z_CS Z_CS_PIN, + +#if HAS_Z_AXIS + + #if PIN_EXISTS(Z_MIN) + #define _Z_MIN Z_MIN_PIN, + #else + #define _Z_MIN + #endif + #if PIN_EXISTS(Z_MAX) + #define _Z_MAX Z_MAX_PIN, + #else + #define _Z_MAX + #endif + #if PIN_EXISTS(Z_CS) && AXIS_HAS_SPI(Z) + #define _Z_CS Z_CS_PIN, + #else + #define _Z_CS + #endif + #if PIN_EXISTS(Z_MS1) + #define _Z_MS1 Z_MS1_PIN, + #else + #define _Z_MS1 + #endif + #if PIN_EXISTS(Z_MS2) + #define _Z_MS2 Z_MS2_PIN, + #else + #define _Z_MS2 + #endif + #if PIN_EXISTS(Z_MS3) + #define _Z_MS3 Z_MS3_PIN, + #else + #define _Z_MS3 + #endif + #if PIN_EXISTS(Z_ENABLE) + #define _Z_ENABLE_PIN Z_ENABLE_PIN, + #else + #define _Z_ENABLE_PIN + #endif + + #define _Z_PINS Z_STEP_PIN, Z_DIR_PIN, _Z_ENABLE_PIN _Z_MIN _Z_MAX _Z_MS1 _Z_MS2 _Z_MS3 _Z_CS + #else - #define _Z_CS + + #define _Z_PINS + #endif -#if PIN_EXISTS(Z_MS1) - #define _Z_MS1 Z_MS1_PIN, + +#if LINEAR_AXES >= 4 + + #if PIN_EXISTS(I_MIN) + #define _I_MIN I_MIN_PIN, + #else + #define _I_MIN + #endif + #if PIN_EXISTS(I_MAX) + #define _I_MAX I_MAX_PIN, + #else + #define _I_MAX + #endif + #if PIN_EXISTS(I_CS) && AXIS_HAS_SPI(I) + #define _I_CS I_CS_PIN, + #else + #define _I_CS + #endif + #if PIN_EXISTS(I_MS1) + #define _I_MS1 I_MS1_PIN, + #else + #define _I_MS1 + #endif + #if PIN_EXISTS(I_MS2) + #define _I_MS2 I_MS2_PIN, + #else + #define _I_MS2 + #endif + #if PIN_EXISTS(I_MS3) + #define _I_MS3 I_MS3_PIN, + #else + #define _I_MS3 + #endif + #if PIN_EXISTS(I_ENABLE) + #define _I_ENABLE_PIN I_ENABLE_PIN, + #else + #define _I_ENABLE_PIN + #endif + + #define _I_PINS I_STEP_PIN, I_DIR_PIN, _I_ENABLE_PIN _I_MIN _I_MAX _I_MS1 _I_MS2 _I_MS3 _I_CS + #else - #define _Z_MS1 + + #define _I_PINS + #endif -#if PIN_EXISTS(Z_MS2) - #define _Z_MS2 Z_MS2_PIN, + +#if LINEAR_AXES >= 5 + + #if PIN_EXISTS(J_MIN) + #define _J_MIN J_MIN_PIN, + #else + #define _J_MIN + #endif + #if PIN_EXISTS(J_MAX) + #define _J_MAX J_MAX_PIN, + #else + #define _J_MAX + #endif + #if PIN_EXISTS(J_CS) && AXIS_HAS_SPI(J) + #define _J_CS J_CS_PIN, + #else + #define _J_CS + #endif + #if PIN_EXISTS(J_MS1) + #define _J_MS1 J_MS1_PIN, + #else + #define _J_MS1 + #endif + #if PIN_EXISTS(J_MS2) + #define _J_MS2 J_MS2_PIN, + #else + #define _J_MS2 + #endif + #if PIN_EXISTS(J_MS3) + #define _J_MS3 J_MS3_PIN, + #else + #define _J_MS3 + #endif + #if PIN_EXISTS(J_ENABLE) + #define _J_ENABLE_PIN J_ENABLE_PIN, + #else + #define _J_ENABLE_PIN + #endif + + #define _J_PINS J_STEP_PIN, J_DIR_PIN, _J_ENABLE_PIN _J_MIN _J_MAX _J_MS1 _J_MS2 _J_MS3 _J_CS + #else - #define _Z_MS2 + + #define _J_PINS + #endif -#if PIN_EXISTS(Z_MS3) - #define _Z_MS3 Z_MS3_PIN, + +#if LINEAR_AXES >= 6 + + #if PIN_EXISTS(K_MIN) + #define _K_MIN K_MIN_PIN, + #else + #define _K_MIN + #endif + #if PIN_EXISTS(K_MAX) + #define _K_MAX K_MAX_PIN, + #else + #define _K_MAX + #endif + #if PIN_EXISTS(K_CS) && AXIS_HAS_SPI(K) + #define _K_CS K_CS_PIN, + #else + #define _K_CS + #endif + #if PIN_EXISTS(K_MS1) + #define _K_MS1 K_MS1_PIN, + #else + #define _K_MS1 + #endif + #if PIN_EXISTS(K_MS2) + #define _K_MS2 K_MS2_PIN, + #else + #define _K_MS2 + #endif + #if PIN_EXISTS(K_MS3) + #define _K_MS3 K_MS3_PIN, + #else + #define _K_MS3 + #endif + #if PIN_EXISTS(K_ENABLE) + #define _K_ENABLE_PIN K_ENABLE_PIN, + #else + #define _K_ENABLE_PIN + #endif + + #define _K_PINS K_STEP_PIN, K_DIR_PIN, _K_ENABLE_PIN _K_MIN _K_MAX _K_MS1 _K_MS2 _K_MS3 _K_CS + #else - #define _Z_MS3 -#endif -#define _Z_PINS Z_STEP_PIN, Z_DIR_PIN, Z_ENABLE_PIN, _Z_MIN _Z_MAX _Z_MS1 _Z_MS2 _Z_MS3 _Z_CS + #define _K_PINS + +#endif // // Extruder Chip Select, Digital Micro-steps @@ -338,7 +507,7 @@ #define _E6_PINS #define _E7_PINS -#if EXTRUDERS +#if HAS_EXTRUDERS #undef _E0_PINS #define _E0_PINS E0_STEP_PIN, E0_DIR_PIN, E0_ENABLE_PIN, _E0_CS _E0_MS1 _E0_MS2 _E0_MS3 #endif @@ -423,30 +592,32 @@ #define _H6_PINS #define _H7_PINS +#define DIO_PIN(P) TERN(TARGET_LPC1768, P, analogInputToDigitalPin(P)) + #if HAS_HOTEND #undef _H0_PINS - #define _H0_PINS HEATER_0_PIN, E0_AUTO_FAN_PIN, analogInputToDigitalPin(TEMP_0_PIN), + #define _H0_PINS HEATER_0_PIN, E0_AUTO_FAN_PIN, DIO_PIN(TEMP_0_PIN), #if HAS_MULTI_HOTEND #undef _H1_PINS - #define _H1_PINS HEATER_1_PIN, E1_AUTO_FAN_PIN, analogInputToDigitalPin(TEMP_1_PIN), + #define _H1_PINS HEATER_1_PIN, E1_AUTO_FAN_PIN, DIO_PIN(TEMP_1_PIN), #if HOTENDS > 2 #undef _H2_PINS - #define _H2_PINS HEATER_2_PIN, E2_AUTO_FAN_PIN, analogInputToDigitalPin(TEMP_2_PIN), + #define _H2_PINS HEATER_2_PIN, E2_AUTO_FAN_PIN, DIO_PIN(TEMP_2_PIN), #if HOTENDS > 3 #undef _H3_PINS - #define _H3_PINS HEATER_3_PIN, E3_AUTO_FAN_PIN, analogInputToDigitalPin(TEMP_3_PIN), + #define _H3_PINS HEATER_3_PIN, E3_AUTO_FAN_PIN, DIO_PIN(TEMP_3_PIN), #if HOTENDS > 4 #undef _H4_PINS - #define _H4_PINS HEATER_4_PIN, E4_AUTO_FAN_PIN, analogInputToDigitalPin(TEMP_4_PIN), + #define _H4_PINS HEATER_4_PIN, E4_AUTO_FAN_PIN, DIO_PIN(TEMP_4_PIN), #if HOTENDS > 5 #undef _H5_PINS - #define _H5_PINS HEATER_5_PIN, E5_AUTO_FAN_PIN, analogInputToDigitalPin(TEMP_5_PIN), + #define _H5_PINS HEATER_5_PIN, E5_AUTO_FAN_PIN, DIO_PIN(TEMP_5_PIN), #if HOTENDS > 6 #undef _H6_PINS - #define _H6_PINS HEATER_6_PIN, E6_AUTO_FAN_PIN, analogInputToDigitalPin(TEMP_6_PIN), + #define _H6_PINS HEATER_6_PIN, E6_AUTO_FAN_PIN, DIO_PIN(TEMP_6_PIN), #if HOTENDS > 7 #undef _H7_PINS - #define _H7_PINS HEATER_7_PIN, E7_AUTO_FAN_PIN, analogInputToDigitalPin(TEMP_7_PIN), + #define _H7_PINS HEATER_7_PIN, E7_AUTO_FAN_PIN, DIO_PIN(TEMP_7_PIN), #endif // HOTENDS > 7 #endif // HOTENDS > 6 #endif // HOTENDS > 5 @@ -655,13 +826,13 @@ #endif #if TEMP_SENSOR_BED && PINS_EXIST(TEMP_BED, HEATER_BED) - #define _BED_PINS HEATER_BED_PIN, analogInputToDigitalPin(TEMP_BED_PIN), + #define _BED_PINS HEATER_BED_PIN, DIO_PIN(TEMP_BED_PIN), #else #define _BED_PINS #endif #if TEMP_SENSOR_CHAMBER && PIN_EXISTS(TEMP_CHAMBER) - #define _CHAMBER_TEMP analogInputToDigitalPin(TEMP_CHAMBER_PIN), + #define _CHAMBER_TEMP DIO_PIN(TEMP_CHAMBER_PIN), #else #define _CHAMBER_TEMP #endif @@ -676,14 +847,50 @@ #define _CHAMBER_FAN #endif +#if TEMP_SENSOR_COOLER && PIN_EXISTS(TEMP_COOLER) + #define _COOLER_TEMP DIO_PIN(TEMP_COOLER_PIN), +#else + #define _COOLER_TEMP +#endif +#if TEMP_SENSOR_COOLER && PIN_EXISTS(COOLER) + #define _COOLER COOLER_PIN, +#else + #define _COOLER +#endif +#if TEMP_SENSOR_COOLER && PINS_EXIST(TEMP_COOLER, COOLER_AUTO_FAN) + #define _COOLER_FAN COOLER_AUTO_FAN_PIN, +#else + #define _COOLER_FAN +#endif + #ifndef HAL_SENSITIVE_PINS #define HAL_SENSITIVE_PINS #endif -#define SENSITIVE_PINS { \ - _X_PINS _Y_PINS _Z_PINS _X2_PINS _Y2_PINS _Z2_PINS _Z3_PINS _Z4_PINS _Z_PROBE \ +#ifdef RUNTIME_ONLY_ANALOG_TO_DIGITAL + #define _SP_END +#else + #define _SP_END -2 + + // Move a regular pin in front to the end + template + struct OnlyPins : OnlyPins { }; + + // Remove a -1 from the front + template + struct OnlyPins<-1, D...> : OnlyPins { }; + + // Remove -2 from the front, emit the rest, cease propagation + template + struct OnlyPins<_SP_END, D...> { static constexpr size_t size = sizeof...(D); static constexpr pin_t table[sizeof...(D)] PROGMEM = { D... }; }; +#endif + +#define SENSITIVE_PINS \ + _X_PINS _Y_PINS _Z_PINS _I_PINS _J_PINS _K_PINS \ + _X2_PINS _Y2_PINS _Z2_PINS _Z3_PINS _Z4_PINS _Z_PROBE \ _E0_PINS _E1_PINS _E2_PINS _E3_PINS _E4_PINS _E5_PINS _E6_PINS _E7_PINS \ _H0_PINS _H1_PINS _H2_PINS _H3_PINS _H4_PINS _H5_PINS _H6_PINS _H7_PINS \ _PS_ON _FAN0 _FAN1 _FAN2 _FAN3 _FAN4 _FAN5 _FAN6 _FAN7 _FANC \ - _BED_PINS _CHAMBER_TEMP _CHAMBER_HEATER _CHAMBER_FAN HAL_SENSITIVE_PINS \ -} + _BED_PINS _CHAMBER_TEMP _CHAMBER_HEATER _CHAMBER_FAN \ + _COOLER_TEMP _COOLER _COOLER_FAN HAL_SENSITIVE_PINS \ + _SP_END diff --git a/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h b/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h index a0e035a91688..2717439f24f4 100644 --- a/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h +++ b/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h @@ -41,7 +41,7 @@ // // SD CARD SPI // -#define SDSS SS_PIN +#define SDSS SD_SS_PIN // // Timers diff --git a/Marlin/src/pins/stm32f1/env_validate.h b/Marlin/src/pins/stm32f1/env_validate.h new file mode 100644 index 000000000000..2e7b78517215 --- /dev/null +++ b/Marlin/src/pins/stm32f1/env_validate.h @@ -0,0 +1,26 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#if NOT_TARGET(__STM32F1__, STM32F1) + #error "Oops! Select an STM32F1 board in 'Tools > Board.'" +#endif diff --git a/Marlin/src/pins/stm32f1/pins_BEAST.h b/Marlin/src/pins/stm32f1/pins_BEAST.h new file mode 100644 index 000000000000..2ace47822e16 --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_BEAST.h @@ -0,0 +1,145 @@ +/** + * 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 + +#include "env_validate.h" + +/** + * 21017 Victor Perez Marlin for stm32f1 test + */ + +#define BOARD_INFO_NAME "Beast STM32" +#define DEFAULT_MACHINE_NAME "STM32F103RET6" + +// Enable I2C_EEPROM for testing +#define I2C_EEPROM + +// Ignore temp readings during development. +//#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 + +// +// Limit Switches +// +#define X_STOP_PIN PD5 +#define Y_STOP_PIN PD6 +#define Z_STOP_PIN PD7 + +// +// Steppers +// +#define X_STEP_PIN PE0 +#define X_DIR_PIN PE1 +#define X_ENABLE_PIN PC0 + +#define Y_STEP_PIN PE2 +#define Y_DIR_PIN PE3 +#define Y_ENABLE_PIN PC1 + +#define Z_STEP_PIN PE4 +#define Z_DIR_PIN PE5 +#define Z_ENABLE_PIN PC2 + +#define E0_STEP_PIN PE6 +#define E0_DIR_PIN PE7 +#define E0_ENABLE_PIN PC3 + +/** + * TODO: Currently using same Enable pin to all steppers. + */ + +#define E1_STEP_PIN PE8 +#define E1_DIR_PIN PE9 +#define E1_ENABLE_PIN PC4 + +#define E2_STEP_PIN PE10 +#define E2_DIR_PIN PE11 +#define E2_ENABLE_PIN PC5 + +// +// Misc. Functions +// +#define SDSS PA15 +#define LED_PIN PB2 + +// +// Heaters / Fans +// +#define HEATER_0_PIN PD12 // EXTRUDER 1 +#define HEATER_1_PIN PD13 +#define HEATER_2_PIN PD14 + +#define HEATER_BED_PIN PB9 // BED + +#ifndef FAN_PIN + #define FAN_PIN PB10 +#endif + +#define FAN_SOFT_PWM + +// +// Temperature Sensors +// +#define TEMP_BED_PIN PA0 // Analog Input +#define TEMP_0_PIN PA1 // Analog Input +#define TEMP_1_PIN PA2 // Analog Input +#define TEMP_2_PIN PA3 // Analog Input + +// +// LCD Pins +// +#if HAS_WIRED_LCD + + #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) + #error "REPRAPWORLD_GRAPHICAL_LCD is not supported." + #else + #define LCD_PINS_RS PB8 + #define LCD_PINS_ENABLE PD2 + #define LCD_PINS_D4 PB12 + #define LCD_PINS_D5 PB13 + #define LCD_PINS_D6 PB14 + #define LCD_PINS_D7 PB15 + #if !IS_NEWPANEL + #error "Non-NEWPANEL LCD is not supported." + #endif + #endif + + #if IS_NEWPANEL + #if IS_RRD_SC + #error "RRD Smart Controller is not supported." + #elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD) + #error "REPRAPWORLD_GRAPHICAL_LCD is not supported." + #elif ENABLED(LCD_I2C_PANELOLU2) + #error "LCD_I2C_PANELOLU2 is not supported." + #elif ENABLED(LCD_I2C_VIKI) + #error "LCD_I2C_VIKI is not supported." + #elif ANY(VIKI2, miniVIKI) + #error "VIKI2 / miniVIKI is not supported." + #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) + #error "ELB_FULL_GRAPHIC_CONTROLLER is not supported." + #elif ENABLED(MINIPANEL) + #error "MINIPANEL is not supported." + #else + #error "Other generic NEWPANEL LCD is not supported." + #endif + #endif // IS_NEWPANEL + +#endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h new file mode 100644 index 000000000000..63ad06dc577a --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h @@ -0,0 +1,184 @@ +/** + * 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 + +/** + * BigTreeTech SKR CR-6 (STM32F103RET6) board pin assignments + */ + +#define DEFAULT_MACHINE_NAME "Creality3D" +#define BOARD_INFO_NAME "BTT SKR CR-6" + +#include "env_validate.h" + +// +// Release PB4 (Z_STEP_PIN) from JTAG NRST role +// +#define DISABLE_DEBUG + +// +// USB connect control +// +#define USB_CONNECT_PIN PA14 +#define USB_CONNECT_INVERTING false + +// +// EEPROM +// + +#if NO_EEPROM_SELECTED + #define I2C_EEPROM +#endif + +/* I2C */ +#if ENABLED(I2C_EEPROM) + #define IIC_EEPROM_SDA PB7 + #define IIC_EEPROM_SCL PB6 + + #define MARLIN_EEPROM_SIZE 0x1000 // 4KB +#elif ENABLED(SDCARD_EEPROM_EMULATION) + #define MARLIN_EEPROM_SIZE 0x1000 // 4KB +#endif + +#define E2END (MARLIN_EEPROM_SIZE - 1) // 2KB + +// +// Limit Switches +// + +#define X_STOP_PIN PC0 +#define Y_STOP_PIN PC1 +#define Z_STOP_PIN PC14 // Endtop or Probe + +#define FIL_RUNOUT_PIN PC15 + +// +// Probe +// +#define PROBE_TARE_PIN PA1 +#define PROBE_ACTIVATION_SWITCH_PIN PC2 // Optoswitch to Enable Z Probe + +// +// Steppers +// +#define X_ENABLE_PIN PB14 +#define X_STEP_PIN PB13 +#define X_DIR_PIN PB12 + +#define Y_ENABLE_PIN PB11 +#define Y_STEP_PIN PB10 +#define Y_DIR_PIN PB2 + +#define Z_ENABLE_PIN PB1 +#define Z_STEP_PIN PB0 +#define Z_DIR_PIN PC5 + +#define E0_ENABLE_PIN PD2 +#define E0_STEP_PIN PB3 +#define E0_DIR_PIN PB4 + +// +// Temperature Sensors +// +#define TEMP_0_PIN PA0 // TH1 +#define TEMP_BED_PIN PC3 // TB1 + +// +// Heaters / Fans +// + +#define HEATER_0_PIN PC8 // HEATER1 +#define HEATER_BED_PIN PC9 // HOT BED + +#define FAN_PIN PC6 // FAN +#define FAN_SOFT_PWM + +#define CONTROLLER_FAN_PIN PC7 + +// +// 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_D4 PB9 + + #define BEEPER_PIN PB5 +#endif + +#if HAS_TMC_UART + /** + * TMC2209 stepper drivers + * Hardware serial communication ports. + */ + #define X_HARDWARE_SERIAL MSerial4 + #define Y_HARDWARE_SERIAL MSerial4 + #define Z_HARDWARE_SERIAL MSerial4 + #define E0_HARDWARE_SERIAL MSerial4 + + // Default TMC slave addresses + #ifndef X_SLAVE_ADDRESS + #define X_SLAVE_ADDRESS 0 + #endif + #ifndef Y_SLAVE_ADDRESS + #define Y_SLAVE_ADDRESS 1 + #endif + #ifndef Z_SLAVE_ADDRESS + #define Z_SLAVE_ADDRESS 2 + #endif + #ifndef E0_SLAVE_ADDRESS + #define E0_SLAVE_ADDRESS 3 + #endif +#endif + +// +// SD Card +// + +#define HAS_ONBOARD_SD + +#ifndef SDCARD_CONNECTION + #define SDCARD_CONNECTION ONBOARD +#endif + +#if SD_CONNECTION_IS(ONBOARD) + #define SD_DETECT_PIN PC4 + #define ONBOARD_SD_CS_PIN PA4 // Chip select for "System" SD card +#endif + +// +// Misc. Functions +// +#define CASE_LIGHT_PIN PA13 + +#ifndef NEOPIXEL_PIN + #define NEOPIXEL_PIN PA8 +#endif + +#define SUICIDE_PIN PC13 +#ifndef SUICIDE_PIN_INVERTING + #define SUICIDE_PIN_INVERTING false +#endif 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 63b97b666faf..9b71570b0838 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h @@ -21,11 +21,9 @@ */ #pragma once -#if NOT_TARGET(TARGET_STM32F1) - #error "Oops! Select an STM32F1 board in 'Tools > Board.'" -#endif +#include "env_validate.h" -#define BOARD_INFO_NAME "BTT SKR E3 DIP V1.0" +#define BOARD_INFO_NAME "BTT SKR E3 DIP V1.x" // Release PB3/PB4 (TMC_SW Pins) from JTAG pins #define DISABLE_JTAG @@ -48,20 +46,20 @@ // // Limit Switches // -#define X_STOP_PIN PC1 // "X-STOP" -#define Y_STOP_PIN PC0 // "Y-STOP" -#define Z_STOP_PIN PC15 // "Z-STOP" +#define X_STOP_PIN PC1 // X-STOP +#define Y_STOP_PIN PC0 // Y-STOP +#define Z_STOP_PIN PC15 // Z-STOP // // Z Probe must be this pin // -#define Z_MIN_PROBE_PIN PC14 // "PROBE" +#define Z_MIN_PROBE_PIN PC14 // PROBE // // Filament Runout Sensor // #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN PC2 // "E0-STOP" + #define FIL_RUNOUT_PIN PC2 // E0-STOP #endif // @@ -222,7 +220,7 @@ #define LCD_BACKLIGHT_PIN -1 #else - #error "Only CR10_STOCKDISPLAY, ZONESTAR_LCD, ENDER2_STOCKDISPLAY, MKS_MINI_12864, and MKS_LCD12864 are currently supported on the BIGTREE_SKR_E3_DIP." + #error "Only CR10_STOCKDISPLAY, ZONESTAR_LCD, ENDER2_STOCKDISPLAY, MKS_MINI_12864, and MKS_LCD12864A/B are currently supported on the BIGTREE_SKR_E3_DIP." #endif #endif // HAS_WIRED_LCD @@ -264,7 +262,7 @@ #define BEEPER_PIN PB6 #define CLCD_MOD_RESET PA9 - #define CLCD_SPI_CS PA8 + #define CLCD_SPI_CS PB8 #endif // TOUCH_UI_FTDI_EVE && LCD_FYSETC_TFT81050 @@ -278,12 +276,16 @@ #if SD_CONNECTION_IS(ONBOARD) #define SD_DETECT_PIN PC4 + #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) #define SD_DETECT_PIN PA15 - #define SS_PIN PA10 + #define SD_SS_PIN PA10 #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "SD CUSTOM_CABLE is not compatible with SKR E3 DIP." #endif #define ONBOARD_SPI_DEVICE 1 // SPI1 #define ONBOARD_SD_CS_PIN PA4 // Chip select for "System" SD card +#define SDSS ONBOARD_SD_CS_PIN diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_0.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_0.h index 78751a6bac87..a09da02e1584 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_0.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_0.h @@ -34,4 +34,18 @@ #define Y_HARDWARE_SERIAL MSerial4 #define Z_HARDWARE_SERIAL MSerial4 #define E0_HARDWARE_SERIAL MSerial4 + + // Default TMC slave addresses + #ifndef X_SLAVE_ADDRESS + #define X_SLAVE_ADDRESS 0 + #endif + #ifndef Y_SLAVE_ADDRESS + #define Y_SLAVE_ADDRESS 2 + #endif + #ifndef Z_SLAVE_ADDRESS + #define Z_SLAVE_ADDRESS 1 + #endif + #ifndef E0_SLAVE_ADDRESS + #define E0_SLAVE_ADDRESS 3 + #endif #endif 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 8d384c739681..4951d697a72f 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 @@ -25,7 +25,9 @@ #define BOARD_INFO_NAME "BTT SKR Mini E3 V1.2" -#define NEOPIXEL_PIN PC7 // LED driving pin +#ifndef NEOPIXEL_PIN + #define NEOPIXEL_PIN PC7 // LED driving pin +#endif /** * TMC2208/TMC2209 stepper drivers @@ -34,17 +36,17 @@ // // Software serial // - #define X_SERIAL_TX_PIN PB15 - #define X_SERIAL_RX_PIN PB15 + #define X_SERIAL_TX_PIN PB15 + #define X_SERIAL_RX_PIN PB15 - #define Y_SERIAL_TX_PIN PC6 - #define Y_SERIAL_RX_PIN PC6 + #define Y_SERIAL_TX_PIN PC6 + #define Y_SERIAL_RX_PIN PC6 - #define Z_SERIAL_TX_PIN PC10 - #define Z_SERIAL_RX_PIN PC10 + #define Z_SERIAL_TX_PIN PC10 + #define Z_SERIAL_RX_PIN PC10 - #define E0_SERIAL_TX_PIN PC11 - #define E0_SERIAL_RX_PIN PC11 + #define E0_SERIAL_TX_PIN PC11 + #define E0_SERIAL_RX_PIN PC11 // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 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 0a0d857db3f4..9dc02c495b45 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 @@ -23,6 +23,8 @@ #define SKR_MINI_E3_V2 +#define BOARD_CUSTOM_BUILD_FLAGS -DTONE_CHANNEL=4 -DTONE_TIMER=4 -DTIMER_TONE=4 + // Onboard I2C EEPROM #if NO_EEPROM_SELECTED #define I2C_EEPROM @@ -32,14 +34,20 @@ #include "pins_BTT_SKR_MINI_E3_common.h" -#define BOARD_INFO_NAME "BTT SKR Mini E3 V2.0" +#ifndef BOARD_INFO_NAME + #define BOARD_INFO_NAME "BTT SKR Mini E3 V2.0" +#endif // Release PA13/PA14 (led, usb control) from SWD pins #define DISABLE_DEBUG -#define NEOPIXEL_PIN PA8 // LED driving pin +#ifndef NEOPIXEL_PIN + #define NEOPIXEL_PIN PA8 // LED driving pin +#endif -#define PS_ON_PIN PC13 // Power Supply Control +#ifndef PS_ON_PIN + #define PS_ON_PIN PC13 // Power Supply Control +#endif #define FAN1_PIN PC7 @@ -47,13 +55,27 @@ #define CONTROLLER_FAN_PIN FAN1_PIN #endif -/** - * TMC220x stepper drivers - * Hardware serial communication ports. - */ #if HAS_TMC_UART + /** + * TMC220x stepper drivers + * Hardware serial communication ports + */ #define X_HARDWARE_SERIAL MSerial4 #define Y_HARDWARE_SERIAL MSerial4 #define Z_HARDWARE_SERIAL MSerial4 #define E0_HARDWARE_SERIAL MSerial4 + + // Default TMC slave addresses + #ifndef X_SLAVE_ADDRESS + #define X_SLAVE_ADDRESS 0 + #endif + #ifndef Y_SLAVE_ADDRESS + #define Y_SLAVE_ADDRESS 2 + #endif + #ifndef Z_SLAVE_ADDRESS + #define Z_SLAVE_ADDRESS 1 + #endif + #ifndef E0_SLAVE_ADDRESS + #define E0_SLAVE_ADDRESS 3 + #endif #endif 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 50257f4f4608..8f305542a981 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 @@ -21,9 +21,7 @@ */ #pragma once -#if NOT_TARGET(TARGET_STM32F1) - #error "Oops! Select an STM32F1 board in 'Tools > Board.'" -#endif +#include "env_validate.h" // Release PB3/PB4 (E0 STP/DIR) from JTAG pins #define DISABLE_JTAG @@ -41,25 +39,32 @@ // // Servos // -#define SERVO0_PIN PA1 // "SERVOS" +#define SERVO0_PIN PA1 // SERVOS // // Limit Switches // -#define X_STOP_PIN PC0 // "X-STOP" -#define Y_STOP_PIN PC1 // "Y-STOP" -#define Z_STOP_PIN PC2 // "Z-STOP" +#define X_STOP_PIN PC0 // X-STOP +#define Y_STOP_PIN PC1 // Y-STOP +#define Z_STOP_PIN PC2 // Z-STOP // // Z Probe must be this pin // -#define Z_MIN_PROBE_PIN PC14 // "PROBE" +#define Z_MIN_PROBE_PIN PC14 // PROBE // // Filament Runout Sensor // #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN PC15 // "E0-STOP" + #define FIL_RUNOUT_PIN PC15 // E0-STOP +#endif + +// +// Power-loss Detection +// +#ifndef POWER_LOSS_PIN + #define POWER_LOSS_PIN PC12 // Power Loss Detection: PWR-DET #endif // @@ -112,14 +117,14 @@ /** * SKR Mini E3 V1.0, V1.2 SKR Mini E3 V2.0 - * _____ _____ - * 5V | 1 2 | GND 5V | 1 2 | GND - * (LCD_EN) PB7 | 3 4 | PB8 (LCD_RS) (LCD_EN) PB15 | 3 4 | PB8 (LCD_RS) - * (LCD_D4) PB9 | 5 6 PA10 (BTN_EN2) (LCD_D4) PB9 | 5 6 PA10 (BTN_EN2) - * RESET | 7 8 | PA9 (BTN_EN1) RESET | 7 8 | PA9 (BTN_EN1) - * (BTN_ENC) PB6 | 9 10| PB5 (BEEPER) (BTN_ENC) PA15 | 9 10| PB5 (BEEPER) - * ----- ----- - * EXP1 EXP1 + * ______ ______ + * 5V | 1 2 | GND 5V | 1 2 | GND + * (LCD_EN) PB7 | 3 4 | PB8 (LCD_RS) (LCD_EN) PB15 | 3 4 | PB8 (LCD_RS) + * (LCD_D4) PB9 | 5 6 PA10 (BTN_EN2) (LCD_D4) PB9 | 5 6 PA10 (BTN_EN2) + * RESET | 7 8 | PA9 (BTN_EN1) RESET | 7 8 | PA9 (BTN_EN1) + * (BTN_ENC) PB6 | 9 10 | PB5 (BEEPER) (BTN_ENC) PA15 | 9 10 | PB5 (BEEPER) + * ------ ------ + * EXP1 EXP1 */ #ifdef SKR_MINI_E3_V2 #define EXP1_9 PA15 @@ -129,7 +134,28 @@ #define EXP1_3 PB7 #endif -#if HAS_WIRED_LCD +#if ENABLED(DWIN_CREALITY_LCD) + /** + * ------ ------ ------ + * VCC | 1 2 | GND VCC | 1 2 | GND GND | 2 1 | VCC + * A | 3 4 | B A | 3 4 | B B | 4 3 | A + * | 5 6 TX BEEP | 5 6 ENT ENT | 6 5 | BEEP + * | 7 8 | RX TX | 7 8 | RX RX | 8 7 | TX + * BEEP | 9 10 | ENT | 9 10 | | 10 9 | + * ------ ------ ------ + * EXP1 DWIN DWIN (plug) + * + * All pins are labeled as printed on DWIN PCB. Connect TX-TX, A-A and so on. + */ + + #error "DWIN_CREALITY_LCD requires a custom cable, see diagram above this line. Comment out this line to continue." + + #define BEEPER_PIN EXP1_9 + #define BTN_EN1 EXP1_3 + #define BTN_EN2 PB8 + #define BTN_ENC PB5 + +#elif HAS_WIRED_LCD #if ENABLED(CR10_STOCKDISPLAY) @@ -179,19 +205,19 @@ * TFTGLCD_PANEL_SPI display pinout * * Board Display - * _____ _____ - * 5V | 1 2 | GND (SPI1-MISO) MISO | 1 2 | SCK (SPI1-SCK) - * (FREE) PB7 | 3 4 | PB8 (LCD_CS) (PA9) GLCD_CS | 3 4 | SD_CS (PA10) - * (FREE) PB9 | 5 6 | PA10 (SD_CS) (FREE) | 5 6 | MOSI (SPI1-MOSI) - * RESET | 7 8 | PA9 (MOD_RESET) (PB5) SD_DET | 7 8 | (FREE) - * (BEEPER) PB6 | 9 10| PB5 (SD_DET) GND | 9 10| 5V - * ----- ----- - * EXP1 EXP1 + * ______ ______ + * 5V | 1 2 | GND (SPI1-MISO) MISO | 1 2 | SCK (SPI1-SCK) + * (FREE) PB7 | 3 4 | PB8 (LCD_CS) (PA9) LCD_CS | 3 4 | SD_CS (PA10) + * (FREE) PB9 | 5 6 | PA10 (SD_CS) (FREE) | 5 6 | MOSI (SPI1-MOSI) + * RESET | 7 8 | PA9 (MOD_RESET) (PB5) SD_DET | 7 8 | (FREE) + * (BEEPER) PB6 | 9 10 | PB5 (SD_DET) GND | 9 10 | 5V + * ------ ------ + * EXP1 EXP1 * * Needs custom cable: * - * Board Adapter Display - * _________ + * Board Display + * * EXP1-1 ----------- EXP1-10 * EXP1-2 ----------- EXP1-9 * SPI1-4 ----------- EXP1-6 @@ -218,17 +244,18 @@ #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. Comment out this line to continue." - /** FYSETC TFT TFT81050 display pinout + /** + * FYSETC TFT TFT81050 display pinout * * Board Display - * _____ _____ - * 5V | 1 2 | GND (SPI1-MISO) MISO | 1 2 | SCK (SPI1-SCK) - * (FREE) PB7 | 3 4 | PB8 (LCD_CS) (PA9) MOD_RESET | 3 4 | SD_CS (PA10) - * (FREE) PB9 | 5 6 | PA10 (SD_CS) (PB8) LCD_CS | 5 6 | MOSI (SPI1-MOSI) - * RESET | 7 8 | PA9 (MOD_RESET) (PB5) SD_DET | 7 8 | RESET - * (BEEPER) PB6 | 9 10| PB5 (SD_DET) GND | 9 10| 5V - * ----- ----- - * EXP1 EXP1 + * ______ ______ + * 5V | 1 2 | GND (SPI1-MISO) MISO | 1 2 | SCK (SPI1-SCK) + * (FREE) PB7 | 3 4 | PB8 (LCD_CS) (PA9) MOD_RESET | 3 4 | SD_CS (PA10) + * (FREE) PB9 | 5 6 | PA10 (SD_CS) (PB8) LCD_CS | 5 6 | MOSI (SPI1-MOSI) + * RESET | 7 8 | PA9 (MOD_RESET) (PB5) SD_DET | 7 8 | RESET + * (BEEPER) PB6 | 9 10 | PB5 (SD_DET) GND | 9 10 | 5V + * ------ ------ + * EXP1 EXP1 * * Needs custom cable: * @@ -267,10 +294,16 @@ #define SD_DETECT_PIN PC4 #elif SD_CONNECTION_IS(LCD) && (BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) || IS_TFTGLCD_PANEL) #define SD_DETECT_PIN PB5 - #define SS_PIN PA10 + #define SD_SS_PIN PA10 #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "SD CUSTOM_CABLE is not compatible with SKR Mini E3." #endif -#define ONBOARD_SPI_DEVICE 1 // SPI1 +#define ONBOARD_SPI_DEVICE 1 // SPI1 -> used only by HAL/STM32F1... #define ONBOARD_SD_CS_PIN PA4 // Chip select for "System" SD card + +#define ENABLE_SPI1 +#define SDSS ONBOARD_SD_CS_PIN +#define SD_SCK_PIN PA5 +#define SD_MISO_PIN PA6 +#define SD_MOSI_PIN PA7 diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_MZ_V1_0.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_MZ_V1_0.h new file mode 100644 index 000000000000..96420cf32263 --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_MZ_V1_0.h @@ -0,0 +1,26 @@ +/** + * 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 BOARD_INFO_NAME "BTT SKR Mini MZ V1.0" + +#include "pins_BTT_SKR_MINI_E3_V2_0.h" 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 47fff4467c72..6b3d2832d08a 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 @@ -21,9 +21,7 @@ */ #pragma once -#if NOT_TARGET(TARGET_STM32F1) - #error "Oops! Select an STM32F1 board in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "BTT SKR Mini V1.1" @@ -175,10 +173,15 @@ #else // !FYSETC_MINI_12864 #define LCD_PINS_D4 PC13 - #if ENABLED(ULTIPANEL) + #if IS_ULTIPANEL #define LCD_PINS_D5 PB7 #define LCD_PINS_D6 PC15 #define LCD_PINS_D7 PC14 + + #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 @@ -210,19 +213,18 @@ #endif #if SD_CONNECTION_IS(LCD) - #define ENABLE_SPI3 + #define SPI_DEVICE 3 #define SD_DETECT_PIN PB9 - #define SCK_PIN PB3 - #define MISO_PIN PB4 - #define MOSI_PIN PB5 - #define SS_PIN PA15 + #define SD_SCK_PIN PB3 + #define SD_MISO_PIN PB4 + #define SD_MOSI_PIN PB5 + #define SD_SS_PIN PA15 #elif SD_CONNECTION_IS(ONBOARD) - #define ENABLE_SPI1 #define SD_DETECT_PIN PA3 - #define SCK_PIN PA5 - #define MISO_PIN PA6 - #define MOSI_PIN PA7 - #define SS_PIN PA4 + #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 diff --git a/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h b/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h index 66930a2ea5a6..dc8b8c50f160 100644 --- a/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h +++ b/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h @@ -21,10 +21,10 @@ */ #pragma once -#if NOT_TARGET(TARGET_STM32F1) - #error "Oops! Select an STM32F1 board in 'Tools > Board.'" -#elif HOTENDS > 1 || E_STEPPERS > 1 - #error "CCROBOT-ONLINE MEEB_3DP only supports 1 hotend / E-stepper. Comment out this line to continue." +#include "env_validate.h" + +#if HOTENDS > 1 || E_STEPPERS > 1 + #error "CCROBOT-ONLINE MEEB_3DP only supports one hotend / E-stepper. Comment out this line to continue." #endif // https://github.com/ccrobot-online/MEEB_3DP @@ -165,12 +165,11 @@ // SD-NAND // #if SD_CONNECTION_IS(ONBOARD) - #define ENABLE_SPI1 #define SD_DETECT_PIN -1 - #define SCK_PIN PA5 - #define MISO_PIN PA6 - #define MOSI_PIN PA7 - #define SS_PIN PA4 + #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 diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D.h b/Marlin/src/pins/stm32f1/pins_CHITU3D.h index 3a872db0253e..2d33fb9f2cc2 100644 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D.h @@ -21,9 +21,7 @@ */ #pragma once -#if NOT_TARGET(__STM32F1__, __STM32F4__) - #error "Oops! Select an STM32F1/4 board in 'Tools > Board.'" -#endif +#include "env_validate.h" /** * 2017 Victor Perez Marlin for stm32f1 test @@ -32,53 +30,40 @@ #define BOARD_INFO_NAME "Chitu3D" #define DEFAULT_MACHINE_NAME "STM32F103RET6" +#define BOARD_NO_NATIVE_USB + // Enable I2C_EEPROM for testing //#define I2C_EEPROM // Ignore temp readings during development. //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 +// +// Limit Switches +// +#define X_STOP_PIN PG10 +#define Y_STOP_PIN PA12 +#define Z_STOP_PIN PA14 + // // Steppers // #define X_STEP_PIN PE5 #define X_DIR_PIN PE6 #define X_ENABLE_PIN PC13 -#define X_MIN_PIN PG10 -#define X_MAX_PIN -1 #define Y_STEP_PIN PE2 #define Y_DIR_PIN PE3 #define Y_ENABLE_PIN PE4 -#define Y_MIN_PIN PA12 -#define Y_MAX_PIN #define Z_STEP_PIN PB9 #define Z_DIR_PIN PE0 #define Z_ENABLE_PIN PE1 -#define Z_MIN_PIN PA14 -#define Z_MAX_PIN -1 - -#define Y2_STEP_PIN -1 -#define Y2_DIR_PIN -1 -#define Y2_ENABLE_PIN -1 - -#define Z2_STEP_PIN -1 -#define Z2_DIR_PIN -1 -#define Z2_ENABLE_PIN -1 #define E0_STEP_PIN PB4 #define E0_DIR_PIN PB5 #define E0_ENABLE_PIN PB8 -#define E1_STEP_PIN -1 -#define E1_DIR_PIN -1 -#define E1_ENABLE_PIN -1 - -#define E2_STEP_PIN -1 -#define E2_DIR_PIN -1 -#define E2_ENABLE_PIN -1 - // // Misc. Functions // @@ -96,12 +81,7 @@ // Heaters / Fans // #define HEATER_0_PIN PD12 // HOT-END -#define HEATER_1_PIN -1 -#define HEATER_2_PIN -1 - #define HEATER_BED_PIN PG11 // HOT-BED -#define HEATER_BED2_PIN -1 // BED2 -#define HEATER_BED3_PIN -1 // BED3 #ifndef FAN_PIN #define FAN_PIN PG14 // MAIN BOARD FAN @@ -112,10 +92,8 @@ // // Temperature Sensors // -#define TEMP_BED_PIN PA0 // Analog Input #define TEMP_0_PIN PA1 // Analog Input -#define TEMP_1_PIN -1 // Analog Input -#define TEMP_2_PIN -1 // Analog Input +#define TEMP_BED_PIN PA0 // Analog Input // // LCD Pins @@ -126,7 +104,7 @@ #define LCD_PINS_RS PD1 // 49 // CS chip select /SS chip slave select #define LCD_PINS_ENABLE PD3 // 51 // SID (MOSI) #define LCD_PINS_D4 PD4 // 52 // SCK (CLK) clock - #elif BOTH(NEWPANEL, PANEL_ONE) + #elif BOTH(IS_NEWPANEL, PANEL_ONE) #define LCD_PINS_RS PB8 #define LCD_PINS_ENABLE PD2 #define LCD_PINS_D4 PB12 @@ -140,20 +118,20 @@ #define LCD_PINS_D5 PB13 #define LCD_PINS_D6 PB14 #define LCD_PINS_D7 PB15 - #if DISABLED(NEWPANEL) + #if !IS_NEWPANEL #define BEEPER_PIN PC1 // 33 // Buttons attached to a shift register // Not wired yet - //#define SHIFT_CLK PC6 // 38 - //#define SHIFT_LD PC10 // 42 - //#define SHIFT_OUT PC8 // 40 - //#define SHIFT_EN PA1 // 17 + //#define SHIFT_CLK_PIN PC6 // 38 + //#define SHIFT_LD_PIN PC10 // 42 + //#define SHIFT_OUT_PIN PC8 // 40 + //#define SHIFT_EN_PIN PA1 // 17 #endif #endif - #if ENABLED(NEWPANEL) + #if IS_NEWPANEL - #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) + #if IS_RRD_SC #define BEEPER_PIN PC5 @@ -254,13 +232,13 @@ #define BEEPER_PIN PC1 // 33 // Buttons directly attached to AUX-2 - #if ENABLED(REPRAPWORLD_KEYPAD) + #if IS_RRW_KEYPAD #define BTN_EN1 PE0 // 64 #define BTN_EN2 PD11 // 59 #define BTN_ENC PD15 // 63 - #define SHIFT_OUT PC8 // 40 - #define SHIFT_CLK PC12 // 44 - #define SHIFT_LD PC10 // 42 + #define SHIFT_OUT_PIN PC8 // 40 + #define SHIFT_CLK_PIN PC12 // 44 + #define SHIFT_LD_PIN PC10 // 42 #elif ENABLED(PANEL_ONE) #define BTN_EN1 PD11 // 59 // AUX2 PIN 3 #define BTN_EN2 PD15 // 63 // AUX2 PIN 4 @@ -279,6 +257,10 @@ #endif #endif - #endif // NEWPANEL + #endif // IS_NEWPANEL + + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h b/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h index b02d414089ff..afe58df803d6 100644 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h @@ -21,183 +21,8 @@ */ #pragma once -#if NOT_TARGET(__STM32F1__, __STM32F4__) - #error "Oops! Select an STM32F1/4 board in 'Tools > Board.'" -#endif +#define BOARD_INFO_NAME "Chitu3D V5" -/** - * 2017 Victor Perez Marlin for stm32f1 test - */ - -#define BOARD_INFO_NAME "Chitu3D V5" -#define DEFAULT_MACHINE_NAME "STM32F103ZET6" - -#define DISABLE_JTAG - -// -// EEPROM -// -#define FLASH_EEPROM_EMULATION -#if ENABLED(FLASH_EEPROM_EMULATION) - // SoC Flash (framework-arduinoststm32-maple/STM32F1/libraries/EEPROM/EEPROM.h) - #define EEPROM_START_ADDRESS (0x8000000UL + (512 * 1024) - 2 * EEPROM_PAGE_SIZE) - #define EEPROM_PAGE_SIZE (0x800U) // 2KB, but will use 2x more (4KB) - #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE -#else - #define MARLIN_EEPROM_SIZE 0x800U // On SD, Limit to 2KB, require this amount of RAM -#endif - -// -// Limit Switches -// -#define X_STOP_PIN PG10 -#define Y_STOP_PIN PA12 -#define Z_STOP_PIN PA14 - -// -// Steppers -// -#define X_ENABLE_PIN PC13 -#define X_STEP_PIN PE5 -#define X_DIR_PIN PE6 - -#define Y_ENABLE_PIN PE4 -#define Y_STEP_PIN PE2 -#define Y_DIR_PIN PE3 - -#define Z_ENABLE_PIN PE1 -#define Z_STEP_PIN PB9 -#define Z_DIR_PIN PE0 - -#define E0_ENABLE_PIN PB8 -#define E0_STEP_PIN PB4 -#define E0_DIR_PIN PB5 - -#define E1_ENABLE_PIN PG8 -#define E1_STEP_PIN PC7 -#define E1_DIR_PIN PC6 - -// -// Temperature Sensors -// -#define TEMP_0_PIN PA1 // TH1 -#define TEMP_BED_PIN PA0 // TB1 - -// -// Heaters -// -#define HEATER_0_PIN PG12 // HEATER1 -#define HEATER_BED_PIN PG11 // HOT BED - -// -// Fans -// -#define CONTROLLER_FAN_PIN PD6 // BOARD FAN -#define FAN_PIN PG13 // FAN -#define FAN_PIN_2 PG14 - -// -// Misc -// -#define BEEPER_PIN PB0 -//#define LED_PIN -1 -//#define POWER_LOSS_PIN -1 -#define FIL_RUNOUT_PIN PA15 - -// SPI Flash -#define HAS_SPI_FLASH 1 -#if HAS_SPI_FLASH - #define SPI_FLASH_SIZE 0x200000 // 2MB -#endif - -// SPI 2 -#define W25QXX_CS_PIN PB12 -#define W25QXX_MOSI_PIN PB15 -#define W25QXX_MISO_PIN PB14 -#define W25QXX_SCK_PIN PB13 - -// -// TronXY TFT Support -// - -#if HAS_FSMC_TFT - - // Shared FSMC - - #define TOUCH_CS_PIN PB7 // SPI1_NSS - #define TOUCH_SCK_PIN PA5 // SPI1_SCK - #define TOUCH_MISO_PIN PA6 // SPI1_MISO - #define TOUCH_MOSI_PIN PA7 // SPI1_MOSI - - #define TFT_RESET_PIN PF11 - #define TFT_BACKLIGHT_PIN PD13 - - #define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT - #define FSMC_CS_PIN PD7 - #define FSMC_RS_PIN PD11 - #define FSMC_DMA_DEV DMA2 - #define FSMC_DMA_CHANNEL DMA_CH5 - -#endif - -#if ENABLED(TFT_LVGL_UI) - // LVGL - #define HAS_SPI_FLASH_FONT 1 - #define HAS_GCODE_PREVIEW 1 - #define HAS_GCODE_DEFAULT_VIEW_IN_FLASH 0 - #define HAS_LANG_SELECT_SCREEN 1 - #define HAS_BAK_VIEW_IN_FLASH 0 - #define HAS_LOGO_IN_FLASH 0 -#elif ENABLED(TFT_COLOR_UI) - // Color UI - #define TFT_DRIVER ILI9488 - #define TFT_BUFFER_SIZE 14400 -#elif ENABLED(TFT_CLASSIC_UI) - // Emulated DOGM - #define GRAPHICAL_TFT_UPSCALE 3 -#endif - -// XPT2046 Touch Screen calibration -#if EITHER(TFT_LVGL_UI, TFT_COLOR_UI) - #ifndef XPT2046_X_CALIBRATION - #define XPT2046_X_CALIBRATION -17181 - #endif - #ifndef XPT2046_Y_CALIBRATION - #define XPT2046_Y_CALIBRATION 11434 - #endif - #ifndef XPT2046_X_OFFSET - #define XPT2046_X_OFFSET 501 - #endif - #ifndef XPT2046_Y_OFFSET - #define XPT2046_Y_OFFSET -9 - #endif -#elif ENABLED(TFT_CLASSIC_UI) - #ifndef XPT2046_X_CALIBRATION - #define XPT2046_X_CALIBRATION -12316 - #endif - #ifndef XPT2046_Y_CALIBRATION - #define XPT2046_Y_CALIBRATION 8981 - #endif - #ifndef XPT2046_X_OFFSET - #define XPT2046_X_OFFSET 340 - #endif - #ifndef XPT2046_Y_OFFSET - #define XPT2046_Y_OFFSET -20 - #endif -#endif - -// SPI1(PA7)=LCD & SPI3(PB5)=STUFF, are not available -// Needs to use SPI2 -#define ENABLE_SPI2 -#define SCK_PIN PB13 -#define MISO_PIN PB14 -#define MOSI_PIN PB15 -#define SS_PIN PB12 +#define Z_STOP_PIN PG9 -// -// SD Card -// -#define SDIO_SUPPORT -#define SD_DETECT_PIN -1 // PF0, but it isn't connected -#define SDIO_CLOCK 4500000 -#define SDIO_READ_RETRIES 16 +#include "pins_CHITU3D_common.h" diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h b/Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h index cafd50dcf22c..b76ef52c420a 100644 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h @@ -21,198 +21,14 @@ */ #pragma once -#if NOT_TARGET(__STM32F1__, __STM32F4__) - #error "Oops! Select an STM32F1/4 board in 'Tools > Board.'" -#endif - -/** - * 2017 Victor Perez Marlin for stm32f1 test - */ - -#define BOARD_INFO_NAME "Chitu3D" -#define DEFAULT_MACHINE_NAME "STM32F103ZET6" - -#define DISABLE_JTAG - -// -// EEPROM -// - -#if NO_EEPROM_SELECTED - #define FLASH_EEPROM_EMULATION -#endif - -#if ENABLED(FLASH_EEPROM_EMULATION) - // SoC Flash (framework-arduinoststm32-maple/STM32F1/libraries/EEPROM/EEPROM.h) - #define EEPROM_START_ADDRESS (0x8000000UL + (512 * 1024) - 2 * EEPROM_PAGE_SIZE) - #define EEPROM_PAGE_SIZE (0x800U) // 2KB, but will use 2x more (4KB) - #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE -#else - #define MARLIN_EEPROM_SIZE 0x800U // On SD, Limit to 2KB, require this amount of RAM -#endif - -// -// Limit Switches -// -#define X_STOP_PIN PG10 -#define Y_STOP_PIN PA12 -#define Z_STOP_PIN PG9 - -// -// Steppers -// -#define X_ENABLE_PIN PC13 -#define X_STEP_PIN PE5 -#define X_DIR_PIN PE6 - -#define Y_ENABLE_PIN PE4 -#define Y_STEP_PIN PE2 -#define Y_DIR_PIN PE3 - -#define Z_ENABLE_PIN PE1 -#define Z_STEP_PIN PB9 -#define Z_DIR_PIN PE0 +#define BOARD_INFO_NAME "Chitu3D V6" #define Z2_ENABLE_PIN PF3 #define Z2_STEP_PIN PF5 #define Z2_DIR_PIN PF1 -#define E0_ENABLE_PIN PB8 -#define E0_STEP_PIN PB4 -#define E0_DIR_PIN PB5 - -#define E1_ENABLE_PIN PG8 -#define E1_STEP_PIN PC7 -#define E1_DIR_PIN PC6 - -// -// Temperature Sensors -// -#define TEMP_0_PIN PA1 // TH1 -#define TEMP_BED_PIN PA0 // TB1 - -// -// Heaters -// -#define HEATER_0_PIN PG12 // HEATER1 -#define HEATER_BED_PIN PG11 // HOT BED -//#define HEATER_BED_INVERTING true - -// -// Fans -// -#define CONTROLLER_FAN_PIN PD6 // BOARD FAN -#define FAN_PIN PG13 // FAN -#define FAN_PIN_2 PG14 - -// -// Misc -// -#define BEEPER_PIN PB0 -//#define LED_PIN PD3 -//#define POWER_LOSS_PIN PG2 // PG4 PW_DET - -#ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN PA15 // MT_DET -#endif #ifndef FIL_RUNOUT2_PIN #define FIL_RUNOUT2_PIN PF13 #endif -// SPI Flash -#define HAS_SPI_FLASH 1 -#if HAS_SPI_FLASH - #define SPI_FLASH_SIZE 0x200000 // 2MB -#endif - -// SPI 2 -#define W25QXX_CS_PIN PB12 -#define W25QXX_MOSI_PIN PB15 -#define W25QXX_MISO_PIN PB14 -#define W25QXX_SCK_PIN PB13 - -// -// TronXY TFT Support -// - -#if HAS_FSMC_TFT - - // Shared FSMC - - #define TOUCH_CS_PIN PB7 // SPI1_NSS - #define TOUCH_SCK_PIN PA5 // SPI1_SCK - #define TOUCH_MISO_PIN PA6 // SPI1_MISO - #define TOUCH_MOSI_PIN PA7 // SPI1_MOSI - - #define TFT_RESET_PIN PF11 - #define TFT_BACKLIGHT_PIN PD13 - - #define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT - #define FSMC_CS_PIN PD7 - #define FSMC_RS_PIN PD11 - #define FSMC_DMA_DEV DMA2 - #define FSMC_DMA_CHANNEL DMA_CH5 - -#endif - -#if ENABLED(TFT_LVGL_UI) - // LVGL - #define HAS_SPI_FLASH_FONT 1 - #define HAS_GCODE_PREVIEW 1 - #define HAS_GCODE_DEFAULT_VIEW_IN_FLASH 0 - #define HAS_LANG_SELECT_SCREEN 1 - #define HAS_BAK_VIEW_IN_FLASH 0 - #define HAS_LOGO_IN_FLASH 0 -#elif ENABLED(TFT_COLOR_UI) - // Color UI - #define TFT_DRIVER ILI9488 - #define TFT_BUFFER_SIZE 14400 -#elif ENABLED(TFT_CLASSIC_UI) - // Emulated DOGM - #define GRAPHICAL_TFT_UPSCALE 3 -#endif - -// XPT2046 Touch Screen calibration -#if EITHER(TFT_LVGL_UI, TFT_COLOR_UI) - #ifndef XPT2046_X_CALIBRATION - #define XPT2046_X_CALIBRATION -17181 - #endif - #ifndef XPT2046_Y_CALIBRATION - #define XPT2046_Y_CALIBRATION 11434 - #endif - #ifndef XPT2046_X_OFFSET - #define XPT2046_X_OFFSET 501 - #endif - #ifndef XPT2046_Y_OFFSET - #define XPT2046_Y_OFFSET -9 - #endif -#elif ENABLED(TFT_CLASSIC_UI) - #ifndef XPT2046_X_CALIBRATION - #define XPT2046_X_CALIBRATION -12316 - #endif - #ifndef XPT2046_Y_CALIBRATION - #define XPT2046_Y_CALIBRATION 8981 - #endif - #ifndef XPT2046_X_OFFSET - #define XPT2046_X_OFFSET 340 - #endif - #ifndef XPT2046_Y_OFFSET - #define XPT2046_Y_OFFSET -20 - #endif -#endif - -// SPI1(PA7)=LCD & SPI3(PB5)=STUFF, are not available -// so SPI2 is required. -#define ENABLE_SPI2 -#define SCK_PIN PB13 -#define MISO_PIN PB14 -#define MOSI_PIN PB15 -#define SS_PIN PB12 - -// -// SD Card -// -#define SDIO_SUPPORT -#define SD_DETECT_PIN -1 // PF0, but it isn't connected -#define SDIO_CLOCK 4500000 -#define SDIO_READ_RETRIES 16 +#include "pins_CHITU3D_common.h" diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D_V9.h b/Marlin/src/pins/stm32f1/pins_CHITU3D_V9.h new file mode 100755 index 000000000000..eb7f91deab96 --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D_V9.h @@ -0,0 +1,36 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#define BOARD_INFO_NAME "Chitu3D V9" + +#define Z_STOP_PIN PA14 + +#define Z2_ENABLE_PIN PF3 +#define Z2_STEP_PIN PF5 +#define Z2_DIR_PIN PF1 + +#ifndef FIL_RUNOUT2_PIN + #define FIL_RUNOUT2_PIN PF13 +#endif + +#include "pins_CHITU3D_common.h" diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D_common.h b/Marlin/src/pins/stm32f1/pins_CHITU3D_common.h new file mode 100644 index 000000000000..0319afa5e990 --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D_common.h @@ -0,0 +1,177 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include "env_validate.h" + +#ifndef BOARD_INFO_NAME + #define BOARD_INFO_NAME "Chitu3D" +#endif +#ifndef DEFAULT_MACHINE_NAME + #define DEFAULT_MACHINE_NAME "STM32F103ZET6" +#endif + +#define BOARD_NO_NATIVE_USB +#define DISABLE_JTAG + +// +// EEPROM +// + +#if NO_EEPROM_SELECTED + #define FLASH_EEPROM_EMULATION +#endif + +#if ENABLED(FLASH_EEPROM_EMULATION) + // SoC Flash (framework-arduinoststm32-maple/STM32F1/libraries/EEPROM/EEPROM.h) + #define EEPROM_START_ADDRESS (0x8000000UL + (512 * 1024) - 2 * EEPROM_PAGE_SIZE) + #define EEPROM_PAGE_SIZE (0x800U) // 2KB, but will use 2x more (4KB) + #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE +#else + #define MARLIN_EEPROM_SIZE 0x800U // On SD, Limit to 2KB, require this amount of RAM +#endif + +// +// Limit Switches +// +#define X_STOP_PIN PG10 +#define Y_STOP_PIN PA12 +#ifndef Z_STOP_PIN + #define Z_STOP_PIN PG9 +#endif + +// +// Steppers +// +#define X_ENABLE_PIN PC13 +#define X_STEP_PIN PE5 +#define X_DIR_PIN PE6 + +#define Y_ENABLE_PIN PE4 +#define Y_STEP_PIN PE2 +#define Y_DIR_PIN PE3 + +#define Z_ENABLE_PIN PE1 +#define Z_STEP_PIN PB9 +#define Z_DIR_PIN PE0 + +#define E0_ENABLE_PIN PB8 +#define E0_STEP_PIN PB4 +#define E0_DIR_PIN PB5 + +#define E1_ENABLE_PIN PG8 +#define E1_STEP_PIN PC7 +#define E1_DIR_PIN PC6 + +// +// Temperature Sensors +// +#define TEMP_0_PIN PA1 // TH1 Analog Input +#define TEMP_BED_PIN PA0 // TB1 Analog Input + +// +// Heaters +// +#define HEATER_0_PIN PG12 // HEATER1 +#define HEATER_BED_PIN PG11 // HOT BED +//#define HEATER_BED_INVERTING true + +// +// Fans +// +#define CONTROLLER_FAN_PIN PD6 // BOARD FAN +#define FAN_PIN PG13 // FAN +#define FAN2_PIN PG14 + +// +// Misc +// +#define BEEPER_PIN PB0 +//#define LED_PIN PD3 +//#define POWER_LOSS_PIN PG2 // PG4 PW_DET + +#ifndef FIL_RUNOUT_PIN + #define FIL_RUNOUT_PIN PA15 // MT_DET +#endif + +// SPI Flash +#define HAS_SPI_FLASH 1 +#if HAS_SPI_FLASH + #define SPI_FLASH_SIZE 0x200000 // 2MB +#endif + +// SPI 2 +#define W25QXX_CS_PIN PB12 +#define W25QXX_MOSI_PIN PB15 +#define W25QXX_MISO_PIN PB14 +#define W25QXX_SCK_PIN PB13 + +// +// TFT with FSMC interface +// +#if HAS_FSMC_TFT + #define TOUCH_CS_PIN PB7 // SPI1_NSS + #define TOUCH_SCK_PIN PA5 // SPI1_SCK + #define TOUCH_MISO_PIN PA6 // SPI1_MISO + #define TOUCH_MOSI_PIN PA7 // SPI1_MOSI + + #define TFT_RESET_PIN PF11 + #define TFT_BACKLIGHT_PIN PD13 + + #define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT + #define FSMC_CS_PIN PD7 + #define FSMC_RS_PIN PD11 + #define FSMC_DMA_DEV DMA2 + #define FSMC_DMA_CHANNEL DMA_CH5 + + #define TFT_CS_PIN FSMC_CS_PIN + #define TFT_RS_PIN FSMC_RS_PIN +#endif + +#if HAS_TFT_LVGL_UI + // LVGL + #define HAS_SPI_FLASH_FONT 1 + #define HAS_GCODE_PREVIEW 1 + #define HAS_GCODE_DEFAULT_VIEW_IN_FLASH 0 + #define HAS_LANG_SELECT_SCREEN 1 + #define HAS_BAK_VIEW_IN_FLASH 0 + #define HAS_LOGO_IN_FLASH 0 +#elif ENABLED(TFT_COLOR_UI) + // Color UI + #define TFT_BUFFER_SIZE 14400 +#endif + +// SPI1(PA7)=LCD & SPI3(PB5)=STUFF, are not available +// so SPI2 is required. +#define SPI_DEVICE 2 +#define SD_SCK_PIN PB13 +#define SD_MISO_PIN PB14 +#define SD_MOSI_PIN PB15 +#define SD_SS_PIN PB12 + +// +// SD Card +// +#define SDIO_SUPPORT +#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_V4.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h index eb910dd8466e..6b3c4ed8fae7 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. - * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm + * 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 @@ -19,17 +19,16 @@ * along with this program. If not, see . * */ +#pragma once /** - * CREALITY (STM32F103) board pin assignments + * Creality 4.2.x (STM32F103RET6) board pin assignments */ -#if NOT_TARGET(__STM32F1__) - #error "Oops! Select an STM32F1 board in 'Tools > Board.'" -#endif +#include "env_validate.h" #if HOTENDS > 1 || E_STEPPERS > 1 - #error "CREALITY supports up to 1 hotends / E-steppers. Comment out this line to continue." + #error "Creality V4 only supports one hotend / E-stepper. Comment out this line to continue." #endif #ifndef BOARD_INFO_NAME @@ -39,40 +38,34 @@ #define DEFAULT_MACHINE_NAME "Ender 3 V2" #endif +#define BOARD_NO_NATIVE_USB + // // EEPROM // #if NO_EEPROM_SELECTED - // FLASH - //#define FLASH_EEPROM_EMULATION - - // I2C - #define IIC_BL24CXX_EEPROM // EEPROM on I2C-0 used only for display settings - #if ENABLED(IIC_BL24CXX_EEPROM) - #define IIC_EEPROM_SDA PA11 - #define IIC_EEPROM_SCL PA12 - #define MARLIN_EEPROM_SIZE 0x800 // 2Kb (24C16) - #else - #define SDCARD_EEPROM_EMULATION // SD EEPROM until all EEPROM is BL24CXX - #define MARLIN_EEPROM_SIZE 0x800 // 2Kb - #endif - - // SPI - //#define SPI_EEPROM // EEPROM on SPI-0 - //#define SPI_CHAN_EEPROM1 ? - //#define SPI_EEPROM1_CS ? - - // 2K EEPROM - //#define SPI_EEPROM2_CS ? + #define IIC_BL24CXX_EEPROM // EEPROM on I2C-0 + //#define SDCARD_EEPROM_EMULATION +#endif - // 32Mb FLASH - //#define SPI_FLASH_CS ? +#if ENABLED(IIC_BL24CXX_EEPROM) + #define IIC_EEPROM_SDA PA11 + #define IIC_EEPROM_SCL PA12 + #define MARLIN_EEPROM_SIZE 0x800 // 2Kb (24C16) +#elif ENABLED(SDCARD_EEPROM_EMULATION) + #define MARLIN_EEPROM_SIZE 0x800 // 2Kb #endif // // Servos // -#define SERVO0_PIN PB0 // BLTouch OUT +#ifndef SERVO0_PIN + #ifndef HAS_PIN_27_BOARD + #define SERVO0_PIN PB0 // BLTouch OUT + #else + #define SERVO0_PIN PC6 + #endif +#endif // // Limit Switches @@ -81,7 +74,9 @@ #define Y_STOP_PIN PA6 #define Z_STOP_PIN PA7 -#define Z_MIN_PROBE_PIN PB1 // BLTouch IN +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN PB1 // BLTouch IN +#endif // // Filament Runout Sensor @@ -142,8 +137,12 @@ #define HEATER_0_PIN PA1 // HEATER1 #define HEATER_BED_PIN PA2 // HOT BED -#define FAN_PIN PA0 // FAN -#define FAN_SOFT_PWM +#ifndef FAN_PIN + #define FAN_PIN PA0 // FAN +#endif +#if PIN_EXISTS(FAN) + #define FAN_SOFT_PWM +#endif // // SD Card @@ -170,7 +169,9 @@ #define BTN_EN1 PB10 #define BTN_EN2 PB14 - #define BEEPER_PIN PC6 + #ifndef HAS_PIN_27_BOARD + #define BEEPER_PIN PC6 + #endif #elif ENABLED(VET6_12864_LCD) diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h new file mode 100644 index 000000000000..d106c98e1360 --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h @@ -0,0 +1,209 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * CREALITY 4.2.10 (STM32F103) board pin assignments + */ + +#include "env_validate.h" + +#if HOTENDS > 1 || E_STEPPERS > 1 + #error "CREALITY supports up to 1 hotends / E-steppers. Comment out this line to continue." +#endif + +#ifndef BOARD_INFO_NAME + #define BOARD_INFO_NAME "Creality V4.2.10" +#endif +#ifndef DEFAULT_MACHINE_NAME + #define DEFAULT_MACHINE_NAME "3DPrintMill" +#endif + +#define BOARD_NO_NATIVE_USB + +// +// EEPROM +// +#if NO_EEPROM_SELECTED + // FLASH + //#define FLASH_EEPROM_EMULATION + + // I2C + #define IIC_BL24CXX_EEPROM // EEPROM on I2C-0 used only for display settings + #if ENABLED(IIC_BL24CXX_EEPROM) + #define IIC_EEPROM_SDA PA11 + #define IIC_EEPROM_SCL PA12 + #define MARLIN_EEPROM_SIZE 0x800 // 2Kb (24C16) + #else + #define SDCARD_EEPROM_EMULATION // SD EEPROM until all EEPROM is BL24CXX + #define MARLIN_EEPROM_SIZE 0x800 // 2Kb + #endif + + // SPI + //#define SPI_EEPROM // EEPROM on SPI-0 + //#define SPI_CHAN_EEPROM1 ? + //#define SPI_EEPROM1_CS ? + + // 2K EEPROM + //#define SPI_EEPROM2_CS ? + + // 32Mb FLASH + //#define SPI_FLASH_CS ? +#endif + +// +// Servos +// +#define SERVO0_PIN PB0 // BLTouch OUT + +// +// Limit Switches +// +#define X_STOP_PIN PA3 +#define Y_STOP_PIN PA7 +#define Z_STOP_PIN PA5 + +#define Z_MIN_PROBE_PIN PA5 // BLTouch IN + +// +// Filament Runout Sensor +// +#ifndef FIL_RUNOUT_PIN + #define FIL_RUNOUT_PIN PA6 // "Pulled-high" +#endif + +// +// Steppers +// +#define X_ENABLE_PIN PC3 +#ifndef X_STEP_PIN + #define X_STEP_PIN PC2 +#endif +#ifndef X_DIR_PIN + #define X_DIR_PIN PB9 +#endif + +#define Y_ENABLE_PIN PC3 +#ifndef Y_STEP_PIN + #define Y_STEP_PIN PB8 +#endif +#ifndef Y_DIR_PIN + #define Y_DIR_PIN PB7 +#endif + +#define Z_ENABLE_PIN PC3 +#ifndef Z_STEP_PIN + #define Z_STEP_PIN PB6 +#endif +#ifndef Z_DIR_PIN + #define Z_DIR_PIN PB5 +#endif + +#define E0_ENABLE_PIN PC3 +#ifndef E0_STEP_PIN + #define E0_STEP_PIN PB4 +#endif +#ifndef E0_DIR_PIN + #define E0_DIR_PIN PB3 +#endif + +// +// Release PB4 (Y_ENABLE_PIN) from JTAG NRST role +// +#define DISABLE_DEBUG + +// +// Temperature Sensors +// +#define TEMP_0_PIN PC5 // TH1 +#define TEMP_BED_PIN PC4 // TB1 + +// +// Heaters / Fans +// +#define HEATER_0_PIN PA0 // HEATER1 +#define HEATER_BED_PIN PA1 // HOT BED + +#define FAN_PIN PA2 // FAN +#define FAN_SOFT_PWM + +// +// 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 ENABLED(CR10_STOCKDISPLAY) && NONE(RET6_12864_LCD, VET6_12864_LCD) + #error "Define RET6_12864_LCD or VET6_12864_LCD to select pins for CR10_STOCKDISPLAY with the Creality V4 controller." +#endif + +#if ENABLED(RET6_12864_LCD) + + // RET6 12864 LCD + #define LCD_PINS_RS PB12 + #define LCD_PINS_ENABLE PB15 + #define LCD_PINS_D4 PB13 + + #define BTN_ENC PB2 + #define BTN_EN1 PB10 + #define BTN_EN2 PB14 + + #define BEEPER_PIN PC6 + +#elif ENABLED(VET6_12864_LCD) + + // VET6 12864 LCD + #define LCD_PINS_RS PA4 + #define LCD_PINS_ENABLE PA7 + #define LCD_PINS_D4 PA5 + + #define BTN_ENC PC5 + #define BTN_EN1 PB10 + #define BTN_EN2 PA6 + +#elif ENABLED(DWIN_CREALITY_LCD) + + // RET6 DWIN ENCODER LCD + #define BTN_ENC PB14 + #define BTN_EN1 PB15 + #define BTN_EN2 PB12 + + //#define LCD_LED_PIN PB2 + #ifndef BEEPER_PIN + #define BEEPER_PIN PB13 + #undef SPEAKER + #endif + +#elif ENABLED(DWIN_VET6_CREALITY_LCD) + + // VET6 DWIN ENCODER LCD + #define BTN_ENC PA6 + #define BTN_EN1 PA7 + #define BTN_EN2 PA4 + + #define BEEPER_PIN PA5 + +#endif diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V427.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V427.h index 5b51ece07f08..c327abee7796 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V427.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V427.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. - * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm + * 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 @@ -19,15 +19,12 @@ * along with this program. If not, see . * */ +#pragma once /** * CREALITY v4.2.7 (STM32F103) board pin assignments */ -#if NOT_TARGET(__STM32F1__) - #error "Oops! Select an STM32F1 board in 'Tools > Board.'" -#endif - #define BOARD_INFO_NAME "Creality v4.2.7" #define DEFAULT_MACHINE_NAME "Creality3D" diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V431.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V431.h new file mode 100644 index 000000000000..e8ae84da8f9e --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V431.h @@ -0,0 +1,40 @@ +/** + * 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 + +/** + * CREALITY v4.3.1 (STM32F103) board pin assignments + */ + +#define BOARD_INFO_NAME "Creality v4.3.1" +#define DEFAULT_MACHINE_NAME "Creality3D" + +// +// Steppers +// +#define X_STEP_PIN PB8 +#define X_DIR_PIN PB7 + +#define Y_STEP_PIN PC2 +#define Y_DIR_PIN PB9 + +#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 new file mode 100644 index 000000000000..64e07a0bc832 --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V452.h @@ -0,0 +1,39 @@ +/** + * 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 + +/** + * Creality v4.5.2 (STM32F103RET6) board pin assignments + */ + +#if HOTENDS > 1 || E_STEPPERS > 1 + #error "Creality v4.5.2 only supports one hotend / E-stepper. Comment out this line to continue." +#endif + +#define BOARD_INFO_NAME "Creality v4.5.2" + +#define HEATER_0_PIN PA1 // HEATER1 +#define HEATER_BED_PIN PA2 // HOT BED +#define FAN_PIN PA0 // FAN +#define PROBE_ACTIVATION_SWITCH_PIN PC6 // Optoswitch to Enable Z Probe + +#include "pins_CREALITY_V45x.h" diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V453.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V453.h new file mode 100644 index 000000000000..ca437312c8e1 --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V453.h @@ -0,0 +1,39 @@ +/** + * 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 + +/** + * Creality v4.5.3 (STM32F103RET6) board pin assignments + */ + +#if HOTENDS > 1 || E_STEPPERS > 1 + #error "Creality v4.5.3 only supports one hotend / E-stepper. Comment out this line to continue." +#endif + +#define BOARD_INFO_NAME "Creality v4.5.3" + +#define HEATER_0_PIN PB14 // HEATER1 +#define HEATER_BED_PIN PB13 // HOT BED +#define FAN_PIN PB15 // FAN +#define PROBE_ACTIVATION_SWITCH_PIN PB2 // Optoswitch to Enable Z Probe + +#include "pins_CREALITY_V45x.h" diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V45x.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V45x.h new file mode 100644 index 000000000000..39dccf1271af --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V45x.h @@ -0,0 +1,112 @@ +/** + * 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 + +/** + * Creality v4.5.2 and v4.5.3 (STM32F103RET6) board pin assignments + */ + +#include "env_validate.h" + +#define DEFAULT_MACHINE_NAME "Creality3D" + +// +// Release PB4 (Z_STEP_PIN) from JTAG NRST role +// +#define DISABLE_DEBUG + +#define BOARD_NO_NATIVE_USB + +// +// EEPROM +// +#if NO_EEPROM_SELECTED + #define IIC_BL24CXX_EEPROM // EEPROM on I2C-0 + //#define SDCARD_EEPROM_EMULATION +#endif + +#if ENABLED(IIC_BL24CXX_EEPROM) + #define IIC_EEPROM_SDA PA11 + #define IIC_EEPROM_SCL PA12 + #define MARLIN_EEPROM_SIZE 0x800 // 2Kb (24C16) +#elif ENABLED(SDCARD_EEPROM_EMULATION) + #define MARLIN_EEPROM_SIZE 0x800 // 2Kb +#endif + +// +// Limit Switches +// +#define X_STOP_PIN PC4 +#define Y_STOP_PIN PC5 +#define Z_STOP_PIN PA4 + +#define FIL_RUNOUT_PIN PA7 + +// +// Probe +// +#define PROBE_TARE_PIN PA5 + +// +// Steppers +// +#define X_ENABLE_PIN PC3 +#define X_STEP_PIN PB8 +#define X_DIR_PIN PB7 + +#define Y_ENABLE_PIN PC3 +#define Y_STEP_PIN PB6 +#define Y_DIR_PIN PB5 + +#define Z_ENABLE_PIN PC3 +#define Z_STEP_PIN PB4 +#define Z_DIR_PIN PB3 + +#define E0_ENABLE_PIN PC3 +#define E0_STEP_PIN PC2 +#define E0_DIR_PIN PB9 + +// +// Temperature Sensors +// +#define TEMP_0_PIN PB1 // TH1 +#define TEMP_BED_PIN PB0 // TB1 + +// +// Heaters / Fans +// + +#define FAN_SOFT_PWM + +// +// SD Card +// +#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 SDIO_CLOCK 6000000 // In original source code overridden by Creality in sdio.h + +// +// Misc. Functions +// +#define CASE_LIGHT_PIN PA6 diff --git a/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h b/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h new file mode 100644 index 000000000000..2dea59ef4180 --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h @@ -0,0 +1,323 @@ +/** + * 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 + +/** + * FLSUN HiSpeed V1 (STM32F103VET6) board pin assignments + * FLSun Hispeed (clone MKS_Robin_miniV2) board. + * + * MKS Robin Mini USB uses UART3 (PB10-TX, PB11-RX) + * #define SERIAL_PORT_2 3 + */ + +#if NOT_TARGET(__STM32F1__, STM32F1xx) + #error "Oops! Select an STM32F1 board in 'Tools > Board.'" +#elif HOTENDS > 1 || E_STEPPERS > 1 + #error "FLSUN HiSpeedV1 only supports one hotend / E-stepper. Comment out this line to continue." +#endif + +#define BOARD_INFO_NAME "FLSun HiSpeedV1" +#define BOARD_WEBSITE_URL "github.com/Foxies-CSTL" + +#define BOARD_NO_NATIVE_USB + +// 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 + +// +// EEPROM +// +#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) + #define FLASH_EEPROM_EMULATION + #define EEPROM_PAGE_SIZE (0x800U) // 2KB + #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) + #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2KB +#endif + +// +// SPI +// Note: FLSun Hispeed (clone MKS_Robin_miniV2) board is using SPI2 interface. +// +#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 HAS_SPI_FLASH 1 +#define SPI_FLASH_SIZE 0x1000000 // 16MB + +#if HAS_SPI_FLASH + // SPI 2 + #define W25QXX_CS_PIN PB12 // SPI2_NSS / Flash chip-select + #define W25QXX_MOSI_PIN PB15 + #define W25QXX_MISO_PIN PB14 + #define W25QXX_SCK_PIN PB13 +#endif + +// +// Servos +// +//#define SERVO0_PIN PA8 // use IO0 to enable BLTOUCH support/remove Mks_Wifi + +// +// Limit Switches +// +#define X_STOP_PIN PA15 // -X +#define Y_STOP_PIN PA12 // -Y +#define Z_MIN_PIN PA11 // -Z +#define Z_MAX_PIN PC4 // +Z + +#ifndef FIL_RUNOUT_PIN + #define FIL_RUNOUT_PIN MT_DET_1_PIN +#endif + +// +// Steppers +// +#define X_ENABLE_PIN PE4 // X_EN +#define X_STEP_PIN PE3 // X_STEP +#define X_DIR_PIN PE2 // X_DIR + +#define Y_ENABLE_PIN PE1 // Y_EN +#define Y_STEP_PIN PE0 // Y_STEP +#define Y_DIR_PIN PB9 // Y_DIR + +#define Z_ENABLE_PIN PB8 // Z_EN +#define Z_STEP_PIN PB5 // Z_STEP +#define Z_DIR_PIN PB4 // Z_DIR + +#define E0_ENABLE_PIN PB3 // E0_EN +#define E0_STEP_PIN PD6 // E0_STEP +#define E0_DIR_PIN PD3 // E0_DIR + +/** + * FLSUN Hi-Speed has no hard-wired UART pins for TMC drivers. + * Several wiring options are provided below, defaulting to + * to the most compatible. + */ +#if HAS_TMC_UART + // SoftwareSerial with one pin per driver + // Compatible with TMC2208 and TMC2209 drivers + #define X_SERIAL_TX_PIN PA10 // RXD1 + #define X_SERIAL_RX_PIN PA10 // RXD1 + #define Y_SERIAL_TX_PIN PA9 // TXD1 + #define Y_SERIAL_RX_PIN PA9 // TXD1 + #define Z_SERIAL_TX_PIN PC7 // IO1 + #define Z_SERIAL_RX_PIN PC7 // IO1 + #define TMC_BAUD_RATE 19200 +#else + // Motor current PWM pins + #define MOTOR_CURRENT_PWM_XY_PIN PA6 // VREF2/3 CONTROL XY + #define MOTOR_CURRENT_PWM_Z_PIN PA7 // VREF4 CONTROL Z + #define MOTOR_CURRENT_PWM_RANGE 1500 // (255 * (1000mA / 65535)) * 257 = 1000 is equal 1.6v Vref in turn equal 1Amp + #ifndef DEFAULT_PWM_MOTOR_CURRENT + #define DEFAULT_PWM_MOTOR_CURRENT { 800, 800, 800 } + #endif + + /** + * MKS Robin_Wifi or another ESP8266 module + * + * __ESP(M1)__ -J1- + * GND| 15 | | 08 |+3v3 (22) RXD1 (PA10) + * | 16 | | 07 |MOSI (21) TXD1 (PA9) Active LOW, probably OK to leave floating + * IO2| 17 | | 06 |MISO (19) IO1 (PC7) Leave as unused (ESP3D software configures this with a pullup so OK to leave as floating) + * IO0| 18 | | 05 |CLK (18) IO0 (PA8) Must be HIGH (ESP3D software configures this with a pullup so OK to leave as floating) + * IO1| 19 | | 03 |EN (03) WIFI_EN Must be HIGH for module to run + * | nc | | nc | (01) WIFI_CTRL (PA5) + * RX| 21 | | nc | + * TX| 22 | | 01 |RST + *  ̄ ̄ AE ̄ ̄ + */ + // Module ESP-WIFI + #define ESP_WIFI_MODULE_COM 2 // 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 + #define ESP_WIFI_MODULE_RESET_PIN PA5 // WIFI CTRL/RST + #define ESP_WIFI_MODULE_ENABLE_PIN -1 + #define ESP_WIFI_MODULE_TXD_PIN PA9 // MKS or ESP WIFI RX PIN + #define ESP_WIFI_MODULE_RXD_PIN PA10 // MKS or ESP WIFI TX PIN +#endif + +// +// EXTRUDER +// +#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 + #define MOTOR_CURRENT_PWM_RANGE 1500 // (255 * (1000mA / 65535)) * 257 = 1000 is equal 1.6v Vref in turn equal 1Amp + #ifndef DEFAULT_PWM_MOTOR_CURRENT + #define DEFAULT_PWM_MOTOR_CURRENT { 800, 800, 800 } + #endif +#endif + +// +// Temperature Sensors (THM) +// +#define TEMP_0_PIN PC1 // TEMP_E0 +#define TEMP_BED_PIN PC0 // TEMP_BED + +// +// Heaters / Fans +// +#define HEATER_0_PIN PC3 // HEATER_E0 +#define HEATER_BED_PIN PA0 // HEATER_BED-WKUP + +#define FAN_PIN PB1 // E_FAN + +// +// Misc. Functions +// +#if ENABLED(BACKUP_POWER_SUPPLY) + #define POWER_LOSS_PIN PA2 // PW_DET (UPS) MKSPWC +#else + //#define POWER_LOSS_PIN PA1 // PW_SO +#endif + +/** + * Connector J2 + * ------- + * DIO O|1 2|O 3v3 + * CSK O|3 5|O GND + * RST O|5 6|O GND + * ------- + */ +//#define SW_DIO PA13 +//#define SW_CLK PA14 +//#define SW_RST NRST // (14) + +// +// Power Supply Control +// +#if ENABLED(PSU_CONTROL) + #define KILL_PIN PA2 // PW_DET + #define KILL_PIN_STATE HIGH + //#define PS_ON_PIN PA3 // PW_CN /PW_OFF +#endif + +#define MT_DET_1_PIN PA4 // MT_DET +#define MT_DET_2_PIN PE6 // FALA_CRTL +#define MT_DET_PIN_INVERTING false + +// +// LED / NEOPixel +// +//#define LED_PIN PB2 // BOOT1 + +#if ENABLED(NEOPIXEL_LED) + #define LED_PWM PC7 // IO1 + #ifndef NEOPIXEL_PIN + #define NEOPIXEL_PIN LED_PWM // USED WIFI IO0/IO1 PIN + #endif +#endif + +// +// SD Card +// +#ifndef SDCARD_CONNECTION + #define SDCARD_CONNECTION ONBOARD +#endif + +// Use the on-board card socket labeled SD_Extender +#if SD_CONNECTION_IS(CUSTOM_CABLE) + #define SD_SCK_PIN PC12 + #define SD_MISO_PIN PC8 + #define SD_MOSI_PIN PD2 + #define SD_SS_PIN -1 + #define SD_DETECT_PIN PD12 // SD_CD (if -1 no detection) +#else + #define SDIO_SUPPORT + #define SDIO_CLOCK 4500000 // 4.5 MHz + #define SDIO_READ_RETRIES 16 + #define ONBOARD_SPI_DEVICE 1 // SPI1 + #define ONBOARD_SD_CS_PIN PC11 + #define SD_DETECT_PIN -1 // SD_CD (-1 active refresh) +#endif + +// +// LCD / Controller +// +#ifndef BEEPER_PIN + #define BEEPER_PIN PC5 +#endif + +#if ENABLED(SPEAKER) && BEEPER_PIN == PC5 + #error "FLSun HiSpeed default BEEPER_PIN is not a SPEAKER." +#endif + +// +// TFT with FSMC interface +// +#if HAS_FSMC_TFT + /** + * Note: MKS Robin TFT screens use various TFT controllers + * Supported screens are based on the ILI9341, ST7789V and ILI9328 (320x240) + * ILI9488 is not supported + * Define init sequences for other screens in u8g_dev_tft_320x240_upscale_from_128x64.cpp + * + * If the screen stays white, disable 'LCD_RESET_PIN' + * to let the bootloader init the screen. + * + * Setting an 'LCD_RESET_PIN' may cause a flicker when entering the LCD menu + * because Marlin uses the reset as a failsafe to revive a glitchy LCD. + */ + //#define TFT_RESET_PIN PC6 // FSMC_RST + #define TFT_BACKLIGHT_PIN PD13 + + #define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT + #define FSMC_CS_PIN PD7 // NE4 + #define FSMC_RS_PIN PD11 // A0 + #define FSMC_DMA_DEV DMA2 + #define FSMC_DMA_CHANNEL DMA_CH5 + + #define TFT_CS_PIN TFT_CS_PIN + #define TFT_RS_PIN TFT_RS_PIN + + #ifdef 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 +#elif HAS_GRAPHICAL_TFT + #define TFT_RESET_PIN PC6 + #define TFT_BACKLIGHT_PIN PD13 + #define TFT_CS_PIN PD7 // NE4 + #define TFT_RS_PIN PD11 // A0 +#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 + #define TOUCH_INT_PIN -1 +#endif diff --git a/Marlin/src/pins/stm32f1/pins_FLY_MINI.h b/Marlin/src/pins/stm32f1/pins_FLY_MINI.h index 55a809efab91..be0a622b1d71 100644 --- a/Marlin/src/pins/stm32f1/pins_FLY_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_FLY_MINI.h @@ -16,17 +16,15 @@ * 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 . + * along with this program. If not, see . * */ #pragma once -#ifndef __STM32F1__ - #error "Oops! Select an STM32F1 board in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "FLY_MINI" -#define BOARD_WEBSITE_URL "github.com/FLYmaker" +#define BOARD_WEBSITE_URL "github.com/FLYmaker/FLY-MINI" #define DISABLE_JTAG // @@ -132,13 +130,13 @@ // // LCD / Controller // -#define ENABLE_SPI2 -#define SS_PIN PB12 -#define SCK_PIN PB13 -#define MISO_PIN PB14 -#define MOSI_PIN PB15 +#define SPI_DEVICE 2 +#define SD_SS_PIN PB12 +#define SD_SCK_PIN PB13 +#define SD_MISO_PIN PB14 +#define SD_MOSI_PIN PB15 -#define SDSS SS_PIN +#define SDSS SD_SS_PIN #define SD_DETECT_PIN PB11 #define BEEPER_PIN PC14 @@ -154,6 +152,10 @@ #define BTN_EN2 PB3 #define BTN_ENC PC13 +#if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder +#endif + // // Filament runout // diff --git a/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h b/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h index ebe5964d0588..7ffe67c4f86b 100644 --- a/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h +++ b/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h @@ -21,13 +21,13 @@ */ #pragma once -#if NOT_TARGET(__STM32F1__) - #error "Oops! Select an STM32F1 board in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "FYSETC AIO II" #define BOARD_WEBSITE_URL "fysetc.com" +#define BOARD_NO_NATIVE_USB + #define DISABLE_JTAG #define pins_v2_20190128 // new pins define @@ -85,18 +85,29 @@ #define E0_ENABLE_PIN PC13 #if HAS_TMC_UART - /** * TMC2208/TMC2209 stepper drivers */ - // // Hardware serial with switch - // - #define X_HARDWARE_SERIAL MSerial1 - #define Y_HARDWARE_SERIAL MSerial1 - #define Z_HARDWARE_SERIAL MSerial1 - #define E0_HARDWARE_SERIAL MSerial1 + #define X_HARDWARE_SERIAL MSerial2 + #define Y_HARDWARE_SERIAL MSerial2 + #define Z_HARDWARE_SERIAL MSerial2 + #define E0_HARDWARE_SERIAL MSerial2 + + // Default TMC slave addresses + #ifndef X_SLAVE_ADDRESS + #define X_SLAVE_ADDRESS 0 + #endif + #ifndef Y_SLAVE_ADDRESS + #define Y_SLAVE_ADDRESS 1 + #endif + #ifndef Z_SLAVE_ADDRESS + #define Z_SLAVE_ADDRESS 2 + #endif + #ifndef E0_SLAVE_ADDRESS + #define E0_SLAVE_ADDRESS 3 + #endif // The 4xTMC2209 module doesn't have a serial multiplexer and // needs to set *_SLAVE_ADDRESS in Configuration_adv.h for X,Y,Z,E0 @@ -106,6 +117,8 @@ #define SERIAL_MUL_PIN2 PB12 #endif + // Reduce baud rate to improve software serial reliability + #define TMC_BAUD_RATE 19200 #endif // @@ -162,7 +175,7 @@ // not connected to a pin #define SD_DETECT_PIN PC3 - #if ENABLED(NEWPANEL) + #if IS_NEWPANEL // The encoder and click button #define BTN_EN1 PC10 #define BTN_EN2 PC11 diff --git a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h index de5ea45d44e8..552ad9ac5717 100644 --- a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h +++ b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h @@ -21,19 +21,18 @@ */ #pragma once -#if NOT_TARGET(__STM32F1__) - #error "Oops! Select an STM32F1 board in 'Tools > Board.'" -#endif +#include "env_validate.h" #define DEFAULT_MACHINE_NAME "3D Printer" #define BOARD_INFO_NAME "FYSETC Cheetah" #define BOARD_WEBSITE_URL "fysetc.com" -// https://github.com/FYSETC/Cheetah // Ignore temp readings during development. //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 +#define BOARD_NO_NATIVE_USB + #define DISABLE_JTAG #if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) @@ -79,10 +78,26 @@ #define E0_DIR_PIN PC14 #define E0_ENABLE_PIN PC13 -#define X_HARDWARE_SERIAL MSerial2 -#define Y_HARDWARE_SERIAL MSerial2 -#define Z_HARDWARE_SERIAL MSerial2 -#define E0_HARDWARE_SERIAL MSerial2 +#if HAS_TMC_UART + #define X_HARDWARE_SERIAL MSerial2 + #define Y_HARDWARE_SERIAL MSerial2 + #define Z_HARDWARE_SERIAL MSerial2 + #define E0_HARDWARE_SERIAL MSerial2 + + // Default TMC slave addresses + #ifndef X_SLAVE_ADDRESS + #define X_SLAVE_ADDRESS 0 + #endif + #ifndef Y_SLAVE_ADDRESS + #define Y_SLAVE_ADDRESS 1 + #endif + #ifndef Z_SLAVE_ADDRESS + #define Z_SLAVE_ADDRESS 2 + #endif + #ifndef E0_SLAVE_ADDRESS + #define E0_SLAVE_ADDRESS 3 + #endif +#endif // // Heaters / Fans @@ -153,7 +168,7 @@ //#define LCD_CONTRAST_INIT 190 - #if ENABLED(NEWPANEL) + #if IS_NEWPANEL #define BTN_EN1 PC10 #define BTN_EN2 PC11 #define BTN_ENC PC12 diff --git a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH_V12.h b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH_V12.h index 5e8bd11b4bd0..ba35265d10a0 100644 --- a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH_V12.h +++ b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH_V12.h @@ -21,9 +21,7 @@ */ #pragma once -#if NOT_TARGET(__STM32F1__) - #error "Oops! Select an STM32F1 board in 'Tools > Board.'" -#endif +#include "env_validate.h" #include "pins_FYSETC_CHEETAH.h" @@ -36,7 +34,7 @@ #undef RGB_LED_G_PIN #undef RGB_LED_B_PIN -#define FAN1_PIN PB0 // Fan1 +#define FAN1_PIN PB0 // Fan1 #if HAS_TMC_UART @@ -47,17 +45,17 @@ // // Software serial // - #define X_SERIAL_TX_PIN PA11 - #define X_SERIAL_RX_PIN PA12 + #define X_SERIAL_TX_PIN PA11 + #define X_SERIAL_RX_PIN PA12 - #define Y_SERIAL_TX_PIN PB6 - #define Y_SERIAL_RX_PIN PB7 + #define Y_SERIAL_TX_PIN PB6 + #define Y_SERIAL_RX_PIN PB7 - #define Z_SERIAL_TX_PIN PB10 - #define Z_SERIAL_RX_PIN PB11 + #define Z_SERIAL_TX_PIN PB10 + #define Z_SERIAL_RX_PIN PB11 - #define E0_SERIAL_TX_PIN PA2 - #define E0_SERIAL_RX_PIN PA3 + #define E0_SERIAL_TX_PIN PA2 + #define E0_SERIAL_RX_PIN PA3 // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h b/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h index ca25c45a7bba..4edd67a14df2 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h @@ -22,17 +22,16 @@ #pragma once /** - * 24 May 2018 - @chepo for STM32F103VET6 - * Schematic: https://github.com/chepo92/Smartto/blob/master/circuit_diagram/Rostock301/Hardware_GTM32_PRO_VB.pdf + * Geeetech GTM32 Mini board pin assignments */ -#if NOT_TARGET(__STM32F1__) - #error "Oops! Select an STM32F1 board in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "GTM32 Pro VB" #define DEFAULT_MACHINE_NAME "STM32F103VET6" +#define BOARD_NO_NATIVE_USB + //#define DISABLE_DEBUG // @@ -137,7 +136,7 @@ // #if HAS_WIRED_LCD - #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) + #if IS_RRD_SC // // LCD display on J2 FFC40 // Geeetech's LCD2004A Control Panel is very much like @@ -172,7 +171,7 @@ #endif // HAS_WIRED_LCD -#if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) +#if IS_RRD_SC // // Geeetech's LCD2004A Control Panel is very much like // RepRapDiscount Smart Controller, but adds an FFC40 connector @@ -214,23 +213,23 @@ // // SD Card on RepRapDiscount Smart Controller (J2) or on SD_CARD connector // - #define SS_PIN PC11 - #define SCK_PIN PC12 - #define MOSI_PIN PD2 - #define MISO_PIN PC8 + #define SD_SS_PIN PC11 + #define SD_SCK_PIN PC12 + #define SD_MOSI_PIN PD2 + #define SD_MISO_PIN PC8 #define SD_DETECT_PIN PC7 #else // // Use the on-board card socket labeled TF_CARD_SOCKET // - #define SS_PIN PA4 - #define SCK_PIN PA5 - #define MOSI_PIN PA7 - #define MISO_PIN PA6 + #define SD_SS_PIN PA4 + #define SD_SCK_PIN PA5 + #define SD_MOSI_PIN PA7 + #define SD_MISO_PIN PA6 #define SD_DETECT_PIN -1 // Card detect is not connected #endif -#define SDSS SS_PIN +#define SDSS SD_SS_PIN // // ESP WiFi can be soldered to J9 connector which is wired to USART2. diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h b/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h index 02fd3bcae721..f346c3a9fdf1 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h @@ -22,17 +22,16 @@ #pragma once /** - * 24 May 2018 - @chepo for STM32F103VET6 - * Schematic: https://github.com/chepo92/Smartto/blob/master/circuit_diagram/Rostock301/Hardware_GTM32_PRO_VB.pdf + * Geeetech GTM32 Mini A30 board pin assignments */ -#if NOT_TARGET(__STM32F1__) - #error "Oops! Select an STM32F1 board in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "GTM32 Pro VB" #define DEFAULT_MACHINE_NAME "STM32F103VET6" +#define BOARD_NO_NATIVE_USB + //#define DISABLE_DEBUG // @@ -137,7 +136,7 @@ // #if HAS_WIRED_LCD - #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) + #if IS_RRD_SC // // LCD display on J2 FFC40 // Geeetech's LCD2004A Control Panel is very much like @@ -208,23 +207,23 @@ // // SD Card on RepRapDiscount Smart Controller (J2) or on SD_CARD connector // - #define SS_PIN PC11 - #define SCK_PIN PC12 - #define MOSI_PIN PD2 - #define MISO_PIN PC8 + #define SD_SS_PIN PC11 + #define SD_SCK_PIN PC12 + #define SD_MOSI_PIN PD2 + #define SD_MISO_PIN PC8 #define SD_DETECT_PIN PC7 #else // // Use the on-board card socket labeled TF_CARD_SOCKET // - #define SS_PIN PA4 - #define SCK_PIN PA5 - #define MOSI_PIN PA7 - #define MISO_PIN PA6 + #define SD_SS_PIN PA4 + #define SD_SCK_PIN PA5 + #define SD_MOSI_PIN PA7 + #define SD_MISO_PIN PA6 #define SD_DETECT_PIN -1 // Card detect is not connected #endif -#define SDSS SS_PIN +#define SDSS SD_SS_PIN // // ESP WiFi can be soldered to J9 connector which is wired to USART2. diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h b/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h index ca25c45a7bba..2545642bae17 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h @@ -22,17 +22,21 @@ #pragma once /** - * 24 May 2018 - @chepo for STM32F103VET6 - * Schematic: https://github.com/chepo92/Smartto/blob/master/circuit_diagram/Rostock301/Hardware_GTM32_PRO_VB.pdf + * Geeetech GTM32 Pro VB board pin assignments + * http://www.geeetech.com/wiki/index.php/File:Hardware_GTM32_PRO_VB.pdf + * + * Also applies to GTM32 Pro VD */ -#if NOT_TARGET(__STM32F1__) - #error "Oops! Select an STM32F1 board in 'Tools > Board.'" -#endif +#include "env_validate.h" -#define BOARD_INFO_NAME "GTM32 Pro VB" +#ifndef BOARD_INFO_NAME + #define BOARD_INFO_NAME "GTM32 Pro VB" +#endif #define DEFAULT_MACHINE_NAME "STM32F103VET6" +#define BOARD_NO_NATIVE_USB + //#define DISABLE_DEBUG // @@ -137,7 +141,7 @@ // #if HAS_WIRED_LCD - #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) + #if IS_RRD_SC // // LCD display on J2 FFC40 // Geeetech's LCD2004A Control Panel is very much like @@ -172,7 +176,7 @@ #endif // HAS_WIRED_LCD -#if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) +#if IS_RRD_SC // // Geeetech's LCD2004A Control Panel is very much like // RepRapDiscount Smart Controller, but adds an FFC40 connector @@ -214,23 +218,23 @@ // // SD Card on RepRapDiscount Smart Controller (J2) or on SD_CARD connector // - #define SS_PIN PC11 - #define SCK_PIN PC12 - #define MOSI_PIN PD2 - #define MISO_PIN PC8 + #define SD_SS_PIN PC11 + #define SD_SCK_PIN PC12 + #define SD_MOSI_PIN PD2 + #define SD_MISO_PIN PC8 #define SD_DETECT_PIN PC7 #else // // Use the on-board card socket labeled TF_CARD_SOCKET // - #define SS_PIN PA4 - #define SCK_PIN PA5 - #define MOSI_PIN PA7 - #define MISO_PIN PA6 + #define SD_SS_PIN PA4 + #define SD_SCK_PIN PA5 + #define SD_MOSI_PIN PA7 + #define SD_MISO_PIN PA6 #define SD_DETECT_PIN -1 // Card detect is not connected #endif -#define SDSS SS_PIN +#define SDSS SD_SS_PIN // // ESP WiFi can be soldered to J9 connector which is wired to USART2. diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VD.h b/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VD.h new file mode 100644 index 000000000000..fb8c73c45f24 --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VD.h @@ -0,0 +1,30 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * Geeetech GTM32 Pro VD board pin assignments + */ + +#define BOARD_INFO_NAME "GTM32 Pro VD" + +#include "pins_GTM32_PRO_VB.h" diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h b/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h index fc18263fddf6..865de809e20a 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h @@ -22,17 +22,16 @@ #pragma once /** - * 24 May 2018 - @chepo for STM32F103VET6 - * Schematic: https://github.com/chepo92/Smartto/blob/master/circuit_diagram/Rostock301/Hardware_GTM32_PRO_VB.pdf + * Geeetech GTM32 Rev. B board pin assignments */ -#if NOT_TARGET(__STM32F1__) - #error "Oops! Select an STM32F1 board in 'Tools > Board.'" -#endif +#include "env_validate.h" -#define BOARD_INFO_NAME "GTM32 Pro VB" +#define BOARD_INFO_NAME "GTM32 Rev B" #define DEFAULT_MACHINE_NAME "M201" +#define BOARD_NO_NATIVE_USB + //#define DISABLE_DEBUG // @@ -137,7 +136,7 @@ // #if HAS_WIRED_LCD - #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) + #if IS_RRD_SC // // LCD display on J2 FFC40 @@ -210,24 +209,24 @@ // // SD Card on RepRapDiscount Smart Controller (J2) or on SD_CARD connector // - #define SS_PIN PB12 // PC11 - #define SCK_PIN PB13 // PC12 // PC1 - #define MOSI_PIN PB15 // PD2 // PD2 - #define MISO_PIN PB14 // PC8 + #define SD_SS_PIN PB12 // PC11 + #define SD_SCK_PIN PB13 // PC12 // PC1 + #define SD_MOSI_PIN PB15 // PD2 // PD2 + #define SD_MISO_PIN PB14 // PC8 #define SD_DETECT_PIN PC7 #else // // Use the on-board card socket labeled TF_CARD_SOCKET // - #define SS_PIN PA4 - #define SCK_PIN PA5 - #define MOSI_PIN PA7 - #define MISO_PIN PA6 // PA6 + #define SD_SS_PIN PA4 + #define SD_SCK_PIN PA5 + #define SD_MOSI_PIN PA7 + #define SD_MISO_PIN PA6 // PA6 #define SD_DETECT_PIN -1 // Card detect is not connected #endif -#define SDSS SS_PIN +#define SDSS SD_SS_PIN // // ESP WiFi can be soldered to J9 connector which is wired to USART2. diff --git a/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h b/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h index 3c277233d73e..98465a86073e 100644 --- a/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h +++ b/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h @@ -26,31 +26,38 @@ * ║║ ╦╠═╣│ │├┬┘│ │├┬┘├─┤╠╣ │ │├┬┘│ ││││ │ │ ││││ * ╚╝╚═╝╩ ╩└─┘┴└─└─┘┴└─┴ ┴╚ └─┘┴└─└─┘┴ ┴o└─┘└─┘┴ ┴ * Pin assignments for 32-bit JGAurora A5S & A1 + * + * https://jgaurorawiki.com/_media/jgaurora_a5s_a1_pinout.png */ -#if NOT_TARGET(__STM32F1__) - #error "Oops! Select an STM32F1 board in 'Tools > Board.'" -#elif HOTENDS > 1 || E_STEPPERS > 1 - #error "JGAurora 32-bit board only supports 1 hotend / E-stepper. Comment out this line to continue." +#include "env_validate.h" + +#if HOTENDS > 1 || E_STEPPERS > 1 + #error "JGAurora A5S A1 only supports one hotend / E-stepper. Comment out this line to continue." #endif -#define BOARD_INFO_NAME "JGAurora A5S A1 board" + +#define BOARD_INFO_NAME "JGAurora A5S A1" + +#define BOARD_NO_NATIVE_USB #ifndef STM32_XL_DENSITY #define STM32_XL_DENSITY #endif //#define MCU_STM32F103ZE // not yet required -// Enable EEPROM Emulation for this board, so that we don't overwrite factory data - -//#define I2C_EEPROM // AT24C64 -//#define MARLIN_EEPROM_SIZE 0x8000UL // 64KB -//#define FLASH_EEPROM_EMULATION -//#define MARLIN_EEPROM_SIZE 0x1000UL // 4KB -//#define MARLIN_EEPROM_SIZE (EEPROM_START_ADDRESS + (EEPROM_PAGE_SIZE) * 2UL) +// Enable EEPROM Emulation for this board, so that we don't overwrite factory data +#if NO_EEPROM_SELECTED + //#define I2C_EEPROM // AT24C64 + //#define FLASH_EEPROM_EMULATION +#endif -//#define EEPROM_CHITCHAT -//#define DEBUG_EEPROM_READWRITE +#if ENABLED(I2C_EEPROM) + //#define MARLIN_EEPROM_SIZE 0x8000UL // 32KB +#elif ENABLED(FLASH_EEPROM_EMULATION) + //#define MARLIN_EEPROM_SIZE 0x1000UL // 4KB + //#define MARLIN_EEPROM_SIZE (EEPROM_START_ADDRESS + (EEPROM_PAGE_SIZE) * 2UL) +#endif // // Limit Switches @@ -102,15 +109,20 @@ #define FIL_RUNOUT_PIN PC7 // -// LCD +// TFT with FSMC interface // -#define LCD_BACKLIGHT_PIN PF11 -#define FSMC_CS_PIN PD7 -#define FSMC_RS_PIN PG0 +#if HAS_FSMC_TFT + #define LCD_BACKLIGHT_PIN PF11 + #define FSMC_CS_PIN PD7 + #define FSMC_RS_PIN PG0 -#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_USE_DMA_FSMC // Use DMA transfers to send data to the TFT + #define FSMC_DMA_DEV DMA2 + #define FSMC_DMA_CHANNEL DMA_CH5 + + #define TFT_CS_PIN FSMC_CS_PIN + #define TFT_RS_PIN FSMC_RS_PIN +#endif // // SD Card @@ -129,4 +141,7 @@ #if NEED_TOUCH_PINS #define TOUCH_CS_PIN PA4 #define TOUCH_INT_PIN PC4 + #define TOUCH_MISO_PIN PA6 + #define TOUCH_MOSI_PIN PA7 + #define TOUCH_SCK_PIN PA5 #endif diff --git a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h index af81bbebe2d4..f9ec42b68efe 100644 --- a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h +++ b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h @@ -25,11 +25,12 @@ #if NOT_TARGET(__STM32F1__, STM32F1xx) #error "Oops! Select a STM32F1 board in 'Tools > Board.'" #elif HOTENDS > 1 || E_STEPPERS > 1 - #error "Longer3D board only supports 1 hotend / E-stepper. Comment out this line to continue." + #error "Longer3D only supports one hotend / E-stepper. Comment out this line to continue." #endif #define BOARD_INFO_NAME "Longer3D" -#define ALFAWISE_UX0 // Common to all Longer3D STM32F1 boards (used for Open drain mosfets) + +#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 @@ -90,10 +91,20 @@ #define FAN_MAX_PWM 255 //#define BEEPER_PIN PD13 // pin 60 (Servo PWM output 5V/GND on Board V0G+) made for BL-Touch sensor - // Can drive a PC Buzzer, if connected between PWM and 5V pins + // Can drive a PC Buzzer, if connected between PWM and 5V pins #define LED_PIN PC2 // pin 17 +// Longer3D board mosfets are passing by default +// Avoid nozzle heat and fan start before serial init +#define BOARD_OPENDRAIN_MOSFETS + +#define BOARD_PREINIT() { \ + OUT_WRITE_OD(HEATER_0_PIN, 0); \ + OUT_WRITE_OD(HEATER_BED_PIN, 0); \ + OUT_WRITE_OD(FAN_PIN, 0); \ +} + // // PWM for a servo probe // Other servo devices are not supported on this board! @@ -106,35 +117,32 @@ //#undef Z_MAX_PIN // Uncomment if using ZMAX connector (PE5) #endif -/** - * Note: Alfawise screens use various TFT controllers. Supported screens - * are based on the ILI9341, ILI9328 and ST7798V. Define init sequences for - * other screens in u8g_dev_tft_320x240_upscale_from_128x64.cpp - * - * If the screen stays white, disable 'LCD_RESET_PIN' to let the bootloader - * init the screen. - * - * Setting an 'LCD_RESET_PIN' may cause a flicker when entering the LCD menu - * because Marlin uses the reset as a failsafe to revive a glitchy LCD. - */ +// +// TFT with FSMC interface +// +#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 TFT_RESET_PIN PC4 // pin 33 -#define TFT_BACKLIGHT_PIN PD12 // pin 59 -#define FSMC_CS_PIN PD7 // pin 88 = FSMC_NE1 -#define FSMC_RS_PIN PD11 // pin 58 A16 Register. Only one address needed + #define TFT_CS_PIN FSMC_CS_PIN + #define TFT_RS_PIN FSMC_RS_PIN -#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 TFT_RESET_PIN PC4 // pin 33 + #define TFT_BACKLIGHT_PIN PD12 // pin 59 -#define DOGLCD_MOSI -1 // Prevent auto-define by Conditionals_post.h -#define DOGLCD_SCK -1 + #define DOGLCD_MOSI -1 // Prevent auto-define by Conditionals_post.h + #define DOGLCD_SCK -1 -// Longer/Alfawise TFT -#define LONGER_LK_TFT28 + // Buffer for Color UI + #define TFT_BUFFER_SIZE 3200 +#endif -// Buffer for Color UI -#define TFT_BUFFER_SIZE 3200 +#if ENABLED(SDIO_SUPPORT) + #define SD_SS_PIN -1 // else SDSS set to PA4 in M43 (spi_pins.h) +#endif /** * Note: Alfawise U20/U30 boards DON'T use SPI2, as the hardware designer @@ -144,7 +152,7 @@ #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 + #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) #endif @@ -155,6 +163,7 @@ // #if NO_EEPROM_SELECTED //#define SPI_EEPROM + //#define HAS_SPI_FLASH 1 // need MARLIN_DEV_MODE for M993/M994 eeprom backup tests #define FLASH_EEPROM_EMULATION #endif @@ -167,6 +176,12 @@ #define EEPROM_MOSI BOARD_SPI1_MOSI_PIN // PA7 pin 32 #define EEPROM_PAGE_SIZE 0x1000U // 4KB (from datasheet) #define MARLIN_EEPROM_SIZE 16UL * (EEPROM_PAGE_SIZE) // Limit to 64KB for now... +#elif HAS_SPI_FLASH + #define SPI_FLASH_SIZE 0x40000U // limit to 256KB (M993 will reboot with 512) + #define W25QXX_CS_PIN PC5 + #define W25QXX_MOSI_PIN PA7 + #define W25QXX_MISO_PIN PA6 + #define W25QXX_SCK_PIN PA5 #elif ENABLED(FLASH_EEPROM_EMULATION) // SoC Flash (framework-arduinoststm32-maple/STM32F1/libraries/EEPROM/EEPROM.h) #define EEPROM_PAGE_SIZE (0x800U) // 2KB diff --git a/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h b/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h index 95e7e92174fa..32d1937653d7 100644 --- a/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h +++ b/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h @@ -41,7 +41,7 @@ #define FLASH_EEPROM_EMULATION #endif -#define SDSS SS_PIN +#define SDSS SD_SS_PIN // Also in HAL/STM32F1/spi_pins.h // Based on PWM timer usage, we have to use these timers and soft PWM for the fans // On STM32F103: @@ -53,9 +53,9 @@ // // Limit Switches // -#define X_MIN_PIN PB4 -#define Y_MIN_PIN PA15 -#define Z_MIN_PIN PB5 +#define X_STOP_PIN PB4 +#define Y_STOP_PIN PA15 +#define Z_STOP_PIN PB5 // // Steppers diff --git a/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h b/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h new file mode 100644 index 000000000000..3fed0adac336 --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h @@ -0,0 +1,173 @@ +/** + * 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 + +/** + * MKS Robin mini (STM32F103VET6) board pin assignments + */ + +#if NOT_TARGET(STM32F1, STM32F1xx) + #error "Oops! Select an STM32F1 board in 'Tools > Board.'" +#elif HOTENDS > 2 || E_STEPPERS > 2 + #error "MKS Robin supports up to 2 hotends / E-steppers. Comment out this line to continue." +#endif + +#define BOARD_INFO_NAME "Mingda MPX_ARM_MINI" + +#define BOARD_NO_NATIVE_USB +#define DISABLE_DEBUG + +// +// EEPROM +// + +/* +//Mingda used an unknown EEPROM chip ATMLH753, so I turned on the emulation below. +//It is connected to EEPROM PB6 PB7 + +#define I2C_EEPROM +#undef NO_EEPROM_SELECTED +#define MARLIN_EEPROM_SIZE 0x1000 // 4KB +#define USE_SHARED_EEPROM 1 // Use Platform-independent Arduino functions for I2C EEPROM +#define E2END 0xFFFF // EEPROM end address AT24C256 (32kB) +*/ + +#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) + #define FLASH_EEPROM_EMULATION + #define EEPROM_PAGE_SIZE 0x800U // 2KB + #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) + #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2KB +#endif + +#define SPI_DEVICE 2 + +// +// Limit Switches +// +#define X_MIN_PIN PD6 +#define X_MAX_PIN PG15 +#define Y_MIN_PIN PG9 +#define Y_MAX_PIN PG14 +#define Z_MIN_PIN PG10 +#define Z_MAX_PIN PG13 + +#ifndef FIL_RUNOUT_PIN + #define FIL_RUNOUT_PIN PG11 +#endif + +// +// Steppers +// +#define X_ENABLE_PIN PD13 +#define X_STEP_PIN PD12 +#define X_DIR_PIN PD11 + +#define Y_ENABLE_PIN PG4 +#define Y_STEP_PIN PG3 +#define Y_DIR_PIN PG2 + +#define Z_ENABLE_PIN PG7 +#define Z_STEP_PIN PG6 +#define Z_DIR_PIN PG5 + +#define E0_ENABLE_PIN PC7 +#define E0_STEP_PIN PC6 +#define E0_DIR_PIN PG8 + +// +// Temperature Sensors +// +//#define TEMP_0_PIN PF6 // THERM_E0 +//#define TEMP_0_PIN PB3 // E0 K+ +#define TEMP_BED_PIN PF7 // THERM_BED + +#define TEMP_0_CS_PIN PB5 +#define TEMP_0_SCK_PIN PB3 +#define TEMP_0_MISO_PIN PB4 +#define TEMP_0_MOSI_PIN PA14 + +// +// Heaters / Fans +// +#define HEATER_0_PIN PB0 +#define HEATER_BED_PIN PB1 + +#define FAN_PIN PA0 // FAN + +// +// SD Card +// +#ifndef SDCARD_CONNECTION + #define SDCARD_CONNECTION ONBOARD +#endif + +#define SDIO_SUPPORT +#define SDIO_CLOCK 4500000 // 4.5 MHz +#define SDIO_READ_RETRIES 16 + +#define SD_DETECT_PIN PC5 +#define ONBOARD_SPI_DEVICE 1 // SPI1 +#define ONBOARD_SD_CS_PIN PC10 + +// +// LCD / Controller +// +#define BEEPER_PIN PE4 + +// +// TFT with FSMC interface +// +#if HAS_FSMC_TFT + /** + * Note: MKS Robin TFT screens use various TFT controllers + * Supported screens are based on the ILI9341, ST7789V and ILI9328 (320x240) + * ILI9488 is not supported + * Define init sequences for other screens in u8g_dev_tft_320x240_upscale_from_128x64.cpp + * + * If the screen stays white, disable 'TFT_RESET_PIN' + * to let the bootloader init the screen. + * + * Setting an 'TFT_RESET_PIN' may cause a flicker when entering the LCD menu + * because Marlin uses the reset as a failsafe to revive a glitchy LCD. + */ + #define TFT_RESET_PIN PF15 + #define TFT_BACKLIGHT_PIN PF11 + + #define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT + #define FSMC_CS_PIN PD7 // NE4 + #define FSMC_RS_PIN PG0 // A0 + #define FSMC_DMA_DEV DMA2 + #define FSMC_DMA_CHANNEL DMA_CH5 + + #define TFT_CS_PIN FSMC_CS_PIN + #define TFT_RS_PIN FSMC_RS_PIN + + #define TOUCH_BUTTONS_HW_SPI + #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 +#endif + +#if NEED_TOUCH_PINS + #define TOUCH_CS_PIN PA4 // SPI2_NSS + #define TOUCH_SCK_PIN PA5 // SPI2_SCK + #define TOUCH_MISO_PIN PA6 // SPI2_MISO + #define TOUCH_MOSI_PIN PA7 // SPI2_MOSI +#endif diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h index 8831d6804b05..4d798ffe282b 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h @@ -22,8 +22,7 @@ #pragma once /** - * MKS Robin (STM32F130ZET6) board pin assignments - * + * MKS Robin (STM32F103ZET6) board pin assignments * https://github.com/makerbase-mks/MKS-Robin/tree/master/MKS%20Robin/Hardware */ @@ -35,21 +34,28 @@ #define BOARD_INFO_NAME "MKS Robin" +#define BOARD_NO_NATIVE_USB + // // Release PB4 (Y_ENABLE_PIN) from JTAG NRST role // #define DISABLE_JTAG // -// Enable SD EEPROM to prevent infinite boot loop +// EEPROM // -#ifdef ARDUINO_ARCH_STM32 - #define FLASH_EEPROM_EMULATION +#if NO_EEPROM_SELECTED + #ifdef ARDUINO_ARCH_STM32 + #define FLASH_EEPROM_EMULATION + #else + #define SDCARD_EEPROM_EMULATION + #endif +#endif + +#if ENABLED(FLASH_EEPROM_EMULATION) #define EEPROM_PAGE_SIZE (0x800U) // 2KB #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) #define MARLIN_EEPROM_SIZE (EEPROM_PAGE_SIZE) -#else - #define SDCARD_EEPROM_EMULATION #endif // @@ -101,31 +107,56 @@ #define TEMP_BED_PIN PC0 // TB1 // -// Heaters / Fans +// Heaters // #define HEATER_0_PIN PC7 // HEATER1 #define HEATER_1_PIN PA6 // HEATER2 #define HEATER_BED_PIN PC6 // HOT BED +// +// Fan +// #define FAN_PIN PA7 // FAN -/** - * Note: MKS Robin board is using SPI2 interface. Make sure your stm32duino library is configured accordingly - */ -//#define MAX6675_SS_PIN PE5 // TC1 - CS1 -//#define MAX6675_SS_PIN PE6 // TC2 - CS2 +// +// Thermocouples +// +//#define TEMP_0_CS_PIN PE5 // TC1 - CS1 +//#define TEMP_0_CS_PIN PE6 // TC2 - CS2 + +// +// Filament runout sensor +// +#define FIL_RUNOUT_PIN PF11 // MT_DET +// +// Power loss detection +// #define POWER_LOSS_PIN PA2 // PW_DET + +// +// Power supply control +// #define PS_ON_PIN PA3 // PW_OFF -#define FIL_RUNOUT_PIN PF11 // MT_DET -#ifdef ARDUINO_ARCH_STM32F1 - #define BEEPER_PIN PC13 -#else - #define BEEPER_PIN -1 -#endif +// +// Piezzoelectric speaker +// +#define BEEPER_PIN PC13 + +// +// Activity LED +// #define LED_PIN PB2 +// +// ESP12-S Wi-Fi module +// +#define WIFI_IO0_PIN PG1 + +// +// TFT with FSMC interface +// #if HAS_FSMC_TFT /** * Note: MKS Robin TFT screens use various TFT controllers @@ -133,27 +164,27 @@ * ILI9488 is not supported * Define init sequences for other screens in u8g_dev_tft_320x240_upscale_from_128x64.cpp * - * If the screen stays white, disable 'LCD_RESET_PIN' + * If the screen stays white, disable 'TFT_RESET_PIN' * to let the bootloader init the screen. * - * Setting an 'LCD_RESET_PIN' may cause a flicker when entering the LCD menu + * Setting an 'TFT_RESET_PIN' may cause a flicker when entering the LCD menu * because Marlin uses the reset as a failsafe to revive a glitchy LCD. */ - //#define LCD_RESET_PIN PF6 - #define LCD_BACKLIGHT_PIN PG11 + #define TFT_RESET_PIN PF6 + #define TFT_BACKLIGHT_PIN PG11 + + #define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT #define FSMC_CS_PIN PG12 // NE4 #define FSMC_RS_PIN PF0 // A0 + #define FSMC_DMA_DEV DMA2 + #define FSMC_DMA_CHANNEL DMA_CH5 + #define TFT_CS_PIN FSMC_CS_PIN #define TFT_RS_PIN FSMC_RS_PIN - #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 -#elif HAS_GRAPHICAL_TFT - #define TFT_RESET_PIN PF6 - #define TFT_BACKLIGHT_PIN PG11 - #define TFT_CS_PIN PG12 // NE4 - #define TFT_RS_PIN PF0 // A0 + #define TOUCH_BUTTONS_HW_SPI + #define TOUCH_BUTTONS_HW_SPI_DEVICE 2 + #define TFT_BUFFER_SIZE 14400 #endif #if NEED_TOUCH_PINS @@ -164,50 +195,88 @@ #define TOUCH_INT_PIN -1 #endif +// SPI2 is shared by LCD touch driver and flash // SPI1(PA7) & SPI3(PB5) not available -#define ENABLE_SPI2 +#define SPI_DEVICE 2 +#define SDIO_SUPPORT +#define SDIO_CLOCK 4500000 +#define SDIO_READ_RETRIES 16 #if ENABLED(SDIO_SUPPORT) - #define SCK_PIN PB13 // SPI2 - #define MISO_PIN PB14 // SPI2 - #define MOSI_PIN PB15 // SPI2 - #define SD_DETECT_PIN PF12 // SD_CD + #define SD_SCK_PIN PB13 // SPI2 + #define SD_MISO_PIN PB14 // SPI2 + #define SD_MOSI_PIN PB15 // SPI2 + /** + * MKS Robin has a few hardware revisions + * https://github.com/makerbase-mks/MKS-Robin/tree/master/MKS%20Robin/Hardware + * + * MKS Robin <= V2.3 have no SD_DETECT_PIN. + * MKS Robin >= V2.4 have SD_DETECT_PIN on PF12. + * + * Uncomment here or add SD_DETECT_PIN to Configuration.h. + */ + //#define SD_DETECT_PIN -1 + //#define SD_DETECT_PIN PF12 // SD_CD #else // SD as custom software SPI (SDIO pins) - #define SCK_PIN PC12 - #define MISO_PIN PC8 - #define MOSI_PIN PD2 - #define SS_PIN -1 + #define SD_SCK_PIN PC12 + #define SD_MISO_PIN PC8 + #define SD_MOSI_PIN PD2 + #define SD_SS_PIN -1 #define ONBOARD_SD_CS_PIN PC11 #define SDSS PD2 #define SD_DETECT_PIN -1 #endif +// +// Trinamic TMC2208/2209 UART +// #if HAS_TMC_UART /** - * TMC2208/TMC2209 stepper drivers + * This board does not have dedicated TMC UART pins. Custom wiring is needed. + * You may uncomment one of the options below, or add it to your Configuration.h. + * + * When using up to four TMC2209 drivers, hardware serial is recommended on + * MSerial0 or MSerial1. * - * Hardware serial communication ports. - * If undefined software serial is used according to the pins below + * When using TMC2208 or more than four drivers, SoftwareSerial will be needed, + * to provide dedicated pins for each drier. */ - //#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 - - // Unused servo pins may be repurposed with SoftwareSerialM - //#define X_SERIAL_TX_PIN PF8 // SERVO3_PIN -- XS2 - 6 - //#define Y_SERIAL_TX_PIN PF9 // SERVO2_PIN -- XS2 - 5 - //#define Z_SERIAL_TX_PIN PA1 // SERVO1_PIN -- XS1 - 6 - //#define E0_SERIAL_TX_PIN PC3 // SERVO0_PIN -- XS1 - 5 - //#define X_SERIAL_RX_PIN X_SERIAL_TX_PIN - //#define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN - //#define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN - //#define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN - - // Reduce baud rate for software serial reliability - #if HAS_TMC_SW_SERIAL + + //#define TMC_HARDWARE_SERIAL + #if ENABLED(TMC_HARDWARE_SERIAL) + #define X_HARDWARE_SERIAL MSerial0 + #define X2_HARDWARE_SERIAL MSerial0 + #define Y_HARDWARE_SERIAL MSerial0 + #define Y2_HARDWARE_SERIAL MSerial0 + #define Z_HARDWARE_SERIAL MSerial0 + #define Z2_HARDWARE_SERIAL MSerial0 + #define E0_HARDWARE_SERIAL MSerial0 + #define E1_HARDWARE_SERIAL MSerial0 + #endif + + //#define TMC_SOFTWARE_SERIAL + #if ENABLED(TMC_SOFTWARE_SERIAL) + #define X_SERIAL_TX_PIN PF8 // SERVO3_PIN -- XS2 - 6 + #define Y_SERIAL_TX_PIN PF9 // SERVO2_PIN -- XS2 - 5 + #define Z_SERIAL_TX_PIN PA1 // SERVO1_PIN -- XS1 - 6 + #define E0_SERIAL_TX_PIN PC3 // SERVO0_PIN -- XS1 - 5 + #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN + #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN + #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN + #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN #define TMC_BAUD_RATE 19200 #endif #endif + +// +// W25Q64 64Mb (8MB) SPI flash +// +#define HAS_SPI_FLASH 1 +#if HAS_SPI_FLASH + #define SPI_FLASH_SIZE 0x800000 // 8MB + #define W25QXX_CS_PIN PG9 + #define W25QXX_MOSI_PIN PB15 + #define W25QXX_MISO_PIN PB14 + #define W25QXX_SCK_PIN PB13 +#endif diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3.h index 2028cd9dd4d0..89ace3493fc2 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3.h @@ -26,7 +26,7 @@ */ #if HOTENDS > 1 || E_STEPPERS > 1 - #error "MKS Robin E3 supports up to 1 hotends / E-steppers. Comment out this line to continue." + #error "MKS Robin E3 only supports one hotend / E-stepper. Comment out this line to continue." #endif #ifndef BOARD_INFO_NAME diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D.h index d1f6dece5c15..a629bce9f38d 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D.h @@ -26,7 +26,7 @@ */ #if HOTENDS > 1 || E_STEPPERS > 1 - #error "MKS Robin E3D supports up to 1 hotends / E-steppers. Comment out this line to continue." + #error "MKS Robin E3D only supports one hotend / E-stepper. Comment out this line to continue." #endif #ifndef BOARD_INFO_NAME 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 new file mode 100644 index 000000000000..0d927cf7cb6a --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D_V1_1.h @@ -0,0 +1,67 @@ +/** + * 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 + +/** + * MKS Robin E3D v1.1 (STM32F103RCT6) board pin assignments + */ + +#if HOTENDS > 1 || E_STEPPERS > 1 + #error "MKS Robin E3D v1.1 only supports one hotend / E-stepper. Comment out this line to continue." +#endif + +#ifndef BOARD_INFO_NAME + #define BOARD_INFO_NAME "MKS Robin E3D V1.1" +#endif + +// +// Steppers +// +#ifndef X_CS_PIN + #define X_CS_PIN PC7 +#endif +#ifndef Y_CS_PIN + #define Y_CS_PIN PD2 +#endif +#ifndef Z_CS_PIN + #define Z_CS_PIN PC12 +#endif +#ifndef E0_CS_PIN + #define E0_CS_PIN PC11 +#endif + +// +// Software 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 +#endif + +#include "pins_MKS_ROBIN_E3_V1_1_common.h" diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h index 94a28953ccf3..2fc99f297104 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h @@ -22,23 +22,28 @@ #pragma once /** - * MKS Robin nano (STM32F130VET6) board pin assignments + * MKS Robin nano (STM32F103VET6) board pin assignments */ -#if NOT_TARGET(__STM32F1__) - #error "Oops! Select an STM32F1 board in 'Tools > Board.'" -#elif HOTENDS > 1 || E_STEPPERS > 1 - #error "MKS Robin e3p supports up to 1 hotends / E-steppers. Comment out this line to continue." +#include "env_validate.h" + +#if HOTENDS > 1 || E_STEPPERS > 1 + #error "MKS Robin E3P only supports one hotend / E-stepper. Comment out this line to continue." #elif HAS_FSMC_TFT - #error "MKS Robin e3p doesn't support FSMC-based TFT displays." + #error "MKS Robin E3P doesn't support FSMC-based TFT displays." #endif -#define BOARD_INFO_NAME "MKS Robin e3p" +#define BOARD_INFO_NAME "MKS Robin E3P" + +#define BOARD_NO_NATIVE_USB +#define MKS_HARDWARE_TEST_ONLY_E0 + +// 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 // @@ -55,8 +60,12 @@ // // Note: MKS Robin board is using SPI2 interface. // -//#define SPI_MODULE 2 -#define ENABLE_SPI2 +#define SPI_DEVICE 2 + +// +// Servos +// +#define SERVO0_PIN PA8 // Enable BLTOUCH // // Limit Switches @@ -154,7 +163,7 @@ // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 -#endif // TMC2208 || TMC2209 +#endif // HAS_TMC_UART // // Temperature Sensors @@ -174,12 +183,11 @@ // Misc. Functions // #if HAS_TFT_LVGL_UI - //#define MKSPWC - #ifdef MKSPWC - #define SUICIDE_PIN PB2 // Enable MKSPWC SUICIDE PIN - #define SUICIDE_PIN_INVERTING false // Enable MKSPWC PIN STATE - #define KILL_PIN PA2 // Enable MKSPWC DET PIN - #define KILL_PIN_STATE true // Enable MKSPWC PIN STATE + #if ENABLED(PSU_CONTROL) // MKSPWC + #define SUICIDE_PIN PB2 // PW_OFF + #define SUICIDE_PIN_INVERTING false + #define KILL_PIN PA2 // PW_DET + #define KILL_PIN_STATE HIGH #endif #define MT_DET_1_PIN PA4 // LVGL UI FILAMENT RUNOUT1 PIN @@ -199,8 +207,6 @@ #define FIL_RUNOUT_PIN PA4 #endif -#define SERVO0_PIN PA8 // Enable BLTOUCH - //#define LED_PIN PB2 // @@ -210,17 +216,23 @@ #define SDCARD_CONNECTION ONBOARD #endif -#define SDIO_SUPPORT -#define SDIO_CLOCK 4500000 // 4.5 MHz -#define SD_DETECT_PIN PD12 -#define ONBOARD_SD_CS_PIN PC11 +#if SD_CONNECTION_IS(ONBOARD) + #define SDIO_SUPPORT + #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 +#endif // // LCD / Controller // -#ifndef BEEPER_PIN - #define BEEPER_PIN PC5 -#endif /** * Note: MKS Robin TFT screens use various TFT controllers. @@ -257,71 +269,29 @@ #define TOUCH_BUTTONS_HW_SPI #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 - #ifndef TFT_WIDTH - #define TFT_WIDTH 480 - #endif - #ifndef TFT_HEIGHT - #define TFT_HEIGHT 320 - #endif - - #define LCD_READ_ID 0xD3 #define LCD_USE_DMA_SPI #endif -#if ENABLED(SPI_GRAPHICAL_TFT) +#if ENABLED(TFT_CLASSIC_UI) // Emulated DOGM SPI - #ifndef GRAPHICAL_TFT_UPSCALE - #define GRAPHICAL_TFT_UPSCALE 3 - #endif - #ifndef TFT_PIXEL_OFFSET_Y - #define TFT_PIXEL_OFFSET_Y 32 - #endif - + #define LCD_PINS_ENABLE PD13 + #define LCD_PINS_RS PC6 #define BTN_ENC PE13 #define BTN_EN1 PE8 #define BTN_EN2 PE11 - - #define LCD_PINS_ENABLE PD13 - #define LCD_PINS_RS PC6 - -#elif ENABLED(TFT_480x320_SPI) - #define TFT_DRIVER ST7796 +#elif ENABLED(TFT_COLOR_UI) #define TFT_BUFFER_SIZE 14400 #endif -// XPT2046 Touch Screen calibration -#if EITHER(HAS_TFT_LVGL_UI, TFT_480x320_SPI) - #ifndef XPT2046_X_CALIBRATION - #define XPT2046_X_CALIBRATION -17253 - #endif - #ifndef XPT2046_Y_CALIBRATION - #define XPT2046_Y_CALIBRATION 11579 - #endif - #ifndef XPT2046_X_OFFSET - #define XPT2046_X_OFFSET 514 - #endif - #ifndef XPT2046_Y_OFFSET - #define XPT2046_Y_OFFSET -24 - #endif -#elif ENABLED(SPI_GRAPHICAL_TFT) - #ifndef XPT2046_X_CALIBRATION - #define XPT2046_X_CALIBRATION -11386 - #endif - #ifndef XPT2046_Y_CALIBRATION - #define XPT2046_Y_CALIBRATION 8684 - #endif - #ifndef XPT2046_X_OFFSET - #define XPT2046_X_OFFSET 339 - #endif - #ifndef XPT2046_Y_OFFSET - #define XPT2046_Y_OFFSET -18 - #endif -#endif - #if HAS_WIRED_LCD && !HAS_SPI_TFT - - // NON TFT Displays + #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 #if ENABLED(MKS_MINI_12864) @@ -335,17 +305,45 @@ #define DOGLCD_SCK PA5 #define DOGLCD_MOSI PA7 - // Required for MKS_MINI_12864 with this board - #define MKS_LCD12864B - #undef SHOW_BOOTSCREEN + #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 + #endif + + #ifndef BEEPER_PIN + #define BEEPER_PIN -1 + #endif + + #elif ENABLED(MKS_MINI_12864_V3) + #define DOGLCD_CS PD13 + #define DOGLCD_A0 PC6 + #define LCD_PINS_DC DOGLCD_A0 + #define LCD_BACKLIGHT_PIN -1 + #define LCD_RESET_PIN PE14 + #define NEOPIXEL_PIN PE15 + #define DOGLCD_MOSI PA7 + #define DOGLCD_SCK PA5 + #if SD_CONNECTION_IS(ONBOARD) + #define FORCE_SOFT_SPI + #endif + //#define LCD_SCREEN_ROT_180 #else // !MKS_MINI_12864 #define LCD_PINS_D4 PE14 - #if ENABLED(ULTIPANEL) + #if IS_ULTIPANEL #define LCD_PINS_D5 PE15 #define LCD_PINS_D6 PD11 #define LCD_PINS_D7 PD10 + + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif + #endif #ifndef BOARD_ST7920_DELAY_1 @@ -371,6 +369,10 @@ #define W25QXX_SCK_PIN PB13 #endif +#ifndef BEEPER_PIN + #define BEEPER_PIN PC5 +#endif + #if ENABLED(SPEAKER) && BEEPER_PIN == PC5 #error "MKS Robin nano default BEEPER_PIN is not a SPEAKER." #endif diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_V1_1.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_V1_1.h new file mode 100644 index 000000000000..002c35fe54c1 --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_V1_1.h @@ -0,0 +1,36 @@ +/** + * 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 + +/** + * MKS Robin E3 v1.1 (STM32F103RCT6) board pin assignments + */ + +#if HOTENDS > 1 || E_STEPPERS > 1 + #error "MKS Robin E3 v1.1 only supports one hotend / E-stepper. Comment out this line to continue." +#endif + +#ifndef BOARD_INFO_NAME + #define BOARD_INFO_NAME "MKS Robin E3 V1.1" +#endif + +#include "pins_MKS_ROBIN_E3_V1_1_common.h" 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 new file mode 100644 index 000000000000..4eaf2e946939 --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_V1_1_common.h @@ -0,0 +1,39 @@ +/** + * 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 + +// +// EEPROM +// +// Onboard I2C EEPROM +#if NO_EEPROM_SELECTED + #define I2C_EEPROM + #define MARLIN_EEPROM_SIZE 0x1000// 4KB + #undef NO_EEPROM_SELECTED +#endif + +#define Z_STEP_PIN PC14 +#define Z_DIR_PIN PC15 + +#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 015e29bdbe60..da7ba05795a9 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h @@ -25,9 +25,9 @@ * MKS Robin E3 & E3D (STM32F103RCT6) common board pin assignments */ -#if NOT_TARGET(__STM32F1__) - #error "Oops! Select an STM32F1 board in 'Tools > Board.'" -#endif +#include "env_validate.h" + +#define BOARD_NO_NATIVE_USB #define BOARD_WEBSITE_URL "github.com/makerbase-mks" @@ -68,15 +68,19 @@ #define Y_DIR_PIN PB9 #define Y_ENABLE_PIN PB12 -#define Z_STEP_PIN PB7 -#define Z_DIR_PIN PB6 +#ifndef Z_STEP_PIN + #define Z_STEP_PIN PB7 +#endif +#ifndef Z_DIR_PIN + #define Z_DIR_PIN PB6 +#endif #define Z_ENABLE_PIN PB8 #define E0_STEP_PIN PB4 #define E0_DIR_PIN PB3 #define E0_ENABLE_PIN PB5 -#if HAS_TMC220x +#if HAS_TMC_UART /** * TMC2208/TMC2209 stepper drivers * @@ -122,6 +126,19 @@ #define FIL_RUNOUT_PIN PB10 // MT_DET +// +// Power Supply Control +// +#if ENABLED(PSU_CONTROL) // MKSPWC + #ifndef PS_ON_PIN + #define PS_ON_PIN PA14 // PW_OFF + #endif + #ifndef KILL_PIN + #define KILL_PIN PB10 // PW_DET + #define KILL_PIN_STATE HIGH + #endif +#endif + /** * _____ _____ _____ * (BEEPER) PC1 | 1 2 | PC3 (BTN_ENC) (MISO) PB14 | 1 2 | PB13 (SD_SCK) 5V | 1 2 | GND @@ -151,13 +168,31 @@ #define DOGLCD_SCK PB13 #define DOGLCD_MOSI PB15 + #elif ENABLED(MKS_MINI_12864_V3) + #define DOGLCD_CS PA4 + #define DOGLCD_A0 PA5 + #define LCD_PINS_DC DOGLCD_A0 + #define LCD_BACKLIGHT_PIN -1 + #define LCD_RESET_PIN PA6 + #define NEOPIXEL_PIN PA7 + #define DOGLCD_MOSI PB15 + #define DOGLCD_SCK PB13 + #define FORCE_SOFT_SPI + #define SOFTWARE_SPI + //#define LCD_SCREEN_ROT_180 + #else #define LCD_PINS_D4 PA6 - #if ENABLED(ULTIPANEL) + #if IS_ULTIPANEL #define LCD_PINS_D5 PA7 #define LCD_PINS_D6 PC4 #define LCD_PINS_D7 PC5 + + #if !defined(BTN_ENC_EN) && ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif + #endif #endif // !MKS_MINI_12864 @@ -167,12 +202,20 @@ // // SD Card // -#define ENABLE_SPI2 +#define SPI_DEVICE 2 +#define ONBOARD_SPI_DEVICE 2 +#define SDSS SD_SS_PIN +#define SDCARD_CONNECTION ONBOARD #define SD_DETECT_PIN PC10 -#define SCK_PIN PB13 -#define MISO_PIN PB14 -#define MOSI_PIN PB15 -#define SS_PIN PA15 +#define ONBOARD_SD_CS_PIN SD_SS_PIN +#define NO_SD_HOST_DRIVE + +// TODO: This is the only way to set SPI for SD on STM32 (for now) +#define ENABLE_SPI2 +#define SD_SCK_PIN PB13 +#define SD_MISO_PIN PB14 +#define SD_MOSI_PIN PB15 +#define SD_SS_PIN PA15 #ifndef BOARD_ST7920_DELAY_1 #define BOARD_ST7920_DELAY_1 DELAY_NS(125) diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h index aa1ccedb3550..73c77d092a0e 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h @@ -21,10 +21,10 @@ */ #pragma once -#if NOT_TARGET(__STM32F1__) - #error "Oops! Select an STM32F1 board in 'Tools > Board.'" -#elif HOTENDS > 1 || E_STEPPERS > 1 - #error "MKS Robin Lite supports only 1 hotend / E-stepper. Comment out this line to continue." +#include "env_validate.h" + +#if HOTENDS > 1 || E_STEPPERS > 1 + #error "MKS Robin Lite only supports one hotend / E-stepper. Comment out this line to continue." #endif #ifndef BOARD_INFO_NAME @@ -32,9 +32,10 @@ #endif #define BOARD_WEBSITE_URL "github.com/makerbase-mks" +#define BOARD_NO_NATIVE_USB + //#define DISABLE_DEBUG #define DISABLE_JTAG -#define ENABLE_SPI2 // // Limit Switches @@ -103,7 +104,7 @@ #else // !MKS_MINI_12864 #define LCD_PINS_D4 PC1 - #if ENABLED(ULTIPANEL) + #if IS_ULTIPANEL #define LCD_PINS_D5 -1 #define LCD_PINS_D6 -1 #define LCD_PINS_D7 -1 @@ -135,9 +136,13 @@ // // SD Card // -#define ENABLE_SPI2 #define SD_DETECT_PIN PC10 -#define SCK_PIN PB13 -#define MISO_PIN P1B4 -#define MOSI_PIN P1B5 -#define SS_PIN PA15 + +// +// SPI +// +#define SPI_DEVICE 2 +#define SD_SCK_PIN PB13 +#define SD_MISO_PIN PB14 +#define SD_MOSI_PIN PB15 +#define SD_SS_PIN PA15 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE3.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE3.h index d5318b8e8787..73fefddf8fbc 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE3.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE3.h @@ -25,9 +25,9 @@ * MKS Robin Lite 3 (STM32F103RCT6) board pin assignments */ -#if NOT_TARGET(__STM32F1__) - #error "Oops! Select an STM32F1 board in 'Tools > Board.'" -#elif HOTENDS > 2 || E_STEPPERS > 2 +#include "env_validate.h" + +#if HOTENDS > 2 || E_STEPPERS > 2 #error "MKS Robin Lite3 supports up to 2 hotends / E-steppers. Comment out this line to continue." #endif @@ -36,9 +36,10 @@ #endif #define BOARD_WEBSITE_URL "github.com/makerbase-mks" +#define BOARD_NO_NATIVE_USB + //#define DISABLE_DEBUG #define DISABLE_JTAG -#define ENABLE_SPI2 // // Servos @@ -87,9 +88,9 @@ // // Temperature Sensors // -#define TEMP_BED_PIN PA1 //TB -#define TEMP_0_PIN PA0 //TH1 -#define TEMP_1_PIN PA2 //TH2 +#define TEMP_BED_PIN PA1 // TB +#define TEMP_0_PIN PA0 // TH1 +#define TEMP_1_PIN PA2 // TH2 #define FIL_RUNOUT_PIN PB10 // MT_DET @@ -124,32 +125,35 @@ #else // !MKS_MINI_12864 #define LCD_PINS_D4 PA6 - #if ENABLED(ULTIPANEL) + #if IS_ULTIPANEL #define LCD_PINS_D5 PA7 #define LCD_PINS_D6 PC4 #define LCD_PINS_D7 PC5 + + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif + #endif #endif // !MKS_MINI_12864 + #define BOARD_ST7920_DELAY_1 DELAY_NS(125) + #define BOARD_ST7920_DELAY_2 DELAY_NS(125) + #define BOARD_ST7920_DELAY_3 DELAY_NS(125) + #endif // HAS_WIRED_LCD // // SD Card // -#define ENABLE_SPI2 #define SD_DETECT_PIN PC10 -#define SCK_PIN PB13 -#define MISO_PIN PB14 -#define MOSI_PIN PB15 -#define SS_PIN PA15 -#ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(125) -#endif -#ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(125) -#endif -#ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(125) -#endif +// +// SPI +// +#define SPI_DEVICE 2 +#define SD_SCK_PIN PB13 +#define SD_MISO_PIN PB14 +#define SD_MOSI_PIN PB15 +#define SD_SS_PIN PA15 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h index 2b099b3e9372..d4a2f59b4256 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h @@ -22,17 +22,19 @@ #pragma once /** - * MKS Robin mini (STM32F130VET6) board pin assignments + * MKS Robin mini (STM32F103VET6) board pin assignments */ -#if NOT_TARGET(__STM32F1__) - #error "Oops! Select an STM32F1 board in 'Tools > Board.'" -#elif HOTENDS > 1 || E_STEPPERS > 1 - #error "MKS Robin mini only supports 1 hotend / E-stepper. Comment out this line to continue." +#include "env_validate.h" + +#if HOTENDS > 1 || E_STEPPERS > 1 + #error "MKS Robin mini only supports one hotend / E-stepper. Comment out this line to continue." #endif #define BOARD_INFO_NAME "MKS Robin Mini" +#define BOARD_NO_NATIVE_USB + // // Release PB4 (Y_ENABLE_PIN) from JTAG NRST role // @@ -48,7 +50,14 @@ #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2KB #endif -#define ENABLE_SPI2 +#define SPI_DEVICE 2 + +// +// Servos +// +#ifndef SERVO0_PIN + #define SERVO0_PIN PA8 // Enable BLTOUCH support on IO0 (WIFI connector) +#endif // // Limit Switches @@ -89,6 +98,7 @@ #ifndef DEFAULT_PWM_MOTOR_CURRENT #define DEFAULT_PWM_MOTOR_CURRENT { 800, 800, 800 } #endif + // // Temperature Sensors // @@ -109,8 +119,6 @@ #define POWER_LOSS_PIN PA2 // PW_DET #define PS_ON_PIN PA3 // PW_OFF -#define SERVO0_PIN PA8 // Enable BLTOUCH support on IO0 (WIFI connector) - #define MT_DET_1_PIN PA4 #define MT_DET_PIN_INVERTING false @@ -139,23 +147,7 @@ * If the screen stays white, disable 'LCD_RESET_PIN' * to let the bootloader init the screen. */ -#if ENABLED(TOUCH_SCREEN) - #ifndef XPT2046_X_CALIBRATION - #define XPT2046_X_CALIBRATION 12033 - #endif - #ifndef XPT2046_Y_CALIBRATION - #define XPT2046_Y_CALIBRATION -9047 - #endif - #ifndef XPT2046_X_OFFSET - #define XPT2046_X_OFFSET -30 - #endif - #ifndef XPT2046_Y_OFFSET - #define XPT2046_Y_OFFSET 254 - #endif -#endif - -#if ENABLED(FSMC_GRAPHICAL_TFT) - +#if EITHER(HAS_FSMC_GRAPHICAL_TFT, TFT_320x240) #define FSMC_CS_PIN PD7 // NE4 #define FSMC_RS_PIN PD11 // A0 @@ -165,39 +157,38 @@ #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 - -#elif ENABLED(TFT_320x240) //TFT32/28 - - #define TFT_RESET_PIN PC6 - #define TFT_BACKLIGHT_PIN PD13 - - #define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT - #define FSMC_CS_PIN PD7 - #define FSMC_RS_PIN PD11 - #define FSMC_DMA_DEV DMA2 - #define FSMC_DMA_CHANNEL DMA_CH5 - +#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 ILI9341_COLOR_RGB // YV for normal screen mounting #define ILI9341_ORIENTATION ILI9341_MADCTL_MY | ILI9341_MADCTL_MV // XV for 180° rotated screen mounting //#define ILI9341_ORIENTATION ILI9341_MADCTL_MX | ILI9341_MADCTL_MV +#endif - #define ILI9341_COLOR_RGB +#if ENABLED(TOUCH_SCREEN) + #ifndef TOUCH_CALIBRATION_X + #define TOUCH_CALIBRATION_X 12033 + #endif + #ifndef TOUCH_CALIBRATION_Y + #define TOUCH_CALIBRATION_Y -9047 + #endif + #ifndef TOUCH_OFFSET_X + #define TOUCH_OFFSET_X -30 + #endif + #ifndef TOUCH_OFFSET_Y + #define TOUCH_OFFSET_Y 254 + #endif #endif #define HAS_SPI_FLASH 1 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h index 16d6d2ffc442..2a5c9f727372 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h @@ -22,7 +22,8 @@ #pragma once /** - * MKS Robin nano (STM32F130VET6) board pin assignments + * MKS Robin nano (STM32F103VET6) board pin assignments + * https://github.com/makerbase-mks/MKS-Robin-Nano-V1.X/tree/master/hardware */ #if NOT_TARGET(STM32F1, STM32F1xx) @@ -33,6 +34,11 @@ #define BOARD_INFO_NAME "MKS Robin Nano" +#define BOARD_NO_NATIVE_USB + +// Avoid conflict with TIMER_SERVO when using the STM32 HAL +#define TEMP_TIMER 5 + // // Release PB4 (Y_ENABLE_PIN) from JTAG NRST role // @@ -48,7 +54,12 @@ #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2KB #endif -#define ENABLE_SPI2 +#define SPI_DEVICE 2 + +// +// Servos +// +#define SERVO0_PIN PA8 // Enable BLTOUCH // // Limit Switches @@ -94,7 +105,7 @@ #ifndef HEATER_0_PIN #define HEATER_0_PIN PC3 #endif -#if HOTENDS == 1 +#if HOTENDS == 1 && DISABLED(HEATERS_PARALLEL) #ifndef FAN1_PIN #define FAN1_PIN PB0 #endif @@ -113,21 +124,32 @@ // // Thermocouples // -//#define MAX6675_SS_PIN PE5 // TC1 - CS1 -//#define MAX6675_SS_PIN PE6 // TC2 - CS2 +//#define TEMP_0_CS_PIN PE5 // TC1 - CS1 +//#define TEMP_0_CS_PIN PE6 // TC2 - CS2 // -// Misc. Functions +// Power Supply Control // -#if HAS_TFT_LVGL_UI - //#define MKSPWC - #ifdef MKSPWC - #define SUICIDE_PIN PB2 // Enable MKSPWC SUICIDE PIN - #define SUICIDE_PIN_INVERTING false // Enable MKSPWC PIN STATE - #define KILL_PIN PA2 // Enable MKSPWC DET PIN - #define KILL_PIN_STATE true // Enable MKSPWC PIN STATE +#if ENABLED(PSU_CONTROL) // MKSPWC + #if HAS_TFT_LVGL_UI + #error "PSU_CONTROL cannot be used with TFT_LVGL_UI. Disable PSU_CONTROL to continue." + #endif + #ifndef PS_ON_PIN + #define PS_ON_PIN PB2 // SUICIDE + #endif + #ifndef KILL_PIN + #define KILL_PIN PA2 + #define KILL_PIN_STATE HIGH #endif +#else + #define SUICIDE_PIN PB2 + #define SUICIDE_PIN_INVERTING false +#endif +// +// Misc. Functions +// +#if HAS_TFT_LVGL_UI #define MT_DET_1_PIN PA4 // LVGL UI FILAMENT RUNOUT1 PIN #define MT_DET_2_PIN PE6 // LVGL UI FILAMENT RUNOUT2 PIN #define MT_DET_PIN_INVERTING false // LVGL UI filament RUNOUT PIN STATE @@ -142,8 +164,6 @@ #define FIL_RUNOUT2_PIN PE6 #endif -#define SERVO0_PIN PA8 // Enable BLTOUCH support - //#define LED_PIN PB2 // @@ -163,82 +183,41 @@ // #define BEEPER_PIN PC5 -/** - * Note: MKS Robin TFT screens use various TFT controllers. - * If the screen stays white, disable 'LCD_RESET_PIN' - * to let the bootloader init the screen. - */ - -// Shared FSMC Configs +// +// TFT with FSMC interface +// #if HAS_FSMC_TFT - #define DOGLCD_MOSI -1 // prevent redefine Conditionals_post.h - #define DOGLCD_SCK -1 + /** + * Note: MKS Robin TFT screens use various TFT controllers. + * If the screen stays white, disable 'TFT_RESET_PIN' + * to let the bootloader init the screen. + */ + #define TFT_RESET_PIN PC6 // FSMC_RST + #define TFT_BACKLIGHT_PIN PD13 - #define FSMC_CS_PIN PD7 // NE4 - #define FSMC_RS_PIN PD11 // A0 + #define DOGLCD_MOSI -1 // Prevent auto-define by Conditionals_post.h + #define DOGLCD_SCK -1 #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 TFT_RESET_PIN PC6 // FSMC_RST - #define TFT_BACKLIGHT_PIN PD13 - #define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT #define FSMC_CS_PIN PD7 #define FSMC_RS_PIN PD11 #define FSMC_DMA_DEV DMA2 #define FSMC_DMA_CHANNEL DMA_CH5 + #define TFT_CS_PIN FSMC_CS_PIN + #define TFT_RS_PIN FSMC_RS_PIN + #define TOUCH_BUTTONS_HW_SPI #define TOUCH_BUTTONS_HW_SPI_DEVICE 2 #define TFT_BUFFER_SIZE 14400 #endif -// XPT2046 Touch Screen calibration -#if EITHER(TFT_LVGL_UI_FSMC, TFT_480x320) - #ifndef XPT2046_X_CALIBRATION - #define XPT2046_X_CALIBRATION 17880 - #endif - #ifndef XPT2046_Y_CALIBRATION - #define XPT2046_Y_CALIBRATION -12234 - #endif - #ifndef XPT2046_X_OFFSET - #define XPT2046_X_OFFSET -45 - #endif - #ifndef XPT2046_Y_OFFSET - #define XPT2046_Y_OFFSET 349 - #endif -#elif ENABLED(TFT_CLASSIC_UI) - #ifndef XPT2046_X_CALIBRATION - #define XPT2046_X_CALIBRATION 12149 - #endif - #ifndef XPT2046_Y_CALIBRATION - #define XPT2046_Y_CALIBRATION -8746 - #endif - #ifndef XPT2046_X_OFFSET - #define XPT2046_X_OFFSET -35 - #endif - #ifndef XPT2046_Y_OFFSET - #define XPT2046_Y_OFFSET 256 - #endif -#elif ENABLED(TFT_320x240) - #ifndef XPT2046_X_CALIBRATION - #define XPT2046_X_CALIBRATION -12246 - #endif - #ifndef XPT2046_Y_CALIBRATION - #define XPT2046_Y_CALIBRATION 9453 - #endif - #ifndef XPT2046_X_OFFSET - #define XPT2046_X_OFFSET 360 - #endif - #ifndef XPT2046_Y_OFFSET - #define XPT2046_Y_OFFSET -22 - #endif -#endif - #define HAS_SPI_FLASH 1 #if HAS_SPI_FLASH #define SPI_FLASH_SIZE 0x1000000 // 16MB 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 846fe80a08fa..31ce016e67a1 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h @@ -22,10 +22,10 @@ #pragma once /** - * MKS Robin nano (STM32F130VET6) board pin assignments + * MKS Robin nano (STM32F103VET6) board pin assignments */ -#if NOT_TARGET(__STM32F1__) +#if NOT_TARGET(__STM32F1__, STM32F1) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #elif HOTENDS > 2 || E_STEPPERS > 2 #error "MKS Robin nano supports up to 2 hotends / E-steppers. Comment out this line to continue." @@ -35,10 +35,14 @@ #define BOARD_INFO_NAME "MKS Robin nano V2.0" +#define BOARD_NO_NATIVE_USB + +// 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 // @@ -55,8 +59,12 @@ // // Note: MKS Robin board is using SPI2 interface. // -//#define SPI_MODULE 2 -#define ENABLE_SPI2 +#define SPI_DEVICE 2 + +// +// Servos +// +#define SERVO0_PIN PA8 // Enable BLTOUCH // // Limit Switches @@ -159,7 +167,7 @@ // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 -#endif // TMC2208 || TMC2209 +#endif // HAS_TMC_UART // // Temperature Sensors @@ -180,20 +188,32 @@ // // Thermocouples // -//#define MAX6675_SS_PIN PE5 // TC1 - CS1 -//#define MAX6675_SS_PIN PE6 // TC2 - CS2 +//#define TEMP_0_CS_PIN PE5 // TC1 - CS1 +//#define TEMP_0_CS_PIN PE6 // TC2 - CS2 + +// +// Power Supply Control +// +#if ENABLED(PSU_CONTROL) // MKSPWC + #if HAS_TFT_LVGL_UI + #error "PSU_CONTROL cannot be used with TFT_LVGL_UI. Disable PSU_CONTROL to continue." + #endif + #ifndef PS_ON_PIN + #define PS_ON_PIN PB2 // SUICIDE + #endif + #ifndef KILL_PIN + #define KILL_PIN PA2 + #define KILL_PIN_STATE HIGH + #endif +#else + #define SUICIDE_PIN PB2 + #define SUICIDE_PIN_INVERTING false +#endif // // Misc. Functions // #if HAS_TFT_LVGL_UI - //#define MKSPWC - #ifdef MKSPWC - #define SUICIDE_PIN PB2 // Enable MKSPWC SUICIDE PIN - #define SUICIDE_PIN_INVERTING false // Enable MKSPWC PIN STATE - #define KILL_PIN PA2 // Enable MKSPWC DET PIN - #define KILL_PIN_STATE true // Enable MKSPWC PIN STATE - #endif #define MT_DET_1_PIN PA4 // LVGL UI FILAMENT RUNOUT1 PIN #define MT_DET_2_PIN PE6 // LVGL UI FILAMENT RUNOUT2 PIN @@ -214,8 +234,6 @@ #define FIL_RUNOUT2_PIN PE6 #endif -#define SERVO0_PIN PA8 // Enable BLTOUCH - //#define LED_PIN PB2 // @@ -225,10 +243,19 @@ #define SDCARD_CONNECTION ONBOARD #endif -#define SDIO_SUPPORT -#define SDIO_CLOCK 4500000 // 4.5 MHz -#define SD_DETECT_PIN PD12 -#define ONBOARD_SD_CS_PIN PC11 +#if SD_CONNECTION_IS(ONBOARD) + #define SDIO_SUPPORT + #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 +#endif // // LCD / Controller @@ -275,56 +302,23 @@ #if ENABLED(TFT_CLASSIC_UI) // Emulated DOGM SPI - #ifndef GRAPHICAL_TFT_UPSCALE - #define GRAPHICAL_TFT_UPSCALE 3 - #endif - #ifndef TFT_PIXEL_OFFSET_Y - #define TFT_PIXEL_OFFSET_Y 32 - #endif - + #define LCD_PINS_ENABLE PD13 + #define LCD_PINS_RS PC6 #define BTN_ENC PE13 #define BTN_EN1 PE8 #define BTN_EN2 PE11 - - #define LCD_PINS_ENABLE PD13 - #define LCD_PINS_RS PC6 - #elif ENABLED(TFT_COLOR_UI) #define TFT_BUFFER_SIZE 14400 #endif -// XPT2046 Touch Screen calibration -#if EITHER(TFT_LVGL_UI, TFT_COLOR_UI) - #ifndef XPT2046_X_CALIBRATION - #define XPT2046_X_CALIBRATION -17253 - #endif - #ifndef XPT2046_Y_CALIBRATION - #define XPT2046_Y_CALIBRATION 11579 - #endif - #ifndef XPT2046_X_OFFSET - #define XPT2046_X_OFFSET 514 - #endif - #ifndef XPT2046_Y_OFFSET - #define XPT2046_Y_OFFSET -24 - #endif -#elif ENABLED(TFT_CLASSIC_UI) - #ifndef XPT2046_X_CALIBRATION - #define XPT2046_X_CALIBRATION -11386 - #endif - #ifndef XPT2046_Y_CALIBRATION - #define XPT2046_Y_CALIBRATION 8684 - #endif - #ifndef XPT2046_X_OFFSET - #define XPT2046_X_OFFSET 339 - #endif - #ifndef XPT2046_Y_OFFSET - #define XPT2046_Y_OFFSET -18 - #endif -#endif - #if HAS_WIRED_LCD && !HAS_SPI_TFT - - // NON TFT Displays + #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 #if ENABLED(MKS_MINI_12864) @@ -351,13 +345,32 @@ #define BEEPER_PIN -1 #endif + #elif ENABLED(MKS_MINI_12864_V3) + #define DOGLCD_CS PD13 + #define DOGLCD_A0 PC6 + #define LCD_PINS_DC DOGLCD_A0 + #define LCD_BACKLIGHT_PIN -1 + #define LCD_RESET_PIN PE14 + #define NEOPIXEL_PIN PE15 + #define DOGLCD_MOSI PA7 + #define DOGLCD_SCK PA5 + #if SD_CONNECTION_IS(ONBOARD) + #define FORCE_SOFT_SPI + #endif + //#define LCD_SCREEN_ROT_180 + #else // !MKS_MINI_12864 #define LCD_PINS_D4 PE14 - #if ENABLED(ULTIPANEL) + #if IS_ULTIPANEL #define LCD_PINS_D5 PE15 #define LCD_PINS_D6 PD11 #define LCD_PINS_D7 PD10 + + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif + #endif #ifndef BOARD_ST7920_DELAY_1 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h index 32203f52ea8d..2f62563edbee 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h @@ -25,14 +25,16 @@ * MKS Robin pro (STM32F103ZET6) board pin assignments */ -#if NOT_TARGET(__STM32F1__) - #error "Oops! Select an STM32F1 board in 'Tools > Board.'" -#elif HOTENDS > 3 || E_STEPPERS > 3 +#include "env_validate.h" + +#if HOTENDS > 3 || E_STEPPERS > 3 #error "MKS Robin pro supports up to 3 hotends / E-steppers. Comment out this line to continue." #endif #define BOARD_INFO_NAME "MKS Robin pro" +#define BOARD_NO_NATIVE_USB + // // Release PB4 (Y_ENABLE_PIN) from JTAG NRST role // @@ -41,13 +43,12 @@ // // Note: MKS Robin board is using SPI2 interface. // -//#define SPI_MODULE 2 -#define ENABLE_SPI2 +#define SPI_DEVICE 2 // // Servos // -#define SERVO0_PIN PA8 // BLTOUCH +#define SERVO0_PIN PA8 // Enable BLTOUCH // // Limit Switches @@ -174,14 +175,32 @@ /** * Note: MKS Robin Pro board is using SPI2 interface. Make sure your stm32duino library is configured accordingly */ -//#define MAX6675_SS_PIN PE5 // TC1 - CS1 -//#define MAX6675_SS_PIN PF11 // TC2 - CS2 +//#define TEMP_0_CS_PIN PE5 // TC1 - CS1 +//#define TEMP_0_CS_PIN PF11 // TC2 - CS2 #define POWER_LOSS_PIN PA2 // PW_DET -#define PS_ON_PIN PG11 // PW_OFF #define FIL_RUNOUT_PIN PA4 // MT_DET1 -//#define FIL_RUNOUT_PIN PE6 // MT_DET2 -//#define FIL_RUNOUT_PIN PG14 // MT_DET3 +#define FIL_RUNOUT2_PIN PE6 // MT_DET2 +#define FIL_RUNOUT3_PIN PG14 // MT_DET3 + +// +// Power Supply Control +// +#if ENABLED(PSU_CONTROL) // MKSPWC + #if HAS_TFT_LVGL_UI + #error "PSU_CONTROL cannot be used with TFT_LVGL_UI. Disable PSU_CONTROL to continue." + #endif + #ifndef PS_ON_PIN + #define PS_ON_PIN PG11 // SUICIDE + #endif + #ifndef KILL_PIN + #define KILL_PIN PA2 + #define KILL_PIN_STATE HIGH + #endif +#else + #define SUICIDE_PIN PG11 + #define SUICIDE_PIN_INVERTING false +#endif // // SD Card @@ -191,12 +210,11 @@ #endif #if SD_CONNECTION_IS(LCD) - #define ENABLE_SPI2 #define SD_DETECT_PIN PG3 - #define SCK_PIN PB13 - #define MISO_PIN PB14 - #define MOSI_PIN PB15 - #define SS_PIN PG6 + #define SD_SCK_PIN PB13 + #define SD_MISO_PIN PB14 + #define SD_MOSI_PIN PB15 + #define SD_SS_PIN PG6 #elif SD_CONNECTION_IS(ONBOARD) #define SDIO_SUPPORT #define SD_DETECT_PIN PD12 @@ -205,20 +223,38 @@ #error "No custom SD drive cable defined for this board." #endif -/** - * Note: MKS Robin TFT screens use various TFT controllers. - * If the screen stays white, disable 'LCD_RESET_PIN' - * to let the bootloader init the screen. - */ -#if ENABLED(FSMC_GRAPHICAL_TFT) +// +// TFT with FSMC interface +// +#if HAS_FSMC_TFT + /** + * Note: MKS Robin TFT screens use various TFT controllers. + * If the screen stays white, disable 'LCD_RESET_PIN' + * to let the bootloader init the screen. + */ + #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 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 PF6 #define LCD_BACKLIGHT_PIN PD13 + #define TFT_BUFFER_SIZE 14400 + #if NEED_TOUCH_PINS - #define TOUCH_CS_PIN PA7 + #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 #else #define BEEPER_PIN PC5 #define BTN_ENC PG2 @@ -254,10 +290,15 @@ #else // !MKS_MINI_12864 && !ENDER2_STOCKDISPLAY #define LCD_PINS_D4 PF14 - #if ENABLED(ULTIPANEL) + #if IS_ULTIPANEL #define LCD_PINS_D5 PF15 #define LCD_PINS_D6 PF12 #define LCD_PINS_D7 PF13 + + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif + #endif #endif // !MKS_MINI_12864 && !ENDER2_STOCKDISPLAY @@ -265,11 +306,20 @@ #endif #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(125) + #define BOARD_ST7920_DELAY_1 DELAY_NS(125) #endif #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(125) + #define BOARD_ST7920_DELAY_2 DELAY_NS(125) #endif #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(125) + #define BOARD_ST7920_DELAY_3 DELAY_NS(125) +#endif + +#define HAS_SPI_FLASH 1 +#if HAS_SPI_FLASH + #define SPI_FLASH_SIZE 0x1000000 // 16MB + #define W25QXX_CS_PIN PB12 // Flash chip-select + #define W25QXX_MOSI_PIN PB15 + #define W25QXX_MISO_PIN PB14 + #define W25QXX_SCK_PIN PB13 #endif diff --git a/Marlin/src/pins/stm32f1/pins_MORPHEUS.h b/Marlin/src/pins/stm32f1/pins_MORPHEUS.h index ccc92b7527d1..87919c12f488 100644 --- a/Marlin/src/pins/stm32f1/pins_MORPHEUS.h +++ b/Marlin/src/pins/stm32f1/pins_MORPHEUS.h @@ -30,7 +30,7 @@ * MORPHEUS Board pin assignments */ -#if NOT_TARGET(__STM32F1__) +#if NOT_TARGET(__STM32F1__, STM32F1xx) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #endif @@ -39,9 +39,9 @@ // // Limit Switches // -#define X_MIN_PIN PB14 -#define Y_MIN_PIN PB13 -#define Z_MIN_PIN PB12 +#define X_STOP_PIN PB14 +#define Y_STOP_PIN PB13 +#define Z_STOP_PIN PB12 // // Z Probe (when not Z_MIN_PIN) @@ -90,3 +90,4 @@ #define LED_PIN PC13 #define SDSS PA3 #define TFTGLCD_CS PA4 +#define SD_DETECT_PIN PC14 diff --git a/Marlin/src/pins/stm32f1/pins_STM32F1R.h b/Marlin/src/pins/stm32f1/pins_STM32F1R.h index cf2ba2c5fa74..c08b707d7e99 100644 --- a/Marlin/src/pins/stm32f1/pins_STM32F1R.h +++ b/Marlin/src/pins/stm32f1/pins_STM32F1R.h @@ -21,9 +21,7 @@ */ #pragma once -#if NOT_TARGET(__STM32F1__) - #error "Oops! Select an STM32F1 board in 'Tools > Board.'" -#endif +#include "env_validate.h" /** * 21017 Victor Perez Marlin for stm32f1 test @@ -100,16 +98,7 @@ #if HAS_WIRED_LCD #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 - #elif BOTH(NEWPANEL, PANEL_ONE) - #define LCD_PINS_RS PB8 - #define LCD_PINS_ENABLE PD2 - #define LCD_PINS_D4 PB12 - #define LCD_PINS_D5 PB13 - #define LCD_PINS_D6 PB14 - #define LCD_PINS_D7 PB15 + #error "REPRAPWORLD_GRAPHICAL_LCD is not supported." #else #define LCD_PINS_RS PB8 #define LCD_PINS_ENABLE PD2 @@ -117,145 +106,33 @@ #define LCD_PINS_D5 PB13 #define LCD_PINS_D6 PB14 #define LCD_PINS_D7 PB15 - #if DISABLED(NEWPANEL) - #define BEEPER_PIN 33 - // Buttons attached to a shift register - // Not wired yet - //#define SHIFT_CLK 38 - //#define SHIFT_LD 42 - //#define SHIFT_OUT 40 - //#define SHIFT_EN 17 + #if !IS_NEWPANEL + #error "Non-NEWPANEL LCD is not supported." #endif #endif - #if ENABLED(NEWPANEL) - - #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) - - #define BEEPER_PIN 37 - - #define BTN_EN1 31 - #define BTN_EN2 33 - #define BTN_ENC 35 - - #define SD_DETECT_PIN 49 - #define KILL_PIN 41 - - #if ENABLED(BQ_LCD_SMART_CONTROLLER) - #define LCD_BACKLIGHT_PIN 39 - #endif - + #if IS_NEWPANEL + #if IS_RRD_SC + #error "RRD Smart Controller is not supported." #elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - - #define BTN_EN1 64 - #define BTN_EN2 59 - #define BTN_ENC 63 - #define SD_DETECT_PIN 42 - + #error "REPRAPWORLD_GRAPHICAL_LCD is not supported." #elif ENABLED(LCD_I2C_PANELOLU2) - - #define BTN_EN1 47 - #define BTN_EN2 43 - #define BTN_ENC 32 - #define LCD_SDSS 53 - #define SD_DETECT_PIN -1 - #define KILL_PIN 41 - + #error "LCD_I2C_PANELOLU2 is not supported." #elif ENABLED(LCD_I2C_VIKI) - - #define BTN_EN1 22 // https://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42. - #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 - + #error "LCD_I2C_VIKI is not supported." #elif ANY(VIKI2, miniVIKI) - - #define BEEPER_PIN 33 - - // Pins for DOGM SPI LCD Support - #define DOGLCD_A0 44 - #define DOGLCD_CS 45 - #define LCD_SCREEN_ROT_180 - - #define BTN_EN1 22 - #define BTN_EN2 7 - #define BTN_ENC 39 - - #define SDSS 53 - #define SD_DETECT_PIN -1 // Pin 49 for display sd interface, 72 for easy adapter board - - #define KILL_PIN 31 - - #define STAT_LED_RED_PIN 32 - #define STAT_LED_BLUE_PIN 35 - + #error "VIKI2 / miniVIKI is not supported." #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) - #define BTN_EN1 35 - #define BTN_EN2 37 - #define BTN_ENC 31 - #define SD_DETECT_PIN 49 - #define LCD_SDSS 53 - #define KILL_PIN 41 - #define BEEPER_PIN 23 - #define DOGLCD_CS 29 - #define DOGLCD_A0 27 - #define LCD_BACKLIGHT_PIN 33 - + #error "ELB_FULL_GRAPHIC_CONTROLLER is not supported." #elif ENABLED(MINIPANEL) - - #define BEEPER_PIN 42 - // Pins for DOGM SPI LCD Support - #define DOGLCD_A0 44 - #define DOGLCD_CS 66 - #define LCD_BACKLIGHT_PIN 65 // backlight LED on A11/D65 - #define SDSS 53 - - #define KILL_PIN 64 - // GLCD features - // Uncomment screen orientation - //#define LCD_SCREEN_ROT_90 - //#define LCD_SCREEN_ROT_180 - //#define LCD_SCREEN_ROT_270 - // The encoder and click button - #define BTN_EN1 40 - #define BTN_EN2 63 - #define BTN_ENC 59 - // not connected to a pin - #define SD_DETECT_PIN 49 - + #error "MINIPANEL is not supported." #else - - // Beeper on AUX-4 - #define BEEPER_PIN 33 - - // Buttons directly attached to AUX-2 - #if ENABLED(REPRAPWORLD_KEYPAD) - #define BTN_EN1 64 - #define BTN_EN2 59 - #define BTN_ENC 63 - #define SHIFT_OUT 40 - #define SHIFT_CLK 44 - #define SHIFT_LD 42 - #elif ENABLED(PANEL_ONE) - #define BTN_EN1 59 // AUX2 PIN 3 - #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 - #endif - - #if ENABLED(G3D_PANEL) - #define SD_DETECT_PIN 49 - #define KILL_PIN 41 - #else - //#define SD_DETECT_PIN -1 // Ramps doesn't use this - #endif - + #error "Other generic NEWPANEL LCD is not supported." #endif - #endif // NEWPANEL + #endif + + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h b/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h index e74698f89eff..7171de919d03 100644 --- a/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h @@ -21,12 +21,10 @@ */ #pragma once -#if NOT_TARGET(__STM32F1__, __STM32F4__) - #error "Oops! Select an STM32F1/4 board in 'Tools > Board.'" -#endif +#include "env_validate.h" /** - * 21017 Victor Perez Marlin for stm32f1 test + * 10 Dec 2017 Victor Perez Marlin for stm32f1 test */ #define BOARD_INFO_NAME "STM3R Mini" @@ -115,16 +113,7 @@ #if HAS_WIRED_LCD #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 - #elif BOTH(NEWPANEL, PANEL_ONE) - #define LCD_PINS_RS PB8 - #define LCD_PINS_ENABLE PD2 - #define LCD_PINS_D4 PB12 - #define LCD_PINS_D5 PB13 - #define LCD_PINS_D6 PB14 - #define LCD_PINS_D7 PB15 + #error "REPRAPWORLD_GRAPHICAL_LCD is not supported." #else #define LCD_PINS_RS PB8 #define LCD_PINS_ENABLE PD2 @@ -132,14 +121,8 @@ #define LCD_PINS_D5 PB13 #define LCD_PINS_D6 PB14 #define LCD_PINS_D7 PB15 - #if DISABLED(NEWPANEL) - #define BEEPER_PIN 33 - // Buttons attached to a shift register - // Not wired yet - //#define SHIFT_CLK 38 - //#define SHIFT_LD 42 - //#define SHIFT_OUT 40 - //#define SHIFT_EN 17 + #if !IS_NEWPANEL + #error "Non-NEWPANEL LCD is not supported." #endif #endif @@ -151,135 +134,26 @@ #define TOUCH_MISO_PIN PB15 #define TOUCH_INT_PIN PC6 // (PenIRQ coming from ADS7843) - #elif ENABLED(NEWPANEL) - - #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) - - #define BEEPER_PIN 37 - - #define BTN_EN1 31 - #define BTN_EN2 33 - #define BTN_ENC 35 - - #define SD_DETECT_PIN 49 - #define KILL_PIN 41 - - #if ENABLED(BQ_LCD_SMART_CONTROLLER) - #define LCD_BACKLIGHT_PIN 39 - #endif + #elif IS_NEWPANEL + #if IS_RRD_SC + #error "RRD Smart Controller is not supported." #elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - - #define BTN_EN1 64 - #define BTN_EN2 59 - #define BTN_ENC 63 - #define SD_DETECT_PIN 42 - + #error "REPRAPWORLD_GRAPHICAL_LCD is not supported." #elif ENABLED(LCD_I2C_PANELOLU2) - - #define BTN_EN1 47 - #define BTN_EN2 43 - #define BTN_ENC 32 - #define LCD_SDSS 53 - #define SD_DETECT_PIN -1 - #define KILL_PIN 41 - + #error "LCD_I2C_PANELOLU2 is not supported." #elif ENABLED(LCD_I2C_VIKI) - - #define BTN_EN1 22 // https://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42. - #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 - + #error "LCD_I2C_VIKI is not supported." #elif ANY(VIKI2, miniVIKI) - - #define BEEPER_PIN 33 - - // Pins for DOGM SPI LCD Support - #define DOGLCD_A0 44 - #define DOGLCD_CS 45 - #define LCD_SCREEN_ROT_180 - - #define BTN_EN1 22 - #define BTN_EN2 7 - #define BTN_ENC 39 - - #define SDSS 53 - #define SD_DETECT_PIN -1 // Pin 49 for display sd interface, 72 for easy adapter board - - #define KILL_PIN 31 - - #define STAT_LED_RED_PIN 32 - #define STAT_LED_BLUE_PIN 35 - + #error "VIKI2 / miniVIKI is not supported." #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) - - #define BTN_EN1 35 - #define BTN_EN2 37 - #define BTN_ENC 31 - #define SD_DETECT_PIN 49 - #define LCD_SDSS 53 - #define KILL_PIN 41 - #define BEEPER_PIN 23 - #define DOGLCD_CS 29 - #define DOGLCD_A0 27 - #define LCD_BACKLIGHT_PIN 33 - + #error "ELB_FULL_GRAPHIC_CONTROLLER is not supported." #elif ENABLED(MINIPANEL) - - #define BEEPER_PIN 42 - // Pins for DOGM SPI LCD Support - #define DOGLCD_A0 44 - #define DOGLCD_CS 66 - #define LCD_BACKLIGHT_PIN 65 // backlight LED on A11/D65 - #define SDSS 53 - - #define KILL_PIN 64 - // GLCD features - // Uncomment screen orientation - //#define LCD_SCREEN_ROT_90 - //#define LCD_SCREEN_ROT_180 - //#define LCD_SCREEN_ROT_270 - // The encoder and click button - #define BTN_EN1 40 - #define BTN_EN2 63 - #define BTN_ENC 59 - // not connected to a pin - #define SD_DETECT_PIN 49 - + #error "MINIPANEL is not supported." #else - - // Beeper on AUX-4 - #define BEEPER_PIN 33 - - // Buttons directly attached to AUX-2 - #if ENABLED(REPRAPWORLD_KEYPAD) - #define BTN_EN1 64 - #define BTN_EN2 59 - #define BTN_ENC 63 - #define SHIFT_OUT 40 - #define SHIFT_CLK 44 - #define SHIFT_LD 42 - #elif ENABLED(PANEL_ONE) - #define BTN_EN1 59 // AUX2 PIN 3 - #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 - #endif - - #if ENABLED(G3D_PANEL) - #define SD_DETECT_PIN 49 - #define KILL_PIN 41 - #else - //#define SD_DETECT_PIN -1 // Ramps doesn't use this - #endif - + #error "Other generic NEWPANEL LCD is not supported." #endif - #endif // NEWPANEL + + #endif #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h b/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h index bfd1f2abdcbd..5b59a157f163 100644 --- a/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h +++ b/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h @@ -22,21 +22,26 @@ #pragma once /** - * ANYCUBIC Trigorilla Pro (STM32F130ZET6) board pin assignments. + * ANYCUBIC Trigorilla Pro (STM32F103ZET6) board pin assignments. * It is the same used by the Tronxy X5SA thanks to ftoz1 for sharing it * https://github.com/MarlinFirmware/Marlin/issues/14655 * https://github.com/MarlinFirmware/Marlin/files/3401484/x5sa-main_board-2.pdf */ -#if NOT_TARGET(__STM32F1__) - #error "Oops! Select an STM32F1 board in 'Tools > Board.'" -#elif HOTENDS > 2 || E_STEPPERS > 2 +#include "env_validate.h" + +#if HOTENDS > 2 || E_STEPPERS > 2 #error "Trigorilla Pro supports up to 2 hotends / E-steppers. Comment out this line to continue." #endif #define BOARD_INFO_NAME "Trigorilla Pro" + +#define BOARD_NO_NATIVE_USB + #define DISABLE_JTAG +//#define SWAPPED_Z_PLUGS + // // EEPROM // @@ -53,10 +58,22 @@ // // Limit Switches // -#define X_MAX_PIN PG10 -#define Y_MAX_PIN PA12 -#define Z_MAX_PIN PA14 -#define Z_MIN_PIN PA13 +#define X_STOP_PIN PG10 +#define Y_STOP_PIN PA12 +#ifndef Z_MIN_PIN + #ifdef SWAPPED_Z_PLUGS + #define Z_MIN_PIN PA14 + #else + #define Z_MIN_PIN PA13 + #endif +#endif +#ifndef Z_MAX_PIN + #ifdef SWAPPED_Z_PLUGS + #define Z_MAX_PIN PA13 + #else + #define Z_MAX_PIN PA14 + #endif +#endif // // Steppers @@ -109,20 +126,24 @@ //#define POWER_LOSS_PIN PG2 // PG4 PW_DET #define FIL_RUNOUT_PIN PA15 // MT_DET -/** - * Note: MKS Robin TFT screens use various TFT controllers - * Supported screens are based on the ILI9341, ST7789V and ILI9328 (320x240) - * ILI9488 is not supported. - * Define init sequences for other screens in u8g_dev_tft_320x240_upscale_from_128x64.cpp - * - * If the screen stays white, disable 'LCD_RESET_PIN' to let the bootloader init the screen. - * - * Setting an 'LCD_RESET_PIN' may cause a flicker when entering the LCD menu - * because Marlin uses the reset as a failsafe to revive a glitchy LCD. - */ +// +// TFT with FSMC interface +// #if HAS_FSMC_TFT + /** + * Note: MKS Robin TFT screens use various TFT controllers + * Supported screens are based on the ILI9341, ST7789V and ILI9328 (320x240) + * ILI9488 is not supported. + * Define init sequences for other screens in u8g_dev_tft_320x240_upscale_from_128x64.cpp + * + * If the screen stays white, disable 'LCD_RESET_PIN' to let the bootloader init the screen. + * + * Setting an 'LCD_RESET_PIN' may cause a flicker when entering the LCD menu + * because Marlin uses the reset as a failsafe to revive a glitchy LCD. + */ #define TFT_RESET_PIN PF11 #define TFT_BACKLIGHT_PIN PD13 + #define FSMC_CS_PIN PD7 // NE4 #define FSMC_RS_PIN PD11 // A0 @@ -137,31 +158,18 @@ #endif // XPT2046 Touch Screen calibration -#if ENABLED(TFT_COLOR_UI) || ENABLED(TFT_LVGL_UI) - #ifndef XPT2046_X_CALIBRATION - #define XPT2046_X_CALIBRATION -17181 +#if ANY(TFT_COLOR_UI, TFT_LVGL_UI, TFT_CLASSIC_UI) + #ifndef TOUCH_CALIBRATION_X + #define TOUCH_CALIBRATION_X -17181 #endif - #ifndef XPT2046_Y_CALIBRATION - #define XPT2046_Y_CALIBRATION 11434 + #ifndef TOUCH_CALIBRATION_Y + #define TOUCH_CALIBRATION_Y 11434 #endif - #ifndef XPT2046_X_OFFSET - #define XPT2046_X_OFFSET 501 + #ifndef TOUCH_OFFSET_X + #define TOUCH_OFFSET_X 501 #endif - #ifndef XPT2046_Y_OFFSET - #define XPT2046_Y_OFFSET -9 - #endif -#elif ENABLED(TFT_CLASSIC_UI) - #ifndef XPT2046_X_CALIBRATION - #define XPT2046_X_CALIBRATION -12316 - #endif - #ifndef XPT2046_Y_CALIBRATION - #define XPT2046_Y_CALIBRATION 8981 - #endif - #ifndef XPT2046_X_OFFSET - #define XPT2046_X_OFFSET 340 - #endif - #ifndef XPT2046_Y_OFFSET - #define XPT2046_Y_OFFSET -20 + #ifndef TOUCH_OFFSET_Y + #define TOUCH_OFFSET_Y -9 #endif #endif @@ -173,21 +181,23 @@ #endif // SPI1(PA7) & SPI3(PB5) not available -#define ENABLE_SPI2 +#define SPI_DEVICE 2 #if ENABLED(SDIO_SUPPORT) - #define SCK_PIN PB13 // SPI2 ok - #define MISO_PIN PB14 // SPI2 ok - #define MOSI_PIN PB15 // SPI2 ok - #define SS_PIN PC11 // PB12 is X- ok + #define SD_SCK_PIN PB13 // SPI2 ok + #define SD_MISO_PIN PB14 // SPI2 ok + #define SD_MOSI_PIN PB15 // SPI2 ok + #define SD_SS_PIN PC11 // PB12 is X- ok #define SD_DETECT_PIN -1 // SD_CD ok #else // SD as custom software SPI (SDIO pins) - #define SCK_PIN PC12 - #define MISO_PIN PC8 - #define MOSI_PIN PD2 - #define SS_PIN -1 + #define SD_SCK_PIN PC12 + #define SD_MISO_PIN PC8 + #define SD_MOSI_PIN PD2 + #define SD_SS_PIN -1 #define ONBOARD_SD_CS_PIN PC11 #define SDSS PD2 #define SD_DETECT_PIN -1 #endif + +#undef SWAPPED_Z_PLUGS diff --git a/Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h b/Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h new file mode 100644 index 000000000000..bad5db7125e1 --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h @@ -0,0 +1,235 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include "env_validate.h" + +#define BOARD_INFO_NAME "ZONESTAR ZM3E2 V1.0" + +#define DISABLE_DEBUG +//#define DISABLE_JTAG + +#if NO_EEPROM_SELECTED + #define FLASH_EEPROM_EMULATION + #define EEPROM_PAGE_SIZE (0x800) // 2KB + #define EEPROM_START_ADDRESS (0x08000000 + (STM32_FLASH_SIZE) * 1024 - 2 * EEPROM_PAGE_SIZE) + #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2KB +#endif + +//============================================================================= +// Zonestar ZM3E2 V1.0 (STM32F103RCT6) board pin assignments +//============================================================================= +// PA0 PWR_HOLD | PB0 BEEP | PC0 HEATER_0 +// PA1 FAN_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 +// PA5 SD_SCK | PB5 Z_DIR | PC5 BTN_EN2 +// PA6 SD_MISO | PB6 Z_STEP | PC6 FAN1 +// PA7 SD_MOSI | PB7 Z_EN | PC7 FIL_RUNOUT +// PA8 X_DIR | PB8 Y_STEP | PC8 X_EN +// PA9 LCD_RS | PB9 Y_DIR | PC9 X_STEP +// PA10 LCD_SCK | PB10 BTN_ENC | PC10 Z_MIN_PROBE_PIN +// PA11 USB_D- | PB11 BTN_EN1 | PC11 FIL_RUNOUT2 +// PA12 USB_D+ | PB12 LED | PC12 E1_DIR +// PA13 MS1 | PB13 E0_EN | PC13 Y_STOP +// PA14 MS2 | PB14 E0_STEP | PC14 Y_EN +// PA15 PWM | PB15 E0_DIR | PC15 X_STOP +// PD0 NC +// PD1 NC +// PD2 E1_STEP + +//============================================================================= +// EXP1 connector +// MARK I/O ZONESTAR_12864LCD ZONESTAR_12864OLED +// 10 MOSI PB1 KILL SDA +// 9 SCK PB0 BEEP SCK +// 8 TX1 PA9 DOGLCD_CS CS +// 7 RX1 PA10 DOGLCD_SCK DC +// 6 ENA PC5 BTN_EN2 KNOB_ENB +// 5 DAT PB2 DOGLCD_MOSI RESET +// 4 TX3 PB10 BTN_ENC KNOB_ENC +// 3 RX3 PB11 BTN_EN1 KNOB_ENA +// 2 +5V +// 1 GND + +#define EXP1_03_PIN PB11 +#define EXP1_04_PIN PB10 +#define EXP1_05_PIN PB2 +#define EXP1_06_PIN PC5 +#define EXP1_07_PIN PA10 +#define EXP1_08_PIN PA9 +#define EXP1_09_PIN PB0 +#define EXP1_10_PIN PB1 + +// AUX1 connector +// 1 +5V +// 2 TX2 PA2 UART2_TX +// 3 RX2 PA3 UART2_RX +// 4 GND + +// AUX2 connector to BLTouch +// 1 +5V +// 2 SEN PC10 +// 3 PWM PA15 +// 4 GND +//============================================================================= + +// +// Servos +// +#define SERVO0_PIN PA15 + +// +// Limit Switches +// +#define X_STOP_PIN PC15 +#define Y_STOP_PIN PC13 +#define Z_STOP_PIN PB4 + +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN PC10 // BLTouch (3DTouch) +#endif + +// +// Filament Runout Sensor +// +#define FIL_RUNOUT_PIN PC7 // E0_SW +//#define FIL_RUNOUT2_PIN PC11 // E1_SW + +// +// Steppers +// +#define MS1_PIN PA13 +#define MS2_PIN PA14 + +#define X_STEP_PIN PC9 +#define X_DIR_PIN PA8 +#define X_ENABLE_PIN PC8 + +#define Y_STEP_PIN PB8 +#define Y_DIR_PIN PB9 +#define Y_ENABLE_PIN PC14 + +#define Z_STEP_PIN PB6 +#define Z_DIR_PIN PB5 +#define Z_ENABLE_PIN PB7 + +#define E0_STEP_PIN PB14 +#define E0_DIR_PIN PB15 +#define E0_ENABLE_PIN PB13 + +#define E1_STEP_PIN PD2 +#define E1_DIR_PIN PC12 +#define E1_ENABLE_PIN PB3 + +// +// Heaters / Fans +// +#define HEATER_0_PIN PC0 // EXTRUDER 1 +#define HEATER_BED_PIN PC1 // BED + +#define FAN1_PIN PC6 +#define FAN_PIN PA1 + +// +// Temperature Sensors +// +#define TEMP_BED_PIN PC2 // Analog Input +#define TEMP_0_PIN PC3 // Analog Input + +#define LED_PIN PB12 +//#define KILL_PIN PB1 // @EXP1 +#define SUICIDE_PIN PA0 + +// +// SD card +// +#define ENABLE_SPI1 +#define SD_DETECT_PIN PC4 +#define SD_SCK_PIN PA5 +#define SD_MISO_PIN PA6 +#define SD_MOSI_PIN PA7 +#define SD_SS_PIN PA4 + +// +// LCD Pins +// +#if ENABLED(ZONESTAR_12864LCD) + + //================================================================================ + // LCD 128x64 + //================================================================================ + // EXP1 connector + // MARK I/O ZONESTAR_12864LCD + // 10 MOSI PB1 KILL + // 9 SCK PB0 BEEP + // 8 TX1 PA9 LCD_PINS_RS + // 7 RX1 PA10 LCD_PINS_D4 + // 6 ENA PC5 BTN_EN2 + // 5 DAT PB2 LCD_PINS_ENABLE + // 4 TX3 PB10 BTN_ENC + // 3 RX3 PB11 BTN_EN1 + // 2 +5V + // 1 GND + + #define LCDSCREEN_NAME "ZONESTAR LCD12864" + #define LCD_PINS_RS EXP1_08_PIN + #define LCD_PINS_ENABLE EXP1_05_PIN + #define LCD_PINS_D4 EXP1_07_PIN + //#define KILL_PIN EXP1_10_PIN + #define BEEPER_PIN EXP1_09_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_06_PIN + #define BTN_ENC EXP1_04_PIN + #define BOARD_ST7920_DELAY_1 DELAY_NS(125) + #define BOARD_ST7920_DELAY_2 DELAY_NS(200) + #define BOARD_ST7920_DELAY_3 DELAY_NS(125) + +#elif EITHER(ZONESTAR_12864OLED, ZONESTAR_12864OLED_SSD1306) + + //================================================================================ + // OLED 128x64 + //================================================================================ + // 10 MOSI PB1 OLED_SDA + // 9 SCK PB0 OLED_SCK + // 8 TX1 PA9 OLED_CS + // 7 RX1 PA10 OLED_DC + // 6 ENA PC5 KNOB_ENA + // 5 DAT PB2 OLED_RESET + // 4 TX3 PB10 KNOB_ENC + // 3 RX3 PB11 KNOB_ENB + + #define FORCE_SOFT_SPI + #define LCDSCREEN_NAME "ZONESTAR 12864OLED" + #define LCD_PINS_RS EXP1_05_PIN // = LCD_RESET_PIN + #define LCD_PINS_DC EXP1_07_PIN // DC + #define DOGLCD_CS EXP1_08_PIN // CS + #define DOGLCD_A0 LCD_PINS_DC // A0 = DC + #define DOGLCD_MOSI EXP1_10_PIN // SDA + #define DOGLCD_SCK EXP1_09_PIN // SCK + // Encoder + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_06_PIN + #define BTN_ENC EXP1_04_PIN + +#endif diff --git a/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h b/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h new file mode 100644 index 000000000000..8a6bb4b5f87b --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h @@ -0,0 +1,355 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include "env_validate.h" + +#define BOARD_INFO_NAME "ZONESTAR ZM3E4 V1.0" + +//#define DISABLE_DEBUG +#define DISABLE_JTAG + +#if NO_EEPROM_SELECTED + #define FLASH_EEPROM_EMULATION + #define EEPROM_PAGE_SIZE (0x800) // 2KB + #define EEPROM_START_ADDRESS (0x08000000 + (STM32_FLASH_SIZE) * 1024 - 2 * EEPROM_PAGE_SIZE) + #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2KB +#endif + +//#define OPTION_DUALZ_DRIVE +//#define OPTION_Z2_ENDSTOP +//#define SWITCH_EXTRUDER_SEQUENCE + +//============================================================================= +// Zonestar ZM3E4 V1.0 (STM32F103VCT6) board pin assignments +//============================================================================= +// PA0 | PB0 HEAT_1 | PC0 AXU_SDA +// PA1 | PB1 FAN1 | PC1 TEMP_E1 +// PA2 HEAT_BED | PB2 BOOT1 | PC2 TEMP_E0 +// PA3 PWR_HOLD | PB3 SPI3_SCK | PC3 TEMP_BED +// PA4 SD_CS | PB4 SPI3_MISO | PC4 SD_DETECT +// PA5 SD_SCK | PB5 SPI3_MOSI | PC5 HEAT_0 +// PA6 SD_MISO | PB6 SERVO3 | PC6 E1_STEP +// PA7 SD_MOSI | PB7 SERVO2 | PC7 E1_EN +// PA8 X_DIR | PB8 FAN2/SERVO1 | PC8 FIL_RUNOUT_PIN +// PA9 UART1_RX | PB9 SERVO0 | PC9 E0_DIR +// PA10 UART1_TX | PB10 TX3 | PC10 E0_EN +// PA11 USB_D- | PB11 RX3 | PC11 Z2_EN +// PA12 USB_D+ | PB12 LED | PC12 Z2_STEP +// PA13 SWD_SDO | PB13 Z1_MAX | PC13 X_MIN +// PA14 SWD_SCK | PB14 Y_MAX | PC14 WIFI_RST +// PA15 SPI3_CS | PB15 PWR_DET | PC15 WIFI_CS +// PD0 Z2_DIR | PE0 Y_EN +// PD1 Z2_MIN | PE1 Y_STEP +// PD2 Z1_EN | PE2 Y_DIR +// PD3 Z1_STEP | PE3 Y_MIN +// PD4 Z1_DIR | PE4 X_DIR +// PD5 WIFI_RXD | PE5 X_STEP +// PD6 WIFI_TXD | PE6 X_EN +// PD7 Z1_MIN | PE7 AXU_SCL +// PD8 X_MAX | PE8 BTN_EN1 +// PD9 E3_DIR | PE9 LCD_SCK +// PD10 E3_STEP | PE10 LCD_MOSI +// PD11 E3_EN | PE11 BEEPER +// PD12 E2_DIR | PE12 LCD_EN +// PD13 E2_STEP | PE13 KILL +// PD14 E2_EN | PE14 BTN_EN2 +// PD15 E1_DIR | PE15 BTN_ENC +//============================================================================= + +// EXP1 connector +// MARK I/O ZONESTAR_LCD12864 REPRAPDISCOUNT_LCD12864 +// 10 RS PE13 KILL BTN_ENC +// 9 BP PE11 BEEP BEEP +// 8 EN PE12 DOGLCD_CS LCDRS +// 7 MOSI PE10 DOGLCD_SCK LCDE +// 6 EN1 PE8 BTN_EN1 NC +// 5 SCK PE9 DOGLCD_MOSI LCD4 +// 4 ENC PE15 BTN_ENC NC +// 3 EN2 PE14 BTN_EN2 NC +// 2 +5V +5V +// 1 GND GND + +#define EXP1_03_PIN PE14 +#define EXP1_04_PIN PE15 +#define EXP1_05_PIN PE9 +#define EXP1_06_PIN PE8 +#define EXP1_07_PIN PE10 +#define EXP1_08_PIN PE12 +#define EXP1_09_PIN PE11 +#define EXP1_10_PIN PE13 + +// EXP2 connector +// MARK I/O ZONESTAR_LCD12864 REPRAPDISCOUNT_LCD12864 +// 10 +// 9 +// 8 RX0 PA9 UART1_RX +// 7 TX0 PA10 UART1_TX BTN_EN2 +// 6 CS3 PA15 +// 5 MISO3 PB4 BTN_EN1 +// 4 MOSI3 PB5 KILL +// 3 SCK3 PB3 +// 2 +5V +5V +// 1 GND GND + +#define EXP2_03_PIN PB3 +#define EXP2_04_PIN PB5 +#define EXP2_05_PIN PB4 +#define EXP2_06_PIN PA15 +#define EXP2_07_PIN PA10 +#define EXP2_08_PIN PA9 + +// AUX1 connector +// 1 +5V +// 2 GND +// 3 RX3 PB11 UART3_RX +// 4 TX3 PB10 UART3_TX +// 5 SCL PE7 +// 6 SDA PC0 + +// WiFi +// 1 +5V +// 2 GND +// 3 WIFI_TXD PD5 UART2_RX +// 4 WIFI_RXD PD6 UART2_TX +// 5 WIFI_RST PC14 +// 6 WIFI_CS PC15 +//============================================================================= + +// +// Servos +// +#define SERVO0_PIN PB9 +#define SERVO2_PIN PB7 +#define SERVO3_PIN PB6 + +// +// Limit Switches +// +#define X_MIN_PIN PC13 +#define X_MAX_PIN PD8 +#define Y_MIN_PIN PE3 +#define Y_MAX_PIN PB14 +#define Z_MIN_PIN PD7 +#define Z_MAX_PIN PB13 + +// +// Filament Runout Sensor +// +#ifndef FIL_RUNOUT_PIN + #define FIL_RUNOUT_PIN PC8 +#endif + +// +// Steppers +// +#if ENABLED(COREXY) + #define X_ENABLE_PIN PE0 + #define X_STEP_PIN PE1 + #define X_DIR_PIN PE2 + + #define Y_ENABLE_PIN PE6 + #define Y_STEP_PIN PE5 + #define Y_DIR_PIN PE4 +#else + #define X_ENABLE_PIN PE6 + #define X_STEP_PIN PE5 + #define X_DIR_PIN PE4 + + #define Y_ENABLE_PIN PE0 + #define Y_STEP_PIN PE1 + #define Y_DIR_PIN PE2 +#endif + +#define Z_ENABLE_PIN PD2 +#define Z_STEP_PIN PD3 +#define Z_DIR_PIN PD4 + +#ifdef OPTION_DUALZ_DRIVE + #define Z2_ENABLE_PIN PC11 + #define Z2_STEP_PIN PC12 + #define Z2_DIR_PIN PD0 +#endif + +#ifdef OPTION_Z2_ENDSTOP + #define Z2_MIN_PIN PD1 + #define Z2_MAX_PIN PB12 +#endif + +#ifdef SWITCH_EXTRUDER_SEQUENCE + #define E3_ENABLE_PIN PC10 + #define E3_STEP_PIN PA8 + #define E3_DIR_PIN PC9 + + #define E2_STEP_PIN PC6 + #define E2_DIR_PIN PD15 + #define E2_ENABLE_PIN PC7 + + #define E1_STEP_PIN PD13 + #define E1_DIR_PIN PD12 + #define E1_ENABLE_PIN PD14 + + #define E0_STEP_PIN PD10 + #define E0_DIR_PIN PD9 + #define E0_ENABLE_PIN PD11 +#else + #define E0_ENABLE_PIN PC10 + #define E0_STEP_PIN PA8 + #define E0_DIR_PIN PC9 + + #define E1_STEP_PIN PC6 + #define E1_DIR_PIN PD15 + #define E1_ENABLE_PIN PC7 + + #define E2_STEP_PIN PD13 + #define E2_DIR_PIN PD12 + #define E2_ENABLE_PIN PD14 + + #define E3_STEP_PIN PD10 + #define E3_DIR_PIN PD9 + #define E3_ENABLE_PIN PD11 +#endif + +// +// Temperature Sensors +// +#define TEMP_0_PIN PC2 // TH0 +#define TEMP_BED_PIN PC3 // TB1 + +// +// Heaters / Fans +// +#define HEATER_0_PIN PC5 // HEATER0 +#define HEATER_BED_PIN PA2 // HOT BED + +#if ENABLED(OPTION_CHAMBER) + #define TEMP_CHAMBER_PIN PC1 + #define HEATER_CHAMBER_PIN PB0 +#else + #define TEMP_1_PIN PC1 // TH1 + #define HEATER_1_PIN PB0 // HEATER1 +#endif + +#define FAN_PIN PB1 // FAN1 +#define FAN1_PIN PB8 // FAN2 + +// +// Misc. Functions +// + +//#define POWER_LOSS_PIN PB15 +#define LED_PIN PA0 +#define SUICIDE_PIN PA3 + +// +// SD card +// +#define ENABLE_SPI1 +#define SD_DETECT_PIN PC4 +#define SD_SCK_PIN PA5 +#define SD_MISO_PIN PA6 +#define SD_MOSI_PIN PA7 +#define SD_SS_PIN PA4 + +// WiFi Functions +#define WIFI_RST PC15 +#define WIFI_EN PC14 + +// +// LCD / Controller +// +#if ENABLED(ZONESTAR_12864LCD) + #define LCDSCREEN_NAME "ZONESTAR LCD12864" + #define LCD_PINS_RS EXP1_08_PIN // 7 CS make sure for zonestar zm3e4! + #define LCD_PINS_ENABLE EXP1_05_PIN // 6 DATA make sure for zonestar zm3e4! + #define LCD_PINS_D4 EXP1_07_PIN // 8 SCK make sure for zonestar zm3e4! + #define BEEPER_PIN EXP1_09_PIN + #define KILL_PIN -1 // EXP1_10_PIN + #define BTN_EN1 EXP1_06_PIN + #define BTN_EN2 EXP1_03_PIN + #define BTN_ENC EXP1_04_PIN +#elif ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define LCDSCREEN_NAME "REPRAPDISCOUNT LCD12864" + #define LCD_PINS_RS EXP1_08_PIN // 7 CS make sure for zonestar zm3e4! + #define LCD_PINS_ENABLE EXP1_07_PIN // 6 DATA make sure for zonestar zm3e4! + #define LCD_PINS_D4 EXP1_05_PIN // 8 SCK make sure for zonestar zm3e4! + #define BEEPER_PIN EXP1_09_PIN + #define KILL_PIN EXP2_04_PIN + #define BTN_EN1 EXP2_05_PIN + #define BTN_EN2 EXP2_07_PIN + #define BTN_ENC EXP1_10_PIN +#elif ENABLED(ZONESTAR_DWIN_LCD) + // Connect to EXP2 connector + #define LCDSCREEN_NAME "ZONESTAR DWIN LCD" + #define BEEPER_PIN EXP2_06_PIN + #define KILL_PIN PC0 + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_04_PIN + #define BTN_ENC EXP2_05_PIN +#endif + +#if ENABLED(ZONESTAR_LCD2004_KNOB) + #define LCDSCREEN_NAME "LCD2004 KNOB" + #define LCD_PINS_RS EXP1_08_PIN + #define LCD_PINS_ENABLE EXP1_07_PIN + #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_03_PIN + #define LCD_PINS_D7 EXP1_04_PIN + #define BTN_EN1 EXP2_07_PIN + #define BTN_EN2 EXP2_05_PIN + #define BTN_ENC EXP1_10_PIN + #define BEEPER_PIN EXP1_09_PIN + #define KILL_PIN EXP2_04_PIN +#elif ENABLED(ZONESTAR_LCD2004_ADCKEY) + #define LCDSCREEN_NAME "LCD2004 5KEY" + #define LCD_PINS_RS EXP1_08_PIN + #define LCD_PINS_ENABLE EXP1_07_PIN + #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_03_PIN + #define LCD_PINS_D7 EXP1_04_PIN + #define ADC_KEYPAD_PIN PC0 // PIN6 of AUX1 +#endif + +#if HAS_MARLINUI_U8GLIB + #define BOARD_ST7920_DELAY_1 DELAY_NS(125) + #define BOARD_ST7920_DELAY_2 DELAY_NS(250) + #define BOARD_ST7920_DELAY_3 DELAY_NS(125) +#endif + +// Remap SERVO0 PIN for BLTouch +#if ENABLED(BLTOUCH_ON_EXP1) + // BLTouch connected to EXP1 + #define BLTOUCH_PROBE_PIN EXP1_06_PIN + #define BLTOUCH_GND_PIN EXP1_04_PIN + #undef SERVO0_PIN + #define SERVO0_PIN EXP1_03_PIN +#elif ENABLED(BLTOUCH_ON_EXP2) + // BLTouch connected to EXP2 + #define BLTOUCH_PROBE_PIN EXP2_03_PIN + #define BLTOUCH_GND_PIN EXP2_04_PIN + #undef SERVO0_PIN + #define SERVO0_PIN EXP2_06_PIN +#else + #define BLTOUCH_PROBE_PIN PB13 +#endif diff --git a/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h b/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h new file mode 100644 index 000000000000..5bbf43bbfac3 --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h @@ -0,0 +1,328 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include "env_validate.h" + +#define BOARD_INFO_NAME "ZONESTAR ZM3E4 V2.0" + +//#define DISABLE_DEBUG +#define DISABLE_JTAG + +#if NO_EEPROM_SELECTED + #define FLASH_EEPROM_EMULATION + #define EEPROM_PAGE_SIZE (0x800) // 2KB + #define EEPROM_START_ADDRESS (0x08000000 + (STM32_FLASH_SIZE) * 1024 - 2 * EEPROM_PAGE_SIZE) + #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2KB +#endif + +//#define OPTION_DUALZ_DRIVE +//#define OPTION_Z2_ENDSTOP +//#define OPTION_REPEAT_PRINTING +//#define SWITCH_EXTRUDER_SEQUENCE + +//============================================================================= +// Zonestar ZM3E4 V2.0 (STM32F103VET6) board pin assignments +//============================================================================= +// PA0 | PB0 HEAT_1 | PC0 AUX_SDA +// PA1 | PB1 FAN1 | PC1 TEMP_E1 +// PA2 HEAT_BED | PB2 BOOT1 | PC2 TEMP_E0 +// PA3 PWR_HOLD | PB3 SPI3_SCK | PC3 TEMP_BED +// PA4 SD_CS | PB4 SPI3_MISO | PC4 SD_DETECT +// PA5 SD_SCK | PB5 SPI3_MOSI | PC5 HEAT_0 +// PA6 SD_MISO | PB6 SERVO3 | PC6 E1_STEP +// PA7 SD_MOSI | PB7 SERVO2 | PC7 E1_EN +// PA8 X_DIR | PB8 FAN2/SERVO1 | PC8 FIL_RUNOUT_PIN +// PA9 UART1_RX | PB9 SERVO0 | PC9 E0_DIR +// PA10 UART1_TX | PB10 TX3 | PC10 E0_EN +// PA11 USB_D- | PB11 RX3 | PC11 Z2_EN +// PA12 USB_D+ | PB12 LED | PC12 Z2_STEP +// PA13 SWD_SDO | PB13 Z1_MAX | PC13 X_MIN +// PA14 SWD_SCK | PB14 Y_MAX | PC14 WIFI_RST +// PA15 SPI3_CS | PB15 PWR_DET | PC15 WIFI_CS +// PD0 Z2_DIR | PE0 Y_EN +// PD1 Z2_MIN | PE1 Y_STEP +// PD2 Z1_EN | PE2 Y_DIR +// PD3 Z1_STEP | PE3 Y_MIN +// PD4 Z1_DIR | PE4 X_DIR +// PD5 WIFI_RXD | PE5 X_STEP +// PD6 WIFI_TXD | PE6 X_EN +// PD7 Z1_MIN | PE7 AUX_SCL +// PD8 X_MAX | PE8 BTN_EN1 +// PD9 E3_DIR | PE9 LCD_SCK +// PD10 E3_STEP | PE10 LCD_MOSI +// PD11 E3_EN | PE11 BEEPER +// PD12 E2_DIR | PE12 LCD_EN +// PD13 E2_STEP | PE13 KILL +// PD14 E2_EN | PE14 BTN_EN2 +// PD15 E1_DIR | PE15 BTN_ENC + +//============================================================================= +// EXP1 connector +// MARK I/O ZONESTAR_LCD12864 REPRAPDISCOUNT_LCD12864 +// 10 RS PE13 KILL BTN_ENC +// 9 BP PE11 BEEP BEEP +// 8 EN PE12 DOGLCD_CS LCDRS +// 7 MOSI PE10 DOGLCD_SCK LCDE +// 6 EN1 PE8 BTN_EN1 NC +// 5 SCK PE9 DOGLCD_MOSI LCD4 +// 4 ENC PE15 BTN_ENC NC +// 3 EN2 PE14 BTN_EN2 NC +// 2 +5V +// 1 GND + +#define EXP1_03_PIN PE14 +#define EXP1_04_PIN PE15 +#define EXP1_05_PIN PE9 +#define EXP1_06_PIN PE8 +#define EXP1_07_PIN PE10 +#define EXP1_08_PIN PE12 +#define EXP1_09_PIN PE11 +#define EXP1_10_PIN PE13 + +// EXP2 connector +// MARK I/O ZONESTAR_LCD12864 REPRAPDISCOUNT_LCD12864 +// 10 SDA PC0 +// 9 SCL PE7 +// 8 RX1 PA9 UART1_RX +// 7 TX1 PA10 UART1_TX BTN_EN2 +// 6 CS3 PA15 +// 5 MISO3 PB4 BTN_EN1 +// 4 MOSI3 PB5 KILL +// 3 SCK3 PB3 +// 2 +5V +// 1 GND + +#define EXP2_03_PIN PB3 +#define EXP2_04_PIN PB5 +#define EXP2_05_PIN PB4 +#define EXP2_06_PIN PA15 +#define EXP2_07_PIN PA10 +#define EXP2_08_PIN PA9 +#define EXP2_09_PIN PE7 +#define EXP2_10_PIN PC0 + +// AUX1 connector +// 1 +5V +// 2 GND +// 3 RX3 PB11 UART3_RX +// 4 TX3 PB10 UART3_TX +// 5 SCL PE7 +// 6 SDA PC0 + +// WiFi +// 1 +5V +// 2 GND +// 3 WIFI_TXD PD5 UART2_RX +// 4 WIFI_RXD PD6 UART2_TX +// 5 WIFI_RST PC14 +// 6 WIFI_CS PC15 +//============================================================================= + +// +// Servos +// +#define SERVO0_PIN PB9 +//#define SERVO1_PIN PB8 +#define SERVO2_PIN PB7 +#define SERVO3_PIN PB6 + +// +// Limit Switches +// +#define X_MIN_PIN PC13 +#define Y_MIN_PIN PE3 +#define Z_MIN_PIN PD7 +#define X_MAX_PIN PD8 +#define Y_MAX_PIN PB14 +#define Z_MAX_PIN PB13 + +#ifdef OPTION_Z2_ENDSTOP + #define Z2_MIN_PIN PD1 + #define Z2_MAX_PIN PB12 +#endif + +// +// Steppers +// +#if ENABLED(COREXY) + #define X_ENABLE_PIN PE0 + #define X_STEP_PIN PE1 + #define X_DIR_PIN PE2 + + #define Y_ENABLE_PIN PE6 + #define Y_STEP_PIN PE5 + #define Y_DIR_PIN PE4 +#else + #define X_ENABLE_PIN PE6 + #define X_STEP_PIN PE5 + #define X_DIR_PIN PE4 + + #define Y_ENABLE_PIN PE0 + #define Y_STEP_PIN PE1 + #define Y_DIR_PIN PE2 +#endif + +#define Z_ENABLE_PIN PD2 +#define Z_STEP_PIN PD3 +#define Z_DIR_PIN PD4 + +#ifdef OPTION_DUALZ_DRIVE + #define Z2_ENABLE_PIN PC11 + #define Z2_STEP_PIN PC12 + #define Z2_DIR_PIN PD0 +#endif + +#ifdef OPTION_REPEAT_PRINTING + #define REPRINT_STOP_PIN PD8 // X_MAX_PIN + #define FORWARD_PIN PA13 + #define BACK_PIN PA14 +#endif + +#ifdef SWITCH_EXTRUDER_SEQUENCE + #define E3_ENABLE_PIN PC10 + #define E3_STEP_PIN PA8 + #define E3_DIR_PIN PC9 + + #define E2_STEP_PIN PC6 + #define E2_DIR_PIN PD15 + #define E2_ENABLE_PIN PC7 + + #define E1_STEP_PIN PD13 + #define E1_DIR_PIN PD12 + #define E1_ENABLE_PIN PD14 + + #define E0_STEP_PIN PD10 + #define E0_DIR_PIN PD9 + #define E0_ENABLE_PIN PD11 +#else + #define E0_ENABLE_PIN PC10 + #define E0_STEP_PIN PA8 + #define E0_DIR_PIN PC9 + + #define E1_STEP_PIN PC6 + #define E1_DIR_PIN PD15 + #define E1_ENABLE_PIN PC7 + + #define E2_STEP_PIN PD13 + #define E2_DIR_PIN PD12 + #define E2_ENABLE_PIN PD14 + + #define E3_STEP_PIN PD10 + #define E3_DIR_PIN PD9 + #define E3_ENABLE_PIN PD11 +#endif + +// +// Temperature Sensors +// +#define TEMP_0_PIN PC2 // TH0 +//#define TEMP_1_PIN PC1 // TH1 +#define TEMP_BED_PIN PC3 // TB1 + +// +// Heaters +// +#define HEATER_0_PIN PC5 // HEATER0 +//#define HEATER_1_PIN PB0 // HEATER1 +#define HEATER_BED_PIN PA2 // HOT BED + +// +// Fans +// +#define FAN_PIN PB1 // FAN1 +#define FAN1_PIN PB8 // FAN2 + +// +// Misc. Functions +// +//#define POWER_LOSS_PIN PB15 +#define LED_PIN PA0 +#define SUICIDE_PIN PA3 +#define FIL_RUNOUT_PIN PC8 + +// +// SD card +// +#define ENABLE_SPI1 +#define SD_DETECT_PIN PC4 +#define SD_SCK_PIN PA5 +#define SD_MISO_PIN PA6 +#define SD_MOSI_PIN PA7 +#define SD_SS_PIN PA4 + +// WiFi Functions +#define WIFI_RST PC15 +#define WIFI_EN PC14 + +#if ENABLED(ZONESTAR_12864LCD) + #define LCDSCREEN_NAME "ZONESTAR LCD12864" + #define LCD_PINS_RS EXP1_08_PIN // 7 CS make sure for zonestar zm3e4! + #define LCD_PINS_ENABLE EXP1_05_PIN // 6 DATA make sure for zonestar zm3e4! + #define LCD_PINS_D4 EXP1_07_PIN // 8 SCK make sure for zonestar zm3e4! + #define BEEPER_PIN EXP1_09_PIN + #define KILL_PIN -1 // EXP1_10_PIN + #define BTN_EN1 EXP1_06_PIN + #define BTN_EN2 EXP1_03_PIN + #define BTN_ENC EXP1_04_PIN +#elif ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define LCDSCREEN_NAME "REPRAPDISCOUNT LCD12864" + #define LCD_PINS_RS EXP2_08_PIN // 7 CS make sure for zonestar zm3e4! + #define LCD_PINS_ENABLE EXP2_05_PIN // 6 DATA make sure for zonestar zm3e4! + #define LCD_PINS_D4 EXP2_07_PIN // 8 SCK make sure for zonestar zm3e4! + #define BEEPER_PIN EXP2_10_PIN + #define KILL_PIN EXP2_09_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_06_PIN + #define BTN_ENC EXP2_04_PIN +#elif ENABLED(ZONESTAR_DWIN_LCD) + // Connect to EXP2 connector + #define LCDSCREEN_NAME "ZONESTAR DWIN LCD" + #define BEEPER_PIN EXP2_06_PIN // PE11 + #define KILL_PIN -1 // EXP1_10_PIN + #define BTN_EN2 EXP2_04_PIN // PE8 + #define BTN_EN1 EXP2_03_PIN // PE14 + #define BTN_ENC EXP2_05_PIN // PE15 +#endif + +#if HAS_MARLINUI_U8GLIB + #define BOARD_ST7920_DELAY_1 DELAY_NS(200) // Tclk_fall <200ns + #define BOARD_ST7920_DELAY_2 DELAY_NS(250) // Tdata_width >200ns + #define BOARD_ST7920_DELAY_3 DELAY_NS(200) // Tclk_rise <200ns +#endif + +// Remap SERVO0 PIN for BLTouch +#if ENABLED(BLTOUCH_ON_EXP1) + // BLTouch connected to EXP1 + #define BLTOUCH_PROBE_PIN EXP1_06_PIN + #define BLTOUCH_GND_PIN EXP1_04_PIN + #undef SERVO0_PIN + #define SERVO0_PIN EXP1_03_PIN +#elif ENABLED(BLTOUCH_ON_EXP2) + // BLTouch connected to EXP2 + #define BLTOUCH_PROBE_PIN EXP2_03_PIN + #define BLTOUCH_GND_PIN EXP2_04_PIN + #undef SERVO0_PIN + #define SERVO0_PIN EXP2_06_PIN +#else + #define BLTOUCH_PROBE_PIN PB13 // Z1_MAX +#endif diff --git a/Marlin/src/pins/stm32f4/env_validate.h b/Marlin/src/pins/stm32f4/env_validate.h new file mode 100644 index 000000000000..c01401f06c9a --- /dev/null +++ b/Marlin/src/pins/stm32f4/env_validate.h @@ -0,0 +1,28 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#if NOT_TARGET(STM32F4) && (DISABLED(ALLOW_STM32DUINO) || NOT_TARGET(STM32F4xx)) + #error "Oops! Select an STM32F4 board in 'Tools > Board.'" +#endif + +#undef ALLOW_STM32DUINO diff --git a/Marlin/src/pins/stm32f4/pins_ANET_ET4.h b/Marlin/src/pins/stm32f4/pins_ANET_ET4.h new file mode 100644 index 000000000000..d2ee2e013c3a --- /dev/null +++ b/Marlin/src/pins/stm32f4/pins_ANET_ET4.h @@ -0,0 +1,228 @@ +/** + * 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 + +#include "env_validate.h" + +#include "env_validate.h" + +#if HOTENDS > 1 || E_STEPPERS > 1 + #error "Anet ET4 only supports one hotend / E-stepper. Comment out this line to continue." +#endif + +#ifndef BOARD_INFO_NAME + #define BOARD_INFO_NAME "Anet ET4 1.x" +#endif + +// +// EEPROM +// + +// Use one of these or SDCard-based Emulation will be used +#if NO_EEPROM_SELECTED + //#define SRAM_EEPROM_EMULATION // Use BackSRAM-based EEPROM emulation + #define FLASH_EEPROM_EMULATION // Use Flash-based EEPROM emulation + //#define IIC_BL24CXX_EEPROM // Use I2C EEPROM onboard IC (AT24C04C, Size 4KB, PageSize 16B) +#endif + +#if ENABLED(FLASH_EEPROM_EMULATION) + // Decrease delays and flash wear by spreading writes across the + // 128 kB sector allocated for EEPROM emulation. + #define FLASH_EEPROM_LEVELING +#elif ENABLED(IIC_BL24CXX_EEPROM) + #define IIC_EEPROM_SDA PB11 + #define IIC_EEPROM_SCL PB10 + #define EEPROM_DEVICE_ADDRESS 0xA0 + #define MARLIN_EEPROM_SIZE 0x1000 // 4KB +#endif + +// +// Limit Switches +// +#define X_STOP_PIN PC13 +#define Y_STOP_PIN PE12 +#define Z_STOP_PIN PE11 + +// +// Z Probe +// +#if ENABLED(BLTOUCH) + #error "You will need to use 24V to 5V converter and remove one resistor and capacitor from the motherboard. See https://github.com/davidtgbe/Marlin/blob/bugfix-2.0.x/docs/Tutorials/bltouch-en.md for more information. Comment out this line to proceed at your own risk." + #define SERVO0_PIN PC3 +#elif !defined(Z_MIN_PROBE_PIN) + #define Z_MIN_PROBE_PIN PC3 +#endif + +// +// Filament Runout Sensor +// +#ifndef FIL_RUNOUT_PIN + #define FIL_RUNOUT_PIN PA2 +#endif + +// +// Power Loss Detection +// +#ifndef POWER_LOSS_PIN + #define POWER_LOSS_PIN PA8 +#endif + +// +// LED PIN +// +#define LED_PIN PD12 + +// +// Steppers +// +#define X_STEP_PIN PB6 +#define X_DIR_PIN PB5 +#define X_ENABLE_PIN PB7 + +#define Y_STEP_PIN PB3 +#define Y_DIR_PIN PD6 +#define Y_ENABLE_PIN PB4 + +#define Z_STEP_PIN PA12 +#define Z_DIR_PIN PA11 +#define Z_ENABLE_PIN PA15 + +#define E0_STEP_PIN PB9 +#define E0_DIR_PIN PB8 +#define E0_ENABLE_PIN PE0 + +// +// Temperature Sensors +// +#define TEMP_0_PIN PA1 +#define TEMP_BED_PIN PA4 + +// +// Heaters +// +#define HEATER_0_PIN PA0 +#define HEATER_BED_PIN PE2 + +// +// Fans +// +#define FAN_PIN PE3 // Layer fan +#define FAN1_PIN PE1 // Hotend fan + +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN FAN1_PIN +#endif + +// +// LCD / Controller +// +#if HAS_SPI_TFT || HAS_FSMC_TFT + #define TFT_RESET_PIN PE6 + #define TFT_CS_PIN PD7 + #define TFT_RS_PIN PD13 + + #if HAS_FSMC_TFT + #define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT + #define FSMC_CS_PIN TFT_CS_PIN + #define FSMC_RS_PIN TFT_RS_PIN + #define TFT_INTERFACE_FSMC_8BIT + #endif +#endif + +// +// Touch Screen +// https://ldm-systems.ru/f/doc/catalog/HY-TFT-2,8/XPT2046.pdf +// +#if NEED_TOUCH_PINS + #define TOUCH_CS_PIN PB2 + #define TOUCH_SCK_PIN PB0 + #define TOUCH_MOSI_PIN PE5 + #define TOUCH_MISO_PIN PE4 + #define TOUCH_INT_PIN PB1 +#endif + +#if ENABLED(ANET_ET5_TFT35) + #ifndef TOUCH_CALIBRATION_X + #define TOUCH_CALIBRATION_X 17125 + #endif + #ifndef TOUCH_CALIBRATION_Y + #define TOUCH_CALIBRATION_Y -11307 + #endif + #ifndef TOUCH_OFFSET_X + #define TOUCH_OFFSET_X -26 + #endif + #ifndef TOUCH_OFFSET_Y + #define TOUCH_OFFSET_Y 337 + #endif + #ifndef TOUCH_ORIENTATION + #define TOUCH_ORIENTATION TOUCH_PORTRAIT + #endif +#elif ENABLED(ANET_ET4_TFT28) + #ifndef TOUCH_CALIBRATION_X + #define TOUCH_CALIBRATION_X -11838 + #endif + #ifndef TOUCH_CALIBRATION_Y + #define TOUCH_CALIBRATION_Y 8776 + #endif + #ifndef TOUCH_OFFSET_X + #define TOUCH_OFFSET_X 333 + #endif + #ifndef TOUCH_OFFSET_Y + #define TOUCH_OFFSET_Y -17 + #endif + #ifndef TOUCH_ORIENTATION + #define TOUCH_ORIENTATION TOUCH_PORTRAIT + #endif +#endif + +// +// SD Card +// +//#define SDIO_SUPPORT + +#ifndef SDCARD_CONNECTION + #define SDCARD_CONNECTION CUSTOM_CABLE +#endif + +#if ENABLED(SDSUPPORT) + + #define SDIO_D0_PIN PC8 + #define SDIO_D1_PIN PC9 + #define SDIO_D2_PIN PC10 + #define SDIO_D3_PIN PC11 + #define SDIO_CK_PIN PC12 + #define SDIO_CMD_PIN PD2 + + #if DISABLED(SDIO_SUPPORT) + #define SOFTWARE_SPI + #define SDSS SDIO_D3_PIN + #define SD_SCK_PIN SDIO_CK_PIN + #define SD_MISO_PIN SDIO_D0_PIN + #define SD_MOSI_PIN SDIO_CMD_PIN + #endif + + #ifndef SD_DETECT_PIN + #define SD_DETECT_PIN PD3 + #endif + +#endif diff --git a/Marlin/src/pins/stm32f4/pins_ANET_ET4P.h b/Marlin/src/pins/stm32f4/pins_ANET_ET4P.h new file mode 100644 index 000000000000..f5ebf82a4858 --- /dev/null +++ b/Marlin/src/pins/stm32f4/pins_ANET_ET4P.h @@ -0,0 +1,34 @@ +/** + * 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 BOARD_INFO_NAME "Anet ET4P 1.x" + +// +// TMC2208 Configuration_adv defaults for Anet ET4P-MB_V1.x +// +#if !AXIS_DRIVER_TYPE_X(TMC2208_STANDALONE) || !AXIS_DRIVER_TYPE_Y(TMC2208_STANDALONE) || !AXIS_DRIVER_TYPE_Z(TMC2208_STANDALONE) || !AXIS_DRIVER_TYPE_E0(TMC2208_STANDALONE) + #error "ANET_ET4P requires ([XYZ]|E0)_DRIVER_TYPE set to TMC2208_STANDALONE." +#endif + +#include "pins_ANET_ET4.h" diff --git a/Marlin/src/pins/stm32f4/pins_ARMED.h b/Marlin/src/pins/stm32f4/pins_ARMED.h index db57db14d549..a67af089f20a 100644 --- a/Marlin/src/pins/stm32f4/pins_ARMED.h +++ b/Marlin/src/pins/stm32f4/pins_ARMED.h @@ -24,9 +24,9 @@ #pragma once -#if NOT_TARGET(STM32F4) - #error "Oops! Select an STM32F4 board in 'Tools > Board.'" -#elif HOTENDS > 2 || E_STEPPERS > 2 +#include "env_validate.h" + +#if HOTENDS > 2 || E_STEPPERS > 2 #error "Arm'ed supports up to 2 hotends / E-steppers." #endif diff --git a/Marlin/src/pins/stm32f4/pins_BEAST.h b/Marlin/src/pins/stm32f4/pins_BEAST.h deleted file mode 100644 index 268b7b59cd45..000000000000 --- a/Marlin/src/pins/stm32f4/pins_BEAST.h +++ /dev/null @@ -1,285 +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 - -#if NOT_TARGET(__STM32F1__, __STM32F4__) - #error "Oops! Select an STM32F1/4 board in 'Tools > Board.'" -#endif - -/** - * 21017 Victor Perez Marlin for stm32f1 test - */ - -#define BOARD_INFO_NAME "Beast STM32" -#define DEFAULT_MACHINE_NAME "STM32F103RET6" - -// Enable I2C_EEPROM for testing -#define I2C_EEPROM - -// Ignore temp readings during development. -//#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 - -// -// Steppers -// -#define X_STEP_PIN PE0 -#define X_DIR_PIN PE1 -#define X_ENABLE_PIN PC0 -#define X_MIN_PIN PD5 -#define X_MAX_PIN -1 - -#define Y_STEP_PIN PE2 -#define Y_DIR_PIN PE3 -#define Y_ENABLE_PIN PC1 -#define Y_MIN_PIN PD6 -#define Y_MAX_PIN - -#define Z_STEP_PIN PE4 -#define Z_DIR_PIN PE5 -#define Z_ENABLE_PIN PC2 -#define Z_MIN_PIN PD7 -#define Z_MAX_PIN -1 - -#define Y2_STEP_PIN -1 -#define Y2_DIR_PIN -1 -#define Y2_ENABLE_PIN -1 - -#define Z2_STEP_PIN -1 -#define Z2_DIR_PIN -1 -#define Z2_ENABLE_PIN -1 - -#define E0_STEP_PIN PE6 -#define E0_DIR_PIN PE7 -#define E0_ENABLE_PIN PC3 - -/** - * TODO: Currently using same Enable pin to all steppers. - */ - -#define E1_STEP_PIN PE8 -#define E1_DIR_PIN PE9 -#define E1_ENABLE_PIN PC4 - -#define E2_STEP_PIN PE10 -#define E2_DIR_PIN PE11 -#define E2_ENABLE_PIN PC5 - -// -// Misc. Functions -// -#define SDSS PA15 -#define LED_PIN PB2 - -#define PS_ON_PIN -1 -#define KILL_PIN -1 - -// -// Heaters / Fans -// -#define HEATER_0_PIN PD12 // EXTRUDER 1 -#define HEATER_1_PIN PD13 -#define HEATER_2_PIN PD14 - -#define HEATER_BED_PIN PB9 // BED -#define HEATER_BED2_PIN -1 // BED2 -#define HEATER_BED3_PIN -1 // BED3 - -#ifndef FAN_PIN - #define FAN_PIN PB10 -#endif - -#define FAN_SOFT_PWM - -// -// Temperature Sensors -// -#define TEMP_BED_PIN PA0 // Analog Input -#define TEMP_0_PIN PA1 // Analog Input -#define TEMP_1_PIN PA2 // Analog Input -#define TEMP_2_PIN PA3 // Analog Input - -// -// LCD Pins -// -#if HAS_WIRED_LCD - - #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 - #elif BOTH(NEWPANEL, PANEL_ONE) - #define LCD_PINS_RS PB8 - #define LCD_PINS_ENABLE 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_D4 PB12 - #define LCD_PINS_D5 PB13 - #define LCD_PINS_D6 PB14 - #define LCD_PINS_D7 PB15 - #if DISABLED(NEWPANEL) - #define BEEPER_PIN 33 - // Buttons attached to a shift register - // Not wired yet - //#define SHIFT_CLK 38 - //#define SHIFT_LD 42 - //#define SHIFT_OUT 40 - //#define SHIFT_EN 17 - #endif - #endif - - #if ENABLED(NEWPANEL) - - #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) - - #define BEEPER_PIN 37 - - #define BTN_EN1 31 - #define BTN_EN2 33 - #define BTN_ENC 35 - - #define SD_DETECT_PIN 49 - #define KILL_PIN 41 - - #if ENABLED(BQ_LCD_SMART_CONTROLLER) - #define LCD_BACKLIGHT_PIN 39 - #endif - - #elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - - #define BTN_EN1 64 - #define BTN_EN2 59 - #define BTN_ENC 63 - #define SD_DETECT_PIN 42 - - #elif ENABLED(LCD_I2C_PANELOLU2) - - #define BTN_EN1 47 - #define BTN_EN2 43 - #define BTN_ENC 32 - #define LCD_SDSS 53 - #define SD_DETECT_PIN -1 - #define KILL_PIN 41 - - #elif ENABLED(LCD_I2C_VIKI) - - #define BTN_EN1 22 // https://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42. - #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 - - #elif ANY(VIKI2, miniVIKI) - - #define BEEPER_PIN 33 - - // Pins for DOGM SPI LCD Support - #define DOGLCD_A0 44 - #define DOGLCD_CS 45 - #define LCD_SCREEN_ROT_180 - - #define BTN_EN1 22 - #define BTN_EN2 7 - #define BTN_ENC 39 - - #define SDSS 53 - #define SD_DETECT_PIN -1 // Pin 49 for display sd interface, 72 for easy adapter board - - #define KILL_PIN 31 - - #define STAT_LED_RED_PIN 32 - #define STAT_LED_BLUE_PIN 35 - - #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) - - #define BTN_EN1 35 - #define BTN_EN2 37 - #define BTN_ENC 31 - #define SD_DETECT_PIN 49 - #define LCD_SDSS 53 - #define KILL_PIN 41 - #define BEEPER_PIN 23 - #define DOGLCD_CS 29 - #define DOGLCD_A0 27 - #define LCD_BACKLIGHT_PIN 33 - - #elif ENABLED(MINIPANEL) - - #define BEEPER_PIN 42 - // Pins for DOGM SPI LCD Support - #define DOGLCD_A0 44 - #define DOGLCD_CS 66 - #define LCD_BACKLIGHT_PIN 65 // backlight LED on A11/D65 - #define SDSS 53 - - #define KILL_PIN 64 - // GLCD features - // Uncomment screen orientation - //#define LCD_SCREEN_ROT_90 - //#define LCD_SCREEN_ROT_180 - //#define LCD_SCREEN_ROT_270 - // The encoder and click button - #define BTN_EN1 40 - #define BTN_EN2 63 - #define BTN_ENC 59 - // not connected to a pin - #define SD_DETECT_PIN 49 - - #else - - // Beeper on AUX-4 - #define BEEPER_PIN 33 - - // Buttons directly attached to AUX-2 - #if ENABLED(REPRAPWORLD_KEYPAD) - #define BTN_EN1 64 - #define BTN_EN2 59 - #define BTN_ENC 63 - #define SHIFT_OUT 40 - #define SHIFT_CLK 44 - #define SHIFT_LD 42 - #elif ENABLED(PANEL_ONE) - #define BTN_EN1 59 // AUX2 PIN 3 - #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 - #endif - - #if ENABLED(G3D_PANEL) - #define SD_DETECT_PIN 49 - #define KILL_PIN 41 - #else - //#define SD_DETECT_PIN -1 // Ramps doesn't use this - #endif - - #endif - #endif // NEWPANEL - -#endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h b/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h index b13d495542f8..d8a83bef3a89 100644 --- a/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h +++ b/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h @@ -27,9 +27,10 @@ * Shield - https://github.com/jmz52/Hardware */ -#if NOT_TARGET(STM32F4, STM32F4xx) - #error "Oops! Select an STM32F4 board in 'Tools > Board.'" -#elif HOTENDS > 2 || E_STEPPERS > 2 +#define ALLOW_STM32DUINO +#include "env_validate.h" + +#if HOTENDS > 2 || E_STEPPERS > 2 #error "Black STM32F4VET6 supports up to 2 hotends / E-steppers." #endif @@ -132,6 +133,10 @@ #define DOGLCD_CS LCD_PINS_D5 #define DOGLCD_A0 LCD_PINS_D6 +#if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder +#endif + // // Onboard SD support // @@ -152,8 +157,8 @@ #ifndef SDIO_SUPPORT #define SOFTWARE_SPI // Use soft SPI for onboard SD #define SDSS SDIO_D3_PIN - #define SCK_PIN SDIO_CK_PIN - #define MISO_PIN SDIO_D0_PIN - #define MOSI_PIN SDIO_CMD_PIN + #define SD_SCK_PIN SDIO_CK_PIN + #define SD_MISO_PIN SDIO_D0_PIN + #define SD_MOSI_PIN SDIO_CMD_PIN #endif #endif diff --git a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h index c37f6cce0445..408048bfe249 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h @@ -21,10 +21,10 @@ */ #pragma once -#if NOT_TARGET(STM32F4) - #error "Oops! Select an STM32F4 board in 'Tools > Board.'" -#elif HOTENDS > 1 || E_STEPPERS > 1 - #error "BIGTREE BTT002 V1.0 supports up to 1 hotends / E-steppers." +#include "env_validate.h" + +#if HOTENDS > 1 || E_STEPPERS > 1 + #error "BIGTREE BTT002 V1.0 only supports one hotend / E-stepper. Comment out this line to continue." #endif #define BOARD_INFO_NAME "BTT BTT002 V1.0" @@ -172,68 +172,119 @@ #define FAN_PIN PB8 // Fan1 #define FAN1_PIN PB9 // Fan0 -// HAL SPI1 pins -#define CUSTOM_SPI_PINS -#if ENABLED(CUSTOM_SPI_PINS) - #define SCK_PIN PA5 // SPI1 SCLK - #define SS_PIN PA4 // SPI1 SSEL - #define MISO_PIN PA6 // SPI1 MISO - #define MOSI_PIN PA7 // SPI1 MOSI -#endif - -// -// Misc. Functions -// -#define SDSS PA4 - /** - * -------------------------------------BTT002 V1.0-------------------------------------------- - * ----- ----- | - * PA3 | · · | GND 5V | · · | GND | - * NRESET | · · | PC4(SD_DET) (LCD_D7) PE13 | · · | PE12 (LCD_D6) | - * (MOSI)PA7 | · · | PB0(BTN_EN2) (LCD_D5) PE11 | · · | PE10 (LCD_D4) | - * (SD_SS)PA4 | · · | PC5(BTN_EN1) (LCD_RS) PE8 | · · | PE9 (LCD_EN) | - * (SCK)PA5 | · · | PA6(MISO) (BTN_ENC) PB1 | · · | PE7 (BEEPER) | - * ----- ----- | - * EXP2 EXP1 | - * -------------------------------------------------------------------------------------------- + * -----------------------------------BTT002 V1.0---------------------------------------- + * ------ ------ | + * PA3 | 1 2 | GND 5V | 1 2 | GND | + * NRESET | 3 4 | PC4 (SD_DET) (LCD_D7) PE13 | 3 4 | PE12 (LCD_D6) | + * (MOSI) PA7 | 5 6 | PB0 (BTN_EN2) (LCD_D5) PE11 | 5 6 | PE10 (LCD_D4) | + * (SD_SS) PA4 | 7 8 | PC5 (BTN_EN1) (LCD_RS) PE8 | 7 8 | PE9 (LCD_EN) | + * (SCK) PA5 | 9 10 | PA6 (MISO) (BTN_ENC) PB1 | 9 10 | PE7 (BEEPER) | + * ------ ------ | + * EXP2 EXP1 | + * -------------------------------------------------------------------------------------- */ +#define EXP1_03_PIN PE13 +#define EXP1_04_PIN PE12 +#define EXP1_05_PIN PE11 +#define EXP1_06_PIN PE10 +#define EXP1_07_PIN PE8 +#define EXP1_08_PIN PE9 +#define EXP1_09_PIN PB1 +#define EXP1_10_PIN PE7 + +#define EXP2_01_PIN PA3 +#define EXP2_03_PIN -1 +#define EXP2_04_PIN PC4 +#define EXP2_05_PIN PA7 +#define EXP2_06_PIN PB0 +#define EXP2_07_PIN PA4 +#define EXP2_08_PIN PC5 +#define EXP2_09_PIN PA5 +#define EXP2_10_PIN PA6 + +// HAL SPI1 pins +#define SD_SCK_PIN EXP2_09_PIN // SPI1 SCLK +#define SD_SS_PIN EXP2_07_PIN // SPI1 SSEL +#define SD_MISO_PIN EXP2_10_PIN // SPI1 MISO +#define SD_MOSI_PIN EXP2_05_PIN // SPI1 MOSI + +#define SDSS EXP2_07_PIN + // // LCDs and Controllers // #if HAS_WIRED_LCD - #define BEEPER_PIN PE7 - #define BTN_ENC PB1 + #define BEEPER_PIN EXP1_10_PIN + #define BTN_ENC EXP1_09_PIN + + #define SD_DETECT_PIN EXP2_04_PIN #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS PE12 + #define LCD_PINS_RS EXP1_04_PIN + + #define BTN_EN1 EXP1_08_PIN + #define BTN_EN2 EXP1_06_PIN + + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN - #define BTN_EN1 PE9 - #define BTN_EN2 PE10 + #elif ENABLED(MKS_MINI_12864) - #define LCD_PINS_ENABLE PE13 - #define LCD_PINS_D4 PE11 + #define DOGLCD_A0 EXP1_04_PIN + #define DOGLCD_CS EXP1_05_PIN + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN #else - #define LCD_PINS_RS PE8 + #define LCD_PINS_RS EXP1_07_PIN - #define BTN_EN1 PC5 - #define BTN_EN2 PB0 - #define SD_DETECT_PIN PC4 + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN - #define LCD_SDSS PA4 + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN - #define LCD_PINS_ENABLE PE9 - #define LCD_PINS_D4 PE10 + #if ENABLED(FYSETC_MINI_12864) + #define DOGLCD_CS EXP1_08_PIN + #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_MOSI EXP2_05_PIN + #define DOGLCD_MISO EXP2_10_PIN + #define DOGLCD_SCK EXP2_09_PIN - #if ENABLED(ULTIPANEL) - #define LCD_PINS_D5 PE11 - #define LCD_PINS_D6 PE12 - #define LCD_PINS_D7 PE13 - #endif + #define LCD_BACKLIGHT_PIN -1 + + #define FORCE_SOFT_SPI + #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) + #ifndef RGB_LED_R_PIN + #define RGB_LED_R_PIN EXP1_05_PIN + #endif + #ifndef RGB_LED_G_PIN + #define RGB_LED_G_PIN EXP1_04_PIN + #endif + #ifndef RGB_LED_B_PIN + #define RGB_LED_B_PIN EXP1_03_PIN + #endif + #elif ENABLED(FYSETC_MINI_12864_2_1) + #define NEOPIXEL_PIN EXP1_05_PIN + #endif + #endif // !FYSETC_MINI_12864 + + #if IS_ULTIPANEL + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_04_PIN + #define LCD_PINS_D7 EXP1_03_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 // Alter timing for graphical display diff --git a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h new file mode 100644 index 000000000000..a806611c18fd --- /dev/null +++ b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h @@ -0,0 +1,393 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#if NOT_TARGET(STM32F4) + #error "Oops! Select an STM32F4 board in 'Tools > Board.'" +#endif + +#ifndef BOARD_INFO_NAME + #define BOARD_INFO_NAME "BTT E3 RRF" +#endif + +// Add-on board for IDEX conversion +//#define BTT_E3_RRF_IDEX_BOARD + +// Onboard I2C EEPROM +#define I2C_EEPROM +#define MARLIN_EEPROM_SIZE 0x1000 // 4KB + +// +// Servos +// +#define SERVO0_PIN PB0 // SERVOS + +// +// Limit Switches +// +#define X_STOP_PIN PC0 // X-STOP +#define Y_STOP_PIN PC1 // Y-STOP +#define Z_STOP_PIN PC2 // Z-STOP + +#if ENABLED(BTT_E3_RRF_IDEX_BOARD) + #if X2_USE_ENDSTOP == _XMAX_ + #define X_MAX_PIN FPC2_PIN // X2-STOP + #elif X2_USE_ENDSTOP == _XMIN_ + #define X_MIN_PIN FPC2_PIN // X2-STOP + #endif +#endif + +// +// Z Probe must be this pin +// +#define Z_MIN_PROBE_PIN PC5 // PROBE + +// +// Filament Runout Sensor +// +#ifndef FIL_RUNOUT_PIN + #define FIL_RUNOUT_PIN PC3 // E0-STOP +#endif + +#if !defined(FIL1_RUNOUT2_PIN) && ENABLED(BTT_E3_RRF_IDEX_BOARD) + #define FIL_RUNOUT2_PIN FPC3_PIN // E1-STOP +#endif + +// +// Power-loss Detection +// +#ifndef POWER_LOSS_PIN + #define POWER_LOSS_PIN PE0 // Power Loss Detection: PWR-DET +#endif + +// +// Steppers +// +#define X_ENABLE_PIN PD7 +#define X_STEP_PIN PD5 +#define X_DIR_PIN PD4 + +#define Y_ENABLE_PIN PD3 +#define Y_STEP_PIN PD0 +#define Y_DIR_PIN PA15 + +#define Z_ENABLE_PIN PD14 +#define Z_STEP_PIN PC6 +#define Z_DIR_PIN PC7 + +#define E0_ENABLE_PIN PD10 +#define E0_STEP_PIN PD12 +#define E0_DIR_PIN PD13 + +#if ENABLED(BTT_E3_RRF_IDEX_BOARD) + #define E1_ENABLE_PIN FPC7_PIN // E1EN + #define E1_STEP_PIN FPC5_PIN // E1STP + #define E1_DIR_PIN FPC4_PIN // E1DIR + + #define X2_ENABLE_PIN FPC13_PIN // X2EN + #define X2_STEP_PIN FPC11_PIN // X2STP + #define X2_DIR_PIN FPC10_PIN // X2DIR +#endif + +/** + * TMC2208/TMC2209 stepper drivers + */ +#if HAS_TMC_UART + // + // Software serial + // + #define X_SERIAL_TX_PIN PD6 + #define X_SERIAL_RX_PIN PD6 + + #define Y_SERIAL_TX_PIN PD1 + #define Y_SERIAL_RX_PIN PD1 + + #define Z_SERIAL_TX_PIN PD15 + #define Z_SERIAL_RX_PIN PD15 + + #define E0_SERIAL_TX_PIN PD11 + #define E0_SERIAL_RX_PIN PD11 + + #if ENABLED(BTT_E3_RRF_IDEX_BOARD) + #define X2_SERIAL_TX_PIN FPC12_PIN // X2UART + #define X2_SERIAL_RX_PIN FPC12_PIN // X2UART + + #define E1_SERIAL_TX_PIN FPC6_PIN // E1UART + #define E1_SERIAL_RX_PIN FPC6_PIN // E1UART + #endif + + // Reduce baud rate to improve software serial reliability + #define TMC_BAUD_RATE 19200 +#endif + +// +// Temperature Sensors +// +#define TEMP_BED_PIN PA1 // Analog Input "TB" +#define TEMP_0_PIN PA0 // Analog Input "TH0" + +#if ENABLED(BTT_E3_RRF_IDEX_BOARD) + #define TEMP_1_PIN FPC9_PIN // Analog Input "TH1" + #define PT100_PIN FPC8_PIN // Analog Input "PT100" (INA826) +#endif + +// +// Heaters / Fans +// +#define HEATER_BED_PIN PB4 // "HB" +#define HEATER_0_PIN PB3 // "HE0" + +#if ENABLED(BTT_E3_RRF_IDEX_BOARD) + #define HEATER_1_PIN FPC16_PIN // "HE1" +#endif + +#define FAN_PIN PB5 // "FAN0" + +#ifndef CONTROLLER_FAN_PIN + #define CONTROLLER_FAN_PIN PB6 // "FAN1" +#endif + +#if ENABLED(BTT_E3_RRF_IDEX_BOARD) + #define FAN1_PIN FPC15_PIN // "FAN0" in IDEX board + #define FAN2_PIN FPC14_PIN // "FAN1" in IDEX board +#else + //#define FAN1_PIN PB6 // "FAN1" +#endif + +// +// Misc. Functions +// +#ifndef NEOPIXEL_PIN + #define NEOPIXEL_PIN PB7 // LED driving pin +#endif + +#ifndef PS_ON_PIN + #define PS_ON_PIN PE1 // Power Supply Control +#endif + +/** + * BTT E3 RRF + * _____ + * 5V | 1 2 | GND + * (LCD_EN) PE11 | 3 4 | PB1 (LCD_RS) + * (LCD_D4) PE10 | 5 6 PB2 (BTN_EN2) + * RESET | 7 8 | PE7 (BTN_EN1) + * (BTN_ENC) PE9 | 9 10| PE8 (BEEPER) + * ----- + * EXP1 + */ + +#if HAS_WIRED_LCD + + #if ENABLED(CR10_STOCKDISPLAY) + + #define BEEPER_PIN PE8 + #define BTN_ENC PE9 + + #define BTN_EN1 PE7 + #define BTN_EN2 PB2 + + #define LCD_PINS_RS PB1 + #define LCD_PINS_ENABLE PE11 + #define LCD_PINS_D4 PE10 + + // CR10_STOCKDISPLAY default timing is too fast + #undef BOARD_ST7920_DELAY_1 + #undef BOARD_ST7920_DELAY_2 + #undef BOARD_ST7920_DELAY_3 + + #elif ENABLED(ZONESTAR_LCD) // ANET A8 LCD Controller - Must convert to 3.3V - CONNECTING TO 5V WILL DAMAGE THE BOARD! + + #error "CAUTION! ZONESTAR_LCD requires wiring modifications. See 'pins_BTT_E3_RRF.h' for details. Comment out this line to continue." + + #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 ADC_KEYPAD_PIN PB0 // Repurpose servo pin for ADC - CONNECTING TO 5V WILL DAMAGE THE BOARD! + + #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) + + #define BTN_ENC PE9 + #define BTN_EN1 PE7 + #define BTN_EN2 PB2 + + #define DOGLCD_CS PB1 + #define DOGLCD_A0 PE10 + #define DOGLCD_SCK PE8 + #define DOGLCD_MOSI PE11 + + #define FORCE_SOFT_SPI + #define LCD_BACKLIGHT_PIN -1 + + #elif IS_TFTGLCD_PANEL + + #if ENABLED(TFTGLCD_PANEL_SPI) + + #error "CAUTION! TFTGLCD_PANEL_SPI requires wiring modifications. See 'pins_BTT_E3_RRF.h' for details. Comment out this line to continue." + + /** + * TFTGLCD_PANEL_SPI display pinout + * + * Board Display + * _____ _____ + * 5V | 1 2 | GND (SPI1-MISO) MISO | 1 2 | SCK (SPI1-SCK) + * (FREE) PE11 | 3 4 | PB1 (LCD_CS) (PE7) LCD_CS | 3 4 | SD_CS (PB2) + * (FREE) PE10 | 5 6 | PB2 (SD_CS) (FREE) | 5 6 | MOSI (SPI1-MOSI) + * RESET | 7 8 | PE7 (MOD_RESET) (PE8) SD_DET | 7 8 | (FREE) + * (BEEPER) PE9 | 9 10| PE8 (SD_DET) GND | 9 10| 5V + * ----- ----- + * EXP1 EXP1 + * + * Needs custom cable: + * + * Board Adapter Display + * _________ + * EXP1-1 ----------- EXP1-10 + * EXP1-2 ----------- EXP1-9 + * SPI1-4 ----------- EXP1-6 + * EXP1-4 ----------- FREE + * SPI1-3 ----------- EXP1-2 + * EXP1-6 ----------- EXP1-4 + * EXP1-7 ----------- FREE + * EXP1-8 ----------- EXP1-3 + * SPI1-1 ----------- EXP1-1 + * EXP1-10 ----------- EXP1-7 + */ + + #define TFTGLCD_CS PE7 + + #endif + + #else + #error "Only CR10_STOCKDISPLAY, ZONESTAR_LCD, ENDER2_STOCKDISPLAY, MKS_MINI_12864, and TFTGLCD_PANEL_(SPI|I2C) are currently supported on the BTT_E3_RRF." + #endif + + // Alter timing for graphical display + #if HAS_MARLINUI_U8GLIB + #ifndef BOARD_ST7920_DELAY_1 + #define BOARD_ST7920_DELAY_1 DELAY_NS(96) + #endif + #ifndef BOARD_ST7920_DELAY_2 + #define BOARD_ST7920_DELAY_2 DELAY_NS(48) + #endif + #ifndef BOARD_ST7920_DELAY_3 + #define BOARD_ST7920_DELAY_3 DELAY_NS(600) + #endif + #endif + +#endif // HAS_WIRED_LCD + +#if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) + + #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_BTT_E3_RRF.h' for details. Comment out this line to continue." + + /** FYSETC TFT TFT81050 display pinout + * + * Board Display + * _____ _____ + * 5V | 1 2 | GND (SPI1-MISO) MISO | 1 2 | SCK (SPI1-SCK) + * (FREE) PE11 | 3 4 | PB1 (LCD_CS) (PE7) MOD_RESET | 3 4 | SD_CS (PB2) + * (FREE) PE10 | 5 6 | PB2 (SD_CS) (PB1) LCD_CS | 5 6 | MOSI (SPI1-MOSI) + * RESET | 7 8 | PE7 (MOD_RESET) (PE8) SD_DET | 7 8 | RESET + * (BEEPER) PE9 | 9 10| PE8 (SD_DET) GND | 9 10| 5V + * ----- ----- + * EXP1 EXP1 + * + * Needs custom cable: + * + * Board Adapter Display + * _________ + * EXP1-1 ----------- EXP1-10 + * EXP1-2 ----------- EXP1-9 + * SPI1-4 ----------- EXP1-6 + * EXP1-4 ----------- EXP1-5 + * SPI1-3 ----------- EXP1-2 + * EXP1-6 ----------- EXP1-4 + * EXP1-7 ----------- EXP1-8 + * EXP1-8 ----------- EXP1-3 + * SPI1-1 ----------- EXP1-1 + * EXP1-10 ----------- EXP1-7 + */ + + #define CLCD_SPI_BUS 1 // SPI1 connector + + #define BEEPER_PIN PE9 + + #define CLCD_MOD_RESET PE7 + #define CLCD_SPI_CS PB1 + +#endif // TOUCH_UI_FTDI_EVE && LCD_FYSETC_TFT81050 + +// +// SD Support +// + +#ifndef SDCARD_CONNECTION + #define SDCARD_CONNECTION ONBOARD +#endif + +#if SD_CONNECTION_IS(ONBOARD) + #define SDIO_SUPPORT // Use SDIO for onboard SD + #define SDIO_D0_PIN PC8 + #define SDIO_D1_PIN PC9 + #define SDIO_D2_PIN PC10 + #define SDIO_D3_PIN PC11 + #define SDIO_CK_PIN PC12 + #define SDIO_CMD_PIN PD2 + + //#define SDIO_CLOCK 48000000 + #define SD_DETECT_PIN PC4 +#elif SD_CONNECTION_IS(CUSTOM_CABLE) + #error "SD CUSTOM_CABLE is not compatible with BTT E3 RRF." +#endif + +// +// WIFI +// + +#define ESP_WIFI_MODULE_COM 3 // 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 +#define ESP_WIFI_MODULE_RESET_PIN PA4 +#define ESP_WIFI_MODULE_ENABLE_PIN PA5 +#define ESP_WIFI_MODULE_GPIO0_PIN PA6 + +#if ENABLED(BTT_E3_RRF_IDEX_BOARD) + #define FPC2_PIN PB11 + #define FPC3_PIN PB10 + #define FPC4_PIN PE12 + #define FPC5_PIN PE13 + #define FPC6_PIN PE14 + #define FPC7_PIN PE15 + #define FPC8_PIN PA3 + #define FPC9_PIN PA2 + #define FPC10_PIN PA8 + #define FPC11_PIN PC15 + #define FPC12_PIN PC14 + #define FPC13_PIN PC13 + #define FPC14_PIN PE6 + #define FPC15_PIN PE5 + #define FPC16_PIN PE4 + #define FPC17_PIN PE3 +#endif 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 dc8ce9f2d1b2..3151a38ae8f9 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h @@ -21,12 +21,12 @@ */ #pragma once -#if NOT_TARGET(STM32F4) - #error "Oops! Select an STM32F4 board in 'Tools > Board.'" +#include "env_validate.h" + +#if E_STEPPERS > MAX_E_STEPPERS + #error "Marlin extruder/hotends limit! Increase MAX_E_STEPPERS to continue." #elif HOTENDS > 8 || E_STEPPERS > 8 #error "BIGTREE GTR V1.0 supports up to 8 hotends / E-steppers." -#elif HOTENDS > MAX_EXTRUDERS || E_STEPPERS > MAX_EXTRUDERS - #error "Marlin extruder/hotends limit! Increase MAX_EXTRUDERS to continue." #endif #define BOARD_INFO_NAME "BTT GTR V1.0" @@ -35,37 +35,86 @@ #define I2C_EEPROM #define MARLIN_EEPROM_SIZE 0x2000 // 8KB (24C64 ... 64Kb = 8KB) -#define TP // Enable to define servo and probe pins +// USB Flash Drive support +#define HAS_OTG_USB_HOST_SUPPORT + +#define M5_EXTENDER // The M5 extender is attached // // Servos // -#if ENABLED(TP) - #define SERVO0_PIN PB11 +#define SERVO0_PIN PB11 // BLTOUCH +#define SOL0_PIN PC7 // Toolchanger + +#if ENABLED(TOOL_SENSOR) + #define TOOL_SENSOR1_PIN PH6 + #define TOOL_SENSOR2_PIN PI4 + //#define TOOL_SENSOR3_PIN PF4 +#else + #define PS_ON_PIN PH6 #endif -#define PS_ON_PIN PH6 +// +// Trinamic Stallguard pins +// +#define X_DIAG_PIN PF2 // X- +#define Y_DIAG_PIN PC13 // Y- +#define Z_DIAG_PIN PE0 // Z- +#define E0_DIAG_PIN PG14 // X+ +#define E1_DIAG_PIN PG9 // Y+ +#define E2_DIAG_PIN PD3 // Z+ // // Limit Switches // -#define X_MIN_PIN PF2 -#define X_MAX_PIN PG14 -#define Y_MIN_PIN PC13 -#define Y_MAX_PIN PG9 -#define Z_MIN_PIN PE0 -#define Z_MAX_PIN PD3 +#ifdef X_STALL_SENSITIVITY + #define X_STOP_PIN X_DIAG_PIN + #if X_HOME_TO_MIN + #define X_MAX_PIN E0_DIAG_PIN // X+ + #else + #define X_MIN_PIN E0_DIAG_PIN // X+ + #endif +#else + #define X_MIN_PIN X_DIAG_PIN // X- + #define X_MAX_PIN E0_DIAG_PIN // X+ +#endif + +#ifdef Y_STALL_SENSITIVITY + #define Y_STOP_PIN Y_DIAG_PIN + #if Y_HOME_TO_MIN + #define Y_MAX_PIN E1_DIAG_PIN // Y+ + #else + #define Y_MIN_PIN E1_DIAG_PIN // Y+ + #endif +#else + #define Y_MIN_PIN Y_DIAG_PIN // Y- + #define Y_MAX_PIN E1_DIAG_PIN // Y+ +#endif + +#ifdef Z_STALL_SENSITIVITY + #define Z_STOP_PIN Z_DIAG_PIN + #if Z_HOME_TO_MIN + #define Z_MAX_PIN E2_DIAG_PIN // Z+ + #else + #define Z_MIN_PIN E2_DIAG_PIN // Z+ + #endif +#else + #define Z_MIN_PIN Z_DIAG_PIN // Z- + #define Z_MAX_PIN E2_DIAG_PIN // Z+ +#endif // // Pins on the extender // -//#define X_MIN_PIN PI4 -//#define X2_MIN_PIN PF12 -//#define Y_MIN_PIN PF4 -//#define Y2_MIN_PIN PI7 -//#define Z_MIN_PIN PF6 +#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 +#endif -#if ENABLED(TP) && !defined(Z_MIN_PROBE_PIN) +#ifndef Z_MIN_PROBE_PIN #define Z_MIN_PROBE_PIN PH11 // Z Probe must be PH11 #endif @@ -114,39 +163,43 @@ #define E2_CS_PIN PC12 #endif -#define E3_STEP_PIN PF3 -#define E3_DIR_PIN PG3 -#define E3_ENABLE_PIN PF8 -#ifndef E3_CS_PIN - #define E3_CS_PIN PG4 -#endif +#if ENABLED(M5_EXTENDER) -#define E4_STEP_PIN PD14 -#define E4_DIR_PIN PD11 -#define E4_ENABLE_PIN PG2 -#ifndef E4_CS_PIN - #define E4_CS_PIN PE15 -#endif + #define E3_STEP_PIN PF3 + #define E3_DIR_PIN PG3 + #define E3_ENABLE_PIN PF8 + #ifndef E3_CS_PIN + #define E3_CS_PIN PG4 + #endif -#define E5_STEP_PIN PE12 -#define E5_DIR_PIN PE10 -#define E5_ENABLE_PIN PF14 -#ifndef E5_CS_PIN - #define E5_CS_PIN PE7 -#endif + #define E4_STEP_PIN PD14 + #define E4_DIR_PIN PD11 + #define E4_ENABLE_PIN PG2 + #ifndef E4_CS_PIN + #define E4_CS_PIN PE15 + #endif -#define E6_STEP_PIN PG0 -#define E6_DIR_PIN PG1 -#define E6_ENABLE_PIN PE8 -#ifndef E6_CS_PIN - #define E6_CS_PIN PF15 -#endif + #define E5_STEP_PIN PE12 + #define E5_DIR_PIN PE10 + #define E5_ENABLE_PIN PF14 + #ifndef E5_CS_PIN + #define E5_CS_PIN PE7 + #endif + + #define E6_STEP_PIN PG0 + #define E6_DIR_PIN PG1 + #define E6_ENABLE_PIN PE8 + #ifndef E6_CS_PIN + #define E6_CS_PIN PF15 + #endif + + #define E7_STEP_PIN PH12 + #define E7_DIR_PIN PH15 + #define E7_ENABLE_PIN PI0 + #ifndef E7_CS_PIN + #define E7_CS_PIN PH14 + #endif -#define E7_STEP_PIN PH12 -#define E7_DIR_PIN PH15 -#define E7_ENABLE_PIN PI0 -#ifndef E7_CS_PIN - #define E7_CS_PIN PH14 #endif // @@ -180,11 +233,11 @@ //#define E0_HARDWARE_SERIAL Serial1 //#define E1_HARDWARE_SERIAL Serial1 //#define E2_HARDWARE_SERIAL Serial1 - //#define E3_HARDWARE_SERIAL Serial1 - //#define E4_HARDWARE_SERIAL Serial1 - //#define E5_HARDWARE_SERIAL Serial1 - //#define E6_HARDWARE_SERIAL Serial1 - //#define E7_HARDWARE_SERIAL Serial1 + //#define E3_HARDWARE_SERIAL Serial1 // M5 MOTOR 1 + //#define E4_HARDWARE_SERIAL Serial1 // M5 MOTOR 2 + //#define E5_HARDWARE_SERIAL Serial1 // M5 MOTOR 3 + //#define E6_HARDWARE_SERIAL Serial1 // M5 MOTOR 4 + //#define E7_HARDWARE_SERIAL Serial1 // M5 MOTOR 5 // // Software serial @@ -207,20 +260,22 @@ #define E2_SERIAL_TX_PIN PC12 #define E2_SERIAL_RX_PIN PC12 - #define E3_SERIAL_TX_PIN PG4 - #define E3_SERIAL_RX_PIN PG4 + #if ENABLED(M5_EXTENDER) + #define E3_SERIAL_TX_PIN PG4 + #define E3_SERIAL_RX_PIN PG4 - #define E4_SERIAL_TX_PIN PE15 - #define E4_SERIAL_RX_PIN PE15 + #define E4_SERIAL_TX_PIN PE15 + #define E4_SERIAL_RX_PIN PE15 - #define E5_SERIAL_TX_PIN PE7 - #define E5_SERIAL_RX_PIN PE7 + #define E5_SERIAL_TX_PIN PE7 + #define E5_SERIAL_RX_PIN PE7 - #define E6_SERIAL_TX_PIN PF15 - #define E6_SERIAL_RX_PIN PF15 + #define E6_SERIAL_TX_PIN PF15 + #define E6_SERIAL_RX_PIN PF15 - #define E7_SERIAL_TX_PIN PH14 - #define E7_SERIAL_RX_PIN PH14 + #define E7_SERIAL_TX_PIN PH14 + #define E7_SERIAL_RX_PIN PH14 + #endif // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 @@ -233,27 +288,29 @@ #define TEMP_1_PIN PC2 // T2 <-> E1 #define TEMP_2_PIN PC3 // T3 <-> E2 -#define TEMP_3_PIN PA3 // T4 <-> E3 -#define TEMP_4_PIN PF9 // T5 <-> E4 -#define TEMP_5_PIN PF10 // T6 <-> E5 -#define TEMP_6_PIN PF7 // T7 <-> E6 -#define TEMP_7_PIN PF5 // T8 <-> E7 +#if ENABLED(M5_EXTENDER) + #define TEMP_3_PIN PA3 // M5 TEMP1 + #define TEMP_4_PIN PF9 // M5 TEMP2 + #define TEMP_5_PIN PF10 // M5 TEMP3 + #define TEMP_6_PIN PF7 // M5 TEMP4 + #define TEMP_7_PIN PF5 // M5 TEMP5 +#endif #define TEMP_BED_PIN PC0 // T0 <-> Bed -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple // Uses a separate SPI bus -// If you have a two-way thermocouple, you can customize two THERMO_CSx_PIN pins (x:1~2) +// If you have a two-way thermocouple, you can customize two TEMP_x_CS_PIN pins (x:0~1) -#define THERMO_SCK_PIN PI1 // SCK -#define THERMO_DO_PIN PI2 // MISO -#define THERMO_CS1_PIN PH9 // CS1 -#define THERMO_CS2_PIN PH2 // CS2 +#define TEMP_0_CS_PIN PH9 // GTR K-TEMP +#define TEMP_0_SCK_PIN PI1 // SCK +#define TEMP_0_MISO_PIN PI2 // MISO +//#define TEMP_0_MOSI_PIN ... // For MAX31865 -#define MAX6675_SS_PIN THERMO_CS1_PIN -#define MAX6675_SS2_PIN THERMO_CS2_PIN -#define MAX6675_SCK_PIN THERMO_SCK_PIN -#define MAX6675_DO_PIN THERMO_DO_PIN +#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 // // Heaters / Fans @@ -262,11 +319,13 @@ #define HEATER_1_PIN PA1 // Heater1 #define HEATER_2_PIN PB0 // Heater2 -#define HEATER_3_PIN PD15 // Heater3 -#define HEATER_4_PIN PD13 // Heater4 -#define HEATER_5_PIN PD12 // Heater5 -#define HEATER_6_PIN PE13 // Heater6 -#define HEATER_7_PIN PI6 // Heater7 +#if ENABLED(M5_EXTENDER) + #define HEATER_3_PIN PD15 // M5 HEAT1 + #define HEATER_4_PIN PD13 // M5 HEAT2 + #define HEATER_5_PIN PD12 // M5 HEAT3 + #define HEATER_6_PIN PE13 // M5 HEAT4 + #define HEATER_7_PIN PI6 // M5 HEAT5 +#endif #define HEATER_BED_PIN PA2 // Hotbed @@ -274,14 +333,16 @@ #define FAN1_PIN PE6 // Fan1 #define FAN2_PIN PC8 // Fan2 -#define FAN3_PIN PI5 // Fan3 -#define FAN4_PIN PE9 // Fan4 -#define FAN5_PIN PE11 // Fan5 -//#define FAN6_PIN PC9 // Fan6 -//#define FAN7_PIN PE14 // Fan7 +#if ENABLED(M5_EXTENDER) + #define FAN3_PIN PI5 // M5 FAN1 + #define FAN4_PIN PE9 // M5 FAN2 + #define FAN5_PIN PE11 // M5 FAN3 + //#define FAN6_PIN PC9 // M5 FAN4 + //#define FAN7_PIN PE14 // M5 FAN5 +#endif #ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION ONBOARD + #define SDCARD_CONNECTION ONBOARD #endif // @@ -291,18 +352,16 @@ // #if SD_CONNECTION_IS(LCD) - #define SD_DETECT_PIN PB10 - #define SDSS PB12 + #define SD_DETECT_PIN EXP2_04_PIN + #define SDSS EXP2_07_PIN #elif SD_CONNECTION_IS(ONBOARD) - // Instruct the STM32 HAL to override the default SPI pins from the variant.h file - #define CUSTOM_SPI_PINS #define SDSS PA4 - #define SS_PIN SDSS - #define SCK_PIN PA5 - #define MISO_PIN PA6 - #define MOSI_PIN PA7 + #define SD_SS_PIN SDSS + #define SD_SCK_PIN PA5 + #define SD_MISO_PIN PA6 + #define SD_MOSI_PIN PA7 #define SD_DETECT_PIN PC4 #elif SD_CONNECTION_IS(CUSTOM_CABLE) @@ -310,31 +369,64 @@ #endif /** - * ----- ----- - * NC | · · | GND 5V | · · | GND - * RESET | · · | PB10(SD_DETECT) (LCD_D7) PG5 | · · | PG6 (LCD_D6) - * (MOSI)PB15 | · · | PH10(BTN_EN2) (LCD_D5) PG7 | · · | PG8 (LCD_D4) - * (SD_SS)PB12 | · · | PD10(BTN_EN1) (LCD_RS) PA8 | · · | PC10 (LCD_EN) - * (SCK)PB13 | · · | PB14(MISO) (BTN_ENC) PA15 | · · | PC11 (BEEPER) - * ----- ----- - * EXP2 EXP1 + * ------ ------ + * NC | 1 2 | GND 5V | 1 2 | GND + * RESET | 3 4 | PB10 (SD_DETECT) (LCD_D7) PG5 | 3 4 | PG6 (LCD_D6) + * (MOSI) PB15 | 5 6 | PH10 (BTN_EN2) (LCD_D5) PG7 | 5 6 | PG8 (LCD_D4) + * (SD_SS) PB12 | 7 8 | PD10 (BTN_EN1) (LCD_RS) PA8 | 7 8 | PC10 (LCD_EN) + * (SCK) PB13 | 9 10 | PB14 (MISO) (BTN_ENC) PA15 | 9 10 | PC11 (BEEPER) + * ------ ------ + * EXP2 EXP1 */ +#define EXP1_03_PIN PG5 +#define EXP1_04_PIN PG6 +#define EXP1_05_PIN PG7 +#define EXP1_06_PIN PG8 +#define EXP1_07_PIN PA8 +#define EXP1_08_PIN PC10 +#define EXP1_09_PIN PA15 +#define EXP1_10_PIN PC11 + +#define EXP2_04_PIN PB10 +#define EXP2_05_PIN PB15 +#define EXP2_06_PIN PH10 +#define EXP2_07_PIN PB12 +#define EXP2_08_PIN PD10 +#define EXP2_09_PIN PB13 +#define EXP2_10_PIN PB14 // // LCDs and Controllers // -#if HAS_WIRED_LCD - #define BEEPER_PIN PC11 - #define BTN_ENC PA15 +#if ANY(TFT_COLOR_UI, TFT_LVGL_UI, TFT_CLASSIC_UI) + + #define TFT_CS_PIN EXP2_07_PIN + #define TFT_A0_PIN EXP2_04_PIN + #define TFT_SCK_PIN EXP2_09_PIN + #define TFT_MISO_PIN EXP2_10_PIN + #define TFT_MOSI_PIN EXP2_05_PIN + + #define TOUCH_INT_PIN EXP1_04_PIN + #define TOUCH_MISO_PIN EXP1_05_PIN + #define TOUCH_MOSI_PIN EXP1_08_PIN + #define TOUCH_SCK_PIN EXP1_06_PIN + #define TOUCH_CS_PIN EXP1_07_PIN + #define BTN_ENC EXP1_09_PIN + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN + +#elif HAS_WIRED_LCD + #define BEEPER_PIN EXP1_10_PIN + #define BTN_ENC EXP1_09_PIN #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS PG6 + #define LCD_PINS_RS EXP1_04_PIN - #define BTN_EN1 PC10 - #define BTN_EN2 PG8 + #define BTN_EN1 EXP1_08_PIN + #define BTN_EN2 EXP1_06_PIN - #define LCD_PINS_ENABLE PG5 - #define LCD_PINS_D4 PG7 + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN // CR10_STOCKDISPLAY default timing is too fast #undef BOARD_ST7920_DELAY_1 @@ -342,53 +434,58 @@ #undef BOARD_ST7920_DELAY_3 #elif ENABLED(MKS_MINI_12864) - #define DOGLCD_A0 PG6 - #define DOGLCD_CS PG7 - #define BTN_EN1 PD10 - #define BTN_EN2 PH10 + #define DOGLCD_A0 EXP1_04_PIN + #define DOGLCD_CS EXP1_05_PIN + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN #if SD_CONNECTION_IS(ONBOARD) #define SOFTWARE_SPI #endif #else - #define LCD_PINS_RS PA8 + #define LCD_PINS_RS EXP1_07_PIN - #define BTN_EN1 PD10 - #define BTN_EN2 PH10 + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN - #define LCD_PINS_ENABLE PC10 - #define LCD_PINS_D4 PG8 + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN #if ENABLED(FYSETC_MINI_12864) - #define DOGLCD_CS PC10 - #define DOGLCD_A0 PA8 + #define DOGLCD_CS EXP1_08_PIN + #define DOGLCD_A0 EXP1_07_PIN #if SD_CONNECTION_IS(ONBOARD) #define SOFTWARE_SPI #endif //#define LCD_BACKLIGHT_PIN -1 - #define LCD_RESET_PIN PG8 // Must be high or open for LCD to operate normally. + #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) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN PG7 + #define RGB_LED_R_PIN EXP1_05_PIN #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN PG6 + #define RGB_LED_G_PIN EXP1_04_PIN #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN PG5 + #define RGB_LED_B_PIN EXP1_03_PIN #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN PF13 + #define NEOPIXEL_PIN EXP1_05_PIN #endif #endif // !FYSETC_MINI_12864 - #if ENABLED(ULTIPANEL) - #define LCD_PINS_D5 PG7 - #define LCD_PINS_D6 PG6 - #define LCD_PINS_D7 PG5 + #if IS_ULTIPANEL + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_04_PIN + #define LCD_PINS_D7 EXP1_03_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 @@ -409,3 +506,4 @@ #endif // HAS_WIRED_LCD #undef TP +#undef M5_EXTENDER diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h new file mode 100644 index 000000000000..e51e0a24bb02 --- /dev/null +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h @@ -0,0 +1,26 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#define BOARD_INFO_NAME "BTT OCTOPUS V1.0" + +#include "pins_BTT_OCTOPUS_V1_common.h" diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_1.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_1.h new file mode 100644 index 000000000000..93240c16b8f8 --- /dev/null +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_1.h @@ -0,0 +1,26 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#define BOARD_INFO_NAME "BTT OCTOPUS V1.1" + +#include "pins_BTT_OCTOPUS_V1_common.h" diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h new file mode 100644 index 000000000000..25622bc62d87 --- /dev/null +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h @@ -0,0 +1,543 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include "env_validate.h" + +// Onboard I2C EEPROM +#define I2C_EEPROM +#define MARLIN_EEPROM_SIZE 0x8000 // 32KB (24C32A) +#define I2C_SCL_PIN PB8 +#define I2C_SDA_PIN PB9 + +// USB Flash Drive support +#define HAS_OTG_USB_HOST_SUPPORT + +// Avoid conflict with TIMER_TONE +#define STEP_TIMER 10 + +// +// Servos +#define SERVO0_PIN PB6 + +// +// Misc. Functions +// +#define LED_PIN PA13 + +// +// Trinamic Stallguard pins +// +#define X_DIAG_PIN PG6 // X-STOP +#define Y_DIAG_PIN PG9 // Y-STOP +#define Z_DIAG_PIN PG10 // Z-STOP +#define Z2_DIAG_PIN PG11 // Z2-STOP +#define E0_DIAG_PIN PG12 // E0DET +#define E1_DIAG_PIN PG13 // E1DET +#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 + +// +// Limit Switches +// +#ifdef X_STALL_SENSITIVITY + #define X_STOP_PIN X_DIAG_PIN + #if X_HOME_TO_MIN + #define X_MAX_PIN E0_DIAG_PIN // E0DET + #else + #define X_MIN_PIN E0_DIAG_PIN // E0DET + #endif +#elif ENABLED(X_DUAL_ENDSTOPS) + #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 + #endif +#else + #define X_STOP_PIN X_DIAG_PIN // X-STOP +#endif + +#ifdef Y_STALL_SENSITIVITY + #define Y_STOP_PIN Y_DIAG_PIN + #if Y_HOME_TO_MIN + #define Y_MAX_PIN E1_DIAG_PIN // E1DET + #else + #define Y_MIN_PIN E1_DIAG_PIN // E1DET + #endif +#elif ENABLED(Y_DUAL_ENDSTOPS) + #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 + #endif +#else + #define Y_STOP_PIN Y_DIAG_PIN // Y-STOP +#endif + +#ifdef Z_STALL_SENSITIVITY + #define Z_STOP_PIN Z_DIAG_PIN + #if Z_HOME_TO_MIN + #define Z_MAX_PIN E2_DIAG_PIN // PWRDET + #else + #define Z_MIN_PIN E2_DIAG_PIN // PWRDET + #endif +#elif ENABLED(Z_MULTI_ENDSTOPS) + #ifndef Z_MIN_PIN + #define Z_MIN_PIN Z_DIAG_PIN // Z-STOP + #endif + #ifndef Z_MAX_PIN + #define Z_MAX_PIN E2_DIAG_PIN // PWRDET + #endif +#else + #define Z_STOP_PIN Z_DIAG_PIN // Z-STOP +#endif + +// +// Filament Runout Sensor +// +#define FIL_RUNOUT_PIN PG12 // E0DET +#define FIL_RUNOUT2_PIN PG13 // E1DET +#define FIL_RUNOUT3_PIN PG14 // E2DET +#define FIL_RUNOUT4_PIN PG15 // E3DET + +// +// Power Supply Control +// +#ifndef PS_ON_PIN + #define PS_ON_PIN PE11 // PS-ON +#endif + +// +// Power Loss Detection +// +#ifndef POWER_LOSS_PIN + #define POWER_LOSS_PIN PC0 // PWRDET +#endif + +// +// NeoPixel LED +// +#ifndef NEOPIXEL_PIN + #define NEOPIXEL_PIN PB0 +#endif + +// +// Steppers +// +#define X_STEP_PIN PF13 // MOTOR 0 +#define X_DIR_PIN PF12 +#define X_ENABLE_PIN PF14 +#ifndef X_CS_PIN + #define X_CS_PIN PC4 +#endif + +#define Y_STEP_PIN PG0 // MOTOR 1 +#define Y_DIR_PIN PG1 +#define Y_ENABLE_PIN PF15 +#ifndef Y_CS_PIN + #define Y_CS_PIN PD11 +#endif + +#define Z_STEP_PIN PF11 // MOTOR 2 +#define Z_DIR_PIN PG3 +#define Z_ENABLE_PIN PG5 +#ifndef Z_CS_PIN + #define Z_CS_PIN PC6 +#endif + +#define Z2_STEP_PIN PG4 // MOTOR 3 +#define Z2_DIR_PIN PC1 +#define Z2_ENABLE_PIN PA0 +#ifndef Z2_CS_PIN + #define Z2_CS_PIN PC7 +#endif + +#define E0_STEP_PIN PF9 // MOTOR 4 +#define E0_DIR_PIN PF10 +#define E0_ENABLE_PIN PG2 +#ifndef E0_CS_PIN + #define E0_CS_PIN PF2 +#endif + +#define E1_STEP_PIN PC13 // MOTOR 5 +#define E1_DIR_PIN PF0 +#define E1_ENABLE_PIN PF1 +#ifndef E1_CS_PIN + #define E1_CS_PIN PE4 +#endif + +#define E2_STEP_PIN PE2 // MOTOR 6 +#define E2_DIR_PIN PE3 +#define E2_ENABLE_PIN PD4 +#ifndef E2_CS_PIN + + #define E2_CS_PIN PE1 +#endif + +#define E3_STEP_PIN PE6 // MOTOR 7 +#define E3_DIR_PIN PA14 +#define E3_ENABLE_PIN PE0 +#ifndef E3_CS_PIN + #define E3_CS_PIN PD3 +#endif + +// +// Temperature Sensors +// +#define TEMP_BED_PIN PF3 // TB +#if TEMP_SENSOR_0 == 20 + #define TEMP_0_PIN PF8 // PT100 Connector +#else + #define TEMP_0_PIN PF4 // TH0 +#endif +#define TEMP_1_PIN PF5 // TH1 +#define TEMP_2_PIN PF6 // TH2 +#define TEMP_3_PIN PF7 // TH3 + +// +// Heaters / Fans +// +#define HEATER_BED_PIN PA1 // Hotbed +#define HEATER_0_PIN PA2 // Heater0 +#define HEATER_1_PIN PA3 // Heater1 +#define HEATER_2_PIN PB10 // Heater2 +#define HEATER_3_PIN PB11 // Heater3 + +#define FAN_PIN PA8 // Fan0 +#define FAN1_PIN PE5 // Fan1 +#define FAN2_PIN PD12 // Fan2 +#define FAN3_PIN PD13 // Fan3 +#define FAN4_PIN PD14 // Fan4 +#define FAN5_PIN PD15 // Fan5 + +// +// SD Support +// +#ifndef SDCARD_CONNECTION + #if HAS_WIRED_LCD + #define SDCARD_CONNECTION LCD + #else + #define SDCARD_CONNECTION ONBOARD + #endif +#endif + +// +// Software 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 +#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 Serial1 + //#define X2_HARDWARE_SERIAL Serial1 + //#define Y_HARDWARE_SERIAL Serial1 + //#define Y2_HARDWARE_SERIAL Serial1 + //#define Z_HARDWARE_SERIAL Serial1 + //#define Z2_HARDWARE_SERIAL Serial1 + //#define E0_HARDWARE_SERIAL Serial1 + //#define E1_HARDWARE_SERIAL Serial1 + //#define E2_HARDWARE_SERIAL Serial1 + //#define E3_HARDWARE_SERIAL Serial1 + //#define E4_HARDWARE_SERIAL Serial1 + + // + // Software serial + // + #define X_SERIAL_TX_PIN PC4 + #define X_SERIAL_RX_PIN PC4 + + #define Y_SERIAL_TX_PIN PD11 + #define Y_SERIAL_RX_PIN PD11 + + #define Z_SERIAL_TX_PIN PC6 + #define Z_SERIAL_RX_PIN PC6 + + #define Z2_SERIAL_TX_PIN PC7 + #define Z2_SERIAL_RX_PIN PC7 + + #define E0_SERIAL_TX_PIN PF2 + #define E0_SERIAL_RX_PIN PF2 + + #define E1_SERIAL_TX_PIN PE4 + #define E1_SERIAL_RX_PIN PE4 + + #define E2_SERIAL_TX_PIN PE1 + #define E2_SERIAL_RX_PIN PE1 + + #define E3_SERIAL_TX_PIN PD3 + #define E3_SERIAL_RX_PIN PD3 + + // Reduce baud rate to improve software serial reliability + #define TMC_BAUD_RATE 19200 +#endif + +/** + * ______ ______ + * NC | 1 2 | GND 5V | 1 2 | GND + * RESET | 3 4 | PC15 (SD_DETECT) (LCD_D7) PE15 | 3 4 | PE14 (LCD_D6) + * (MOSI) PA7 | 5 6 PB1 (BTN_EN2) (LCD_D5) PE13 | 5 6 PE12 (LCD_D4) + * (SD_SS) PA4 | 7 8 | PB2 (BTN_EN1) (LCD_RS) PE10 | 7 8 | PE9 (LCD_EN) + * (SCK) PA5 | 9 10 | PA6 (MISO) (BTN_ENC) PE7 | 9 10 | PE8 (BEEPER) + * ------ ----- + * EXP2 EXP1 + */ + +#define EXP1_03_PIN PE15 +#define EXP1_04_PIN PE14 +#define EXP1_05_PIN PE13 +#define EXP1_06_PIN PE12 +#define EXP1_07_PIN PE10 +#define EXP1_08_PIN PE9 +#define EXP1_09_PIN PE7 +#define EXP1_10_PIN PE8 + +#define EXP2_03_PIN -1 +#define EXP2_04_PIN PC15 +#define EXP2_05_PIN PA7 +#define EXP2_06_PIN PB2 +#define EXP2_07_PIN PA4 +#define EXP2_08_PIN PB1 +#define EXP2_09_PIN PA5 +#define EXP2_10_PIN PA6 + +// +// Onboard SD card +// 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 + #ifndef SD_DETECT_STATE + #define SD_DETECT_STATE HIGH + #elif SD_DETECT_STATE == LOW + #error "BOARD_BTT_OCTOPUS_V1_0 onboard SD requires SD_DETECT_STATE set to HIGH." + #endif + #define SD_DETECT_PIN PC14 +#elif SD_CONNECTION_IS(LCD) + + #define SDSS PA4 + #define SD_SS_PIN SDSS + #define SD_SCK_PIN PA5 + #define SD_MISO_PIN PA6 + #define SD_MOSI_PIN PA7 + #define SD_DETECT_PIN PC15 + +#elif SD_CONNECTION_IS(CUSTOM_CABLE) + #error "CUSTOM_CABLE is not a supported SDCARD_CONNECTION for this board" +#endif + +#if ENABLED(BTT_MOTOR_EXPANSION) + /** + * ______ ______ + * NC | 1 2 | GND NC | 1 2 | GND + * NC | 3 4 | M1EN M2EN | 3 4 | M3EN + * M1STP | 5 6 M1DIR M1RX | 5 6 M1DIAG + * M2DIR | 7 8 | M2STP M2RX | 7 8 | M2DIAG + * M3DIR | 9 10 | M3STP M3RX | 9 10 | M3DIAG + * ------ ------ + * EXP2 EXP1 + */ + + // M1 on Driver Expansion Module + #define E4_STEP_PIN EXP2_05_PIN + #define E4_DIR_PIN EXP2_06_PIN + #define E4_ENABLE_PIN EXP2_04_PIN + #define E4_DIAG_PIN EXP1_06_PIN + #define E4_CS_PIN EXP1_05_PIN + #if HAS_TMC_UART + #define E4_SERIAL_TX_PIN EXP1_05_PIN + #define E4_SERIAL_RX_PIN EXP1_05_PIN + #endif + + // M2 on Driver Expansion Module + #define E5_STEP_PIN EXP2_08_PIN + #define E5_DIR_PIN EXP2_07_PIN + #define E5_ENABLE_PIN EXP1_03_PIN + #define E5_DIAG_PIN EXP1_08_PIN + #define E5_CS_PIN EXP1_07_PIN + #if HAS_TMC_UART + #define E5_SERIAL_TX_PIN EXP1_07_PIN + #define E5_SERIAL_RX_PIN EXP1_07_PIN + #endif + + // M3 on Driver Expansion Module + #define E6_STEP_PIN EXP2_10_PIN + #define E6_DIR_PIN EXP2_09_PIN + #define E6_ENABLE_PIN EXP1_04_PIN + #define E6_DIAG_PIN EXP1_10_PIN + #define E6_CS_PIN EXP1_09_PIN + #if HAS_TMC_UART + #define E6_SERIAL_TX_PIN EXP1_09_PIN + #define E6_SERIAL_RX_PIN EXP1_09_PIN + #endif + +#endif // BTT_MOTOR_EXPANSION + +// +// LCDs and Controllers +// +#if IS_TFTGLCD_PANEL + + #if ENABLED(TFTGLCD_PANEL_SPI) + #define TFTGLCD_CS EXP2_08_PIN + #endif + +#elif HAS_WIRED_LCD + + #define BEEPER_PIN EXP1_10_PIN + #define BTN_ENC EXP1_09_PIN + + #if ENABLED(CR10_STOCKDISPLAY) + + #define LCD_PINS_RS EXP1_04_PIN + + #define BTN_EN1 EXP1_08_PIN + #define BTN_EN2 EXP1_06_PIN + + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN + + // CR10_STOCKDISPLAY default timing is too fast + #undef BOARD_ST7920_DELAY_1 + #undef BOARD_ST7920_DELAY_2 + #undef BOARD_ST7920_DELAY_3 + + #else + + #define LCD_PINS_RS EXP1_07_PIN + + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN + + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN + + #if ENABLED(FYSETC_MINI_12864) + #define DOGLCD_CS EXP1_08_PIN + #define DOGLCD_A0 EXP1_07_PIN + //#define LCD_BACKLIGHT_PIN -1 + #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) + #ifndef RGB_LED_R_PIN + #define RGB_LED_R_PIN EXP1_05_PIN + #endif + #ifndef RGB_LED_G_PIN + #define RGB_LED_G_PIN EXP1_04_PIN + #endif + #ifndef RGB_LED_B_PIN + #define RGB_LED_B_PIN EXP1_03_PIN + #endif + #elif ENABLED(FYSETC_MINI_12864_2_1) + #define NEOPIXEL_PIN EXP1_05_PIN + #endif + #endif // !FYSETC_MINI_12864 + + #if IS_ULTIPANEL + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_04_PIN + #define LCD_PINS_D7 EXP1_03_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 +#endif // HAS_WIRED_LCD + +// Alter timing for graphical display +#if HAS_MARLINUI_U8GLIB + #ifndef BOARD_ST7920_DELAY_1 + #define BOARD_ST7920_DELAY_1 DELAY_NS(120) // DELAY_NS(96) + #endif + #ifndef BOARD_ST7920_DELAY_2 + #define BOARD_ST7920_DELAY_2 DELAY_NS(80) // DELAY_NS(48) + #endif + #ifndef BOARD_ST7920_DELAY_3 + #define BOARD_ST7920_DELAY_3 DELAY_NS(580) // DELAY_NS(600) + #endif +#endif + +#if HAS_SPI_TFT + #define TFT_CS_PIN EXP2_07_PIN + #define TFT_A0_PIN EXP2_04_PIN + #define TFT_SCK_PIN EXP2_09_PIN + #define TFT_MISO_PIN EXP2_10_PIN + #define TFT_MOSI_PIN EXP2_05_PIN + + #define TOUCH_INT_PIN EXP1_04_PIN + #define TOUCH_MISO_PIN EXP1_05_PIN + #define TOUCH_MOSI_PIN EXP1_08_PIN + #define TOUCH_SCK_PIN EXP1_06_PIN + #define TOUCH_CS_PIN EXP1_07_PIN + + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN + #define BTN_ENC EXP1_09_PIN +#endif + +// +// WIFI +// + +/** + * ------- + * GND | 9 | | 8 | 3.3V + * (ESP-CS) PB12 | 10 | | 7 | PB15 (ESP-MOSI) + * 3.3V | 11 | | 6 | PB14 (ESP-MISO) + * (ESP-IO0) PD7 | 12 | | 5 | PB13 (ESP-CLK) + * (ESP-IO4) PD10 | 13 | | 4 | NC + * NC | 14 | | 3 | PE15 (ESP-EN) + * (ESP-RX) PD8 | 15 | | 2 | NC + * (ESP-TX) PD9 | 16 | | 1 | PE14 (ESP-RST) + * ------- + * WIFI + */ +#define ESP_WIFI_MODULE_COM 3 // 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 +#define ESP_WIFI_MODULE_RESET_PIN PG7 +#define ESP_WIFI_MODULE_ENABLE_PIN PG8 +#define ESP_WIFI_MODULE_GPIO0_PIN PD7 +#define ESP_WIFI_MODULE_GPIO4_PIN PD10 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 83fd987d9dbf..eb3ce730a696 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h @@ -21,8 +21,18 @@ */ #pragma once -#if NOT_TARGET(STM32F4) - #error "Oops! Select an STM32F4 board in 'Tools > Board.'" +#include "env_validate.h" + +// 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) + #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." + #endif #endif // Use one of these or SDCard-based Emulation will be used @@ -37,6 +47,9 @@ #define FLASH_EEPROM_LEVELING #endif +// USB Flash Drive support +#define HAS_OTG_USB_HOST_SUPPORT + // // Servos // @@ -58,7 +71,7 @@ // #ifdef X_STALL_SENSITIVITY #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_DIR < 0 + #if X_HOME_TO_MIN #define X_MAX_PIN PE15 // E0 #else #define X_MIN_PIN PE15 // E0 @@ -70,7 +83,7 @@ #ifdef Y_STALL_SENSITIVITY #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_DIR < 0 + #if Y_HOME_TO_MIN #define Y_MAX_PIN PE10 // E1 #else #define Y_MIN_PIN PE10 // E1 @@ -82,7 +95,7 @@ #ifdef Z_STALL_SENSITIVITY #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_DIR < 0 + #if Z_HOME_TO_MIN #define Z_MAX_PIN PG5 // E2 #else #define Z_MIN_PIN PG5 // E2 @@ -125,7 +138,7 @@ #define Y_STEP_PIN PE11 #define Y_DIR_PIN PE8 #define Y_ENABLE_PIN PD7 - #ifndef Y_CS_PIN +#ifndef Y_CS_PIN #define Y_CS_PIN PB8 #endif @@ -218,27 +231,81 @@ // // Temperature Sensors +// Use ADC pins without pullup for sensors that don't need a pullup. // -#define TEMP_0_PIN PF4 // T1 <-> E0 -#define TEMP_1_PIN PF5 // T2 <-> E1 -#define TEMP_2_PIN PF6 // T3 <-> E2 -#define TEMP_BED_PIN PF3 // T0 <-> Bed +#if TEMP_SENSOR_0_IS_AD8495 || TEMP_SENSOR_0 == 20 + #define TEMP_0_PIN PF8 +#else + #define TEMP_0_PIN PF4 // T1 <-> E0 +#endif +#if TEMP_SENSOR_1_IS_AD8495 || TEMP_SENSOR_1 == 20 + #define TEMP_1_PIN PF9 +#else + #define TEMP_1_PIN PF5 // T2 <-> E1 +#endif +#if TEMP_SENSOR_2_IS_AD8495 || TEMP_SENSOR_2 == 20 + #define TEMP_2_PIN PF10 +#else + #define TEMP_2_PIN PF6 // T3 <-> E2 +#endif +#if TEMP_SENSOR_BED_IS_AD8495 || TEMP_SENSOR_BED == 20 + #define TEMP_BED_PIN PF7 +#else + #define TEMP_BED_PIN PF3 // T0 <-> Bed +#endif + +#if TEMP_SENSOR_PROBE && !defined(TEMP_PROBE_PIN) + #if TEMP_SENSOR_PROBE_IS_AD8495 || TEMP_SENSOR_PROBE == 20 + #if HOTENDS == 2 + #define TEMP_PROBE_PIN PF10 + #elif HOTENDS < 2 + #define TEMP_PROBE_PIN PF9 + #endif + #else + #if HOTENDS == 2 + #define TEMP_PROBE_PIN TEMP_2_PIN + #elif HOTENDS < 2 + #define TEMP_PROBE_PIN TEMP_1_PIN + #endif + #endif +#endif + +#if TEMP_SENSOR_CHAMBER && !defined(TEMP_CHAMBER_PIN) + #if TEMP_SENSOR_CHAMBER_IS_AD8495 || TEMP_SENSOR_CHAMBER == 20 + #define TEMP_CHAMBER_PIN PF10 + #else + #define TEMP_CHAMBER_PIN TEMP_2_PIN + #endif +#endif // -// Heaters / Fans +// Heaters // #define HEATER_0_PIN PB1 // Heater0 #define HEATER_1_PIN PD14 // Heater1 -#define HEATER_2_PIN PB0 // Heater1 +#if TEMP_SENSOR_CHAMBER && HOTENDS < 3 + #define HEATER_CHAMBER_PIN PB0 // Heater2 +#else + #define HEATER_2_PIN PB0 // Heater2 +#endif #define HEATER_BED_PIN PD12 // Hotbed + +// +// Fans +// #define FAN_PIN PC8 // Fan0 #define FAN1_PIN PE5 // Fan1 -#define FAN2_PIN PE6 #ifndef E0_AUTO_FAN_PIN #define E0_AUTO_FAN_PIN FAN1_PIN #endif +#if !defined(CONTROLLER_FAN_PIN) && ENABLED(USE_CONTROLLER_FAN) && HOTENDS < 2 + #define CONTROLLER_FAN_PIN PE6 // Fan2 +#else + #define FAN2_PIN PE6 // Fan2 +#endif + // // Misc. Functions // @@ -247,14 +314,43 @@ #define SDCARD_CONNECTION LCD #endif +/** + * ----- ----- + * NC | 1 2 | GND 5V | 1 2 | GND + * RESET | 3 4 | PF12(SD_DETECT) (LCD_D7) PG7 | 3 4 | PG6 (LCD_D6) + * (MOSI)PB15 | 5 6 PF11(BTN_EN2) (LCD_D5) PG3 | 5 6 PG2 (LCD_D4) + * (SD_SS)PB12 | 7 8 | PG10(BTN_EN1) (LCD_RS) PD10 | 7 8 | PD11 (LCD_EN) + * (SCK)PB13 | 9 10| PB14(MISO) (BTN_ENC) PA8 | 9 10| PG4 (BEEPER) + * ----- ----- + * EXP2 EXP1 + */ + +#define EXP1_03_PIN PG7 +#define EXP1_04_PIN PG6 +#define EXP1_05_PIN PG3 +#define EXP1_06_PIN PG2 +#define EXP1_07_PIN PD10 +#define EXP1_08_PIN PD11 +#define EXP1_09_PIN PA8 +#define EXP1_10_PIN PG4 + +#define EXP2_03_PIN -1 +#define EXP2_04_PIN PF12 +#define EXP2_05_PIN PB15 +#define EXP2_06_PIN PF11 +#define EXP2_07_PIN PB12 +#define EXP2_08_PIN PG10 +#define EXP2_09_PIN PB13 +#define EXP2_10_PIN PB14 + // // Onboard SD card // Must use soft SPI because Marlin's default hardware SPI is tied to LCD's EXP2 // #if SD_CONNECTION_IS(LCD) - #define SD_DETECT_PIN PF12 - #define SDSS PB12 + #define SD_DETECT_PIN EXP2_04_PIN + #define SDSS EXP2_07_PIN #elif SD_CONNECTION_IS(ONBOARD) @@ -264,25 +360,72 @@ // so force Software SPI to work around this issue. #define SOFTWARE_SPI #define SDSS PA4 - #define SCK_PIN PA5 - #define MISO_PIN PA6 - #define MOSI_PIN PB5 + #define SD_SCK_PIN PA5 + #define SD_MISO_PIN PA6 + #define SD_MOSI_PIN PB5 #define SD_DETECT_PIN PB11 #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "CUSTOM_CABLE is not a supported SDCARD_CONNECTION for this board" #endif -/** - * ----- ----- - * NC | · · | GND 5V | · · | GND - * RESET | · · | PF12(SD_DETECT) (LCD_D7) PG7 | · · | PG6 (LCD_D6) - * (MOSI)PB15 | · · | PF11(BTN_EN2) (LCD_D5) PG3 | · · | PG2 (LCD_D4) - * (SD_SS)PB12 | · · | PG10(BTN_EN1) (LCD_RS) PD10 | · · | PD11 (LCD_EN) - * (SCK)PB13 | · · | PB14(MISO) (BTN_ENC) PA8 | · · | PG4 (BEEPER) - * ----- ----- - * EXP2 EXP1 - */ +#if ENABLED(BTT_MOTOR_EXPANSION) + /** _____ _____ + * NC | . . | GND NC | . . | GND + * NC | . . | M1EN M2EN | . . | M3EN + * M1STP | . . M1DIR M1RX | . . M1DIAG + * M2DIR | . . | M2STP M2RX | . . | M2DIAG + * M3DIR | . . | M3STP M3RX | . . | M3DIAG + * ----- ----- + * EXP2 EXP1 + * + * NB In EXP_MOT_USE_EXP2_ONLY mode EXP1 is not used and M2EN and M3EN need to be jumpered to M1EN + */ + + // M1 on Driver Expansion Module + #define E3_STEP_PIN EXP2_05_PIN + #define E3_DIR_PIN EXP2_06_PIN + #define E3_ENABLE_PIN EXP2_04_PIN + #if !EXP_MOT_USE_EXP2_ONLY + #define E3_DIAG_PIN EXP1_06_PIN + #define E3_CS_PIN EXP1_05_PIN + #if HAS_TMC_UART + #define E3_SERIAL_TX_PIN EXP1_05_PIN + #define E3_SERIAL_RX_PIN EXP1_05_PIN + #endif + #endif + + // M2 on Driver Expansion Module + #define E4_STEP_PIN EXP2_08_PIN + #define E4_DIR_PIN EXP2_07_PIN + #if !EXP_MOT_USE_EXP2_ONLY + #define E4_ENABLE_PIN EXP1_03_PIN + #define E4_DIAG_PIN EXP1_08_PIN + #define E4_CS_PIN EXP1_07_PIN + #if HAS_TMC_UART + #define E4_SERIAL_TX_PIN EXP1_07_PIN + #define E4_SERIAL_RX_PIN EXP1_07_PIN + #endif + #else + #define E4_ENABLE_PIN EXP2_04_PIN + #endif + + // M3 on Driver Expansion Module + #define E5_STEP_PIN EXP2_10_PIN + #define E5_DIR_PIN EXP2_09_PIN + #if !EXP_MOT_USE_EXP2_ONLY + #define E5_ENABLE_PIN EXP1_04_PIN + #define E5_DIAG_PIN EXP1_10_PIN + #define E5_CS_PIN EXP1_09_PIN + #if HAS_TMC_UART + #define E5_SERIAL_TX_PIN EXP1_09_PIN + #define E5_SERIAL_RX_PIN EXP1_09_PIN + #endif + #else + #define E5_ENABLE_PIN EXP2_04_PIN + #endif + +#endif // BTT_MOTOR_EXPANSION // // LCDs and Controllers @@ -290,23 +433,23 @@ #if IS_TFTGLCD_PANEL #if ENABLED(TFTGLCD_PANEL_SPI) - #define TFTGLCD_CS PG10 + #define TFTGLCD_CS EXP2_08_PIN #endif #elif HAS_WIRED_LCD - #define BEEPER_PIN PG4 - #define BTN_ENC PA8 + #define BEEPER_PIN EXP1_10_PIN + #define BTN_ENC EXP1_09_PIN #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS PG6 + #define LCD_PINS_RS EXP1_04_PIN - #define BTN_EN1 PD11 - #define BTN_EN2 PG2 + #define BTN_EN1 EXP1_08_PIN + #define BTN_EN2 EXP1_06_PIN - #define LCD_PINS_ENABLE PG7 - #define LCD_PINS_D4 PG3 + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN // CR10_STOCKDISPLAY default timing is too fast #undef BOARD_ST7920_DELAY_1 @@ -315,45 +458,50 @@ #elif ENABLED(MKS_MINI_12864) - #define DOGLCD_A0 PG6 - #define DOGLCD_CS PG3 - #define BTN_EN1 PG10 - #define BTN_EN2 PF11 + #define DOGLCD_A0 EXP1_04_PIN + #define DOGLCD_CS EXP1_05_PIN + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN #else - #define LCD_PINS_RS PD10 + #define LCD_PINS_RS EXP1_07_PIN - #define BTN_EN1 PG10 - #define BTN_EN2 PF11 + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN - #define LCD_PINS_ENABLE PD11 - #define LCD_PINS_D4 PG2 + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN #if ENABLED(FYSETC_MINI_12864) - #define DOGLCD_CS PD11 - #define DOGLCD_A0 PD10 + #define DOGLCD_CS EXP1_08_PIN + #define DOGLCD_A0 EXP1_07_PIN //#define LCD_BACKLIGHT_PIN -1 - #define LCD_RESET_PIN PG2 // Must be high or open for LCD to operate normally. + #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) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN PG3 + #define RGB_LED_R_PIN EXP1_05_PIN #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN PG6 + #define RGB_LED_G_PIN EXP1_04_PIN #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN PG7 + #define RGB_LED_B_PIN EXP1_03_PIN #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN PG3 + #define NEOPIXEL_PIN EXP1_05_PIN #endif #endif // !FYSETC_MINI_12864 - #if ENABLED(ULTIPANEL) - #define LCD_PINS_D5 PG3 - #define LCD_PINS_D6 PG6 - #define LCD_PINS_D7 PG7 + #if IS_ULTIPANEL + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_04_PIN + #define LCD_PINS_D7 EXP1_03_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 @@ -363,10 +511,10 @@ // Alter timing for graphical display #if HAS_MARLINUI_U8GLIB #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(96) + #define BOARD_ST7920_DELAY_1 DELAY_NS(125) #endif #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(48) + #define BOARD_ST7920_DELAY_2 DELAY_NS(90) #endif #ifndef BOARD_ST7920_DELAY_3 #define BOARD_ST7920_DELAY_3 DELAY_NS(600) diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_REV_A.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_REV_A.h new file mode 100644 index 000000000000..be9580ee6695 --- /dev/null +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_REV_A.h @@ -0,0 +1,29 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#define BOARD_INFO_NAME "BTT SKR V2 Rev.A" + +#error "SKR V2 Rev.A requires modification or drivers may be damaged. See https://bit.ly/3t5d9JQ for more information. Comment out this line to continue." +#define DISABLE_DRIVER_SAFE_POWER_PROTECT + +#include "pins_BTT_SKR_V2_0_common.h" diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_REV_B.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_REV_B.h new file mode 100644 index 000000000000..b83f41b26ad0 --- /dev/null +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_REV_B.h @@ -0,0 +1,26 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#define BOARD_INFO_NAME "BTT SKR V2 Rev.B" + +#include "pins_BTT_SKR_V2_0_common.h" diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h new file mode 100644 index 000000000000..e5d6b6891b5b --- /dev/null +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h @@ -0,0 +1,535 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include "env_validate.h" + +// If 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) + #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." + #endif +#endif + +// Use one of these or SDCard-based Emulation will be used +#if NO_EEPROM_SELECTED + //#define SRAM_EEPROM_EMULATION // Use BackSRAM-based EEPROM emulation + #define FLASH_EEPROM_EMULATION // Use Flash-based EEPROM emulation +#endif + +#if ENABLED(FLASH_EEPROM_EMULATION) + // Decrease delays and flash wear by spreading writes across the + // 128 kB sector allocated for EEPROM emulation. + #define FLASH_EEPROM_LEVELING +#endif + +// USB Flash Drive support +#define HAS_OTG_USB_HOST_SUPPORT + +// Avoid conflict with TIMER_TONE +#define STEP_TIMER 10 + +// +// Servos +// +#define SERVO0_PIN PE5 + +// +// Trinamic Stallguard pins +// +#define X_DIAG_PIN PC1 // X-STOP +#define Y_DIAG_PIN PC3 // Y-STOP +#define Z_DIAG_PIN PC0 // Z-STOP +#define E0_DIAG_PIN PC2 // E0DET +#define E1_DIAG_PIN PA0 // E1DET + +// +// Limit Switches +// +#ifdef X_STALL_SENSITIVITY + #define X_STOP_PIN X_DIAG_PIN + #if X_HOME_TO_MIN + #define X_MAX_PIN PC2 // E0DET + #else + #define X_MIN_PIN PC2 // E0DET + #endif +#elif ENABLED(X_DUAL_ENDSTOPS) + #ifndef X_MIN_PIN + #define X_MIN_PIN PC1 // X-STOP + #endif + #ifndef X_MAX_PIN + #define X_MAX_PIN PC2 // E0DET + #endif +#else + #define X_STOP_PIN PC1 // X-STOP +#endif + +#ifdef Y_STALL_SENSITIVITY + #define Y_STOP_PIN Y_DIAG_PIN + #if Y_HOME_TO_MIN + #define Y_MAX_PIN PA0 // E1DET + #else + #define Y_MIN_PIN PA0 // E1DET + #endif +#elif ENABLED(Y_DUAL_ENDSTOPS) + #ifndef Y_MIN_PIN + #define Y_MIN_PIN PC3 // Y-STOP + #endif + #ifndef Y_MAX_PIN + #define Y_MAX_PIN PA0 // E1DET + #endif +#else + #define Y_STOP_PIN PC3 // Y-STOP +#endif + +#ifdef Z_STALL_SENSITIVITY + #define Z_STOP_PIN Z_DIAG_PIN + #if Z_HOME_TO_MIN + #define Z_MAX_PIN PC15 // PWRDET + #else + #define Z_MIN_PIN PC15 // PWRDET + #endif +#elif ENABLED(Z_MULTI_ENDSTOPS) + #ifndef Z_MIN_PIN + #define Z_MIN_PIN PC0 // Z-STOP + #endif + #ifndef Z_MAX_PIN + #define Z_MAX_PIN PC15 // PWRDET + #endif +#else + #ifndef Z_STOP_PIN + #define Z_STOP_PIN PC0 // Z-STOP + #endif +#endif + +// +// Z Probe (when not Z_MIN_PIN) +// +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN PE4 +#endif + +// +// Filament Runout Sensor +// +#define FIL_RUNOUT_PIN PC2 // E0DET +#define FIL_RUNOUT2_PIN PA0 // E1DET + +// +// Power Supply Control +// +#ifndef PS_ON_PIN + #define PS_ON_PIN PE8 // PS-ON +#endif + +// +// Power Loss Detection +// +#ifndef POWER_LOSS_PIN + #define POWER_LOSS_PIN PC15 // PWRDET +#endif + +// +// Control pin of driver/heater/fan power supply +// +#define SAFE_POWER_PIN PC13 + +// +// Steppers +// +#define X_STEP_PIN PE2 +#define X_DIR_PIN PE1 +#define X_ENABLE_PIN PE3 +#ifndef X_CS_PIN + #define X_CS_PIN PE0 +#endif + +#define Y_STEP_PIN PD5 +#define Y_DIR_PIN PD4 +#define Y_ENABLE_PIN PD6 +#ifndef Y_CS_PIN + #define Y_CS_PIN PD3 +#endif + +#define Z_STEP_PIN PA15 +#define Z_DIR_PIN PA8 +#define Z_ENABLE_PIN PD1 +#ifndef Z_CS_PIN + #define Z_CS_PIN PD0 +#endif + +#define E0_STEP_PIN PD15 +#define E0_DIR_PIN PD14 +#define E0_ENABLE_PIN PC7 +#ifndef E0_CS_PIN + #define E0_CS_PIN PC6 +#endif + +#define E1_STEP_PIN PD11 +#define E1_DIR_PIN PD10 +#define E1_ENABLE_PIN PD13 +#ifndef E1_CS_PIN + #define E1_CS_PIN PD12 +#endif + +// +// Temperature Sensors +// +#define TEMP_BED_PIN PA1 // TB +#define TEMP_0_PIN PA2 // TH0 +#define TEMP_1_PIN PA3 // TH1 + +#if HOTENDS == 1 && DISABLED(HEATERS_PARALLEL) + #if TEMP_SENSOR_PROBE + #define TEMP_PROBE_PIN TEMP_1_PIN + #elif TEMP_SENSOR_CHAMBER + #define TEMP_CHAMBER_PIN TEMP_1_PIN + #endif +#endif + +// +// Heaters / Fans +// +#ifndef HEATER_0_PIN + #define HEATER_0_PIN PB3 // Heater0 +#endif +#ifndef HEATER_1_PIN + #define HEATER_1_PIN PB4 // Heater1 +#endif +#ifndef HEATER_BED_PIN + #define HEATER_BED_PIN PD7 // Hotbed +#endif +#ifndef FAN_PIN + #define FAN_PIN PB7 // Fan0 +#endif +#ifndef FAN1_PIN + #define FAN1_PIN PB6 // Fan1 +#endif +#ifndef FAN2_PIN + #define FAN2_PIN PB5 // Fan2 +#endif + +// +// Software 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 +#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 Serial1 + //#define X2_HARDWARE_SERIAL Serial1 + //#define Y_HARDWARE_SERIAL Serial1 + //#define Y2_HARDWARE_SERIAL Serial1 + //#define Z_HARDWARE_SERIAL Serial1 + //#define Z2_HARDWARE_SERIAL Serial1 + //#define E0_HARDWARE_SERIAL Serial1 + //#define E1_HARDWARE_SERIAL Serial1 + //#define E2_HARDWARE_SERIAL Serial1 + //#define E3_HARDWARE_SERIAL Serial1 + //#define E4_HARDWARE_SERIAL Serial1 + + // + // Software serial + // + #define X_SERIAL_TX_PIN PE0 + #define X_SERIAL_RX_PIN PE0 + + #define Y_SERIAL_TX_PIN PD3 + #define Y_SERIAL_RX_PIN PD3 + + #define Z_SERIAL_TX_PIN PD0 + #define Z_SERIAL_RX_PIN PD0 + + #define E0_SERIAL_TX_PIN PC6 + #define E0_SERIAL_RX_PIN PC6 + + #define E1_SERIAL_TX_PIN PD12 + #define E1_SERIAL_RX_PIN PD12 + + // Reduce baud rate to improve software serial reliability + #define TMC_BAUD_RATE 19200 +#endif + +// +// SD Connection +// +#ifndef SDCARD_CONNECTION + #define SDCARD_CONNECTION LCD +#endif + +/** + * ----- ----- + * NC | 1 2 | GND 5V | 1 2 | GND + * RESET | 3 4 | PC4 (SD_DETECT) (LCD_D7) PE13 | 3 4 | PE12 (LCD_D6) + * (MOSI) PA7 | 5 6 PB2 (BTN_EN2) (LCD_D5) PE11 | 5 6 PE10 (LCD_D4) + * (SD_SS) PA4 | 7 8 | PE7 (BTN_EN1) (LCD_RS) PE9 | 7 8 | PB1 (LCD_EN) + * (SCK) PA5 | 9 10| PA6 (MISO) (BTN_ENC) PB0 | 9 10| PC5 (BEEPER) + * ----- ----- + * EXP2 EXP1 + */ + +#define EXP1_03_PIN PE13 +#define EXP1_04_PIN PE12 +#define EXP1_05_PIN PE11 +#define EXP1_06_PIN PE10 +#define EXP1_07_PIN PE9 +#define EXP1_08_PIN PB1 +#define EXP1_09_PIN PB0 +#define EXP1_10_PIN PC5 + +#define EXP2_03_PIN -1 +#define EXP2_04_PIN PC4 +#define EXP2_05_PIN PA7 +#define EXP2_06_PIN PB2 +#define EXP2_07_PIN PA4 +#define EXP2_08_PIN PE7 +#define EXP2_09_PIN PA5 +#define EXP2_10_PIN PA6 + +// +// Onboard SD card +// 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 SDIO_D0_PIN PC8 + #define SDIO_D1_PIN PC9 + #define SDIO_D2_PIN PC10 + #define SDIO_D3_PIN PC11 + #define SDIO_CK_PIN PC12 + #define SDIO_CMD_PIN PD2 + +#elif SD_CONNECTION_IS(LCD) + + #define SDSS PA4 + #define SD_SS_PIN SDSS + #define SD_SCK_PIN PA5 + #define SD_MISO_PIN PA6 + #define SD_MOSI_PIN PA7 + #define SD_DETECT_PIN PC4 + +#elif SD_CONNECTION_IS(CUSTOM_CABLE) + #error "CUSTOM_CABLE is not a supported SDCARD_CONNECTION for this board" +#endif + +#if ENABLED(BTT_MOTOR_EXPANSION) + /** _____ _____ + * NC | . . | GND NC | . . | GND + * NC | . . | M1EN M2EN | . . | M3EN + * M1STP | . . M1DIR M1RX | . . M1DIAG + * M2DIR | . . | M2STP M2RX | . . | M2DIAG + * M3DIR | . . | M3STP M3RX | . . | M3DIAG + * ----- ----- + * EXP2 EXP1 + * + * NB In EXP_MOT_USE_EXP2_ONLY mode EXP1 is not used and M2EN and M3EN need to be jumpered to M1EN + */ + + // M1 on Driver Expansion Module + #define E2_STEP_PIN EXP2_05_PIN + #define E2_DIR_PIN EXP2_06_PIN + #define E2_ENABLE_PIN EXP2_04_PIN + #if !EXP_MOT_USE_EXP2_ONLY + #define E2_DIAG_PIN EXP1_06_PIN + #define E2_CS_PIN EXP1_05_PIN + #if HAS_TMC_UART + #define E2_SERIAL_TX_PIN EXP1_05_PIN + #define E2_SERIAL_RX_PIN EXP1_05_PIN + #endif + #endif + + // M2 on Driver Expansion Module + #define E3_STEP_PIN EXP2_08_PIN + #define E3_DIR_PIN EXP2_07_PIN + #if !EXP_MOT_USE_EXP2_ONLY + #define E3_ENABLE_PIN EXP1_03_PIN + #define E3_DIAG_PIN EXP1_08_PIN + #define E3_CS_PIN EXP1_07_PIN + #if HAS_TMC_UART + #define E3_SERIAL_TX_PIN EXP1_07_PIN + #define E3_SERIAL_RX_PIN EXP1_07_PIN + #endif + #else + #define E3_ENABLE_PIN EXP2_04_PIN + #endif + + // M3 on Driver Expansion Module + #define E4_STEP_PIN EXP2_10_PIN + #define E4_DIR_PIN EXP2_09_PIN + #if !EXP_MOT_USE_EXP2_ONLY + #define E4_ENABLE_PIN EXP1_04_PIN + #define E4_DIAG_PIN EXP1_10_PIN + #define E4_CS_PIN EXP1_09_PIN + #if HAS_TMC_UART + #define E4_SERIAL_TX_PIN EXP1_09_PIN + #define E4_SERIAL_RX_PIN EXP1_09_PIN + #endif + #else + #define E4_ENABLE_PIN EXP2_04_PIN + #endif + +#endif // BTT_MOTOR_EXPANSION + +// +// LCDs and Controllers +// +#if IS_TFTGLCD_PANEL + + #if ENABLED(TFTGLCD_PANEL_SPI) + #define TFTGLCD_CS EXP2_08_PIN + #endif + +#elif HAS_WIRED_LCD + + #define BEEPER_PIN EXP1_10_PIN + #define BTN_ENC EXP1_09_PIN + + #if ENABLED(CR10_STOCKDISPLAY) + + #define LCD_PINS_RS EXP1_04_PIN + + #define BTN_EN1 EXP1_08_PIN + #define BTN_EN2 EXP1_06_PIN + + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN + + // CR10_STOCKDISPLAY default timing is too fast + #undef BOARD_ST7920_DELAY_1 + #undef BOARD_ST7920_DELAY_2 + #undef BOARD_ST7920_DELAY_3 + + #elif ENABLED(MKS_MINI_12864) + + #define DOGLCD_A0 EXP1_04_PIN + #define DOGLCD_CS EXP1_05_PIN + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN + + #else + + #define LCD_PINS_RS EXP1_07_PIN + + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN + + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN + + #if ENABLED(FYSETC_MINI_12864) + #define DOGLCD_CS EXP1_08_PIN + #define DOGLCD_A0 EXP1_07_PIN + //#define LCD_BACKLIGHT_PIN -1 + #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) + #ifndef RGB_LED_R_PIN + #define RGB_LED_R_PIN EXP1_05_PIN + #endif + #ifndef RGB_LED_G_PIN + #define RGB_LED_G_PIN EXP1_04_PIN + #endif + #ifndef RGB_LED_B_PIN + #define RGB_LED_B_PIN EXP1_03_PIN + #endif + #elif ENABLED(FYSETC_MINI_12864_2_1) + #define NEOPIXEL_PIN EXP1_05_PIN + #endif + #endif // !FYSETC_MINI_12864 + + #if IS_ULTIPANEL + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_04_PIN + #define LCD_PINS_D7 EXP1_03_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 + +#endif // HAS_WIRED_LCD + +// Alter timing for graphical display +#if HAS_MARLINUI_U8GLIB + #ifndef BOARD_ST7920_DELAY_1 + #define BOARD_ST7920_DELAY_1 DELAY_NS(120) + #endif + #ifndef BOARD_ST7920_DELAY_2 + #define BOARD_ST7920_DELAY_2 DELAY_NS(80) + #endif + #ifndef BOARD_ST7920_DELAY_3 + #define BOARD_ST7920_DELAY_3 DELAY_NS(580) + #endif +#endif + +// +// NeoPixel LED +// +#ifndef NEOPIXEL_PIN + #define NEOPIXEL_PIN PE6 +#endif + +// +// WIFI +// + +/** + * ------- + * GND | 9 | | 8 | 3.3V + * (ESP-CS) PB12 | 10 | | 7 | PB15 (ESP-MOSI) + * 3.3V | 11 | | 6 | PB14 (ESP-MISO) + * (ESP-IO0) PB10 | 12 | | 5 | PB13 (ESP-CLK) + * (ESP-IO4) PB11 | 13 | | 4 | NC + * NC | 14 | | 3 | 3.3V (ESP-EN) + * (ESP-RX) PD8 | 15 | | 2 | NC + * (ESP-TX) PD9 | 16 | | 1 | PC14 (ESP-RST) + * ------- + * WIFI + */ +#define ESP_WIFI_MODULE_COM 3 // 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 +#define ESP_WIFI_MODULE_RESET_PIN PC14 +#define ESP_WIFI_MODULE_GPIO0_PIN PB10 +#define ESP_WIFI_MODULE_GPIO4_PIN PB11 diff --git a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h index 808751d7a53d..77257f818a5b 100644 --- a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h +++ b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h @@ -21,9 +21,10 @@ */ #pragma once -#if NOT_TARGET(STM32F4, STM32F4xx) - #error "Oops! Select an STM32F4 board in 'Tools > Board.'" -#elif HOTENDS > 6 || E_STEPPERS > 6 +#define ALLOW_STM32DUINO +#include "env_validate.h" + +#if HOTENDS > 6 || E_STEPPERS > 6 #error "FLYF407ZG supports up to 6 hotends / E-steppers." #endif @@ -31,6 +32,10 @@ #define BOARD_WEBSITE_URL "github.com/FLYmaker/FLYF407ZG" #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME +// Avoid conflict with fans and TIMER_TONE +#define TEMP_TIMER 3 +#define STEP_TIMER 5 + // // EEPROM Emulation // @@ -192,16 +197,16 @@ #ifndef SDIO_SUPPORT #define SOFTWARE_SPI // Use soft SPI for onboard SD #define SDSS SDIO_D3_PIN - #define SCK_PIN SDIO_CK_PIN - #define MISO_PIN SDIO_D0_PIN - #define MOSI_PIN SDIO_CMD_PIN + #define SD_SCK_PIN SDIO_CK_PIN + #define SD_MISO_PIN SDIO_D0_PIN + #define SD_MOSI_PIN SDIO_CMD_PIN #endif #elif SD_CONNECTION_IS(LCD) - #define SCK_PIN PB13 - #define MISO_PIN PB14 - #define MOSI_PIN PB15 + #define SD_SCK_PIN PB13 + #define SD_MISO_PIN PB14 + #define SD_MOSI_PIN PB15 #define SDSS PF11 #define SD_DETECT_PIN PB2 diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h b/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h new file mode 100644 index 000000000000..ef1c14aae0bf --- /dev/null +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h @@ -0,0 +1,269 @@ +/** + * 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 + +#include "env_validate.h" + +#define DEFAULT_MACHINE_NAME "3D Printer" + +#define BOARD_INFO_NAME "FYSETC Cheetah V2.0" +#define BOARD_WEBSITE_URL "fysetc.com" + +// USB Flash Drive support +//#define HAS_OTG_USB_HOST_SUPPORT + +// Ignore temp readings during development. +//#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 + +#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) + #define FLASH_EEPROM_EMULATION + #define FLASH_EEPROM_LEVELING + + #define FLASH_SECTOR 2 + #define FLASH_UNIT_SIZE 0x4000 // 16k + #define FLASH_ADDRESS_START 0x8008000 +#endif + +// +// Z Probe +// +#if ENABLED(BLTOUCH) + #error "You need to set jumper to 5v for Bltouch, then comment out this line to proceed." + #define SERVO0_PIN PA0 +#elif !defined(Z_MIN_PROBE_PIN) + #define Z_MIN_PROBE_PIN PA0 +#endif + +// +// Limit Switches +// +#define X_STOP_PIN PB4 +#define Y_STOP_PIN PB3 +#define Z_STOP_PIN PB1 + +// +// Filament runout +// +#define FIL_RUNOUT_PIN PB5 + +// +// Steppers +// +#define X_STEP_PIN PC0 +#define X_DIR_PIN PC1 +#define X_ENABLE_PIN PA8 + +#define Y_STEP_PIN PC14 +#define Y_DIR_PIN PC13 +#define Y_ENABLE_PIN PC15 + +#define Z_STEP_PIN PB9 +#define Z_DIR_PIN PB8 +#define Z_ENABLE_PIN PC2 + +#define E0_STEP_PIN PB2 +#define E0_DIR_PIN PA15 +#define E0_ENABLE_PIN PD2 + +#if HAS_TMC_UART + #define X_HARDWARE_SERIAL Serial2 + #define Y_HARDWARE_SERIAL Serial2 + #define Z_HARDWARE_SERIAL Serial2 + #define E0_HARDWARE_SERIAL Serial2 + + // Default TMC slave addresses + #ifndef X_SLAVE_ADDRESS + #define X_SLAVE_ADDRESS 0 + #endif + #ifndef Y_SLAVE_ADDRESS + #define Y_SLAVE_ADDRESS 2 + #endif + #ifndef Z_SLAVE_ADDRESS + #define Z_SLAVE_ADDRESS 1 + #endif + #ifndef E0_SLAVE_ADDRESS + #define E0_SLAVE_ADDRESS 3 + #endif +#endif + +// +// Heaters / Fans +// +#define HEATER_0_PIN PC6 +#define HEATER_BED_PIN PC7 +#ifndef FAN_PIN + #define FAN_PIN PA1 +#endif +#define FAN1_PIN PC8 + +// +// Temperature Sensors +// +#define TEMP_BED_PIN PC5 // Analog Input +#define TEMP_0_PIN PC4 // Analog Input + +// +// Misc. Functions +// +#define SDSS PA4 +#define SD_DETECT_PIN PC3 + +#ifndef RGB_LED_R_PIN + #define RGB_LED_R_PIN PB0 +#endif +#ifndef RGB_LED_G_PIN + #define RGB_LED_G_PIN PB7 +#endif +#ifndef RGB_LED_B_PIN + #define RGB_LED_B_PIN PB6 +#endif + +/** + * _____ _____ + * 5V | 1 2 | GND 5V | 1 2 | GND + * RESET | 3 4 | PC3 (SD_DETECT) (LCD_D7) PB7 | 3 4 | PB6 (LCD_D6) + * (SD_MOSI) PA7 5 6 | PC11 (BTN_EN2) (LCD_D5) PB14 5 6 | PB13 (LCD_D4) + * (SD_SS) PA4 | 7 8 | PC10 (BTN_EN1) (LCD_RS) PB12 | 7 8 | PB15 (LCD_EN) + * (SD_SCK) PA5 | 9 10| PA6 (SD_MISO) (BTN_ENC) PC12 | 9 10| PC9 (BEEPER) + * ----- ----- + * EXP2 EXP1 + */ + +/** +* _____ +* (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_03_PIN PB7 +#define EXP1_04_PIN PB6 +#define EXP1_05_PIN PB14 +#define EXP1_06_PIN PB13 +#define EXP1_07_PIN PB12 +#define EXP1_08_PIN PB15 +#define EXP1_09_PIN PC12 +#define EXP1_10_PIN PC9 + +#define EXP2_03_PIN -1 +#define EXP2_04_PIN PC3 +#define EXP2_05_PIN PA7 +#define EXP2_06_PIN PC11 +#define EXP2_07_PIN PA4 +#define EXP2_08_PIN PC10 +#define EXP2_09_PIN PA5 +#define EXP2_10_PIN PA6 + +#if HAS_WIRED_LCD + + #define BEEPER_PIN EXP1_10_PIN + #define BTN_ENC EXP1_09_PIN + + #if ENABLED(CR10_STOCKDISPLAY) + + #define LCD_PINS_RS EXP1_07_PIN + + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN + + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN + + // CR10_STOCKDISPLAY default timing is too fast + #undef BOARD_ST7920_DELAY_1 + #undef BOARD_ST7920_DELAY_2 + #undef BOARD_ST7920_DELAY_3 + + #elif ENABLED(MKS_MINI_12864) + + #define DOGLCD_A0 EXP1_04_PIN + #define DOGLCD_CS EXP1_05_PIN + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN + + #else + + #define LCD_PINS_RS EXP1_07_PIN + + #define BTN_EN1 EXP2_06_PIN + #define BTN_EN2 EXP2_08_PIN + + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN + + #if ENABLED(FYSETC_MINI_12864) + #define DOGLCD_CS EXP1_08_PIN + #define DOGLCD_A0 EXP1_07_PIN + //#define LCD_BACKLIGHT_PIN -1 + #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) + #ifndef RGB_LED_R_PIN + #define RGB_LED_R_PIN EXP1_05_PIN + #endif + #ifndef RGB_LED_G_PIN + #define RGB_LED_G_PIN EXP1_04_PIN + #endif + #ifndef RGB_LED_B_PIN + #define RGB_LED_B_PIN EXP1_03_PIN + #endif + #elif ENABLED(FYSETC_MINI_12864_2_1) + #define NEOPIXEL_PIN EXP1_05_PIN + #endif + #endif // !FYSETC_MINI_12864 + + #if IS_ULTIPANEL + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_04_PIN + #define LCD_PINS_D7 EXP1_03_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 + +#endif // HAS_WIRED_LCD + +// Alter timing for graphical display +#if HAS_MARLINUI_U8GLIB + #ifndef BOARD_ST7920_DELAY_1 + #define BOARD_ST7920_DELAY_1 DELAY_NS(96) + #endif + #ifndef BOARD_ST7920_DELAY_2 + #define BOARD_ST7920_DELAY_2 DELAY_NS(48) + #endif + #ifndef BOARD_ST7920_DELAY_3 + #define BOARD_ST7920_DELAY_3 DELAY_NS(600) + #endif +#endif + +#if ENABLED(TOUCH_UI_FTDI_EVE) + #define BEEPER_PIN EXP1_10_PIN + #define CLCD_MOD_RESET EXP2_08_PIN + #define CLCD_SPI_CS EXP2_06_PIN +#endif diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h index 151f6c3bc06e..492383048e0d 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h @@ -21,10 +21,10 @@ */ #pragma once -#if NOT_TARGET(STM32F4) - #error "Oops! Select an STM32F4 board in 'Tools > Board.'" -#elif HOTENDS > 3 || E_STEPPERS > 3 - #error "RUMBA32 supports up to 3 hotends / E-steppers." +#include "env_validate.h" + +#if HOTENDS > 3 || E_STEPPERS > 3 + #error "FYSETC S6 supports up to 3 hotends / E-steppers." #endif #ifndef BOARD_INFO_NAME @@ -34,15 +34,14 @@ #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME #endif -// Change the priority to 3. Priority 2 is for software serial. -//#define TEMP_TIMER_IRQ_PRIO 3 +// Avoid conflict with TIMER_TONE defined in variant +#define STEP_TIMER 10 // // EEPROM Emulation // #if NO_EEPROM_SELECTED #define FLASH_EEPROM_EMULATION - //#define SRAM_EEPROM_EMULATION //#define I2C_EEPROM #endif @@ -57,7 +56,9 @@ // // Servos // -#define SERVO0_PIN PA3 +#ifndef SERVO0_PIN + #define SERVO0_PIN PA3 +#endif // // Limit Switches @@ -169,10 +170,18 @@ // // Heaters / Fans // -#define HEATER_0_PIN PB3 -#define HEATER_1_PIN PB4 -#define HEATER_2_PIN PB15 -#define HEATER_BED_PIN PC8 +#ifndef HEATER_0_PIN + #define HEATER_0_PIN PB3 +#endif +#ifndef HEATER_1_PIN + #define HEATER_1_PIN PB4 +#endif +#ifndef HEATER_2_PIN + #define HEATER_2_PIN PB15 +#endif +#ifndef HEATER_BED_PIN + #define HEATER_BED_PIN PC8 +#endif #define FAN_PIN PB0 #define FAN1_PIN PB1 @@ -181,9 +190,9 @@ // // SPI // -#define SCK_PIN PA5 -#define MISO_PIN PA6 -#define MOSI_PIN PA7 +#define SD_SCK_PIN PA5 +#define SD_MISO_PIN PA6 +#define SD_MOSI_PIN PA7 // // Misc. Functions @@ -199,7 +208,27 @@ // // LCD / Controller // -#if HAS_WIRED_LCD +#if ENABLED(FYSETC_242_OLED_12864) + + #define BTN_EN1 PC9 + #define BTN_EN2 PD1 + #define BTN_ENC PA8 + + #define BEEPER_PIN PC6 + + #define LCD_PINS_DC PC12 + #define LCD_PINS_RS PC7 // LCD_RST + #define DOGLCD_CS PD2 + #define DOGLCD_MOSI PC10 + #define DOGLCD_SCK PC11 + #define DOGLCD_A0 LCD_PINS_DC + #define FORCE_SOFT_SPI + + #define KILL_PIN -1 // NC + #define NEOPIXEL_PIN PD0 + +#elif HAS_WIRED_LCD + #define BEEPER_PIN PC9 #define BTN_ENC PA8 @@ -212,11 +241,6 @@ #define LCD_PINS_ENABLE PD1 #define LCD_PINS_D4 PC12 - // CR10_STOCKDISPLAY default timing is too fast - #undef BOARD_ST7920_DELAY_1 - #undef BOARD_ST7920_DELAY_2 - #undef BOARD_ST7920_DELAY_3 - #else #define LCD_PINS_RS PD2 @@ -230,7 +254,7 @@ #define LCD_PINS_D4 PC10 #if ENABLED(FYSETC_MINI_12864) - // See https://wiki.fysetc.com/Mini12864_Panel + // See https://wiki.fysetc.com/Mini12864_Panel #define DOGLCD_CS PC11 #define DOGLCD_A0 PD2 #if ENABLED(FYSETC_GENERIC_12864_1_1) @@ -250,31 +274,34 @@ #elif ENABLED(FYSETC_MINI_12864_2_1) #define NEOPIXEL_PIN PC12 #endif - #endif // !FYSETC_MINI_12864 + #endif - #if ENABLED(ULTIPANEL) + #if IS_ULTIPANEL #define LCD_PINS_D5 PC12 #define LCD_PINS_D6 PD0 #define LCD_PINS_D7 PD1 + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif #endif #endif - // Alter timing for graphical display - #if HAS_MARLINUI_U8GLIB - #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(96) - #endif - #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(48) - #endif - #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(600) - #endif - #endif - #endif // HAS_WIRED_LCD +// Alter timing for graphical display +#if HAS_MARLINUI_U8GLIB + #ifndef BOARD_ST7920_DELAY_1 + #define BOARD_ST7920_DELAY_1 DELAY_NS(96) + #endif + #ifndef BOARD_ST7920_DELAY_2 + #define BOARD_ST7920_DELAY_2 DELAY_NS(48) + #endif + #ifndef BOARD_ST7920_DELAY_3 + #define BOARD_ST7920_DELAY_3 DELAY_NS(640) + #endif +#endif + #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN PB6 #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 021ef1d5f6b8..641805d855a6 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_S6_V2_0.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_S6_V2_0.h @@ -1,6 +1,6 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm @@ -29,7 +29,6 @@ #if NO_EEPROM_SELECTED #undef NO_EEPROM_SELECTED //#define FLASH_EEPROM_EMULATION - //#define SRAM_EEPROM_EMULATION #define I2C_EEPROM #endif diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h b/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h new file mode 100644 index 000000000000..e90ac552aef1 --- /dev/null +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h @@ -0,0 +1,116 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#ifndef BOARD_INFO_NAME + #define BOARD_INFO_NAME "FYSETC SPIDER" +#endif +#ifndef DEFAULT_MACHINE_NAME + #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME +#endif + +// +// EEPROM Emulation +// +#if NO_EEPROM_SELECTED + #undef NO_EEPROM_SELECTED + //#define FLASH_EEPROM_EMULATION + //#define SRAM_EEPROM_EMULATION + #define I2C_EEPROM +#endif + +#if ENABLED(I2C_EEPROM) + #define MARLIN_EEPROM_SIZE 0x1000 // 4KB +#endif + +// +// Steppers +// +#define X2_STEP_PIN PD12 +#define X2_DIR_PIN PC4 +#define X2_ENABLE_PIN PE8 +#define X2_CS_PIN PA15 + +#define Z2_STEP_PIN PE1 +#define Z2_DIR_PIN PE0 +#define Z2_ENABLE_PIN PC5 +#define Z2_CS_PIN PD11 + +// +// Heaters / Fans +// +#define HEATER_0_PIN PB15 +#define HEATER_1_PIN PC8 +#define HEATER_2_PIN PB3 +#define HEATER_BED_PIN PB4 + +// +// Steppers +// +#define X_ENABLE_PIN PE9 + +// +// Servos +// Z_MAX_PIN only works in input mode +// +#define SERVO0_PIN PA2 + +#if HAS_TMC_UART + #define X_SERIAL_TX_PIN PE7 + #define X_SERIAL_RX_PIN PE7 + #define Y_SERIAL_TX_PIN PE15 + #define Y_SERIAL_RX_PIN PE15 + #define Z_SERIAL_TX_PIN PD10 + #define Z_SERIAL_RX_PIN PD10 + #define E0_SERIAL_TX_PIN PD7 + #define E0_SERIAL_RX_PIN PD7 + #define E1_SERIAL_TX_PIN PC14 + #define E1_SERIAL_RX_PIN PC14 + #define E2_SERIAL_TX_PIN PC15 + #define E2_SERIAL_RX_PIN PC15 + #define X2_SERIAL_TX_PIN PA15 + #define X2_SERIAL_RX_PIN PA15 + #define Z2_SERIAL_TX_PIN PD11 + #define Z2_SERIAL_RX_PIN PD11 +#endif + +// +// Software 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 +#endif + +#if HOTENDS > 3 || E_STEPPERS > 3 + #error "FYSETC SPIDER supports up to 3 hotends / E-steppers." +#else + #include "pins_FYSETC_S6.h" +#endif diff --git a/Marlin/src/pins/stm32f4/pins_GENERIC_STM32F4.h b/Marlin/src/pins/stm32f4/pins_GENERIC_STM32F4.h deleted file mode 100644 index 4acfd743b756..000000000000 --- a/Marlin/src/pins/stm32f4/pins_GENERIC_STM32F4.h +++ /dev/null @@ -1,197 +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 - -/** - * To build with Arduino IDE use "Discovery F407VG" - * To build with PlatformIO use environment "STM32F4" - */ -#if NOT_TARGET(STM32F4, STM32F4xx) - #error "Oops! Select an STM32F4 board in 'Tools > Board.'" -#elif HOTENDS > 2 || E_STEPPERS > 2 - #error "STM32F4 supports up to 2 hotends / E-steppers." -#endif - -#define BOARD_INFO_NAME "Misc. STM32F4" -#define DEFAULT_MACHINE_NAME "STM32F407VET6" - -//#define I2C_EEPROM - -#ifndef MARLIN_EEPROM_SIZE - #define MARLIN_EEPROM_SIZE 0x1000 // 4KB -#endif - -// Ignore temp readings during development. -//#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 - -// -// Limit Switches -// -#define X_MIN_PIN PE0 -#define X_MAX_PIN -1 -#define Y_MIN_PIN PE1 -#define Y_MAX_PIN -1 -#define Z_MIN_PIN PE14 -#define Z_MAX_PIN -1 - -// -// Z Probe (when not Z_MIN_PIN) -// - -//#ifndef Z_MIN_PROBE_PIN -// #define Z_MIN_PROBE_PIN PA4 -//#endif - -// -// Steppers -// - -#define X_STEP_PIN PD3 -#define X_DIR_PIN PD2 -#define X_ENABLE_PIN PD0 -//#ifndef X_CS_PIN -// #define X_CS_PIN PD1 -//#endif - -#define Y_STEP_PIN PE11 -#define Y_DIR_PIN PE10 -#define Y_ENABLE_PIN PE13 -//#ifndef Y_CS_PIN -// #define Y_CS_PIN PE12 -//#endif - -#define Z_STEP_PIN PD6 -#define Z_DIR_PIN PD7 -#define Z_ENABLE_PIN PD4 -//#ifndef Z_CS_PIN -// #define Z_CS_PIN PD5 -//#endif - -#define E0_STEP_PIN PB5 -#define E0_DIR_PIN PB6 -#define E0_ENABLE_PIN PB3 -//#ifndef E0_CS_PIN -// #define E0_CS_PIN PB4 -//#endif - -#define E1_STEP_PIN PE4 -#define E1_DIR_PIN PE2 -#define E1_ENABLE_PIN PE3 -//#ifndef E1_CS_PIN -// #define E1_CS_PIN PE5 -//#endif - -#define SCK_PIN PA5 -#define MISO_PIN PA6 -#define MOSI_PIN PA7 - -// -// Temperature Sensors -// - -#define TEMP_0_PIN PC0 // Analog Input -#define TEMP_1_PIN PC1 // Analog Input -#define TEMP_BED_PIN PC2 // Analog Input - -// -// Heaters / Fans -// - -#define HEATER_0_PIN PA1 -#define HEATER_1_PIN PA2 -#define HEATER_BED_PIN PA0 - -#ifndef FAN_PIN - #define FAN_PIN PC6 -#endif -#define FAN1_PIN PC7 -#define FAN2_PIN PC8 - -#ifndef E0_AUTO_FAN_PIN - #define E0_AUTO_FAN_PIN PC7 -#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 -// - -//#define E_MUX0_PIN PG3 -//#define E_MUX1_PIN PG4 - -// -// Servos -// - -//#define SERVO0_PIN PE13 -//#define SERVO1_PIN PE14 - -#define SDSS PE7 -#define SS_PIN PE7 -#define LED_PIN PB7 //Alive -#define PS_ON_PIN PA10 -#define KILL_PIN PA8 -#define PWR_LOSS PA4 //Power loss / nAC_FAULT - -// -// LCD / Controller -// - -#define SD_DETECT_PIN PA15 -#define BEEPER_PIN PC9 -#define LCD_PINS_RS PE9 -#define LCD_PINS_ENABLE PE8 -#define LCD_PINS_D4 PB12 -#define LCD_PINS_D5 PB13 -#define LCD_PINS_D6 PB14 -#define LCD_PINS_D7 PB15 -#define BTN_EN1 PC4 -#define BTN_EN2 PC5 -#define BTN_ENC PC3 - -// -// Filament runout -// - -#define FIL_RUNOUT_PIN PA3 - -// -// ST7920 Delays -// -#if HAS_MARLINUI_U8GLIB - #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(96) - #endif - #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(48) - #endif - #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(715) - #endif -#endif diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_K.h b/Marlin/src/pins/stm32f4/pins_LERDGE_K.h index 48973688a058..3b75e7072ad3 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_K.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_K.h @@ -18,21 +18,32 @@ */ #pragma once -#if NOT_TARGET(STM32F4, STM32F4xx) - #error "Oops! Select an STM32F4 board in 'Tools > Board.'" -#elif HOTENDS > 2 || E_STEPPERS > 2 +#define ALLOW_STM32DUINO +#include "env_validate.h" + +#if HOTENDS > 2 || E_STEPPERS > 2 #error "LERDGE K supports up to 2 hotends / E-steppers." #endif #define BOARD_INFO_NAME "Lerdge K" #define DEFAULT_MACHINE_NAME "LERDGE" -#define I2C_EEPROM +// EEPROM +#if NO_EEPROM_SELECTED + #define I2C_EEPROM + #define SOFT_I2C_EEPROM // Force the use of Software I2C + #define I2C_SCL_PIN PG14 + #define I2C_SDA_PIN PG13 + #define MARLIN_EEPROM_SIZE 0x10000 +#endif + +// USB Flash Drive support +#define HAS_OTG_USB_HOST_SUPPORT // // Servos // -//#define SERVO0_PIN PB11 +#define SERVO0_PIN PB11 // // Limit Switches @@ -92,6 +103,57 @@ // #define E1_CS_PIN PE4 //#endif +//#define E2_STEP_PIN PF4 // best guess +//#define E2_DIR_PIN PF3 // best guess +//#define E2_ENABLE_PIN PF5 // best guess +//#ifndef E2_CS_PIN +// #define E2_CS_PIN PB2 // best guess +//#endif + +#if HAS_TMC_UART + /** + * TMC2208/TMC2209 stepper drivers + */ + #ifndef X_SERIAL_TX_PIN + #define X_SERIAL_TX_PIN PB2 + #endif + #ifndef X_SERIAL_RX_PIN + #define X_SERIAL_RX_PIN PB2 + #endif + #ifndef Y_SERIAL_TX_PIN + #define Y_SERIAL_TX_PIN PE2 + #endif + #ifndef Y_SERIAL_RX_PIN + #define Y_SERIAL_RX_PIN PE2 + #endif + #ifndef Z_SERIAL_TX_PIN + #define Z_SERIAL_TX_PIN PE3 + #endif + #ifndef Z_SERIAL_RX_PIN + #define Z_SERIAL_RX_PIN PE3 + #endif + #ifndef E0_SERIAL_TX_PIN + #define E0_SERIAL_TX_PIN PE4 + #endif + #ifndef E0_SERIAL_RX_PIN + #define E0_SERIAL_RX_PIN PE4 + #endif + #ifndef E1_SERIAL_TX_PIN + #define E1_SERIAL_TX_PIN PE1 + #endif + #ifndef E1_SERIAL_RX_PIN + #define E1_SERIAL_RX_PIN PE1 + #endif + #ifndef EX_SERIAL_TX_PIN + #define E2_SERIAL_TX_PIN PE0 + #endif + #ifndef EX_SERIAL_RX_PIN + #define E2_SERIAL_RX_PIN PE0 + #endif + // Reduce baud rate to improve software serial reliability + #define TMC_BAUD_RATE 19200 +#endif + // // Temperature Sensors // @@ -115,13 +177,19 @@ #ifndef FAN_PIN #define FAN_PIN PF7 #endif + #define FAN1_PIN PF6 -#define FAN2_PIN PF8 #ifndef E0_AUTO_FAN_PIN - #define E0_AUTO_FAN_PIN PF6 + #define E0_AUTO_FAN_PIN PB1 +#endif + +#ifndef E1_AUTO_FAN_PIN + #define E1_AUTO_FAN_PIN PB0 #endif +#define CONTROLLER_FAN_PIN PF8 + // // LED / Lighting // @@ -129,10 +197,10 @@ //#define CASE_LIGHT_PIN_DO -1 //#define NEOPIXEL_PIN -1 #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN PB7 + #define RGB_LED_R_PIN PB8 // swap R and G pin for compatibility with real wires #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN PB8 + #define RGB_LED_G_PIN PB7 #endif #ifndef RGB_LED_B_PIN #define RGB_LED_B_PIN PB9 @@ -142,39 +210,45 @@ // SD support // #define SDIO_SUPPORT +#define SDIO_CLOCK 4800000 // // Misc. Functions // #define SDSS PC11 #define LED_PIN PA15 // Alive -#define PS_ON_PIN -1 +#define PS_ON_PIN PA4 #define KILL_PIN -1 #define POWER_LOSS_PIN PA4 // Power-loss / nAC_FAULT -#define SCK_PIN PC12 -#define MISO_PIN PC8 -#define MOSI_PIN PD2 -#define SS_PIN PC11 +#define SD_SCK_PIN PC12 +#define SD_MISO_PIN PC8 +#define SD_MOSI_PIN PD2 +#define SD_SS_PIN PC11 #define SD_DETECT_PIN PA8 #define BEEPER_PIN PC7 // -// LCD / Controller +// TFT with FSMC interface // +#if HAS_FSMC_TFT + //#define TFT_DRIVER LERDGE_ST7796 -#define TFT_RESET_PIN PD6 -#define TFT_BACKLIGHT_PIN PD3 + #define TFT_RESET_PIN PD6 + #define TFT_BACKLIGHT_PIN PD3 -#define TFT_CS_PIN PD7 -#define TFT_RS_PIN PD11 + #define TFT_CS_PIN PD7 + #define TFT_RS_PIN PD11 -#define TOUCH_CS_PIN PG15 -#define TOUCH_SCK_PIN PB3 -#define TOUCH_MOSI_PIN PB5 -#define TOUCH_MISO_PIN PB4 + #define TOUCH_CS_PIN PG15 + #define TOUCH_SCK_PIN PB3 + #define TOUCH_MOSI_PIN PB5 + #define TOUCH_MISO_PIN PB4 +#endif -#define BTN_EN1 PG10 -#define BTN_EN2 PG11 -#define BTN_ENC PG9 +#if IS_NEWPANEL + #define BTN_EN1 PG10 + #define BTN_EN2 PG11 + #define BTN_ENC PG9 +#endif diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_S.h b/Marlin/src/pins/stm32f4/pins_LERDGE_S.h index 0600ed43389f..65db99025c8b 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_S.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_S.h @@ -18,9 +18,10 @@ */ #pragma once -#if NOT_TARGET(STM32F4, STM32F4xx) - #error "Oops! Select an STM32F4 board in 'Tools > Board.'" -#elif HOTENDS > 2 || E_STEPPERS > 2 +#define ALLOW_STM32DUINO +#include "env_validate.h" + +#if HOTENDS > 2 || E_STEPPERS > 2 #error "LERDGE S supports up to 2 hotends / E-steppers." #endif @@ -32,64 +33,67 @@ //#define I2C_EEPROM +// USB Flash Drive support +#define HAS_OTG_USB_HOST_SUPPORT + // // Servos // -#define SERVO0_PIN PD12 //confirmed +#define SERVO0_PIN PD12 //#define SERVO1_PIN -1 // // Limit Switches // -#define X_MIN_PIN PG9 //confirmed -#define Y_MIN_PIN PG10 //confirmed -#define Z_MIN_PIN PG11 //confirmed +#define X_MIN_PIN PG9 +#define Y_MIN_PIN PG10 +#define Z_MIN_PIN PG11 -#define X_MAX_PIN PG12 //confirmed -#define Y_MAX_PIN PG13 //confirmed -#define Z_MAX_PIN PG14 //confirmed +#define X_MAX_PIN PG12 +#define Y_MAX_PIN PG13 +#define Z_MAX_PIN PG14 // // Filament runout // -#define FIL_RUNOUT_PIN PC5 //confirmed +#define FIL_RUNOUT_PIN PC5 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN PG8 //confirmed + #define Z_MIN_PROBE_PIN PG8 #endif // // Steppers // -#define X_STEP_PIN PF7 //confirmed -#define X_DIR_PIN PF8 //confirmed -#define X_ENABLE_PIN PF6 //confirmed +#define X_STEP_PIN PF7 +#define X_DIR_PIN PF8 +#define X_ENABLE_PIN PF6 -#define Y_STEP_PIN PF10 //confirmed -#define Y_DIR_PIN PF11 //confirmed -#define Y_ENABLE_PIN PF9 //confirmed +#define Y_STEP_PIN PF10 +#define Y_DIR_PIN PF11 +#define Y_ENABLE_PIN PF9 -#define Z_STEP_PIN PF13 //confirmed -#define Z_DIR_PIN PF14 //confirmed -#define Z_ENABLE_PIN PF12 //confirmed +#define Z_STEP_PIN PF13 +#define Z_DIR_PIN PF14 +#define Z_ENABLE_PIN PF12 -#define E0_STEP_PIN PG0 //confirmed -#define E0_DIR_PIN PG1 //confirmed -#define E0_ENABLE_PIN PF15 //confirmed +#define E0_STEP_PIN PG0 +#define E0_DIR_PIN PG1 +#define E0_ENABLE_PIN PF15 -#define E1_STEP_PIN PG3 //confirmed -#define E1_DIR_PIN PG4 //confirmed -#define E1_ENABLE_PIN PG2 //confirmed +#define E1_STEP_PIN PG3 +#define E1_DIR_PIN PG4 +#define E1_ENABLE_PIN PG2 // // Temperature Sensors // #define TEMP_0_PIN PC0 // See below for activation of thermistor readings #define TEMP_1_PIN PC1 // See below for activation of thermistor readings -#define TEMP_BED_PIN PC3 //confirmed +#define TEMP_BED_PIN PC3 // Lergde-S can choose thermocouple/thermistor mode in software. // For use with thermistors, these pins must be OUT/LOW. @@ -100,27 +104,27 @@ // MAX6675 Cold-Junction-Compensated K-Thermocouple to Digital Converter (0°C to +1024°C) // https://datasheets.maximintegrated.com/en/ds/MAX6675.pdf -#define MAX6675_SCK_PIN PB3 // max6675 datasheet: SCK pin, found with multimeter, not tested -#define MAX6675_DO_PIN PB4 // max6675 datasheet: SO pin, found with multimeter, not tested -#define MAX6675_SS_PIN PC4 // max6675 datasheet: /CS pin, found with multimeter, not tested and likely wrong +#define TEMP_0_CS_PIN PC4 // max6675 datasheet: /CS pin, found with multimeter, not tested and likely wrong +#define TEMP_0_SCK_PIN PB3 // max6675 datasheet: SCK pin, found with multimeter, not tested +#define TEMP_0_MISO_PIN PB4 // max6675 datasheet: SO pin, found with multimeter, not tested // Expansion board with second max6675 // Warning: Some boards leave the slot unpopulated. -//#define MAX6675_SCK2_PIN PB3 // max6675 datasheet: SCK pin, found with multimeter, not tested -//#define MAX6675_DO2_PIN PB4 // max6675 datasheet: SO pin, found with multimeter, not tested -//#define MAX6675_SS2_PIN PF1 // max6675 datasheet: /CS pin, found with multimeter, not tested +//#define TEMP_1_CS_PIN PF1 // max6675 datasheet: /CS pin, found with multimeter, not tested +//#define TEMP_1_SCK_PIN PB3 // max6675 datasheet: SCK pin, found with multimeter, not tested +//#define TEMP_1_MISO_PIN PB4 // max6675 datasheet: SO pin, found with multimeter, not tested // // Heaters / Fans // -#define HEATER_0_PIN PA0 //confirmed -#define HEATER_1_PIN PA1 //confirmed -#define HEATER_BED_PIN PA3 //confirmed +#define HEATER_0_PIN PA0 +#define HEATER_1_PIN PA1 +#define HEATER_BED_PIN PA3 -#define FAN_PIN PA15 // heater 0 fan 1 //confirmed -#define FAN1_PIN PB10 // heater 1 fan 2 //confirmed -#define FAN2_PIN PF5 // heater 0 fan 2 and heater 1 fan 1 (two sockets, switched together) //confirmed +#define FAN_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) #ifndef E0_AUTO_FAN_PIN #define E0_AUTO_FAN_PIN PF5 @@ -136,19 +140,19 @@ // LED / Lighting // //Lerdge-S board has two LED connectors (this is the one on the mainboard) -#define CASE_LIGHT_PIN PC7 //confirmed +#define CASE_LIGHT_PIN PC7 //on the dual extrusion addon board is a RGB connector -#define RGB_LED_R_PIN PC7 // Shared with the mainboard LED light connector (CASE_LIGHT_PIN), confirmed -#define RGB_LED_G_PIN PB0 //confirmed -#define RGB_LED_B_PIN PB1 //confirmed +#define RGB_LED_R_PIN PC7 // Shared with the mainboard LED light connector (CASE_LIGHT_PIN) +#define RGB_LED_G_PIN PB0 +#define RGB_LED_B_PIN PB1 // // Misc. Functions // #define SDSS PC11 // SD is working using SDIO, not sure if this definition is needed? -#define LED_PIN PC6 // Mainboard soldered green LED, confirmed -#define PS_ON_PIN PB2 // Board has a power module connector, confirmed +#define LED_PIN PC6 // Mainboard soldered green LED +#define PS_ON_PIN PB2 // Board has a power module connector #define KILL_PIN -1 // There is no reset button on the LCD #define POWER_LOSS_PIN -1 // PB2 could be used for this as well @@ -156,13 +160,14 @@ // SD support // #define SDIO_SUPPORT +#define SDIO_CLOCK 4800000 -#define SCK_PIN PC12 //confirmed working -#define MISO_PIN PC8 //confirmed working -#define MOSI_PIN PD2 //confirmed working -#define SS_PIN PC11 //confirmed working +#define SD_SCK_PIN PC12 +#define SD_MISO_PIN PC8 +#define SD_MOSI_PIN PD2 +#define SD_SS_PIN PC11 -#define SD_DETECT_PIN PG15 //confirmed +#define SD_DETECT_PIN PG15 // // Persistent Storage @@ -189,14 +194,14 @@ // // The LCD is initialized in FSMC mode -#define BEEPER_PIN PD13 //confirmed +#define BEEPER_PIN PD13 -#define BTN_EN1 PC14 //confirmed -#define BTN_EN2 PC15 //confirmed -#define BTN_ENC PC13 //confirmed +#define BTN_EN1 PC14 +#define BTN_EN2 PC15 +#define BTN_ENC PC13 -#define TFT_RESET_PIN PD6 //confirmed -#define TFT_BACKLIGHT_PIN PD3 //confirmed +#define TFT_RESET_PIN PD6 +#define TFT_BACKLIGHT_PIN PD3 #define TFT_CS_PIN PD7 // TFT works #define TFT_RS_PIN PD11 // TFT works diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_X.h b/Marlin/src/pins/stm32f4/pins_LERDGE_X.h index bed51ca660cf..3a9c286e001e 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_X.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_X.h @@ -18,10 +18,11 @@ */ #pragma once -#if NOT_TARGET(STM32F4, STM32F4xx) - #error "Oops! Select an STM32F4 board in 'Tools > Board.'" -#elif HOTENDS > 1 || E_STEPPERS > 1 - #error "LERDGE X supports only one hotend / E-steppers" +#define ALLOW_STM32DUINO +#include "env_validate.h" + +#if HOTENDS > 1 || E_STEPPERS > 1 + #error "LERDGE X only supports one hotend / E-stepper. Comment out this line to continue." #endif #define BOARD_INFO_NAME "Lerdge X" @@ -31,6 +32,12 @@ #define TEMP_TIMER 2 #define I2C_EEPROM +#define I2C_SCL_PIN PB8 +#define I2C_SDA_PIN PB9 +#define MARLIN_EEPROM_SIZE 0x10000 // FM24CL64 F-RAM 64K (8Kx8) + +// USB Flash Drive support +#define HAS_OTG_USB_HOST_SUPPORT // // Servos @@ -117,16 +124,17 @@ // Lerdge supports auto-power off and power loss sense through a single pin. #define POWER_LOSS_PIN PC14 // Power-loss / nAC_FAULT -#define SCK_PIN PC12 -#define MISO_PIN PC8 -#define MOSI_PIN PD2 -#define SS_PIN PC11 +#define SD_SCK_PIN PC12 +#define SD_MISO_PIN PC8 +#define SD_MOSI_PIN PD2 +#define SD_SS_PIN PC11 // // SD support // #define SDIO_SUPPORT #define SD_DETECT_PIN PA8 +#define SDIO_CLOCK 4800000 // // LCD / Controller diff --git a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h new file mode 100644 index 000000000000..2db558410977 --- /dev/null +++ b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h @@ -0,0 +1,385 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#define ALLOW_STM32DUINO +#include "env_validate.h" + +#if HOTENDS > 3 || E_STEPPERS > 5 + #error "MKS Monster supports up to 3 hotends and 5 E-steppers." +#elif HAS_FSMC_TFT + #error "MKS Monster doesn't support FSMC-based TFT displays." +#endif + +#define BOARD_INFO_NAME "MKS Monster8 V1.x" + +// USB Flash Drive support +#define HAS_OTG_USB_HOST_SUPPORT + +//#define DISABLE_DEBUG + +// Avoid conflict with TIMER_TONE +#define STEP_TIMER 10 + +// 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 +#define I2C_EEPROM // Need use jumpers set i2c for EEPROM +#define MARLIN_EEPROM_SIZE 0x1000 // 4KB +#define I2C_SCL_PIN PB8 // I2C_SCL and CAN_RX +#define I2C_SDA_PIN PB9 // I2C_SDA and CAN_TX + +// +// Servos +// +#define SERVO0_PIN PA8 // Enable BLTOUCH + +// +// Limit Switches for diag signal +// +#define X_DIAG_PIN PA14 // Driver0 diag signal is connect to X- +#define Y_DIAG_PIN PA15 // Driver1 diag signal is connect to Y- +#define Z_DIAG_PIN PB13 // Driver2 diag signal is connect to Z- +#define E0_DIAG_PIN PA13 // Driver3 diag signal is connect to X+ +#define E1_DIAG_PIN PC5 // Driver4 diag signal is connect to Y+ +#define E2_DIAG_PIN PB12 // Driver5 diag signal is connect to Z+ +#define E3_DIAG_PIN -1 // Driver6 diag signal is not connect +#define E4_DIAG_PIN -1 // Driver7 diag signal is not connect + +// Limit Switches for endstop +#define X_MIN_PIN PA14 +#define X_MAX_PIN PA13 +#define Y_MIN_PIN PA15 +#define Y_MAX_PIN PC5 +#define Z_MIN_PIN PB13 +#define Z_MAX_PIN PB12 + +// +// Steppers +// Driver 0 1 2 3 4 5 6 7 +// For X Y Z E0 E1 E2 E3 E4(default pin settings) +// +//Driver0 +#define X_ENABLE_PIN PC15 +#define X_STEP_PIN PC14 +#define X_DIR_PIN PC13 +#ifndef X_CS_PIN + #define X_CS_PIN PE6 +#endif +//Driver1 +#define Y_ENABLE_PIN PC15 +#define Y_STEP_PIN PE5 +#define Y_DIR_PIN PE4 +#ifndef Y_CS_PIN + #define Y_CS_PIN PE3 +#endif +//Driver2 +#define Z_ENABLE_PIN PE2 +#define Z_STEP_PIN PE1 +#define Z_DIR_PIN PE0 +#ifndef Z_CS_PIN + #define Z_CS_PIN PB7 +#endif +//Driver3 +#define E0_ENABLE_PIN PB6 +#define E0_STEP_PIN PB5 +#define E0_DIR_PIN PB4 +#ifndef E0_CS_PIN + #define E0_CS_PIN PB3 +#endif +//Driver4 +#define E1_ENABLE_PIN PD7 +#define E1_STEP_PIN PD6 +#define E1_DIR_PIN PD5 +#ifndef E1_CS_PIN + #define E1_CS_PIN PD4 +#endif +//Driver5 +#define E2_ENABLE_PIN PD3 +#define E2_STEP_PIN PD2 +#define E2_DIR_PIN PD1 +#ifndef E2_CS_PIN + #define E2_CS_PIN PD0 +#endif +//Driver6 +#define E3_ENABLE_PIN PC8 +#define E3_STEP_PIN PC7 +#define E3_DIR_PIN PC6 +#ifndef E3_CS_PIN + #define E3_CS_PIN PD15 +#endif +//Driver7 +#define E4_ENABLE_PIN PD14 +#define E4_STEP_PIN PD13 +#define E4_DIR_PIN PD12 +#ifndef E4_CS_PIN + #define E4_CS_PIN PD11 +#endif + +// +// Software 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 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 +#endif + +#if HAS_TMC_UART + // + // Software serial + // No Hardware serial for steppers + // + #define X_SERIAL_TX_PIN PE6 + #define X_SERIAL_RX_PIN PE6 + + #define Y_SERIAL_TX_PIN PE3 + #define Y_SERIAL_RX_PIN PE3 + + #define Z_SERIAL_TX_PIN PB7 + #define Z_SERIAL_RX_PIN PB7 + + #define E0_SERIAL_TX_PIN PB3 + #define E0_SERIAL_RX_PIN PB3 + + #define E1_SERIAL_TX_PIN PD4 + #define E1_SERIAL_RX_PIN PD4 + + #define E2_SERIAL_TX_PIN PD0 + #define E2_SERIAL_RX_PIN PD0 + + #define E3_SERIAL_TX_PIN PD15 + #define E3_SERIAL_RX_PIN PD15 + + #define E4_SERIAL_TX_PIN PD11 + #define E4_SERIAL_RX_PIN PD11 + + // Reduce baud rate to improve software serial reliability + #define TMC_BAUD_RATE 19200 +#endif + +// +// Temperature Sensors +// +#define TEMP_0_PIN PC1 // TH0 +#define TEMP_1_PIN PC2 // TH1 +#define TEMP_2_PIN PC3 // TH2 +#define TEMP_BED_PIN PC0 // TB + +// +// Heaters / Fans +// +#define HEATER_0_PIN PB1 // HE0 +#define HEATER_1_PIN PB0 // HE1 +#define HEATER_2_PIN PA3 // HE2 +#define HEATER_BED_PIN PB10 // H-BED + +#define FAN_PIN PA2 // FAN0 +#define FAN1_PIN PA1 // FAN1 +#define FAN2_PIN PA0 // FAN2 + +// +// Misc. Functions +// +#define MT_DET_1 PC5 // Y+ +#define MT_DET_2 PB12 // Z+ + +#ifndef FIL_RUNOUT_PIN + #define FIL_RUNOUT_PIN MT_DET_1 +#endif +#ifndef FIL_RUNOUT2_PIN + #define FIL_RUNOUT2_PIN MT_DET_2 +#endif + +// +// Power Supply Control +// +#if ENABLED(PSU_CONTROL) // MKSPWC + #ifndef PS_ON_PIN + #define PS_ON_PIN MT_DET_2 // Z+ + #endif + #ifndef KILL_PIN + #define KILL_PIN MT_DET_1 // Y+ + #define KILL_PIN_STATE HIGH + #endif +#else + #define PW_DET MT_DET_1 + #define PW_OFF MT_DET_2 + #define POWER_LOSS_PIN PW_DET + #define PS_ON_PIN PW_OFF +#endif + +// Random Info +#define USB_SERIAL -1 // USB Serial + +#ifndef SDCARD_CONNECTION + #define SDCARD_CONNECTION ONBOARD +#endif + +// +// Onboard SD card +// +// 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 + #define SDSS PC9 + #define SD_SCK_PIN PC10 + #define SD_MISO_PIN PC11 + #define SD_MOSI_PIN PC12 + #define SD_DETECT_PIN PC4 +// +// LCD SD +// +#elif SD_CONNECTION_IS(LCD) + #define ENABLE_SPI1 + #define SDSS PA4 + #define SD_SCK_PIN PA5 + #define SD_MISO_PIN PA6 + #define SD_MOSI_PIN PA7 + #define SD_DETECT_PIN PB11 +#endif + +/** + * _____ _____ + * (BEEPER)PB2 | · · | PE10(BTN_ENC) (SPI1 MISO) PA6 | · · | PA5 (SPI1 SCK) + * (LCD_EN)PE11 | · · | PD10(LCD_RS) (BTN_EN1) PE9 | · · | PA4 (SPI1 CS) + * (LCD_D4)PD9 | · · PD8(LCD_D5) (BTN_EN2) PE8 | · · PA7 (SPI1 MOSI) + * (LCD_D6)PE15 | · · | PE7(LCD_D7) (SPI1_RS) PB11 | · · | RESET + * GND | · · | 5V GND | · · | 3.3V + *  ̄ ̄ ̄  ̄ ̄ ̄ + * EXP1 EXP2 + */ + +#if ANY(TFT_COLOR_UI, TFT_CLASSIC_UI) + #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 + + #define TFT_CS_PIN PE15 + #define TFT_SCK_PIN PA5 + #define TFT_MISO_PIN PA6 + #define TFT_MOSI_PIN PA7 + #define TFT_DC_PIN PE7 + #define TFT_RST_PIN PD10 + #define TFT_A0_PIN TFT_DC_PIN + + #define TFT_RESET_PIN PD10 + #define TFT_BACKLIGHT_PIN PE11 + + #define TOUCH_BUTTONS_HW_SPI + #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 + + #define LCD_BACKLIGHT_PIN PE11 + #ifndef TFT_WIDTH + #define TFT_WIDTH 480 + #endif + #ifndef TFT_HEIGHT + #define TFT_HEIGHT 320 + #endif + + #define TOUCH_CS_PIN PD9 // SPI1_NSS + #define TOUCH_SCK_PIN PA5 // SPI1_SCK + #define TOUCH_MISO_PIN PA6 // SPI1_MISO + #define TOUCH_MOSI_PIN PA7 // SPI1_MOSI + + #define BTN_EN1 PE9 + #define BTN_EN2 PE8 + #define BEEPER_PIN PB2 + #define BTN_ENC PE10 + + #define LCD_READ_ID 0xD3 + #define LCD_USE_DMA_SPI + + #define TFT_BUFFER_SIZE 14400 + +#elif HAS_WIRED_LCD + + #define BEEPER_PIN PB2 + #define BTN_ENC PE10 + #define LCD_PINS_ENABLE PE11 + #define LCD_PINS_RS PD10 + #define BTN_EN1 PE9 + #define BTN_EN2 PE8 + #define LCD_BACKLIGHT_PIN -1 + + // MKS MINI12864 and MKS LCD12864B; If using MKS LCD12864A (Need to remove RPK2 resistor) + #if ENABLED(MKS_MINI_12864) + //#define LCD_BACKLIGHT_PIN -1 + //#define LCD_RESET_PIN -1 + #define DOGLCD_A0 PD11 + #define DOGLCD_CS PE15 + //#define DOGLCD_SCK PA5 + //#define DOGLCD_MOSI PA7 + + #elif ENABLED(MKS_MINI_12864_V3) + #define DOGLCD_CS PE11 + #define DOGLCD_A0 PD10 + #define LCD_PINS_DC DOGLCD_A0 + #define LCD_BACKLIGHT_PIN -1 + #define LCD_RESET_PIN PD9 + #define NEOPIXEL_PIN PD8 + #define DOGLCD_MOSI PA7 + #define DOGLCD_SCK PA5 + #if SD_CONNECTION_IS(ONBOARD) + #define FORCE_SOFT_SPI + #endif + //#define LCD_SCREEN_ROT_180 + + #else + + #define LCD_PINS_D4 PD9 + #if ENABLED(ULTIPANEL) + #define LCD_PINS_D5 PD8 + #define LCD_PINS_D6 PE15 + #define LCD_PINS_D7 PE7 + #endif + + #define BOARD_ST7920_DELAY_1 DELAY_NS(96) + #define BOARD_ST7920_DELAY_2 DELAY_NS(48) + #define BOARD_ST7920_DELAY_3 DELAY_NS(600) + + #endif // !MKS_MINI_12864 + +#endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN2.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN2.h index c2f5f324ba28..589300f34175 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN2.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN2.h @@ -21,9 +21,9 @@ */ #pragma once -#if NOT_TARGET(STM32F4) - #error "Oops! Select an STM32F4 board in 'Tools > Board.'" -#elif HOTENDS > 2 || E_STEPPERS > 2 +#include "env_validate.h" + +#if HOTENDS > 2 || E_STEPPERS > 2 #error "MKS_ROBIN2 supports up to 2 hotends / E-steppers." #endif diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h new file mode 100644 index 000000000000..eff941b957a0 --- /dev/null +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h @@ -0,0 +1,402 @@ +/** + * 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 "MKS Robin Nano V3 supports up to 2 hotends / E-steppers." +#elif HAS_FSMC_TFT + #error "MKS Robin Nano V3 doesn't support FSMC-based TFT displays." +#endif + +#define BOARD_INFO_NAME "MKS Robin Nano V3" + +// USB Flash Drive support +#define HAS_OTG_USB_HOST_SUPPORT + +// Avoid conflict with TIMER_TONE +#define STEP_TIMER 10 + +// 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 +#define I2C_EEPROM +#define MARLIN_EEPROM_SIZE 0x1000 // 4KB +#define I2C_SCL_PIN PB6 +#define I2C_SDA_PIN PB7 + +// +// Release PB4 (Z_DIR_PIN) from JTAG NRST role +// +//#define DISABLE_DEBUG + +// +// Servos +// +#define SERVO0_PIN PA8 // Enable BLTOUCH + +// +// Limit Switches +// +#define X_DIAG_PIN PA15 +#define Y_DIAG_PIN PD2 +#define Z_DIAG_PIN PC8 +#define E0_DIAG_PIN PC4 +#define E1_DIAG_PIN PE7 + +// +#define X_STOP_PIN PA15 +#define Y_STOP_PIN PD2 +#define Z_MIN_PIN PC8 +#define Z_MAX_PIN PC4 + +// +// Steppers +// +#define X_ENABLE_PIN PE4 +#define X_STEP_PIN PE3 +#define X_DIR_PIN PE2 +#ifndef X_CS_PIN + #define X_CS_PIN PD5 +#endif + +#define Y_ENABLE_PIN PE1 +#define Y_STEP_PIN PE0 +#define Y_DIR_PIN PB9 +#ifndef Y_CS_PIN + #define Y_CS_PIN PD7 +#endif + +#define Z_ENABLE_PIN PB8 +#define Z_STEP_PIN PB5 +#define Z_DIR_PIN PB4 +#ifndef Z_CS_PIN + #define Z_CS_PIN PD4 +#endif + +#define E0_ENABLE_PIN PB3 +#define E0_STEP_PIN PD6 +#define E0_DIR_PIN PD3 +#ifndef E0_CS_PIN + #define E0_CS_PIN PD9 +#endif + +#define E1_ENABLE_PIN PA3 +#define E1_STEP_PIN PD15 +#define E1_DIR_PIN PA1 +#ifndef E1_CS_PIN + #define E1_CS_PIN PD8 +#endif + +// +// Software 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 +#endif + +#if HAS_TMC_UART + // + // Software serial + // No Hardware serial for steppers + // + #define X_SERIAL_TX_PIN PD5 + #define X_SERIAL_RX_PIN PD5 + + #define Y_SERIAL_TX_PIN PD7 + #define Y_SERIAL_RX_PIN PD7 + + #define Z_SERIAL_TX_PIN PD4 + #define Z_SERIAL_RX_PIN PD4 + + #define E0_SERIAL_TX_PIN PD9 + #define E0_SERIAL_RX_PIN PD9 + + #define E1_SERIAL_TX_PIN PD8 + #define E1_SERIAL_RX_PIN PD8 + + // Reduce baud rate to improve software serial reliability + #define TMC_BAUD_RATE 19200 +#endif + +// +// Temperature Sensors +// +#define TEMP_0_PIN PC1 // TH1 +#define TEMP_1_PIN PA2 // TH2 +#define TEMP_BED_PIN PC0 // TB1 + +// +// Heaters / Fans +// +#define HEATER_0_PIN PE5 // HEATER1 +#define HEATER_1_PIN PB0 // HEATER2 +#define HEATER_BED_PIN PA0 // HOT BED + +#define FAN_PIN PC14 // FAN +#define FAN1_PIN PB1 // FAN1 + +// +// Thermocouples +// +//#define TEMP_0_CS_PIN HEATER_0_PIN // TC1 - CS1 +//#define TEMP_0_CS_PIN HEATER_1_PIN // TC2 - CS2 + +// +// Misc. Functions +// +#define MT_DET_1_PIN PA4 +#define MT_DET_2_PIN PE6 +#define MT_DET_PIN_INVERTING false // LVGL UI filament RUNOUT PIN STATE + +#ifndef FIL_RUNOUT_PIN + #define FIL_RUNOUT_PIN MT_DET_1_PIN +#endif +#ifndef FIL_RUNOUT2_PIN + #define FIL_RUNOUT2_PIN MT_DET_2_PIN +#endif + +// +// Enable MKSPWC support +// +//#define SUICIDE_PIN PB2 +//#define LED_PIN PB2 +//#define KILL_PIN PA2 +//#define KILL_PIN_STATE HIGH + +// +// Power Supply Control +// +#if ENABLED(PSU_CONTROL) // MKSPWC + #if HAS_TFT_LVGL_UI + #error "PSU_CONTROL cannot be used with TFT_LVGL_UI. Disable PSU_CONTROL to continue." + #endif + #ifndef PS_ON_PIN + #define PS_ON_PIN PB2 // SUICIDE + #endif + #ifndef KILL_PIN + #define KILL_PIN PA13 // PW_DET + #define KILL_PIN_STATE HIGH + #endif +#else + #define SUICIDE_PIN PB2 + #define SUICIDE_PIN_INVERTING false +#endif + +#ifndef POWER_LOSS_PIN + #define POWER_LOSS_PIN PA13 // PW_DET +#endif + +// Random Info +#define USB_SERIAL -1 // USB Serial +#define WIFI_SERIAL 3 // USART3 +#define MKS_WIFI_MODULE_SERIAL 1 // USART1 +#define MKS_WIFI_MODULE_SPI 2 // SPI2 + +#ifndef SDCARD_CONNECTION + #define SDCARD_CONNECTION ONBOARD +#endif + +// MKS WIFI MODULE +#if ENABLED(MKS_WIFI_MODULE) + #define WIFI_IO0_PIN PC13 // MKS ESP WIFI IO0 PIN + #define WIFI_IO1_PIN PC7 // MKS ESP WIFI IO1 PIN + #define WIFI_RESET_PIN PE9 // MKS ESP WIFI RESET PIN +#endif + +// MKS TEST +#if ENABLED(MKS_TEST) + #define MKS_TEST_POWER_LOSS_PIN PA13 // PW_DET + #define MKS_TEST_PS_ON_PIN PB2 // PW_OFF +#endif + +// +// Onboard SD card +// +// 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 + #define SDSS PC9 + #define SD_SCK_PIN PC10 + #define SD_MISO_PIN PC11 + #define SD_MOSI_PIN PC12 + #define SD_DETECT_PIN PD12 +#endif + +// +// LCD SD +// +#if 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 +#endif + +// +// LCD / Controller +#define SPI_FLASH +#define HAS_SPI_FLASH 1 +#define SPI_DEVICE 2 +#define SPI_FLASH_SIZE 0x1000000 +#if ENABLED(SPI_FLASH) + #define W25QXX_CS_PIN PB12 + #define W25QXX_MOSI_PIN PC3 + #define W25QXX_MISO_PIN PC2 + #define W25QXX_SCK_PIN PB13 +#endif + +/** + * _____ _____ + * (BEEPER)PC5 | · · | PE13(BTN_ENC) (SPI1 MISO) PA6 | · · | PA5 (SPI1 SCK) + * (LCD_EN)PD13 | · · | PC6(LCD_RS) (BTN_EN1) PE8 | · · | PE10 (SPI1 CS) + * (LCD_D4)PE14 | · · PE15(LCD_D5) (BTN_EN2) PE11 | · · PA7 (SPI1 MOSI) + * (LCD_D6)PD11 | · · | PD10(LCD_D7) (SPI1_RS) PE12 | · · | RESET + * GND | · · | 5V GND | · · | 3.3V + *  ̄ ̄ ̄  ̄ ̄ ̄ + * EXP1 EXP2 + */ + +#if ANY(TFT_COLOR_UI, TFT_LVGL_UI, TFT_CLASSIC_UI) + #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 + + #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_RST_PIN PC6 + #define TFT_A0_PIN TFT_DC_PIN + + #define TFT_RESET_PIN PC6 + #define TFT_BACKLIGHT_PIN PD13 + + #define TOUCH_BUTTONS_HW_SPI + #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 + + #define LCD_BACKLIGHT_PIN PD13 + #ifndef TFT_WIDTH + #define TFT_WIDTH 480 + #endif + #ifndef TFT_HEIGHT + #define TFT_HEIGHT 320 + #endif + + #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 BTN_EN1 PE8 + #define BTN_EN2 PE11 + #define BEEPER_PIN PC5 + #define BTN_ENC PE13 + + #define LCD_READ_ID 0xD3 + #define LCD_USE_DMA_SPI + + #define TFT_BUFFER_SIZE 14400 + +#elif HAS_WIRED_LCD + + #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 + + // MKS MINI12864 and MKS LCD12864B; If using MKS LCD12864A (Need to remove RPK2 resistor) + #if ENABLED(MKS_MINI_12864) + //#define LCD_BACKLIGHT_PIN -1 + //#define LCD_RESET_PIN -1 + #define DOGLCD_A0 PD11 + #define DOGLCD_CS PE15 + //#define DOGLCD_SCK PA5 + //#define DOGLCD_MOSI PA7 + + // Required for MKS_MINI_12864 with this board + //#define MKS_LCD12864B + //#undef SHOW_BOOTSCREEN + + #elif ENABLED(MKS_MINI_12864_V3) + #define DOGLCD_CS PD13 + #define DOGLCD_A0 PC6 + #define LCD_PINS_DC DOGLCD_A0 + #define LCD_BACKLIGHT_PIN -1 + #define LCD_RESET_PIN PE14 + #define NEOPIXEL_PIN PE15 + #define DOGLCD_MOSI PA7 + #define DOGLCD_SCK PA5 + #if SD_CONNECTION_IS(ONBOARD) + #define FORCE_SOFT_SPI + #endif + //#define LCD_SCREEN_ROT_180 + + #else // !MKS_MINI_12864 + + #define LCD_PINS_D4 PE14 + #if ENABLED(ULTIPANEL) + #define LCD_PINS_D5 PE15 + #define LCD_PINS_D6 PD11 + #define LCD_PINS_D7 PD10 + #endif + + #define BOARD_ST7920_DELAY_1 DELAY_NS(96) + #define BOARD_ST7920_DELAY_2 DELAY_NS(48) + #define BOARD_ST7920_DELAY_3 DELAY_NS(600) + + #endif // !MKS_MINI_12864 + +#endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h new file mode 100644 index 000000000000..2e47f98e9f93 --- /dev/null +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h @@ -0,0 +1,374 @@ +/** + * 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 "MKS Robin Nano V3 supports up to 1 hotends / E-steppers." +#endif + +#define BOARD_INFO_NAME "MKS Robin PRO V2" + +// Avoid conflict with TIMER_TONE +#define STEP_TIMER 10 + +// 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 +#define I2C_EEPROM +#define MARLIN_EEPROM_SIZE 0x1000 // 4KB + +// USB Flash Drive support +#define HAS_OTG_USB_HOST_SUPPORT + +// +// Release PB4 (Y_ENABLE_PIN) from JTAG NRST role +// +//#define DISABLE_DEBUG + +// +// Note: MKS Robin board is using SPI2 interface. +// +//#define SPI_MODULE 2 + +// +// Servos +// +#define SERVO0_PIN PA8 // Enable BLTOUCH + +// +// Limit Switches +// +#define X_DIAG_PIN PA15 +#define Y_DIAG_PIN PA12 +#define Z_DIAG_PIN PA11 +#define E0_DIAG_PIN PC4 +#define E1_DIAG_PIN PE7 + +#define X_STOP_PIN PA15 +#define Y_STOP_PIN PA12 +#define Z_MIN_PIN PA11 +#define Z_MAX_PIN PC4 + +#ifndef FIL_RUNOUT_PIN + #define FIL_RUNOUT_PIN PA4 // MT_DET +#endif + +// +// Steppers +// +#define X_ENABLE_PIN PE4 +#define X_STEP_PIN PE3 +#define X_DIR_PIN PE2 +#ifndef X_CS_PIN + #define X_CS_PIN PD5 +#endif + +#define Y_ENABLE_PIN PE1 +#define Y_STEP_PIN PE0 +#define Y_DIR_PIN PB9 +#ifndef Y_CS_PIN + #define Y_CS_PIN PD7 +#endif + +#define Z_ENABLE_PIN PB8 +#define Z_STEP_PIN PB5 +#define Z_DIR_PIN PB4 +#ifndef Z_CS_PIN + #define Z_CS_PIN PD4 +#endif + +#define E0_ENABLE_PIN PB3 +#define E0_STEP_PIN PD6 +#define E0_DIR_PIN PD3 +#ifndef E0_CS_PIN + #define E0_CS_PIN PD9 +#endif + +#define E1_ENABLE_PIN PA3 +#define E1_STEP_PIN PD15 +#define E1_DIR_PIN PA1 +#ifndef E1_CS_PIN + #define E1_CS_PIN PD8 +#endif + +// +// Software 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 +#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 Serial1 + //#define X2_HARDWARE_SERIAL Serial1 + //#define Y_HARDWARE_SERIAL Serial1 + //#define Y2_HARDWARE_SERIAL Serial1 + //#define Z_HARDWARE_SERIAL Serial1 + //#define Z2_HARDWARE_SERIAL Serial1 + //#define E0_HARDWARE_SERIAL Serial1 + //#define E1_HARDWARE_SERIAL Serial1 + //#define E2_HARDWARE_SERIAL Serial1 + //#define E3_HARDWARE_SERIAL Serial1 + //#define E4_HARDWARE_SERIAL Serial1 + + // + // Software serial + // + + #define X_SERIAL_TX_PIN PD5 + #define X_SERIAL_RX_PIN PD5 + + #define Y_SERIAL_TX_PIN PD7 + #define Y_SERIAL_RX_PIN PD7 + + #define Z_SERIAL_TX_PIN PD4 + #define Z_SERIAL_RX_PIN PD4 + + #define E0_SERIAL_TX_PIN PD9 + #define E0_SERIAL_RX_PIN PD9 + + #define E1_SERIAL_TX_PIN PD8 + #define E1_SERIAL_RX_PIN PD8 + + // Reduce baud rate to improve software serial reliability + #define TMC_BAUD_RATE 19200 +#endif // HAS_TMC_UART + +// +// Temperature Sensors +// +#define TEMP_0_PIN PC1 // TH1 +#define TEMP_1_PIN PC2 // TH2 +#define TEMP_BED_PIN PC0 // TB1 + +// +// Heaters / Fans +// +#define HEATER_0_PIN PC3 // HEATER1 +#define HEATER_1_PIN PB0 // HEATER2 +#define HEATER_BED_PIN PA0 // HOT BED + +#define FAN_PIN PB1 // FAN + +// +// Thermocouples +// +//#define TEMP_0_CS_PIN PE5 // TC1 - CS1 +//#define TEMP_0_CS_PIN PE6 // TC2 - CS2 + +// +// Misc. Functions +// +//#define PS_ON_PIN PA3 // PW_OFF + +// +// Power Supply Control +// +#if ENABLED(PSU_CONTROL) // MKSPWC + //#define SUICIDE_PIN PB2 // LED + //#define KILL_PIN PA2 // PW_DET + //#define KILL_PIN_STATE HIGH +#else + //#define POWER_LOSS_PIN PA2 // PW_DET + //#define LED_PIN PB2 +#endif + +#ifndef SDCARD_CONNECTION + #define SDCARD_CONNECTION ONBOARD +#endif + +//#define USE_NEW_SPI_API 1 + +// +// Onboard SD card +// NOT compatible with LCD +// +// detect pin doesn't work when ONBOARD and NO_SD_HOST_DRIVE disabled +#if !defined(SDCARD_CONNECTION) || SDCARD_CONNECTION == ONBOARD + #if USE_NEW_SPI_API + #define SD_SPI MARLIN_SPI(HardwareSPI3, PC9) + #else + #define ENABLE_SPI3 + #define SD_SS_PIN -1 + #define SDSS PC9 + #define SD_SCK_PIN PC10 + #define SD_MISO_PIN PC11 + #define SD_MOSI_PIN PC12 + #endif + #define SD_DETECT_PIN PD12 +#endif + +/* +// +// LCD SD +// +#if SDCARD_CONNECTION == 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 +#endif +*/ + +// +// LCD / Controller +#define SPI_FLASH +#define HAS_SPI_FLASH 1 +#define SPI_DEVICE 2 +#define SPI_FLASH_SIZE 0x1000000 +#if ENABLED(SPI_FLASH) + #define W25QXX_CS_PIN PB12 + #define W25QXX_MOSI_PIN PB15 + #define W25QXX_MISO_PIN PB14 + #define W25QXX_SCK_PIN PB13 +#endif + +/** + * _____ _____ + * (BEEPER)PC5 | · · | PE13(BTN_ENC) (SPI1 MISO) PA6 | · · | PA5 (SPI1 SCK) + * (LCD_EN)PD13 | · · | PC6(LCD_RS) (BTN_EN1) PE8 | · · | PE10 (SPI1 CS) + * (LCD_D4)PE14 | · · | PE15(LCD_D5) (BTN_EN2) PE11 | · · | PA7 (SPI1 MOSI) + * (LCD_D6)PD11 | · · | PD10(LCD_D7) (SPI DET) PE12 | · · | RESET + * GND | · · | 5V GND | · · | 3.3V + *  ̄ ̄ ̄  ̄ ̄ ̄ + * EXP1 EXP2 + */ + +#if ANY(TFT_COLOR_UI, TFT_LVGL_UI, TFT_CLASSIC_UI) + #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 + + #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_RST_PIN PC6 + #define TFT_A0_PIN TFT_DC_PIN + + #define TFT_RESET_PIN PC6 + #define TFT_BACKLIGHT_PIN PD13 + + #define TOUCH_BUTTONS_HW_SPI + #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 + + #define LCD_BACKLIGHT_PIN PD13 + #ifndef TFT_WIDTH + #define TFT_WIDTH 480 + #endif + #ifndef TFT_HEIGHT + #define TFT_HEIGHT 320 + #endif + + #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 BTN_EN1 PE8 + #define BTN_EN2 PE11 + #define BEEPER_PIN PC5 + #define BTN_ENC PE13 + + #define LCD_READ_ID 0xD3 + #define LCD_USE_DMA_SPI + + //#define TFT_DRIVER ST7796 + #define TFT_BUFFER_SIZE 14400 + +#elif HAS_WIRED_LCD + + #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 + + // MKS MINI12864 and MKS LCD12864B; If using MKS LCD12864A (Need to remove RPK2 resistor) + #if ENABLED(MKS_MINI_12864) + //#define LCD_BACKLIGHT_PIN -1 + //#define LCD_RESET_PIN -1 + #define DOGLCD_A0 PD11 + #define DOGLCD_CS PE15 + //#define DOGLCD_SCK PA5 + //#define DOGLCD_MOSI PA7 + + // Required for MKS_MINI_12864 with this board + //#define MKS_LCD12864B + //#undef SHOW_BOOTSCREEN + + #else // !MKS_MINI_12864 + + #define LCD_PINS_D4 PE14 + #if ENABLED(ULTIPANEL) + #define LCD_PINS_D5 PE15 + #define LCD_PINS_D6 PD11 + #define LCD_PINS_D7 PD10 + #endif + + #ifndef ST7920_DELAY_1 + #define ST7920_DELAY_1 DELAY_NS(96) + #endif + #ifndef ST7920_DELAY_2 + #define ST7920_DELAY_2 DELAY_NS(48) + #endif + #ifndef ST7920_DELAY_3 + #define ST7920_DELAY_3 DELAY_NS(600) + #endif + + #endif // !MKS_MINI_12864 + +#endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/stm32f4/pins_RUMBA32_MKS.h b/Marlin/src/pins/stm32f4/pins_RUMBA32_MKS.h index ab277d43722a..4dce7b79c019 100644 --- a/Marlin/src/pins/stm32f4/pins_RUMBA32_MKS.h +++ b/Marlin/src/pins/stm32f4/pins_RUMBA32_MKS.h @@ -46,8 +46,6 @@ #define FLASH_EEPROM_LEVELING #endif -#define ENABLE_SPI1 - #include "pins_RUMBA32_common.h" #if HAS_TMC_UART diff --git a/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h b/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h index d52bb11d1206..7bf148874c3f 100644 --- a/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h +++ b/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h @@ -25,9 +25,9 @@ * Common pin assignments for all RUMBA32 boards */ -#if NOT_TARGET(STM32F4) - #error "Oops! Select an STM32F4 board in 'Tools > Board.'" -#elif HOTENDS > 3 || E_STEPPERS > 3 +#include "env_validate.h" + +#if HOTENDS > 3 || E_STEPPERS > 3 #error "RUMBA32 boards support up to 3 hotends / E-steppers." #endif @@ -45,9 +45,8 @@ // This will be difficult to solve from the Arduino IDE, without modifying the RUMBA32 variant // included with the STM32 framework. -#define STEP_TIMER 10 -#define TEMP_TIMER 14 -#define HAL_TIMER_RATE F_CPU +#define STEP_TIMER 10 +#define TEMP_TIMER 14 // // Limit Switches @@ -127,9 +126,9 @@ // // SPI // -#define SCK_PIN PA5 -#define MISO_PIN PA6 -#define MOSI_PIN PA7 +#define SD_SCK_PIN PA5 +#define SD_MISO_PIN PA6 +#define SD_MOSI_PIN PA7 // // Misc. Functions @@ -161,10 +160,15 @@ #define DOGLCD_A0 PE14 #endif - #if ENABLED(ULTIPANEL) + #if IS_ULTIPANEL #define LCD_PINS_D5 PE13 #define LCD_PINS_D6 PE14 #define LCD_PINS_D7 PE15 + + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif + #endif // Alter timing for graphical display @@ -176,7 +180,7 @@ #define BOARD_ST7920_DELAY_2 DELAY_NS(48) #endif #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(600) + #define BOARD_ST7920_DELAY_3 DELAY_NS(640) #endif #endif diff --git a/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h b/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h index 0278dd8434b6..5f8ffe975b8d 100644 --- a/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h +++ b/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h @@ -40,9 +40,7 @@ #pragma once -#if NOT_TARGET(STM32F4) - #error "Oops! Select an STM32F4 board in 'Tools > Board.'" -#endif +#include "env_validate.h" #ifndef MACHINE_NAME #define MACHINE_NAME "STEVAL-3DP001V1" @@ -120,13 +118,13 @@ #define L6470_CHAIN_MOSI_PIN 19 // PA7 #define L6470_CHAIN_SS_PIN 16 // PA4 - //#define SCK_PIN L6470_CHAIN_SCK_PIN - //#define MISO_PIN L6470_CHAIN_MISO_PIN - //#define MOSI_PIN L6470_CHAIN_MOSI_PIN + //#define SD_SCK_PIN L6470_CHAIN_SCK_PIN + //#define SD_MISO_PIN L6470_CHAIN_MISO_PIN + //#define SD_MOSI_PIN L6470_CHAIN_MOSI_PIN #else - //#define SCK_PIN 13 // PB13 SPI_S - //#define MISO_PIN 12 // PB14 SPI_M - //#define MOSI_PIN 11 // PB15 SPI_M + //#define SD_SCK_PIN 13 // PB13 SPI_S + //#define SD_MISO_PIN 12 // PB14 SPI_M + //#define SD_MOSI_PIN 11 // PB15 SPI_M #endif /** @@ -175,7 +173,6 @@ // // Misc functions // -#define SDSS 16 // PA4 SPI_CS #define LED_PIN -1 // 9 // PE1 green LED Heart beat #define PS_ON_PIN -1 #define KILL_PIN -1 @@ -247,14 +244,17 @@ #ifndef SDIO_SUPPORT #define SOFTWARE_SPI // Use soft SPI for onboard SD - #undef SDSS #define SDSS SDIO_D3_PIN - #define SCK_PIN SDIO_CK_PIN - #define MISO_PIN SDIO_D0_PIN - #define MOSI_PIN SDIO_CMD_PIN + #define SD_SCK_PIN SDIO_CK_PIN + #define SD_MISO_PIN SDIO_D0_PIN + #define SD_MOSI_PIN SDIO_CMD_PIN #endif #endif +#ifndef SDSS + #define SDSS 16 // PA4 SPI_CS +#endif + // OTG // 30 // PA11 OTG_DM // 31 // PA12 OTG_DP diff --git a/Marlin/src/pins/stm32f4/pins_VAKE403D.h b/Marlin/src/pins/stm32f4/pins_VAKE403D.h index e2463fd47e6f..9d122c264225 100644 --- a/Marlin/src/pins/stm32f4/pins_VAKE403D.h +++ b/Marlin/src/pins/stm32f4/pins_VAKE403D.h @@ -21,9 +21,10 @@ */ #pragma once -#if NOT_TARGET(STM32F4, STM32F4xx) - #error "Oops! Select an STM32F4 board in 'Tools > Board.'" -#elif HOTENDS > 2 || E_STEPPERS > 2 +#define ALLOW_STM32DUINO +#include "env_validate.h" + +#if HOTENDS > 2 || E_STEPPERS > 2 #error "STM32F4 supports up to 2 hotends / E-steppers." #endif @@ -99,16 +100,16 @@ #define E1_CS_PIN PB0 #endif -#define SCK_PIN PE12 // PA5 // SPI1 for SD card -#define MISO_PIN PE13 // PA6 -#define MOSI_PIN PE14 // PA7 +#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 MOSI_PIN // SPI Master Out Slave In pin -//#define SPI_MISO_PIN MISO_PIN // SPI Master In Slave Out pin -//#define SPI_SCK_PIN SCK_PIN // SPI Clock pin +//#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) @@ -159,7 +160,7 @@ #if ENABLED(SDSUPPORT) #define SD_DETECT_PIN PB7 - #define SS_PIN PB_15 // USD_CS -> CS for onboard SD + #define SD_SS_PIN PB_15 // USD_CS -> CS for onboard SD #endif // diff --git a/Marlin/src/pins/stm32f7/pins_NUCLEO_F767ZI.h b/Marlin/src/pins/stm32f7/pins_NUCLEO_F767ZI.h index 5e3d5f4ab538..5e50548c9b5c 100644 --- a/Marlin/src/pins/stm32f7/pins_NUCLEO_F767ZI.h +++ b/Marlin/src/pins/stm32f7/pins_NUCLEO_F767ZI.h @@ -21,7 +21,7 @@ */ #pragma once -#ifndef STM32F767xx +#if NOT_TARGET(STM32F767xx) #error "Oops! Select an STM32F767 environment" #endif @@ -36,12 +36,12 @@ // Decrease delays and flash wear by spreading writes across the // 128 kB sector allocated for EEPROM emulation. // Not yet supported on F7 hardware - // #define FLASH_EEPROM_LEVELING + //#define FLASH_EEPROM_LEVELING #endif /** * Timer assignments - * + * * TIM1 - * TIM2 - Hardware PWM (Fan/Heater Pins) * TIM3 - Hardware PWM (Servo Pins) @@ -55,18 +55,17 @@ * TIM12 - * TIM13 - * TIM14 - TEMP_TIMER (Marlin) - * + * */ -#define STEP_TIMER 4 -#define TEMP_TIMER 14 - +#define STEP_TIMER 4 +#define TEMP_TIMER 14 /** * These pin assignments are arbitrary and intending for testing purposes. * Assignments may not be ideal, and not every assignment has been tested. * Proceed at your own risk. * _CN7_ - * (X_STEP) PC6 | · · | PB8 (X_EN) + * (X_STEP) PC6 | · · | PB8 (X_EN) * (X_DIR) PB15 | · · | PB9 (X_CS) * (LCD_D4) PB13 | · · | AVDD * _CN8_ PB12 | · · | GND @@ -77,8 +76,8 @@ * +5V | · · | PC12 (SDSS) PA4 | · · | PD15 (LCD_ENABLE) * GND | · · | PD2 (SERVO0_PIN) PB4 | · · | PF12 (LCD_RS) * GND | · · | PG2  ̄ ̄ ̄ - * VIN | · · | PG3 -_*  ̄ ̄ ̄ _CN10 + * VIN | · · | PG3 + *  ̄ ̄ ̄ _CN10 * AVDD | · · | PF13 (BTN_EN1) * _CN9_ AGND | · · | PE9 (BTN_EN2) * (TEMP_0) PA3 | · · | PD7 GND | · · | PE11 (BTN_ENC) @@ -140,7 +139,7 @@ _*  ̄ ̄ ̄ _CN10 #define Z_SERIAL_RX_PIN PE12 #define E_SERIAL_TX_PIN PG9 - #define E_SERIAL_RX_PIN PG9 + #define E_SERIAL_RX_PIN PG9 #endif // @@ -152,13 +151,13 @@ _*  ̄ ̄ ̄ _CN10 // // Heaters / Fans // -#define HEATER_0_PIN PA15 // PWM Capable, TIM2_CH1 -#define HEATER_BED_PIN PB3 // PWM Capable, TIM2_CH2 +#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 + #define FAN_PIN PB10 // PWM Capable, TIM2_CH3 #endif -#define FAN1_PIN PB11 // PWM Capable, TIM2_CH4 +#define FAN1_PIN PB11 // PWM Capable, TIM2_CH4 #ifndef E0_AUTO_FAN_PIN #define E0_AUTO_FAN_PIN FAN1_PIN @@ -167,33 +166,30 @@ _*  ̄ ̄ ̄ _CN10 // // Servos // -#define SERVO0_PIN PB4 // PWM Capable, TIM3_CH1 -#define SERVO1_PIN PB5 // PWM Capable, TIM3_CH2 +#define SERVO0_PIN PB4 // PWM Capable, TIM3_CH1 +#define SERVO1_PIN PB5 // PWM Capable, TIM3_CH2 // SPI for external SD Card (Not entirely sure this will work) -#define SCK_PIN PA5 -#define MISO_PIN PA6 -#define MOSI_PIN PA7 -#define SS_PIN PA4 +#define SD_SCK_PIN PA5 +#define SD_MISO_PIN PA6 +#define SD_MOSI_PIN PA7 +#define SD_SS_PIN PA4 #define SDSS PA4 -#define LED_PIN LED_BLUE +#define LED_PIN LED_BLUE // // LCD / Controller // -#if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) - #define BEEPER_PIN PC7 // LCD_BEEPER +#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_D4 PB13 // LCD_D4 - // #define LCD_PINS_D5 - // #define LCD_PINS_D6 - // #define LCD_PINS_D7 #define BTN_EN1 PF13 // BTN_EN1 - #define BTN_EN2 PE9 // BTN_EN2 + #define BTN_EN2 PE9 // BTN_EN2 #define BOARD_ST7920_DELAY_1 DELAY_NS(125) #define BOARD_ST7920_DELAY_2 DELAY_NS(63) diff --git a/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h b/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h index c3dc004728d8..133dcd2935d3 100644 --- a/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h +++ b/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h @@ -33,7 +33,7 @@ #endif #if HOTENDS > 1 || E_STEPPERS > 1 - #error "RemRam supports only one hotend / E-stepper." + #error "RemRam only supports one hotend / E-stepper. Comment out this line to continue." #endif // diff --git a/Marlin/src/pins/stm32f7/pins_THE_BORG.h b/Marlin/src/pins/stm32f7/pins_THE_BORG.h deleted file mode 100644 index c050824a83da..000000000000 --- a/Marlin/src/pins/stm32f7/pins_THE_BORG.h +++ /dev/null @@ -1,183 +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 - -#if NOT_TARGET(STM32F7) - #error "Oops! Select an STM32F7 board in 'Tools > Board.'" -#elif HOTENDS > 3 || E_STEPPERS > 3 - #error "The-Borg supports up to 3 hotends / E-steppers." -#endif - -#define BOARD_INFO_NAME "The-Borge" -#define DEFAULT_MACHINE_NAME BOARD_INFO_NAME - -#ifndef MARLIN_EEPROM_SIZE - #define MARLIN_EEPROM_SIZE 0x1000 -#endif - -// Ignore temp readings during development. -//#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 - -// -// Limit Switches -// -#define X_MIN_PIN PE9 -#define X_MAX_PIN PE10 -#define Y_MIN_PIN PE7 -#define Y_MAX_PIN PE8 -#define Z_MIN_PIN PF15 -#define Z_MAX_PIN PG0 -#define E_MIN_PIN PE2 -#define E_MAX_PIN PE3 - -// -// Z Probe (when not Z_MIN_PIN) -// -#ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN PA4 -#endif - -// -// Steppers -// -#define STEPPER_ENABLE_PIN PE0 - -#define X_STEP_PIN PC6 // 96, 39 in Arduino -#define X_DIR_PIN PC7 -#define X_ENABLE_PIN PC8 - -#define Y_STEP_PIN PD9 -#define Y_DIR_PIN PD10 -#define Y_ENABLE_PIN PD11 - -#define Z_STEP_PIN PE15 -#define Z_DIR_PIN PG1 -#define Z_ENABLE_PIN PD8 - -#define E0_STEP_PIN PB1 -#define E0_DIR_PIN PB2 -#define E0_ENABLE_PIN PE11 - -#define E1_STEP_PIN PC4 -#define E1_DIR_PIN PC5 -#define E1_ENABLE_PIN PB0 - -#define E2_STEP_PIN PC13 -#define E2_DIR_PIN PC14 -#define E2_ENABLE_PIN PC15 - -#define Z2_STEP_PIN PC13 -#define Z2_DIR_PIN PC14 -#define Z2_ENABLE_PIN PC15 - -#define SCK_PIN PA5 -#define MISO_PIN PA6 -#define MOSI_PIN PA7 - -#define SPI1_SCK_PIN PA5 -#define SPI1_MISO_PIN PA6 -#define SPI1_MOSI_PIN PA7 - -#define SPI6_SCK_PIN PG13 -#define SPI6_MISO_PIN PG12 -#define SPI6_MOSI_PIN PG14 - -// -// Temperature Sensors -// - -#define TEMP_0_PIN PC3 // Analog Input -#define TEMP_1_PIN PC2 // Analog Input -#define TEMP_2_PIN PC1 // Analog Input -#define TEMP_3_PIN PC0 // Analog Input - -#define TEMP_BED_PIN PF10 // Analog Input - -#define TEMP_5_PIN PE12 // Analog Input, Probe temp - -// -// Heaters / Fans -// -#define HEATER_0_PIN PD15 -#define HEATER_1_PIN PD14 -#define HEATER_BED_PIN PF6 - -#ifndef FAN_PIN - #define FAN_PIN PD13 -#endif -#define FAN1_PIN PA0 -#define FAN2_PIN PA1 - -#ifndef E0_AUTO_FAN_PIN - #define E0_AUTO_FAN_PIN PA1 -#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 -// - -#define E_MUX0_PIN PG3 -#define E_MUX1_PIN PG4 - -// -// Servos -// - -#define SERVO0_PIN PE13 -#define SERVO1_PIN PE14 - -#define SDSS PA8 -#define SS_PIN PA8 -#define LED_PIN PA2 // Alive -#define PS_ON_PIN PA3 -#define KILL_PIN -1 //PD5 // EXP2-10 -#define PWR_LOSS PG5 // Power loss / nAC_FAULT - -// -// MAX7219_DEBUG -// -#define MAX7219_CLK_PIN PG10 // EXP1-1 -#define MAX7219_DIN_PIN PD7 // EXP1-3 -#define MAX7219_LOAD_PIN PD1 // EXP1-5 - -// -// LCD / Controller -// -//#define SD_DETECT_PIN -1 //PB6) // EXP2-4 -#define BEEPER_PIN PG10 // EXP1-1 -#define LCD_PINS_RS PG9 // EXP1-4 -#define LCD_PINS_ENABLE PD7 // EXP1-3 -#define LCD_PINS_D4 PD1 // EXP1-5 -#define LCD_PINS_D5 PF0 // EXP1-6 -#define LCD_PINS_D6 PD3 // EXP1-7 -#define LCD_PINS_D7 PD4 // EXP1-8 -#define BTN_EN1 PD6 // EXP2-5 -#define BTN_EN2 PD0 // EXP2-3 -#define BTN_ENC PG11 // EXP1-2 diff --git a/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX.h b/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX.h new file mode 100644 index 000000000000..d85bbf7bed95 --- /dev/null +++ b/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX.h @@ -0,0 +1,239 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#if NOT_TARGET(STM32H7) + #error "Oops! Select an STM32H7 board in 'Tools > Board.'" +#endif + +#define BOARD_INFO_NAME "BTT SKR SE BX" +#define DEFAULT_MACHINE_NAME "BIQU-BX" + +// Onboard I2C EEPROM +#define I2C_EEPROM +#define MARLIN_EEPROM_SIZE 0x1000 // 4KB (24C32 ... 32Kb = 4KB) + +// USB Flash Drive support +#define HAS_OTG_USB_HOST_SUPPORT + +// +// Limit Switches +// +#define X_MIN_PIN PB11 +#define X_MAX_PIN PD13 +#define Y_MIN_PIN PB12 +#define Y_MAX_PIN PB13 +#define Z_MIN_PIN PD12 +#define Z_MAX_PIN PD11 + +#define FIL_RUNOUT_PIN PD13 +#define FIL_RUNOUT2_PIN PB13 + +#define LED_PIN PA13 +#define BEEPER_PIN PA14 + +#define TFT_BACKLIGHT_PIN PB5 + +#define POWER_MONITOR_PIN PB0 +#define RPI_POWER_PIN PE5 + +#define SAFE_POWER_PIN PI11 +#define SERVO0_PIN PA2 + +// +// Z Probe (when not Z_MIN_PIN) +// +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN PH2 // Probe +#endif + +// +// Steppers +// +#define X_STEP_PIN PG13 +#define X_DIR_PIN PG12 +#define X_ENABLE_PIN PG14 +#define X_CS_PIN PG10 + +#define Y_STEP_PIN PB3 +#define Y_DIR_PIN PD3 +#define Y_ENABLE_PIN PB4 +#define Y_CS_PIN PD4 + +#define Z_STEP_PIN PD7 +#define Z_DIR_PIN PD6 +#define Z_ENABLE_PIN PG9 +#define Z_CS_PIN PD5 + +#define E0_STEP_PIN PC14 +#define E0_DIR_PIN PC13 +#define E0_ENABLE_PIN PC15 +#define E0_CS_PIN PI8 + +#define E1_STEP_PIN PA8 +#define E1_DIR_PIN PC9 +#define E1_ENABLE_PIN PD2 +#define E1_CS_PIN PC8 + +// +// Software 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 +#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 Serial + //#define X2_HARDWARE_SERIAL Serial1 + //#define Y_HARDWARE_SERIAL Serial1 + //#define Y2_HARDWARE_SERIAL Serial1 + //#define Z_HARDWARE_SERIAL Serial1 + //#define Z2_HARDWARE_SERIAL Serial1 + //#define E0_HARDWARE_SERIAL Serial1 + //#define E1_HARDWARE_SERIAL Serial1 + //#define E2_HARDWARE_SERIAL Serial1 + //#define E3_HARDWARE_SERIAL Serial1 + //#define E4_HARDWARE_SERIAL Serial1 + //#define E5_HARDWARE_SERIAL Serial1 + //#define E6_HARDWARE_SERIAL Serial1 + //#define E7_HARDWARE_SERIAL Serial1 + + // + // Software serial + // + #define X_SERIAL_TX_PIN PG10 + #define X_SERIAL_RX_PIN PG10 + + #define Y_SERIAL_TX_PIN PD4 + #define Y_SERIAL_RX_PIN PD4 + + #define Z_SERIAL_TX_PIN PD5 + #define Z_SERIAL_RX_PIN PD5 + + #define E0_SERIAL_TX_PIN PI8 + #define E0_SERIAL_RX_PIN PI8 + + #define E1_SERIAL_TX_PIN PC8 + #define E1_SERIAL_RX_PIN PC8 + + // Reduce baud rate to improve software serial reliability + #define TMC_BAUD_RATE 19200 +#endif + +// +// Temperature Sensors +// +#define TEMP_0_PIN PH4 // TH0 +#define TEMP_1_PIN PA3 // TH1 +#define TEMP_BED_PIN PH5 // TB + +// +// Heaters / Fans +// +#define HEATER_0_PIN PC4 +#define HEATER_1_PIN PC5 +#define HEATER_BED_PIN PA4 + +#define FAN_PIN PA5 // "FAN0" +#define FAN1_PIN PA6 // "FAN1" +#define FAN2_PIN PA7 // "FAN2" + +#define NEOPIXEL_PIN PH3 +#define NEOPIXEL2_PIN PB1 + +#if HAS_LTDC_TFT + + // LTDC_LCD Timing + #define LTDC_LCD_CLK 50 // LTDC clock frequency = 50Mhz + #define LTDC_LCD_HSYNC 30 // Horizontal synchronization + #define LTDC_LCD_HBP 114 // Horizontal back porch + #define LTDC_LCD_HFP 16 // Horizontal front porch + #define LTDC_LCD_VSYNC 3 // Vertical synchronization + #define LTDC_LCD_VBP 32 // Vertical back porch + #define LTDC_LCD_VFP 10 // Vertical front porch + + #define TFT_BACKLIGHT_PIN PB5 + #define LCD_DE_PIN PF10 + #define LCD_CLK_PIN PG7 + #define LCD_VSYNC_PIN PI9 + #define LCD_HSYNC_PIN PI10 + #define LCD_R7_PIN PG6 // R5 + #define LCD_R6_PIN PH12 + #define LCD_R5_PIN PH11 + #define LCD_R4_PIN PH10 + #define LCD_R3_PIN PH9 + #define LCD_G7_PIN PI2 // G6 + #define LCD_G6_PIN PI1 + #define LCD_G5_PIN PI0 + #define LCD_G4_PIN PH15 + #define LCD_G3_PIN PH14 + #define LCD_G2_PIN PH13 + #define LCD_B7_PIN PI7 // B5 + #define LCD_B6_PIN PI6 + #define LCD_B5_PIN PI5 + #define LCD_B4_PIN PI4 + #define LCD_B3_PIN PG11 + + // GT911 Capacitive Touch Sensor + #if ENABLED(TFT_TOUCH_DEVICE_GT911) + #define GT911_RST_PIN PE4 + #define GT911_INT_PIN PE3 + #define GT911_SW_I2C_SCL_PIN PE2 + #define GT911_SW_I2C_SDA_PIN PE6 + #endif + +#endif + +#if IS_NEWPANEL + #define BTN_EN1 PH6 + #define BTN_EN2 PH7 + #define BTN_ENC PH8 +#endif + +// +// SD card +// +#ifndef SDCARD_CONNECTION + #define SDCARD_CONNECTION ONBOARD +#endif + +#define SOFTWARE_SPI +#define SDSS PA15 +#define SD_SS_PIN SDSS +#define SD_SCK_PIN PC10 +#define SD_MISO_PIN PC11 +#define SD_MOSI_PIN PC12 +#define SD_DETECT_PIN PI3 diff --git a/Marlin/src/pins/teensy2/env_validate.h b/Marlin/src/pins/teensy2/env_validate.h new file mode 100644 index 000000000000..5f0ea4f3b672 --- /dev/null +++ b/Marlin/src/pins/teensy2/env_validate.h @@ -0,0 +1,28 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#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 diff --git a/Marlin/src/pins/teensy2/pins_5DPRINT.h b/Marlin/src/pins/teensy2/pins_5DPRINT.h index 908e12e0bae2..6e1f9c021746 100644 --- a/Marlin/src/pins/teensy2/pins_5DPRINT.h +++ b/Marlin/src/pins/teensy2/pins_5DPRINT.h @@ -68,9 +68,7 @@ * https://bitbucket.org/makible/5dprint-d8-controller-board */ -#if NOT_TARGET(__AVR_AT90USB1286__) - #error "Oops! Select 'Teensy++ 2.0' or 'Printrboard' in 'Tools > Board.'" -#endif +#include "env_validate.h" #define DEFAULT_MACHINE_NAME "Makibox" #define BOARD_INFO_NAME "5DPrint D8" diff --git a/Marlin/src/pins/teensy2/pins_BRAINWAVE.h b/Marlin/src/pins/teensy2/pins_BRAINWAVE.h index 97d210a0f852..cdcc249c00d2 100644 --- a/Marlin/src/pins/teensy2/pins_BRAINWAVE.h +++ b/Marlin/src/pins/teensy2/pins_BRAINWAVE.h @@ -69,7 +69,7 @@ */ #if NOT_TARGET(__AVR_AT90USB646__) - #error "Oops! Select 'AT90USB646_TEENSYPP' in 'Tools > Board.'" + #error "Oops! Select 'Brainwave' in 'Tools > Board.'" #endif #define BOARD_INFO_NAME "Brainwave" diff --git a/Marlin/src/pins/teensy2/pins_BRAINWAVE_PRO.h b/Marlin/src/pins/teensy2/pins_BRAINWAVE_PRO.h index e41fcaab9442..319130ef968d 100644 --- a/Marlin/src/pins/teensy2/pins_BRAINWAVE_PRO.h +++ b/Marlin/src/pins/teensy2/pins_BRAINWAVE_PRO.h @@ -75,9 +75,7 @@ * 4. The programmer is no longer needed. Remove it. */ -#if NOT_TARGET(__AVR_AT90USB1286__) - #error "Oops! Select 'Teensy++ 2.0' or 'Printrboard' in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "Brainwave Pro" diff --git a/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h b/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h index ffecc03b4a25..cb038fe73702 100644 --- a/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h +++ b/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h @@ -62,9 +62,7 @@ * 4. The programmer is no longer needed. Remove it. */ -#if NOT_TARGET(__AVR_AT90USB1286__) - #error "Oops! Select 'Teensy++ 2.0' or 'Printrboard' in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "Printrboard" @@ -118,13 +116,12 @@ // // Misc. Functions // -#define SDSS 26 // B6 SDCS #define FILWIDTH_PIN 2 // Analog Input // // LCD / Controller // -#if BOTH(ULTRA_LCD, NEWPANEL) +#if IS_ULTRA_LCD && IS_NEWPANEL #define LCD_PINS_RS 9 // E1 JP11-11 #define LCD_PINS_ENABLE 8 // E0 JP11-10 @@ -144,7 +141,6 @@ #define BTN_EN2 3 // D3 RX1 JP2-7 #define BTN_ENC 45 // F7 TDI JP2-12 - #undef SDSS #define SDSS 43 // F5 TMS JP2-8 #define STAT_LED_RED_PIN 12 // C2 JP11-14 @@ -155,7 +151,7 @@ #define BTN_EN1 3 // D3 RX1 JP2-7 #define BTN_EN2 2 // D2 TX1 JP2-5 #define BTN_ENC 41 // F3 JP2-4 - #undef SDSS + #define SDSS 38 // F0 B-THERM connector - use SD card on Panelolu2 #else @@ -166,4 +162,8 @@ #endif -#endif // ULTRA_LCD && NEWPANEL +#endif // IS_ULTRA_LCD && IS_NEWPANEL + +#ifndef SDSS + #define SDSS 26 // B6 SDCS +#endif diff --git a/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h b/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h index d4f9fc76415d..539a3bb8f3df 100644 --- a/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h +++ b/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h @@ -63,9 +63,7 @@ * 4. The programmer is no longer needed. Remove it. */ -#if NOT_TARGET(__AVR_AT90USB1286__) - #error "Oops! Select 'Teensy++ 2.0' or 'Printrboard' in 'Tools > Board.'" -#endif +#include "env_validate.h" #if !defined(__MARLIN_DEPS__) && !defined(USBCON) #error "USBCON should be defined by the platform for this board." @@ -143,7 +141,7 @@ #endif // NO_EXTRUDRBOARD // Enable control of stepper motor currents with the I2C based MCP4728 DAC used on Printrboard REVF -#define HAS_MOTOR_CURRENT_DAC +#define HAS_MOTOR_CURRENT_DAC 1 // Set default drive strength percents if not already defined - X, Y, Z, E axis #ifndef DAC_MOTOR_CURRENT_DEFAULT diff --git a/Marlin/src/pins/teensy2/pins_SAV_MKI.h b/Marlin/src/pins/teensy2/pins_SAV_MKI.h index 4d083ecd12e2..cdba535090e4 100644 --- a/Marlin/src/pins/teensy2/pins_SAV_MKI.h +++ b/Marlin/src/pins/teensy2/pins_SAV_MKI.h @@ -62,13 +62,11 @@ * 4. The programmer is no longer needed. Remove it. */ -#if NOT_TARGET(__AVR_AT90USB1286__) - #error "Oops! Select 'Teensy++ 2.0' or 'Printrboard' in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "SAV MkI" #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME -#define DEFAULT_SOURCE_CODE_URL "https://tinyurl.com/onru38b" +#define DEFAULT_SOURCE_CODE_URL "tinyurl.com/onru38b" // // Servos diff --git a/Marlin/src/pins/teensy2/pins_TEENSY2.h b/Marlin/src/pins/teensy2/pins_TEENSY2.h index 4efd83d9bc5c..efb409bf3259 100644 --- a/Marlin/src/pins/teensy2/pins_TEENSY2.h +++ b/Marlin/src/pins/teensy2/pins_TEENSY2.h @@ -107,9 +107,7 @@ * E DIR 35 a7 a3 31 Y DIR */ -#if NOT_TARGET(__AVR_AT90USB1286__) - #error "Oops! Select 'Teensy++ 2.0' or 'Printrboard' in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "Teensy++2.0" @@ -168,7 +166,7 @@ // // LCD / Controller // -#if ENABLED(ULTIPANEL) +#if IS_ULTIPANEL #define LCD_PINS_RS 8 // E0 #define LCD_PINS_ENABLE 9 // E1 #define LCD_PINS_D4 10 // C0 diff --git a/Marlin/src/pins/teensy2/pins_TEENSYLU.h b/Marlin/src/pins/teensy2/pins_TEENSYLU.h index 9de119b62b4a..535ce534d437 100644 --- a/Marlin/src/pins/teensy2/pins_TEENSYLU.h +++ b/Marlin/src/pins/teensy2/pins_TEENSYLU.h @@ -18,6 +18,7 @@ * You should have received a copy of the GNU General Public License * along with this program. If not, see . */ +#pragma once /** * Rev C 2 JUN 2017 @@ -72,6 +73,9 @@ * The pin assignments in this file match the silkscreen. */ +#define ALLOW_AT90USB1286P +#include "env_validate.h" + #if NOT_TARGET(__AVR_AT90USB1286__, __AVR_AT90USB1286P__) #error "Oops! Select 'Teensy++ 2.0' or 'Printrboard' in 'Tools > Board.'" #endif @@ -141,7 +145,7 @@ // // LCD / Controller // -#if BOTH(ULTRA_LCD, NEWPANEL) +#if IS_ULTRA_LCD && IS_NEWPANEL #define BEEPER_PIN -1 @@ -154,7 +158,7 @@ #define SD_DETECT_PIN -1 -#endif // ULTRA_LCD && NEWPANEL +#endif // IS_ULTRA_LCD && IS_NEWPANEL // // M3/M4/M5 - Spindle/Laser Control diff --git a/Marlin/src/pins/teensy3/pins_TEENSY35_36.h b/Marlin/src/pins/teensy3/pins_TEENSY35_36.h index 2e09c8a425ca..71c348536a7f 100644 --- a/Marlin/src/pins/teensy3/pins_TEENSY35_36.h +++ b/Marlin/src/pins/teensy3/pins_TEENSY35_36.h @@ -139,14 +139,14 @@ #define LCD_PINS_D7 45 #endif -#if ENABLED(NEWPANEL) +#if IS_NEWPANEL #define BTN_EN1 46 #define BTN_EN2 47 #define BTN_ENC 48 #endif -#if ENABLED(REPRAPWORLD_KEYPAD) - #define SHIFT_OUT 40 - #define SHIFT_CLK 44 - #define SHIFT_LD 42 +#if IS_RRW_KEYPAD + #define SHIFT_OUT_PIN 40 + #define SHIFT_CLK_PIN 44 + #define SHIFT_LD_PIN 42 #endif diff --git a/Marlin/src/sd/Sd2Card.cpp b/Marlin/src/sd/Sd2Card.cpp index 491c0692c72f..a81932d49485 100644 --- a/Marlin/src/sd/Sd2Card.cpp +++ b/Marlin/src/sd/Sd2Card.cpp @@ -30,7 +30,7 @@ #include "../inc/MarlinConfig.h" -#if ENABLED(SDSUPPORT) && NONE(USB_FLASH_DRIVE_SUPPORT, SDIO_SUPPORT) +#if NEED_SD2CARD_SPI /* Enable FAST CRC computations - You can trade speed for FLASH space if * needed by disabling the following define */ @@ -63,7 +63,7 @@ 0x0E,0x07,0x1C,0x15,0x2A,0x23,0x38,0x31,0x46,0x4F,0x54,0x5D,0x62,0x6B,0x70,0x79 }; - static uint8_t CRC7(const uint8_t* data, uint8_t n) { + static uint8_t CRC7(const uint8_t *data, uint8_t n) { uint8_t crc = 0; while (n > 0) { crc = pgm_read_byte(&crctab7[ (crc << 1) ^ *data++ ]); @@ -72,7 +72,7 @@ return (crc << 1) | 1; } #else - static uint8_t CRC7(const uint8_t* data, uint8_t n) { + static uint8_t CRC7(const uint8_t *data, uint8_t n) { uint8_t crc = 0; LOOP_L_N(i, n) { uint8_t d = data[i]; @@ -88,7 +88,12 @@ #endif // Send command and return error code. Return zero for OK -uint8_t Sd2Card::cardCommand(const uint8_t cmd, const uint32_t arg) { +uint8_t DiskIODriver_SPI_SD::cardCommand(const uint8_t cmd, const uint32_t arg) { + + #if ENABLED(SDCARD_COMMANDS_SPLIT) + if (cmd != CMD12) chipDeselect(); + #endif + // Select card chipSelect(); @@ -133,7 +138,7 @@ uint8_t Sd2Card::cardCommand(const uint8_t cmd, const uint32_t arg) { * \return The number of 512 byte data blocks in the card * or zero if an error occurs. */ -uint32_t Sd2Card::cardSize() { +uint32_t DiskIODriver_SPI_SD::cardSize() { csd_t csd; if (!readCSD(&csd)) return 0; if (csd.v1.csd_ver == 0) { @@ -155,12 +160,12 @@ uint32_t Sd2Card::cardSize() { } } -void Sd2Card::chipDeselect() { +void DiskIODriver_SPI_SD::chipDeselect() { extDigitalWrite(chipSelectPin_, HIGH); spiSend(0xFF); // Ensure MISO goes high impedance } -void Sd2Card::chipSelect() { +void DiskIODriver_SPI_SD::chipSelect() { spiInit(spiRate_); extDigitalWrite(chipSelectPin_, LOW); } @@ -178,7 +183,7 @@ void Sd2Card::chipSelect() { * * \return true for success, false for failure. */ -bool Sd2Card::erase(uint32_t firstBlock, uint32_t lastBlock) { +bool DiskIODriver_SPI_SD::erase(uint32_t firstBlock, uint32_t lastBlock) { if (ENABLED(SDCARD_READONLY)) return false; csd_t csd; @@ -216,7 +221,7 @@ bool Sd2Card::erase(uint32_t firstBlock, uint32_t lastBlock) { * \return true if single block erase is supported. * false if single block erase is not supported. */ -bool Sd2Card::eraseSingleBlockEnable() { +bool DiskIODriver_SPI_SD::eraseSingleBlockEnable() { csd_t csd; return readCSD(&csd) ? csd.v1.erase_blk_en : false; } @@ -230,7 +235,7 @@ bool Sd2Card::eraseSingleBlockEnable() { * \return true for success, false for failure. * The reason for failure can be determined by calling errorCode() and errorData(). */ -bool Sd2Card::init(const uint8_t sckRateID, const pin_t chipSelectPin) { +bool DiskIODriver_SPI_SD::init(const uint8_t sckRateID, const pin_t chipSelectPin) { #if IS_TEENSY_35_36 || IS_TEENSY_40_41 chipSelectPin_ = BUILTIN_SDCARD; const uint8_t ret = SDHC_CardInit(); @@ -324,10 +329,12 @@ bool Sd2Card::init(const uint8_t sckRateID, const pin_t chipSelectPin) { } chipDeselect(); + ready = true; return setSckRate(sckRateID); FAIL: chipDeselect(); + ready = false; return false; } @@ -338,7 +345,7 @@ bool Sd2Card::init(const uint8_t sckRateID, const pin_t chipSelectPin) { * \param[out] dst Pointer to the location that will receive the data. * \return true for success, false for failure. */ -bool Sd2Card::readBlock(uint32_t blockNumber, uint8_t* dst) { +bool DiskIODriver_SPI_SD::readBlock(uint32_t blockNumber, uint8_t *dst) { #if IS_TEENSY_35_36 || IS_TEENSY_40_41 return 0 == SDHC_CardReadBlock(dst, blockNumber); #endif @@ -378,7 +385,7 @@ bool Sd2Card::readBlock(uint32_t blockNumber, uint8_t* dst) { * * \return true for success, false for failure. */ -bool Sd2Card::readData(uint8_t* dst) { +bool DiskIODriver_SPI_SD::readData(uint8_t *dst) { chipSelect(); return readData(dst, 512); } @@ -421,7 +428,7 @@ bool Sd2Card::readData(uint8_t* dst) { }; // faster CRC-CCITT // uses the x^16,x^12,x^5,x^1 polynomial. - static uint16_t CRC_CCITT(const uint8_t* data, size_t n) { + static uint16_t CRC_CCITT(const uint8_t *data, size_t n) { uint16_t crc = 0; for (size_t i = 0; i < n; i++) { crc = pgm_read_word(&crctab16[(crc >> 8 ^ data[i]) & 0xFF]) ^ (crc << 8); @@ -431,7 +438,7 @@ bool Sd2Card::readData(uint8_t* dst) { #else // slower CRC-CCITT // uses the x^16,x^12,x^5,x^1 polynomial. - static uint16_t CRC_CCITT(const uint8_t* data, size_t n) { + static uint16_t CRC_CCITT(const uint8_t *data, size_t n) { uint16_t crc = 0; for (size_t i = 0; i < n; i++) { crc = (uint8_t)(crc >> 8) | (crc << 8); @@ -445,7 +452,7 @@ bool Sd2Card::readData(uint8_t* dst) { #endif #endif // SD_CHECK_AND_RETRY -bool Sd2Card::readData(uint8_t* dst, const uint16_t count) { +bool DiskIODriver_SPI_SD::readData(uint8_t *dst, const uint16_t count) { bool success = false; const millis_t read_timeout = millis() + SD_READ_TIMEOUT; @@ -477,8 +484,8 @@ bool Sd2Card::readData(uint8_t* dst, const uint16_t count) { } /** read CID or CSR register */ -bool Sd2Card::readRegister(const uint8_t cmd, void* buf) { - uint8_t* dst = reinterpret_cast(buf); +bool DiskIODriver_SPI_SD::readRegister(const uint8_t cmd, void *buf) { + uint8_t *dst = reinterpret_cast(buf); if (cardCommand(cmd, 0)) { error(SD_CARD_ERROR_READ_REG); chipDeselect(); @@ -497,7 +504,7 @@ bool Sd2Card::readRegister(const uint8_t cmd, void* buf) { * * \return true for success, false for failure. */ -bool Sd2Card::readStart(uint32_t blockNumber) { +bool DiskIODriver_SPI_SD::readStart(uint32_t blockNumber) { if (type() != SD_CARD_TYPE_SDHC) blockNumber <<= 9; const bool success = !cardCommand(CMD18, blockNumber); @@ -511,7 +518,7 @@ bool Sd2Card::readStart(uint32_t blockNumber) { * * \return true for success, false for failure. */ -bool Sd2Card::readStop() { +bool DiskIODriver_SPI_SD::readStop() { chipSelect(); const bool success = !cardCommand(CMD12, 0); if (!success) error(SD_CARD_ERROR_CMD12); @@ -531,7 +538,7 @@ bool Sd2Card::readStop() { * \return The value one, true, is returned for success and the value zero, * false, is returned for an invalid value of \a sckRateID. */ -bool Sd2Card::setSckRate(const uint8_t sckRateID) { +bool DiskIODriver_SPI_SD::setSckRate(const uint8_t sckRateID) { const bool success = (sckRateID <= 6); if (success) spiRate_ = sckRateID; else error(SD_CARD_ERROR_SCK_RATE); return success; @@ -542,12 +549,14 @@ bool Sd2Card::setSckRate(const uint8_t sckRateID) { * \param[in] timeout_ms Timeout to abort. * \return true for success, false for timeout. */ -bool Sd2Card::waitNotBusy(const millis_t timeout_ms) { +bool DiskIODriver_SPI_SD::waitNotBusy(const millis_t timeout_ms) { const millis_t wait_timeout = millis() + timeout_ms; while (spiRec() != 0xFF) if (ELAPSED(millis(), wait_timeout)) return false; return true; } +void DiskIODriver_SPI_SD::error(const uint8_t code) { errorCode_ = code; } + /** * Write a 512 byte block to an SD card. * @@ -555,7 +564,7 @@ bool Sd2Card::waitNotBusy(const millis_t timeout_ms) { * \param[in] src Pointer to the location of the data to be written. * \return true for success, false for failure. */ -bool Sd2Card::writeBlock(uint32_t blockNumber, const uint8_t* src) { +bool DiskIODriver_SPI_SD::writeBlock(uint32_t blockNumber, const uint8_t *src) { if (ENABLED(SDCARD_READONLY)) return false; #if IS_TEENSY_35_36 || IS_TEENSY_40_41 @@ -586,7 +595,7 @@ bool Sd2Card::writeBlock(uint32_t blockNumber, const uint8_t* src) { * \param[in] src Pointer to the location of the data to be written. * \return true for success, false for failure. */ -bool Sd2Card::writeData(const uint8_t* src) { +bool DiskIODriver_SPI_SD::writeData(const uint8_t *src) { if (ENABLED(SDCARD_READONLY)) return false; bool success = true; @@ -601,7 +610,7 @@ bool Sd2Card::writeData(const uint8_t* src) { } // Send one block of data for write block or write multiple blocks -bool Sd2Card::writeData(const uint8_t token, const uint8_t* src) { +bool DiskIODriver_SPI_SD::writeData(const uint8_t token, const uint8_t *src) { if (ENABLED(SDCARD_READONLY)) return false; const uint16_t crc = TERN(SD_CHECK_AND_RETRY, CRC_CCITT(src, 512), 0xFFFF); @@ -629,7 +638,7 @@ bool Sd2Card::writeData(const uint8_t token, const uint8_t* src) { * * \return true for success, false for failure. */ -bool Sd2Card::writeStart(uint32_t blockNumber, const uint32_t eraseCount) { +bool DiskIODriver_SPI_SD::writeStart(uint32_t blockNumber, const uint32_t eraseCount) { if (ENABLED(SDCARD_READONLY)) return false; bool success = false; @@ -650,7 +659,7 @@ bool Sd2Card::writeStart(uint32_t blockNumber, const uint32_t eraseCount) { * * \return true for success, false for failure. */ -bool Sd2Card::writeStop() { +bool DiskIODriver_SPI_SD::writeStop() { if (ENABLED(SDCARD_READONLY)) return false; bool success = false; @@ -666,4 +675,4 @@ bool Sd2Card::writeStop() { return success; } -#endif // SDSUPPORT +#endif // NEED_SD2CARD_SPI diff --git a/Marlin/src/sd/Sd2Card.h b/Marlin/src/sd/Sd2Card.h index 6900502e03e9..e0dce02a0236 100644 --- a/Marlin/src/sd/Sd2Card.h +++ b/Marlin/src/sd/Sd2Card.h @@ -35,47 +35,50 @@ #include "SdFatConfig.h" #include "SdInfo.h" +#include "disk_io_driver.h" #include -uint16_t const SD_INIT_TIMEOUT = 2000, // init timeout ms - SD_ERASE_TIMEOUT = 10000, // erase timeout ms - SD_READ_TIMEOUT = 300, // read timeout ms - SD_WRITE_TIMEOUT = 600; // write time out ms +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 -uint8_t const SD_CARD_ERROR_CMD0 = 0x01, // timeout error for command CMD0 (initialize card in SPI mode) - SD_CARD_ERROR_CMD8 = 0x02, // CMD8 was not accepted - not a valid SD card - SD_CARD_ERROR_CMD12 = 0x03, // card returned an error response for CMD12 (write stop) - SD_CARD_ERROR_CMD17 = 0x04, // card returned an error response for CMD17 (read block) - SD_CARD_ERROR_CMD18 = 0x05, // card returned an error response for CMD18 (read multiple block) - SD_CARD_ERROR_CMD24 = 0x06, // card returned an error response for CMD24 (write block) - SD_CARD_ERROR_CMD25 = 0x07, // WRITE_MULTIPLE_BLOCKS command failed - SD_CARD_ERROR_CMD58 = 0x08, // card returned an error response for CMD58 (read OCR) - SD_CARD_ERROR_ACMD23 = 0x09, // SET_WR_BLK_ERASE_COUNT failed - SD_CARD_ERROR_ACMD41 = 0x0A, // ACMD41 initialization process timeout - SD_CARD_ERROR_BAD_CSD = 0x0B, // card returned a bad CSR version field - SD_CARD_ERROR_ERASE = 0x0C, // erase block group command failed - SD_CARD_ERROR_ERASE_SINGLE_BLOCK = 0x0D, // card not capable of single block erase - SD_CARD_ERROR_ERASE_TIMEOUT = 0x0E, // Erase sequence timed out - SD_CARD_ERROR_READ = 0x0F, // card returned an error token instead of read data - SD_CARD_ERROR_READ_REG = 0x10, // read CID or CSD failed - SD_CARD_ERROR_READ_TIMEOUT = 0x11, // timeout while waiting for start of read data - SD_CARD_ERROR_STOP_TRAN = 0x12, // card did not accept STOP_TRAN_TOKEN - SD_CARD_ERROR_WRITE = 0x13, // card returned an error token as a response to a write operation - SD_CARD_ERROR_WRITE_BLOCK_ZERO = 0x14, // REMOVE - not used ... attempt to write protected block zero - SD_CARD_ERROR_WRITE_MULTIPLE = 0x15, // card did not go ready for a multiple block write - 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 - // 0x1A is unused now, it was: card returned an error for CMD59 (CRC_ON_OFF) - SD_CARD_ERROR_READ_CRC = 0x1B; // invalid read CRC +typedef enum : uint8_t { + SD_CARD_ERROR_CMD0 = 0x01, // Timeout error for command CMD0 (initialize card in SPI mode) + SD_CARD_ERROR_CMD8 = 0x02, // CMD8 was not accepted - not a valid SD card + SD_CARD_ERROR_CMD12 = 0x03, // Card returned an error response for CMD12 (write stop) + SD_CARD_ERROR_CMD17 = 0x04, // Card returned an error response for CMD17 (read block) + SD_CARD_ERROR_CMD18 = 0x05, // Card returned an error response for CMD18 (read multiple block) + SD_CARD_ERROR_CMD24 = 0x06, // Card returned an error response for CMD24 (write block) + SD_CARD_ERROR_CMD25 = 0x07, // WRITE_MULTIPLE_BLOCKS command failed + SD_CARD_ERROR_CMD58 = 0x08, // Card returned an error response for CMD58 (read OCR) + SD_CARD_ERROR_ACMD23 = 0x09, // SET_WR_BLK_ERASE_COUNT failed + SD_CARD_ERROR_ACMD41 = 0x0A, // ACMD41 initialization process timeout + SD_CARD_ERROR_BAD_CSD = 0x0B, // Card returned a bad CSR version field + SD_CARD_ERROR_ERASE = 0x0C, // Erase block group command failed + SD_CARD_ERROR_ERASE_SINGLE_BLOCK = 0x0D, // Card not capable of single block erase + SD_CARD_ERROR_ERASE_TIMEOUT = 0x0E, // Erase sequence timed out + SD_CARD_ERROR_READ = 0x0F, // Card returned an error token instead of read data + SD_CARD_ERROR_READ_REG = 0x10, // Read CID or CSD failed + SD_CARD_ERROR_READ_TIMEOUT = 0x11, // Timeout while waiting for start of read data + SD_CARD_ERROR_STOP_TRAN = 0x12, // Card did not accept STOP_TRAN_TOKEN + SD_CARD_ERROR_WRITE = 0x13, // Card returned an error token as a response to a write operation + SD_CARD_ERROR_WRITE_BLOCK_ZERO = 0x14, // REMOVE - not used ... attempt to write protected block zero + SD_CARD_ERROR_WRITE_MULTIPLE = 0x15, // Card did not go ready for a multiple block write + 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 + // 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; // card types -uint8_t const SD_CARD_TYPE_SD1 = 1, // Standard capacity V1 SD card - SD_CARD_TYPE_SD2 = 2, // Standard capacity V2 SD card - SD_CARD_TYPE_SDHC = 3; // High Capacity SD card +uint8_t const SD_CARD_TYPE_SD1 = 1, // Standard capacity V1 SD card + SD_CARD_TYPE_SD2 = 2, // Standard capacity V2 SD card + SD_CARD_TYPE_SDHC = 3; // High Capacity SD card /** * Define SOFTWARE_SPI to use bit-bang SPI @@ -93,12 +96,11 @@ uint8_t const SD_CARD_TYPE_SD1 = 1, // Standard capacity V1 * \class Sd2Card * \brief Raw access to SD and SDHC flash memory cards. */ -class Sd2Card { +class DiskIODriver_SPI_SD : public DiskIODriver { public: - Sd2Card() : errorCode_(SD_CARD_ERROR_INIT_NOT_CALLED), type_(0) {} + DiskIODriver_SPI_SD() : errorCode_(SD_CARD_ERROR_INIT_NOT_CALLED), type_(0) {} - uint32_t cardSize(); bool erase(uint32_t firstBlock, uint32_t lastBlock); bool eraseSingleBlockEnable(); @@ -106,7 +108,7 @@ class Sd2Card { * Set SD error code. * \param[in] code value for error code. */ - inline void error(const uint8_t code) { errorCode_ = code; } + void error(const uint8_t code); /** * \return error code for last error. See Sd2Card.h for a list of error codes. @@ -122,9 +124,15 @@ class Sd2Card { * * \return true for success or false for failure. */ - bool init(const uint8_t sckRateID, const pin_t chipSelectPin); + bool init(const uint8_t sckRateID, const pin_t chipSelectPin) override; - bool readBlock(uint32_t block, uint8_t* dst); + bool setSckRate(const uint8_t sckRateID); + + /** + * Return the card type: SD V1, SD V2 or SDHC + * \return 0 - SD V1, 1 - SD V2, or 3 - SDHC. + */ + int type() const { return type_; } /** * Read a card's CID register. The CID contains card identification @@ -135,7 +143,7 @@ class Sd2Card { * * \return true for success or false for failure. */ - bool readCID(cid_t* cid) { return readRegister(CMD10, cid); } + bool readCID(cid_t *cid) { return readRegister(CMD10, cid); } /** * Read a card's CSD register. The CSD contains Card-Specific Data that @@ -145,24 +153,27 @@ class Sd2Card { * * \return true for success or false for failure. */ - inline bool readCSD(csd_t* csd) { return readRegister(CMD9, csd); } + inline bool readCSD(csd_t *csd) override { return readRegister(CMD9, csd); } - bool readData(uint8_t* dst); - bool readStart(uint32_t blockNumber); - bool readStop(); - bool setSckRate(const uint8_t sckRateID); + bool readData(uint8_t *dst) override; + bool readStart(uint32_t blockNumber) override; + bool readStop() override; - /** - * Return the card type: SD V1, SD V2 or SDHC - * \return 0 - SD V1, 1 - SD V2, or 3 - SDHC. - */ - int type() const {return type_;} - bool writeBlock(uint32_t blockNumber, const uint8_t* src); - bool writeData(const uint8_t* src); - bool writeStart(uint32_t blockNumber, const uint32_t eraseCount); - bool writeStop(); + bool writeData(const uint8_t *src) override; + bool writeStart(const uint32_t blockNumber, const uint32_t eraseCount) override; + bool writeStop() override; + + bool readBlock(uint32_t block, uint8_t *dst) override; + bool writeBlock(uint32_t blockNumber, const uint8_t *src) override; + + uint32_t cardSize() override; + + bool isReady() override { return ready; }; + + void idle() override {} private: + bool ready = false; uint8_t chipSelectPin_, errorCode_, spiRate_, @@ -176,11 +187,11 @@ class Sd2Card { } uint8_t cardCommand(const uint8_t cmd, const uint32_t arg); - bool readData(uint8_t* dst, const uint16_t count); - bool readRegister(const uint8_t cmd, void* buf); + bool readData(uint8_t *dst, const uint16_t count); + bool readRegister(const uint8_t cmd, void *buf); void chipDeselect(); void chipSelect(); inline void type(const uint8_t value) { type_ = value; } bool waitNotBusy(const millis_t timeout_ms); - bool writeData(const uint8_t token, const uint8_t* src); + bool writeData(const uint8_t token, const uint8_t *src); }; diff --git a/Marlin/src/sd/Sd2Card_sdio.h b/Marlin/src/sd/Sd2Card_sdio.h index 10fb757359f4..cc29f5d46d3c 100644 --- a/Marlin/src/sd/Sd2Card_sdio.h +++ b/Marlin/src/sd/Sd2Card_sdio.h @@ -23,17 +23,37 @@ #include "../inc/MarlinConfig.h" -#if ENABLED(SDIO_SUPPORT) +#include "SdInfo.h" +#include "disk_io_driver.h" bool SDIO_Init(); bool SDIO_ReadBlock(uint32_t block, uint8_t *dst); bool SDIO_WriteBlock(uint32_t block, const uint8_t *src); +bool SDIO_IsReady(); +uint32_t SDIO_GetCardSize(); -class Sd2Card { +class DiskIODriver_SDIO : public DiskIODriver { public: - bool init(uint8_t sckRateID = 0, uint8_t chipSelectPin = 0) { return SDIO_Init(); } - bool readBlock(uint32_t block, uint8_t *dst) { return SDIO_ReadBlock(block, dst); } - bool writeBlock(uint32_t block, const uint8_t *src) { return SDIO_WriteBlock(block, src); } -}; + bool init(const uint8_t sckRateID=0, const pin_t chipSelectPin=0) override { return SDIO_Init(); } + + bool readCSD(csd_t *csd) override { return false; } + + bool readStart(const uint32_t block) override { curBlock = block; return true; } + bool readData(uint8_t *dst) override { return readBlock(curBlock++, dst); } + bool readStop() override { curBlock = -1; return true; } + + bool writeStart(const uint32_t block, const uint32_t) override { curBlock = block; return true; } + bool writeData(const uint8_t *src) override { return writeBlock(curBlock++, src); } + bool writeStop() override { curBlock = -1; return true; } -#endif // SDIO_SUPPORT + bool readBlock(uint32_t block, uint8_t *dst) override { return SDIO_ReadBlock(block, dst); } + bool writeBlock(uint32_t block, const uint8_t *src) override { return SDIO_WriteBlock(block, src); } + + uint32_t cardSize() override { return SDIO_GetCardSize(); } + + bool isReady() override { return SDIO_IsReady(); } + + void idle() override {} + private: + uint32_t curBlock; +}; diff --git a/Marlin/src/sd/SdBaseFile.cpp b/Marlin/src/sd/SdBaseFile.cpp index 2bc9f96e8c92..b357495a3edb 100644 --- a/Marlin/src/sd/SdBaseFile.cpp +++ b/Marlin/src/sd/SdBaseFile.cpp @@ -21,12 +21,12 @@ */ #if __GNUC__ > 8 - // The NXP platform updated GCC from 7.2.1 to 9.2.1 - // and this new warning apparently can be ignored. #pragma GCC diagnostic ignored "-Waddress-of-packed-member" #endif /** + * sd/SdBaseFile.cpp + * * Arduino SdFat Library * Copyright (c) 2009 by William Greiman * @@ -40,10 +40,10 @@ #include "SdBaseFile.h" #include "../MarlinCore.h" -SdBaseFile* SdBaseFile::cwd_ = 0; // Pointer to Current Working Directory +SdBaseFile *SdBaseFile::cwd_ = 0; // Pointer to Current Working Directory // callback function for date/time -void (*SdBaseFile::dateTime_)(uint16_t* date, uint16_t* time) = 0; +void (*SdBaseFile::dateTime_)(uint16_t *date, uint16_t *time) = 0; // add a cluster to a file bool SdBaseFile::addCluster() { @@ -118,7 +118,7 @@ bool SdBaseFile::close() { * Reasons for failure include file is not contiguous, file has zero length * or an I/O error occurred. */ -bool SdBaseFile::contiguousRange(uint32_t* bgnBlock, uint32_t* endBlock) { +bool SdBaseFile::contiguousRange(uint32_t *bgnBlock, uint32_t *endBlock) { // error if no blocks if (firstCluster_ == 0) return false; @@ -155,7 +155,7 @@ bool SdBaseFile::contiguousRange(uint32_t* bgnBlock, uint32_t* endBlock) { * a file is already open, the file already exists, the root * directory is full or an I/O error. */ -bool SdBaseFile::createContiguous(SdBaseFile* dirFile, const char* path, uint32_t size) { +bool SdBaseFile::createContiguous(SdBaseFile *dirFile, const char *path, uint32_t size) { if (ENABLED(SDCARD_READONLY)) return false; uint32_t count; @@ -186,13 +186,12 @@ bool SdBaseFile::createContiguous(SdBaseFile* dirFile, const char* path, uint32_ * * \return true for success, false for failure. */ -bool SdBaseFile::dirEntry(dir_t* dir) { - dir_t* p; +bool SdBaseFile::dirEntry(dir_t *dir) { // make sure fields on SD are correct if (!sync()) return false; // read entry - p = cacheDirEntry(SdVolume::CACHE_FOR_READ); + dir_t *p = cacheDirEntry(SdVolume::CACHE_FOR_READ); if (!p) return false; // copy to caller's struct @@ -207,7 +206,7 @@ bool SdBaseFile::dirEntry(dir_t* dir) { * \param[in] dir The directory structure containing the name. * \param[out] name A 13 byte char array for the formatted name. */ -void SdBaseFile::dirName(const dir_t& dir, char* name) { +void SdBaseFile::dirName(const dir_t &dir, char *name) { uint8_t j = 0; LOOP_L_N(i, 11) { if (dir.name[i] == ' ')continue; @@ -229,7 +228,7 @@ void SdBaseFile::dirName(const dir_t& dir, char* name) { * * \return true if the file exists else false. */ -bool SdBaseFile::exists(const char* name) { +bool SdBaseFile::exists(const char *name) { SdBaseFile file; return file.open(this, name, O_READ); } @@ -254,7 +253,7 @@ bool SdBaseFile::exists(const char* name) { * \return For success fgets() returns the length of the string in \a str. * If no data is read, fgets() returns zero for EOF or -1 if an error occurred. **/ -int16_t SdBaseFile::fgets(char* str, int16_t num, char* delim) { +int16_t SdBaseFile::fgets(char *str, int16_t num, char *delim) { char ch; int16_t n = 0; int16_t r = -1; @@ -293,7 +292,7 @@ bool SdBaseFile::getDosName(char * const name) { return true; } // cache entry - dir_t* p = cacheDirEntry(SdVolume::CACHE_FOR_READ); + dir_t *p = cacheDirEntry(SdVolume::CACHE_FOR_READ); if (!p) return false; // format name @@ -301,7 +300,7 @@ bool SdBaseFile::getDosName(char * const name) { return true; } -void SdBaseFile::getpos(filepos_t* pos) { +void SdBaseFile::getpos(filepos_t *pos) { pos->position = curPosition_; pos->cluster = curCluster_; } @@ -386,7 +385,7 @@ int8_t SdBaseFile::lsPrintNext(uint8_t flags, uint8_t indent) { } // Format directory name field from a 8.3 name string -bool SdBaseFile::make83Name(const char* str, uint8_t* name, const char** ptr) { +bool SdBaseFile::make83Name(const char *str, uint8_t *name, const char **ptr) { uint8_t n = 7, // Max index until a dot is found i = 11; while (i) name[--i] = ' '; // Set whole FILENAME.EXT to spaces @@ -401,8 +400,8 @@ bool SdBaseFile::make83Name(const char* str, uint8_t* name, const char** ptr) { // Fail for illegal characters PGM_P p = PSTR("|<>^+=?/[];,*\"\\"); while (uint8_t b = pgm_read_byte(p++)) if (b == c) return false; - if (i > n || c < 0x21 || c == 0x7F) return false; // Check size, non-printable characters - name[i++] = (c < 'a' || c > 'z') ? (c) : (c + ('A' - 'a')); // Uppercase required for 8.3 name + if (i > n || c < 0x21 || c == 0x7F) return false; // Check size, non-printable characters + name[i++] = c + (WITHIN(c, 'a', 'z') ? 'A' - 'a' : 0); // Uppercase required for 8.3 name } } *ptr = str; // Set passed pointer to the end @@ -423,13 +422,13 @@ bool SdBaseFile::make83Name(const char* str, uint8_t* name, const char** ptr) { * Reasons for failure include this file is already open, \a parent is not a * directory, \a path is invalid or already exists in \a parent. */ -bool SdBaseFile::mkdir(SdBaseFile* parent, const char* path, bool pFlag) { +bool SdBaseFile::mkdir(SdBaseFile *parent, const char *path, bool pFlag) { if (ENABLED(SDCARD_READONLY)) return false; uint8_t dname[11]; SdBaseFile dir1, dir2; - SdBaseFile* sub = &dir1; - SdBaseFile* start = parent; + SdBaseFile *sub = &dir1; + SdBaseFile *start = parent; if (!parent || isOpen()) return false; @@ -455,13 +454,9 @@ bool SdBaseFile::mkdir(SdBaseFile* parent, const char* path, bool pFlag) { return mkdir(parent, dname); } -bool SdBaseFile::mkdir(SdBaseFile* parent, const uint8_t dname[11]) { +bool SdBaseFile::mkdir(SdBaseFile *parent, const uint8_t dname[11]) { if (ENABLED(SDCARD_READONLY)) return false; - uint32_t block; - dir_t d; - dir_t* p; - if (!parent->isDir()) return false; // create a normal file @@ -478,19 +473,20 @@ bool SdBaseFile::mkdir(SdBaseFile* parent, const uint8_t dname[11]) { if (!sync()) return false; // cache entry - should already be in cache due to sync() call - p = cacheDirEntry(SdVolume::CACHE_FOR_WRITE); + dir_t *p = cacheDirEntry(SdVolume::CACHE_FOR_WRITE); if (!p) return false; // change directory entry attribute p->attributes = DIR_ATT_DIRECTORY; // make entry for '.' + dir_t d; memcpy(&d, p, sizeof(d)); d.name[0] = '.'; LOOP_S_L_N(i, 1, 11) d.name[i] = ' '; // cache block for '.' and '..' - block = vol_->clusterStartBlock(firstCluster_); + uint32_t block = vol_->clusterStartBlock(firstCluster_); if (!vol_->cacheRawBlock(block, SdVolume::CACHE_FOR_WRITE)) return false; // copy '.' to block @@ -523,7 +519,7 @@ bool SdBaseFile::mkdir(SdBaseFile* parent, const uint8_t dname[11]) { * * \return true for success, false for failure. */ -bool SdBaseFile::open(const char* path, uint8_t oflag) { +bool SdBaseFile::open(const char *path, uint8_t oflag) { return open(cwd_, path, oflag); } @@ -577,7 +573,7 @@ bool SdBaseFile::open(const char* path, uint8_t oflag) { * a directory, \a path is invalid, the file does not exist * or can't be opened in the access mode specified by oflag. */ -bool SdBaseFile::open(SdBaseFile* dirFile, const char* path, uint8_t oflag) { +bool SdBaseFile::open(SdBaseFile *dirFile, const char *path, uint8_t oflag) { uint8_t dname[11]; SdBaseFile dir1, dir2; SdBaseFile *parent = dirFile, *sub = &dir1; @@ -605,10 +601,10 @@ bool SdBaseFile::open(SdBaseFile* dirFile, const char* path, uint8_t oflag) { } // open with filename in dname -bool SdBaseFile::open(SdBaseFile* dirFile, const uint8_t dname[11], uint8_t oflag) { +bool SdBaseFile::open(SdBaseFile *dirFile, const uint8_t dname[11], uint8_t oflag) { bool emptyFound = false, fileFound = false; uint8_t index; - dir_t* p; + dir_t *p; vol_ = dirFile->vol_; @@ -696,9 +692,7 @@ bool SdBaseFile::open(SdBaseFile* dirFile, const uint8_t dname[11], uint8_t ofla * See open() by path for definition of flags. * \return true for success or false for failure. */ -bool SdBaseFile::open(SdBaseFile* dirFile, uint16_t index, uint8_t oflag) { - dir_t* p; - +bool SdBaseFile::open(SdBaseFile *dirFile, uint16_t index, uint8_t oflag) { vol_ = dirFile->vol_; // error if already open @@ -711,7 +705,7 @@ bool SdBaseFile::open(SdBaseFile* dirFile, uint16_t index, uint8_t oflag) { if (!dirFile->seekSet(32 * index)) return false; // read entry into cache - p = dirFile->readDirCache(); + dir_t *p = dirFile->readDirCache(); if (!p) return false; // error if empty slot or '.' or '..' @@ -725,7 +719,7 @@ bool SdBaseFile::open(SdBaseFile* dirFile, uint16_t index, uint8_t oflag) { // open a cached directory entry. Assumes vol_ is initialized bool SdBaseFile::openCachedEntry(uint8_t dirIndex, uint8_t oflag) { - dir_t* p; + dir_t *p; #if ENABLED(SDCARD_READONLY) if (oflag & (O_WRITE | O_CREAT | O_TRUNC)) goto FAIL; @@ -784,10 +778,7 @@ bool SdBaseFile::openCachedEntry(uint8_t dirIndex, uint8_t oflag) { * See open() by path for definition of flags. * \return true for success or false for failure. */ -bool SdBaseFile::openNext(SdBaseFile* dirFile, uint8_t oflag) { - dir_t* p; - uint8_t index; - +bool SdBaseFile::openNext(SdBaseFile *dirFile, uint8_t oflag) { if (!dirFile) return false; // error if already open @@ -796,10 +787,10 @@ bool SdBaseFile::openNext(SdBaseFile* dirFile, uint8_t oflag) { vol_ = dirFile->vol_; while (1) { - index = 0xF & (dirFile->curPosition_ >> 5); + uint8_t index = 0xF & (dirFile->curPosition_ >> 5); // read entry into cache - p = dirFile->readDirCache(); + dir_t *p = dirFile->readDirCache(); if (!p) return false; // done if last entry @@ -825,9 +816,8 @@ bool SdBaseFile::openNext(SdBaseFile* dirFile, uint8_t oflag) { * * \return true for success, false for failure. */ -bool SdBaseFile::openParent(SdBaseFile* dir) { +bool SdBaseFile::openParent(SdBaseFile *dir) { dir_t entry; - dir_t* p; SdBaseFile file; uint32_t c; uint32_t cluster; @@ -850,7 +840,7 @@ bool SdBaseFile::openParent(SdBaseFile* dir) { // first block of parent dir if (!vol_->cacheRawBlock(lbn, SdVolume::CACHE_FOR_READ)) return false; - p = &vol_->cacheBuffer_.dir[1]; + dir_t *p = &vol_->cacheBuffer_.dir[1]; // verify name for '../..' if (p->name[0] != '.' || p->name[1] != '.') return false; // '..' is pointer to first cluster of parent. open '../..' to find parent @@ -881,7 +871,7 @@ bool SdBaseFile::openParent(SdBaseFile* dir) { * Reasons for failure include the file is already open, the FAT volume has * not been initialized or it a FAT12 volume. */ -bool SdBaseFile::openRoot(SdVolume* vol) { +bool SdBaseFile::openRoot(SdVolume *vol) { // error if file is already open if (isOpen()) return false; @@ -926,7 +916,7 @@ int SdBaseFile::peek() { // print uint8_t with width 2 static void print2u(const uint8_t v) { if (v < 10) SERIAL_CHAR('0'); - SERIAL_ECHO(int(v)); + SERIAL_ECHO(v); } /** @@ -1008,8 +998,8 @@ int16_t SdBaseFile::read() { * read() called before a file has been opened, corrupt file system * or an I/O error occurred. */ -int16_t SdBaseFile::read(void* buf, uint16_t nbyte) { - uint8_t* dst = reinterpret_cast(buf); +int16_t SdBaseFile::read(void *buf, uint16_t nbyte) { + uint8_t *dst = reinterpret_cast(buf); uint16_t offset, toRead; uint32_t block; // raw device block number @@ -1049,7 +1039,7 @@ int16_t SdBaseFile::read(void* buf, uint16_t nbyte) { else { // read block to cache and copy data to caller if (!vol_->cacheRawBlock(block, SdVolume::CACHE_FOR_READ)) return -1; - uint8_t* src = vol_->cache()->data + offset; + uint8_t *src = vol_->cache()->data + offset; memcpy(dst, src, n); } dst += n; @@ -1059,6 +1049,20 @@ int16_t SdBaseFile::read(void* buf, uint16_t nbyte) { return nbyte; } +/** + * Calculate a checksum for an 8.3 filename + * + * \param name The 8.3 file name to calculate + * + * \return The checksum byte + */ +uint8_t lfn_checksum(const uint8_t *name) { + uint8_t sum = 0; + for (uint8_t i = 11; i; i--) + sum = ((sum & 1) << 7) + (sum >> 1) + *name++; + return sum; +} + /** * Read the next entry in a directory. * @@ -1070,52 +1074,116 @@ int16_t SdBaseFile::read(void* buf, uint16_t nbyte) { * readDir() called before a directory has been opened, this is not * a directory file or an I/O error occurred. */ -int8_t SdBaseFile::readDir(dir_t* dir, char* longFilename) { +int8_t SdBaseFile::readDir(dir_t *dir, char *longFilename) { int16_t n; // if not a directory file or miss-positioned return an error if (!isDir() || (0x1F & curPosition_)) return -1; + #define INVALIDATE_LONGNAME() (longFilename[0] = longFilename[1] = '\0') + // If we have a longFilename buffer, mark it as invalid. // If a long filename is found it will be filled automatically. - if (longFilename) longFilename[0] = '\0'; + if (longFilename) INVALIDATE_LONGNAME(); + + uint8_t checksum_error = 0xFF, checksum = 0; while (1) { n = read(dir, sizeof(dir_t)); if (n != sizeof(dir_t)) return n ? -1 : 0; - // last entry if DIR_NAME_FREE + // Last entry if DIR_NAME_FREE if (dir->name[0] == DIR_NAME_FREE) return 0; - // skip deleted entry and entry for . and .. + // Skip deleted entry and entry for . and .. if (dir->name[0] == DIR_NAME_DELETED || dir->name[0] == '.') { - if (longFilename) longFilename[0] = '\0'; // Invalidate erased file long name, if any + if (longFilename) INVALIDATE_LONGNAME(); // Invalidate erased file long name, if any continue; } - // Fill the long filename if we have a long filename entry. - // Long filename entries are stored before the short filename. - if (longFilename && 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 - if (VFAT->firstClusterLow == 0) { - const uint8_t seq = VFAT->sequenceNumber & 0x1F; - if (WITHIN(seq, 1, MAX_VFAT_ENTRIES)) { - // TODO: Store the filename checksum to verify if a long-filename-unaware system modified the file table. - n = (seq - 1) * (FILENAME_LENGTH); - LOOP_L_N(i, FILENAME_LENGTH) - longFilename[n + i] = (i < 5) ? VFAT->name1[i] : (i < 11) ? VFAT->name2[i - 5] : VFAT->name3[i - 11]; - // If this VFAT entry is the last one, add a NUL terminator at the end of the string - if (VFAT->sequenceNumber & 0x40) longFilename[n + FILENAME_LENGTH] = '\0'; + if (longFilename) { + // Fill the long filename if we have a long filename entry. + // Long filename entries are stored before the short filename. + 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 + if (VFAT->firstClusterLow == 0) { + const uint8_t seq = VFAT->sequenceNumber & 0x1F; + if (WITHIN(seq, 1, MAX_VFAT_ENTRIES)) { + n = (seq - 1) * (FILENAME_LENGTH); + if (n == 0) { + checksum = VFAT->checksum; + checksum_error = 0; + } + else if (checksum != VFAT->checksum) // orphan detected + checksum_error = 1; + + LOOP_L_N(i, FILENAME_LENGTH) { + 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 + // needs static bytes addressing. So here just store full UTF-16LE words to re-convert later. + uint16_t idx = (n + i) * 2; // This is fixed as FAT LFN always contain UTF-16LE encoding + longFilename[idx] = utf16_ch & 0xFF; + longFilename[idx + 1] = (utf16_ch >> 8) & 0xFF; + #else + // Replace all multibyte characters to '_' + longFilename[n + i] = (utf16_ch > 0xFF) ? '_' : (utf16_ch & 0xFF); + #endif + } + // If this VFAT entry is the last one, add a NUL terminator at the end of the string + if (VFAT->sequenceNumber & 0x40) + longFilename[(n + FILENAME_LENGTH) * LONG_FILENAME_CHARSIZE] = '\0'; + } } } + else { + if (!checksum_error && lfn_checksum(dir->name) != checksum) checksum_error = 1; // orphan detected + if (checksum_error) INVALIDATE_LONGNAME(); + } } - // Return if normal file or subdirectory - if (DIR_IS_FILE_OR_SUBDIR(dir)) return n; + + // Post-process normal file or subdirectory longname, if any + if (DIR_IS_FILE_OR_SUBDIR(dir)) { + #if ENABLED(UTF_FILENAME_SUPPORT) + #if LONG_FILENAME_CHARSIZE > 2 + // Add warning for developers for currently not supported 3-byte cases (Conversion series of 2-byte + // codepoints to 3-byte in-place will break the rest of filename) + #error "Currently filename re-encoding is done in-place. It may break the remaining chars to use 3-byte codepoints." + #endif + + // Is there a long filename to decode? + if (longFilename) { + // Reset n to the start of the long name + n = 0; + for (uint16_t idx = 0; idx < (LONG_FILENAME_LENGTH) / 2; idx += 2) { // idx is fixed since FAT LFN always contains UTF-16LE encoding + const uint16_t utf16_ch = longFilename[idx] | (longFilename[idx + 1] << 8); + if (0xD800 == (utf16_ch & 0xF800)) // Surrogate pair - encode as '_' + longFilename[n++] = '_'; + else if (0 == (utf16_ch & 0xFF80)) // Encode as 1-byte UTF-8 char + longFilename[n++] = utf16_ch & 0x007F; + else if (0 == (utf16_ch & 0xF800)) { // Encode as 2-byte UTF-8 char + longFilename[n++] = 0xC0 | ((utf16_ch >> 6) & 0x1F); + longFilename[n++] = 0x80 | ( utf16_ch & 0x3F); + } + else { + #if LONG_FILENAME_CHARSIZE > 2 // Encode as 3-byte UTF-8 char + longFilename[n++] = 0xE0 | ((utf16_ch >> 12) & 0x0F); + longFilename[n++] = 0xC0 | ((utf16_ch >> 6) & 0x3F); + longFilename[n++] = 0xC0 | ( utf16_ch & 0x3F); + #else // Encode as '_' + longFilename[n++] = '_'; + #endif + } + if (0 == utf16_ch) break; // End of filename + } // idx + } // longFilename + #endif + return n; + } // DIR_IS_FILE_OR_SUBDIR } } - // Read next directory entry into the cache // Assumes file is correctly positioned dir_t* SdBaseFile::readDirCache() { @@ -1152,12 +1220,11 @@ dir_t* SdBaseFile::readDirCache() { bool SdBaseFile::remove() { if (ENABLED(SDCARD_READONLY)) return false; - dir_t* d; // free any clusters - will fail if read-only or directory if (!truncate(0)) return false; // cache directory entry - d = cacheDirEntry(SdVolume::CACHE_FOR_WRITE); + dir_t *d = cacheDirEntry(SdVolume::CACHE_FOR_WRITE); if (!d) return false; // mark entry deleted @@ -1188,7 +1255,7 @@ bool SdBaseFile::remove() { * \a dirFile is not a directory, \a path is not found * or an I/O error occurred. */ -bool SdBaseFile::remove(SdBaseFile* dirFile, const char* path) { +bool SdBaseFile::remove(SdBaseFile *dirFile, const char *path) { if (ENABLED(SDCARD_READONLY)) return false; SdBaseFile file; @@ -1205,13 +1272,10 @@ bool SdBaseFile::remove(SdBaseFile* dirFile, const char* path) { * Reasons for failure include \a dirFile is not open or is not a directory * file, newPath is invalid or already exists, or an I/O error occurs. */ -bool SdBaseFile::rename(SdBaseFile* dirFile, const char* newPath) { +bool SdBaseFile::rename(SdBaseFile *dirFile, const char *newPath) { if (ENABLED(SDCARD_READONLY)) return false; - dir_t entry; uint32_t dirCluster = 0; - SdBaseFile file; - dir_t* d; // must be an open file or subdirectory if (!(isFile() || isSubDir())) return false; @@ -1221,16 +1285,18 @@ bool SdBaseFile::rename(SdBaseFile* dirFile, const char* newPath) { // sync() and cache directory entry sync(); - d = cacheDirEntry(SdVolume::CACHE_FOR_WRITE); + dir_t *d = cacheDirEntry(SdVolume::CACHE_FOR_WRITE); if (!d) return false; // save directory entry + dir_t entry; memcpy(&entry, d, sizeof(entry)); // mark entry deleted d->name[0] = DIR_NAME_DELETED; // make directory entry for new path + SdBaseFile file; if (isFile()) { if (!file.open(dirFile, newPath, O_CREAT | O_EXCL | O_WRITE)) { goto restore; @@ -1309,7 +1375,7 @@ bool SdBaseFile::rmdir() { // make sure directory is empty while (curPosition_ < fileSize_) { - dir_t* p = readDirCache(); + dir_t *p = readDirCache(); if (!p) return false; // done if past last used entry if (p->name[0] == DIR_NAME_FREE) break; @@ -1349,7 +1415,7 @@ bool SdBaseFile::rmRfStar() { // remember position index = curPosition_ / 32; - dir_t* p = readDirCache(); + dir_t *p = readDirCache(); if (!p) return false; // done if past last entry @@ -1391,7 +1457,7 @@ bool SdBaseFile::rmRfStar() { * \param[in] oflag Values for \a oflag are constructed by a bitwise-inclusive * OR of open flags. see SdBaseFile::open(SdBaseFile*, const char*, uint8_t). */ -SdBaseFile::SdBaseFile(const char* path, uint8_t oflag) { +SdBaseFile::SdBaseFile(const char *path, uint8_t oflag) { type_ = FAT_FILE_TYPE_CLOSED; writeError = false; open(path, oflag); @@ -1434,7 +1500,7 @@ bool SdBaseFile::seekSet(const uint32_t pos) { return true; } -void SdBaseFile::setpos(filepos_t* pos) { +void SdBaseFile::setpos(filepos_t *pos) { curPosition_ = pos->position; curCluster_ = pos->cluster; } @@ -1452,7 +1518,7 @@ bool SdBaseFile::sync() { if (ENABLED(SDCARD_READONLY) || !isOpen()) goto FAIL; if (flags_ & F_FILE_DIR_DIRTY) { - dir_t* d = cacheDirEntry(SdVolume::CACHE_FOR_WRITE); + dir_t *d = cacheDirEntry(SdVolume::CACHE_FOR_WRITE); // check for deleted by another open file object if (!d || d->name[0] == DIR_NAME_DELETED) goto FAIL; @@ -1489,8 +1555,7 @@ bool SdBaseFile::sync() { * * \return true for success, false for failure. */ -bool SdBaseFile::timestamp(SdBaseFile* file) { - dir_t* d; +bool SdBaseFile::timestamp(SdBaseFile *file) { dir_t dir; // get timestamps @@ -1499,7 +1564,7 @@ bool SdBaseFile::timestamp(SdBaseFile* file) { // update directory fields if (!sync()) return false; - d = cacheDirEntry(SdVolume::CACHE_FOR_WRITE); + dir_t *d = cacheDirEntry(SdVolume::CACHE_FOR_WRITE); if (!d) return false; // copy timestamps @@ -1552,7 +1617,6 @@ bool SdBaseFile::timestamp(uint8_t flags, uint16_t year, uint8_t month, if (ENABLED(SDCARD_READONLY)) return false; uint16_t dirDate, dirTime; - dir_t* d; if (!isOpen() || year < 1980 @@ -1569,7 +1633,7 @@ bool SdBaseFile::timestamp(uint8_t flags, uint16_t year, uint8_t month, // update directory entry if (!sync()) return false; - d = cacheDirEntry(SdVolume::CACHE_FOR_WRITE); + dir_t *d = cacheDirEntry(SdVolume::CACHE_FOR_WRITE); if (!d) return false; dirDate = FAT_DATE(year, month, day); @@ -1663,13 +1727,13 @@ bool SdBaseFile::truncate(uint32_t length) { * include write() is called before a file has been opened, write is called * for a read-only file, device is full, a corrupt file system or an I/O error. */ -int16_t SdBaseFile::write(const void* buf, uint16_t nbyte) { +int16_t SdBaseFile::write(const void *buf, uint16_t nbyte) { #if ENABLED(SDCARD_READONLY) writeError = true; return -1; #endif // convert void* to uint8_t* - must be before goto statements - const uint8_t* src = reinterpret_cast(buf); + const uint8_t *src = reinterpret_cast(buf); // number of bytes left to write - must be before goto statements uint16_t nToWrite = nbyte; @@ -1735,7 +1799,7 @@ int16_t SdBaseFile::write(const void* buf, uint16_t nbyte) { // rewrite part of block if (!vol_->cacheRawBlock(block, SdVolume::CACHE_FOR_WRITE)) goto FAIL; } - uint8_t* dst = vol_->cache()->data + blockOffset; + uint8_t *dst = vol_->cache()->data + blockOffset; memcpy(dst, src, n); } curPosition_ += n; diff --git a/Marlin/src/sd/SdBaseFile.h b/Marlin/src/sd/SdBaseFile.h index 13a1be863d0f..342edefb7079 100644 --- a/Marlin/src/sd/SdBaseFile.h +++ b/Marlin/src/sd/SdBaseFile.h @@ -22,11 +22,8 @@ #pragma once /** - * \file - * \brief SdBaseFile class - */ - -/** + * sd/SdBaseFile.h + * * Arduino SdFat Library * Copyright (c) 2009 by William Greiman * @@ -166,7 +163,7 @@ uint16_t const FAT_DEFAULT_TIME = (1 << 11); class SdBaseFile { public: SdBaseFile() : writeError(false), type_(FAT_FILE_TYPE_CLOSED) {} - SdBaseFile(const char* path, uint8_t oflag); + SdBaseFile(const char *path, uint8_t oflag); ~SdBaseFile() { if (isOpen()) close(); } /** @@ -182,18 +179,18 @@ class SdBaseFile { * get position for streams * \param[out] pos struct to receive position */ - void getpos(filepos_t* pos); + void getpos(filepos_t *pos); /** * set position for streams * \param[out] pos struct with value for new position */ - void setpos(filepos_t* pos); + void setpos(filepos_t *pos); bool close(); - bool contiguousRange(uint32_t* bgnBlock, uint32_t* endBlock); - bool createContiguous(SdBaseFile* dirFile, - const char* path, uint32_t size); + bool contiguousRange(uint32_t *bgnBlock, uint32_t *endBlock); + bool createContiguous(SdBaseFile *dirFile, + const char *path, uint32_t size); /** * \return The current cluster number for a file or directory. */ @@ -207,7 +204,7 @@ class SdBaseFile { /** * \return Current working directory */ - static SdBaseFile* cwd() { return cwd_; } + static SdBaseFile *cwd() { return cwd_; } /** * Set the date/time callback function @@ -216,7 +213,7 @@ class SdBaseFile { * function is of the form: * * \code - * void dateTime(uint16_t* date, uint16_t* time) { + * void dateTime(uint16_t *date, uint16_t *time) { * uint16_t year; * uint8_t month, day, hour, minute, second; * @@ -238,7 +235,7 @@ class SdBaseFile { * See the timestamp() function. */ static void dateTimeCallback( - void (*dateTime)(uint16_t* date, uint16_t* time)) { + void (*dateTime)(uint16_t *date, uint16_t *time)) { dateTime_ = dateTime; } @@ -246,10 +243,10 @@ class SdBaseFile { * Cancel the date/time callback function. */ static void dateTimeCallbackCancel() { dateTime_ = 0; } - bool dirEntry(dir_t* dir); - static void dirName(const dir_t& dir, char* name); - bool exists(const char* name); - int16_t fgets(char* str, int16_t num, char* delim = 0); + bool dirEntry(dir_t *dir); + static void dirName(const dir_t& dir, char *name); + bool exists(const char *name); + int16_t fgets(char *str, int16_t num, char *delim = 0); /** * \return The total number of bytes in a file or directory. @@ -289,27 +286,27 @@ class SdBaseFile { bool getDosName(char * const name); void ls(uint8_t flags = 0, uint8_t indent = 0); - bool mkdir(SdBaseFile* dir, const char* path, bool pFlag = true); - bool open(SdBaseFile* dirFile, uint16_t index, uint8_t oflag); - bool open(SdBaseFile* dirFile, const char* path, uint8_t oflag); - bool open(const char* path, uint8_t oflag = O_READ); - bool openNext(SdBaseFile* dirFile, uint8_t oflag); - bool openRoot(SdVolume* vol); + bool mkdir(SdBaseFile *dir, const char *path, bool pFlag = true); + bool open(SdBaseFile *dirFile, uint16_t index, uint8_t oflag); + bool open(SdBaseFile *dirFile, const char *path, uint8_t oflag); + bool open(const char *path, uint8_t oflag = O_READ); + bool openNext(SdBaseFile *dirFile, uint8_t oflag); + bool openRoot(SdVolume *vol); int peek(); static void printFatDate(uint16_t fatDate); static void printFatTime(uint16_t fatTime); bool printName(); int16_t read(); - int16_t read(void* buf, uint16_t nbyte); - int8_t readDir(dir_t* dir, char* longFilename); - static bool remove(SdBaseFile* dirFile, const char* path); + int16_t read(void *buf, uint16_t nbyte); + int8_t readDir(dir_t *dir, char *longFilename); + static bool remove(SdBaseFile *dirFile, const char *path); bool remove(); /** * Set the file's current position to zero. */ void rewind() { seekSet(0); } - bool rename(SdBaseFile* dirFile, const char* newPath); + bool rename(SdBaseFile *dirFile, const char *newPath); bool rmdir(); bool rmRfStar(); @@ -328,7 +325,7 @@ class SdBaseFile { bool seekEnd(const int32_t offset = 0) { return seekSet(fileSize_ + offset); } bool seekSet(const uint32_t pos); bool sync(); - bool timestamp(SdBaseFile* file); + bool timestamp(SdBaseFile *file); bool timestamp(uint8_t flag, uint16_t year, uint8_t month, uint8_t day, uint8_t hour, uint8_t minute, uint8_t second); @@ -344,14 +341,14 @@ class SdBaseFile { * \return SdVolume that contains this file. */ SdVolume* volume() const { return vol_; } - int16_t write(const void* buf, uint16_t nbyte); + int16_t write(const void *buf, uint16_t nbyte); private: friend class SdFat; // allow SdFat to set cwd_ - static SdBaseFile* cwd_; // global pointer to cwd dir + static SdBaseFile *cwd_; // global pointer to cwd dir // data time callback function - static void (*dateTime_)(uint16_t* date, uint16_t* time); + static void (*dateTime_)(uint16_t *date, uint16_t *time); // bits defined in flags_ static uint8_t const F_OFLAG = (O_ACCMODE | O_APPEND | O_SYNC), // should be 0x0F @@ -367,21 +364,21 @@ class SdBaseFile { uint8_t dirIndex_; // index of directory entry in dirBlock uint32_t fileSize_; // file size in bytes uint32_t firstCluster_; // first cluster of file - SdVolume* vol_; // volume where file is located + SdVolume *vol_; // volume where file is located /** * EXPERIMENTAL - Don't use! */ - //bool openParent(SdBaseFile* dir); + //bool openParent(SdBaseFile *dir); // private functions bool addCluster(); bool addDirCluster(); dir_t* cacheDirEntry(uint8_t action); int8_t lsPrintNext(uint8_t flags, uint8_t indent); - static bool make83Name(const char* str, uint8_t* name, const char** ptr); - bool mkdir(SdBaseFile* parent, const uint8_t dname[11]); - bool open(SdBaseFile* dirFile, const uint8_t dname[11], uint8_t oflag); + static bool make83Name(const char *str, uint8_t *name, const char **ptr); + bool mkdir(SdBaseFile *parent, const uint8_t dname[11]); + bool open(SdBaseFile *dirFile, const uint8_t dname[11], uint8_t oflag); bool openCachedEntry(uint8_t cacheIndex, uint8_t oflags); dir_t* readDirCache(); }; diff --git a/Marlin/src/sd/SdFatConfig.h b/Marlin/src/sd/SdFatConfig.h index 2e03a4181f7e..dfba64129526 100644 --- a/Marlin/src/sd/SdFatConfig.h +++ b/Marlin/src/sd/SdFatConfig.h @@ -22,7 +22,8 @@ #pragma once /** - * SdFatConfig.h + * sd/SdFatConfig.h + * * Arduino SdFat Library * Copyright (c) 2009 by William Greiman * @@ -38,7 +39,7 @@ * * Each card requires about 550 bytes of SRAM so use of a Mega is recommended. */ -#define USE_MULTIPLE_CARDS 0 +#define USE_MULTIPLE_CARDS 0 //TODO? ENABLED(MULTI_VOLUME) /** * Call flush for endl if ENDL_CALLS_FLUSH is nonzero @@ -102,5 +103,10 @@ #define FILENAME_LENGTH 13 // Number of UTF-16 characters per entry +// UTF-8 may use up to 3 bytes to represent single UTF-16 code point. +// We discard 3-byte characters allowing only 2-bytes +// or 1-byte if UTF_FILENAME_SUPPORT disabled. +#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 * MAX_VFAT_ENTRIES + 1) +#define LONG_FILENAME_LENGTH (FILENAME_LENGTH * LONG_FILENAME_CHARSIZE * MAX_VFAT_ENTRIES + 1) diff --git a/Marlin/src/sd/SdFatStructs.h b/Marlin/src/sd/SdFatStructs.h index 484d4e50c6c9..03bbc1c194c9 100644 --- a/Marlin/src/sd/SdFatStructs.h +++ b/Marlin/src/sd/SdFatStructs.h @@ -22,11 +22,8 @@ #pragma once /** - * \file - * \brief FAT file structures - */ - -/** + * sd/SdFatStructs.h + * * Arduino SdFat Library * Copyright (c) 2009 by William Greiman * @@ -574,7 +571,7 @@ uint8_t const DIR_NAME_0xE5 = 0x05, // escape for name[0] = 0xE5 * * \return true if the entry is for part of a long name else false. */ -static inline uint8_t DIR_IS_LONG_NAME(const dir_t* dir) { +static inline uint8_t DIR_IS_LONG_NAME(const dir_t *dir) { return (dir->attributes & DIR_ATT_LONG_NAME_MASK) == DIR_ATT_LONG_NAME; } @@ -587,7 +584,7 @@ uint8_t const DIR_ATT_FILE_TYPE_MASK = (DIR_ATT_VOLUME_ID | DIR_ATT_DIRECTORY); * * \return true if the entry is for a normal file else false. */ -static inline uint8_t DIR_IS_FILE(const dir_t* dir) { +static inline uint8_t DIR_IS_FILE(const dir_t *dir) { return (dir->attributes & DIR_ATT_FILE_TYPE_MASK) == 0; } @@ -597,7 +594,7 @@ static inline uint8_t DIR_IS_FILE(const dir_t* dir) { * * \return true if the entry is for a subdirectory else false. */ -static inline uint8_t DIR_IS_SUBDIR(const dir_t* dir) { +static inline uint8_t DIR_IS_SUBDIR(const dir_t *dir) { return (dir->attributes & DIR_ATT_FILE_TYPE_MASK) == DIR_ATT_DIRECTORY; } @@ -607,6 +604,6 @@ static inline uint8_t DIR_IS_SUBDIR(const dir_t* dir) { * * \return true if the entry is for a normal file or subdirectory else false. */ -static inline uint8_t DIR_IS_FILE_OR_SUBDIR(const dir_t* dir) { +static inline uint8_t DIR_IS_FILE_OR_SUBDIR(const dir_t *dir) { return (dir->attributes & DIR_ATT_VOLUME_ID) == 0; } diff --git a/Marlin/src/sd/SdFatUtil.cpp b/Marlin/src/sd/SdFatUtil.cpp index e2c467c5b6d4..e6f7a9a01305 100644 --- a/Marlin/src/sd/SdFatUtil.cpp +++ b/Marlin/src/sd/SdFatUtil.cpp @@ -21,6 +21,8 @@ */ /** + * sd/SdFatUtil.cpp + * * Arduino SdFat Library * Copyright (c) 2008 by William Greiman * @@ -46,7 +48,7 @@ return &top - reinterpret_cast(sbrk(0)); } -#else +#elif defined(__AVR__) extern char* __brkval; extern char __bss_end; diff --git a/Marlin/src/sd/SdFatUtil.h b/Marlin/src/sd/SdFatUtil.h index 7afed2ede06b..f1bb65747e76 100644 --- a/Marlin/src/sd/SdFatUtil.h +++ b/Marlin/src/sd/SdFatUtil.h @@ -22,6 +22,8 @@ #pragma once /** + * sd/SdFatUtil.h + * * Arduino SdFat Library * Copyright (c) 2008 by William Greiman * diff --git a/Marlin/src/sd/SdFile.cpp b/Marlin/src/sd/SdFile.cpp index c82fe2c5ed77..bce96ef02db5 100644 --- a/Marlin/src/sd/SdFile.cpp +++ b/Marlin/src/sd/SdFile.cpp @@ -21,6 +21,8 @@ */ /** + * sd/SdFile.cpp + * * Arduino SdFat Library * Copyright (c) 2009 by William Greiman * @@ -41,7 +43,7 @@ * \param[in] oflag Values for \a oflag are constructed by a bitwise-inclusive * OR of open flags. see SdBaseFile::open(SdBaseFile*, const char*, uint8_t). */ -SdFile::SdFile(const char* path, uint8_t oflag) : SdBaseFile(path, oflag) { } +SdFile::SdFile(const char *path, uint8_t oflag) : SdBaseFile(path, oflag) { } /** * Write data to an open file. @@ -58,7 +60,7 @@ SdFile::SdFile(const char* path, uint8_t oflag) : SdBaseFile(path, oflag) { } * include write() is called before a file has been opened, write is called * for a read-only file, device is full, a corrupt file system or an I/O error. */ -int16_t SdFile::write(const void* buf, uint16_t nbyte) { return SdBaseFile::write(buf, nbyte); } +int16_t SdFile::write(const void *buf, uint16_t nbyte) { return SdBaseFile::write(buf, nbyte); } /** * Write a byte to a file. Required by the Arduino Print class. @@ -76,7 +78,7 @@ int16_t SdFile::write(const void* buf, uint16_t nbyte) { return SdBaseFile::writ * \param[in] str Pointer to the string. * Use writeError to check for errors. */ -void SdFile::write(const char* str) { SdBaseFile::write(str, strlen(str)); } +void SdFile::write(const char *str) { SdBaseFile::write(str, strlen(str)); } /** * Write a PROGMEM string to a file. diff --git a/Marlin/src/sd/SdFile.h b/Marlin/src/sd/SdFile.h index 52c8f1f0dbbc..1691898899c0 100644 --- a/Marlin/src/sd/SdFile.h +++ b/Marlin/src/sd/SdFile.h @@ -22,11 +22,8 @@ #pragma once /** - * \file - * \brief SdFile class - */ - -/** + * sd/SdFile.h + * * Arduino SdFat Library * Copyright (c) 2009 by William Greiman * @@ -42,18 +39,18 @@ * \class SdFile * \brief SdBaseFile with Print. */ -class SdFile : public SdBaseFile/*, public Print*/ { +class SdFile : public SdBaseFile { public: SdFile() {} - SdFile(const char* name, uint8_t oflag); + SdFile(const char *name, uint8_t oflag); #if ARDUINO >= 100 size_t write(uint8_t b); #else - void write(uint8_t b); + void write(uint8_t b); #endif - int16_t write(const void* buf, uint16_t nbyte); - void write(const char* str); + int16_t write(const void *buf, uint16_t nbyte); + void write(const char *str); void write_P(PGM_P str); void writeln_P(PGM_P str); }; diff --git a/Marlin/src/sd/SdVolume.cpp b/Marlin/src/sd/SdVolume.cpp index 63731f728c60..1b1fdc5a7c1e 100644 --- a/Marlin/src/sd/SdVolume.cpp +++ b/Marlin/src/sd/SdVolume.cpp @@ -21,6 +21,8 @@ */ /** + * sd/SdVolume.cpp + * * Arduino SdFat Library * Copyright (c) 2009 by William Greiman * @@ -39,13 +41,13 @@ // raw block cache uint32_t SdVolume::cacheBlockNumber_; // current block number cache_t SdVolume::cacheBuffer_; // 512 byte cache for Sd2Card - Sd2Card* SdVolume::sdCard_; // pointer to SD card object + DiskIODriver *SdVolume::sdCard_; // pointer to SD card object bool SdVolume::cacheDirty_; // cacheFlush() will write block if true uint32_t SdVolume::cacheMirrorBlock_; // mirror block for second FAT -#endif // USE_MULTIPLE_CARDS +#endif // find a contiguous group of clusters -bool SdVolume::allocContiguous(uint32_t count, uint32_t* curCluster) { +bool SdVolume::allocContiguous(uint32_t count, uint32_t *curCluster) { if (ENABLED(SDCARD_READONLY)) return false; // start of group @@ -147,7 +149,7 @@ bool SdVolume::cacheRawBlock(uint32_t blockNumber, bool dirty) { } // return the size in bytes of a cluster chain -bool SdVolume::chainSize(uint32_t cluster, uint32_t* size) { +bool SdVolume::chainSize(uint32_t cluster, uint32_t *size) { uint32_t s = 0; do { if (!fatGet(cluster, &cluster)) return false; @@ -158,7 +160,7 @@ bool SdVolume::chainSize(uint32_t cluster, uint32_t* size) { } // Fetch a FAT entry -bool SdVolume::fatGet(uint32_t cluster, uint32_t* value) { +bool SdVolume::fatGet(uint32_t cluster, uint32_t *value) { uint32_t lba; if (cluster > (clusterCount_ + 1)) return false; if (FAT12_SUPPORT && fatType_ == 12) { @@ -324,9 +326,9 @@ int32_t SdVolume::freeClusterCount() { * Reasons for failure include not finding a valid partition, not finding a valid * FAT file system in the specified partition or an I/O error. */ -bool SdVolume::init(Sd2Card* dev, uint8_t part) { +bool SdVolume::init(DiskIODriver* dev, uint8_t part) { uint32_t totalBlocks, volumeStartBlock = 0; - fat32_boot_t* fbs; + fat32_boot_t *fbs; sdCard_ = dev; fatType_ = 0; @@ -340,7 +342,7 @@ bool SdVolume::init(Sd2Card* dev, uint8_t part) { if (part) { if (part > 4) return false; if (!cacheRawBlock(volumeStartBlock, CACHE_FOR_READ)) return false; - part_t* p = &cacheBuffer_.mbr.part[part - 1]; + part_t *p = &cacheBuffer_.mbr.part[part - 1]; if ((p->boot & 0x7F) != 0 || p->totalSectors < 100 || p->firstSector == 0) return false; // not a valid partition volumeStartBlock = p->firstSector; diff --git a/Marlin/src/sd/SdVolume.h b/Marlin/src/sd/SdVolume.h index 1ffa888468be..b8e70ca9d7f5 100644 --- a/Marlin/src/sd/SdVolume.h +++ b/Marlin/src/sd/SdVolume.h @@ -22,11 +22,8 @@ #pragma once /** - * \file - * \brief SdVolume class - */ - -/** + * sd/SdVolume.h + * * Arduino SdFat Library * Copyright (c) 2009 by William Greiman * @@ -39,9 +36,11 @@ #if ENABLED(USB_FLASH_DRIVE_SUPPORT) #include "usb_flashdrive/Sd2Card_FlashDrive.h" -#elif ENABLED(SDIO_SUPPORT) +#endif + +#if NEED_SD2CARD_SDIO #include "Sd2Card_sdio.h" -#else +#elif NEED_SD2CARD_SPI #include "Sd2Card.h" #endif @@ -50,6 +49,7 @@ //============================================================================== // SdVolume class + /** * \brief Cache for an SD data block */ @@ -87,14 +87,14 @@ class SdVolume { * Initialize a FAT volume. Try partition one first then try super * floppy format. * - * \param[in] dev The Sd2Card where the volume is located. + * \param[in] dev The DiskIODriver where the volume is located. * * \return true for success, false for failure. * Reasons for failure include not finding a valid partition, not finding * a valid FAT file system or an I/O error. */ - bool init(Sd2Card* dev) { return init(dev, 1) ? true : init(dev, 0); } - bool init(Sd2Card* dev, uint8_t part); + bool init(DiskIODriver *dev) { return init(dev, 1) || init(dev, 0); } + bool init(DiskIODriver *dev, uint8_t part); // inline functions that return volume info uint8_t blocksPerCluster() const { return blocksPerCluster_; } //> \return The volume's cluster size in blocks. @@ -115,10 +115,10 @@ class SdVolume { uint32_t rootDirStart() const { return rootDirStart_; } /** - * Sd2Card object for this volume - * \return pointer to Sd2Card object. + * DiskIODriver object for this volume + * \return pointer to DiskIODriver object. */ - Sd2Card* sdCard() { return sdCard_; } + DiskIODriver* sdCard() { return sdCard_; } /** * Debug access to FAT table @@ -127,7 +127,7 @@ class SdVolume { * \param[out] v value of entry * \return true for success or false for failure */ - bool dbgFat(uint32_t n, uint32_t* v) { return fatGet(n, v); } + bool dbgFat(uint32_t n, uint32_t *v) { return fatGet(n, v); } private: // Allow SdBaseFile access to SdVolume private data. @@ -141,13 +141,13 @@ class SdVolume { #if USE_MULTIPLE_CARDS cache_t cacheBuffer_; // 512 byte cache for device blocks uint32_t cacheBlockNumber_; // Logical number of block in the cache - Sd2Card* sdCard_; // Sd2Card object for cache + DiskIODriver *sdCard_; // DiskIODriver object for cache bool cacheDirty_; // cacheFlush() will write block if true uint32_t cacheMirrorBlock_; // block number for mirror FAT #else static cache_t cacheBuffer_; // 512 byte cache for device blocks static uint32_t cacheBlockNumber_; // Logical number of block in the cache - static Sd2Card* sdCard_; // Sd2Card object for cache + static DiskIODriver *sdCard_; // DiskIODriver object for cache static bool cacheDirty_; // cacheFlush() will write block if true static uint32_t cacheMirrorBlock_; // block number for mirror FAT #endif @@ -164,7 +164,7 @@ class SdVolume { uint16_t rootDirEntryCount_; // number of entries in FAT16 root dir uint32_t rootDirStart_; // root start block for FAT16, cluster for FAT32 - bool allocContiguous(uint32_t count, uint32_t* curCluster); + bool allocContiguous(uint32_t count, uint32_t *curCluster); uint8_t blockOfCluster(uint32_t position) const { return (position >> 9) & (blocksPerCluster_ - 1); } uint32_t clusterStartBlock(uint32_t cluster) const { return dataStartBlock_ + ((cluster - 2) << clusterSizeShift_); } uint32_t blockNumber(uint32_t cluster, uint32_t position) const { return clusterStartBlock(cluster) + blockOfCluster(position); } @@ -186,8 +186,8 @@ class SdVolume { cacheBlockNumber_ = blockNumber; } void cacheSetDirty() { cacheDirty_ |= CACHE_FOR_WRITE; } - bool chainSize(uint32_t beginCluster, uint32_t* size); - bool fatGet(uint32_t cluster, uint32_t* value); + bool chainSize(uint32_t beginCluster, uint32_t *size); + bool fatGet(uint32_t cluster, uint32_t *value); bool fatPut(uint32_t cluster, uint32_t value); bool fatPutEOC(uint32_t cluster) { return fatPut(cluster, 0x0FFFFFFF); } bool freeChain(uint32_t cluster); @@ -196,6 +196,6 @@ class SdVolume { if (fatType_ == 16) return cluster >= FAT16EOC_MIN; return cluster >= FAT32EOC_MIN; } - bool readBlock(uint32_t block, uint8_t* dst) { return sdCard_->readBlock(block, dst); } - bool writeBlock(uint32_t block, const uint8_t* dst) { return sdCard_->writeBlock(block, dst); } + bool readBlock(uint32_t block, uint8_t *dst) { return sdCard_->readBlock(block, dst); } + bool writeBlock(uint32_t block, const uint8_t *dst) { return sdCard_->writeBlock(block, dst); } }; diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index e154ea9f314b..c0bc81a3ef3c 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -29,10 +29,10 @@ #include "cardreader.h" #include "../MarlinCore.h" -#include "../lcd/ultralcd.h" +#include "../lcd/marlinui.h" #if ENABLED(DWIN_CREALITY_LCD) - #include "../lcd/dwin/e3v2/dwin.h" + #include "../lcd/e3v2/creality/dwin.h" #endif #include "../module/planner.h" // for synchronize @@ -57,14 +57,21 @@ #include "../core/debug_out.h" #include "../libs/hex_print.h" +// extern + +PGMSTR(M21_STR, "M21"); +PGMSTR(M23_STR, "M23 %s"); +PGMSTR(M24_STR, "M24"); + // public: card_flags_t CardReader::flag; char CardReader::filename[FILENAME_LENGTH], CardReader::longFilename[LONG_FILENAME_LENGTH]; -int8_t CardReader::autostart_index; + +IF_DISABLED(NO_SD_AUTOSTART, uint8_t CardReader::autofile_index); // = 0 #if BOTH(HAS_MULTI_SERIAL, BINARY_FILE_TRANSFER) - int8_t CardReader::transfer_port_index; + serial_index_t CardReader::transfer_port_index; #endif // private: @@ -114,17 +121,35 @@ uint8_t CardReader::workDirDepth; #endif // SDCARD_SORT_ALPHA -Sd2Card CardReader::sd2card; +#if HAS_USB_FLASH_DRIVE + DiskIODriver_USBFlash CardReader::media_driver_usbFlash; +#endif + +#if NEED_SD2CARD_SDIO || NEED_SD2CARD_SPI + CardReader::sdcard_driver_t CardReader::media_driver_sdcard; +#endif + +DiskIODriver* CardReader::driver = nullptr; SdVolume CardReader::volume; SdFile CardReader::file; -uint8_t CardReader::file_subcall_ctr; -uint32_t CardReader::filespos[SD_PROCEDURE_DEPTH]; -char CardReader::proc_filenames[SD_PROCEDURE_DEPTH][MAXPATHNAMELENGTH]; +#if HAS_MEDIA_SUBCALLS + uint8_t CardReader::file_subcall_ctr; + uint32_t CardReader::filespos[SD_PROCEDURE_DEPTH]; + char CardReader::proc_filenames[SD_PROCEDURE_DEPTH][MAXPATHNAMELENGTH]; +#endif uint32_t CardReader::filesize, CardReader::sdpos; CardReader::CardReader() { + changeMedia(& + #if HAS_USB_FLASH_DRIVE && !SHARED_VOLUME_IS(SD_ONBOARD) + media_driver_usbFlash + #else + media_driver_sdcard + #endif + ); + #if ENABLED(SDCARD_SORT_ALPHA) sort_count = 0; #if ENABLED(SDSORT_GCODE) @@ -133,16 +158,17 @@ CardReader::CardReader() { //sort_reverse = false; #endif #endif - flag.sdprinting = flag.mounted = flag.saving = flag.logging = false; + + flag.sdprinting = flag.sdprintdone = flag.mounted = flag.saving = flag.logging = false; filesize = sdpos = 0; - file_subcall_ctr = 0; + + TERN_(HAS_MEDIA_SUBCALLS, file_subcall_ctr = 0); + + IF_DISABLED(NO_SD_AUTOSTART, autofile_cancel()); workDirDepth = 0; ZERO(workDirParents); - // Disable autostart until card is initialized - autostart_index = -1; - #if ENABLED(SDSUPPORT) && PIN_EXISTS(SD_DETECT) SET_INPUT_PULLUP(SD_DETECT_PIN); #endif @@ -232,48 +258,84 @@ void CardReader::selectByName(SdFile dir, const char * const match) { } } -// -// Recursive method to list all files within a folder -// -void CardReader::printListing(SdFile parent, const char * const prepend/*=nullptr*/) { +/** + * Recursive method to print all files within a folder in flat + * DOS 8.3 format. This style of listing is the most compatible + * with legacy hosts. + * + * This method recurses to unlimited depth and lists all G-code + * files within the given parent. If the hierarchy is very deep + * this can blow up the stack, so a 'depth' parameter would be a + * good addition. + */ +void CardReader::printListing( + SdFile parent + OPTARG(LONG_FILENAME_HOST_SUPPORT, const bool includeLongNames/*=false*/) + , const char * const prepend/*=nullptr*/ + OPTARG(LONG_FILENAME_HOST_SUPPORT, const char * const prependLong/*=nullptr*/) +) { dir_t p; while (parent.readDir(&p, longFilename) > 0) { if (DIR_IS_SUBDIR(&p)) { - // Get the short name for the item, which we know is a folder - char dosFilename[FILENAME_LENGTH]; + 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] = '/'; + } + char* dosFilename = path + lenPrepend; createFilename(dosFilename, p); - // Allocate enough stack space for the full path to a folder, trailing slash, and nul - const bool prepend_is_empty = (!prepend || prepend[0] == '\0'); - const int len = (prepend_is_empty ? 1 : strlen(prepend)) + strlen(dosFilename) + 1 + 1; - char path[len]; - - // Append the FOLDERNAME12/ to the passed string. - // It contains the full path to the "parent" argument. - // We now have the full path to the item in this folder. - strcpy(path, prepend_is_empty ? "/" : prepend); // root slash if prepend is empty - strcat(path, dosFilename); // FILENAME_LENGTH characters maximum - strcat(path, "/"); // 1 character - - // Serial.print(path); - // Get a new directory object using the full path // and dive recursively into it. - SdFile child; - if (!child.open(&parent, dosFilename, O_READ)) { - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR(STR_SD_CANT_OPEN_SUBDIR, dosFilename); + SdFile child; // child.close() in destructor + if (child.open(&parent, dosFilename, O_READ)) + #if ENABLED(LONG_FILENAME_HOST_SUPPORT) + if (includeLongNames) { + size_t lenPrependLong = prependLong ? strlen(prependLong) + 1 : 0; + // Allocate enough stack space for the full long path including / separator + char pathLong[lenPrependLong + strlen(longFilename) + 1]; + if (prependLong) { + strcpy(pathLong, prependLong); + pathLong[lenPrependLong - 1] = '/'; + } + strcpy(pathLong + lenPrependLong, longFilename); + printListing(child, true, path, pathLong); + } + else + printListing(child, false, path); + #else + printListing(child, path); + #endif + else { + SERIAL_ECHO_MSG(STR_SD_CANT_OPEN_SUBDIR, dosFilename); + return; } - printListing(child, path); - // close() is done automatically by destructor of SdFile } else if (is_dir_or_gcode(p)) { - createFilename(filename, p); - if (prepend) SERIAL_ECHO(prepend); - SERIAL_ECHO(filename); + if (prepend) { + SERIAL_ECHO(prepend); + SERIAL_CHAR('/'); + } + SERIAL_ECHO(createFilename(filename, p)); SERIAL_CHAR(' '); - SERIAL_ECHOLN(p.fileSize); + #if ENABLED(LONG_FILENAME_HOST_SUPPORT) + if (!includeLongNames) + #endif + SERIAL_ECHOLN(p.fileSize); + #if ENABLED(LONG_FILENAME_HOST_SUPPORT) + else { + SERIAL_ECHO(p.fileSize); + SERIAL_CHAR(' '); + if (prependLong) { + SERIAL_ECHO(prependLong); + SERIAL_CHAR('/'); + } + SERIAL_ECHOLN(longFilename[0] ? longFilename : "???"); + } + #endif } } } @@ -281,10 +343,10 @@ void CardReader::printListing(SdFile parent, const char * const prepend/*=nullpt // // List all files on the SD card // -void CardReader::ls() { +void CardReader::ls(TERN_(LONG_FILENAME_HOST_SUPPORT, bool includeLongNames/*=false*/)) { if (flag.mounted) { root.rewind(); - printListing(root); + printListing(root OPTARG(LONG_FILENAME_HOST_SUPPORT, includeLongNames)); } } @@ -315,7 +377,7 @@ void CardReader::ls() { // Go to the next segment while (path[++i]) { } - // SERIAL_ECHOPGM("Looking for segment: "); SERIAL_ECHOLN(segment); + //SERIAL_ECHOLNPAIR("Looking for segment: ", segment); // Find the item, setting the long filename diveDir.rewind(); @@ -352,7 +414,7 @@ void CardReader::ls() { // // Echo the DOS 8.3 filename (and long filename, if any) // -void CardReader::printFilename() { +void CardReader::printSelectedFilename() { if (file.isOpen()) { char dosFilename[FILENAME_LENGTH]; file.getDosName(dosFilename); @@ -360,7 +422,7 @@ void CardReader::printFilename() { #if ENABLED(LONG_FILENAME_HOST_SUPPORT) selectFileByName(dosFilename); if (longFilename[0]) { - SERIAL_ECHO(' '); + SERIAL_CHAR(' '); SERIAL_ECHO(longFilename); } #endif @@ -375,12 +437,12 @@ void CardReader::mount() { flag.mounted = false; if (root.isOpen()) root.close(); - if (!sd2card.init(SPI_SPEED, SDSS) + if (!driver->init(SD_SPI_SPEED, SDSS) #if defined(LCD_SDSS) && (LCD_SDSS != SDSS) - && !sd2card.init(SPI_SPEED, LCD_SDSS) + && !driver->init(SD_SPI_SPEED, LCD_SDSS) #endif ) SERIAL_ECHO_MSG(STR_SD_INIT_FAIL); - else if (!volume.init(&sd2card)) + else if (!volume.init(driver)) SERIAL_ERROR_MSG(STR_SD_VOL_INIT_FAIL); else if (!root.openRoot(&volume)) SERIAL_ERROR_MSG(STR_SD_OPENROOT_FAIL); @@ -422,7 +484,8 @@ void CardReader::manage_media() { if (stat) { // Media Inserted safe_delay(500); // Some boards need a delay to get settled - mount(); // Try to mount the media + if (TERN1(SD_IGNORE_AT_STARTUP, old_stat != 2)) + mount(); // Try to mount the media #if MB(FYSETC_CHEETAH, FYSETC_CHEETAH_V12, FYSETC_AIO_II) reset_stepper_drivers(); // Workaround for Cheetah bug #endif @@ -438,20 +501,31 @@ void CardReader::manage_media() { if (stat) { TERN_(SDCARD_EEPROM_EMULATION, settings.first_load()); - if (old_stat == 2) // First mount? + if (old_stat == 2) { // First mount? DEBUG_ECHOLNPGM("First mount."); - TERN(POWER_LOSS_RECOVERY, - recovery.check(), // Check for PLR file. (If not there it will beginautostart) - beginautostart() // Look for auto0.g on the next loop - ); + #if ENABLED(POWER_LOSS_RECOVERY) + recovery.check(); // Check for PLR file. (If not there then call autofile_begin) + #elif DISABLED(NO_SD_AUTOSTART) + autofile_begin(); // Look for auto0.g on the next loop + #endif + } } } else DEBUG_ECHOLNPGM("SD: No UI Detected."); } +/** + * "Release" the media by clearing the 'mounted' flag. + * Used by M22, "Release Media", manage_media. + */ void CardReader::release() { - endFilePrint(); + // Card removed while printing? Abort! + if (IS_SD_PRINTING()) + abortFilePrintSoon(); + else + endFilePrintNow(); + flag.mounted = false; flag.workDirIsRoot = true; #if ALL(SDCARD_SORT_ALPHA, SDSORT_USES_RAM, SDSORT_CACHE_NAMES) @@ -459,39 +533,57 @@ void CardReader::release() { #endif } +/** + * Open a G-code file and set Marlin to start processing it. + * Enqueues M23 and M24 commands to initiate a media print. + */ void CardReader::openAndPrintFile(const char *name) { - char cmd[4 + strlen(name) + 1]; // Room for "M23 ", filename, and null - extern const char M23_STR[]; + char cmd[4 + strlen(name) + 1 + 3 + 1]; // Room for "M23 ", filename, "\n", "M24", and null sprintf_P(cmd, M23_STR, name); for (char *c = &cmd[4]; *c; c++) *c = tolower(*c); - queue.enqueue_one_now(cmd); - queue.enqueue_now_P(M24_STR); + strcat_P(cmd, PSTR("\nM24")); + queue.inject(cmd); } -void CardReader::startFileprint() { +/** + * Start or resume a media print by setting the sdprinting flag. + * The file browser pre-sort is also purged to free up memory, + * since you cannot browse files during active printing. + * Used by M24 and anywhere Start / Resume applies. + */ +void CardReader::startOrResumeFilePrinting() { if (isMounted()) { flag.sdprinting = true; + flag.sdprintdone = false; TERN_(SD_RESORT, flush_presort()); } } -void CardReader::endFilePrint(TERN_(SD_RESORT, const bool re_sort/*=false*/)) { +// +// Run tasks upon finishing or aborting a file print. +// +void CardReader::endFilePrintNow(TERN_(SD_RESORT, const bool re_sort/*=false*/)) { TERN_(ADVANCED_PAUSE_FEATURE, did_pause_print = 0); TERN_(DWIN_CREALITY_LCD, HMI_flag.print_finish = flag.sdprinting); - flag.sdprinting = flag.abort_sd_printing = false; + flag.abort_sd_printing = false; if (isFileOpen()) file.close(); TERN_(SD_RESORT, if (re_sort) presort()); } -void CardReader::openLogFile(char * const path) { +void CardReader::abortFilePrintNow(TERN_(SD_RESORT, const bool re_sort/*=false*/)) { + flag.sdprinting = flag.sdprintdone = false; + endFilePrintNow(TERN_(SD_RESORT, re_sort)); +} + +void CardReader::openLogFile(const char * const path) { flag.logging = DISABLED(SDCARD_READONLY); - TERN(SDCARD_READONLY,,openFileWrite(path)); + IF_DISABLED(SDCARD_READONLY, openFileWrite(path)); } // // Get the root-relative DOS path of the selected file // -void CardReader::getAbsFilename(char *dst) { +void CardReader::getAbsFilenameInCWD(char *dst) { *dst++ = '/'; uint8_t cnt = 1; @@ -517,12 +609,11 @@ void openFailed(const char * const fname) { void announceOpen(const uint8_t doing, const char * const path) { if (doing) { - PORT_REDIRECT(SERIAL_BOTH); + PORT_REDIRECT(SerialMask::All); SERIAL_ECHO_START(); SERIAL_ECHOPGM("Now "); - serialprintPGM(doing == 1 ? PSTR("doing") : PSTR("fresh")); + SERIAL_ECHOPGM_P(doing == 1 ? PSTR("doing") : PSTR("fresh")); SERIAL_ECHOLNPAIR(" file: ", path); - PORT_RESTORE(); } } @@ -534,43 +625,46 @@ void announceOpen(const uint8_t doing, const char * const path) { // - 1 : (no file open) Opening a macro (M98). // - 2 : Resuming from a sub-procedure // -void CardReader::openFileRead(char * const path, const uint8_t subcall_type/*=0*/) { +void CardReader::openFileRead(const char * const path, const uint8_t subcall_type/*=0*/) { if (!isMounted()) return; switch (subcall_type) { case 0: // Starting a new print. "Now fresh file: ..." announceOpen(2, path); - file_subcall_ctr = 0; + TERN_(HAS_MEDIA_SUBCALLS, file_subcall_ctr = 0); break; - case 1: // Starting a sub-procedure + #if HAS_MEDIA_SUBCALLS - // With no file is open it's a simple macro. "Now doing file: ..." - if (!isFileOpen()) { announceOpen(1, path); break; } + case 1: // Starting a sub-procedure - // Too deep? The firmware has to bail. - if (file_subcall_ctr > SD_PROCEDURE_DEPTH - 1) { - SERIAL_ERROR_MSG("Exceeded max SUBROUTINE depth:" STRINGIFY(SD_PROCEDURE_DEPTH)); - kill(GET_TEXT(MSG_KILL_SUBCALL_OVERFLOW)); - return; - } + // With no file is open it's a simple macro. "Now doing file: ..." + if (!isFileOpen()) { announceOpen(1, path); break; } - // Store current filename (based on workDirParents) and position - getAbsFilename(proc_filenames[file_subcall_ctr]); - filespos[file_subcall_ctr] = sdpos; + // Too deep? The firmware has to bail. + if (file_subcall_ctr > SD_PROCEDURE_DEPTH - 1) { + SERIAL_ERROR_MSG("Exceeded max SUBROUTINE depth:", SD_PROCEDURE_DEPTH); + kill(GET_TEXT(MSG_KILL_SUBCALL_OVERFLOW)); + return; + } - // For sub-procedures say 'SUBROUTINE CALL target: "..." parent: "..." pos12345' - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR("SUBROUTINE CALL target:\"", path, "\" parent:\"", proc_filenames[file_subcall_ctr], "\" pos", sdpos); - file_subcall_ctr++; - break; + // Store current filename (based on workDirParents) and position + getAbsFilenameInCWD(proc_filenames[file_subcall_ctr]); + filespos[file_subcall_ctr] = sdpos; - case 2: // Resuming previous file after sub-procedure - SERIAL_ECHO_MSG("END SUBROUTINE"); - break; + // For sub-procedures say 'SUBROUTINE CALL target: "..." parent: "..." pos12345' + SERIAL_ECHO_MSG("SUBROUTINE CALL target:\"", path, "\" parent:\"", proc_filenames[file_subcall_ctr], "\" pos", sdpos); + file_subcall_ctr++; + break; + + case 2: // Resuming previous file after sub-procedure + SERIAL_ECHO_MSG("END SUBROUTINE"); + break; + + #endif } - endFilePrint(); + abortFilePrintNow(); SdFile *diveDir; const char * const fname = diveToFile(true, diveDir, path); @@ -580,10 +674,11 @@ void CardReader::openFileRead(char * const path, const uint8_t subcall_type/*=0* filesize = file.fileSize(); sdpos = 0; - PORT_REDIRECT(SERIAL_BOTH); - SERIAL_ECHOLNPAIR(STR_SD_FILE_OPENED, fname, STR_SD_SIZE, filesize); - SERIAL_ECHOLNPGM(STR_SD_FILE_SELECTED); - PORT_RESTORE(); + { // Don't remove this block, as the PORT_REDIRECT is a RAII + PORT_REDIRECT(SerialMask::All); + SERIAL_ECHOLNPAIR(STR_SD_FILE_OPENED, fname, STR_SD_SIZE, filesize); + SERIAL_ECHOLNPGM(STR_SD_FILE_SELECTED); + } selectFileByName(fname); ui.set_status(longFilename[0] ? longFilename : fname); @@ -599,13 +694,13 @@ inline void echo_write_to_file(const char * const fname) { // // Open a file by DOS path for write // -void CardReader::openFileWrite(char * const path) { +void CardReader::openFileWrite(const char * const path) { if (!isMounted()) return; announceOpen(2, path); - file_subcall_ctr = 0; + TERN_(HAS_MEDIA_SUBCALLS, file_subcall_ctr = 0); - endFilePrint(); + abortFilePrintNow(); SdFile *diveDir; const char * const fname = diveToFile(false, diveDir, path); @@ -632,14 +727,24 @@ void CardReader::openFileWrite(char * const path) { // bool CardReader::fileExists(const char * const path) { if (!isMounted()) return false; + + DEBUG_ECHOLNPAIR("fileExists: ", path); + + // Dive to the file's directory and get the base name SdFile *diveDir = nullptr; const char * const fname = diveToFile(false, diveDir, path); - if (fname) { - diveDir->rewind(); - selectByName(*diveDir, fname); - diveDir->close(); - } - return fname != nullptr; + if (!fname) return false; + + // Get the longname of the checked file + //diveDir->rewind(); + //selectByName(*diveDir, fname); + //diveDir->close(); + + // Try to open the file and return the result + SdFile tmpFile; + const bool success = tmpFile.open(diveDir, fname, O_READ); + if (success) tmpFile.close(); + return success; } // @@ -648,16 +753,16 @@ bool CardReader::fileExists(const char * const path) { void CardReader::removeFile(const char * const name) { if (!isMounted()) return; - //endFilePrint(); + //abortFilePrintNow(); - SdFile *curDir; - const char * const fname = diveToFile(false, curDir, name); + SdFile *itsDirPtr; + const char * const fname = diveToFile(false, itsDirPtr, name); if (!fname) return; #if ENABLED(SDCARD_READONLY) SERIAL_ECHOLNPAIR("Deletion failed (read-only), File: ", fname, "."); #else - if (file.remove(curDir, fname)) { + if (file.remove(itsDirPtr, fname)) { SERIAL_ECHOLNPAIR("File deleted:", fname); sdpos = 0; TERN_(SDCARD_SORT_ALPHA, presort()); @@ -669,8 +774,7 @@ void CardReader::removeFile(const char * const name) { void CardReader::report_status() { if (isPrinting()) { - SERIAL_ECHOPGM(STR_SD_PRINTING_BYTE); - SERIAL_ECHO(sdpos); + SERIAL_ECHOPAIR(STR_SD_PRINTING_BYTE, sdpos); SERIAL_CHAR('/'); SERIAL_ECHOLN(filesize); } @@ -679,12 +783,12 @@ void CardReader::report_status() { } void CardReader::write_command(char * const buf) { - char* begin = buf; - char* npos = nullptr; - char* end = buf + strlen(buf) - 1; + char *begin = buf, + *npos = nullptr, + *end = buf + strlen(buf) - 1; file.writeError = false; - if ((npos = strchr(buf, 'N')) != nullptr) { + if ((npos = strchr(buf, 'N'))) { begin = strchr(npos, ' ') + 1; end = strchr(npos, '*') - 1; } @@ -696,42 +800,48 @@ void CardReader::write_command(char * const buf) { if (file.writeError) SERIAL_ERROR_MSG(STR_SD_ERR_WRITE_TO_FILE); } -// -// Run the next autostart file. Called: -// - On boot after successful card init -// - After finishing the previous autostart file -// - From the LCD command to run the autostart file -// - -void CardReader::checkautostart() { - - if (autostart_index < 0 || flag.sdprinting) return; - - if (!isMounted()) mount(); - TERN_(SDCARD_EEPROM_EMULATION, else settings.first_load()); +#if DISABLED(NO_SD_AUTOSTART) + /** + * Run all the auto#.g files. Called: + * - On boot after successful card init. + * - From the LCD command to Run Auto Files + */ + void CardReader::autofile_begin() { + autofile_index = 1; + (void)autofile_check(); + } - // Don't run auto#.g when a PLR file exists - if (isMounted() && TERN1(POWER_LOSS_RECOVERY, !recovery.valid())) { - char autoname[8]; - sprintf_P(autoname, PSTR("auto%c.g"), autostart_index + '0'); - dir_t p; - root.rewind(); - while (root.readDir(&p, nullptr) > 0) { - for (int8_t i = (int8_t)strlen((char*)p.name); i--;) p.name[i] = tolower(p.name[i]); - if (p.name[9] != '~' && strncmp((char*)p.name, autoname, 5) == 0) { + /** + * Run the next auto#.g file. Called: + * - On boot after successful card init + * - After finishing the previous auto#.g file + * - From the LCD command to begin the auto#.g files + * + * Return 'true' if an auto file was started + */ + bool CardReader::autofile_check() { + if (!autofile_index) return false; + + if (!isMounted()) + mount(); + else if (ENABLED(SDCARD_EEPROM_EMULATION)) + settings.first_load(); + + // Don't run auto#.g when a PLR file exists + if (isMounted() && TERN1(POWER_LOSS_RECOVERY, !recovery.valid())) { + char autoname[10]; + sprintf_P(autoname, PSTR("/auto%c.g"), '0' + autofile_index - 1); + if (fileExists(autoname)) { + cdroot(); openAndPrintFile(autoname); - autostart_index++; - return; + autofile_index++; + return true; } } + autofile_cancel(); + return false; } - autostart_index = -1; -} - -void CardReader::beginautostart() { - autostart_index = 0; - cdroot(); -} +#endif void CardReader::closefile(const bool store_location/*=false*/) { file.sync(); @@ -787,100 +897,109 @@ uint16_t CardReader::countFilesInWorkDir() { /** * Dive to the given DOS 8.3 file path, with optional echo of the dive paths. * + * On entry: + * - The workDir points to the last-set navigation target by cd, cdup, cdroot, or diveToFile(true, ...) + * * On exit: * - Your curDir pointer contains an SdFile reference to the file's directory. * - If update_cwd was 'true' the workDir now points to the file's directory. * * Returns a pointer to the last segment (filename) of the given DOS 8.3 path. + * On exit, inDirPtr contains an SdFile reference to the file's directory. * * A nullptr result indicates an unrecoverable error. + * + * NOTE: End the path with a slash to dive to a folder. In this case the + * returned filename will be blank (points to the end of the path). */ -const char* CardReader::diveToFile(const bool update_cwd, SdFile*& diveDir, const char * const path, const bool echo/*=false*/) { +const char* CardReader::diveToFile(const bool update_cwd, SdFile* &inDirPtr, const char * const path, const bool echo/*=false*/) { + DEBUG_SECTION(est, "diveToFile", true); + // Track both parent and subfolder static SdFile newDir1, newDir2; - SdFile *sub = &newDir1, *startDir; + SdFile *sub = &newDir1, *startDirPtr; // Parsing the path string - const char *item_name_adr = path; + const char *atom_ptr = path; - DEBUG_ECHOLNPAIR("diveToFile: path = '", path, "'"); + DEBUG_ECHOLNPAIR(" path = '", path, "'"); if (path[0] == '/') { // Starting at the root directory? - diveDir = &root; - item_name_adr++; - DEBUG_ECHOLNPAIR("diveToFile: CWD to root: ", hex_address((void*)diveDir)); + inDirPtr = &root; + atom_ptr++; + DEBUG_ECHOLNPAIR(" CWD to root: ", hex_address((void*)inDirPtr)); if (update_cwd) workDirDepth = 0; // The cwd can be updated for the benefit of sub-programs } else - diveDir = &workDir; // Dive from workDir (as set by the UI) + inDirPtr = &workDir; // Dive from workDir (as set by the UI) - startDir = diveDir; + startDirPtr = inDirPtr; - DEBUG_ECHOLNPAIR("diveToFile: startDir = ", hex_address((void*)startDir)); + DEBUG_ECHOLNPAIR(" startDirPtr = ", hex_address((void*)startDirPtr)); - while (item_name_adr) { + while (atom_ptr) { // Find next subdirectory delimiter - char * const name_end = strchr(item_name_adr, '/'); + const char * const name_end = strchr(atom_ptr, '/'); // Last atom in the path? Item found. - if (name_end <= item_name_adr) break; + if (name_end <= atom_ptr) break; - // Set subDirName - const uint8_t len = name_end - item_name_adr; + // Isolate the next subitem name + const uint8_t len = name_end - atom_ptr; char dosSubdirname[len + 1]; - strncpy(dosSubdirname, item_name_adr, len); + strncpy(dosSubdirname, atom_ptr, len); dosSubdirname[len] = 0; if (echo) SERIAL_ECHOLN(dosSubdirname); - DEBUG_ECHOLNPAIR("diveToFile: sub = ", hex_address((void*)sub)); + DEBUG_ECHOLNPAIR(" sub = ", hex_address((void*)sub)); - // Open diveDir (closing first) + // Open inDirPtr (closing first) sub->close(); - if (!sub->open(diveDir, dosSubdirname, O_READ)) { + if (!sub->open(inDirPtr, dosSubdirname, O_READ)) { openFailed(dosSubdirname); - item_name_adr = nullptr; + atom_ptr = nullptr; break; } - // Close diveDir if not at starting-point - if (diveDir != startDir) { - DEBUG_ECHOLNPAIR("diveToFile: closing diveDir: ", hex_address((void*)diveDir)); - diveDir->close(); + // Close inDirPtr if not at starting-point + if (inDirPtr != startDirPtr) { + DEBUG_ECHOLNPAIR(" closing inDirPtr: ", hex_address((void*)inDirPtr)); + inDirPtr->close(); } - // diveDir now subDir - diveDir = sub; - DEBUG_ECHOLNPAIR("diveToFile: diveDir = sub: ", hex_address((void*)diveDir)); + // inDirPtr now subDir + inDirPtr = sub; + DEBUG_ECHOLNPAIR(" inDirPtr = sub: ", hex_address((void*)inDirPtr)); // Update workDirParents and workDirDepth if (update_cwd) { - DEBUG_ECHOLNPAIR("diveToFile: update_cwd"); + DEBUG_ECHOLNPAIR(" update_cwd"); if (workDirDepth < MAX_DIR_DEPTH) - workDirParents[workDirDepth++] = *diveDir; + workDirParents[workDirDepth++] = *inDirPtr; } // Point sub at the other scratch object - sub = (diveDir != &newDir1) ? &newDir1 : &newDir2; - DEBUG_ECHOLNPAIR("diveToFile: swapping sub = ", hex_address((void*)sub)); + sub = (inDirPtr != &newDir1) ? &newDir1 : &newDir2; + DEBUG_ECHOLNPAIR(" swapping sub = ", hex_address((void*)sub)); // Next path atom address - item_name_adr = name_end + 1; + atom_ptr = name_end + 1; } if (update_cwd) { - workDir = *diveDir; - DEBUG_ECHOLNPAIR("diveToFile: final workDir = ", hex_address((void*)diveDir)); + workDir = *inDirPtr; + DEBUG_ECHOLNPAIR(" final workDir = ", hex_address((void*)inDirPtr)); flag.workDirIsRoot = (workDirDepth == 0); TERN_(SDCARD_SORT_ALPHA, presort()); } - return item_name_adr; + DEBUG_ECHOLNPAIR(" returning string ", atom_ptr ?: "nullptr"); + return atom_ptr; } void CardReader::cd(const char * relpath) { - SdFile newDir; - SdFile *parent = workDir.isOpen() ? &workDir : &root; + SdFile newDir, *parent = &getWorkDir(); if (newDir.open(parent, relpath, O_READ)) { workDir = newDir; @@ -889,10 +1008,8 @@ void CardReader::cd(const char * relpath) { workDirParents[workDirDepth++] = workDir; TERN_(SDCARD_SORT_ALPHA, presort()); } - else { - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR(STR_SD_CANT_ENTER_SUBDIR, relpath); - } + else + SERIAL_ECHO_MSG(STR_SD_CANT_ENTER_SUBDIR, relpath); } int8_t CardReader::cdup() { @@ -907,6 +1024,7 @@ int8_t CardReader::cdup() { void CardReader::cdroot() { workDir = root; flag.workDirIsRoot = true; + workDirDepth = 0; TERN_(SDCARD_SORT_ALPHA, presort()); } @@ -1036,7 +1154,9 @@ void CardReader::cdroot() { #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 - TERN_(HAS_FOLDER_SORTING, bool dir1 = flag.filenameIsDir); + #if HAS_FOLDER_SORTING + bool dir1 = flag.filenameIsDir; + #endif #endif for (uint16_t j = 0; j < i; ++j) { @@ -1099,7 +1219,7 @@ void CardReader::cdroot() { #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]); - TERN_(HAS_FOLDER_SORTING, free(isDir)); + TERN_(HAS_FOLDER_SORTING, delete [] isDir); #endif #endif } @@ -1125,14 +1245,14 @@ void CardReader::cdroot() { void CardReader::flush_presort() { if (sort_count > 0) { #if ENABLED(SDSORT_DYNAMIC_RAM) - delete sort_order; + delete [] sort_order; #if ENABLED(SDSORT_CACHE_NAMES) LOOP_L_N(i, sort_count) { free(sortshort[i]); // strdup free(sortnames[i]); // strdup } - delete sortshort; - delete sortnames; + delete [] sortshort; + delete [] sortnames; #endif #endif sort_count = 0; @@ -1156,37 +1276,26 @@ uint16_t CardReader::get_num_Files() { // Return from procedure or close out the Print Job // void CardReader::fileHasFinished() { - planner.synchronize(); file.close(); - if (file_subcall_ctr > 0) { // Resume calling file after closing procedure - file_subcall_ctr--; - openFileRead(proc_filenames[file_subcall_ctr], 2); // 2 = Returning from sub-procedure - setIndex(filespos[file_subcall_ctr]); - startFileprint(); - } - else { - endFilePrint(TERN_(SD_RESORT, true)); + #if HAS_MEDIA_SUBCALLS + if (file_subcall_ctr > 0) { // Resume calling file after closing procedure + file_subcall_ctr--; + openFileRead(proc_filenames[file_subcall_ctr], 2); // 2 = Returning from sub-procedure + setIndex(filespos[file_subcall_ctr]); + startOrResumeFilePrinting(); + return; + } + #endif - marlin_state = MF_SD_COMPLETE; - } + endFilePrintNow(TERN_(SD_RESORT, true)); + + flag.sdprintdone = true; // Stop getting bytes from the SD card + marlin_state = MF_SD_COMPLETE; // Tell Marlin to enqueue M1001 soon } #if ENABLED(AUTO_REPORT_SD_STATUS) - uint8_t CardReader::auto_report_sd_interval = 0; - millis_t CardReader::next_sd_report_ms; - #if HAS_MULTI_SERIAL - int8_t CardReader::auto_report_port; - #endif - - void CardReader::auto_report_sd_status() { - millis_t current_ms = millis(); - if (auto_report_sd_interval && ELAPSED(current_ms, next_sd_report_ms)) { - next_sd_report_ms = current_ms + 1000UL * auto_report_sd_interval; - PORT_REDIRECT(auto_report_port); - report_status(); - } - } -#endif // AUTO_REPORT_SD_STATUS + AutoReporter CardReader::auto_reporter; +#endif #if ENABLED(POWER_LOSS_RECOVERY) @@ -1200,7 +1309,7 @@ void CardReader::fileHasFinished() { if (!isMounted()) return; if (recovery.file.isOpen()) return; if (!recovery.file.open(&root, recovery.filename, read ? O_READ : O_CREAT | O_WRITE | O_TRUNC | O_SYNC)) - SERIAL_ECHOLNPAIR(STR_SD_OPEN_FILE_FAIL, recovery.filename, "."); + openFailed(recovery.filename); else if (!read) echo_write_to_file(recovery.filename); } @@ -1214,7 +1323,7 @@ void CardReader::fileHasFinished() { removeFile(recovery.filename); #if ENABLED(DEBUG_POWER_LOSS_RECOVERY) SERIAL_ECHOPGM("Power-loss file delete"); - serialprintPGM(jobRecoverFileExists() ? PSTR(" failed.\n") : PSTR("d.\n")); + SERIAL_ECHOPGM_P(jobRecoverFileExists() ? PSTR(" failed.\n") : PSTR("d.\n")); #endif } } diff --git a/Marlin/src/sd/cardreader.h b/Marlin/src/sd/cardreader.h index 33645b6531eb..66cb97baeb9e 100644 --- a/Marlin/src/sd/cardreader.h +++ b/Marlin/src/sd/cardreader.h @@ -23,10 +23,10 @@ #include "../inc/MarlinConfig.h" -#define IFSD(A,B) TERN(SDSUPPORT,A,B) - #if ENABLED(SDSUPPORT) +extern const char M23_STR[], M24_STR[]; + #if BOTH(SDCARD_SORT_ALPHA, SDSORT_DYNAMIC_RAM) #define SD_RESORT 1 #endif @@ -42,11 +42,35 @@ #define MAXPATHNAMELENGTH (1 + (MAXDIRNAMELENGTH + 1) * (MAX_DIR_DEPTH) + 1 + FILENAME_LENGTH) // "/" + N * ("ADIRNAME/") + "filename.ext" #include "SdFile.h" +#include "disk_io_driver.h" + +#if ENABLED(USB_FLASH_DRIVE_SUPPORT) + #include "usb_flashdrive/Sd2Card_FlashDrive.h" +#endif + +#if NEED_SD2CARD_SDIO + #include "Sd2Card_sdio.h" +#elif NEED_SD2CARD_SPI + #include "Sd2Card.h" +#endif + +#if ENABLED(MULTI_VOLUME) + #define SV_SD_ONBOARD 1 + #define SV_USB_FLASH_DRIVE 2 + #define _VOLUME_ID(N) _CAT(SV_, N) + #define SHARED_VOLUME_IS(N) (DEFAULT_SHARED_VOLUME == _VOLUME_ID(N)) + #if !SHARED_VOLUME_IS(SD_ONBOARD) && !SHARED_VOLUME_IS(USB_FLASH_DRIVE) + #error "DEFAULT_SHARED_VOLUME must be either SD_ONBOARD or USB_FLASH_DRIVE." + #endif +#else + #define SHARED_VOLUME_IS(...) 0 +#endif typedef struct { bool saving:1, logging:1, sdprinting:1, + sdprintdone:1, mounted:1, filenameIsDir:1, workDirIsRoot:1, @@ -57,6 +81,10 @@ typedef struct { ; } card_flags_t; +#if ENABLED(AUTO_REPORT_SD_STATUS) + #include "../libs/autoreport.h" +#endif + class CardReader { public: static card_flags_t flag; // Flags (above) @@ -66,9 +94,9 @@ class CardReader { // Fast! binary file transfer #if ENABLED(BINARY_FILE_TRANSFER) #if HAS_MULTI_SERIAL - static int8_t transfer_port_index; + static serial_index_t transfer_port_index; #else - static constexpr int8_t transfer_port_index = 0; + static constexpr serial_index_t transfer_port_index = 0; #endif #endif @@ -76,28 +104,31 @@ class CardReader { CardReader(); + static void changeMedia(DiskIODriver *_driver) { driver = _driver; } + static SdFile getroot() { return root; } static void mount(); static void release(); static inline bool isMounted() { return flag.mounted; } - static void ls(); // Handle media insert/remove static void manage_media(); // SD Card Logging - static void openLogFile(char * const path); + static void openLogFile(const char * const path); static void write_command(char * const buf); - // Auto-Start files - static int8_t autostart_index; // Index of autoX.g files - static void beginautostart(); - static void checkautostart(); + #if DISABLED(NO_SD_AUTOSTART) // Auto-Start auto#.g file handling + static uint8_t autofile_index; // Next auto#.g index to run, plus one. Ignored by autofile_check when zero. + static void autofile_begin(); // Begin check. Called automatically after boot-up. + static bool autofile_check(); // Check for the next auto-start file and run it. + static inline void autofile_cancel() { autofile_index = 0; } + #endif // Basic file ops - static void openFileRead(char * const path, const uint8_t subcall=0); - static void openFileWrite(char * const path); + static void openFileRead(const char * const path, const uint8_t subcall=0); + static void openFileWrite(const char * const path); static void closefile(const bool store_location=false); static bool fileExists(const char * const name); static void removeFile(const char * const name); @@ -116,65 +147,101 @@ class CardReader { // Select a file static void selectFileByIndex(const uint16_t nr); - static void selectFileByName(const char* const match); + static void selectFileByName(const char * const match); // (working directory only) // Print job - static void openAndPrintFile(const char *name); // (working directory) - static void fileHasFinished(); - static void getAbsFilename(char *dst); - static void printFilename(); - static void startFileprint(); - static void endFilePrint(TERN_(SD_RESORT, const bool re_sort=false)); static void report_status(); - static inline void pauseSDPrint() { flag.sdprinting = false; } - static inline bool isPaused() { return isFileOpen() && !flag.sdprinting; } - static inline bool isPrinting() { return flag.sdprinting; } + static void getAbsFilenameInCWD(char *dst); + static void printSelectedFilename(); + static void openAndPrintFile(const char *name); // (working directory or full path) + static void startOrResumeFilePrinting(); + static void endFilePrintNow(TERN_(SD_RESORT, const bool re_sort=false)); + static void abortFilePrintNow(TERN_(SD_RESORT, const bool re_sort=false)); + static void fileHasFinished(); + static inline void abortFilePrintSoon() { flag.abort_sd_printing = true; } + static inline void pauseSDPrint() { flag.sdprinting = false; } + static inline bool isPrinting() { return flag.sdprinting; } + static inline bool isPaused() { return isFileOpen() && !isPrinting(); } #if HAS_PRINT_PROGRESS_PERMYRIAD - static inline uint16_t permyriadDone() { return (isFileOpen() && filesize) ? sdpos / ((filesize + 9999) / 10000) : 0; } + static inline uint16_t permyriadDone() { + if (flag.sdprintdone) return 10000; + if (isFileOpen() && filesize) return sdpos / ((filesize + 9999) / 10000); + return 0; + } #endif - static inline uint8_t percentDone() { return (isFileOpen() && filesize) ? sdpos / ((filesize + 99) / 100) : 0; } - - // Helper for open and remove - static const char* diveToFile(const bool update_cwd, SdFile*& curDir, const char * const path, const bool echo=false); + static inline uint8_t percentDone() { + if (flag.sdprintdone) return 100; + if (isFileOpen() && filesize) return sdpos / ((filesize + 99) / 100); + return 0; + } + + /** + * Dive down to a relative or absolute path. + * Relative paths apply to the workDir. + * + * update_cwd: Pass 'true' to update the workDir on success. + * inDirPtr: On exit your pointer points to the target SdFile. + * A nullptr indicates failure. + * path: Start with '/' for abs path. End with '/' to get a folder ref. + * echo: Set 'true' to print the path throughout the loop. + */ + static const char* diveToFile(const bool update_cwd, SdFile* &inDirPtr, const char * const path, const bool echo=false); #if ENABLED(SDCARD_SORT_ALPHA) static void presort(); static void getfilename_sorted(const uint16_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(bool b) { sort_alpha = b; presort(); } + FORCE_INLINE static void setSortFolders(int 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); } #endif + static void ls(TERN_(LONG_FILENAME_HOST_SUPPORT, bool includeLongNames=false)); + #if ENABLED(POWER_LOSS_RECOVERY) static bool jobRecoverFileExists(); static void openJobRecoveryFile(const bool read); static void removeJobRecoveryFile(); #endif - static inline bool isFileOpen() { return isMounted() && file.isOpen(); } - static inline uint32_t getIndex() { return sdpos; } - static inline uint32_t getFileSize() { return filesize; } - static inline bool eof() { return sdpos >= filesize; } - static inline void setIndex(const uint32_t index) { sdpos = index; file.seekSet(index); } - static inline char* getWorkDirName() { workDir.getDosName(filename); return filename; } - static inline int16_t get() { sdpos = file.curPosition(); return (int16_t)file.read(); } - static inline int16_t read(void* buf, uint16_t nbyte) { return file.isOpen() ? file.read(buf, nbyte) : -1; } - static inline int16_t write(void* buf, uint16_t nbyte) { return file.isOpen() ? file.write(buf, nbyte) : -1; } + // Current Working Dir - Set by cd, cdup, cdroot, and diveToFile(true, ...) + static inline char* getWorkDirName() { workDir.getDosName(filename); return filename; } + static inline SdFile& getWorkDir() { return workDir.isOpen() ? workDir : root; } + + // Print File stats + static inline uint32_t getFileSize() { return filesize; } + static inline uint32_t getIndex() { return sdpos; } + static inline bool isFileOpen() { return isMounted() && file.isOpen(); } + static inline bool eof() { return getIndex() >= getFileSize(); } + + // File data operations + static inline int16_t get() { int16_t out = (int16_t)file.read(); sdpos = file.curPosition(); return out; } + static inline int16_t read(void *buf, uint16_t nbyte) { return file.isOpen() ? file.read(buf, nbyte) : -1; } + static inline int16_t write(void *buf, uint16_t nbyte) { return file.isOpen() ? file.write(buf, nbyte) : -1; } + static inline void setIndex(const uint32_t index) { file.seekSet((sdpos = index)); } - static Sd2Card& getSd2Card() { return sd2card; } + // TODO: rename to diskIODriver() + static DiskIODriver* diskIODriver() { return driver; } #if ENABLED(AUTO_REPORT_SD_STATUS) - static void auto_report_sd_status(); - static inline void set_auto_report_interval(uint8_t v) { - TERN_(HAS_MULTI_SERIAL, auto_report_port = serial_port_index); - NOMORE(v, 60); - auto_report_sd_interval = v; - next_sd_report_ms = millis() + 1000UL * v; - } + // + // SD Auto Reporting + // + struct AutoReportSD { static void report() { report_status(); } }; + static AutoReporter auto_reporter; + #endif + + #if SHARED_VOLUME_IS(USB_FLASH_DRIVE) || ENABLED(USB_FLASH_DRIVE_SUPPORT) + #define HAS_USB_FLASH_DRIVE 1 + static DiskIODriver_USBFlash media_driver_usbFlash; + #endif + + #if NEED_SD2CARD_SDIO || NEED_SD2CARD_SPI + typedef TERN(NEED_SD2CARD_SDIO, DiskIODriver_SDIO, DiskIODriver_SPI_SD) sdcard_driver_t; + static sdcard_driver_t media_driver_sdcard; #endif private: @@ -232,7 +299,7 @@ class CardReader { #if ENABLED(SDSORT_DYNAMIC_RAM) static uint8_t *isDir; #elif ENABLED(SDSORT_CACHE_NAMES) || DISABLED(SDSORT_USES_STACK) - static uint8_t isDir[(SDSORT_LIMIT+7)>>3]; + static uint8_t isDir[(SDSORT_LIMIT + 7) >> 3]; #endif #endif @@ -240,31 +307,20 @@ class CardReader { #endif // SDCARD_SORT_ALPHA - static Sd2Card sd2card; + static DiskIODriver *driver; static SdVolume volume; static SdFile file; - static uint32_t filesize, sdpos; + static uint32_t filesize, // Total size of the current file, in bytes + sdpos; // Index most recently read (one behind file.getPos) // // Procedure calls to other files // - #ifndef SD_PROCEDURE_DEPTH - #define SD_PROCEDURE_DEPTH 1 - #endif - static uint8_t file_subcall_ctr; - static uint32_t filespos[SD_PROCEDURE_DEPTH]; - static char proc_filenames[SD_PROCEDURE_DEPTH][MAXPATHNAMELENGTH]; - - // - // SD Auto Reporting - // - #if ENABLED(AUTO_REPORT_SD_STATUS) - static uint8_t auto_report_sd_interval; - static millis_t next_sd_report_ms; - #if HAS_MULTI_SERIAL - static int8_t auto_report_port; - #endif + #if HAS_MEDIA_SUBCALLS + static uint8_t file_subcall_ctr; + static uint32_t filespos[SD_PROCEDURE_DEPTH]; + static char proc_filenames[SD_PROCEDURE_DEPTH][MAXPATHNAMELENGTH]; #endif // @@ -274,7 +330,12 @@ class CardReader { static int countItems(SdFile dir); static void selectByIndex(SdFile dir, const uint8_t index); static void selectByName(SdFile dir, const char * const match); - static void printListing(SdFile parent, const char * const prepend=nullptr); + static void printListing( + SdFile parent + OPTARG(LONG_FILENAME_HOST_SUPPORT, const bool includeLongNames=false) + , const char * const prepend=nullptr + OPTARG(LONG_FILENAME_HOST_SUPPORT, const char * const prependLong=nullptr) + ); #if ENABLED(SDCARD_SORT_ALPHA) static void flush_presort(); @@ -282,7 +343,7 @@ class CardReader { }; #if ENABLED(USB_FLASH_DRIVE_SUPPORT) - #define IS_SD_INSERTED() Sd2Card::isInserted() + #define IS_SD_INSERTED() DiskIODriver_USBFlash::isInserted() #elif PIN_EXISTS(SD_DETECT) #define IS_SD_INSERTED() (READ(SD_DETECT_PIN) == SD_DETECT_STATE) #else @@ -290,7 +351,8 @@ class CardReader { #define IS_SD_INSERTED() true #endif -#define IS_SD_PRINTING() card.flag.sdprinting +#define IS_SD_PRINTING() (card.flag.sdprinting && !card.flag.abort_sd_printing) +#define IS_SD_FETCHING() (!card.flag.sdprintdone && IS_SD_PRINTING()) #define IS_SD_PAUSED() card.isPaused() #define IS_SD_FILE_OPEN() card.isFileOpen() @@ -299,6 +361,7 @@ extern CardReader card; #else // !SDSUPPORT #define IS_SD_PRINTING() false +#define IS_SD_FETCHING() false #define IS_SD_PAUSED() false #define IS_SD_FILE_OPEN() false diff --git a/Marlin/src/sd/disk_io_driver.h b/Marlin/src/sd/disk_io_driver.h new file mode 100644 index 000000000000..02e2b3c73991 --- /dev/null +++ b/Marlin/src/sd/disk_io_driver.h @@ -0,0 +1,67 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include + +/** + * DiskIO Interface + * + * Interface for low level disk io + */ +class DiskIODriver { +public: + /** + * Initialize an SD flash memory card with default clock rate and chip + * select pin. See sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin). + * + * \return true for success or false for failure. + */ + virtual bool init(const uint8_t sckRateID, const pin_t chipSelectPin) = 0; //TODO: only for SPI + + /** + * Read a card's CSD register. The CSD contains Card-Specific Data that + * provides information regarding access to the card's contents. + * + * \param[out] csd pointer to area for returned data. + * + * \return true for success or false for failure. + */ + virtual bool readCSD(csd_t* csd) = 0; + + virtual bool readStart(const uint32_t block) = 0; + virtual bool readData(uint8_t* dst) = 0; + virtual bool readStop() = 0; + + virtual bool writeStart(const uint32_t block, const uint32_t) = 0; + virtual bool writeData(const uint8_t* src) = 0; + virtual bool writeStop() = 0; + + virtual bool readBlock(uint32_t block, uint8_t* dst) = 0; + virtual bool writeBlock(uint32_t blockNumber, const uint8_t* src) = 0; + + virtual uint32_t cardSize() = 0; + + virtual bool isReady() = 0; + + virtual void idle() = 0; +}; diff --git a/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.cpp b/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.cpp index a097df510523..19754184154e 100644 --- a/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.cpp +++ b/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.cpp @@ -44,16 +44,17 @@ #include "../../core/serial.h" #include "../../module/temperature.h" -static_assert(USB_CS_PIN != -1, "USB_CS_PIN must be defined"); -static_assert(USB_INTR_PIN != -1, "USB_INTR_PIN must be defined"); +#if DISABLED(USE_OTG_USB_HOST) && !PINS_EXIST(USB_CS, USB_INTR) + #error "USB_FLASH_DRIVE_SUPPORT requires USB_CS_PIN and USB_INTR_PIN to be defined." +#endif #if ENABLED(USE_UHS3_USB) #define NO_AUTO_SPEED - #define UHS_MAX3421E_SPD 8000000 >> SPI_SPEED + #define UHS_MAX3421E_SPD 8000000 >> SD_SPI_SPEED #define UHS_DEVICE_WINDOWS_USB_SPEC_VIOLATION_DESCRIPTOR_DEVICE 1 #define UHS_HOST_MAX_INTERFACE_DRIVERS 2 #define MASS_MAX_SUPPORTED_LUN 1 - #define USB_HOST_SERIAL MYSERIAL0 + #define USB_HOST_SERIAL MYSERIAL1 // Workaround for certain issues with UHS3 #define SKIP_PAGE3F // Required for IOGEAR media adapter @@ -81,6 +82,17 @@ static_assert(USB_INTR_PIN != -1, "USB_INTR_PIN must be defined"); #define UHS_START (usb.Init() == 0) #define UHS_STATE(state) UHS_USB_HOST_STATE_##state +#elif ENABLED(USE_OTG_USB_HOST) + + #if HAS_SD_HOST_DRIVE + #include HAL_PATH(../../HAL, msc_sd.h) + #endif + + #include HAL_PATH(../../HAL, usb_host.h) + + #define UHS_START usb.start() + #define rREVISION 0 + #define UHS_STATE(state) USB_STATE_##state #else #include "lib-uhs2/Usb.h" #include "lib-uhs2/masstorage.h" @@ -94,7 +106,7 @@ static_assert(USB_INTR_PIN != -1, "USB_INTR_PIN must be defined"); #include "Sd2Card_FlashDrive.h" -#include "../../lcd/ultralcd.h" +#include "../../lcd/marlinui.h" static enum { UNINITIALIZED, @@ -109,7 +121,7 @@ static enum { uint32_t lun0_capacity; #endif -bool Sd2Card::usbStartup() { +bool DiskIODriver_USBFlash::usbStartup() { if (state <= DO_STARTUP) { SERIAL_ECHOPGM("Starting USB host..."); if (!UHS_START) { @@ -135,7 +147,7 @@ bool Sd2Card::usbStartup() { // the USB library to monitor for such events. This function also takes care // of initializing the USB library for the first time. -void Sd2Card::idle() { +void DiskIODriver_USBFlash::idle() { usb.Task(); const uint8_t task_state = usb.getUsbTaskState(); @@ -246,16 +258,16 @@ void Sd2Card::idle() { // Marlin calls this function to check whether an USB drive is inserted. // This is equivalent to polling the SD_DETECT when using SD cards. -bool Sd2Card::isInserted() { +bool DiskIODriver_USBFlash::isInserted() { return state == MEDIA_READY; } -bool Sd2Card::ready() { - return state > DO_STARTUP; +bool DiskIODriver_USBFlash::isReady() { + return state > DO_STARTUP && usb.getUsbTaskState() == UHS_STATE(RUNNING); } // Marlin calls this to initialize an SD card once it is inserted. -bool Sd2Card::init(const uint8_t, const pin_t) { +bool DiskIODriver_USBFlash::init(const uint8_t, const pin_t) { if (!isInserted()) return false; #if USB_DEBUG >= 1 @@ -274,7 +286,7 @@ bool Sd2Card::init(const uint8_t, const pin_t) { } // Returns the capacity of the card in blocks. -uint32_t Sd2Card::cardSize() { +uint32_t DiskIODriver_USBFlash::cardSize() { if (!isInserted()) return false; #if USB_DEBUG < 3 const uint32_t @@ -283,7 +295,7 @@ uint32_t Sd2Card::cardSize() { return lun0_capacity; } -bool Sd2Card::readBlock(uint32_t block, uint8_t* dst) { +bool DiskIODriver_USBFlash::readBlock(uint32_t block, uint8_t *dst) { if (!isInserted()) return false; #if USB_DEBUG >= 3 if (block >= lun0_capacity) { @@ -297,7 +309,7 @@ bool Sd2Card::readBlock(uint32_t block, uint8_t* dst) { return bulk.Read(0, block, 512, 1, dst) == 0; } -bool Sd2Card::writeBlock(uint32_t block, const uint8_t* src) { +bool DiskIODriver_USBFlash::writeBlock(uint32_t block, const uint8_t *src) { if (!isInserted()) return false; #if USB_DEBUG >= 3 if (block >= lun0_capacity) { diff --git a/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.h b/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.h index 8ca95ba7061c..3390bc51becc 100644 --- a/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.h +++ b/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.h @@ -23,29 +23,31 @@ /** * \file - * \brief Sd2Card class for V2 SD/SDHC cards + * \brief Sd2Card class for USB Flash Drive */ - #include "../SdFatConfig.h" #include "../SdInfo.h" +#include "../disk_io_driver.h" -/** - * Define SOFTWARE_SPI to use bit-bang SPI - */ -#if EITHER(MEGA_SOFT_SPI, USE_SOFTWARE_SPI) - #define SOFTWARE_SPI -#endif +#if DISABLED(USE_OTG_USB_HOST) + /** + * Define SOFTWARE_SPI to use bit-bang SPI + */ + #if EITHER(MEGA_SOFT_SPI, USE_SOFTWARE_SPI) + #define SOFTWARE_SPI + #endif -// SPI pin definitions - do not edit here - change in SdFatConfig.h -#if ENABLED(SOFTWARE_SPI) - #warning "Auto-assigning '10' as the SD_CHIP_SELECT_PIN." - #define SD_CHIP_SELECT_PIN 10 // Software SPI chip select pin for the SD -#else - // hardware pin defs - #define SD_CHIP_SELECT_PIN SS_PIN // The default chip select pin for the SD card is SS. + // SPI pin definitions - do not edit here - change in SdFatConfig.h + #if ENABLED(SOFTWARE_SPI) + #warning "Auto-assigning '10' as the SD_CHIP_SELECT_PIN." + #define SD_CHIP_SELECT_PIN 10 // Software SPI chip select pin for the SD + #else + // hardware pin defs + #define SD_CHIP_SELECT_PIN SD_SS_PIN // The default chip select pin for the SD card is SS. + #endif #endif -class Sd2Card { +class DiskIODriver_USBFlash : public DiskIODriver { private: uint32_t pos; @@ -53,23 +55,26 @@ class Sd2Card { public: static bool usbStartup(); + static bool isInserted(); - bool init(const uint8_t sckRateID=0, const pin_t chipSelectPin=SD_CHIP_SELECT_PIN); + bool init(const uint8_t sckRateID=0, const pin_t chipSelectPin=TERN(USE_OTG_USB_HOST, 0, SD_CHIP_SELECT_PIN)) override; - static void idle(); + inline bool readCSD(csd_t*) override { return true; } - inline bool readStart(const uint32_t block) { pos = block; return ready(); } - inline bool readData(uint8_t* dst) { return readBlock(pos++, dst); } - inline bool readStop() const { return true; } + inline bool readStart(const uint32_t block) override { pos = block; return isReady(); } + inline bool readData(uint8_t *dst) override { return readBlock(pos++, dst); } + inline bool readStop() override { return true; } - inline bool writeStart(const uint32_t block, const uint32_t) { pos = block; return ready(); } - inline bool writeData(uint8_t* src) { return writeBlock(pos++, src); } - inline bool writeStop() const { return true; } + inline bool writeStart(const uint32_t block, const uint32_t) override { pos = block; return isReady(); } + inline bool writeData(const uint8_t *src) override { return writeBlock(pos++, src); } + inline bool writeStop() override { return true; } - bool readBlock(uint32_t block, uint8_t* dst); - bool writeBlock(uint32_t blockNumber, const uint8_t* src); + bool readBlock(uint32_t block, uint8_t *dst) override; + bool writeBlock(uint32_t blockNumber, const uint8_t *src) override; - uint32_t cardSize(); - static bool isInserted(); - static bool ready(); + uint32_t cardSize() override; + + bool isReady() override; + + void idle() override; }; diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/Usb.cpp b/Marlin/src/sd/usb_flashdrive/lib-uhs2/Usb.cpp index 8a989157b40a..75421f4482a8 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/Usb.cpp +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/Usb.cpp @@ -22,7 +22,10 @@ * Web : https://www.circuitsathome.com * e-mail : support@circuitsathome.com */ -/* USB functions */ + +// +// USB functions supporting Flash Drive +// #include "../../../inc/MarlinConfigPre.h" @@ -35,7 +38,7 @@ static uint8_t usb_task_state; /* constructor */ USB::USB() : bmHubPre(0) { - usb_task_state = USB_DETACHED_SUBSTATE_INITIALIZE; //set up state machine + usb_task_state = USB_DETACHED_SUBSTATE_INITIALIZE; // Set up state machine init(); } @@ -45,13 +48,8 @@ void USB::init() { bmHubPre = 0; } -uint8_t USB::getUsbTaskState() { - return usb_task_state; -} - -void USB::setUsbTaskState(uint8_t state) { - usb_task_state = state; -} +uint8_t USB::getUsbTaskState() { return usb_task_state; } +void USB::setUsbTaskState(uint8_t state) { usb_task_state = state; } EpInfo* USB::getEpInfoEntry(uint8_t addr, uint8_t ep) { UsbDevice *p = addrPool.GetUsbDevicePtr(addr); @@ -70,9 +68,11 @@ EpInfo* USB::getEpInfoEntry(uint8_t addr, uint8_t ep) { return nullptr; } -/* set device table entry */ - -/* each device is different and has different number of endpoints. This function plugs endpoint record structure, defined in application, to devtable */ +/** + * Set device table entry + * Each device is different and has different number of endpoints. + * This function plugs endpoint record structure, defined in application, to devtable + */ uint8_t USB::setEpInfoEntry(uint8_t addr, uint8_t epcount, EpInfo* eprecord_ptr) { if (!eprecord_ptr) return USB_ERROR_INVALID_ARGUMENT; @@ -112,7 +112,7 @@ uint8_t USB::SetAddress(uint8_t addr, uint8_t ep, EpInfo **ppep, uint16_t *nak_l USBTRACE2(" NAK Limit: ", nak_limit); USBTRACE("\r\n"); */ - regWr(rPERADDR, addr); //set peripheral address + regWr(rPERADDR, addr); // Set peripheral address uint8_t mode = regRd(rMODE); @@ -121,8 +121,6 @@ uint8_t USB::SetAddress(uint8_t addr, uint8_t ep, EpInfo **ppep, uint16_t *nak_l //Serial.print("\r\nLS: "); //Serial.println(p->lowspeed, HEX); - - // Set bmLOWSPEED and bmHUBPRE in case of low-speed device, reset them otherwise regWr(rMODE, (p->lowspeed) ? mode | bmLOWSPEED | bmHubPre : mode & ~(bmHUBPRE | bmLOWSPEED)); @@ -133,11 +131,10 @@ uint8_t USB::SetAddress(uint8_t addr, uint8_t ep, EpInfo **ppep, uint16_t *nak_l /* depending on request. Actual requests are defined as inlines */ /* return codes: */ /* 00 = success */ - /* 01-0f = non-zero HRSLT */ uint8_t USB::ctrlReq(uint8_t addr, uint8_t ep, uint8_t bmReqType, uint8_t bRequest, uint8_t wValLo, uint8_t wValHi, - uint16_t wInd, uint16_t total, uint16_t nbytes, uint8_t* dataptr, USBReadParser *p) { - bool direction = false; //request direction, IN or OUT + uint16_t wInd, uint16_t total, uint16_t nbytes, uint8_t *dataptr, USBReadParser *p) { + bool direction = false; // Request direction, IN or OUT uint8_t rcode; SETUP_PKT setup_pkt; @@ -157,15 +154,15 @@ uint8_t USB::ctrlReq(uint8_t addr, uint8_t ep, uint8_t bmReqType, uint8_t bReque setup_pkt.wIndex = wInd; setup_pkt.wLength = total; - bytesWr(rSUDFIFO, 8, (uint8_t*) & setup_pkt); //transfer to setup packet FIFO + bytesWr(rSUDFIFO, 8, (uint8_t*) & setup_pkt); // Transfer to setup packet FIFO - rcode = dispatchPkt(tokSETUP, ep, nak_limit); //dispatch packet + rcode = dispatchPkt(tokSETUP, ep, nak_limit); // Dispatch packet if (rcode) return rcode; // Return HRSLT if not zero - if (dataptr != nullptr) { //data stage, if present - if (direction) { //IN transfer + if (dataptr) { // Data stage, if present + if (direction) { // IN transfer uint16_t left = total; - pep->bmRcvToggle = 1; //bmRCVTOG1; + pep->bmRcvToggle = 1; // BmRCVTOG1; while (left) { // Bytes read into buffer @@ -174,7 +171,7 @@ uint8_t USB::ctrlReq(uint8_t addr, uint8_t ep, uint8_t bmReqType, uint8_t bReque rcode = InTransfer(pep, nak_limit, &read, dataptr); if (rcode == hrTOGERR) { - // yes, we flip it wrong here so that next time it is actually correct! + // Yes, we flip it wrong here so that next time it is actually correct! pep->bmRcvToggle = (regRd(rHRSL) & bmSNDTOGRD) ? 0 : 1; continue; } @@ -189,22 +186,22 @@ uint8_t USB::ctrlReq(uint8_t addr, uint8_t ep, uint8_t bmReqType, uint8_t bReque if (read < nbytes) break; } } - else { //OUT transfer - pep->bmSndToggle = 1; //bmSNDTOG1; + else { // OUT transfer + pep->bmSndToggle = 1; // BmSNDTOG1; rcode = OutTransfer(pep, nak_limit, nbytes, dataptr); } - if (rcode) return rcode; // return error + if (rcode) return rcode; // Return error } // Status stage - return dispatchPkt((direction) ? tokOUTHS : tokINHS, ep, nak_limit); //GET if direction + return dispatchPkt((direction) ? tokOUTHS : tokINHS, ep, nak_limit); // GET if direction } -/* IN transfer to arbitrary endpoint. Assumes PERADDR is set. Handles multiple packets if necessary. Transfers 'nbytes' bytes. */ -/* 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*/) { +/** + * IN transfer to arbitrary endpoint. Assumes PERADDR is set. Handles multiple packets if necessary. Transfers 'nbytes' bytes. + * 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*/) { EpInfo *pep = nullptr; uint16_t nak_limit = 0; @@ -218,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; @@ -227,29 +224,29 @@ uint8_t USB::InTransfer(EpInfo *pep, uint16_t nak_limit, uint16_t *nbytesptr, ui uint8_t maxpktsize = pep->maxPktSize; *nbytesptr = 0; - regWr(rHCTL, (pep->bmRcvToggle) ? bmRCVTOG1 : bmRCVTOG0); //set toggle value + regWr(rHCTL, (pep->bmRcvToggle) ? bmRCVTOG1 : bmRCVTOG0); // Set toggle value - // use a 'break' to exit this loop + // Use a 'break' to exit this loop for (;;) { - rcode = dispatchPkt(tokIN, pep->epAddr, nak_limit); //IN packet to EP-'endpoint'. Function takes care of NAKS. + rcode = dispatchPkt(tokIN, pep->epAddr, nak_limit); // IN packet to EP-'endpoint'. Function takes care of NAKS. if (rcode == hrTOGERR) { - // yes, we flip it wrong here so that next time it is actually correct! + // Yes, we flip it wrong here so that next time it is actually correct! pep->bmRcvToggle = (regRd(rHRSL) & bmRCVTOGRD) ? 0 : 1; - regWr(rHCTL, (pep->bmRcvToggle) ? bmRCVTOG1 : bmRCVTOG0); //set toggle value + regWr(rHCTL, (pep->bmRcvToggle) ? bmRCVTOG1 : bmRCVTOG0); // Set toggle value continue; } if (rcode) { //printf(">>>>>>>> Problem! dispatchPkt %2.2x\r\n", rcode); - break; //should be 0, indicating ACK. Else return error code. + break; // Should be 0, indicating ACK. Else return error code. } /* check for RCVDAVIRQ and generate error if not present */ /* the only case when absence of RCVDAVIRQ makes sense is when toggle error occurred. Need to add handling for that */ if ((regRd(rHIRQ) & bmRCVDAVIRQ) == 0) { //printf(">>>>>>>> Problem! NO RCVDAVIRQ!\r\n"); - rcode = 0xF0; //receive error + rcode = 0xF0; // Receive error break; } - pktsize = regRd(rRCVBC); //number of received bytes + pktsize = regRd(rRCVBC); // Number of received bytes //printf("Got %i bytes \r\n", pktsize); // This would be OK, but... //assert(pktsize <= nbytes); @@ -266,7 +263,7 @@ uint8_t USB::InTransfer(EpInfo *pep, uint16_t nak_limit, uint16_t *nbytesptr, ui data = bytesRd(rRCVFIFO, ((pktsize > mem_left) ? mem_left : pktsize), data); regWr(rHIRQ, bmRCVDAVIRQ); // Clear the IRQ & free the buffer - *nbytesptr += pktsize; // add this packet's byte count to total transfer length + *nbytesptr += pktsize; // Add this packet's byte count to total transfer length /* The transfer is complete under two conditions: */ /* 1. The device sent a short packet (L.T. maxPacketSize) */ @@ -284,11 +281,12 @@ uint8_t USB::InTransfer(EpInfo *pep, uint16_t nak_limit, uint16_t *nbytesptr, ui return rcode; } -/* OUT transfer to arbitrary endpoint. Handles multiple packets if necessary. Transfers 'nbytes' bytes. */ -/* Handles NAK bug per Maxim Application Note 4000 for single buffer transfer */ - -/* rcode 0 if no errors. rcode 01-0f is relayed from HRSL */ -uint8_t USB::outTransfer(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t* data) { +/** + * OUT transfer to arbitrary endpoint. Handles multiple packets if necessary. Transfers 'nbytes' bytes. + * Handles NAK bug per Maxim Application Note 4000 for single buffer transfer + * rcode 0 if no errors. rcode 01-0f is relayed from HRSL + */ +uint8_t USB::outTransfer(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t *data) { EpInfo *pep = nullptr; uint16_t nak_limit = 0; @@ -300,7 +298,7 @@ uint8_t USB::outTransfer(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t* dat uint8_t USB::OutTransfer(EpInfo *pep, uint16_t nak_limit, uint16_t nbytes, uint8_t *data) { uint8_t rcode = hrSUCCESS, retry_count; - uint8_t *data_p = data; //local copy of the data pointer + uint8_t *data_p = data; // Local copy of the data pointer uint16_t bytes_tosend, nak_count; uint16_t bytes_left = nbytes; @@ -311,17 +309,17 @@ uint8_t USB::OutTransfer(EpInfo *pep, uint16_t nak_limit, uint16_t nbytes, uint8 uint32_t timeout = (uint32_t)millis() + USB_XFER_TIMEOUT; - regWr(rHCTL, (pep->bmSndToggle) ? bmSNDTOG1 : bmSNDTOG0); //set toggle value + regWr(rHCTL, (pep->bmSndToggle) ? bmSNDTOG1 : bmSNDTOG0); // Set toggle value while (bytes_left) { retry_count = 0; nak_count = 0; bytes_tosend = (bytes_left >= maxpktsize) ? maxpktsize : bytes_left; - bytesWr(rSNDFIFO, bytes_tosend, data_p); //filling output FIFO - regWr(rSNDBC, bytes_tosend); //set number of bytes - regWr(rHXFR, (tokOUT | pep->epAddr)); //dispatch packet - while (!(regRd(rHIRQ) & bmHXFRDNIRQ)); //wait for the completion IRQ - regWr(rHIRQ, bmHXFRDNIRQ); //clear IRQ + bytesWr(rSNDFIFO, bytes_tosend, data_p); // Filling output FIFO + regWr(rSNDBC, bytes_tosend); // Set number of bytes + regWr(rHXFR, (tokOUT | pep->epAddr)); // Dispatch packet + while (!(regRd(rHIRQ) & bmHXFRDNIRQ)); // Wait for the completion IRQ + regWr(rHIRQ, bmHXFRDNIRQ); // Clear IRQ rcode = (regRd(rHRSL) & 0x0F); while (rcode && ((int32_t)((uint32_t)millis() - timeout) < 0L)) { @@ -330,18 +328,18 @@ uint8_t USB::OutTransfer(EpInfo *pep, uint16_t nak_limit, uint16_t nbytes, uint8 nak_count++; if (nak_limit && (nak_count == nak_limit)) goto breakout; - //return ( rcode); + //return rcode; break; case hrTIMEOUT: retry_count++; if (retry_count == USB_RETRY_LIMIT) goto breakout; - //return ( rcode); + //return rcode; break; case hrTOGERR: - // yes, we flip it wrong here so that next time it is actually correct! + // Yes, we flip it wrong here so that next time it is actually correct! pep->bmSndToggle = (regRd(rHRSL) & bmSNDTOGRD) ? 0 : 1; - regWr(rHCTL, (pep->bmSndToggle) ? bmSNDTOG1 : bmSNDTOG0); //set toggle value + regWr(rHCTL, (pep->bmSndToggle) ? bmSNDTOG1 : bmSNDTOG0); // Set toggle value break; default: goto breakout; @@ -351,26 +349,27 @@ uint8_t USB::OutTransfer(EpInfo *pep, uint16_t nak_limit, uint16_t nbytes, uint8 regWr(rSNDBC, 0); regWr(rSNDFIFO, *data_p); regWr(rSNDBC, bytes_tosend); - regWr(rHXFR, (tokOUT | pep->epAddr)); //dispatch packet - while (!(regRd(rHIRQ) & bmHXFRDNIRQ)); //wait for the completion IRQ - regWr(rHIRQ, bmHXFRDNIRQ); //clear IRQ + regWr(rHXFR, (tokOUT | pep->epAddr)); // Dispatch packet + while (!(regRd(rHIRQ) & bmHXFRDNIRQ)); // Wait for the completion IRQ + regWr(rHIRQ, bmHXFRDNIRQ); // Clear IRQ rcode = (regRd(rHRSL) & 0x0F); - } // while rcode && .... + } // While rcode && .... bytes_left -= bytes_tosend; data_p += bytes_tosend; - } // while bytes_left... + } // While bytes_left... breakout: - pep->bmSndToggle = (regRd(rHRSL) & bmSNDTOGRD) ? 1 : 0; //bmSNDTOG1 : bmSNDTOG0; //update toggle - return ( rcode); //should be 0 in all cases + pep->bmSndToggle = (regRd(rHRSL) & bmSNDTOGRD) ? 1 : 0; // BmSNDTOG1 : bmSNDTOG0; // Update toggle + return ( rcode); // Should be 0 in all cases } -/* dispatch USB packet. Assumes peripheral address is set and relevant buffer is loaded/empty */ -/* If NAK, tries to re-send up to nak_limit times */ -/* If nak_limit == 0, do not count NAKs, exit after timeout */ -/* If bus timeout, re-sends up to USB_RETRY_LIMIT times */ - -/* return codes 0x00-0x0F are HRSLT( 0x00 being success ), 0xFF means timeout */ +/** + * Dispatch USB packet. Assumes peripheral address is set and relevant buffer is loaded/empty + * If NAK, tries to re-send up to nak_limit times + * If nak_limit == 0, do not count NAKs, exit after timeout + * If bus timeout, re-sends up to USB_RETRY_LIMIT times + * return codes 0x00-0x0F are HRSLT( 0x00 being success ), 0xFF means timeout + */ uint8_t USB::dispatchPkt(uint8_t token, uint8_t ep, uint16_t nak_limit) { uint32_t timeout = (uint32_t)millis() + USB_XFER_TIMEOUT; uint8_t tmpdata; @@ -380,29 +379,28 @@ uint8_t USB::dispatchPkt(uint8_t token, uint8_t ep, uint16_t nak_limit) { while ((int32_t)((uint32_t)millis() - timeout) < 0L) { #if defined(ESP8266) || defined(ESP32) - yield(); // needed in order to reset the watchdog timer on the ESP8266 + yield(); // Needed in order to reset the watchdog timer on the ESP8266 #endif - regWr(rHXFR, (token | ep)); //launch the transfer + regWr(rHXFR, (token | ep)); // Launch the transfer rcode = USB_ERROR_TRANSFER_TIMEOUT; - while ((int32_t)((uint32_t)millis() - timeout) < 0L) { //wait for transfer completion + while ((int32_t)((uint32_t)millis() - timeout) < 0L) { // Wait for transfer completion #if defined(ESP8266) || defined(ESP32) - yield(); // needed to reset the watchdog timer on the ESP8266 + yield(); // Needed to reset the watchdog timer on the ESP8266 #endif tmpdata = regRd(rHIRQ); if (tmpdata & bmHXFRDNIRQ) { - regWr(rHIRQ, bmHXFRDNIRQ); //clear the interrupt + regWr(rHIRQ, bmHXFRDNIRQ); // Clear the interrupt rcode = 0x00; break; } - } // while millis() < timeout + } // While millis() < timeout - //if (rcode != 0x00) //exit if timeout - // return ( rcode); + //if (rcode != 0x00) return rcode; // Exit if timeout - rcode = (regRd(rHRSL) & 0x0F); //analyze transfer result + rcode = (regRd(rHRSL) & 0x0F); // Analyze transfer result switch (rcode) { case hrNAK: @@ -419,12 +417,12 @@ uint8_t USB::dispatchPkt(uint8_t token, uint8_t ep, uint16_t nak_limit) { return (rcode); } - } // while timeout > millis() + } // While timeout > millis() return rcode; } -/* USB main task. Performs enumeration/cleanup */ -void USB::Task() { //USB state machine +// USB main task. Performs enumeration/cleanup +void USB::Task() { // USB state machine uint8_t rcode; uint8_t tmpdata; static uint32_t delay = 0; @@ -437,19 +435,19 @@ void USB::Task() { //USB state machine /* modify USB task state if Vbus changed */ switch (tmpdata) { - case SE1: //illegal state + case SE1: // Illegal state usb_task_state = USB_DETACHED_SUBSTATE_ILLEGAL; lowspeed = false; break; - case SE0: //disconnected + case SE0: // Disconnected if ((usb_task_state & USB_STATE_MASK) != USB_STATE_DETACHED) usb_task_state = USB_DETACHED_SUBSTATE_INITIALIZE; lowspeed = false; break; case LSHOST: lowspeed = true; - //intentional fallthrough - case FSHOST: //attached + // Intentional fallthrough + case FSHOST: // Attached if ((usb_task_state & USB_STATE_MASK) == USB_STATE_DETACHED) { delay = (uint32_t)millis() + USB_SETTLE_DELAY; usb_task_state = USB_ATTACHED_SUBSTATE_SETTLE; @@ -470,31 +468,31 @@ void USB::Task() { //USB state machine usb_task_state = USB_DETACHED_SUBSTATE_WAIT_FOR_DEVICE; break; - case USB_DETACHED_SUBSTATE_WAIT_FOR_DEVICE: //just sit here + case USB_DETACHED_SUBSTATE_WAIT_FOR_DEVICE: // Just sit here break; - case USB_DETACHED_SUBSTATE_ILLEGAL: //just sit here + case USB_DETACHED_SUBSTATE_ILLEGAL: // Just sit here break; - case USB_ATTACHED_SUBSTATE_SETTLE: //settle time for just attached device + case USB_ATTACHED_SUBSTATE_SETTLE: // Settle time for just attached device if ((int32_t)((uint32_t)millis() - delay) >= 0L) usb_task_state = USB_ATTACHED_SUBSTATE_RESET_DEVICE; - else break; // don't fall through + else break; // Don't fall through case USB_ATTACHED_SUBSTATE_RESET_DEVICE: - regWr(rHCTL, bmBUSRST); //issue bus reset + regWr(rHCTL, bmBUSRST); // Issue bus reset usb_task_state = USB_ATTACHED_SUBSTATE_WAIT_RESET_COMPLETE; break; case USB_ATTACHED_SUBSTATE_WAIT_RESET_COMPLETE: if ((regRd(rHCTL) & bmBUSRST) == 0) { - tmpdata = regRd(rMODE) | bmSOFKAENAB; //start SOF generation + tmpdata = regRd(rMODE) | bmSOFKAENAB; // Start SOF generation regWr(rMODE, tmpdata); usb_task_state = USB_ATTACHED_SUBSTATE_WAIT_SOF; - //delay = (uint32_t)millis() + 20; //20ms wait after reset per USB spec + //delay = (uint32_t)millis() + 20; // 20ms wait after reset per USB spec } break; - case USB_ATTACHED_SUBSTATE_WAIT_SOF: //todo: change check order + case USB_ATTACHED_SUBSTATE_WAIT_SOF: // Todo: change check order if (regRd(rHIRQ) & bmFRAMEIRQ) { - //when first SOF received _and_ 20ms has passed we can continue + // When first SOF received _and_ 20ms has passed we can continue /* - if (delay < (uint32_t)millis()) //20ms passed + if (delay < (uint32_t)millis()) // 20ms passed usb_task_state = USB_STATE_CONFIGURING; */ usb_task_state = USB_ATTACHED_SUBSTATE_WAIT_RESET; @@ -503,7 +501,7 @@ void USB::Task() { //USB state machine break; case USB_ATTACHED_SUBSTATE_WAIT_RESET: if ((int32_t)((uint32_t)millis() - delay) >= 0L) usb_task_state = USB_STATE_CONFIGURING; - else break; // don't fall through + else break; // Don't fall through case USB_STATE_CONFIGURING: //Serial.print("\r\nConf.LS: "); @@ -565,11 +563,11 @@ uint8_t USB::AttemptConfig(uint8_t driver, uint8_t parent, uint8_t port, bool lo if (rcode == USB_ERROR_CONFIG_REQUIRES_ADDITIONAL_RESET) { if (parent == 0) { // Send a bus reset on the root interface. - regWr(rHCTL, bmBUSRST); //issue bus reset - delay(102); // delay 102ms, compensate for clock inaccuracy. + regWr(rHCTL, bmBUSRST); // Issue bus reset + delay(102); // Delay 102ms, compensate for clock inaccuracy. } else { - // reset parent port + // Reset parent port devConfig[parent]->ResetHubPort(port); } } @@ -592,11 +590,11 @@ uint8_t USB::AttemptConfig(uint8_t driver, uint8_t parent, uint8_t port, bool lo // Issue a bus reset, because the device may be in a limbo state if (parent == 0) { // Send a bus reset on the root interface. - regWr(rHCTL, bmBUSRST); //issue bus reset - delay(102); // delay 102ms, compensate for clock inaccuracy. + regWr(rHCTL, bmBUSRST); // Issue bus reset + delay(102); // Delay 102ms, compensate for clock inaccuracy. } else { - // reset parent port + // Reset parent port devConfig[parent]->ResetHubPort(port); } } @@ -623,19 +621,19 @@ uint8_t USB::AttemptConfig(uint8_t driver, uint8_t parent, uint8_t port, bool lo * 4: set address * 5: pUsb->setEpInfoEntry(bAddress, 1, epInfo), exit on fail * 6: while (configurations) { - * for (each configuration) { - * for (each driver) { - * 6a: Ask device if it likes configuration. Returns 0 on OK. - * If successful, the driver configured device. - * The driver now owns the endpoints, and takes over managing them. - * The following will need codes: - * Everything went well, instance consumed, exit with success. - * Instance already in use, ignore it, try next driver. - * Not a supported device, ignore it, try next driver. - * Not a supported configuration for this device, ignore it, try next driver. - * Could not configure device, fatal, exit with fail. - * } - * } + * for (each configuration) { + * for (each driver) { + * 6a: Ask device if it likes configuration. Returns 0 on OK. + * If successful, the driver configured device. + * The driver now owns the endpoints, and takes over managing them. + * The following will need codes: + * Everything went well, instance consumed, exit with success. + * Instance already in use, ignore it, try next driver. + * Not a supported device, ignore it, try next driver. + * Not a supported configuration for this device, ignore it, try next driver. + * Could not configure device, fatal, exit with fail. + * } + * } * } * 7: for (each driver) { * 7a: Ask device if it knows this VID/PID. Acts exactly like 6a, but using VID/PID @@ -671,7 +669,7 @@ uint8_t USB::Configuring(uint8_t parent, uint8_t port, bool lowspeed) { oldep_ptr = p->epinfo; // Temporary assign new pointer to epInfo to p->epinfo in order to - // avoid toggle inconsistence + // Avoid toggle inconsistence p->epinfo = &epInfo; @@ -687,7 +685,7 @@ uint8_t USB::Configuring(uint8_t parent, uint8_t port, bool lowspeed) { return rcode; } - // to-do? + // To-do? // Allocate new address according to device class //bAddress = addrPool.AllocAddress(parent, false, port); @@ -698,11 +696,11 @@ uint8_t USB::Configuring(uint8_t parent, uint8_t port, bool lowspeed) { // Qualify with subclass too. // // VID/PID & class tests default to false for drivers not yet ported - // subclass defaults to true, so you don't have to define it if you don't have to. + // Subclass defaults to true, so you don't have to define it if you don't have to. // for (devConfigIndex = 0; devConfigIndex < USB_NUMDEVICES; devConfigIndex++) { - if (!devConfig[devConfigIndex]) continue; // no driver - if (devConfig[devConfigIndex]->GetAddress()) continue; // consumed + if (!devConfig[devConfigIndex]) continue; // No driver + if (devConfig[devConfigIndex]->GetAddress()) continue; // Consumed if (devConfig[devConfigIndex]->DEVSUBCLASSOK(subklass) && (devConfig[devConfigIndex]->VIDPIDOK(vid, pid) || devConfig[devConfigIndex]->DEVCLASSOK(klass))) { rcode = AttemptConfig(devConfigIndex, parent, port, lowspeed); if (rcode != USB_DEV_CONFIG_ERROR_DEVICE_NOT_SUPPORTED) @@ -712,20 +710,20 @@ uint8_t USB::Configuring(uint8_t parent, uint8_t port, bool lowspeed) { if (devConfigIndex < USB_NUMDEVICES) return rcode; - // blindly attempt to configure + // Blindly attempt to configure for (devConfigIndex = 0; devConfigIndex < USB_NUMDEVICES; devConfigIndex++) { if (!devConfig[devConfigIndex]) continue; - if (devConfig[devConfigIndex]->GetAddress()) continue; // consumed + if (devConfig[devConfigIndex]->GetAddress()) continue; // Consumed if (devConfig[devConfigIndex]->DEVSUBCLASSOK(subklass) && (devConfig[devConfigIndex]->VIDPIDOK(vid, pid) || devConfig[devConfigIndex]->DEVCLASSOK(klass))) continue; // If this is true it means it must have returned USB_DEV_CONFIG_ERROR_DEVICE_NOT_SUPPORTED above rcode = AttemptConfig(devConfigIndex, parent, port, lowspeed); //printf("ERROR ENUMERATING %2.2x\r\n", rcode); if (!(rcode == USB_DEV_CONFIG_ERROR_DEVICE_NOT_SUPPORTED || rcode == USB_ERROR_CLASS_INSTANCE_ALREADY_IN_USE)) { - // in case of an error dev_index should be reset to 0 - // in order to start from the very beginning the - // next time the program gets here + // In case of an error dev_index should be reset to 0 + // in order to start from the very beginning the + // next time the program gets here //if (rcode != USB_DEV_CONFIG_ERROR_DEVICE_INIT_INCOMPLETE) - // devConfigIndex = 0; + //devConfigIndex = 0; return rcode; } } @@ -744,20 +742,22 @@ uint8_t USB::ReleaseDevice(uint8_t addr) { return 0; } -#if 1 //!defined(USB_METHODS_INLINE) -//get device descriptor - -uint8_t USB::getDevDescr(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t* dataptr) { +// Get device descriptor +uint8_t USB::getDevDescr(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t *dataptr) { return ctrlReq(addr, ep, bmREQ_GET_DESCR, USB_REQUEST_GET_DESCRIPTOR, 0x00, USB_DESCRIPTOR_DEVICE, 0x0000, nbytes, nbytes, dataptr, nullptr); } -//get configuration descriptor -uint8_t USB::getConfDescr(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t conf, uint8_t* dataptr) { +// Get configuration descriptor +uint8_t USB::getConfDescr(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t conf, uint8_t *dataptr) { return ctrlReq(addr, ep, bmREQ_GET_DESCR, USB_REQUEST_GET_DESCRIPTOR, conf, USB_DESCRIPTOR_CONFIGURATION, 0x0000, nbytes, nbytes, dataptr, nullptr); } -/* Requests Configuration Descriptor. Sends two Get Conf Descr requests. The first one gets the total length of all descriptors, then the second one requests this - total length. The length of the first request can be shorter ( 4 bytes ), however, there are devices which won't work unless this length is set to 9 */ +/** + * Requests Configuration Descriptor. Sends two Get Conf Descr requests. + * The first one gets the total length of all descriptors, then the second one requests this + * total length. The length of the first request can be shorter (4 bytes), however, there are + * devices which won't work unless this length is set to 9. + */ uint8_t USB::getConfDescr(uint8_t addr, uint8_t ep, uint8_t conf, USBReadParser *p) { const uint8_t bufSize = 64; uint8_t buf[bufSize]; @@ -773,25 +773,23 @@ uint8_t USB::getConfDescr(uint8_t addr, uint8_t ep, uint8_t conf, USBReadParser return ctrlReq(addr, ep, bmREQ_GET_DESCR, USB_REQUEST_GET_DESCRIPTOR, conf, USB_DESCRIPTOR_CONFIGURATION, 0x0000, total, bufSize, buf, p); } -//get string descriptor - -uint8_t USB::getStrDescr(uint8_t addr, uint8_t ep, uint16_t ns, uint8_t index, uint16_t langid, uint8_t* dataptr) { +// Get string descriptor +uint8_t USB::getStrDescr(uint8_t addr, uint8_t ep, uint16_t ns, uint8_t index, uint16_t langid, uint8_t *dataptr) { return ctrlReq(addr, ep, bmREQ_GET_DESCR, USB_REQUEST_GET_DESCRIPTOR, index, USB_DESCRIPTOR_STRING, langid, ns, ns, dataptr, nullptr); } -//set address +// Set address uint8_t USB::setAddr(uint8_t oldaddr, uint8_t ep, uint8_t newaddr) { uint8_t rcode = ctrlReq(oldaddr, ep, bmREQ_SET, USB_REQUEST_SET_ADDRESS, newaddr, 0x00, 0x0000, 0x0000, 0x0000, nullptr, nullptr); - //delay(2); //per USB 2.0 sect.9.2.6.3 + //delay(2); // Per USB 2.0 sect.9.2.6.3 delay(300); // Older spec says you should wait at least 200ms return rcode; //return ctrlReq(oldaddr, ep, bmREQ_SET, USB_REQUEST_SET_ADDRESS, newaddr, 0x00, 0x0000, 0x0000, 0x0000, nullptr, nullptr); } -//set configuration +// Set configuration uint8_t USB::setConf(uint8_t addr, uint8_t ep, uint8_t conf_value) { return ctrlReq(addr, ep, bmREQ_SET, USB_REQUEST_SET_CONFIGURATION, conf_value, 0x00, 0x0000, 0x0000, 0x0000, nullptr, nullptr); } -#endif // defined(USB_METHODS_INLINE) #endif // USB_FLASH_DRIVE_SUPPORT diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/UsbCore.h b/Marlin/src/sd/usb_flashdrive/lib-uhs2/UsbCore.h index d94958dd5492..2b6e1be52274 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/UsbCore.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/UsbCore.h @@ -114,7 +114,7 @@ typedef MAX3421e MAX3421E; // Official Arduinos (UNO, Duemilanove, Mega #define USB_NUMDEVICES 16 //number of USB devices //#define HUB_MAX_HUBS 7 // maximum number of hubs that can be attached to the host controller -#define HUB_PORT_RESET_DELAY 20 // hub port reset delay 10 ms recomended, can be up to 20 ms +#define HUB_PORT_RESET_DELAY 20 // hub port reset delay 10 ms recommended, can be up to 20 ms /* USB state machine states */ #define USB_STATE_MASK 0xF0 @@ -250,19 +250,19 @@ class USB : public MAX3421E { uint8_t setEpInfoEntry(uint8_t addr, uint8_t epcount, EpInfo* eprecord_ptr); /* Control requests */ - uint8_t getDevDescr(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t* dataptr); - uint8_t getConfDescr(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t conf, uint8_t* dataptr); + uint8_t getDevDescr(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t *dataptr); + uint8_t getConfDescr(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t conf, uint8_t *dataptr); uint8_t getConfDescr(uint8_t addr, uint8_t ep, uint8_t conf, USBReadParser *p); - uint8_t getStrDescr(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t index, uint16_t langid, uint8_t* dataptr); + uint8_t getStrDescr(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t index, uint16_t langid, uint8_t *dataptr); uint8_t setAddr(uint8_t oldaddr, uint8_t ep, uint8_t newaddr); uint8_t setConf(uint8_t addr, uint8_t ep, uint8_t conf_value); /**/ - uint8_t ctrlData(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t* dataptr, bool direction); + uint8_t ctrlData(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t *dataptr, bool direction); uint8_t ctrlStatus(uint8_t ep, bool direction, uint16_t nak_limit); - uint8_t inTransfer(uint8_t addr, uint8_t ep, uint16_t *nbytesptr, uint8_t* data, uint8_t bInterval = 0); - uint8_t outTransfer(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t* data); + uint8_t inTransfer(uint8_t addr, uint8_t ep, uint16_t *nbytesptr, uint8_t *data, uint8_t bInterval = 0); + uint8_t outTransfer(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t *data); uint8_t dispatchPkt(uint8_t token, uint8_t ep, uint16_t nak_limit); void Task(); @@ -272,7 +272,7 @@ class USB : public MAX3421E { uint8_t ReleaseDevice(uint8_t addr); uint8_t ctrlReq(uint8_t addr, uint8_t ep, uint8_t bmReqType, uint8_t bRequest, uint8_t wValLo, uint8_t wValHi, - uint16_t wInd, uint16_t total, uint16_t nbytes, uint8_t* dataptr, USBReadParser *p); + uint16_t wInd, uint16_t total, uint16_t nbytes, uint8_t *dataptr, USBReadParser *p); private: void init(); @@ -285,17 +285,17 @@ class USB : public MAX3421E { #if 0 //defined(USB_METHODS_INLINE) //get device descriptor -inline uint8_t USB::getDevDescr(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t* dataptr) { +inline uint8_t USB::getDevDescr(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t *dataptr) { return ( ctrlReq(addr, ep, bmREQ_GET_DESCR, USB_REQUEST_GET_DESCRIPTOR, 0x00, USB_DESCRIPTOR_DEVICE, 0x0000, nbytes, dataptr)); } //get configuration descriptor -inline uint8_t USB::getConfDescr(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t conf, uint8_t* dataptr) { +inline uint8_t USB::getConfDescr(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t conf, uint8_t *dataptr) { return ( ctrlReq(addr, ep, bmREQ_GET_DESCR, USB_REQUEST_GET_DESCRIPTOR, conf, USB_DESCRIPTOR_CONFIGURATION, 0x0000, nbytes, dataptr)); } //get string descriptor -inline uint8_t USB::getStrDescr(uint8_t addr, uint8_t ep, uint16_t nuint8_ts, uint8_t index, uint16_t langid, uint8_t* dataptr) { +inline uint8_t USB::getStrDescr(uint8_t addr, uint8_t ep, uint16_t nuint8_ts, uint8_t index, uint16_t langid, uint8_t *dataptr) { return ( ctrlReq(addr, ep, bmREQ_GET_DESCR, USB_REQUEST_GET_DESCRIPTOR, index, USB_DESCRIPTOR_STRING, langid, nuint8_ts, dataptr)); } //set address diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/confdescparser.h b/Marlin/src/sd/usb_flashdrive/lib-uhs2/confdescparser.h index 9ed35fff65c8..19d3756535f9 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/confdescparser.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/confdescparser.h @@ -57,7 +57,7 @@ class ConfigDescParser : public USBReadParser { uint8_t dscrLen; // Descriptor length uint8_t dscrType; // Descriptor type - bool isGoodInterface; // Apropriate interface flag + bool isGoodInterface; // Appropriate interface flag uint8_t confValue; // Configuration value uint8_t protoValue; // Protocol value uint8_t ifaceNumber; // Interface number diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.cpp b/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.cpp index a84a68320413..1aeef1703fec 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.cpp +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.cpp @@ -956,12 +956,6 @@ uint8_t BulkOnly::HandleUsbError(uint8_t error, uint8_t index) { return ((error && !count) ? MASS_ERR_GENERAL_USB_ERROR : MASS_ERR_SUCCESS); } -#if MS_WANT_PARSER - uint8_t BulkOnly::Transaction(CommandBlockWrapper *pcbw, uint16_t buf_size, void *buf) { - return Transaction(CommandBlockWrapper *pcbw, uint16_t buf_size, void *buf, 0); - } -#endif - /** * For driver use only. * @@ -972,9 +966,7 @@ uint8_t BulkOnly::HandleUsbError(uint8_t error, uint8_t index) { * @return */ uint8_t BulkOnly::Transaction(CommandBlockWrapper *pcbw, uint16_t buf_size, void *buf - #if MS_WANT_PARSER - , uint8_t flags - #endif + OPTARG(MS_WANT_PARSER, uint8_t flags/*=0*/) ) { #if MS_WANT_PARSER uint16_t bytes = (pcbw->dCBWDataTransferLength > buf_size) ? buf_size : pcbw->dCBWDataTransferLength; diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.h b/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.h index 25df006e513d..aafb91624b00 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.h @@ -553,10 +553,7 @@ class BulkOnly : public USBDeviceConfig, public UsbConfigXtracter { bool IsValidCSW(CommandStatusWrapper *pcsw, CommandBlockWrapperBase *pcbw); uint8_t ClearEpHalt(uint8_t index); - #if MS_WANT_PARSER - uint8_t Transaction(CommandBlockWrapper *cbw, uint16_t bsize, void *buf, uint8_t flags); - #endif - uint8_t Transaction(CommandBlockWrapper *cbw, uint16_t bsize, void *buf); + uint8_t Transaction(CommandBlockWrapper *cbw, uint16_t bsize, void *buf OPTARG(MS_WANT_PARSER, uint8_t flags=0)); uint8_t HandleUsbError(uint8_t error, uint8_t index); uint8_t HandleSCSIError(uint8_t status); }; diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/printhex.h b/Marlin/src/sd/usb_flashdrive/lib-uhs2/printhex.h index 319cd9c4c87d..6ded4fa9cc8f 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/printhex.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/printhex.h @@ -32,12 +32,12 @@ void E_Notifyc(char c, int lvl); template void PrintHex(T val, int lvl) { - int num_nibbles = sizeof (T) * 2; + int num_nybbles = sizeof (T) * 2; do { - char v = 48 + (((val >> (num_nibbles - 1) * 4)) & 0x0F); + char v = 48 + (((val >> (num_nybbles - 1) * 4)) & 0x0F); if (v > 57) v += 7; E_Notifyc(v, lvl); - } while (--num_nibbles); + } while (--num_nybbles); } template @@ -48,12 +48,12 @@ void PrintBin(T val, int lvl) { template void SerialPrintHex(T val) { - int num_nibbles = sizeof (T) * 2; + int num_nybbles = sizeof (T) * 2; do { - char v = 48 + (((val >> (num_nibbles - 1) * 4)) & 0x0F); + char v = 48 + (((val >> (num_nybbles - 1) * 4)) & 0x0F); if (v > 57) v += 7; USB_HOST_SERIAL.print(v); - } while (--num_nibbles); + } while (--num_nybbles); } template diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/settings.h b/Marlin/src/sd/usb_flashdrive/lib-uhs2/settings.h index 2de0d465e8f3..7ce7b5e6ba85 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/settings.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/settings.h @@ -66,7 +66,7 @@ * For example Serial3. */ #if ENABLED(USB_FLASH_DRIVE_SUPPORT) - #define USB_HOST_SERIAL MYSERIAL0 + #define USB_HOST_SERIAL MYSERIAL1 #endif #ifndef USB_HOST_SERIAL diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.cpp b/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.cpp index 6d2182cb8bbd..4ee206bc3297 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.cpp +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.cpp @@ -16,7 +16,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ /* What follows is a modified version of the MAX3421e originally defined in @@ -51,7 +51,7 @@ void MAX3421e::regWr(uint8_t reg, uint8_t data) { // multiple-byte write // return a pointer to memory position after last written -uint8_t* MAX3421e::bytesWr(uint8_t reg, uint8_t nbytes, uint8_t* data_p) { +uint8_t* MAX3421e::bytesWr(uint8_t reg, uint8_t nbytes, uint8_t *data_p) { cs(); spiSend(reg | 0x02); while (nbytes--) spiSend(*data_p++); @@ -79,7 +79,7 @@ uint8_t MAX3421e::regRd(uint8_t reg) { // multiple-byte register read // return a pointer to a memory position after last read -uint8_t* MAX3421e::bytesRd(uint8_t reg, uint8_t nbytes, uint8_t* data_p) { +uint8_t* MAX3421e::bytesRd(uint8_t reg, uint8_t nbytes, uint8_t *data_p) { cs(); spiSend(reg); while (nbytes--) *data_p++ = spiRec(); @@ -114,13 +114,7 @@ bool MAX3421e::start() { ncs(); spiBegin(); - spiInit( - #ifdef SPI_SPEED - SPI_SPEED - #else - SPI_FULL_SPEED - #endif - ); + spiInit(SD_SPI_SPEED); // MAX3421e - full-duplex, level interrupt, vbus off. regWr(rPINCTL, (bmFDUPSPI | bmINTLEVEL | GPX_VBDET)); diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.h b/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.h index 07ca811a4def..cbdd28185863 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.h @@ -16,7 +16,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once @@ -37,10 +37,10 @@ class MAX3421e { bool start(); void regWr(uint8_t reg, uint8_t data); - uint8_t* bytesWr(uint8_t reg, uint8_t nbytes, uint8_t* data_p); + uint8_t* bytesWr(uint8_t reg, uint8_t nbytes, uint8_t *data_p); void gpioWr(uint8_t data); uint8_t regRd(uint8_t reg); - uint8_t* bytesRd(uint8_t reg, uint8_t nbytes, uint8_t* data_p); + uint8_t* bytesRd(uint8_t reg, uint8_t nbytes, uint8_t *data_p); uint8_t gpioRd(); bool reset(); 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 1591f3b74b8a..58d7ba200cb5 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 @@ -248,7 +248,7 @@ e-mail : support@circuitsathome.com #define UHS_HOST_TRANSFER_MAX_MS 10000 // USB transfer timeout in ms, per section 9.2.6.1 of USB 2.0 spec #define UHS_HOST_TRANSFER_RETRY_MAXIMUM 3 // 3 retry limit for a transfer #define UHS_HOST_DEBOUNCE_DELAY_MS 500 // settle delay in milliseconds -#define UHS_HUB_RESET_DELAY_MS 20 // hub port reset delay, 10ms recomended, but can be up to 20ms +#define UHS_HUB_RESET_DELAY_MS 20 // hub port reset delay, 10ms recommended, but can be up to 20ms // // We only provide the minimum needed information for enumeration. 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 9c7b5001c090..f78a3bb8f0fa 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 @@ -90,7 +90,7 @@ uint8_t UHS_USB_HOST_BASE::setEpInfoEntry(uint8_t addr, uint8_t iface, uint8_t e } /** - * sets all enpoint addresses to zero. + * sets all endpoint addresses to zero. * Sets all max packet sizes to defaults * Clears all endpoint attributes * Sets bmNakPower to USB_NAK_DEFAULT @@ -594,7 +594,7 @@ void UHS_USB_HOST_BASE::ReleaseDevice(uint8_t addr) { * @param dataptr pointer to the data to return * @return status of the request, zero is success. */ -uint8_t UHS_USB_HOST_BASE::getDevDescr(uint8_t addr, uint16_t nbytes, uint8_t* dataptr) { +uint8_t UHS_USB_HOST_BASE::getDevDescr(uint8_t addr, uint16_t nbytes, uint8_t *dataptr) { return ( ctrlReq(addr, mkSETUP_PKT8(UHS_bmREQ_GET_DESCR, USB_REQUEST_GET_DESCRIPTOR, 0x00, USB_DESCRIPTOR_DEVICE, 0x0000, nbytes), nbytes, dataptr)); } @@ -607,7 +607,7 @@ uint8_t UHS_USB_HOST_BASE::getDevDescr(uint8_t addr, uint16_t nbytes, uint8_t* d * @param dataptr ointer to the data to return * @return status of the request, zero is success. */ -uint8_t UHS_USB_HOST_BASE::getConfDescr(uint8_t addr, uint16_t nbytes, uint8_t conf, uint8_t* dataptr) { +uint8_t UHS_USB_HOST_BASE::getConfDescr(uint8_t addr, uint16_t nbytes, uint8_t conf, uint8_t *dataptr) { return ( ctrlReq(addr, mkSETUP_PKT8(UHS_bmREQ_GET_DESCR, USB_REQUEST_GET_DESCRIPTOR, conf, USB_DESCRIPTOR_CONFIGURATION, 0x0000, nbytes), nbytes, dataptr)); } @@ -621,7 +621,7 @@ uint8_t UHS_USB_HOST_BASE::getConfDescr(uint8_t addr, uint16_t nbytes, uint8_t c * @param dataptr pointer to the data to return * @return status of the request, zero is success. */ -uint8_t UHS_USB_HOST_BASE::getStrDescr(uint8_t addr, uint16_t ns, uint8_t index, uint16_t langid, uint8_t* dataptr) { +uint8_t UHS_USB_HOST_BASE::getStrDescr(uint8_t addr, uint16_t ns, uint8_t index, uint16_t langid, uint8_t *dataptr) { return ( ctrlReq(addr, mkSETUP_PKT8(UHS_bmREQ_GET_DESCR, USB_REQUEST_GET_DESCRIPTOR, index, USB_DESCRIPTOR_STRING, langid, ns), ns, dataptr)); } @@ -668,7 +668,7 @@ uint8_t UHS_USB_HOST_BASE::setConf(uint8_t addr, uint8_t conf_value) { * @param data pointer to buffer to hold transfer * @return zero for success or error code */ -uint8_t UHS_USB_HOST_BASE::outTransfer(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t* data) { +uint8_t UHS_USB_HOST_BASE::outTransfer(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t *data) { UHS_EpInfo *pep = NULL; uint16_t nak_limit = 0; HOST_DEBUG("outTransfer: addr: 0x%2.2x ep: 0x%2.2x nbytes: 0x%4.4x data: 0x%p\r\n", addr, ep, nbytes, data); @@ -689,7 +689,7 @@ uint8_t UHS_USB_HOST_BASE::outTransfer(uint8_t addr, uint8_t ep, uint16_t nbytes * @param data pointer to buffer to hold transfer * @return zero for success or error code */ -uint8_t UHS_USB_HOST_BASE::inTransfer(uint8_t addr, uint8_t ep, uint16_t *nbytesptr, uint8_t* data) { +uint8_t UHS_USB_HOST_BASE::inTransfer(uint8_t addr, uint8_t ep, uint16_t *nbytesptr, uint8_t *data) { UHS_EpInfo *pep = NULL; uint16_t nak_limit = 0; @@ -980,11 +980,11 @@ uint8_t UHS_USB_HOST_BASE::eat(UHS_EpInfo *pep, uint16_t *left, uint16_t *read, return rcode; } -uint8_t UHS_USB_HOST_BASE::ctrlReq(uint8_t addr, uint64_t Request, uint16_t nbytes, uint8_t* dataptr) { +uint8_t UHS_USB_HOST_BASE::ctrlReq(uint8_t addr, uint64_t Request, uint16_t nbytes, uint8_t *dataptr) { //bool direction = bmReqType & 0x80; //request direction, IN or OUT uint8_t rcode = 0; - // Serial.println(""); + //Serial.println(); UHS_EpInfo *pep = ctrlReqOpen(addr, Request, dataptr); if(!pep) { HOST_DEBUG("ctrlReq1: ERROR_NULL_EPINFO addr: %d\r\n", addr); 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 c5458208d2da..bb2a87cf0382 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 @@ -144,175 +144,13 @@ e-mail : support@circuitsathome.com #define UHS_GET_DPI(x) (x) #endif -#ifndef __AVR__ -#ifndef __PGMSPACE_H_ -// This define should prevent reading the system pgmspace.h if included elsewhere -// This is not normally needed. -#define __PGMSPACE_H_ 1 -#endif - -#ifndef PROGMEM -#define PROGMEM -#endif -#ifndef PGM_P -#define PGM_P const char * -#endif -#ifndef PSTR -#define PSTR(str) (str) -#endif -#ifndef F -#define F(str) (str) -#endif -#ifndef _SFR_BYTE -#define _SFR_BYTE(n) (n) -#endif -#ifndef memchr_P -#define memchr_P(str, c, len) memchr((str), (c), (len)) -#endif -#ifndef memcmp_P -#define memcmp_P(a, b, n) memcmp((a), (b), (n)) -#endif -#ifndef memcpy_P -#define memcpy_P(dest, src, num) memcpy((dest), (src), (num)) -#endif -#ifndef memmem_P -#define memmem_P(a, alen, b, blen) memmem((a), (alen), (b), (blen)) -#endif -#ifndef memrchr_P -#define memrchr_P(str, val, len) memrchr((str), (val), (len)) -#endif -#ifndef strcat_P -#define strcat_P(dest, src) strcat((dest), (src)) -#endif -#ifndef strchr_P -#define strchr_P(str, c) strchr((str), (c)) -#endif -#ifndef strchrnul_P -#define strchrnul_P(str, c) strchrnul((str), (c)) -#endif -#ifndef strcmp_P -#define strcmp_P(a, b) strcmp((a), (b)) -#endif -#ifndef strcpy_P -#define strcpy_P(dest, src) strcpy((dest), (src)) -#endif -#ifndef strcasecmp_P -#define strcasecmp_P(a, b) strcasecmp((a), (b)) -#endif -#ifndef strcasestr_P -#define strcasestr_P(a, b) strcasestr((a), (b)) -#endif -#ifndef strlcat_P -#define strlcat_P(dest, src, len) strlcat((dest), (src), (len)) -#endif -#ifndef strlcpy_P -#define strlcpy_P(dest, src, len) strlcpy((dest), (src), (len)) -#endif -#ifndef strlen_P -#define strlen_P(s) strlen((const char *)(s)) -#endif -#ifndef strnlen_P -#define strnlen_P(str, len) strnlen((str), (len)) -#endif -#ifndef strncmp_P -#define strncmp_P(a, b, n) strncmp((a), (b), (n)) -#endif -#ifndef strncasecmp_P -#define strncasecmp_P(a, b, n) strncasecmp((a), (b), (n)) -#endif -#ifndef strncat_P -#define strncat_P(a, b, n) strncat((a), (b), (n)) -#endif -#ifndef strncpy_P -#define strncpy_P(a, b, n) strncmp((a), (b), (n)) -#endif -#ifndef strpbrk_P -#define strpbrk_P(str, chrs) strpbrk((str), (chrs)) -#endif -#ifndef strrchr_P -#define strrchr_P(str, c) strrchr((str), (c)) -#endif -#ifndef strsep_P -#define strsep_P(strp, delim) strsep((strp), (delim)) -#endif -#ifndef strspn_P -#define strspn_P(str, chrs) strspn((str), (chrs)) -#endif -#ifndef strstr_P -#define strstr_P(a, b) strstr((a), (b)) -#endif -#ifndef sprintf_P -#define sprintf_P(s, ...) sprintf((s), __VA_ARGS__) -#endif -#ifndef vfprintf_P -#define vfprintf_P(s, ...) vfprintf((s), __VA_ARGS__) -#endif -#ifndef printf_P -#define printf_P(...) printf(__VA_ARGS__) -#endif -#ifndef snprintf_P -#define snprintf_P(s, n, ...) ((s), (n), __VA_ARGS__) -#endif -#ifndef vsprintf_P -#define vsprintf_P(s, ...) ((s),__VA_ARGS__) -#endif -#ifndef vsnprintf_P -#define vsnprintf_P(s, n, ...) ((s), (n),__VA_ARGS__) -#endif -#ifndef fprintf_P -#define fprintf_P(s, ...) ((s), __VA_ARGS__) -#endif - -#ifndef pgm_read_byte -#define pgm_read_byte(addr) (*(const unsigned char *)(addr)) -#endif -#ifndef pgm_read_word -#define pgm_read_word(addr) (*(const unsigned short *)(addr)) -#endif -#ifndef pgm_read_dword -#define pgm_read_dword(addr) (*(const unsigned long *)(addr)) -#endif -#ifndef pgm_read_float -#define pgm_read_float(addr) (*(const float *)(addr)) -#endif - -#ifndef pgm_read_byte_near -#define pgm_read_byte_near(addr) pgm_read_byte(addr) -#endif -#ifndef pgm_read_word_near -#define pgm_read_word_near(addr) pgm_read_word(addr) -#endif -#ifndef pgm_read_dword_near -#define pgm_read_dword_near(addr) pgm_read_dword(addr) -#endif -#ifndef pgm_read_float_near -#define pgm_read_float_near(addr) pgm_read_float(addr) -#endif -#ifndef pgm_read_byte_far -#define pgm_read_byte_far(addr) pgm_read_byte(addr) -#endif -#ifndef pgm_read_word_far -#define pgm_read_word_far(addr) pgm_read_word(addr) -#endif -#ifndef pgm_read_dword_far -#define pgm_read_dword_far(addr) pgm_read_dword(addr) -#endif -#ifndef pgm_read_float_far -#define pgm_read_float_far(addr) pgm_read_float(addr) -#endif - -#ifndef pgm_read_pointer -#define pgm_read_pointer -#endif - -#endif - +#include "../../../../HAL/shared/progmem.h" //////////////////////////////////////////////////////////////////////////////// // HANDY MACROS //////////////////////////////////////////////////////////////////////////////// -// Atmoically set/clear single bits using bitbands. +// Atomically set/clear single bits using bitbands. // Believe it or not, this boils down to a constant, // and is less code than using |= &= operators. // Bonus, it makes code easier to read too. 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 bfa052b8f7e3..edf673a4fbe7 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 @@ -33,13 +33,13 @@ void E_Notifyc(char c, int lvl); template void PrintHex(T val, int lvl) { - int num_nibbles = sizeof (T) * 2; + int num_nybbles = sizeof (T) * 2; do { - char v = 48 + (((val >> (num_nibbles - 1) * 4)) & 0x0F); + char v = 48 + (((val >> (num_nybbles - 1) * 4)) & 0x0F); if(v > 57) v += 7; E_Notifyc(v, lvl); - } while(--num_nibbles); + } while(--num_nybbles); } template @@ -53,13 +53,13 @@ void PrintBin(T val, int lvl) { template void SerialPrintHex(T val) { - int num_nibbles = sizeof (T) * 2; + int num_nybbles = sizeof (T) * 2; do { - char v = 48 + (((val >> (num_nibbles - 1) * 4)) & 0x0F); + char v = 48 + (((val >> (num_nybbles - 1) * 4)) & 0x0F); if(v > 57) v += 7; USB_HOST_SERIAL.print(v); - } while(--num_nibbles); + } while(--num_nybbles); } template diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_usbhost.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_usbhost.h index b289a896efea..b81dbf2a28f0 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_usbhost.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_usbhost.h @@ -103,7 +103,7 @@ class UHS_USB_HOST_BASE { return (current_state == usb_task_state); }; - virtual UHS_EpInfo * UHS_NI ctrlReqOpen(NOTUSED(uint8_t addr), NOTUSED(uint64_t Request), NOTUSED(uint8_t* dataptr)) { + virtual UHS_EpInfo * UHS_NI ctrlReqOpen(NOTUSED(uint8_t addr), NOTUSED(uint64_t Request), NOTUSED(uint8_t *dataptr)) { return NULL; }; @@ -213,17 +213,17 @@ class UHS_USB_HOST_BASE { uint8_t UHS_NI EPClearHalt(uint8_t addr, uint8_t ep); - uint8_t UHS_NI ctrlReq(uint8_t addr, uint64_t Request, uint16_t nbytes, uint8_t* dataptr); + uint8_t UHS_NI ctrlReq(uint8_t addr, uint64_t Request, uint16_t nbytes, uint8_t *dataptr); - uint8_t UHS_NI getDevDescr(uint8_t addr, uint16_t nbytes, uint8_t* dataptr); + uint8_t UHS_NI getDevDescr(uint8_t addr, uint16_t nbytes, uint8_t *dataptr); - uint8_t UHS_NI getConfDescr(uint8_t addr, uint16_t nbytes, uint8_t conf, uint8_t* dataptr); + uint8_t UHS_NI getConfDescr(uint8_t addr, uint16_t nbytes, uint8_t conf, uint8_t *dataptr); uint8_t UHS_NI setAddr(uint8_t oldaddr, uint8_t newaddr); uint8_t UHS_NI setConf(uint8_t addr, uint8_t conf_value); - uint8_t UHS_NI getStrDescr(uint8_t addr, uint16_t nbytes, uint8_t index, uint16_t langid, uint8_t* dataptr); + uint8_t UHS_NI getStrDescr(uint8_t addr, uint16_t nbytes, uint8_t index, uint16_t langid, uint8_t *dataptr); void UHS_NI ReleaseDevice(uint8_t addr); @@ -262,8 +262,8 @@ class UHS_USB_HOST_BASE { uint8_t enumerateInterface(ENUMERATION_INFO *ei); uint8_t getNextInterface(ENUMERATION_INFO *ei, UHS_EpInfo *pep, uint8_t data[], uint16_t *left, uint16_t *read, uint8_t *offset); uint8_t initDescrStream(ENUMERATION_INFO *ei, USB_FD_CONFIGURATION_DESCRIPTOR *ucd, UHS_EpInfo *pep, uint8_t *data, uint16_t *left, uint16_t *read, uint8_t *offset); - uint8_t outTransfer(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t* data); - uint8_t inTransfer(uint8_t addr, uint8_t ep, uint16_t *nbytesptr, uint8_t* data); + uint8_t outTransfer(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t *data); + uint8_t inTransfer(uint8_t addr, uint8_t ep, uint16_t *nbytesptr, uint8_t *data); uint8_t doSoftReset(uint8_t parent, uint8_t port, uint8_t address); uint8_t getone(UHS_EpInfo *pep, uint16_t *left, uint16_t *read, uint8_t *dataptr, uint8_t *offset); uint8_t eat(UHS_EpInfo *pep, uint16_t *left, uint16_t *read, uint8_t *dataptr, uint8_t *offset, uint16_t *yum); 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 56d6400979f9..7d17d626c1ba 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 @@ -388,7 +388,7 @@ public UHS_USB_HOST_BASE return (!condet); }; - virtual UHS_EpInfo *ctrlReqOpen(uint8_t addr, uint64_t Request, uint8_t* dataptr); + virtual UHS_EpInfo *ctrlReqOpen(uint8_t addr, uint64_t Request, uint8_t *dataptr); virtual void UHS_NI vbusPower(VBUS_t state) { regWr(rPINCTL, (bmFDUPSPI | bmIRQ_SENSE) | (uint8_t)(state)); @@ -483,8 +483,8 @@ public UHS_USB_HOST_BASE void gpioWr(uint8_t data); uint8_t regRd(uint8_t reg); uint8_t gpioRd(); - uint8_t* bytesWr(uint8_t reg, uint8_t nbytes, uint8_t* data_p); - uint8_t* bytesRd(uint8_t reg, uint8_t nbytes, uint8_t* data_p); + uint8_t* bytesWr(uint8_t reg, uint8_t nbytes, uint8_t *data_p); + uint8_t* bytesRd(uint8_t reg, uint8_t nbytes, uint8_t *data_p); // ARM/NVIC specific, used to emulate reentrant ISR. #ifdef SWI_IRQ_NUM 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 f7dd315a0490..6cfc0152d058 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 @@ -76,7 +76,7 @@ void UHS_NI MAX3421E_HOST::regWr(uint8_t reg, uint8_t data) { /* multiple-byte write */ /* returns a pointer to memory position after last written */ -uint8_t* UHS_NI MAX3421E_HOST::bytesWr(uint8_t reg, uint8_t nbytes, uint8_t* data_p) { +uint8_t* UHS_NI MAX3421E_HOST::bytesWr(uint8_t reg, uint8_t nbytes, uint8_t *data_p) { SPIclass.beginTransaction(MAX3421E_SPI_Settings); MARLIN_UHS_WRITE_SS(LOW); SPIclass.transfer(reg | 0x02); @@ -96,7 +96,7 @@ uint8_t* UHS_NI MAX3421E_HOST::bytesWr(uint8_t reg, uint8_t nbytes, uint8_t* dat /* GPIO write */ /*GPIO byte is split between 2 registers, so two writes are needed to write one byte */ -/* GPOUT bits are in the low nibble. 0-3 in IOPINS1, 4-7 in IOPINS2 */ +/* GPOUT bits are in the low nybble. 0-3 in IOPINS1, 4-7 in IOPINS2 */ void UHS_NI MAX3421E_HOST::gpioWr(uint8_t data) { regWr(rIOPINS1, data); data >>= 4; @@ -117,7 +117,7 @@ uint8_t UHS_NI MAX3421E_HOST::regRd(uint8_t reg) { /* multiple-byte register read */ /* returns a pointer to a memory position after last read */ -uint8_t* UHS_NI MAX3421E_HOST::bytesRd(uint8_t reg, uint8_t nbytes, uint8_t* data_p) { +uint8_t* UHS_NI MAX3421E_HOST::bytesRd(uint8_t reg, uint8_t nbytes, uint8_t *data_p) { SPIclass.beginTransaction(MAX3421E_SPI_Settings); MARLIN_UHS_WRITE_SS(LOW); SPIclass.transfer(reg); @@ -132,11 +132,11 @@ uint8_t* UHS_NI MAX3421E_HOST::bytesRd(uint8_t reg, uint8_t nbytes, uint8_t* dat /* GPIO read. See gpioWr for explanation */ -/* GPIN pins are in high nibbles of IOPINS1, IOPINS2 */ +/* GPIN pins are in high nybbles of IOPINS1, IOPINS2 */ uint8_t UHS_NI MAX3421E_HOST::gpioRd() { uint8_t gpin = 0; gpin = regRd(rIOPINS2); //pins 4-7 - gpin &= 0xF0; //clean lower nibble + gpin &= 0xF0; //clean lower nybble gpin |= (regRd(rIOPINS1) >> 4); //shift low bits and OR with upper from previous operation. return ( gpin); } @@ -472,7 +472,7 @@ uint8_t UHS_NI MAX3421E_HOST::SetAddress(uint8_t addr, uint8_t ep, UHS_EpInfo ** * @param data pointer to data buffer * @return 0 on success */ -uint8_t UHS_NI MAX3421E_HOST::InTransfer(UHS_EpInfo *pep, uint16_t nak_limit, uint16_t *nbytesptr, uint8_t* data) { +uint8_t UHS_NI MAX3421E_HOST::InTransfer(UHS_EpInfo *pep, uint16_t nak_limit, uint16_t *nbytesptr, uint8_t *data) { uint8_t rcode = 0; uint8_t pktsize; 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 0ac90f0df3a6..eeaa4f81d9fe 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 @@ -140,7 +140,7 @@ AJK_IIF(AJK_BITAND(AJK_IS_COMPARABLE(x))(AJK_IS_COMPARABLE(y)) ) \ #define AJK_MAKE_FUNS(AJK_v, AJK_args, AJK_count, AJK_body) AJK_EVAL(AJK_REPEAT(AJK_count, AJK_FUN, AJK_v, AJK_args, AJK_body)) #ifdef AJK_TEST_MACRO_LOGIC -#define BODY(AJKindex) some(C, statement); contaning(a, test[AJKindex]); +#define BODY(AJKindex) some(C, statement); containing(a, test[AJKindex]); #define ZERO_TIMES_TEST 0 #define THREE_TIMES_TEST 3 blank > AJK_MAKE_LIST(VARIABLE_, ZERO_TIMES_TEST) < because zero repeats diff --git a/README.md b/README.md index 1e78528b7a88..72b354d4feb6 100644 --- a/README.md +++ b/README.md @@ -16,6 +16,10 @@ Marlin 2.0 takes this popular RepRap firmware to the next level by adding suppor Download earlier versions of Marlin on the [Releases page](https://github.com/MarlinFirmware/Marlin/releases). +## Example Configurations + +Before building Marlin you'll need to configure it for your specific hardware. Your vendor should have already provided source code with configurations for the installed firmware, but if you ever decide to upgrade you'll need updated configuration files. Marlin users have contributed dozens of tested example configurations to get you started. Visit the [MarlinFirmware/Configurations](https://github.com/MarlinFirmware/Configurations) repository to find the right configuration for your hardware. + ## Building Marlin 2.0 To build Marlin 2.0 you'll need [Arduino IDE 1.8.8 or newer](https://www.arduino.cc/en/main/software) or [PlatformIO](http://docs.platformio.org/en/latest/ide.html#platformio-ide). Detailed build and install instructions are posted at: @@ -30,6 +34,7 @@ To build Marlin 2.0 you'll need [Arduino IDE 1.8.8 or newer](https://www.arduino [Arduino AVR](https://www.arduino.cc/)|ATmega|RAMPS, Melzi, RAMBo [Teensy++ 2.0](http://www.microchip.com/wwwproducts/en/AT90USB1286)|AT90USB1286|Printrboard [Arduino Due](https://www.arduino.cc/en/Guide/ArduinoDue)|SAM3X8E|RAMPS-FD, RADDS, RAMPS4DUE + [ESP32](https://github.com/espressif/arduino-esp32)|ESP32|FYSETC E4, E4d@BOX, MRR [LPC1768](http://www.nxp.com/products/microcontrollers-and-processors/arm-based-processors-and-mcus/lpc-cortex-m-mcus/lpc1700-cortex-m3/512kb-flash-64kb-sram-ethernet-usb-lqfp100-package:LPC1768FBD100)|ARM® Cortex-M3|MKS SBASE, Re-ARM, Selena Compact [LPC1769](https://www.nxp.com/products/processors-and-microcontrollers/arm-microcontrollers/general-purpose-mcus/lpc1700-cortex-m3/512kb-flash-64kb-sram-ethernet-usb-lqfp100-package:LPC1769FBD100)|ARM® Cortex-M3|Smoothieboard, Azteeg X5 mini, TH3D EZBoard [STM32F103](https://www.st.com/en/microcontrollers-microprocessors/stm32f103.html)|ARM® Cortex-M3|Malyan M200, GTM32 Pro, MKS Robin, BTT SKR Mini @@ -40,6 +45,7 @@ To build Marlin 2.0 you'll need [Arduino IDE 1.8.8 or newer](https://www.arduino [Teensy 3.6](https://www.pjrc.com/store/teensy36.html)|ARM® Cortex-M4| [Teensy 4.0](https://www.pjrc.com/store/teensy40.html)|ARM® Cortex-M7| [Teensy 4.1](https://www.pjrc.com/store/teensy41.html)|ARM® Cortex-M7| + Linux Native|x86/ARM/etc.|Raspberry Pi ## Submitting Changes @@ -49,23 +55,30 @@ To build Marlin 2.0 you'll need [Arduino IDE 1.8.8 or newer](https://www.arduino ## Marlin Support -For best results getting help with configuration and troubleshooting, please use the following resources: +The Issue Queue is reserved for Bug Reports and Feature Requests. To get help with configuration and troubleshooting, please use the following resources: - [Marlin Documentation](http://marlinfw.org) - Official Marlin documentation - [Marlin Discord](https://discord.gg/n5NJ59y) - Discuss issues with Marlin users and developers - Facebook Group ["Marlin Firmware"](https://www.facebook.com/groups/1049718498464482/) - RepRap.org [Marlin Forum](http://forums.reprap.org/list.php?415) -- [Tom's 3D Forums](https://forum.toms3d.org/) - Facebook Group ["Marlin Firmware for 3D Printers"](https://www.facebook.com/groups/3Dtechtalk/) - [Marlin Configuration](https://www.youtube.com/results?search_query=marlin+configuration) on YouTube -## Credits +## Contributors + +Marlin is constantly improving thanks to a huge number of contributors from all over the world bringing their specialties and talents. Huge thanks are due to [all the contributors](https://github.com/MarlinFirmware/Marlin/graphs/contributors) who regularly patch up bugs, help direct traffic, and basically keep Marlin from falling apart. Marlin's continued existence would not be possible without them. + +## Administration -The current Marlin dev team consists of: +Regular users can open and close their own issues, but only the administrators can do project-related things like add labels, merge changes, set milestones, and kick trolls. The current Marlin admin team consists of: - - Scott Lahteine [[@thinkyhead](https://github.com/thinkyhead)] - USA   [Donate](http://www.thinkyhead.com/donate-to-marlin) + - Scott Lahteine [[@thinkyhead](https://github.com/thinkyhead)] - USA - Project Maintainer   [![Donate](https://api.flattr.com/button/flattr-badge-large.png)](http://www.thinkyhead.com/donate-to-marlin) - Roxanne Neufeld [[@Roxy-3D](https://github.com/Roxy-3D)] - USA + - Keith Bennett [[@thisiskeithb](https://github.com/thisiskeithb)] - USA + - Victor Oliveira [[@rhapsodyv](https://github.com/rhapsodyv)] - Brazil - Chris Pepper [[@p3p](https://github.com/p3p)] - UK + - Jason Smith [[@sjasonsmith](https://github.com/sjasonsmith)] - USA + - Luu Lac [[@shitcreek](https://github.com/shitcreek)] - USA - Bob Kuhn [[@Bob-the-Kuhn](https://github.com/Bob-the-Kuhn)] - USA - Erik van der Zalm [[@ErikZalm](https://github.com/ErikZalm)] - Netherlands   [![Flattr Erik](https://api.flattr.com/button/flattr-badge-large.png)](https://flattr.com/submit/auto?user_id=ErikZalm&url=https://github.com/MarlinFirmware/Marlin&title=Marlin&language=&tags=github&category=software) diff --git a/buildroot/bin/build_all_examples b/buildroot/bin/build_all_examples new file mode 100755 index 000000000000..bce95dce8861 --- /dev/null +++ b/buildroot/bin/build_all_examples @@ -0,0 +1,101 @@ +#!/usr/bin/env bash +# +# build_all_examples base_branch [resume_point] +# + +GITREPO=https://github.com/MarlinFirmware/Configurations.git +STAT_FILE=./.pio/.buildall + +# Check dependencies +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) +[[ -z "$SED" ]] && { echo "No sed found, please install sed" ; exit 1 ; } + +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 ; } + +if [[ $# -lt 1 || $# -gt 2 ]]; then + echo "Usage: $SELF base_branch [resume_point] + base_branch - Configuration branch to download and build + resume_point - Configuration path to start from" + exit +fi + +echo "This script downloads all Configurations and builds Marlin with each one." +echo "On failure the last-built configs will be left in your working copy." +echo "Restore your configs with 'git checkout -f' or 'git reset --hard HEAD'." + +unset BRANCH +unset FIRST_CONF +if [[ -f "$STAT_FILE" ]]; then + IFS='*' read BRANCH FIRST_CONF <"$STAT_FILE" +fi + +# If -c is given start from the last attempted build +if [[ $1 == '-c' ]]; then + if [[ -z $BRANCH || -z $FIRST_CONF ]]; then + echo "Nothing to continue" + exit + fi +elif [[ $1 == '-s' ]]; then + if [[ -n $BRANCH && -n $FIRST_CONF ]]; then + SKIP_CONF=1 + else + echo "Nothing to skip" + exit + fi +else + BRANCH=${1:-"import-2.0.x"} + FIRST_CONF=$2 +fi + +# Check if the current repository has unmerged changes +if [[ $SKIP_CONF ]]; then + echo "Skipping $FIRST_CONF" +elif [[ $FIRST_CONF ]]; then + echo "Resuming from $FIRST_CONF" +else + git diff --quiet || { echo "The working copy is modified. Commit or stash changes before proceeding."; exit ; } +fi + +# Create a temporary folder inside .pio +TMP=./.pio/build-$BRANCH +[[ -d "$TMP" ]] || mkdir -p $TMP + +# Download Configurations into the temporary folder +if [[ ! -e "$TMP/README.md" ]]; then + echo "Downloading Configurations from GitHub into $TMP" + git clone --depth=1 --single-branch --branch "$BRANCH" $GITREPO "$TMP" || { echo "Failed to clone the configuration repository"; exit ; } +else + echo "Using previously downloaded Configurations at $TMP" +fi + +echo -e "Start building now...\n=====================" +shopt -s nullglob +IFS=' +' +CONF_TREE=$( ls -d "$TMP"/config/examples/*/ "$TMP"/config/examples/*/*/ "$TMP"/config/examples/*/*/*/ "$TMP"/config/examples/*/*/*/*/ | grep -vE ".+\.(\w+)$" ) +DOSKIP=0 +for CONF in $CONF_TREE ; do + # Get a config's directory name + DIR=$( echo $CONF | sed "s|$TMP/config/examples/||" ) + # If looking for a config, skip others + [[ $FIRST_CONF ]] && [[ $FIRST_CONF != $DIR && "$FIRST_CONF/" != $DIR ]] && continue + # Once found, stop looking + unset FIRST_CONF + # If skipping, don't build the found one + [[ $SKIP_CONF ]] && { unset SKIP_CONF ; continue ; } + # ...if skipping, don't build this one + compgen -G "${CONF}Con*.h" > /dev/null || continue + echo "${BRANCH}*${DIR}" >"$STAT_FILE" + "$HERE/build_example" "internal" "$TMP" "$DIR" || { echo "Failed to build $DIR"; exit ; } +done + +# Delete the temp folder and build state +[[ -e "$TMP/config/examples" ]] && rm -rf "$TMP" +rm "$STAT_FILE" diff --git a/buildroot/bin/build_example b/buildroot/bin/build_example new file mode 100755 index 000000000000..8ebb58f972e1 --- /dev/null +++ b/buildroot/bin/build_example @@ -0,0 +1,29 @@ +#!/usr/bin/env bash +# +# build_example +# +# Usage: build_example internal config-home config-folder +# + +# Require 'internal' as the first argument +[[ "$1" == "internal" ]] || { echo "Don't call this script directly, use build_all_examples instead." ; exit 1 ; } + +echo "Testing $3:" + +SUB=$2/config/examples/$3 +[[ -d "$SUB" ]] || { echo "$SUB is not a good path" ; exit 1 ; } + +compgen -G "${SUB}Con*.h" > /dev/null || { echo "No configuration files found in $SUB" ; exit 1 ; } + +echo "Getting configuration files from $SUB" +cp "$2/config/default"/*.h Marlin/ +cp "$SUB"/Configuration.h Marlin/ 2>/dev/null +cp "$SUB"/Configuration_adv.h Marlin/ 2>/dev/null +cp "$SUB"/_Bootscreen.h Marlin/ 2>/dev/null +cp "$SUB"/_Statusscreen.h Marlin/ 2>/dev/null + +echo "Building the firmware now..." +HERE=`dirname "$0"` +$HERE/mftest -a -n1 || { echo "Failed"; exit 1; } + +echo "Success" diff --git a/buildroot/bin/generate_version b/buildroot/bin/generate_version index b88e3de918b7..70a108b1fedb 100755 --- a/buildroot/bin/generate_version +++ b/buildroot/bin/generate_version @@ -4,47 +4,35 @@ # # Make a Version.h file to accompany CUSTOM_VERSION_FILE # +# Authors: jbrazio, thinkyhead, InsanityAutomation, rfinnie +# -DIR=${1:-"Marlin"} - -# MRCC3=$( git merge-base HEAD upstream/bugfix-2.0.x 2>/dev/null ) -# MRCC2=$( git merge-base HEAD upstream/bugfix-1.1.x 2>/dev/null ) -# MRCC1=$( git merge-base HEAD upstream/1.1.x 2>/dev/null ) - -# BASE='?' -# if [[ -n $MRCC3 && $MRCC3 != $MRCC2 ]]; then -# BASE=bugfix-2.0.x -# elif [[ -n $MRCC2 ]]; then -# BASE=bugfix-1.1.x -# elif [[ -n $MRCC1 ]]; then -# BASE=1.1.x -# fi - -BUILDATE=$(date '+%s') -DISTDATE=$(date '+%Y-%m-%d %H:%M') +set -e -BRANCH=$(git -C "${DIR}" symbolic-ref -q --short HEAD) -VERSION=$(git -C "${DIR}" describe --tags --first-parent 2>/dev/null) +DIR="${1:-Marlin}" +READ_FILE="${READ_FILE:-${DIR}/Version.h}" +WRITE_FILE="${WRITE_FILE:-${READ_FILE}}" -[ -z "${BRANCH}" ] && BRANCH=$(echo "${TRAVIS_BRANCH}") -[ -z "${VERSION}" ] && VERSION=$(git -C "${DIR}" describe --tags --first-parent --always 2>/dev/null) +BRANCH="$(git -C "${DIR}" symbolic-ref -q --short HEAD 2>/dev/null || true)" +VERSION="$(git -C "${DIR}" describe --tags --first-parent 2>/dev/null || true)" -SHORT_BUILD_VERSION=$(echo "${BRANCH}") -DETAILED_BUILD_VERSION=$(echo "${BRANCH}-${VERSION}") +STRING_DISTRIBUTION_DATE="${STRING_DISTRIBUTION_DATE:-$(date '+%Y-%m-%d %H:%M')}" +SHORT_BUILD_VERSION="${SHORT_BUILD_VERSION:-${BRANCH}}" +DETAILED_BUILD_VERSION="${DETAILED_BUILD_VERSION:-${BRANCH}-${VERSION}}" # Gets some misc options from their defaults -DEFAULT_MACHINE_UUID=$(awk -F'"' \ - '/#define DEFAULT_MACHINE_UUID/{ print $2 }' < "${DIR}/Version.h") -MACHINE_NAME=$(awk -F'"' \ - '/#define MACHINE_NAME/{ print $2 }' < "${DIR}/Version.h") -PROTOCOL_VERSION=$(awk -F'"' \ - '/#define PROTOCOL_VERSION/{ print $2 }' < "${DIR}/Version.h") -SOURCE_CODE_URL=$(awk -F'"' \ - '/#define SOURCE_CODE_URL/{ print $2 }' < "${DIR}/Version.h") -WEBSITE_URL=$(awk -F'"' \ - '/#define WEBSITE_URL/{ print $2 }' < "${DIR}/Version.h") - -cat > "${DIR}/Version.h" < "${WRITE_FILE}" < "${DIR}/Version.h" <] [-n|--num=] [-m|--make] [-y|--build=] + mftest [-a|--autobuild] + mftest [-r|--rebuild] + mftest [-u|--autoupload] [-n|--num=] + +OPTIONS + -t --env The environment to apply / run, or the menu index number. + -n --num The index of the test to run. (In file order.) + -m --make Use the make / Docker method for the build. + -y --build Skip 'Do you want to build this test?' and assume YES. + -h --help Print this help. + -a --autobuild PIO Build using the MOTHERBOARD environment. + -u --autoupload PIO Upload using the MOTHERBOARD environment. + -v --verbose Extra output for debugging. + -s --silent Silence build output from PlatformIO. + +env shortcuts: tree due esp lin lpc|lpc8 lpc9 m128 m256|mega stm|f1 f4 f7 s6 teensy|t31|t32 t35|t36 t40|t41 +" +} + +TESTPATH=buildroot/tests + +STATE_FILE="./.pio/.mftestrc" +SED=$(which gsed sed | head -n1) + +shopt -s extglob nocasematch + +# Matching patterns +ISNUM='^[0-9]+$' +ISCMD='^(restore|opt|exec|use|pins|env)_' +ISEXEC='^exec_' +ISCONT='\\ *$' + +# Get environment, test number, etc. from the command +TESTENV='-' +CHOICE=0 +DEBUG=0 + +while getopts 'abhmruvyn:t:-:' OFLAG; do + case "${OFLAG}" in + a) AUTO_BUILD=1 ; bugout "Auto-Build target..." ;; + h) EXIT_USAGE=1 ;; + m) USE_MAKE=1 ; bugout "Using make with Docker..." ;; + n) case "$OPTARG" in + *[!0-9]*) perror "option requires a number" $OFLAG ; EXIT_USAGE=2 ;; + *) CHOICE="$OPTARG" ; bugout "Got a number: $CHOICE" ;; + esac + ;; + r) REBUILD=1 ; bugout "Rebuilding previous..." ;; + s) SILENT_FLAG="-s" ;; + t) TESTENV="$OPTARG" ; bugout "Got a target: $TESTENV" ;; + u) AUTO_BUILD=2 ; bugout "Auto-Upload target..." ;; + v) DEBUG=1 ; bugout "Debug ON" ;; + y) BUILD_YES='Y' ; bugout "Build will initiate..." ;; + -) IFS="=" read -r ONAM OVAL <<< "$OPTARG" + case "$ONAM" in + help) [[ -z "$OVAL" ]] || perror "option can't take value $OVAL" $ONAM ; EXIT_USAGE=1 ;; + autobuild) AUTO_BUILD=1 ; bugout "Auto-Build target..." ;; + autoupload) AUTO_BUILD=2 ; bugout "Auto-Upload target..." ;; + env) case "$OVAL" in + '') perror "option requires a value" $ONAM ; EXIT_USAGE=2 ;; + *) TESTENV="$OVAL" ; bugout "Got a target: $TESTENV" ;; + esac + ;; + num) case "$OVAL" in + [0-9]+) CHOICE="$OVAL" ; bugout "Got a number: $CHOICE" ;; + *) perror "option requires a value" $ONAM ; EXIT_USAGE=2 ;; + esac + ;; + rebuild) REBUILD=1 ; bugout "Rebuilding previous..." ;; + make) USE_MAKE=1 ; bugout "Using make with Docker..." ;; +debug|verbose) DEBUG=1 ; bugout "Debug ON" ;; + build) case "$OVAL" in + ''|y|yes) BUILD_YES='Y' ;; + n|no) BUILD_YES='N' ;; + *) perror "option value must be y, n, yes, or no" $ONAM ; EXIT_USAGE=2 ;; + esac + bugout "Build will initiate? ($BUILD_YES)" + ;; + *) perror "Unknown flag" "$OPTARG" ; EXIT_USAGE=2 ;; + esac + ;; + *) EXIT_USAGE=2 ;; + esac +done + +((EXIT_USAGE)) && { usage ; let EXIT_USAGE-- ; exit $EXIT_USAGE ; } + +if ((REBUILD)); then + bugout "Rebuilding previous..." + # Build with the last-built env + [[ -f "$STATE_FILE" ]] || { errout "No previous (-r) build state found." ; exit 1 ; } + read TESTENV <"$STATE_FILE" + pio run $SILENT_FLAG -d . -e $TESTENV + exit 0 +fi + +case $TESTENV in + tree) pio run -d . -e include_tree ; exit 1 ;; + due) TESTENV='DUE' ;; + esp) TESTENV='esp32' ;; + lin*) TESTENV='linux_native' ;; +lp8|lpc8) TESTENV='LPC1768' ;; +lp9|lpc9) TESTENV='LPC1769' ;; + m128) TESTENV='mega1280' ;; + m256) TESTENV='mega2560' ;; + mega) TESTENV='mega2560' ;; + stm) TESTENV='STM32F103RE' ;; + f1) TESTENV='STM32F103RE' ;; + f4) TESTENV='STM32F4' ;; + f7) TESTENV='STM32F7' ;; + s6) TESTENV='FYSETC_S6' ;; + teensy) TESTENV='teensy31' ;; + t31) TESTENV='teensy31' ;; + t32) TESTENV='teensy31' ;; + t35) TESTENV='teensy35' ;; + t36) TESTENV='teensy35' ;; + t40) TESTENV='teensy41' ;; + t41) TESTENV='teensy41' ;; +[1-9][1-9]|[1-9]) TESTNUM=$TESTENV ; TESTENV=- ;; +esac + +if ((AUTO_BUILD)); then + # + # List environments that apply to the current MOTHERBOARD. + # + case $(uname | tr '[:upper:]' '[:lower:]') in + darwin) SYS='mac' ;; + *linux) SYS='lin' ;; + win*) SYS='win' ;; + msys*) SYS='win' ;; + cygwin*) SYS='win' ;; + mingw*) SYS='win' ;; + *) SYS='uni' ;; + esac + echo ; echo -n "Auto " ; ((AUTO_BUILD == 2)) && echo "Upload..." || echo "Build..." + MB=$( grep -E "^\s*#define MOTHERBOARD" Marlin/Configuration.h | awk '{ print $3 }' | $SED 's/BOARD_//' ) + [[ -z $MB ]] && { echo "Error - Can't read MOTHERBOARD setting." ; exit 1 ; } + BLINE=$( grep -E "define\s+BOARD_$MB\b" Marlin/src/core/boards.h ) + BNUM=$( $SED -E 's/^.+BOARD_[^ ]+ +([0-9]+).+$/\1/' <<<"$BLINE" ) + BDESC=$( $SED -E 's/^.+\/\/ *(.+)$/\1/' <<<"$BLINE" ) + [[ -z $BNUM ]] && { echo "Error - Can't find $MB in boards list." ; exit 1 ; } + ENVS=( $( grep -EA1 "MB\(.*\b$MB\b.*\)" Marlin/src/pins/pins.h | grep -E "#include.+//.+(env|$SYS):[^ ]+" | grep -oE "(env|$SYS):[^ ]+" | $SED -E "s/(env|$SYS)://" ) ) + [[ -z $ENVS ]] && { errout "Error - Can't find target(s) for $MB ($BNUM)." ; exit 1 ; } + ECOUNT=${#ENVS[*]} + + if [[ $ECOUNT == 1 ]]; then + TARGET=$ENVS + else + if [[ $CHOICE == 0 ]]; then + # List env names and numbers. Get selection. + echo "Available targets for \"$BDESC\" | $MB ($BNUM):" + + IND=0 ; for ENV in "${ENVS[@]}"; do let IND++ ; echo " $IND) $ENV" ; done + + if [[ $ECOUNT > 1 ]]; then + for (( ; ; )) + do + read -p "Select a target for '$MB' (1-$ECOUNT) : " CHOICE + [[ -z "$CHOICE" ]] && { echo '(canceled)' ; exit 1 ; } + [[ $CHOICE =~ $ISNUM ]] && ((CHOICE >= 1 && CHOICE <= ECOUNT)) && break + errout ">>> Invalid environment choice '$CHOICE'." + done + echo + fi + else + echo "Detected \"$BDESC\" | $MB ($BNUM)." + [[ $CHOICE > $ECOUNT ]] && { echo "Environment selection out of range." ; exit 1 ; } + fi + TARGET="${ENVS[$CHOICE-1]}" + echo "Selected $TARGET" + fi + + echo "$TARGET" >"$STATE_FILE" + + if ((AUTO_BUILD == 2)); then + echo "Uploading environment $TARGET for board $MB ($BNUM)..." ; echo + pio run $SILENT_FLAG -t upload -e $TARGET + else + echo "Building environment $TARGET for board $MB ($BNUM)..." ; echo + pio run $SILENT_FLAG -e $TARGET + fi + exit 0 +fi + +# +# List available tests and ask for selection +# + +if [[ $TESTENV == '-' ]]; then + IND=0 + NAMES=() + for FILE in $( ls -1 $TESTPATH/* ) + do + let IND++ + TNAME=${FILE/$TESTPATH\//} + NAMES+=($TNAME) + (( IND < 10 )) && echo -n " " + echo " $IND) $TNAME" + done + + echo + for (( ; ; )) + do + if [[ $TESTNUM -gt 0 ]]; then + NAMEIND=$TESTNUM + else + read -p "Select a test to apply (1-$IND) : " NAMEIND + fi + [[ -z $NAMEIND ]] && { errout "(canceled)" ; exit 1 ; } + TESTENV=${NAMES[$NAMEIND-1]} + [[ $TESTNUM -gt 0 ]] && { echo "Preselected test $TESTNUM ... ($TESTENV)" ; TESTNUM='' ; } + [[ $NAMEIND =~ $ISNUM ]] && ((NAMEIND >= 1 && NAMEIND <= IND)) && { TESTENV=${NAMES[$NAMEIND-1]} ; echo ; break ; } + errout "Invalid selection." + done +fi + +# Get the contents of the test file +OUT=$( cat $TESTPATH/$TESTENV 2>/dev/null ) || { errout "Can't find test '$TESTENV'." ; exit 1 ; } + +# Count up the number of tests +TESTCOUNT=$( awk "/$ISEXEC/{a++}END{print a}" <<<"$OUT" ) + +# User entered a number? +(( CHOICE && CHOICE > TESTCOUNT )) && { errout "Invalid test selection '$CHOICE' (1-$TESTCOUNT)." ; exit 1 ; } + +if [[ $CHOICE == 0 ]]; then + # + # List test descriptions with numbers and get selection + # + echo "Available '$TESTENV' tests:" ; echo "$OUT" | { + IND=0 + while IFS= read -r LINE + do + if [[ $LINE =~ $ISEXEC ]]; then + DESC=$( "$SED" -E 's/^exec_test \$1 \$2 "([^"]+)".*$/\1/g' <<<"$LINE" ) + (( ++IND < 10 )) && echo -n " " + echo " $IND) $DESC" + fi + done + } + CHOICE=1 + if [[ $TESTCOUNT > 1 ]]; then + for (( ; ; )) + do + read -p "Select a '$TESTENV' test (1-$TESTCOUNT) : " CHOICE + [[ -z "$CHOICE" ]] && { errout "(canceled)" ; exit 1 ; } + [[ $CHOICE =~ $ISNUM ]] && ((CHOICE >= 1 && CHOICE <= TESTCOUNT)) && break + errout ">>> Invalid test selection '$CHOICE'." + done + fi +fi + +# +# Run the specified test lines +# +echo -ne "\033[0;33m" +echo "$OUT" | { + IND=0 + GOTX=0 + CMD="" + while IFS= read -r LINE + do + if [[ $LINE =~ $ISCMD || $GOTX == 1 ]]; then + ((!IND)) && let IND++ + if [[ $LINE =~ $ISEXEC ]]; then + ((IND++ > CHOICE)) && break + else + ((!HEADER)) && { + HEADER=1 + echo -e "\n#\n# Test $TESTENV ($CHOICE) $DESC\n#" + } + ((IND == CHOICE)) && { + GOTX=1 + [[ $CMD == "" ]] && CMD="$LINE" || CMD=$( echo -e "$CMD$LINE" | $SED -e 's/\\//g' | $SED -E 's/ +/ /g' ) + [[ $LINE =~ $ISCONT ]] || { echo "$CMD" ; eval "$CMD" ; CMD="" ; } + } + fi + fi + done +} +echo -ne "\033[0m" + +# Make clear it's a TEST +opt_set CUSTOM_MACHINE_NAME "\"Test $TESTENV ($CHOICE)\"" + +# Build the test too? +if [[ -z "$BUILD_YES" ]]; then + echo + read -p "Build $TESTENV test #$CHOICE (y/N) ? " BUILD_YES +fi + +[[ $BUILD_YES == 'Y' || $BUILD_YES == 'Yes' ]] && { + ((USE_MAKE)) && make tests-single-local TEST_TARGET=$TESTENV ONLY_TEST=$CHOICE + ((USE_MAKE)) || pio run $SILENT_FLAG -d . -e $TESTENV + echo "$TESTENV" >"$STATE_FILE" +} diff --git a/buildroot/bin/opt_disable b/buildroot/bin/opt_disable index 11526132ef05..0444e1b773e0 100755 --- a/buildroot/bin/opt_disable +++ b/buildroot/bin/opt_disable @@ -3,11 +3,13 @@ # exit on first failure set -e -SED=$(which gsed || which sed) +SED=$(which gsed sed | head -n1) for opt in "$@" ; do - # Logic for returning nonzero based on answer here: https://stackoverflow.com/a/15966279/104648 - eval "${SED} -i '/\([[:blank:]]*\)\(\/\/\)*\([[:blank:]]*\)\(#define \b${opt}\b\)/{s//\1\3\/\/\4/;h};\${x;/./{x;q0};x;q9}' Marlin/Configuration.h" || - eval "${SED} -i '/\([[:blank:]]*\)\(\/\/\)*\([[:blank:]]*\)\(#define \b${opt}\b\)/{s//\1\3\/\/\4/;h};\${x;/./{x;q0};x;q9}' Marlin/Configuration_adv.h" || - (echo "ERROR: opt_disable Can't find ${opt}" >&2 && exit 9) + DID=0 ; FOUND=0 + for FN in Configuration Configuration_adv; do + "${SED}" -i "/^\(\s*\)\(#define\s\+${opt}\b\s\?\)\(\s\s\)\?/{s//\1\/\/\2/;h};\${x;/./{x;q0};x;q9}" Marlin/$FN.h && DID=1 + ((DID||FOUND)) || { grep -E "^\s*//\s*#define\s+${opt}\b" Marlin/$FN.h >/dev/null && FOUND=1 ; } + done + ((DID||FOUND)) || (echo "ERROR: $(basename $0) Can't find ${opt}" >&2 && exit 9) done diff --git a/buildroot/bin/opt_enable b/buildroot/bin/opt_enable index 96686d6c6845..f9be82cbd1f9 100755 --- a/buildroot/bin/opt_enable +++ b/buildroot/bin/opt_enable @@ -3,11 +3,13 @@ # exit on first failure set -e -SED=$(which gsed || which sed) +SED=$(which gsed sed | head -n1) for opt in "$@" ; do - # Logic for returning nonzero based on answer here: https://stackoverflow.com/a/15966279/104648 - eval "${SED} -i '/\(\/\/\)*[[:blank:]]*\(#define \b${opt}\b\)/{s//\2/;h};\${x;/./{x;q0};x;q9}' Marlin/Configuration.h" || - eval "${SED} -i '/\(\/\/\)*[[:blank:]]*\(#define \b${opt}\b\)/{s//\2/;h};\${x;/./{x;q0};x;q9}' Marlin/Configuration_adv.h" || - (echo "ERROR: opt_enable Can't find ${opt}" >&2 && exit 9) + DID=0 ; FOUND=0 + for FN in Configuration Configuration_adv; do + "${SED}" -i "/^\(\s*\)\/\/\(\s*\)\(#define\s\+${opt}\b\)\( \?\)/{s//\1\2\3\4\4\4/;h};\${x;/./{x;q0};x;q9}" Marlin/$FN.h && DID=1 + ((DID||FOUND)) || { grep -E "^\s*#define\s+${opt}\b" Marlin/$FN.h >/dev/null && FOUND=1 ; } + done + ((DID||FOUND)) || (echo "ERROR: $(basename $0) Can't find ${opt}" >&2 && exit 9) done diff --git a/buildroot/bin/opt_set b/buildroot/bin/opt_set index a646e09ae789..b9935512a4b8 100755 --- a/buildroot/bin/opt_set +++ b/buildroot/bin/opt_set @@ -3,10 +3,15 @@ # exit on first failure set -e -SED=$(which gsed || which sed) +SED=$(which gsed sed | head -n1) -# Logic for returning nonzero based on answer here: https://stackoverflow.com/a/15966279/104648 -eval "${SED} -i '/\(\/\/\)*\([[:blank:]]*\)\(#define\s\+\b${1}\b\).*$/{s//\2\3 ${2}/;h};\${x;/./{x;q0};x;q9}' Marlin/Configuration.h" || -eval "${SED} -i '/\(\/\/\)*\([[:blank:]]*\)\(#define\s\+\b${1}\b\).*$/{s//\2\3 ${2}/;h};\${x;/./{x;q0};x;q9}' Marlin/Configuration_adv.h" || -eval "echo '#define ${@}' >>Marlin/Configuration_adv.h" || -(echo "ERROR: opt_set Can't set or add ${1}" >&2 && exit 9) +while [[ $# > 1 ]]; do + DID=0 + for FN in Configuration Configuration_adv; do + "${SED}" -i "/^\(\s*\)\/*\s*\(#define\s\+${1}\b\) *\(.*\)$/{s//\1\2 ${2} \/\/ \3/;h};\${x;/./{x;q0};x;q9}" Marlin/$FN.h && DID=1 + done + ((DID)) || + eval "echo '#define ${1} ${2}' >>Marlin/Configuration.h" || + (echo "ERROR: opt_set Can't set or add ${1}" >&2 && exit 9) + shift 2 +done diff --git a/buildroot/bin/pins_set b/buildroot/bin/pins_set index 87a8692aa25d..158c5224e6d3 100755 --- a/buildroot/bin/pins_set +++ b/buildroot/bin/pins_set @@ -6,6 +6,6 @@ NAM=${PINPATH[1]} PIN=$2 VAL=$3 -SED=$(which gsed || which sed) -eval "${SED} -i '/\(\/\/\)*\(#define \+${PIN}\b\).*$/{s//\2 ${VAL}/;h};\${x;/./{x;q0};x;q9}' Marlin/src/pins/$DIR/pins_${NAM}.h" || +SED=$(which gsed sed | head -n1) +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) diff --git a/buildroot/bin/run_tests b/buildroot/bin/run_tests new file mode 100755 index 000000000000..26284fa69330 --- /dev/null +++ b/buildroot/bin/run_tests @@ -0,0 +1,77 @@ +#!/usr/bin/env bash +# +# run_tests +# +HERE="$( cd "$(dirname "${BASH_SOURCE[0]}")" ; pwd -P )" +TESTS="$HERE/../tests" +export PATH="$HERE:$TESTS:$PATH" + +# exit on first failure +set -e + +exec_test () { + printf "\n\033[0;32m[Test $2] \033[0m$3...\n" + # Check to see if we should skip tests + if [[ -n "$4" ]] ; then + if [[ ! "$3" =~ $4 ]] ; then + printf "\033[1;33mSkipped\033[0m\n" + return 0 + fi + fi + if [[ -z "$VERBOSE_PLATFORMIO" ]] ; then + silent="--silent" + else + silent="-v" + fi + if platformio run --project-dir $1 -e $2 $silent; then + printf "\033[0;32mPassed\033[0m\n" + return 0 + else + if [[ -n $GIT_RESET_HARD ]]; then + git reset --hard HEAD + else + restore_configs + fi + printf "\033[0;31mFailed!\033[0m\n" + return 1 + fi +} +export -f exec_test + +printf "Running \033[0;32m$2\033[0m Tests\n" + +if [[ $2 = "ALL" ]]; then + tests=("$TESTS"/*) + for f in "${tests[@]}"; do + testenv=$(basename $f) + printf "Running \033[0;32m$f\033[0m Tests\n" + exec_test $1 "$testenv --target clean" "Setup Build Environment" + if [[ $GIT_RESET_HARD == "true" ]]; then + git reset --hard HEAD + else + restore_configs + fi + done +else + exec_test $1 "$2 --target clean" "Setup Build Environment" + test_name="$3" + # If the test name is 1 or 2 digits, treat it as an index + if [[ "$test_name" =~ ^[0-9][0-9]?$ ]] ; then + # Find the test name that corresponds to that index + test_name="$(cat $TESTS/$2 | grep -e '^exec_test' | sed -n "$3p" | sed "s/.*\$1 \$2 \"\([^\"]*\).*/\1/g")" + if [[ -z "$test_name" ]] ; then + # Fail if none matches + printf "\033[0;31mCould not find test \033[0m#$3\033[0;31m in \033[0mbuildroot/tests/$2\n" + exit 1 + else + printf "\033[0;32mMatching test \033[0m#$3\033[0;32m: '\033[0m$test_name\033[0;32m'\n" + fi + fi + $TESTS/$2 $1 $2 "$test_name" + if [[ $GIT_RESET_HARD == "true" ]]; then + git reset --hard HEAD + else + restore_configs + fi +fi +printf "\033[0;32mAll tests completed successfully\033[0m\n" diff --git a/buildroot/bin/uncrust b/buildroot/bin/uncrust index 9893b5c380e6..7898f73c8c77 100755 --- a/buildroot/bin/uncrust +++ b/buildroot/bin/uncrust @@ -6,11 +6,12 @@ TMPDIR=`mktemp -d` # Reformat a single file to tmp/ -uncrustify -l CPP -c ./buildroot/share/extras/uncrustify.cfg -f "$1" >$TMPDIR/uncrustify.out - -# Replace the original file -cp "$TMPDIR/uncrustify.out" "$1" +if uncrustify -l CPP -c ./buildroot/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." +fi # Clean up, deliberately -rm "$TMPDIR/uncrustify.out" +[[ -f "$TMPDIR/uncrustify.out" ]] && rm "$TMPDIR/uncrustify.out" rmdir "$TMPDIR" diff --git a/buildroot/share/PlatformIO/boards/BigTree_Btt002.json b/buildroot/share/PlatformIO/boards/BigTree_Btt002.json deleted file mode 100644 index d0d092f1eaba..000000000000 --- a/buildroot/share/PlatformIO/boards/BigTree_Btt002.json +++ /dev/null @@ -1,46 +0,0 @@ -{ - "build": { - "core": "stm32", - "cpu": "cortex-m4", - "extra_flags": "-DSTM32F4 -DSTM32F407xx -DSTM32F40_41xxx", - "f_cpu": "168000000L", - "hwids": [ - [ - "0x1EAF", - "0x0003" - ], - [ - "0x0483", - "0x3748" - ] - ], - "mcu": "stm32f407vgt6", - "variant": "BIGTREE_BTT002" - }, - "debug": { - "jlink_device": "STM32F407VG", - "openocd_target": "stm32f4x", - "svd_path": "STM32F40x.svd" - }, - "frameworks": [ - "arduino" - ], - "name": "STM32F407VG (192k RAM. 1024k Flash)", - "upload": { - "disable_flushing": false, - "maximum_ram_size": 131072, - "maximum_size": 1048576, - "protocol": "stlink", - "protocols": [ - "stlink", - "dfu", - "jlink" - ], - "offset_address": "0x8008000", - "require_upload_port": true, - "use_1200bps_touch": false, - "wait_for_upload_port": false - }, - "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32f407vg.html", - "vendor": "Generic" -} diff --git a/buildroot/share/PlatformIO/boards/BigTree_GTR_v1.json b/buildroot/share/PlatformIO/boards/BigTree_GTR_v1.json deleted file mode 100644 index 32236301c347..000000000000 --- a/buildroot/share/PlatformIO/boards/BigTree_GTR_v1.json +++ /dev/null @@ -1,46 +0,0 @@ -{ - "build": { - "core": "stm32", - "cpu": "cortex-m4", - "extra_flags": "-DSTM32F4 -DSTM32F407xx -DSTM32F40_41xxx", - "f_cpu": "168000000L", - "hwids": [ - [ - "0x1EAF", - "0x0003" - ], - [ - "0x0483", - "0x3748" - ] - ], - "mcu": "stm32f407zgt6", - "variant": "BIGTREE_GTR_V1" - }, - "debug": { - "jlink_device": "STM32F407ZG", - "openocd_target": "stm32f4x", - "svd_path": "STM32F40x.svd" - }, - "frameworks": [ - "arduino" - ], - "name": "STM32F407ZG (192k RAM. 1024k Flash)", - "upload": { - "disable_flushing": false, - "maximum_ram_size": 196608, - "maximum_size": 1048576, - "protocol": "stlink", - "protocols": [ - "stlink", - "dfu", - "jlink" - ], - "offset_address": "0x8008000", - "require_upload_port": true, - "use_1200bps_touch": false, - "wait_for_upload_port": false - }, - "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32f407zg.html", - "vendor": "Generic" -} diff --git a/buildroot/share/PlatformIO/boards/BigTree_SKR_Pro.json b/buildroot/share/PlatformIO/boards/BigTree_SKR_Pro.json deleted file mode 100644 index 211ceacdca0b..000000000000 --- a/buildroot/share/PlatformIO/boards/BigTree_SKR_Pro.json +++ /dev/null @@ -1,46 +0,0 @@ -{ - "build": { - "core": "stm32", - "cpu": "cortex-m4", - "extra_flags": "-DSTM32F4 -DSTM32F407xx -DSTM32F40_41xxx", - "f_cpu": "168000000L", - "hwids": [ - [ - "0x1EAF", - "0x0003" - ], - [ - "0x0483", - "0x3748" - ] - ], - "mcu": "stm32f407zgt6", - "variant": "BIGTREE_SKR_PRO_1v1" - }, - "debug": { - "jlink_device": "STM32F407ZG", - "openocd_target": "stm32f4x", - "svd_path": "STM32F40x.svd" - }, - "frameworks": [ - "arduino" - ], - "name": "STM32F407ZG (192k RAM. 1024k Flash)", - "upload": { - "disable_flushing": false, - "maximum_ram_size": 196608, - "maximum_size": 1048576, - "protocol": "stlink", - "protocols": [ - "stlink", - "dfu", - "jlink" - ], - "offset_address": "0x8008000", - "require_upload_port": true, - "use_1200bps_touch": false, - "wait_for_upload_port": false - }, - "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32f407zg.html", - "vendor": "Generic" -} diff --git a/buildroot/share/PlatformIO/boards/CHITU_F103.json b/buildroot/share/PlatformIO/boards/CHITU_F103.json deleted file mode 100644 index ecf7bff66c87..000000000000 --- a/buildroot/share/PlatformIO/boards/CHITU_F103.json +++ /dev/null @@ -1,48 +0,0 @@ -{ - "build": { - "core": "maple", - "cpu": "cortex-m3", - "extra_flags": "-DSTM32F103xE -DSTM32F1", - "f_cpu": "72000000L", - "hwids": [ - [ - "0x1EAF", - "0x0003" - ], - [ - "0x1EAF", - "0x0004" - ] - ], - "mcu": "stm32f103zet6", - "variant": "CHITU_F103", - "ldscript": "chitu_f103.ld" - }, - "debug": { - "jlink_device": "STM32F103ZE", - "openocd_target": "stm32f1x", - "svd_path": "STM32F103xx.svd" - }, - "frameworks": [ - "arduino" - ], - "name": "CHITU STM32F103Z (64k RAM. 512k Flash)", - "upload": { - "disable_flushing": false, - "maximum_ram_size": 60536, - "maximum_size": 480288, - "protocol": "stlink", - "protocols": [ - "jlink", - "stlink", - "blackmagic", - "serial", - "dfu" - ], - "require_upload_port": true, - "use_1200bps_touch": false, - "wait_for_upload_port": false - }, - "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32f103ze.html", - "vendor": "Generic" -} diff --git a/buildroot/share/PlatformIO/boards/FLYF407ZG.json b/buildroot/share/PlatformIO/boards/FLYF407ZG.json deleted file mode 100644 index 7e585c5057ca..000000000000 --- a/buildroot/share/PlatformIO/boards/FLYF407ZG.json +++ /dev/null @@ -1,64 +0,0 @@ -{ - "build": { - "core": "stm32", - "cpu": "cortex-m4", - "extra_flags": "-DSTM32F407xx", - "f_cpu": "168000000L", - "hwids": [ - [ - "0x1EAF", - "0x0003" - ], - [ - "0x0483", - "0x3748" - ] - ], - "mcu": "stm32f407zgt6", - "variant": "FLY_F407ZG" - }, - "debug": { - "jlink_device": "STM32F407ZG", - "openocd_target": "stm32f4x", - "svd_path": "STM32F40x.svd", - "tools": { - "stlink": { - "server": { - "arguments": [ - "-f", - "scripts/interface/stlink.cfg", - "-c", - "transport select hla_swd", - "-f", - "scripts/target/stm32f4x.cfg", - "-c", - "reset_config none" - ], - "executable": "bin/openocd", - "package": "tool-openocd" - } - } - } - }, - "frameworks": [ - "arduino", - "stm32cube" - ], - "name": "STM32F407ZGT6(192k RAM. 1024k Flash)", - "upload": { - "disable_flushing": false, - "maximum_ram_size": 196608, - "maximum_size": 1048576, - "protocol": "dfu", - "protocols": [ - "stlink", - "dfu", - "jlink" - ], - "require_upload_port": true, - "use_1200bps_touch": false, - "wait_for_upload_port": false - }, - "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32f407ZG.html", - "vendor": "Generic" -} diff --git a/buildroot/share/PlatformIO/boards/LERDGE.json b/buildroot/share/PlatformIO/boards/LERDGE.json deleted file mode 100644 index 011814a13361..000000000000 --- a/buildroot/share/PlatformIO/boards/LERDGE.json +++ /dev/null @@ -1,65 +0,0 @@ -{ - "build": { - "core": "stm32", - "cpu": "cortex-m4", - "extra_flags": "-DSTM32F407xx", - "f_cpu": "168000000L", - "hwids": [ - [ - "0x1EAF", - "0x0003" - ], - [ - "0x0483", - "0x3748" - ] - ], - "mcu": "stm32f407zgt6", - "variant": "LERDGE", - "ldscript": "LERDGE.ld" - }, - "debug": { - "jlink_device": "STM32F407ZG", - "openocd_target": "stm32f4x", - "svd_path": "STM32F40x.svd", - "tools": { - "stlink": { - "server": { - "arguments": [ - "-f", - "scripts/interface/stlink.cfg", - "-c", - "transport select hla_swd", - "-f", - "scripts/target/stm32f4x.cfg", - "-c", - "reset_config none" - ], - "executable": "bin/openocd", - "package": "tool-openocd" - } - } - } - }, - "frameworks": [ - "arduino", - "stm32cube" - ], - "name": "STM32F407ZGT6(192k RAM. 1024k Flash)", - "upload": { - "disable_flushing": false, - "maximum_ram_size": 196608, - "maximum_size": 1048576, - "protocol": "stlink", - "protocols": [ - "stlink", - "dfu", - "jlink" - ], - "require_upload_port": true, - "use_1200bps_touch": false, - "wait_for_upload_port": false - }, - "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32f407ZG.html", - "vendor": "Generic" -} diff --git a/buildroot/share/PlatformIO/boards/MEEB_3DP.json b/buildroot/share/PlatformIO/boards/MEEB_3DP.json deleted file mode 100644 index 870648b32572..000000000000 --- a/buildroot/share/PlatformIO/boards/MEEB_3DP.json +++ /dev/null @@ -1,53 +0,0 @@ -{ - "build": { - "core": "maple", - "cpu": "cortex-m3", - "extra_flags": "-DSTM32F103xE -DSTM32F1", - "f_cpu": "72000000L", - "hwids": [ - [ - "0x1EAF", - "0x0003" - ], - [ - "0x1EAF", - "0x0004" - ] - ], - "libopencm3": { - "ldscript": "stm32f103xc.ld" - }, - "mcu": "stm32f103rct6", - "variant": "MEEB_3DP" - }, - "debug": { - "jlink_device": "STM32F103RC", - "openocd_target": "stm32f1x", - "svd_path": "STM32F103xx.svd" - }, - "frameworks": [ - "arduino", - "cmsis", - "libopencm3", - "stm32cube" - ], - "name": "3D Printer control board for MEEB with 512k flash/rs422 bus/tmc2208 drivers", - "upload": { - "disable_flushing": false, - "maximum_ram_size": 49152, - "maximum_size": 524288, - "protocol": "dfu", - "protocols": [ - "jlink", - "stlink", - "blackmagic", - "serial", - "dfu" - ], - "require_upload_port": true, - "use_1200bps_touch": false, - "wait_for_upload_port": false - }, - "url": "https://github.com/ccrobot-online/MEEB_3DP", - "vendor": "CCROBOT-ONLINE" -} diff --git a/buildroot/share/PlatformIO/boards/STEVAL_STM32F401VE.json b/buildroot/share/PlatformIO/boards/STEVAL_STM32F401VE.json deleted file mode 100644 index bbfb3fdfa508..000000000000 --- a/buildroot/share/PlatformIO/boards/STEVAL_STM32F401VE.json +++ /dev/null @@ -1,65 +0,0 @@ -{ - "build": { - "core": "stm32", - "cpu": "cortex-m4", - "extra_flags": "-DSTM32F401xx", - "f_cpu": "84000000L", - "hwids": [ - [ - "0x1EAF", - "0x0003" - ], - [ - "0x0483", - "0x3748" - ] - ], - "ldscript": "stm32f401xe.ld", - "mcu": "stm32f401vet6", - "variant": "STEVAL_F401VE" - }, - "debug": { - "jlink_device": "STM32F401VE", - "openocd_target": "stm32f4x", - "svd_path": "STM32F40x.svd", - "tools": { - "stlink": { - "server": { - "arguments": [ - "-f", - "scripts/interface/stlink.cfg", - "-c", - "transport select hla_swd", - "-f", - "scripts/target/stm32f4x.cfg", - "-c", - "reset_config none" - ], - "executable": "bin/openocd", - "package": "tool-openocd" - } - } - } - }, - "frameworks": [ - "arduino", - "stm32cube" - ], - "name": "STM32F401VE (96k RAM. 512k Flash)", - "upload": { - "disable_flushing": false, - "maximum_ram_size": 98304, - "maximum_size": 514288, - "protocol": "stlink", - "protocols": [ - "stlink", - "dfu", - "jlink" - ], - "require_upload_port": true, - "use_1200bps_touch": false, - "wait_for_upload_port": false - }, - "url": "https://www.st.com/en/evaluation-tools/steval-3dp001v1.html", - "vendor": "Generic" -} diff --git a/buildroot/share/PlatformIO/boards/archim.json b/buildroot/share/PlatformIO/boards/archim.json deleted file mode 100644 index 60035197f2f3..000000000000 --- a/buildroot/share/PlatformIO/boards/archim.json +++ /dev/null @@ -1,59 +0,0 @@ -{ - "build": { - "core": "arduino", - "cpu": "cortex-m3", - "extra_flags": "-D__SAM3X8E__ -DARDUINO_ARCH_SAM -DARDUINO_SAM_DUE", - "f_cpu": "84000000L", - "hwids": [ - [ - "0x27B1", - "0x0001" - ], - [ - "0x2341", - "0x003E" - ], - [ - "0x2341", - "0x003D" - ] - ], - "ldscript": "linker_scripts/gcc/flash.ld", - "mcu": "at91sam3x8e", - "usb_product": "Archim", - "variant": "archim" - }, - "connectivity": [ - "can" - ], - "debug": { - "jlink_device": "ATSAM3X8E", - "openocd_chipname": "at91sam3X8E", - "openocd_target": "at91sam3XXX", - "svd_path": "ATSAM3X8E.svd" - }, - "frameworks": [ - "arduino", - "simba" - ], - "name": "Archim", - "upload": { - "disable_flushing": true, - "maximum_ram_size": 98304, - "maximum_size": 524288, - "native_usb": true, - "protocol": "sam-ba", - "protocols": [ - "sam-ba", - "jlink", - "blackmagic", - "atmel-ice", - "stlink" - ], - "require_upload_port": true, - "use_1200bps_touch": true, - "wait_for_upload_port": true - }, - "url": "https://ultimachine.com", - "vendor": "UltiMachine" -} diff --git a/buildroot/share/PlatformIO/boards/blackSTM32F407VET6.json b/buildroot/share/PlatformIO/boards/blackSTM32F407VET6.json deleted file mode 100644 index 176563408602..000000000000 --- a/buildroot/share/PlatformIO/boards/blackSTM32F407VET6.json +++ /dev/null @@ -1,64 +0,0 @@ -{ - "build": { - "core": "stm32", - "cpu": "cortex-m4", - "extra_flags": "-DSTM32F407xx", - "f_cpu": "168000000L", - "hwids": [ - [ - "0x1EAF", - "0x0003" - ], - [ - "0x0483", - "0x3748" - ] - ], - "mcu": "stm32f407vet6", - "variant": "MARLIN_F407VE" - }, - "debug": { - "jlink_device": "STM32F407VE", - "openocd_target": "stm32f4x", - "svd_path": "STM32F40x.svd", - "tools": { - "stlink": { - "server": { - "arguments": [ - "-f", - "scripts/interface/stlink.cfg", - "-c", - "transport select hla_swd", - "-f", - "scripts/target/stm32f4x.cfg", - "-c", - "reset_config none" - ], - "executable": "bin/openocd", - "package": "tool-openocd" - } - } - } - }, - "frameworks": [ - "arduino", - "stm32cube" - ], - "name": "STM32F407VE (192k RAM. 512k Flash)", - "upload": { - "disable_flushing": false, - "maximum_ram_size": 131072, - "maximum_size": 514288, - "protocol": "stlink", - "protocols": [ - "stlink", - "dfu", - "jlink" - ], - "require_upload_port": true, - "use_1200bps_touch": false, - "wait_for_upload_port": false - }, - "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32f407ve.html", - "vendor": "Generic" -} diff --git a/buildroot/share/PlatformIO/boards/marlin_BTT_SKR_SE_BX.json b/buildroot/share/PlatformIO/boards/marlin_BTT_SKR_SE_BX.json new file mode 100644 index 000000000000..65735d433b17 --- /dev/null +++ b/buildroot/share/PlatformIO/boards/marlin_BTT_SKR_SE_BX.json @@ -0,0 +1,56 @@ +{ + "build": { + "core": "stm32", + "cpu": "cortex-m7", + "extra_flags": "-DSTM32H743xx", + "f_cpu": "400000000L", + "mcu": "stm32h743iit6", + "variant": "MARLIN_BTT_SKR_SE_BX" + }, + "debug": { + "jlink_device": "STM32H743II", + "openocd_target": "stm32h7x", + "svd_path": "STM32H7x3.svd", + "tools": { + "stlink": { + "server": { + "arguments": [ + "-f", + "scripts/interface/stlink.cfg", + "-c", + "transport select hla_swd", + "-f", + "scripts/target/stm32h7x.cfg", + "-c", + "reset_config none" + ], + "executable": "bin/openocd", + "package": "tool-openocd" + } + } + } + }, + "frameworks": [ + "arduino", + "stm32cube" + ], + "name": "STM32H743II (1024k RAM. 2048k Flash)", + "upload": { + "disable_flushing": false, + "maximum_ram_size": 1048576, + "maximum_size": 2097152, + "protocol": "stlink", + "protocols": [ + "stlink", + "dfu", + "jlink", + "cmsis-dap" + ], + "offset_address": "0x8020000", + "require_upload_port": true, + "use_1200bps_touch": false, + "wait_for_upload_port": false + }, + "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32h743ii.html", + "vendor": "Generic" +} diff --git a/buildroot/share/PlatformIO/boards/marlin_BigTree_BTT002.json b/buildroot/share/PlatformIO/boards/marlin_BigTree_BTT002.json new file mode 100644 index 000000000000..28a79271b89c --- /dev/null +++ b/buildroot/share/PlatformIO/boards/marlin_BigTree_BTT002.json @@ -0,0 +1,46 @@ +{ + "build": { + "core": "stm32", + "cpu": "cortex-m4", + "extra_flags": "-DSTM32F4 -DSTM32F407xx -DSTM32F40_41xxx", + "f_cpu": "168000000L", + "hwids": [ + [ + "0x1EAF", + "0x0003" + ], + [ + "0x0483", + "0x3748" + ] + ], + "mcu": "stm32f407vgt6", + "variant": "MARLIN_BIGTREE_BTT002" + }, + "debug": { + "jlink_device": "STM32F407VG", + "openocd_target": "stm32f4x", + "svd_path": "STM32F40x.svd" + }, + "frameworks": [ + "arduino" + ], + "name": "STM32F407VG (192k RAM. 1024k Flash)", + "upload": { + "disable_flushing": false, + "maximum_ram_size": 131072, + "maximum_size": 1048576, + "protocol": "stlink", + "protocols": [ + "stlink", + "dfu", + "jlink" + ], + "offset_address": "0x8008000", + "require_upload_port": true, + "use_1200bps_touch": false, + "wait_for_upload_port": false + }, + "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32f407vg.html", + "vendor": "Generic" +} diff --git a/buildroot/share/PlatformIO/boards/marlin_BigTree_GTR_v1.json b/buildroot/share/PlatformIO/boards/marlin_BigTree_GTR_v1.json new file mode 100644 index 000000000000..e311ce3b5278 --- /dev/null +++ b/buildroot/share/PlatformIO/boards/marlin_BigTree_GTR_v1.json @@ -0,0 +1,46 @@ +{ + "build": { + "core": "stm32", + "cpu": "cortex-m4", + "extra_flags": "-DSTM32F4 -DSTM32F407xx -DSTM32F40_41xxx", + "f_cpu": "168000000L", + "hwids": [ + [ + "0x1EAF", + "0x0003" + ], + [ + "0x0483", + "0x3748" + ] + ], + "mcu": "stm32f407zgt6", + "variant": "MARLIN_BIGTREE_GTR_V1" + }, + "debug": { + "jlink_device": "STM32F407ZG", + "openocd_target": "stm32f4x", + "svd_path": "STM32F40x.svd" + }, + "frameworks": [ + "arduino" + ], + "name": "STM32F407ZG (192k RAM. 1024k Flash)", + "upload": { + "disable_flushing": false, + "maximum_ram_size": 196608, + "maximum_size": 1048576, + "protocol": "stlink", + "protocols": [ + "stlink", + "dfu", + "jlink" + ], + "offset_address": "0x8008000", + "require_upload_port": true, + "use_1200bps_touch": false, + "wait_for_upload_port": false + }, + "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32f407zg.html", + "vendor": "Generic" +} diff --git a/buildroot/share/PlatformIO/boards/marlin_BigTree_Octopus_v1.json b/buildroot/share/PlatformIO/boards/marlin_BigTree_Octopus_v1.json new file mode 100644 index 000000000000..ea2515407900 --- /dev/null +++ b/buildroot/share/PlatformIO/boards/marlin_BigTree_Octopus_v1.json @@ -0,0 +1,35 @@ +{ + "build": { + "cpu": "cortex-m4", + "extra_flags": "-DSTM32F446xx", + "f_cpu": "180000000L", + "mcu": "stm32f446zet6", + "variant": "MARLIN_BIGTREE_OCTOPUS_V1" + }, + "connectivity": [ + "can" + ], + "debug": { + "jlink_device": "STM32F446ZE", + "openocd_target": "stm32f4x", + "svd_path": "STM32F446x.svd" + }, + "frameworks": [ + "arduino", + "stm32cube" + ], + "name": "STM32F446ZE (128k RAM. 512k Flash)", + "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": "Generic" +} diff --git a/buildroot/share/PlatformIO/boards/marlin_BigTree_SKR_Pro.json b/buildroot/share/PlatformIO/boards/marlin_BigTree_SKR_Pro.json new file mode 100644 index 000000000000..5e76c2c9e205 --- /dev/null +++ b/buildroot/share/PlatformIO/boards/marlin_BigTree_SKR_Pro.json @@ -0,0 +1,46 @@ +{ + "build": { + "core": "stm32", + "cpu": "cortex-m4", + "extra_flags": "-DSTM32F4 -DSTM32F407xx -DSTM32F40_41xxx", + "f_cpu": "168000000L", + "hwids": [ + [ + "0x1EAF", + "0x0003" + ], + [ + "0x0483", + "0x3748" + ] + ], + "mcu": "stm32f407zgt6", + "variant": "MARLIN_BIGTREE_SKR_PRO_11" + }, + "debug": { + "jlink_device": "STM32F407ZG", + "openocd_target": "stm32f4x", + "svd_path": "STM32F40x.svd" + }, + "frameworks": [ + "arduino" + ], + "name": "STM32F407ZG (192k RAM. 1024k Flash)", + "upload": { + "disable_flushing": false, + "maximum_ram_size": 196608, + "maximum_size": 1048576, + "protocol": "stlink", + "protocols": [ + "stlink", + "dfu", + "jlink" + ], + "offset_address": "0x8008000", + "require_upload_port": true, + "use_1200bps_touch": false, + "wait_for_upload_port": false + }, + "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32f407zg.html", + "vendor": "Generic" +} diff --git a/buildroot/share/PlatformIO/boards/marlin_CHITU_F103.json b/buildroot/share/PlatformIO/boards/marlin_CHITU_F103.json new file mode 100644 index 000000000000..dbfbc21cb275 --- /dev/null +++ b/buildroot/share/PlatformIO/boards/marlin_CHITU_F103.json @@ -0,0 +1,47 @@ +{ + "build": { + "core": "maple", + "cpu": "cortex-m3", + "extra_flags": "-DSTM32F103xE -DSTM32F1", + "f_cpu": "72000000L", + "hwids": [ + [ + "0x1EAF", + "0x0003" + ], + [ + "0x1EAF", + "0x0004" + ] + ], + "mcu": "stm32f103zet6", + "variant": "marlin_CHITU_F103" + }, + "debug": { + "jlink_device": "STM32F103ZE", + "openocd_target": "stm32f1x", + "svd_path": "STM32F103xx.svd" + }, + "frameworks": [ + "arduino" + ], + "name": "CHITU STM32F103Z (64k RAM. 512k Flash)", + "upload": { + "disable_flushing": false, + "maximum_ram_size": 60536, + "maximum_size": 480288, + "protocol": "stlink", + "protocols": [ + "jlink", + "stlink", + "blackmagic", + "serial", + "dfu" + ], + "require_upload_port": true, + "use_1200bps_touch": false, + "wait_for_upload_port": false + }, + "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32f103ze.html", + "vendor": "Generic" +} diff --git a/buildroot/share/PlatformIO/boards/marlin_FYSETC_CHEETAH_V20.json b/buildroot/share/PlatformIO/boards/marlin_FYSETC_CHEETAH_V20.json new file mode 100644 index 000000000000..e7b0d28afef9 --- /dev/null +++ b/buildroot/share/PlatformIO/boards/marlin_FYSETC_CHEETAH_V20.json @@ -0,0 +1,66 @@ +{ + "build": { + "core": "stm32", + "cpu": "cortex-m4", + "extra_flags": "-DSTM32F401xx", + "f_cpu": "84000000L", + "hwids": [ + [ + "0x1EAF", + "0x0003" + ], + [ + "0x0483", + "0x3748" + ] + ], + "ldscript": "stm32f401rc.ld", + "mcu": "stm32f401rct6", + "variant": "MARLIN_FYSETC_CHEETAH_V20" + }, + "debug": { + "jlink_device": "STM32F401RC", + "openocd_target": "stm32f4x", + "svd_path": "STM32F40x.svd", + "tools": { + "stlink": { + "server": { + "arguments": [ + "-f", + "scripts/interface/stlink.cfg", + "-c", + "transport select hla_swd", + "-f", + "scripts/target/stm32f4x.cfg", + "-c", + "reset_config none" + ], + "executable": "bin/openocd", + "package": "tool-openocd" + } + } + } + }, + "frameworks": [ + "arduino", + "stm32cube" + ], + "name": "STM32F401RC (64k RAM. 256k Flash)", + "upload": { + "disable_flushing": false, + "maximum_ram_size": 65536, + "maximum_size": 262144, + "protocol": "stlink", + "protocols": [ + "stlink", + "dfu", + "jlink" + ], + "offset_address": "0x800C000", + "require_upload_port": true, + "use_1200bps_touch": false, + "wait_for_upload_port": false + }, + "url": "https://www.fysetc.com", + "vendor": "Generic" +} diff --git a/buildroot/share/PlatformIO/boards/marlin_MEEB_3DP.json b/buildroot/share/PlatformIO/boards/marlin_MEEB_3DP.json new file mode 100644 index 000000000000..73ec9aaf48e2 --- /dev/null +++ b/buildroot/share/PlatformIO/boards/marlin_MEEB_3DP.json @@ -0,0 +1,53 @@ +{ + "build": { + "core": "maple", + "cpu": "cortex-m3", + "extra_flags": "-DSTM32F103xE -DSTM32F1", + "f_cpu": "72000000L", + "hwids": [ + [ + "0x1EAF", + "0x0003" + ], + [ + "0x1EAF", + "0x0004" + ] + ], + "libopencm3": { + "ldscript": "stm32f103xc.ld" + }, + "mcu": "stm32f103rct6", + "variant": "marlin_MEEB_3DP" + }, + "debug": { + "jlink_device": "STM32F103RC", + "openocd_target": "stm32f1x", + "svd_path": "STM32F103xx.svd" + }, + "frameworks": [ + "arduino", + "cmsis", + "libopencm3", + "stm32cube" + ], + "name": "3D Printer control board for MEEB with 512k flash/rs422 bus/tmc2208 drivers", + "upload": { + "disable_flushing": false, + "maximum_ram_size": 49152, + "maximum_size": 524288, + "protocol": "dfu", + "protocols": [ + "jlink", + "stlink", + "blackmagic", + "serial", + "dfu" + ], + "require_upload_port": true, + "use_1200bps_touch": false, + "wait_for_upload_port": false + }, + "url": "https://github.com/ccrobot-online/MEEB_3DP", + "vendor": "CCROBOT-ONLINE" +} diff --git a/buildroot/share/PlatformIO/boards/marlin_STEVAL_STM32F401VE.json b/buildroot/share/PlatformIO/boards/marlin_STEVAL_STM32F401VE.json new file mode 100644 index 000000000000..e260950f25d5 --- /dev/null +++ b/buildroot/share/PlatformIO/boards/marlin_STEVAL_STM32F401VE.json @@ -0,0 +1,64 @@ +{ + "build": { + "core": "stm32", + "cpu": "cortex-m4", + "extra_flags": "-DSTM32F401xx -DARDUINO_STEVAL", + "f_cpu": "84000000L", + "hwids": [ + [ + "0x1EAF", + "0x0003" + ], + [ + "0x0483", + "0x3748" + ] + ], + "mcu": "stm32f401vet6", + "variant": "MARLIN_STEVAL_F401VE" + }, + "debug": { + "jlink_device": "STM32F401VE", + "openocd_target": "stm32f4x", + "svd_path": "STM32F40x.svd", + "tools": { + "stlink": { + "server": { + "arguments": [ + "-f", + "scripts/interface/stlink.cfg", + "-c", + "transport select hla_swd", + "-f", + "scripts/target/stm32f4x.cfg", + "-c", + "reset_config none" + ], + "executable": "bin/openocd", + "package": "tool-openocd" + } + } + } + }, + "frameworks": [ + "arduino", + "stm32cube" + ], + "name": "STM32F401VE (96k RAM. 512k Flash)", + "upload": { + "disable_flushing": false, + "maximum_ram_size": 98304, + "maximum_size": 514288, + "protocol": "stlink", + "protocols": [ + "stlink", + "dfu", + "jlink" + ], + "require_upload_port": true, + "use_1200bps_touch": false, + "wait_for_upload_port": false + }, + "url": "https://www.st.com/en/evaluation-tools/steval-3dp001v1.html", + "vendor": "Generic" +} diff --git a/buildroot/share/PlatformIO/boards/marlin_STM32F407VGT6_CCM.json b/buildroot/share/PlatformIO/boards/marlin_STM32F407VGT6_CCM.json new file mode 100644 index 000000000000..8c211a854900 --- /dev/null +++ b/buildroot/share/PlatformIO/boards/marlin_STM32F407VGT6_CCM.json @@ -0,0 +1,56 @@ +{ + "build": { + "core": "stm32", + "cpu": "cortex-m4", + "extra_flags": "-DSTM32F407xx -DSTM32F4", + "f_cpu": "168000000L", + "hwids": [ + [ + "0x1EAF", + "0x0003" + ], + [ + "0x0483", + "0x3748" + ] + ], + "mcu": "stm32f407vgt6", + "product_line": "STM32F407xx", + "variant": "Generic_F4x7Vx" + }, + "debug": { + "default_tools": [ + "stlink" + ], + "jlink_device": "STM32F407VG", + "openocd_extra_args": [ + "-c", + "reset_config none" + ], + "openocd_target": "stm32f4x", + "svd_path": "STM32F40x.svd" + }, + "frameworks": [ + "arduino", + "cmsis", + "stm32cube", + "libopencm3" + ], + "name": "STM32F407VG (128k RAM, 64k CCM RAM, 1024k Flash", + "upload": { + "disable_flushing": false, + "maximum_ram_size": 131072, + "maximum_size": 1048576, + "protocol": "stlink", + "protocols": [ + "stlink", + "dfu", + "jlink" + ], + "require_upload_port": true, + "use_1200bps_touch": false, + "wait_for_upload_port": false + }, + "url": "https://www.st.com/content/st_com/en/products/microcontrollers/stm32-32-bit-arm-cortex-mcus/stm32-high-performance-mcus/stm32f4-series/stm32f407-417/stm32f407vg.html", + "vendor": "Generic" +} diff --git a/buildroot/share/PlatformIO/boards/marlin_STM32F407ZGT6.json b/buildroot/share/PlatformIO/boards/marlin_STM32F407ZGT6.json new file mode 100644 index 000000000000..f6c78f8ab33b --- /dev/null +++ b/buildroot/share/PlatformIO/boards/marlin_STM32F407ZGT6.json @@ -0,0 +1,63 @@ +{ + "build": { + "core": "stm32", + "cpu": "cortex-m4", + "extra_flags": "-DSTM32F407xx", + "f_cpu": "168000000L", + "hwids": [ + [ + "0x1EAF", + "0x0003" + ], + [ + "0x0483", + "0x3748" + ] + ], + "mcu": "stm32f407zgt6" + }, + "debug": { + "jlink_device": "STM32F407ZG", + "openocd_target": "stm32f4x", + "svd_path": "STM32F40x.svd", + "tools": { + "stlink": { + "server": { + "arguments": [ + "-f", + "scripts/interface/stlink.cfg", + "-c", + "transport select hla_swd", + "-f", + "scripts/target/stm32f4x.cfg", + "-c", + "reset_config none" + ], + "executable": "bin/openocd", + "package": "tool-openocd" + } + } + } + }, + "frameworks": [ + "arduino", + "stm32cube" + ], + "name": "STM32F407ZGT6(192k RAM. 1024k Flash)", + "upload": { + "disable_flushing": false, + "maximum_ram_size": 196608, + "maximum_size": 1048576, + "protocol": "stlink", + "protocols": [ + "stlink", + "dfu", + "jlink" + ], + "require_upload_port": true, + "use_1200bps_touch": false, + "wait_for_upload_port": false + }, + "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32f407ZG.html", + "vendor": "Generic" +} diff --git a/buildroot/share/PlatformIO/boards/marlin_archim.json b/buildroot/share/PlatformIO/boards/marlin_archim.json new file mode 100644 index 000000000000..6d78c1f19576 --- /dev/null +++ b/buildroot/share/PlatformIO/boards/marlin_archim.json @@ -0,0 +1,59 @@ +{ + "build": { + "core": "arduino", + "cpu": "cortex-m3", + "extra_flags": "-D__SAM3X8E__ -DARDUINO_ARCH_SAM -DARDUINO_SAM_DUE", + "f_cpu": "84000000L", + "hwids": [ + [ + "0x27B1", + "0x0001" + ], + [ + "0x2341", + "0x003E" + ], + [ + "0x2341", + "0x003D" + ] + ], + "ldscript": "linker_scripts/gcc/flash.ld", + "mcu": "at91sam3x8e", + "usb_product": "Archim", + "variant": "MARLIN_ARCHIM" + }, + "connectivity": [ + "can" + ], + "debug": { + "jlink_device": "ATSAM3X8E", + "openocd_chipname": "at91sam3X8E", + "openocd_target": "at91sam3XXX", + "svd_path": "ATSAM3X8E.svd" + }, + "frameworks": [ + "arduino", + "simba" + ], + "name": "Archim", + "upload": { + "disable_flushing": true, + "maximum_ram_size": 98304, + "maximum_size": 524288, + "native_usb": true, + "protocol": "sam-ba", + "protocols": [ + "sam-ba", + "jlink", + "blackmagic", + "atmel-ice", + "stlink" + ], + "require_upload_port": true, + "use_1200bps_touch": true, + "wait_for_upload_port": true + }, + "url": "https://ultimachine.com", + "vendor": "UltiMachine" +} diff --git a/buildroot/share/PlatformIO/boards/at90usb1286.json b/buildroot/share/PlatformIO/boards/marlin_at90usb1286.json similarity index 100% rename from buildroot/share/PlatformIO/boards/at90usb1286.json rename to buildroot/share/PlatformIO/boards/marlin_at90usb1286.json diff --git a/buildroot/share/PlatformIO/boards/marlin_blackSTM32F407VET6.json b/buildroot/share/PlatformIO/boards/marlin_blackSTM32F407VET6.json new file mode 100644 index 000000000000..b0fd9db9392a --- /dev/null +++ b/buildroot/share/PlatformIO/boards/marlin_blackSTM32F407VET6.json @@ -0,0 +1,64 @@ +{ + "build": { + "core": "stm32", + "cpu": "cortex-m4", + "extra_flags": "-DSTM32F407xx -DARDUINO_BLACK_F407VE", + "f_cpu": "168000000L", + "hwids": [ + [ + "0x1EAF", + "0x0003" + ], + [ + "0x0483", + "0x3748" + ] + ], + "mcu": "stm32f407vet6", + "variant": "MARLIN_F407VE" + }, + "debug": { + "jlink_device": "STM32F407VE", + "openocd_target": "stm32f4x", + "svd_path": "STM32F40x.svd", + "tools": { + "stlink": { + "server": { + "arguments": [ + "-f", + "scripts/interface/stlink.cfg", + "-c", + "transport select hla_swd", + "-f", + "scripts/target/stm32f4x.cfg", + "-c", + "reset_config none" + ], + "executable": "bin/openocd", + "package": "tool-openocd" + } + } + } + }, + "frameworks": [ + "arduino", + "stm32cube" + ], + "name": "STM32F407VE (192k RAM. 512k Flash)", + "upload": { + "disable_flushing": false, + "maximum_ram_size": 131072, + "maximum_size": 524288, + "protocol": "stlink", + "protocols": [ + "stlink", + "dfu", + "jlink" + ], + "require_upload_port": true, + "use_1200bps_touch": false, + "wait_for_upload_port": false + }, + "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32f407ve.html", + "vendor": "Generic" +} diff --git a/buildroot/share/PlatformIO/boards/malyanM200.json b/buildroot/share/PlatformIO/boards/marlin_malyanM200.json similarity index 100% rename from buildroot/share/PlatformIO/boards/malyanM200.json rename to buildroot/share/PlatformIO/boards/marlin_malyanM200.json diff --git a/buildroot/share/PlatformIO/boards/malyanM200v2.json b/buildroot/share/PlatformIO/boards/marlin_malyanM200v2.json similarity index 100% rename from buildroot/share/PlatformIO/boards/malyanM200v2.json rename to buildroot/share/PlatformIO/boards/marlin_malyanM200v2.json diff --git a/buildroot/share/PlatformIO/ldscripts/STM32F103RE_SKR_E3_DIP.ld b/buildroot/share/PlatformIO/ldscripts/STM32F103RE_SKR_E3_DIP.ld deleted file mode 100644 index 248b7781cf78..000000000000 --- a/buildroot/share/PlatformIO/ldscripts/STM32F103RE_SKR_E3_DIP.ld +++ /dev/null @@ -1,14 +0,0 @@ -MEMORY -{ - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K - 40 - rom (rx) : ORIGIN = 0x08007000, LENGTH = 512K - 28K - 4K -} - -/* 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/ldscripts/STM32F103RC_SKR_MINI_512K.ld b/buildroot/share/PlatformIO/ldscripts/STM32F103RE_SKR_MINI_512K.ld similarity index 100% rename from buildroot/share/PlatformIO/ldscripts/STM32F103RC_SKR_MINI_512K.ld rename to buildroot/share/PlatformIO/ldscripts/STM32F103RE_SKR_MINI_512K.ld diff --git a/buildroot/share/PlatformIO/ldscripts/ZONESTAR_ZM3E_256K.ld b/buildroot/share/PlatformIO/ldscripts/ZONESTAR_ZM3E_256K.ld new file mode 100644 index 000000000000..2404e7cac9bc --- /dev/null +++ b/buildroot/share/PlatformIO/ldscripts/ZONESTAR_ZM3E_256K.ld @@ -0,0 +1,14 @@ +MEMORY +{ + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K - 40 + rom (rx) : ORIGIN = 0x08005000, LENGTH = 256K - 20K - 4K +} + +/* 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/ldscripts/ZONESTAR_ZM3E_512K.ld b/buildroot/share/PlatformIO/ldscripts/ZONESTAR_ZM3E_512K.ld new file mode 100644 index 000000000000..821c8ebbfe38 --- /dev/null +++ b/buildroot/share/PlatformIO/ldscripts/ZONESTAR_ZM3E_512K.ld @@ -0,0 +1,14 @@ +MEMORY +{ + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K - 40 + rom (rx) : ORIGIN = 0x08005000, LENGTH = 512K - 20K - 4K +} + +/* 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/ldscripts/lerdge.ld b/buildroot/share/PlatformIO/ldscripts/lerdge.ld deleted file mode 100644 index aa0b1dd9cb36..000000000000 --- a/buildroot/share/PlatformIO/ldscripts/lerdge.ld +++ /dev/null @@ -1,186 +0,0 @@ -/* -***************************************************************************** -** -** File : LinkerScript.ld -** -** Abstract : Linker script for STM32F407VGTx Device with -** 1024KByte FLASH, 128KByte 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. -** -** (c)Copyright Ac6. -** You may use this file as-is or modify it according to the needs of your -** project. Distribution of this file (unmodified or modified) is not -** permitted. Ac6 permit registered System Workbench for MCU users the -** rights to distribute the assembled, compiled & linked contents of this -** file as part of an application binary file, provided that it is built -** using the System Workbench for MCU toolchain. -** -***************************************************************************** -*/ - -/* 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 = LD_MAX_DATA_SIZE -CCMRAM (rw) : ORIGIN = 0x10000000, 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): - { - . = 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 - - _siccmram = LOADADDR(.ccmram); - - /* CCM-RAM section - * - * IMPORTANT NOTE! - * If initialized variables will be placed in this section, - * the startup code needs to be modified to copy the init-values. - */ - .ccmram : - { - . = ALIGN(4); - _sccmram = .; /* create a global symbol at ccmram start */ - *(.ccmram) - *(.ccmram*) - - . = ALIGN(4); - _eccmram = .; /* create a global symbol at ccmram end */ - } >CCMRAM AT> FLASH - - - /* Uninitialized data section */ - . = ALIGN(4); - .bss : - { - /* This is used by the startup in order to initialize the .bss secion */ - _sbss = .; /* define a global symbol at bss start */ - __bss_start__ = _sbss; - *(.bss) - *(.bss*) - *(COMMON) - - . = ALIGN(4); - _ebss = .; /* define a global symbol at bss end */ - __bss_end__ = _ebss; - } >RAM - - /* User_heap_stack section, used to check that there is enough RAM left */ - ._user_heap_stack : - { - . = ALIGN(4); - PROVIDE ( end = . ); - PROVIDE ( _end = . ); - . = . + _Min_Heap_Size; - . = . + _Min_Stack_Size; - . = ALIGN(4); - } >RAM - - - - /* Remove information from the standard libraries */ - /DISCARD/ : - { - libc.a ( * ) - libm.a ( * ) - libgcc.a ( * ) - } - - .ARM.attributes 0 : { *(.ARM.attributes) } -} diff --git a/buildroot/share/PlatformIO/scripts/SAMD51_grandcentral_m4.py b/buildroot/share/PlatformIO/scripts/SAMD51_grandcentral_m4.py new file mode 100644 index 000000000000..9e37024d118f --- /dev/null +++ b/buildroot/share/PlatformIO/scripts/SAMD51_grandcentral_m4.py @@ -0,0 +1,19 @@ +# +# SAMD51_grandcentral_m4.py +# Customizations for env:SAMD51_grandcentral_m4 +# +from os.path import join, isfile +import shutil +from pprint import pprint + +Import("env") + +mf = env["MARLIN_FEATURES"] +rxBuf = mf["RX_BUFFER_SIZE"] if "RX_BUFFER_SIZE" in mf else "0" +txBuf = mf["TX_BUFFER_SIZE"] if "TX_BUFFER_SIZE" in mf else "0" + +serialBuf = str(max(int(rxBuf), int(txBuf), 350)) + +build_flags = env.get('BUILD_FLAGS') +build_flags.append("-DSERIAL_BUFFER_SIZE=" + serialBuf) +env.Replace(BUILD_FLAGS=build_flags) diff --git a/buildroot/share/PlatformIO/scripts/STEVAL__F401XX.py b/buildroot/share/PlatformIO/scripts/STEVAL__F401XX.py deleted file mode 100644 index 580529c9c1a8..000000000000 --- a/buildroot/share/PlatformIO/scripts/STEVAL__F401XX.py +++ /dev/null @@ -1,9 +0,0 @@ -import os -Import("env") - -custom_ld_script = os.path.abspath("buildroot/share/PlatformIO/variants/STEVAL_F401VE/ldscript.ld") -for i, flag in enumerate(env["LINKFLAGS"]): - if "-Wl,-T" in flag: - env["LINKFLAGS"][i] = "-Wl,-T" + custom_ld_script - elif flag == "-T": - env["LINKFLAGS"][i + 1] = custom_ld_script diff --git a/buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py b/buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py index 547d80ace51c..03e121c435d3 100644 --- a/buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py +++ b/buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py @@ -1,3 +1,6 @@ +# +# buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py +# try: import configparser except ImportError: @@ -51,9 +54,5 @@ def after_upload(source, target, env): print('Use the {0:s} address as the marlin app entry point.'.format(vect_tab_addr)) print('Use the {0:d}KB flash version of stm32f103rct6 chip.'.format(flash_size)) -custom_ld_script = os.path.abspath("buildroot/share/PlatformIO/ldscripts/STM32F103RC_MEEB_3DP.ld") -for i, flag in enumerate(env["LINKFLAGS"]): - if "-Wl,-T" in flag: - env["LINKFLAGS"][i] = "-Wl,-T" + custom_ld_script - elif flag == "-T": - env["LINKFLAGS"][i + 1] = custom_ld_script +import marlin +marlin.custom_ld_script("STM32F103RC_MEEB_3DP.ld") diff --git a/buildroot/share/PlatformIO/scripts/STM32F103RC_SKR_MINI.py b/buildroot/share/PlatformIO/scripts/STM32F103RC_SKR_MINI.py deleted file mode 100644 index 497a035fdf4b..000000000000 --- a/buildroot/share/PlatformIO/scripts/STM32F103RC_SKR_MINI.py +++ /dev/null @@ -1,20 +0,0 @@ -import os -Import("env") - -STM32_FLASH_SIZE = 256 - -for define in env['CPPDEFINES']: - if define[0] == "VECT_TAB_ADDR": - env['CPPDEFINES'].remove(define) - if define[0] == "STM32_FLASH_SIZE": - STM32_FLASH_SIZE = define[1] - -# Relocate firmware from 0x08000000 to 0x08007000 -env['CPPDEFINES'].append(("VECT_TAB_ADDR", "0x08007000")) - -custom_ld_script = os.path.abspath("buildroot/share/PlatformIO/ldscripts/STM32F103RC_SKR_MINI_" + str(STM32_FLASH_SIZE) + "K.ld") -for i, flag in enumerate(env["LINKFLAGS"]): - if "-Wl,-T" in flag: - env["LINKFLAGS"][i] = "-Wl,-T" + custom_ld_script - elif flag == "-T": - env["LINKFLAGS"][i + 1] = custom_ld_script diff --git a/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py b/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py index b69f62578bd4..668475dc010a 100644 --- a/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py +++ b/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py @@ -1,27 +1,17 @@ +# +# buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py +# import os from os.path import join from os.path import expandvars Import("env") -# Relocate firmware from 0x08000000 to 0x08008000 -#for define in env['CPPDEFINES']: -# if define[0] == "VECT_TAB_ADDR": -# env['CPPDEFINES'].remove(define) -#env['CPPDEFINES'].append(("VECT_TAB_ADDR", "0x08008000")) - -#custom_ld_script = os.path.abspath("buildroot/share/PlatformIO/ldscripts/fysetc_stm32f103rc.ld") -#for i, flag in enumerate(env["LINKFLAGS"]): -# if "-Wl,-T" in flag: -# env["LINKFLAGS"][i] = "-Wl,-T" + custom_ld_script -# elif flag == "-T": -# env["LINKFLAGS"][i + 1] = custom_ld_script - # Custom HEX from ELF env.AddPostAction( - join("$BUILD_DIR","${PROGNAME}.elf"), + join("$BUILD_DIR", "${PROGNAME}.elf"), env.VerboseAction(" ".join([ - "$OBJCOPY", "-O ihex", "$TARGET", # TARGET=.pio/build/fysetc_STM32F1/firmware.elf - "\"" + join("$BUILD_DIR","${PROGNAME}.hex") + "\"", # Note: $BUILD_DIR is a full path + "$OBJCOPY", "-O ihex", "$TARGET", + "\"" + join("$BUILD_DIR", "${PROGNAME}.hex") + "\"", # Note: $BUILD_DIR is a full path ]), "Building $TARGET")) # In-line command with arguments diff --git a/buildroot/share/PlatformIO/scripts/STM32F103RE_SKR_E3_DIP.py b/buildroot/share/PlatformIO/scripts/STM32F103RE_SKR_E3_DIP.py deleted file mode 100644 index ecdd57f594e8..000000000000 --- a/buildroot/share/PlatformIO/scripts/STM32F103RE_SKR_E3_DIP.py +++ /dev/null @@ -1,16 +0,0 @@ -import os -Import("env") - -for define in env['CPPDEFINES']: - if define[0] == "VECT_TAB_ADDR": - env['CPPDEFINES'].remove(define) - -# Relocate firmware from 0x08000000 to 0x08007000 -env['CPPDEFINES'].append(("VECT_TAB_ADDR", "0x08007000")) - -custom_ld_script = os.path.abspath("buildroot/share/PlatformIO/ldscripts/STM32F103RE_SKR_E3_DIP.ld") -for i, flag in enumerate(env["LINKFLAGS"]): - if "-Wl,-T" in flag: - env["LINKFLAGS"][i] = "-Wl,-T" + custom_ld_script - elif flag == "-T": - env["LINKFLAGS"][i + 1] = custom_ld_script diff --git a/buildroot/share/PlatformIO/scripts/STM32F103VE_longer.py b/buildroot/share/PlatformIO/scripts/STM32F103VE_longer.py deleted file mode 100644 index ece47ed09601..000000000000 --- a/buildroot/share/PlatformIO/scripts/STM32F103VE_longer.py +++ /dev/null @@ -1,33 +0,0 @@ -import os -Import("env") - -# Relocate firmware from 0x08000000 to 0x08010000 -for define in env['CPPDEFINES']: - if define[0] == "VECT_TAB_ADDR": - env['CPPDEFINES'].remove(define) -env['CPPDEFINES'].append(("VECT_TAB_ADDR", "0x08010000")) - -custom_ld_script = os.path.abspath("buildroot/share/PlatformIO/ldscripts/STM32F103VE_longer.ld") -for i, flag in enumerate(env["LINKFLAGS"]): - if "-Wl,-T" in flag: - env["LINKFLAGS"][i] = "-Wl,-T" + custom_ld_script - elif flag == "-T": - env["LINKFLAGS"][i + 1] = custom_ld_script - - -# Rename ${PROGNAME}.bin and save it as 'project.bin' (No encryption on the Longer3D) -def encrypt(source, target, env): - firmware = open(target[0].path, "rb") - marlin_alfa = open(target[0].dir.path +'/project.bin', "wb") - length = os.path.getsize(target[0].path) - position = 0 - try: - while position < length: - byte = firmware.read(1) - marlin_alfa.write(byte) - position += 1 - finally: - firmware.close() - marlin_alfa.close() - -env.AddPostAction("$BUILD_DIR/${PROGNAME}.bin", encrypt); diff --git a/buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py b/buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py index 4849f59ceb03..0a38e1ceee9d 100644 --- a/buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py +++ b/buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py @@ -1,28 +1,24 @@ -import os,shutil +# +# STM32F1_create_variant.py +# +import os,shutil,marlin from SCons.Script import DefaultEnvironment from platformio import util -def copytree(src, dst, symlinks=False, ignore=None): - for item in os.listdir(src): - s = os.path.join(src, item) - d = os.path.join(dst, item) - if os.path.isdir(s): - shutil.copytree(s, d, symlinks, ignore) - else: - shutil.copy2(s, d) - env = DefaultEnvironment() platform = env.PioPlatform() board = env.BoardConfig() FRAMEWORK_DIR = platform.get_package_dir("framework-arduinoststm32-maple") assert os.path.isdir(FRAMEWORK_DIR) -assert os.path.isdir("buildroot/share/PlatformIO/variants") + +source_root = os.path.join("buildroot", "share", "PlatformIO", "variants") +assert os.path.isdir(source_root) variant = board.get("build.variant") variant_dir = os.path.join(FRAMEWORK_DIR, "STM32F1", "variants", variant) -source_dir = os.path.join("buildroot/share/PlatformIO/variants", variant) +source_dir = os.path.join(source_root, variant) assert os.path.isdir(source_dir) if os.path.isdir(variant_dir): @@ -31,4 +27,4 @@ def copytree(src, dst, symlinks=False, ignore=None): if not os.path.isdir(variant_dir): os.mkdir(variant_dir) -copytree(source_dir, variant_dir) +marlin.copytree(source_dir, variant_dir) diff --git a/buildroot/share/PlatformIO/scripts/add_nanolib.py b/buildroot/share/PlatformIO/scripts/add_nanolib.py new file mode 100644 index 000000000000..3b74b0d2714d --- /dev/null +++ b/buildroot/share/PlatformIO/scripts/add_nanolib.py @@ -0,0 +1,5 @@ +# +# add_nanolib.py +# +Import("env") +env.Append(LINKFLAGS=["--specs=nano.specs"]) diff --git a/buildroot/share/PlatformIO/scripts/chitu_crypt.py b/buildroot/share/PlatformIO/scripts/chitu_crypt.py index aa675878e70e..23d81c1721f9 100644 --- a/buildroot/share/PlatformIO/scripts/chitu_crypt.py +++ b/buildroot/share/PlatformIO/scripts/chitu_crypt.py @@ -1,20 +1,11 @@ -Import("env") -import os -import random -import struct -import uuid +# +# buildroot/share/PlatformIO/scripts/chitu_crypt.py +# Customizations for Chitu boards +# +import os,random,struct,uuid,marlin # Relocate firmware from 0x08000000 to 0x08008800 -env['CPPDEFINES'].remove(("VECT_TAB_ADDR", "0x8000000")) -env['CPPDEFINES'].append(("VECT_TAB_ADDR", "0x08008800")) - -custom_ld_script = os.path.abspath("buildroot/share/PlatformIO/ldscripts/chitu_f103.ld") -for i, flag in enumerate(env["LINKFLAGS"]): - if "-Wl,-T" in flag: - env["LINKFLAGS"][i] = "-Wl,-T" + custom_ld_script - elif flag == "-T": - env["LINKFLAGS"][i + 1] = custom_ld_script - +marlin.relocate_firmware("0x08008800") def calculate_crc(contents, seed): accumulating_xor_value = seed; @@ -42,7 +33,7 @@ def xor_block(r0, r1, block_number, block_size, file_key): for loop_counter in range(0, block_size): # meant to make sure different bits of the key are used. - xor_seed = int(loop_counter/key_length) + xor_seed = int(loop_counter / key_length) # IP is a scratch register / R12 ip = loop_counter - (key_length * xor_seed) @@ -68,7 +59,6 @@ def xor_block(r0, r1, block_number, block_size, file_key): #increment the loop_counter loop_counter = loop_counter + 1 - def encrypt_file(input, output_file, file_length): input_file = bytearray(input.read()) block_size = 0x800 @@ -112,11 +102,10 @@ def encrypt_file(input, output_file, file_length): output_file.write(input_file) return - # Encrypt ${PROGNAME}.bin and save it as 'update.cbd' def encrypt(source, target, env): firmware = open(target[0].path, "rb") - update = open(target[0].dir.path +'/update.cbd', "wb") + update = open(target[0].dir.path + '/update.cbd', "wb") length = os.path.getsize(target[0].path) encrypt_file(firmware, update, length) @@ -124,4 +113,4 @@ def encrypt(source, target, env): firmware.close() update.close() -env.AddPostAction("$BUILD_DIR/${PROGNAME}.bin", encrypt); +marlin.add_post_action(encrypt); diff --git a/buildroot/share/PlatformIO/scripts/common-cxxflags.py b/buildroot/share/PlatformIO/scripts/common-cxxflags.py index 3e75434ee78c..856a246fba76 100644 --- a/buildroot/share/PlatformIO/scripts/common-cxxflags.py +++ b/buildroot/share/PlatformIO/scripts/common-cxxflags.py @@ -10,3 +10,25 @@ #"-Wno-maybe-uninitialized", #"-Wno-sign-compare" ]) + +# +# Add CPU frequency as a compile time constant instead of a runtime variable +# +def add_cpu_freq(): + if 'BOARD_F_CPU' in env: + env['BUILD_FLAGS'].append('-DBOARD_F_CPU=' + env['BOARD_F_CPU']) + +# Useful for JTAG debugging +# +# It will separate release and debug build folders. +# It useful to keep two live versions: a debug version for debugging and another for +# release, for flashing when upload is not done automatically by jlink/stlink. +# Without this, PIO needs to recompile everything twice for any small change. +if env.GetBuildType() == "debug" and env.get('UPLOAD_PROTOCOL') not in ['jlink', 'stlink']: + env['BUILD_DIR'] = '$PROJECT_BUILD_DIR/$PIOENV/debug' + +# On some platform, F_CPU is a runtime variable. Since it's used to convert from ns +# to CPU cycles, this adds overhead preventing small delay (in the order of less than +# 30 cycles) to be generated correctly. By using a compile time constant instead +# the compiler will perform the computation and this overhead will be avoided +add_cpu_freq() diff --git a/buildroot/share/PlatformIO/scripts/common-dependencies.h b/buildroot/share/PlatformIO/scripts/common-dependencies.h index c96907bb3ff1..a88e7084670b 100644 --- a/buildroot/share/PlatformIO/scripts/common-dependencies.h +++ b/buildroot/share/PlatformIO/scripts/common-dependencies.h @@ -26,8 +26,6 @@ * Used by common-dependencies.py */ -#define NUM_SERIAL 1 // Normally provided by HAL/HAL.h - #include "../../../../Marlin/src/inc/MarlinConfig.h" // @@ -37,7 +35,9 @@ // Feature checks for SR_LCD_3W_NL #elif EITHER(LCD_I2C_TYPE_MCP23017, LCD_I2C_TYPE_MCP23008) #define USES_LIQUIDTWI2 -#elif ANY(HAS_MARLINUI_HD44780, LCD_I2C_TYPE_PCF8575, LCD_I2C_TYPE_PCA8574, SR_LCD_2W_NL, LCM1602) +#elif ENABLED(LCD_I2C_TYPE_PCA8574) + #define USES_LIQUIDCRYSTAL_I2C +#elif ANY(HAS_MARLINUI_HD44780, LCD_I2C_TYPE_PCF8575, SR_LCD_2W_NL, LCM1602) #define USES_LIQUIDCRYSTAL #endif @@ -49,10 +49,6 @@ #define HAS_GCODE_M876 #endif -#if EXTRUDERS - #define HAS_EXTRUDERS -#endif - #if ENABLED(DUET_SMART_EFFECTOR) && PIN_EXISTS(SMART_EFFECTOR_MOD) #define HAS_SMART_EFF_MOD #endif @@ -67,9 +63,6 @@ #if ENABLED(CANCEL_OBJECTS) #define HAS_MENU_CANCELOBJECT #endif - #if ENABLED(CUSTOM_USER_MENUS) - #define HAS_MENU_CUSTOM - #endif #if EITHER(DELTA_CALIBRATION_MENU, DELTA_AUTO_CALIBRATION) #define HAS_MENU_DELTA_CALIBRATE #endif @@ -109,6 +102,9 @@ #if ENABLED(TOUCH_SCREEN_CALIBRATION) #define HAS_MENU_TOUCH_SCREEN #endif + #if ENABLED(ASSISTED_TRAMMING_WIZARD) + #define HAS_MENU_TRAMMING + #endif #if ENABLED(AUTO_BED_LEVELING_UBL) #define HAS_MENU_UBL #endif diff --git a/buildroot/share/PlatformIO/scripts/common-dependencies.py b/buildroot/share/PlatformIO/scripts/common-dependencies.py index 4b4bba625874..83dfeca879ec 100644 --- a/buildroot/share/PlatformIO/scripts/common-dependencies.py +++ b/buildroot/share/PlatformIO/scripts/common-dependencies.py @@ -2,19 +2,34 @@ # common-dependencies.py # Convenience script to check dependencies and add libs and sources for Marlin Enabled Features # -import subprocess -import os -import re -try: - import configparser -except ImportError: - import ConfigParser as configparser +import subprocess,os,re + +PIO_VERSION_MIN = (5, 0, 3) try: - # PIO < 4.4 - from platformio.managers.package import PackageManager -except ImportError: - # PIO >= 4.4 - from platformio.package.meta import PackageSpec as PackageManager + from platformio import VERSION as PIO_VERSION + weights = (1000, 100, 1) + version_min = sum([x[0] * float(re.sub(r'[^0-9]', '.', str(x[1]))) for x in zip(weights, PIO_VERSION_MIN)]) + version_cur = sum([x[0] * float(re.sub(r'[^0-9]', '.', str(x[1]))) for x in zip(weights, PIO_VERSION)]) + if version_cur < version_min: + print() + print("**************************************************") + print("****** An update to PlatformIO is ******") + print("****** required to build Marlin Firmware. ******") + print("****** ******") + print("****** Minimum version: ", PIO_VERSION_MIN, " ******") + print("****** Current Version: ", PIO_VERSION, " ******") + print("****** ******") + print("****** Update PlatformIO and try again. ******") + print("**************************************************") + print() + exit(1) +except SystemExit: + exit(1) +except: + print("Can't detect PlatformIO Version") + +from platformio.package.meta import PackageSpec +from platformio.project.config import ProjectConfig Import("env") @@ -25,16 +40,9 @@ except: verbose = 0 -def blab(str): - if verbose: - print(str) - -def parse_pkg_uri(spec): - if PackageManager.__name__ == 'PackageSpec': - return PackageManager(spec).name - else: - name, _, _ = PackageManager.parse_pkg_uri(spec) - return name +def blab(str,level=1): + if verbose >= level: + print("[deps] %s" % str) FEATURE_CONFIG = {} @@ -45,21 +53,29 @@ def add_to_feat_cnf(feature, flines): except: FEATURE_CONFIG[feature] = {} + # Get a reference to the FEATURE_CONFIG under construction feat = FEATURE_CONFIG[feature] - atoms = re.sub(',\\s*', '\n', flines).strip().split('\n') - for dep in atoms: - parts = dep.split('=') + + # Split up passed lines on commas or newlines and iterate + # Add common options to the features config under construction + # For lib_deps replace a previous instance of the same library + atoms = re.sub(r',\\s*', '\n', flines).strip().split('\n') + for line in atoms: + parts = line.split('=') name = parts.pop(0) - rest = '='.join(parts) - if name in ['extra_scripts', 'src_filter', 'lib_ignore']: - feat[name] = rest + if name in ['build_flags', 'extra_scripts', 'src_filter', 'lib_ignore']: + feat[name] = '='.join(parts) + blab("[%s] %s=%s" % (feature, name, feat[name]), 3) else: - feat['lib_deps'] += [dep] + for dep in re.split(r",\s*", line): + lib_name = re.sub(r'@([~^]|[<>]=?)?[\d.]+', '', dep.strip()).split('=').pop(0) + lib_re = re.compile('(?!^' + lib_name + '\\b)') + feat['lib_deps'] = list(filter(lib_re.match, feat['lib_deps'])) + [dep] + blab("[%s] lib_deps = %s" % (feature, dep), 3) def load_config(): - config = configparser.ConfigParser() - config.read("platformio.ini") - items = config.items('features') + blab("========== Gather [features] entries...") + items = ProjectConfig().items('features') for key in items: feature = key[0].upper() if not feature in FEATURE_CONFIG: @@ -67,16 +83,20 @@ def load_config(): add_to_feat_cnf(feature, key[1]) # Add options matching custom_marlin.MY_OPTION to the pile + blab("========== Gather custom_marlin entries...") all_opts = env.GetProjectOptions() for n in all_opts: - mat = re.match(r'custom_marlin\.(.+)', n[0]) + key = n[0] + mat = re.match(r'custom_marlin\.(.+)', key) if mat: try: - val = env.GetProjectOption(n[0]) + val = env.GetProjectOption(key) except: val = None if val: - add_to_feat_cnf(mat.group(1).upper(), val) + opt = mat.group(1).upper() + blab("%s.custom_marlin.%s = '%s'" % ( env['PIOENV'], opt, val )) + add_to_feat_cnf(opt, val) def get_all_known_libs(): known_libs = [] @@ -85,16 +105,14 @@ def get_all_known_libs(): if not 'lib_deps' in feat: continue for dep in feat['lib_deps']: - name = parse_pkg_uri(dep) - known_libs.append(name) + known_libs.append(PackageSpec(dep).name) return known_libs def get_all_env_libs(): env_libs = [] lib_deps = env.GetProjectOption('lib_deps') for dep in lib_deps: - name = parse_pkg_uri(dep) - env_libs.append(name) + env_libs.append(PackageSpec(dep).name) return env_libs def set_env_field(field, value): @@ -108,12 +126,12 @@ def force_ignore_unused_libs(): known_libs = get_all_known_libs() diff = (list(set(known_libs) - set(env_libs))) lib_ignore = env.GetProjectOption('lib_ignore') + diff - if verbose: - print("Ignore libraries:", lib_ignore) + blab("Ignore libraries: %s" % lib_ignore) set_env_field('lib_ignore', lib_ignore) def apply_features_config(): load_config() + blab("========== Apply enabled features...") for feature in FEATURE_CONFIG: if not env.MarlinFeatureIsEnabled(feature): continue @@ -121,25 +139,25 @@ def apply_features_config(): feat = FEATURE_CONFIG[feature] if 'lib_deps' in feat and len(feat['lib_deps']): - blab("Adding lib_deps for %s... " % feature) + blab("========== Adding lib_deps for %s... " % feature, 2) # feat to add deps_to_add = {} for dep in feat['lib_deps']: - name = parse_pkg_uri(dep) - deps_to_add[name] = dep + deps_to_add[PackageSpec(dep).name] = dep + blab("==================== %s... " % dep, 2) # Does the env already have the dependency? deps = env.GetProjectOption('lib_deps') for dep in deps: - name = parse_pkg_uri(dep) + name = PackageSpec(dep).name if name in deps_to_add: del deps_to_add[name] # Are there any libraries that should be ignored? lib_ignore = env.GetProjectOption('lib_ignore') for dep in deps: - name = parse_pkg_uri(dep) + name = PackageSpec(dep).name if name in deps_to_add: del deps_to_add[name] @@ -148,16 +166,22 @@ def apply_features_config(): # Only add the missing dependencies set_env_field('lib_deps', deps + list(deps_to_add.values())) + if 'build_flags' in feat: + f = feat['build_flags'] + blab("========== Adding build_flags for %s: %s" % (feature, f), 2) + new_flags = env.GetProjectOption('build_flags') + [ f ] + env.Replace(BUILD_FLAGS=new_flags) + if 'extra_scripts' in feat: - blab("Running extra_scripts for %s... " % feature) + blab("Running extra_scripts for %s... " % feature, 2) env.SConscript(feat['extra_scripts'], exports="env") if 'src_filter' in feat: - blab("Adding src_filter for %s... " % feature) + blab("========== Adding src_filter for %s... " % feature, 2) src_filter = ' '.join(env.GetProjectOption('src_filter')) # first we need to remove the references to the same folder - my_srcs = re.findall( r'[+-](<.*?>)', feat['src_filter']) - cur_srcs = re.findall( r'[+-](<.*?>)', src_filter) + my_srcs = re.findall(r'[+-](<.*?>)', feat['src_filter']) + cur_srcs = re.findall(r'[+-](<.*?>)', src_filter) for d in my_srcs: if d in cur_srcs: src_filter = re.sub(r'[+-]' + d, '', src_filter) @@ -167,7 +191,7 @@ def apply_features_config(): env.Replace(SRC_FILTER=src_filter) if 'lib_ignore' in feat: - blab("Adding lib_ignore for %s... " % feature) + blab("========== Adding lib_ignore for %s... " % feature, 2) lib_ignore = env.GetProjectOption('lib_ignore') + [feat['lib_ignore']] set_env_field('lib_ignore', lib_ignore) @@ -179,20 +203,25 @@ def apply_features_config(): def search_compiler(): try: filepath = env.GetProjectOption('custom_gcc') - blab('Getting compiler from env') + blab("Getting compiler from env") return filepath except: pass if os.path.exists(GCC_PATH_CACHE): - blab('Getting g++ path from cache') with open(GCC_PATH_CACHE, 'r') as f: return f.read() # Find the current platform compiler by searching the $PATH # which will be in a platformio toolchain bin folder path_regex = re.escape(env['PROJECT_PACKAGES_DIR']) - gcc = "g++" + + # See if the environment provides a default compiler + try: + gcc = env.GetProjectOption('custom_deps_gcc') + except: + gcc = "g++" + if env['PLATFORM'] == 'win32': path_separator = ';' path_regex += r'.*\\bin' @@ -208,16 +237,18 @@ def search_compiler(): for filepath in os.listdir(pathdir): if not filepath.endswith(gcc): continue - + # Use entire path to not rely on env PATH + filepath = os.path.sep.join([pathdir, filepath]) # Cache the g++ path to no search always if os.path.exists(ENV_BUILD_PATH): - blab('Caching g++ for current env') with open(GCC_PATH_CACHE, 'w+') as f: f.write(filepath) return filepath filepath = env.get('CXX') + if filepath == 'CC': + filepath = gcc blab("Couldn't find a compiler! Fallback to %s" % filepath) return filepath @@ -233,7 +264,7 @@ def load_marlin_features(): build_flags = env.ParseFlagsExtended(build_flags) cxx = search_compiler() - cmd = [cxx] + cmd = ['"' + cxx + '"'] # Build flags from board.json #if 'BOARD' in env: @@ -246,7 +277,7 @@ def load_marlin_features(): cmd += ['-D__MARLIN_DEPS__ -w -dM -E -x c++ buildroot/share/PlatformIO/scripts/common-dependencies.h'] cmd = ' '.join(cmd) - blab(cmd) + blab(cmd, 4) define_list = subprocess.check_output(cmd, shell=True).splitlines() marlin_features = {} for define in define_list: diff --git a/buildroot/share/PlatformIO/scripts/copy_marlin_variant_to_framework.py b/buildroot/share/PlatformIO/scripts/copy_marlin_variant_to_framework.py deleted file mode 100644 index f7d3f0d03ab7..000000000000 --- a/buildroot/share/PlatformIO/scripts/copy_marlin_variant_to_framework.py +++ /dev/null @@ -1,58 +0,0 @@ -import os,shutil -from SCons.Script import DefaultEnvironment -from platformio import util -try: - # PIO < 4.4 - from platformio.managers.package import PackageManager -except ImportError: - # PIO >= 4.4 - from platformio.package.meta import PackageSpec as PackageManager - -def parse_pkg_uri(spec): - if PackageManager.__name__ == 'PackageSpec': - return PackageManager(spec).name - else: - name, _, _ = PackageManager.parse_pkg_uri(spec) - return name - -def copytree(src, dst, symlinks=False, ignore=None): - for item in os.listdir(src): - s = os.path.join(src, item) - d = os.path.join(dst, item) - if os.path.isdir(s): - shutil.copytree(s, d, symlinks, ignore) - else: - shutil.copy2(s, d) - -env = DefaultEnvironment() -platform = env.PioPlatform() -board = env.BoardConfig() -variant = board.get("build.variant") - -platform_packages = env.GetProjectOption('platform_packages') -# if there's no framework defined, take it from the class name of platform -framewords = { - "Ststm32Platform": "framework-arduinoststm32", - "AtmelavrPlatform": "framework-arduino-avr" -} -if len(platform_packages) == 0: - platform_name = framewords[platform.__class__.__name__] -else: - platform_name = parse_pkg_uri(platform_packages[0]) - -FRAMEWORK_DIR = platform.get_package_dir(platform_name) -assert os.path.isdir(FRAMEWORK_DIR) -assert os.path.isdir("buildroot/share/PlatformIO/variants") - -variant_dir = os.path.join(FRAMEWORK_DIR, "variants", variant) - -source_dir = os.path.join("buildroot/share/PlatformIO/variants", variant) -assert os.path.isdir(source_dir) - -if os.path.isdir(variant_dir): - shutil.rmtree(variant_dir) - -if not os.path.isdir(variant_dir): - os.mkdir(variant_dir) - -copytree(source_dir, variant_dir) diff --git a/buildroot/share/PlatformIO/scripts/creality.py b/buildroot/share/PlatformIO/scripts/creality.py deleted file mode 100644 index b9d7d7039bb4..000000000000 --- a/buildroot/share/PlatformIO/scripts/creality.py +++ /dev/null @@ -1,17 +0,0 @@ -import os -Import("env") - -# Relocate firmware from 0x08000000 to 0x08007000 -for define in env['CPPDEFINES']: - if define[0] == "VECT_TAB_ADDR": - env['CPPDEFINES'].remove(define) - -env['CPPDEFINES'].append(("VECT_TAB_ADDR", "0x08007000")) - -custom_ld_script = os.path.abspath("buildroot/share/PlatformIO/ldscripts/creality.ld") - -for i, flag in enumerate(env['LINKFLAGS']): - if "-Wl,-T" in flag: - env['LINKFLAGS'][i] = "-Wl,-T" + custom_ld_script - elif flag == "-T": - env['LINKFLAGS'][i + 1] = custom_ld_script diff --git a/buildroot/share/PlatformIO/scripts/custom_board.py b/buildroot/share/PlatformIO/scripts/custom_board.py new file mode 100644 index 000000000000..e462738190dd --- /dev/null +++ b/buildroot/share/PlatformIO/scripts/custom_board.py @@ -0,0 +1,16 @@ +# +# buildroot/share/PlatformIO/scripts/custom_board.py +# +# - For build.address replace VECT_TAB_ADDR to relocate the firmware +# - For build.ldscript use one of the linker scripts in buildroot/share/PlatformIO/ldscripts +# +import marlin +board = marlin.env.BoardConfig() + +address = board.get("build.address", "") +if address: + marlin.relocate_firmware(address) + +ldscript = board.get("build.ldscript", "") +if ldscript: + marlin.custom_ld_script(ldscript) diff --git a/buildroot/share/PlatformIO/scripts/download_mks_assets.py b/buildroot/share/PlatformIO/scripts/download_mks_assets.py index ae2ce467e84a..e922fed2be11 100644 --- a/buildroot/share/PlatformIO/scripts/download_mks_assets.py +++ b/buildroot/share/PlatformIO/scripts/download_mks_assets.py @@ -1,9 +1,9 @@ +# +# buildroot/share/PlatformIO/scripts/download_mks_assets.py +# Added by HAS_TFT_LVGL_UI to download assets from Makerbase repo +# Import("env") -import os -import requests -import zipfile -import tempfile -import shutil +import os,requests,zipfile,tempfile,shutil url = "https://github.com/makerbase-mks/Mks-Robin-Nano-Marlin2.0-Firmware/archive/master.zip" zip_path = os.path.join(env.Dictionary("PROJECT_LIBDEPS_DIR"), "mks-assets.zip") diff --git a/buildroot/share/PlatformIO/scripts/exc.S b/buildroot/share/PlatformIO/scripts/exc.S new file mode 100644 index 000000000000..1db462bb2379 --- /dev/null +++ b/buildroot/share/PlatformIO/scripts/exc.S @@ -0,0 +1,104 @@ +/* ***************************************************************************** + * The MIT License + * + * Copyright (c) 2010 Perry Hung. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + * ****************************************************************************/ + +# On an exception, push a fake stack thread mode stack frame and redirect +# thread execution to a thread mode error handler + +# From RM008: +# The SP is decremented by eight words by the completion of the stack push. +# Figure 5-1 shows the contents of the stack after an exception pre-empts the +# current program flow. +# +# Old SP--> +# xPSR +# PC +# LR +# r12 +# r3 +# r2 +# r1 +# SP--> r0 + +.text +.globl __exc_nmi +.weak __exc_nmi +.globl __exc_hardfault +.weak __exc_hardfault +.globl __exc_memmanage +.weak __exc_memmanage +.globl __exc_busfault +.weak __exc_busfault +.globl __exc_usagefault +.weak __exc_usagefault + +.code 16 +.thumb_func +__exc_nmi: + mov r0, #1 + b __default_exc + +.thumb_func +__exc_hardfault: + mov r0, #2 + b __default_exc + +.thumb_func +__exc_memmanage: + mov r0, #3 + b __default_exc + +.thumb_func +__exc_busfault: + mov r0, #4 + b __default_exc + +.thumb_func +__exc_usagefault: + mov r0, #5 + b __default_exc + +.thumb_func +__default_exc: + ldr r2, NVIC_CCR @ Enable returning to thread mode even if there are + mov r1 ,#1 @ pending exceptions. See flag NONEBASETHRDENA. + str r1, [r2] + cpsid i @ Disable global interrupts + ldr r2, SYSTICK_CSR @ Disable systick handler + mov r1, #0 + str r1, [r2] + ldr r1, CPSR_MASK @ Set default CPSR + push {r1} + ldr r1, TARGET_PC @ Set target pc + push {r1} + sub sp, sp, #24 @ Don't care + ldr r1, EXC_RETURN @ Return to thread mode + mov lr, r1 + bx lr @ Exception exit + +.align 4 +CPSR_MASK: .word 0x61000000 +EXC_RETURN: .word 0xFFFFFFF9 +TARGET_PC: .word __error +NVIC_CCR: .word 0xE000ED14 @ NVIC configuration control register +SYSTICK_CSR: .word 0xE000E010 @ Systick control register diff --git a/buildroot/share/PlatformIO/scripts/fix_framework_weakness.py b/buildroot/share/PlatformIO/scripts/fix_framework_weakness.py new file mode 100644 index 000000000000..fa91b7bb7041 --- /dev/null +++ b/buildroot/share/PlatformIO/scripts/fix_framework_weakness.py @@ -0,0 +1,32 @@ +# +# fix_framework_weakness.py +# +from os.path import join, isfile +import shutil +from pprint import pprint + +Import("env") + +if env.MarlinFeatureIsEnabled("POSTMORTEM_DEBUGGING"): + FRAMEWORK_DIR = env.PioPlatform().get_package_dir("framework-arduinoststm32-maple") + patchflag_path = join(FRAMEWORK_DIR, ".exc-patching-done") + + # patch file only if we didn't do it before + if not isfile(patchflag_path): + print("Patching libmaple exception handlers") + original_file = join(FRAMEWORK_DIR, "STM32F1", "cores", "maple", "libmaple", "exc.S") + backup_file = join(FRAMEWORK_DIR, "STM32F1", "cores", "maple", "libmaple", "exc.S.bak") + src_file = join("buildroot", "share", "PlatformIO", "scripts", "exc.S") + + assert isfile(original_file) and isfile(src_file) + shutil.copyfile(original_file, backup_file) + shutil.copyfile(src_file, original_file); + + def _touch(path): + with open(path, "w") as fp: + fp.write("") + + env.Execute(lambda *args, **kwargs: _touch(patchflag_path)) + print("Done patching exception handler") + + print("Libmaple modified and ready for post mortem debugging") diff --git a/buildroot/share/PlatformIO/scripts/fly_mini.py b/buildroot/share/PlatformIO/scripts/fly_mini.py deleted file mode 100644 index 34d132958d6a..000000000000 --- a/buildroot/share/PlatformIO/scripts/fly_mini.py +++ /dev/null @@ -1,16 +0,0 @@ -import os -Import("env") - -# Relocate firmware from 0x08000000 to 0x08005000 -for define in env['CPPDEFINES']: - if define[0] == "VECT_TAB_ADDR": - env['CPPDEFINES'].remove(define) -env['CPPDEFINES'].append(("VECT_TAB_ADDR", "0x08005000")) - -custom_ld_script = os.path.abspath("buildroot/share/PlatformIO/ldscripts/fly_mini.ld") -for i, flag in enumerate(env["LINKFLAGS"]): - if "-Wl,-T" in flag: - env["LINKFLAGS"][i] = "-Wl,-T" + custom_ld_script - elif flag == "-T": - env["LINKFLAGS"][i + 1] = custom_ld_script - diff --git a/buildroot/share/PlatformIO/scripts/generic_create_variant.py b/buildroot/share/PlatformIO/scripts/generic_create_variant.py index 0b82c69f5a3f..7f76ef94262c 100644 --- a/buildroot/share/PlatformIO/scripts/generic_create_variant.py +++ b/buildroot/share/PlatformIO/scripts/generic_create_variant.py @@ -1,27 +1,54 @@ -import os,shutil +# +# generic_create_variant.py +# +# Copy one of the variants from buildroot/platformio/variants into +# the appropriate framework variants folder, so that its contents +# will be picked up by PlatformIO just like any other variant. +# +import os,shutil,marlin from SCons.Script import DefaultEnvironment from platformio import util env = DefaultEnvironment() + +# +# Get the platform name from the 'platform_packages' option, +# or look it up by the platform.class.name. +# platform = env.PioPlatform() -board = env.BoardConfig() -FRAMEWORK_DIR = platform.get_package_dir("framework-arduinoststm32") +from platformio.package.meta import PackageSpec +platform_packages = env.GetProjectOption('platform_packages') +if len(platform_packages) == 0: + framewords = { + "Ststm32Platform": "framework-arduinoststm32", + "AtmelavrPlatform": "framework-arduino-avr" + } + platform_name = framewords[platform.__class__.__name__] +else: + platform_name = PackageSpec(platform_packages[0]).name + +if platform_name in [ "usb-host-msc", "usb-host-msc-cdc-msc", "usb-host-msc-cdc-msc-2", "usb-host-msc-cdc-msc-3", "tool-stm32duino" ]: + platform_name = "framework-arduinoststm32" + +FRAMEWORK_DIR = platform.get_package_dir(platform_name) assert os.path.isdir(FRAMEWORK_DIR) -assert os.path.isdir("buildroot/share/PlatformIO/variants") -mcu_type = board.get("build.mcu")[:-2] +board = env.BoardConfig() + +#mcu_type = board.get("build.mcu")[:-2] variant = board.get("build.variant") -series = mcu_type[:7].upper() + "xx" +#series = mcu_type[:7].upper() + "xx" + +# Prepare a new empty folder at the destination variant_dir = os.path.join(FRAMEWORK_DIR, "variants", variant) +if os.path.isdir(variant_dir): + shutil.rmtree(variant_dir) +if not os.path.isdir(variant_dir): + os.mkdir(variant_dir) +# Source dir is a local variant sub-folder source_dir = os.path.join("buildroot/share/PlatformIO/variants", variant) assert os.path.isdir(source_dir) -if not os.path.isdir(variant_dir): - os.mkdir(variant_dir) - -for file_name in os.listdir(source_dir): - full_file_name = os.path.join(source_dir, file_name) - if os.path.isfile(full_file_name): - shutil.copy(full_file_name, 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 6c8a4f6034c2..a4001a240ca1 100644 --- a/buildroot/share/PlatformIO/scripts/jgaurora_a5s_a1_with_bootloader.py +++ b/buildroot/share/PlatformIO/scripts/jgaurora_a5s_a1_with_bootloader.py @@ -1,30 +1,21 @@ -import os -Import("env") +# +# buildroot/share/PlatformIO/scripts/jgaurora_a5s_a1_with_bootloader.py +# Customizations for env:jgaurora_a5s_a1 +# +import os,marlin -# Relocate firmware from 0x08000000 to 0x0800A000 -env['CPPDEFINES'].remove(("VECT_TAB_ADDR", "0x8000000")) -#alternatively, for STSTM <=5.1.0 use line below -#env['CPPDEFINES'].remove(("VECT_TAB_ADDR", 134217728)) -env['CPPDEFINES'].append(("VECT_TAB_ADDR", "0x0800A000")) - -custom_ld_script = os.path.abspath("buildroot/share/PlatformIO/ldscripts/jgaurora_a5s_a1.ld") -for i, flag in enumerate(env["LINKFLAGS"]): - if "-Wl,-T" in flag: - env["LINKFLAGS"][i] = "-Wl,-T" + custom_ld_script - elif flag == "-T": - env["LINKFLAGS"][i + 1] = custom_ld_script - -#append ${PROGNAME}.bin firmware after bootloader and save it as 'jgaurora_firmware.bin' -def addboot(source,target,env): +# Append ${PROGNAME}.bin firmware after bootloader and save it as 'jgaurora_firmware.bin' +def addboot(source, target, env): firmware = open(target[0].path, "rb") lengthfirmware = os.path.getsize(target[0].path) - bootloader_dir = "buildroot/share/PlatformIO/scripts/jgaurora_bootloader.bin" - bootloader = open(bootloader_dir, "rb") - lengthbootloader = os.path.getsize(bootloader_dir) - firmware_with_boothloader_dir = target[0].dir.path +'/firmware_with_bootloader.bin' - if os.path.exists(firmware_with_boothloader_dir): - os.remove(firmware_with_boothloader_dir) - firmwareimage = open(firmware_with_boothloader_dir, "wb") + bootloader_bin = "buildroot/share/PlatformIO/scripts/" + "jgaurora_bootloader.bin" + bootloader = open(bootloader_bin, "rb") + lengthbootloader = os.path.getsize(bootloader_bin) + + firmware_with_boothloader_bin = target[0].dir.path + '/firmware_with_bootloader.bin' + if os.path.exists(firmware_with_boothloader_bin): + os.remove(firmware_with_boothloader_bin) + firmwareimage = open(firmware_with_boothloader_bin, "wb") position = 0 while position < lengthbootloader: byte = bootloader.read(1) @@ -38,11 +29,11 @@ def addboot(source,target,env): bootloader.close() firmware.close() firmwareimage.close() - firmware_without_bootloader_dir = target[0].dir.path+'/firmware_for_sd_upload.bin' - if os.path.exists(firmware_without_bootloader_dir): - os.remove(firmware_without_bootloader_dir) - os.rename(target[0].path, firmware_without_bootloader_dir) - #os.rename(target[0].dir.path+'/firmware_with_bootloader.bin', target[0].dir.path+'/firmware.bin') -env.AddPostAction("$BUILD_DIR/${PROGNAME}.bin", addboot); + firmware_without_bootloader_bin = target[0].dir.path + '/firmware_for_sd_upload.bin' + if os.path.exists(firmware_without_bootloader_bin): + os.remove(firmware_without_bootloader_bin) + os.rename(target[0].path, firmware_without_bootloader_bin) + #os.rename(target[0].dir.path+'/firmware_with_bootloader.bin', target[0].dir.path+'/firmware.bin') +marlin.add_post_action(addboot); diff --git a/buildroot/share/PlatformIO/scripts/lerdge.py b/buildroot/share/PlatformIO/scripts/lerdge.py index fd934a127866..5c35c19e7df2 100644 --- a/buildroot/share/PlatformIO/scripts/lerdge.py +++ b/buildroot/share/PlatformIO/scripts/lerdge.py @@ -1,16 +1,16 @@ -import os,sys +# +# buildroot/share/PlatformIO/scripts/lerdge.py +# Customizations for Lerdge build environments: +# env:LERDGEX env:LERDGEX_usb_flash_drive +# env:LERDGES env:LERDGES_usb_flash_drive +# env:LERDGEK env:LERDGEK_usb_flash_drive +# +import os,marlin Import("env") from SCons.Script import DefaultEnvironment board = DefaultEnvironment().BoardConfig() -custom_ld_script = os.path.abspath("buildroot/share/PlatformIO/ldscripts/lerdge.ld") -for i, flag in enumerate(env["LINKFLAGS"]): - if "-Wl,-T" in flag: - env["LINKFLAGS"][i] = "-Wl,-T" + custom_ld_script - elif flag == "-T": - env["LINKFLAGS"][i + 1] = custom_ld_script - def encryptByte(byte): byte = 0xFF & ((byte << 6) | (byte >> 2)) i = 0x58 + byte @@ -27,20 +27,21 @@ def encrypt_file(input, output_file, file_length): output_file.write(input_file) return -# Encrypt ${PROGNAME}.bin and save it as build.firmware +# Encrypt ${PROGNAME}.bin and save it with the name given in build.encrypt def encrypt(source, target, env): - print("Encrypting to:", board.get("build.firmware")) + fwname = board.get("build.encrypt") + print("Encrypting %s to %s" % (target[0].path, fwname)) firmware = open(target[0].path, "rb") - result = open(target[0].dir.path + "/" + board.get("build.firmware"), "wb") + renamed = open(target[0].dir.path + "/" + fwname, "wb") length = os.path.getsize(target[0].path) - encrypt_file(firmware, result, length) + encrypt_file(firmware, renamed, length) firmware.close() - result.close() + renamed.close() -if 'firmware' in board.get("build").keys(): - env.AddPostAction("$BUILD_DIR/${PROGNAME}.bin", encrypt); +if 'encrypt' in board.get("build").keys(): + marlin.add_post_action(encrypt); else: - print("You need to define output file via board_build.firmware = 'filename' parameter") - exit(1); + print("LERDGE builds require output file via board_build.encrypt = 'filename' parameter") + exit(1); diff --git a/buildroot/share/PlatformIO/scripts/marlin.py b/buildroot/share/PlatformIO/scripts/marlin.py new file mode 100644 index 000000000000..3949037904bb --- /dev/null +++ b/buildroot/share/PlatformIO/scripts/marlin.py @@ -0,0 +1,69 @@ +# +# buildroot/share/PlatformIO/scripts/marlin.py +# Helper module with some commonly-used functions +# +import os,shutil + +from SCons.Script import DefaultEnvironment +env = DefaultEnvironment() + +from os.path import join + +def copytree(src, dst, symlinks=False, ignore=None): + for item in os.listdir(src): + s = join(src, item) + d = join(dst, item) + if os.path.isdir(s): + shutil.copytree(s, d, symlinks, ignore) + else: + shutil.copy2(s, d) + +def replace_define(field, value): + for define in env['CPPDEFINES']: + if define[0] == field: + env['CPPDEFINES'].remove(define) + env['CPPDEFINES'].append((field, value)) + +# Relocate the firmware to a new address, such as "0x08005000" +def relocate_firmware(address): + replace_define("VECT_TAB_ADDR", address) + +# Relocate the vector table with a new offset +def relocate_vtab(address): + replace_define("VECT_TAB_OFFSET", address) + +# Replace the existing -Wl,-T with the given ldscript path +def custom_ld_script(ldname): + apath = os.path.abspath("buildroot/share/PlatformIO/ldscripts/" + ldname) + for i, flag in enumerate(env["LINKFLAGS"]): + if "-Wl,-T" in flag: + env["LINKFLAGS"][i] = "-Wl,-T" + apath + elif flag == "-T": + env["LINKFLAGS"][i + 1] = apath + +# Encrypt ${PROGNAME}.bin and save it with a new name +# Called by specific encrypt() functions, mostly for MKS boards +def encrypt_mks(source, target, env, new_name): + import sys + + key = [0xA3, 0xBD, 0xAD, 0x0D, 0x41, 0x11, 0xBB, 0x8D, 0xDC, 0x80, 0x2D, 0xD0, 0xD2, 0xC4, 0x9B, 0x1E, 0x26, 0xEB, 0xE3, 0x33, 0x4A, 0x15, 0xE4, 0x0A, 0xB3, 0xB1, 0x3C, 0x93, 0xBB, 0xAF, 0xF7, 0x3E] + + firmware = open(target[0].path, "rb") + renamed = open(target[0].dir.path + "/" + new_name, "wb") + length = os.path.getsize(target[0].path) + position = 0 + try: + while position < length: + byte = firmware.read(1) + if position >= 320 and position < 31040: + byte = chr(ord(byte) ^ key[position & 31]) + if sys.version_info[0] > 2: + byte = bytes(byte, 'latin1') + renamed.write(byte) + position += 1 + finally: + firmware.close() + renamed.close() + +def add_post_action(action): + env.AddPostAction(join("$BUILD_DIR", "${PROGNAME}.bin"), action); diff --git a/buildroot/share/PlatformIO/scripts/mks_encrypt.py b/buildroot/share/PlatformIO/scripts/mks_encrypt.py deleted file mode 100644 index 0d53cdfbe934..000000000000 --- a/buildroot/share/PlatformIO/scripts/mks_encrypt.py +++ /dev/null @@ -1,32 +0,0 @@ -import os,sys -Import("env") - -from SCons.Script import DefaultEnvironment -board = DefaultEnvironment().BoardConfig() - -# Encrypt ${PROGNAME}.bin and save it as build.firmware ('Robin.bin') -def encrypt(source, target, env): - key = [0xA3, 0xBD, 0xAD, 0x0D, 0x41, 0x11, 0xBB, 0x8D, 0xDC, 0x80, 0x2D, 0xD0, 0xD2, 0xC4, 0x9B, 0x1E, 0x26, 0xEB, 0xE3, 0x33, 0x4A, 0x15, 0xE4, 0x0A, 0xB3, 0xB1, 0x3C, 0x93, 0xBB, 0xAF, 0xF7, 0x3E] - - firmware = open(target[0].path, "rb") - robin = open(target[0].dir.path +'/'+ board.get("build.firmware"), "wb") - length = os.path.getsize(target[0].path) - position = 0 - try: - while position < length: - byte = firmware.read(1) - if position >= 320 and position < 31040: - byte = chr(ord(byte) ^ key[position & 31]) - if sys.version_info[0] > 2: - byte = bytes(byte, 'latin1') - robin.write(byte) - position += 1 - finally: - firmware.close() - robin.close() - -if 'firmware' in board.get("build").keys(): - env.AddPostAction("$BUILD_DIR/${PROGNAME}.bin", encrypt); -else: - print("You need to define output file via board_build.firmware = 'filename' parameter", file=sys.stderr) - exit(1); diff --git a/buildroot/share/PlatformIO/scripts/mks_robin.py b/buildroot/share/PlatformIO/scripts/mks_robin.py index dd2342bf0df2..2dea7c615f79 100644 --- a/buildroot/share/PlatformIO/scripts/mks_robin.py +++ b/buildroot/share/PlatformIO/scripts/mks_robin.py @@ -1,39 +1,5 @@ -import os -Import("env") - -# Relocate firmware from 0x08000000 to 0x08007000 -for define in env['CPPDEFINES']: - if define[0] == "VECT_TAB_ADDR": - env['CPPDEFINES'].remove(define) -env['CPPDEFINES'].append(("VECT_TAB_ADDR", "0x08007000")) - -custom_ld_script = os.path.abspath("buildroot/share/PlatformIO/ldscripts/mks_robin.ld") -for i, flag in enumerate(env["LINKFLAGS"]): - if "-Wl,-T" in flag: - env["LINKFLAGS"][i] = "-Wl,-T" + custom_ld_script - elif flag == "-T": - env["LINKFLAGS"][i + 1] = custom_ld_script - -# Encrypt ${PROGNAME}.bin and save it as 'Robin.bin' -def encrypt(source, target, env): - import sys - - key = [0xA3, 0xBD, 0xAD, 0x0D, 0x41, 0x11, 0xBB, 0x8D, 0xDC, 0x80, 0x2D, 0xD0, 0xD2, 0xC4, 0x9B, 0x1E, 0x26, 0xEB, 0xE3, 0x33, 0x4A, 0x15, 0xE4, 0x0A, 0xB3, 0xB1, 0x3C, 0x93, 0xBB, 0xAF, 0xF7, 0x3E] - - firmware = open(target[0].path, "rb") - robin = open(target[0].dir.path +'/Robin.bin', "wb") - length = os.path.getsize(target[0].path) - position = 0 - try: - while position < length: - byte = firmware.read(1) - if position >= 320 and position < 31040: - byte = chr(ord(byte) ^ key[position & 31]) - if sys.version_info[0] > 2: - byte = bytes(byte, 'latin1') - robin.write(byte) - position += 1 - finally: - firmware.close() - robin.close() -env.AddPostAction("$BUILD_DIR/${PROGNAME}.bin", encrypt); +# +# buildroot/share/PlatformIO/scripts/mks_robin.py +# +import robin +robin.prepare("0x08007000", "mks_robin.ld", "Robin.bin") diff --git a/buildroot/share/PlatformIO/scripts/mks_robin_e3.py b/buildroot/share/PlatformIO/scripts/mks_robin_e3.py index 3af623cce0d7..6ddeccbf80f4 100644 --- a/buildroot/share/PlatformIO/scripts/mks_robin_e3.py +++ b/buildroot/share/PlatformIO/scripts/mks_robin_e3.py @@ -1,40 +1,5 @@ -import os -Import("env") - -# Relocate firmware from 0x08000000 to 0x08005000 -for define in env['CPPDEFINES']: - if define[0] == "VECT_TAB_ADDR": - env['CPPDEFINES'].remove(define) -env['CPPDEFINES'].append(("VECT_TAB_ADDR", "0x08005000")) - -custom_ld_script = os.path.abspath("buildroot/share/PlatformIO/ldscripts/mks_robin_e3.ld") -for i, flag in enumerate(env["LINKFLAGS"]): - if "-Wl,-T" in flag: - env["LINKFLAGS"][i] = "-Wl,-T" + custom_ld_script - elif flag == "-T": - env["LINKFLAGS"][i + 1] = custom_ld_script - - -# Encrypt ${PROGNAME}.bin and save it as 'mksLite.bin' -def encrypt(source, target, env): - import sys - - key = [0xA3, 0xBD, 0xAD, 0x0D, 0x41, 0x11, 0xBB, 0x8D, 0xDC, 0x80, 0x2D, 0xD0, 0xD2, 0xC4, 0x9B, 0x1E, 0x26, 0xEB, 0xE3, 0x33, 0x4A, 0x15, 0xE4, 0x0A, 0xB3, 0xB1, 0x3C, 0x93, 0xBB, 0xAF, 0xF7, 0x3E] - - firmware = open(target[0].path, "rb") - robin = open(target[0].dir.path +'/Robin_e3.bin', "wb") - length = os.path.getsize(target[0].path) - position = 0 - try: - while position < length: - byte = firmware.read(1) - if position >= 320 and position < 31040: - byte = chr(ord(byte) ^ key[position & 31]) - if sys.version_info[0] > 2: - byte = bytes(byte, 'latin1') - robin.write(byte) - position += 1 - finally: - firmware.close() - robin.close() -env.AddPostAction("$BUILD_DIR/${PROGNAME}.bin", encrypt); +# +# buildroot/share/PlatformIO/scripts/mks_robin_e3.py +# +import robin +robin.prepare("0x08005000", "mks_robin_e3.ld", "Robin_e3.bin") diff --git a/buildroot/share/PlatformIO/scripts/mks_robin_e3p.py b/buildroot/share/PlatformIO/scripts/mks_robin_e3p.py index 2aab14bab788..5eeb93c09663 100644 --- a/buildroot/share/PlatformIO/scripts/mks_robin_e3p.py +++ b/buildroot/share/PlatformIO/scripts/mks_robin_e3p.py @@ -1,40 +1,5 @@ -import os -Import("env") - -# Relocate firmware from 0x08000000 to 0x08007000 -for define in env['CPPDEFINES']: - if define[0] == "VECT_TAB_ADDR": - env['CPPDEFINES'].remove(define) -env['CPPDEFINES'].append(("VECT_TAB_ADDR", "0x08007000")) - -custom_ld_script = os.path.abspath("buildroot/share/PlatformIO/ldscripts/mks_robin_e3p.ld") -for i, flag in enumerate(env["LINKFLAGS"]): - if "-Wl,-T" in flag: - env["LINKFLAGS"][i] = "-Wl,-T" + custom_ld_script - elif flag == "-T": - env["LINKFLAGS"][i + 1] = custom_ld_script - - -# Encrypt ${PROGNAME}.bin and save it as 'mks_robin_e3p.bin' -def encrypt(source, target, env): - import sys - - key = [0xA3, 0xBD, 0xAD, 0x0D, 0x41, 0x11, 0xBB, 0x8D, 0xDC, 0x80, 0x2D, 0xD0, 0xD2, 0xC4, 0x9B, 0x1E, 0x26, 0xEB, 0xE3, 0x33, 0x4A, 0x15, 0xE4, 0x0A, 0xB3, 0xB1, 0x3C, 0x93, 0xBB, 0xAF, 0xF7, 0x3E] - - firmware = open(target[0].path, "rb") - robin = open(target[0].dir.path +'/Robin_e3p.bin', "wb") - length = os.path.getsize(target[0].path) - position = 0 - try: - while position < length: - byte = firmware.read(1) - if position >= 320 and position < 31040: - byte = chr(ord(byte) ^ key[position & 31]) - if sys.version_info[0] > 2: - byte = bytes(byte, 'latin1') - robin.write(byte) - position += 1 - finally: - firmware.close() - robin.close() -env.AddPostAction("$BUILD_DIR/${PROGNAME}.bin", encrypt); +# +# buildroot/share/PlatformIO/scripts/mks_robin_e3p.py +# +import robin +robin.prepare("0x08007000", "mks_robin_e3p.ld", "Robin_e3p.bin") diff --git a/buildroot/share/PlatformIO/scripts/mks_robin_lite.py b/buildroot/share/PlatformIO/scripts/mks_robin_lite.py index 2f3ae1fa9a17..c2018336fd1f 100644 --- a/buildroot/share/PlatformIO/scripts/mks_robin_lite.py +++ b/buildroot/share/PlatformIO/scripts/mks_robin_lite.py @@ -1,40 +1,5 @@ -import os -Import("env") - -# Relocate firmware from 0x08000000 to 0x08005000 -for define in env['CPPDEFINES']: - if define[0] == "VECT_TAB_ADDR": - env['CPPDEFINES'].remove(define) -env['CPPDEFINES'].append(("VECT_TAB_ADDR", "0x08005000")) - -custom_ld_script = os.path.abspath("buildroot/share/PlatformIO/ldscripts/mks_robin_lite.ld") -for i, flag in enumerate(env["LINKFLAGS"]): - if "-Wl,-T" in flag: - env["LINKFLAGS"][i] = "-Wl,-T" + custom_ld_script - elif flag == "-T": - env["LINKFLAGS"][i + 1] = custom_ld_script - - -# Encrypt ${PROGNAME}.bin and save it as 'mksLite.bin' -def encrypt(source, target, env): - import sys - - key = [0xA3, 0xBD, 0xAD, 0x0D, 0x41, 0x11, 0xBB, 0x8D, 0xDC, 0x80, 0x2D, 0xD0, 0xD2, 0xC4, 0x9B, 0x1E, 0x26, 0xEB, 0xE3, 0x33, 0x4A, 0x15, 0xE4, 0x0A, 0xB3, 0xB1, 0x3C, 0x93, 0xBB, 0xAF, 0xF7, 0x3E] - - firmware = open(target[0].path, "rb") - robin = open(target[0].dir.path +'/mksLite.bin', "wb") - length = os.path.getsize(target[0].path) - position = 0 - try: - while position < length: - byte = firmware.read(1) - if position >= 320 and position < 31040: - byte = chr(ord(byte) ^ key[position & 31]) - if sys.version_info[0] > 2: - byte = bytes(byte, 'latin1') - robin.write(byte) - position += 1 - finally: - firmware.close() - robin.close() -env.AddPostAction("$BUILD_DIR/${PROGNAME}.bin", encrypt); +# +# buildroot/share/PlatformIO/scripts/mks_robin_lite.py +# +import robin +robin.prepare("0x08005000", "mks_robin_lite.ld", "mksLite.bin") diff --git a/buildroot/share/PlatformIO/scripts/mks_robin_lite3.py b/buildroot/share/PlatformIO/scripts/mks_robin_lite3.py index 67ad442d8212..42c8fb18b691 100644 --- a/buildroot/share/PlatformIO/scripts/mks_robin_lite3.py +++ b/buildroot/share/PlatformIO/scripts/mks_robin_lite3.py @@ -1,40 +1,5 @@ -import os -Import("env") - -# Relocate firmware from 0x08000000 to 0x08005000 -for define in env['CPPDEFINES']: - if define[0] == "VECT_TAB_ADDR": - env['CPPDEFINES'].remove(define) -env['CPPDEFINES'].append(("VECT_TAB_ADDR", "0x08005000")) - -custom_ld_script = os.path.abspath("buildroot/share/PlatformIO/ldscripts/mks_robin_lite.ld") -for i, flag in enumerate(env["LINKFLAGS"]): - if "-Wl,-T" in flag: - env["LINKFLAGS"][i] = "-Wl,-T" + custom_ld_script - elif flag == "-T": - env["LINKFLAGS"][i + 1] = custom_ld_script - - -# Encrypt ${PROGNAME}.bin and save it as 'mksLite.bin' -def encrypt(source, target, env): - import sys - - key = [0xA3, 0xBD, 0xAD, 0x0D, 0x41, 0x11, 0xBB, 0x8D, 0xDC, 0x80, 0x2D, 0xD0, 0xD2, 0xC4, 0x9B, 0x1E, 0x26, 0xEB, 0xE3, 0x33, 0x4A, 0x15, 0xE4, 0x0A, 0xB3, 0xB1, 0x3C, 0x93, 0xBB, 0xAF, 0xF7, 0x3E] - - firmware = open(target[0].path, "rb") - robin = open(target[0].dir.path +'/mksLite3.bin', "wb") - length = os.path.getsize(target[0].path) - position = 0 - try: - while position < length: - byte = firmware.read(1) - if position >= 320 and position < 31040: - byte = chr(ord(byte) ^ key[position & 31]) - if sys.version_info[0] > 2: - byte = bytes(byte, 'latin1') - robin.write(byte) - position += 1 - finally: - firmware.close() - robin.close() -env.AddPostAction("$BUILD_DIR/${PROGNAME}.bin", encrypt); +# +# buildroot/share/PlatformIO/scripts/mks_robin_lite3.py +# +import robin +robin.prepare("0x08005000", "mks_robin_lite.ld", "mksLite3.bin") diff --git a/buildroot/share/PlatformIO/scripts/mks_robin_mini.py b/buildroot/share/PlatformIO/scripts/mks_robin_mini.py old mode 100755 new mode 100644 index d38669830158..b0d83886533a --- a/buildroot/share/PlatformIO/scripts/mks_robin_mini.py +++ b/buildroot/share/PlatformIO/scripts/mks_robin_mini.py @@ -1,40 +1,5 @@ -import os -Import("env") - -# Relocate firmware from 0x08000000 to 0x08007000 -for define in env['CPPDEFINES']: - if define[0] == "VECT_TAB_ADDR": - env['CPPDEFINES'].remove(define) -env['CPPDEFINES'].append(("VECT_TAB_ADDR", "0x08007000")) - -custom_ld_script = os.path.abspath("buildroot/share/PlatformIO/ldscripts/mks_robin_mini.ld") -for i, flag in enumerate(env["LINKFLAGS"]): - if "-Wl,-T" in flag: - env["LINKFLAGS"][i] = "-Wl,-T" + custom_ld_script - elif flag == "-T": - env["LINKFLAGS"][i + 1] = custom_ld_script - - -# Encrypt ${PROGNAME}.bin and save it as 'Robin_mini.bin' -def encrypt(source, target, env): - import sys - - key = [0xA3, 0xBD, 0xAD, 0x0D, 0x41, 0x11, 0xBB, 0x8D, 0xDC, 0x80, 0x2D, 0xD0, 0xD2, 0xC4, 0x9B, 0x1E, 0x26, 0xEB, 0xE3, 0x33, 0x4A, 0x15, 0xE4, 0x0A, 0xB3, 0xB1, 0x3C, 0x93, 0xBB, 0xAF, 0xF7, 0x3E] - - firmware = open(target[0].path, "rb") - robin = open(target[0].dir.path +'/Robin_mini.bin', "wb") - length = os.path.getsize(target[0].path) - position = 0 - try: - while position < length: - byte = firmware.read(1) - if position >= 320 and position < 31040: - byte = chr(ord(byte) ^ key[position & 31]) - if sys.version_info[0] > 2: - byte = bytes(byte, 'latin1') - robin.write(byte) - position += 1 - finally: - firmware.close() - robin.close() -env.AddPostAction("$BUILD_DIR/${PROGNAME}.bin", encrypt); +# +# buildroot/share/PlatformIO/scripts/mks_robin_mini.py +# +import robin +robin.prepare("0x08007000", "mks_robin_mini.ld", "Robin_mini.bin") diff --git a/buildroot/share/PlatformIO/scripts/mks_robin_nano.py b/buildroot/share/PlatformIO/scripts/mks_robin_nano.py old mode 100755 new mode 100644 index a68fd308d443..35e99830c4df --- a/buildroot/share/PlatformIO/scripts/mks_robin_nano.py +++ b/buildroot/share/PlatformIO/scripts/mks_robin_nano.py @@ -1,40 +1,5 @@ -import os -Import("env") - -# Relocate firmware from 0x08000000 to 0x08007000 -for define in env['CPPDEFINES']: - if define[0] == "VECT_TAB_ADDR": - env['CPPDEFINES'].remove(define) -env['CPPDEFINES'].append(("VECT_TAB_ADDR", "0x08007000")) - -custom_ld_script = os.path.abspath("buildroot/share/PlatformIO/ldscripts/mks_robin_nano.ld") -for i, flag in enumerate(env["LINKFLAGS"]): - if "-Wl,-T" in flag: - env["LINKFLAGS"][i] = "-Wl,-T" + custom_ld_script - elif flag == "-T": - env["LINKFLAGS"][i + 1] = custom_ld_script - - -# Encrypt ${PROGNAME}.bin and save it as 'Robin_nano.bin' -def encrypt(source, target, env): - import sys - - key = [0xA3, 0xBD, 0xAD, 0x0D, 0x41, 0x11, 0xBB, 0x8D, 0xDC, 0x80, 0x2D, 0xD0, 0xD2, 0xC4, 0x9B, 0x1E, 0x26, 0xEB, 0xE3, 0x33, 0x4A, 0x15, 0xE4, 0x0A, 0xB3, 0xB1, 0x3C, 0x93, 0xBB, 0xAF, 0xF7, 0x3E] - - firmware = open(target[0].path, "rb") - robin = open(target[0].dir.path +'/Robin_nano.bin', "wb") - length = os.path.getsize(target[0].path) - position = 0 - try: - while position < length: - byte = firmware.read(1) - if position >= 320 and position < 31040: - byte = chr(ord(byte) ^ key[position & 31]) - if sys.version_info[0] > 2: - byte = bytes(byte, 'latin1') - robin.write(byte) - position += 1 - finally: - firmware.close() - robin.close() -env.AddPostAction("$BUILD_DIR/${PROGNAME}.bin", encrypt); +# +# buildroot/share/PlatformIO/scripts/mks_robin_nano.py +# +import robin +robin.prepare("0x08007000", "mks_robin_nano.ld", "Robin_nano.bin") diff --git a/buildroot/share/PlatformIO/scripts/mks_robin_nano35.py b/buildroot/share/PlatformIO/scripts/mks_robin_nano35.py index 0047289adfd0..4a5726ad5b98 100644 --- a/buildroot/share/PlatformIO/scripts/mks_robin_nano35.py +++ b/buildroot/share/PlatformIO/scripts/mks_robin_nano35.py @@ -1,40 +1,5 @@ -import os -Import("env") - -# Relocate firmware from 0x08000000 to 0x08007000 -for define in env['CPPDEFINES']: - if define[0] == "VECT_TAB_ADDR": - env['CPPDEFINES'].remove(define) -env['CPPDEFINES'].append(("VECT_TAB_ADDR", "0x08007000")) - -custom_ld_script = os.path.abspath("buildroot/share/PlatformIO/ldscripts/mks_robin_nano.ld") -for i, flag in enumerate(env["LINKFLAGS"]): - if "-Wl,-T" in flag: - env["LINKFLAGS"][i] = "-Wl,-T" + custom_ld_script - elif flag == "-T": - env["LINKFLAGS"][i + 1] = custom_ld_script - - -# Encrypt ${PROGNAME}.bin and save it as 'Robin_nano35.bin' -def encrypt(source, target, env): - import sys - - key = [0xA3, 0xBD, 0xAD, 0x0D, 0x41, 0x11, 0xBB, 0x8D, 0xDC, 0x80, 0x2D, 0xD0, 0xD2, 0xC4, 0x9B, 0x1E, 0x26, 0xEB, 0xE3, 0x33, 0x4A, 0x15, 0xE4, 0x0A, 0xB3, 0xB1, 0x3C, 0x93, 0xBB, 0xAF, 0xF7, 0x3E] - - firmware = open(target[0].path, "rb") - robin = open(target[0].dir.path +'/Robin_nano35.bin', "wb") - length = os.path.getsize(target[0].path) - position = 0 - try: - while position < length: - byte = firmware.read(1) - if position >= 320 and position < 31040: - byte = chr(ord(byte) ^ key[position & 31]) - if sys.version_info[0] > 2: - byte = bytes(byte, 'latin1') - robin.write(byte) - position += 1 - finally: - firmware.close() - robin.close() -env.AddPostAction("$BUILD_DIR/${PROGNAME}.bin", encrypt); +# +# buildroot/share/PlatformIO/scripts/mks_robin_nano35.py +# +import robin +robin.prepare("0x08007000", "mks_robin_nano.ld", "Robin_nano35.bin") diff --git a/buildroot/share/PlatformIO/scripts/mks_robin_pro.py b/buildroot/share/PlatformIO/scripts/mks_robin_pro.py index 2ebf1ffb9d74..60e2482bb030 100644 --- a/buildroot/share/PlatformIO/scripts/mks_robin_pro.py +++ b/buildroot/share/PlatformIO/scripts/mks_robin_pro.py @@ -1,39 +1,5 @@ -import os -Import("env") - -# Relocate firmware from 0x08000000 to 0x08007000 -for define in env['CPPDEFINES']: - if define[0] == "VECT_TAB_ADDR": - env['CPPDEFINES'].remove(define) -env['CPPDEFINES'].append(("VECT_TAB_ADDR", "0x08007000")) - -custom_ld_script = os.path.abspath("buildroot/share/PlatformIO/ldscripts/mks_robin_pro.ld") -for i, flag in enumerate(env["LINKFLAGS"]): - if "-Wl,-T" in flag: - env["LINKFLAGS"][i] = "-Wl,-T" + custom_ld_script - elif flag == "-T": - env["LINKFLAGS"][i + 1] = custom_ld_script - -# Encrypt ${PROGNAME}.bin and save it as 'Robin.bin' -def encrypt(source, target, env): - import sys - - key = [0xA3, 0xBD, 0xAD, 0x0D, 0x41, 0x11, 0xBB, 0x8D, 0xDC, 0x80, 0x2D, 0xD0, 0xD2, 0xC4, 0x9B, 0x1E, 0x26, 0xEB, 0xE3, 0x33, 0x4A, 0x15, 0xE4, 0x0A, 0xB3, 0xB1, 0x3C, 0x93, 0xBB, 0xAF, 0xF7, 0x3E] - - firmware = open(target[0].path, "rb") - robin = open(target[0].dir.path +'/Robin_pro.bin', "wb") - length = os.path.getsize(target[0].path) - position = 0 - try: - while position < length: - byte = firmware.read(1) - if position >= 320 and position < 31040: - byte = chr(ord(byte) ^ key[position & 31]) - if sys.version_info[0] > 2: - byte = bytes(byte, 'latin1') - robin.write(byte) - position += 1 - finally: - firmware.close() - robin.close() -env.AddPostAction("$BUILD_DIR/${PROGNAME}.bin", encrypt); +# +# buildroot/share/PlatformIO/scripts/mks_robin_pro.py +# +import robin +robin.prepare("0x08007000", "mks_robin_pro.ld", "Robin_pro.bin") diff --git a/buildroot/share/PlatformIO/scripts/offset_and_rename.py b/buildroot/share/PlatformIO/scripts/offset_and_rename.py new file mode 100644 index 000000000000..b42b2f35317c --- /dev/null +++ b/buildroot/share/PlatformIO/scripts/offset_and_rename.py @@ -0,0 +1,60 @@ +# +# offset_and_rename.py +# +# - If '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. +# +# - For 'board_build.rename' add a post-action to rename the firmware file. +# +import os,sys,marlin +Import("env") + +from SCons.Script import DefaultEnvironment +board = DefaultEnvironment().BoardConfig() + +board_keys = board.get("build").keys() + +# +# For build.offset define LD_FLASH_OFFSET, used by ldscript.ld +# +if 'offset' in board_keys: + LD_FLASH_OFFSET = board.get("build.offset") + marlin.relocate_vtab(LD_FLASH_OFFSET) + + # Flash size + maximum_flash_size = int(board.get("upload.maximum_size") / 1024) + marlin.replace_define('STM32_FLASH_SIZE', maximum_flash_size) + + # Get upload.maximum_ram_size (defined by /buildroot/share/PlatformIO/boards/VARIOUS.json) + maximum_ram_size = board.get("upload.maximum_ram_size") + + for i, flag in enumerate(env["LINKFLAGS"]): + if "-Wl,--defsym=LD_FLASH_OFFSET" in flag: + env["LINKFLAGS"][i] = "-Wl,--defsym=LD_FLASH_OFFSET=" + LD_FLASH_OFFSET + if "-Wl,--defsym=LD_MAX_DATA_SIZE" in flag: + env["LINKFLAGS"][i] = "-Wl,--defsym=LD_MAX_DATA_SIZE=" + str(maximum_ram_size - 40) + +# +# For build.encrypt rename and encode the firmware file. +# +if 'encrypt' in board_keys: + + # Encrypt ${PROGNAME}.bin and save it with the name given in build.encrypt + def encrypt(source, target, env): + marlin.encrypt_mks(source, target, env, board.get("build.encrypt")) + + marlin.add_post_action(encrypt); + +# +# For build.rename simply rename the firmware file. +# +if 'rename' in board_keys: + + def rename_target(source, target, env): + firmware = os.path.join(target[0].dir.path, board.get("build.rename")) + import shutil + shutil.copy(target[0].path, firmware) + + marlin.add_post_action(rename_target) diff --git a/buildroot/share/PlatformIO/scripts/openblt.py b/buildroot/share/PlatformIO/scripts/openblt.py new file mode 100644 index 000000000000..6e71ca9eb812 --- /dev/null +++ b/buildroot/share/PlatformIO/scripts/openblt.py @@ -0,0 +1,18 @@ +# +# Convert the ELF to an SREC file suitable for some bootloaders +# +import os,sys +from os.path import join + +Import("env") + +board = env.BoardConfig() +board_keys = board.get("build").keys() +if 'encrypt' in board_keys: + env.AddPostAction( + join("$BUILD_DIR", "${PROGNAME}.bin"), + env.VerboseAction(" ".join([ + "$OBJCOPY", "-O", "srec", + "\"$BUILD_DIR/${PROGNAME}.elf\"", "\"" + join("$BUILD_DIR", board.get("build.encrypt")) + "\"" + ]), "Building $TARGET") + ) diff --git a/buildroot/share/PlatformIO/scripts/preflight-checks.py b/buildroot/share/PlatformIO/scripts/preflight-checks.py new file mode 100644 index 000000000000..27e5c9d70a78 --- /dev/null +++ b/buildroot/share/PlatformIO/scripts/preflight-checks.py @@ -0,0 +1,93 @@ +# +# preflight-checks.py +# Check for common issues prior to compiling +# +import os,re,sys +Import("env") + +def get_envs_for_board(board): + with open(os.path.join("Marlin", "src", "pins", "pins.h"), "r") as file: + + if sys.platform == 'win32': + envregex = r"(?:env|win):" + elif sys.platform == 'darwin': + envregex = r"(?:env|mac|uni):" + elif sys.platform == 'linux': + envregex = r"(?:env|lin|uni):" + else: + envregex = r"(?:env):" + + r = re.compile(r"if\s+MB\((.+)\)") + if board.startswith("BOARD_"): + board = board[6:] + + for line in file: + mbs = r.findall(line) + if mbs and board in re.split(r",\s*", mbs[0]): + line = file.readline() + found_envs = re.match(r"\s*#include .+" + envregex, line) + if found_envs: + envlist = re.findall(envregex + r"(\w+)", line) + return [ "env:"+s for s in envlist ] + return [] + +def check_envs(build_env, board_envs, config): + if build_env in board_envs: + return True + ext = config.get(build_env, 'extends', default=None) + if ext: + if isinstance(ext, str): + return check_envs(ext, board_envs, config) + elif isinstance(ext, list): + for ext_env in ext: + if check_envs(ext_env, board_envs, config): + return True + return False + +def sanity_check_target(): + # Sanity checks: + if 'PIOENV' not in env: + raise SystemExit("Error: PIOENV is not defined. This script is intended to be used with PlatformIO") + + if 'MARLIN_FEATURES' not in env: + raise SystemExit("Error: this script should be used after common Marlin scripts") + + if 'MOTHERBOARD' not in env['MARLIN_FEATURES']: + raise SystemExit("Error: MOTHERBOARD is not defined in Configuration.h") + + build_env = env['PIOENV'] + motherboard = env['MARLIN_FEATURES']['MOTHERBOARD'] + board_envs = get_envs_for_board(motherboard) + config = env.GetProjectConfig() + result = check_envs("env:"+build_env, board_envs, config) + + if not result: + err = "Error: Build environment '%s' is incompatible with %s. Use one of these: %s" % \ + ( build_env, motherboard, ", ".join([ e[4:] for e in board_envs if e.startswith("env:") ]) ) + raise SystemExit(err) + + # + # Check for Config files in two common incorrect places + # + for p in [ env['PROJECT_DIR'], os.path.join(env['PROJECT_DIR'], "config") ]: + for f in [ "Configuration.h", "Configuration_adv.h" ]: + if os.path.isfile(os.path.join(p, f)): + err = "ERROR: Config files found in directory %s. Please move them into the Marlin subfolder." % p + raise SystemExit(err) + + # + # Check for old files indicating an entangled Marlin (mixing old and new code) + # + mixedin = [] + for p in [ os.path.join(env['PROJECT_DIR'], "Marlin/src/lcd/dogm") ]: + for f in [ "ultralcd_DOGM.cpp", "ultralcd_DOGM.h" ]: + if os.path.isfile(os.path.join(p, f)): + mixedin += [ f ] + if mixedin: + err = "ERROR: Old files fell into your Marlin folder. Remove %s and try again" % ", ".join(mixedin) + raise SystemExit(err) + +# Detect that 'vscode init' is running +from SCons.Script import COMMAND_LINE_TARGETS +if "idedata" not in COMMAND_LINE_TARGETS: + sanity_check_target() diff --git a/buildroot/share/PlatformIO/scripts/random-bin.py b/buildroot/share/PlatformIO/scripts/random-bin.py index 4d7ca5dc09b7..c03b8634487a 100644 --- a/buildroot/share/PlatformIO/scripts/random-bin.py +++ b/buildroot/share/PlatformIO/scripts/random-bin.py @@ -1,3 +1,7 @@ +# +# random-bin.py +# Set a unique firmware name based on current date and time +# Import("env") from datetime import datetime diff --git a/buildroot/share/PlatformIO/scripts/robin.py b/buildroot/share/PlatformIO/scripts/robin.py new file mode 100644 index 000000000000..50d0d92d2ff7 --- /dev/null +++ b/buildroot/share/PlatformIO/scripts/robin.py @@ -0,0 +1,12 @@ +# +# buildroot/share/PlatformIO/scripts/robin.py +# +import marlin + +# Apply customizations for a MKS Robin +def prepare(address, ldname, fwname): + def encrypt(source, target, env): + marlin.encrypt_mks(source, target, env, fwname) + marlin.relocate_firmware(address) + marlin.custom_ld_script(ldname) + marlin.add_post_action(encrypt); diff --git a/buildroot/share/PlatformIO/scripts/simulator.py b/buildroot/share/PlatformIO/scripts/simulator.py new file mode 100644 index 000000000000..fb9d93ccebcc --- /dev/null +++ b/buildroot/share/PlatformIO/scripts/simulator.py @@ -0,0 +1,52 @@ +# +# PlatformIO pre: script for simulator builds +# + +# Get the environment thus far for the build +Import("env") + +#print(env.Dump()) + +# +# Give the binary a distinctive name +# + +env['PROGNAME'] = "MarlinSimulator" + +# +# If Xcode is installed add the path to its Frameworks folder, +# or if Mesa is installed try to use its GL/gl.h. +# + +import sys +if sys.platform == 'darwin': + + # + # Silence half of the ranlib warnings. (No equivalent for 'ARFLAGS') + # + env['RANLIBFLAGS'] += [ "-no_warning_for_no_symbols" ] + + # Default paths for Xcode and a lucky GL/gl.h dropped by Mesa + xcode_path = "/Applications/Xcode.app/Contents/Developer/Platforms/MacOSX.platform/Developer/SDKs/MacOSX.sdk/System/Library/Frameworks" + mesa_path = "/opt/local/include/GL/gl.h" + + import os.path + + if os.path.exists(xcode_path): + + env['BUILD_FLAGS'] += [ "-F" + xcode_path ] + print("Using OpenGL framework headers from Xcode.app") + + elif os.path.exists(mesa_path): + + env['BUILD_FLAGS'] += [ '-D__MESA__' ] + print("Using OpenGL header from", mesa_path) + + else: + + print("\n\nNo OpenGL headers found. Install Xcode for matching headers, or use 'sudo port install mesa' to get a GL/gl.h.\n\n") + + # Break out of the PIO build immediately + sys.exit(1) + +env.AddCustomTarget("upload", "$BUILD_DIR/${PROGNAME}", "$BUILD_DIR/${PROGNAME}") diff --git a/buildroot/share/PlatformIO/scripts/stm32_bootloader.py b/buildroot/share/PlatformIO/scripts/stm32_bootloader.py deleted file mode 100644 index d517f1c8d1aa..000000000000 --- a/buildroot/share/PlatformIO/scripts/stm32_bootloader.py +++ /dev/null @@ -1,30 +0,0 @@ -import os,sys,shutil -Import("env") - -from SCons.Script import DefaultEnvironment -board = DefaultEnvironment().BoardConfig() - -def noencrypt(source, target, env): - firmware = os.path.join(target[0].dir.path, board.get("build.firmware")) - # do not overwrite encrypted firmware if present - if not os.path.isfile(firmware): - shutil.copy(target[0].path, firmware) - -if 'offset' in board.get("build").keys(): - LD_FLASH_OFFSET = board.get("build.offset") - - for define in env['CPPDEFINES']: - if define[0] == "VECT_TAB_OFFSET": - env['CPPDEFINES'].remove(define) - env['CPPDEFINES'].append(("VECT_TAB_OFFSET", LD_FLASH_OFFSET)) - - maximum_ram_size = board.get("upload.maximum_ram_size") - - for i, flag in enumerate(env["LINKFLAGS"]): - if "-Wl,--defsym=LD_FLASH_OFFSET" in flag: - env["LINKFLAGS"][i] = "-Wl,--defsym=LD_FLASH_OFFSET=" + LD_FLASH_OFFSET - if "-Wl,--defsym=LD_MAX_DATA_SIZE" in flag: - env["LINKFLAGS"][i] = "-Wl,--defsym=LD_MAX_DATA_SIZE=" + str(maximum_ram_size - 40) - - if 'firmware' in board.get("build").keys(): - env.AddPostAction("$BUILD_DIR/${PROGNAME}.bin", noencrypt); diff --git a/buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py b/buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py new file mode 100644 index 000000000000..c3779289e0f3 --- /dev/null +++ b/buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py @@ -0,0 +1,59 @@ +# +# stm32_serialbuffer.py +# +Import("env") + +# Marlin uses the `RX_BUFFER_SIZE` \ `TX_BUFFER_SIZE` options to +# configure buffer sizes for receiving \ transmitting serial data. +# Stm32duino uses another set of defines for the same purpose, so this +# script gets the values from the configuration and uses them to define +# `SERIAL_RX_BUFFER_SIZE` and `SERIAL_TX_BUFFER_SIZE` as global build +# flags so they are available for use by the platform. +# +# The script will set the value as the default one (64 bytes) +# or the user-configured one, whichever is higher. +# +# Marlin's default buffer sizes are 128 for RX and 32 for TX. +# The highest value is taken (128/64). +# +# If MF_*_BUFFER_SIZE, SERIAL_*_BUFFER_SIZE, USART_*_BUF_SIZE, are +# defined, the first of these values will be used as the minimum. +build_flags = env.ParseFlags(env.get('BUILD_FLAGS'))["CPPDEFINES"] +mf = env["MARLIN_FEATURES"] + +# Get a build flag's value or None +def getBuildFlagValue(name): + for flag in build_flags: + if isinstance(flag, list) and flag[0] == name: + return flag[1] + + return None + +# Get an overriding buffer size for RX or TX from the build flags +def getInternalSize(side): + return getBuildFlagValue(f"MF_{side}_BUFFER_SIZE") or \ + getBuildFlagValue(f"SERIAL_{side}_BUFFER_SIZE") or \ + getBuildFlagValue(f"USART_{side}_BUF_SIZE") + +# Get the largest defined buffer size for RX or TX +def getBufferSize(side, default): + # Get a build flag value or fall back to the given default + internal = int(getInternalSize(side) or default) + flag = side + "_BUFFER_SIZE" + # Return the largest value + return max(int(mf[flag]), internal) if flag in mf else internal + +# Add a build flag if it's not already defined +def tryAddFlag(name, value): + if getBuildFlagValue(name) is None: + env.Append(BUILD_FLAGS=[f"-D{name}={value}"]) + +# Get the largest defined buffer sizes for RX or TX, using defaults for undefined +rxBuf = getBufferSize("RX", 128) +txBuf = getBufferSize("TX", 64) + +# Provide serial buffer sizes to the stm32duino platform +tryAddFlag("SERIAL_RX_BUFFER_SIZE", rxBuf) +tryAddFlag("SERIAL_TX_BUFFER_SIZE", txBuf) +tryAddFlag("USART_RX_BUF_SIZE", rxBuf) +tryAddFlag("USART_TX_BUF_SIZE", txBuf) diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_BTT002/PeripheralPins.c b/buildroot/share/PlatformIO/variants/BIGTREE_BTT002/PeripheralPins.c deleted file mode 100644 index cff269db0b90..000000000000 --- a/buildroot/share/PlatformIO/variants/BIGTREE_BTT002/PeripheralPins.c +++ /dev/null @@ -1,347 +0,0 @@ -/* - ******************************************************************************* - * 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 STM32F407Z(E-G)Tx.xml - */ -#include -#include - -/* ===== - * Note: Commented lines are alternative possibilities which are not used by default. - * If you change them, you should know what you're doing first. - * ===== - */ - -//*** ADC *** - -#ifdef HAL_ADC_MODULE_ENABLED -const PinMap PinMap_ADC[] = { - {PA_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0 E0_DIR - {PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1 BLTOUCH_2 - {PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2 BLTOUCH_4 - {PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3 E1_EN - {PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4 TF_SS - {PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5 TF_SCLK - {PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6 TF_MISO - {PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7 LED - {PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8 HEATER2 - {PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9 HEATER0 - {PC_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10 Z_EN - {PC_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11 EXP_14 - {PC_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12 Z_DIR - {PC_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13 E0_EN - {PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14 EXP_8 - {PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15 EXP_7 - - #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio, 24 ADC - {PF_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC3_IN9 TH_0 - {PF_4, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC3_IN14 TH_1 - {PF_5, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC3_IN15 TH_2 - {PF_6, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC3_IN4 TH_3 - {PF_7, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC3_IN5 EXP_13 - {PF_8, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC3_IN6 EXP_3 - {PF_9, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC3_IN7 EXP_6 - {PF_10, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC3_IN8 EXP_5 - #endif - {NC, NP, 0} -}; -#endif - -//*** DAC *** - -#ifdef HAL_DAC_MODULE_ENABLED -const PinMap PinMap_DAC[] = { - {PA_4, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // DAC_OUT1 - {PA_5, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // DAC_OUT2 - {NC, NP, 0} -}; -#endif - -//*** I2C *** - -#ifdef HAL_I2C_MODULE_ENABLED -const PinMap PinMap_I2C_SDA[] = { - {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)}, - {PB_11, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, - {PC_9, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, - #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio - {PF_0, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, - #endif - {NC, NP, 0} -}; -#endif - -#ifdef HAL_I2C_MODULE_ENABLED -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)}, - #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio - {PF_1, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, - #endif - {NC, NP, 0} -}; -#endif - -//*** PWM *** - -#ifdef HAL_TIM_MODULE_ENABLED -const PinMap PinMap_PWM[] = { - {PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 HEATER0 - {PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 HEATER1 - {PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 HEATER2 - {PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 BED - {PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 0)}, // TIM8_CH3 FAN0 - {PE_5, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 FAN1 - {PE_6, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2 FAN2 - {PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 4, 0)}, // TIM8_CH4 EXTENSION1-4 - - /** - * Unused by specifications on BTT002. (PLEASE CONFIRM) - * Uncomment the corresponding line if you want to have HardwarePWM on some pins. - * WARNING: check timers' usage first to avoid conflicts. - * If you don't know what you're doing leave things as they are or you WILL break something (including hardware) - * If you alter this section DO NOT report bugs to Marlin team since they are most likely caused by you. Thank you. - */ - //{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 BLTOUCH is a "servo" - //{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 BLTOUCH is a "servo" - //{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_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N - //{PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 - //{PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 - //{PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N - //{PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 - //{PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N - //{PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 - //{PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 - //{PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 - //{PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 - //{PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 - //{PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 - //{PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N - //{PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N - //{PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N - //{PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N - //{PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 - //{PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 - //{PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 - //{PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 - //{PB_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_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 - //{PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N - //{PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N - //{PB_14, 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 - //{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 - //{PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 - //{PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 - //{PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 - //{PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 - //{PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 - //{PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 - //{PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 - //{PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 - //{PE_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N - //{PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 - //{PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N - //{PE_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 - //{PE_12, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N - //{PE_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 - //{PE_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 - #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio - //{PF_6, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1 - //{PF_7, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 - //{PF_8, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 - //{PF_9, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 - #endif - {NC, NP, 0} -}; -#endif - -//*** SERIAL *** - -#ifdef HAL_UART_MODULE_ENABLED -const PinMap PinMap_UART_TX[] = { - {PA_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, - {PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - {PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, - {PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, - {PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - {PC_6, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - {PC_10, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, - {PC_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - {PC_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, - {PD_5, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - {PD_8, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio - {PG_14, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - #endif - {NC, NP, 0} -}; - -const PinMap PinMap_UART_RX[] = { - {PA_1, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, - {PA_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - {PA_10, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, - {PB_7, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, - {PB_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - {PC_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - {PC_11, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, - {PC_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - {PD_2, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, - {PD_6, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - {PD_9, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio - {PG_9, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - #endif - {NC, NP, 0} -}; - -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)}, - {PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - {PD_4, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - {PD_12, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio - {PG_8, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - {PG_12, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - #endif - {NC, NP, 0} -}; - -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)}, - {PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - {PD_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - {PD_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio - {PG_13, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - {PG_15, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - #endif - {NC, NP, 0} -}; -#endif - -//*** SPI *** - -#ifdef HAL_SPI_MODULE_ENABLED -const PinMap PinMap_SPI_MOSI[] = { - {PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, - {PB_15, 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} -}; - -const PinMap PinMap_SPI_MISO[] = { - {PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, - {PB_14, 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} -}; - -const PinMap PinMap_SPI_SCLK[] = { - {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, - {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} -}; - -const PinMap PinMap_SPI_SSEL[] = { - {PA_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, - {PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, - {PA_15, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, - {NC, NP, 0} -}; -#endif - -//*** CAN *** - -#ifdef HAL_CAN_MODULE_ENABLED -#error "CAN bus isn't available on this board. Driver should be disabled." -#endif - -//*** ETHERNET *** -#ifdef HAL_ETH_MODULE_ENABLED -#error "Ethernet port isn't available on this board. Driver should be disabled." -#endif - -//*** No QUADSPI *** - -//*** USB *** -#ifdef HAL_PCD_MODULE_ENABLED -const PinMap PinMap_USB_OTG_FS[] = { - //{PA_8, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_SOF used by LCD - //{PA_9, USB_OTG_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_FS_VBUS available on wifi port, if empty - //{PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_ID available on UART1_RX if not used - {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} -}; - -const PinMap PinMap_USB_OTG_HS[] = { /* - #ifdef USE_USB_HS_IN_FS - {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_ID - {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_HS_VBUS - {PB_14, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DM - {PB_15, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DP - #else - #error "USB in HS mode isn't supported by the board" - {PA_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D0 - {PB_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D1 - {PB_1, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D2 - {PB_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D7 - {PB_10, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D3 - {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D5 - {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D6 - {PC_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_STP - {PC_2, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_DIR - {PC_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_NXT - #endif // USE_USB_HS_IN_FS - */ - {NC, NP, 0} -}; -#endif diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_BTT002/hal_conf_extra.h b/buildroot/share/PlatformIO/variants/BIGTREE_BTT002/hal_conf_extra.h deleted file mode 100644 index e0e8239aac08..000000000000 --- a/buildroot/share/PlatformIO/variants/BIGTREE_BTT002/hal_conf_extra.h +++ /dev/null @@ -1,52 +0,0 @@ -#pragma once - -#define HAL_MODULE_ENABLED -#define HAL_ADC_MODULE_ENABLED -#define HAL_CRC_MODULE_ENABLED -#define HAL_DMA_MODULE_ENABLED -#define HAL_GPIO_MODULE_ENABLED -#define HAL_I2C_MODULE_ENABLED -#define HAL_PWR_MODULE_ENABLED -#define HAL_RCC_MODULE_ENABLED -//#define HAL_RTC_MODULE_ENABLED Real Time Clock...do we use it? -#define HAL_SPI_MODULE_ENABLED -#define HAL_TIM_MODULE_ENABLED -#define HAL_USART_MODULE_ENABLED -#define HAL_CORTEX_MODULE_ENABLED -//#define HAL_UART_MODULE_ENABLED // by default -//#define HAL_PCD_MODULE_ENABLED // Since STM32 v3.10700.191028 this is automatically added if any type of USB is enabled (as in Arduino IDE) - -#undef HAL_SD_MODULE_ENABLED -#undef HAL_DAC_MODULE_ENABLED -#undef HAL_FLASH_MODULE_ENABLED -#undef HAL_CAN_MODULE_ENABLED -#undef HAL_CAN_LEGACY_MODULE_ENABLED -#undef HAL_CEC_MODULE_ENABLED -#undef HAL_CRYP_MODULE_ENABLED -#undef HAL_DCMI_MODULE_ENABLED -#undef HAL_DMA2D_MODULE_ENABLED -#undef HAL_ETH_MODULE_ENABLED -#undef HAL_NAND_MODULE_ENABLED -#undef HAL_NOR_MODULE_ENABLED -#undef HAL_PCCARD_MODULE_ENABLED -#undef HAL_SRAM_MODULE_ENABLED -#undef HAL_SDRAM_MODULE_ENABLED -#undef HAL_HASH_MODULE_ENABLED -#undef HAL_EXTI_MODULE_ENABLED -#undef HAL_SMBUS_MODULE_ENABLED -#undef HAL_I2S_MODULE_ENABLED -#undef HAL_IWDG_MODULE_ENABLED -#undef HAL_LTDC_MODULE_ENABLED -#undef HAL_DSI_MODULE_ENABLED -#undef HAL_QSPI_MODULE_ENABLED -#undef HAL_RNG_MODULE_ENABLED -#undef HAL_SAI_MODULE_ENABLED -#undef HAL_IRDA_MODULE_ENABLED -#undef HAL_SMARTCARD_MODULE_ENABLED -#undef HAL_WWDG_MODULE_ENABLED -#undef HAL_HCD_MODULE_ENABLED -#undef HAL_FMPI2C_MODULE_ENABLED -#undef HAL_SPDIFRX_MODULE_ENABLED -#undef HAL_DFSDM_MODULE_ENABLED -#undef HAL_LPTIM_MODULE_ENABLED -#undef HAL_MMC_MODULE_ENABLED diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_BTT002/ldscript.ld b/buildroot/share/PlatformIO/variants/BIGTREE_BTT002/ldscript.ld deleted file mode 100644 index 0c060d175180..000000000000 --- a/buildroot/share/PlatformIO/variants/BIGTREE_BTT002/ldscript.ld +++ /dev/null @@ -1,204 +0,0 @@ -/* -***************************************************************************** -** - -** File : LinkerScript.ld -** -** Abstract : Linker script for STM32F407ZGTx Device with -** 1024KByte FLASH, 128KByte 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 = 0x20020000; /* 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 = 0x8008000, LENGTH = 1024K -RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K -CCMRAM (rw) : ORIGIN = 0x10000000, 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): - { - . = 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 - - _siccmram = LOADADDR(.ccmram); - - /* CCM-RAM section - * - * IMPORTANT NOTE! - * If initialized variables will be placed in this section, - * the startup code needs to be modified to copy the init-values. - */ - .ccmram : - { - . = ALIGN(4); - _sccmram = .; /* create a global symbol at ccmram start */ - *(.ccmram) - *(.ccmram*) - - . = ALIGN(4); - _eccmram = .; /* create a global symbol at ccmram end */ - } >CCMRAM AT> FLASH - - - /* Uninitialized data section */ - . = ALIGN(4); - .bss : - { - /* This is used by the startup in order to initialize the .bss secion */ - _sbss = .; /* define a global symbol at bss start */ - __bss_start__ = _sbss; - *(.bss) - *(.bss*) - *(COMMON) - - . = ALIGN(4); - _ebss = .; /* define a global symbol at bss end */ - __bss_end__ = _ebss; - } >RAM - - /* User_heap_stack section, used to check that there is enough RAM left */ - ._user_heap_stack : - { - . = ALIGN(4); - PROVIDE ( end = . ); - PROVIDE ( _end = . ); - . = . + _Min_Heap_Size; - . = . + _Min_Stack_Size; - . = ALIGN(4); - } >RAM - - /* Remove information from the standard libraries */ - /DISCARD/ : - { - libc.a ( * ) - libm.a ( * ) - libgcc.a ( * ) - } - - .ARM.attributes 0 : { *(.ARM.attributes) } -} diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_BTT002/variant.h b/buildroot/share/PlatformIO/variants/BIGTREE_BTT002/variant.h deleted file mode 100644 index ecc319f47ce0..000000000000 --- a/buildroot/share/PlatformIO/variants/BIGTREE_BTT002/variant.h +++ /dev/null @@ -1,292 +0,0 @@ -/* - ******************************************************************************* - * Copyright (c) 2017, 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. - ******************************************************************************* - */ -#pragma once - -#ifdef __cplusplus -extern "C" { -#endif // __cplusplus - -/*---------------------------------------------------------------------------- - * Pins - *----------------------------------------------------------------------------*/ - -#ifdef STM32F405RX - #define STM32F4X_PIN_NUM 64 //64 pins mcu, 51 gpio - #define STM32F4X_GPIO_NUM 51 - #define STM32F4X_ADC_NUM 16 -#elif defined(STM32F407_5VX) - #define STM32F4X_PIN_NUM 100 //100 pins mcu, 82 gpio - #define STM32F4X_GPIO_NUM 82 - #define STM32F4X_ADC_NUM 16 -#elif defined(STM32F407_5ZX) - #define STM32F4X_PIN_NUM 144 //144 pins mcu, 114 gpio - #define STM32F4X_GPIO_NUM 114 - #define STM32F4X_ADC_NUM 24 -#elif defined(STM32F407IX) - #define STM32F4X_PIN_NUM 176 //176 pins mcu, 140 gpio - #define STM32F4X_GPIO_NUM 140 - #define STM32F4X_ADC_NUM 24 -#else - #error "no match MCU defined" -#endif - -#if STM32F4X_PIN_NUM >= 64 //64 pins mcu, 51 gpio - #define PC13 0 - #define PC14 1 //OSC32_IN - #define PC15 2 //OSC32_OUT - #define PH0 3 //OSC_IN - #define PH1 4 //OSC_OUT - #define PB2 5 //BOOT1 - #define PB10 6 //1:SPI2_SCK / I2C2_SCL / USART3_TX / TIM2_CH3 - #define PB11 7 //1:I2C2_SDA / USART3_RX / TIM2_CH4 - #define PB12 8 //1:SPI2_NSS / OTG_HS_ID - #define PB13 9 //1:SPI2_SCK 2:OTG_HS_VBUS - #define PB14 10 //1:SPI2_MISO / TIM12_CH1 / OTG_HS_DM - #define PB15 11 //SPI2_MOSI / TIM12_CH2 / OTG_HS_DP - #define PC6 12 //1:TIM8_CH1 / SDIO_D6 / USART6_TX / TIM3_CH1 - #define PC7 13 //1:TIM8_CH2 / SDIO_D7 / USART6_RX / TIM3_CH2 - #define PC8 14 //1:TIM8_CH3 / SDIO_D0 / TIM3_CH3 - #define PC9 15 //1:TIM8_CH4 / SDIO_D1 / TIM3_CH4 - #define PA8 16 //1:TIM1_CH1 / I2C3_SCL / OTG_FS_SOF - #define PA9 17 //1:USART1_TX / TIM1_CH2 2:OTG_FS_VBUS - #define PA10 18 //1:USART1_RX / TIM1_CH3 / OTG_FS_ID - #define PA11 19 //1:TIM1_CH4 / OTG_FS_DM - #define PA12 20 //1:OTG_FS_DP - #define PA13 21 //0:JTMS-SWDIO - #define PA14 22 //0:JTCK-SWCLK - #define PA15 23 //0:JTDI 1:SPI3_NSS / SPI1_NSS - #define PC10 24 //1:UART4_TX / SPI3_SCK / SDIO_D2 / USART3_TX - #define PC11 25 //1:UART4_RX / SPI3_MISO / SDIO_D3 / USART3_RX - #define PC12 26 //1:UART5_TX / SPI3_MOSI / SDIO_CK - #define PD2 27 //1:UART5_RX / SDIO_CMD - #define PB3 28 //0:JTDO 1:SPI3_SCK / TIM2_CH2 / SPI1_SCK - #define PB4 29 //0:NJTRST 1:SPI3_MISO / TIM3_CH1 / SPI1_MISO - #define PB5 30 //1:TIM3_CH2 / SPI1_MOSI / SPI3_MOSI - #define PB6 31 //1:I2C1_SCL / TIM4_CH1 / USART1_TX - #define PB7 32 //1:I2C1_SDA / TIM4_CH2 / USART1_RX - #define PB8 33 //1:I2C1_SCL / TIM4_CH3 / SDIO_D4 / TIM10_CH1 - #define PB9 34 //1:I2C1_SDA / TIM4_CH4 / SDIO_D5 / TIM11_CH1 / SPI2_NSS - #define PA0 35 //1:UART4_TX / TIM5_CH1 2:ADC123_IN0 - #define PA1 36 //1:UART4_RX / TIM5_CH2 / TIM2_CH2 2:ADC123_IN1 - #define PA2 37 //1:USART2_TX /TIM5_CH3 / TIM9_CH1 / TIM2_CH3 2:ADC123_IN2 - #define PA3 38 //1:USART2_RX /TIM5_CH4 / TIM9_CH2 / TIM2_CH4 2:ADC123_IN3 - #define PA4 39 //NOT FT 1:SPI1_NSS / SPI3_NSS / USART2_CK 2:ADC12_IN4 / DAC_OUT1 - #define PA5 40 //NOT FT 1:SPI1_SCK 2:ADC12_IN5 / DAC_OUT2 - #define PA6 41 //1:SPI1_MISO / TIM13_CH1 / TIM3_CH1 2:ADC12_IN6 - #define PA7 42 //1:SPI1_MOSI / TIM14_CH1 / TIM3_CH2 2:ADC12_IN7 - #define PB0 43 //1:TIM3_CH3 2:ADC12_IN8 - #define PB1 44 //1:TIM3_CH4 2:ADC12_IN9 - #define PC0 45 //1: 2:ADC123_IN10 - #define PC1 46 //1: 2:ADC123_IN11 - #define PC2 47 //1:SPI2_MISO 2:ADC123_IN12 - #define PC3 48 //1:SPI2_MOSI 2:ADC123_IN13 - #define PC4 49 //1: 2:ADC12_IN14 - #define PC5 50 //1: 2:ADC12_IN15 - #if STM32F4X_PIN_NUM >= 144 - #define PF3 51 //1:FSMC_A3 2:ADC3_IN9 - #define PF4 52 //1:FSMC_A4 2:ADC3_IN14 - #define PF5 53 //1:FSMC_A5 2:ADC3_IN15 - #define PF6 54 //1:TIM10_CH1 2:ADC3_IN4 - #define PF7 55 //1:TIM11_CH1 2:ADC3_IN5 - #define PF8 56 //1:TIM13_CH1 2:ADC3_IN6 - #define PF9 57 //1;TIM14_CH1 2:ADC3_IN7 - #define PF10 58 //2:ADC3_IN8 - #endif -#endif -#if STM32F4X_PIN_NUM >= 100 //100 pins mcu, 82 gpio - #define PE2 (35+STM32F4X_ADC_NUM) //1:FSMC_A23 - #define PE3 (36+STM32F4X_ADC_NUM) //1:FSMC_A19 - #define PE4 (37+STM32F4X_ADC_NUM) //1:FSMC_A20 - #define PE5 (38+STM32F4X_ADC_NUM) //1:FSMC_A21 - #define PE6 (39+STM32F4X_ADC_NUM) //1:FSMC_A22 - #define PE7 (40+STM32F4X_ADC_NUM) //1:FSMC_D4 - #define PE8 (41+STM32F4X_ADC_NUM) //1:FSMC_D5 - #define PE9 (42+STM32F4X_ADC_NUM) //1:FSMC_D6 / TIM1_CH1 - #define PE10 (43+STM32F4X_ADC_NUM) //1:FSMC_D7 - #define PE11 (44+STM32F4X_ADC_NUM) //1:FSMC_D8 / TIM1_CH2 - #define PE12 (45+STM32F4X_ADC_NUM) //1:FSMC_D9 - #define PE13 (46+STM32F4X_ADC_NUM) //1:FSMC_D10 / TIM1_CH3 - #define PE14 (47+STM32F4X_ADC_NUM) //1:FSMC_D11 / TIM1_CH4 - #define PE15 (48+STM32F4X_ADC_NUM) //1:FSMC_D12 - #define PD8 (49+STM32F4X_ADC_NUM) //1:FSMC_D13 / USART3_TX - #define PD9 (50+STM32F4X_ADC_NUM) //1:FSMC_D14 / USART3_RX - #define PD10 (51+STM32F4X_ADC_NUM) //1:FSMC_D15 - #define PD11 (52+STM32F4X_ADC_NUM) //1:FSMC_A16 - #define PD12 (53+STM32F4X_ADC_NUM) //1:FSMC_A17 / TIM4_CH1 - #define PD13 (54+STM32F4X_ADC_NUM) //1:FSMC_A18 / TIM4_CH2 - #define PD14 (55+STM32F4X_ADC_NUM) //1:FSMC_D0 / TIM4_CH3 - #define PD15 (56+STM32F4X_ADC_NUM) //1:FSMC_D1 / TIM4_CH4 - #define PD0 (57+STM32F4X_ADC_NUM) //1:FSMC_D2 - #define PD1 (58+STM32F4X_ADC_NUM) //1:FSMC_D3 - #define PD3 (59+STM32F4X_ADC_NUM) //1:FSMC_CLK - #define PD4 (60+STM32F4X_ADC_NUM) //1:FSMC_NOE - #define PD5 (61+STM32F4X_ADC_NUM) //1:USART2_TX - #define PD6 (62+STM32F4X_ADC_NUM) //1:USART2_RX - #define PD7 (63+STM32F4X_ADC_NUM) - #define PE0 (64+STM32F4X_ADC_NUM) - #define PE1 (65+STM32F4X_ADC_NUM) -#endif -#if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio - #define PF0 (66+STM32F4X_ADC_NUM) //1:FSMC_A0 / I2C2_SDA - #define PF1 (67+STM32F4X_ADC_NUM) //1:FSMC_A1 / I2C2_SCL - #define PF2 (68+STM32F4X_ADC_NUM) //1:FSMC_A2 - #define PF11 (69+STM32F4X_ADC_NUM) - #define PF12 (70+STM32F4X_ADC_NUM) //1:FSMC_A6 - #define PF13 (71+STM32F4X_ADC_NUM) //1:FSMC_A7 - #define PF14 (72+STM32F4X_ADC_NUM) //1:FSMC_A8 - #define PF15 (73+STM32F4X_ADC_NUM) //1:FSMC_A9 - #define PG0 (74+STM32F4X_ADC_NUM) //1:FSMC_A10 - #define PG1 (75+STM32F4X_ADC_NUM) //1:FSMC_A11 - #define PG2 (76+STM32F4X_ADC_NUM) //1:FSMC_A12 - #define PG3 (77+STM32F4X_ADC_NUM) //1:FSMC_A13 - #define PG4 (78+STM32F4X_ADC_NUM) //1:FSMC_A14 - #define PG5 (79+STM32F4X_ADC_NUM) //1:FSMC_A15 - #define PG6 (80+STM32F4X_ADC_NUM) - #define PG7 (81+STM32F4X_ADC_NUM) - #define PG8 (82+STM32F4X_ADC_NUM) - #define PG9 (83+STM32F4X_ADC_NUM) //1:USART6_RX - #define PG10 (84+STM32F4X_ADC_NUM) //1:FSMC_NE3 - #define PG11 (85+STM32F4X_ADC_NUM) - #define PG12 (86+STM32F4X_ADC_NUM) //1:FSMC_NE4 - #define PG13 (87+STM32F4X_ADC_NUM) //1:FSMC_A24 - #define PG14 (88+STM32F4X_ADC_NUM) //1:FSMC_A25 / USART6_TX - #define PG15 (89+STM32F4X_ADC_NUM) -#endif -#if STM32F4X_PIN_NUM >= 176 //176 pins mcu, 140 gpio - #define PI8 (90+STM32F4X_ADC_NUM) - #define PI9 (91+STM32F4X_ADC_NUM) - #define PI10 (92+STM32F4X_ADC_NUM) - #define PI11 (93+STM32F4X_ADC_NUM) - #define PH2 (94+STM32F4X_ADC_NUM) - #define PH3 (95+STM32F4X_ADC_NUM) - #define PH4 (96+STM32F4X_ADC_NUM) //1:I2C2_SCL - #define PH5 (97+STM32F4X_ADC_NUM) //1:I2C2_SDA - #define PH6 (98+STM32F4X_ADC_NUM) //1:TIM12_CH1 - #define PH7 (99+STM32F4X_ADC_NUM) //1:I2C3_SCL - #define PH8 (100+STM32F4X_ADC_NUM) //1:I2C3_SDA - #define PH9 (101+STM32F4X_ADC_NUM) //1:TIM12_CH2 - #define PH10 (102+STM32F4X_ADC_NUM) //1:TIM5_CH1 - #define PH11 (103+STM32F4X_ADC_NUM) //1:TIM5_CH2 - #define PH12 (104+STM32F4X_ADC_NUM) //1:TIM5_CH3 - #define PH13 (105+STM32F4X_ADC_NUM) - #define PH14 (106+STM32F4X_ADC_NUM) - #define PH15 (107+STM32F4X_ADC_NUM) - #define PI0 (108+STM32F4X_ADC_NUM) //1:TIM5_CH4 / SPI2_NSS - #define PI1 (109+STM32F4X_ADC_NUM) //1:SPI2_SCK - #define PI2 (110+STM32F4X_ADC_NUM) //1:TIM8_CH4 /SPI2_MISO - #define PI3 (111+STM32F4X_ADC_NUM) //1:SPI2_MOS - #define PI4 (112+STM32F4X_ADC_NUM) - #define PI5 (113+STM32F4X_ADC_NUM) //1:TIM8_CH1 - #define PI6 (114+STM32F4X_ADC_NUM) //1:TIM8_CH2 - #define PI7 (115+STM32F4X_ADC_NUM) //1:TIM8_CH3 -#endif - -// This must be a literal -#define NUM_DIGITAL_PINS (STM32F4X_GPIO_NUM) -// This must be a literal with a value less than or equal to MAX_ANALOG_INPUTS -#define NUM_ANALOG_INPUTS (STM32F4X_ADC_NUM) -#define NUM_ANALOG_FIRST 35 - -// Below ADC, DAC and PWM definitions already done in the core -// Could be redefined here if needed -// ADC resolution is 12bits -//#define ADC_RESOLUTION 12 -//#define DACC_RESOLUTION 12 - -// PWM resolution -/* - * BEWARE: - * Changing this value from the default (1000) will affect the PWM output value of analogWrite (to a PWM pin) - * Since the pin is toggled on capture, if you change the frequency of the timer you have to adapt the compare value (analogWrite thinks you did) - */ -//#define PWM_FREQUENCY 20000 -//The bottom values are the default and don't need to be redefined -//#define PWM_RESOLUTION 8 -//#define PWM_MAX_DUTY_CYCLE 255 - -// Below SPI and I2C definitions already done in the core -// Could be redefined here if differs from the default one -// SPI Definitions -#define PIN_SPI_MOSI PB15 -#define PIN_SPI_MISO PB14 -#define PIN_SPI_SCK PB13 -#define PIN_SPI_SS PB12 - -// I2C Definitions -#define PIN_WIRE_SDA PB7 -#define PIN_WIRE_SCL PB6 - -// Timer Definitions -//Do not use timer used by PWM pins when possible. See PinMap_PWM in PeripheralPins.c -#define TIMER_TONE TIM7 -#define TIMER_SERVO TIM5 -#define TIMER_SERIAL TIM2 - -// UART Definitions -// Define here Serial instance number to map on Serial generic name -#define SERIAL_UART_INSTANCE 1 //ex: 2 for Serial2 (USART2) -// DEBUG_UART could be redefined to print on another instance than 'Serial' -//#define DEBUG_UART ((USART_TypeDef *) U(S)ARTX) // ex: USART3 -// DEBUG_UART baudrate, default: 9600 if not defined -//#define DEBUG_UART_BAUDRATE x -// DEBUG_UART Tx pin name, default: the first one found in PinMap_UART_TX for DEBUG_UART -//#define DEBUG_PINNAME_TX PX_n // PinName used for TX - -// Default pin used for 'Serial' instance (ex: ST-Link) -// Mandatory for Firmata -#define PIN_SERIAL_RX PA10 -#define PIN_SERIAL_TX PA9 - -#ifdef __cplusplus -} // extern "C" -#endif -/*---------------------------------------------------------------------------- - * Arduino objects - C++ only - *----------------------------------------------------------------------------*/ - -#ifdef __cplusplus -// These serial port names are intended to allow libraries and architecture-neutral -// sketches to automatically default to the correct port name for a particular type -// of use. For example, a GPS module would normally connect to SERIAL_PORT_HARDWARE_OPEN, -// the first hardware serial port whose RX/TX pins are not dedicated to another use. -// -// SERIAL_PORT_MONITOR Port which normally prints to the Arduino Serial Monitor -// -// SERIAL_PORT_USBVIRTUAL Port which is USB virtual serial -// -// SERIAL_PORT_LINUXBRIDGE Port which connects to a Linux system via Bridge library -// -// SERIAL_PORT_HARDWARE Hardware serial port, physical RX & TX pins. -// -// SERIAL_PORT_HARDWARE_OPEN Hardware serial ports which are open for use. Their RX & TX -// pins are NOT connected to anything by default. -#define SERIAL_PORT_MONITOR Serial -#define SERIAL_PORT_HARDWARE Serial1 -#endif diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/PeripheralPins.c b/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/PeripheralPins.c deleted file mode 100644 index db0a439562a6..000000000000 --- a/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/PeripheralPins.c +++ /dev/null @@ -1,380 +0,0 @@ -/* - ******************************************************************************* - * 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 STM32F407Z(E-G)Tx.xml - */ -#include -#include - -/* ===== - * Note: Commented lines are alternative possibilities which are not used by default. - * If you change them, you should know what you're doing first. - * ===== - */ - -//*** ADC *** - -#ifdef HAL_ADC_MODULE_ENABLED -const PinMap PinMap_ADC[] = { - {PA_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0 E0_DIR - {PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1 BLTOUCH_2 - {PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2 BLTOUCH_4 - {PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3 E1_EN - {PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4 TF_SS - {PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5 TF_SCLK - {PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6 TF_MISO - {PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7 LED - {PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8 HEATER2 - {PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9 HEATER0 - {PC_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10 Z_EN - {PC_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11 EXP_14 - {PC_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12 Z_DIR - {PC_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13 E0_EN - {PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14 EXP_8 - {PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15 EXP_7 - - #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio, 24 ADC - {PF_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC3_IN9 TH_0 - {PF_4, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC3_IN14 TH_1 - {PF_5, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC3_IN15 TH_2 - {PF_6, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC3_IN4 TH_3 - {PF_7, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC3_IN5 EXP_13 - {PF_8, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC3_IN6 EXP_3 - {PF_9, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC3_IN7 EXP_6 - {PF_10, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC3_IN8 EXP_5 - #endif - {NC, NP, 0} -}; -#endif - -//*** DAC *** - -#ifdef HAL_DAC_MODULE_ENABLED -const PinMap PinMap_DAC[] = { - {PA_4, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // DAC_OUT1 - {PA_5, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // DAC_OUT2 - {NC, NP, 0} -}; -#endif - -//*** I2C *** - -#ifdef HAL_I2C_MODULE_ENABLED -const PinMap PinMap_I2C_SDA[] = { - {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)}, - {PB_11, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, - {PC_9, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, - #if STM32F4X_PIN_NUM >= 144 // 144 pins mcu, 114 gpio - #if STM32F4X_PIN_NUM >= 176 - {PH_5, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, - {PH_8, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, - #else - {PF_0, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, - #endif - #endif - {NC, NP, 0} -}; -#endif - -#ifdef HAL_I2C_MODULE_ENABLED -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)}, - #if STM32F4X_PIN_NUM >= 144 // 144 pins mcu, 114 gpio - #if STM32F4X_PIN_NUM >= 176 - //{PF_1, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, - {PH_4, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, - {PH_7, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, - #else - {PF_1, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, - #endif - #endif - {NC, NP, 0} -}; -#endif - -//*** PWM *** - -#ifdef HAL_TIM_MODULE_ENABLED -const PinMap PinMap_PWM[] = { - - // Some pins can perform PWM from more than one timer. These were selected to utilize as many channels as - // possible from timers which were already dedicated to PWM output. - // TIM1 = [FAN4, FAN5, HEATER6, FAN7] - // TIM2 = [, HEATER1, BED, ] - // TIM3 = [, , HEATER2, HEATER0] - // TIM4 = [HEATER5, HEATER4, , HEATER3] - // TIM8 = [FAN3, HEATER7, FAN2, FAN6] - // TIM9 = [FAN0, FAN1, , ] - - {PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 HEATER0 - {PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 HEATER1 - {PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 HEATER2 - {PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 HEATER3 - {PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 HEATER4 - {PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 HEATER5 - {PE_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 HEATER6 - {PI_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 HEATER7 - {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 BED - - {PE_5, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 FAN0 - {PE_6, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2 FAN1 - {PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 0)}, // TIM8_CH3 FAN2 - {PI_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 FAN3 - {PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 FAN4 - {PE_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 FAN5 - {PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 4, 0)}, // TIM8_CH4 FAN6 - {PE_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 FAN7 - - - // Alternate timer assignments for pins commonly using PWM - //{PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N HEATER0 - //{PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N HEATER0 - //{PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 HEATER1 - //{PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N HEATER2 - //{PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N HEATER2 - //{PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3 BED - //{PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 BED - //{PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 FAN2 - //{PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 FAN6 - - // Pins with an available timer channel, on a timer already allocated for PWM. - // These can be freely used for purposes requiring PWM, without creating new timer conflicts. - // This pins are very likely already used for other purposes and enabling PWM on them won't be useful. - {PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 BLTouch / Probe Output - {PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 ESP8266 connector. Available if 8266 isn't used - {PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 ESP8266 connector. Available if 8266 isn't used - - /* - * Pins not utilizing hardware PWM on the GTR. - * Uncomment the corresponding line if you want to have HardwarePWM on some pins. - * WARNING: check timers' usage first to avoid conflicts. - * If you don't know what you're doing leave things as they are or you WILL break something (including hardware) - */ - //{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_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_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N - //{PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 - //{PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 - //{PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N - //{PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 - //{PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N - //{PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 - //{PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 - //{PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 - //{PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 - //{PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 - //{PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 - //{PB_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_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 - //{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 - //{PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 - //{PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 - //{PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 - //{PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 - //{PE_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N - //{PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N - //{PE_12, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N - //{PF_6, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1 - //{PF_7, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 - //{PF_8, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 - //{PF_9, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 - //{PH_10, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1 - //{PH_6, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 1, 0)}, // TIM12_CH1 - //{PH_11, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 - {NC, NP, 0} -}; -#endif - -//*** SERIAL *** - -#ifdef HAL_UART_MODULE_ENABLED -const PinMap PinMap_UART_TX[] = { - {PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, - {PD_8, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - {PC_6, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio - //{PG_14, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - #endif - //{PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, - //{PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - //{PD_5, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - //{PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - //{PC_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - //{PA_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, - //{PC_10, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, - //{PC_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, - {NC, NP, 0} -}; - -const PinMap PinMap_UART_RX[] = { - {PA_10, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, - {PD_9, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - {PC_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - //{PA_1, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, - //{PA_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - //{PB_7, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, - //{PB_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - //{PC_11, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, - //{PC_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - //{PD_2, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, - //{PD_6, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio - //{PG_9, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - #endif - {NC, NP, 0} -}; - -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)}, - //{PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - //{PD_4, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - //{PD_12, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio - //{PG_8, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - //{PG_12, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - #endif - {NC, NP, 0} -}; - -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)}, - //{PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - //{PD_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - //{PD_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio - //{PG_13, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - //{PG_15, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - #endif - {NC, NP, 0} -}; -#endif - -//*** SPI *** - -#ifdef HAL_SPI_MODULE_ENABLED -const PinMap PinMap_SPI_MOSI[] = { - //{PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, - {PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, - {PB_15, 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} -}; - -const PinMap PinMap_SPI_MISO[] = { - {PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, - {PB_14, 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} -}; - -const PinMap PinMap_SPI_SCLK[] = { - {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, - {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} -}; - -const PinMap PinMap_SPI_SSEL[] = { - {PA_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, - {PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, - {PA_15, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, - {NC, NP, 0} -}; -#endif - -//*** CAN *** - -#ifdef HAL_CAN_MODULE_ENABLED -#error "CAN bus isn't available on this board. Driver should be disabled." -#endif - -//*** ETHERNET *** -#ifdef HAL_ETH_MODULE_ENABLED -#error "Ethernet port isn't available on this board. Driver should be disabled." -#endif - -//*** No QUADSPI *** - -//*** USB *** -#ifdef HAL_PCD_MODULE_ENABLED -const PinMap PinMap_USB_OTG_FS[] = { - //{PA_8, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_SOF used by LCD - //{PA_9, USB_OTG_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_FS_VBUS available on wifi port, if empty - //{PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_ID available on UART1_RX if not used - {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} -}; - -const PinMap PinMap_USB_OTG_HS[] = { /* - #ifdef USE_USB_HS_IN_FS - {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_ID - {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_HS_VBUS - {PB_14, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DM - {PB_15, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DP - #else - #error "USB in HS mode isn't supported by the board" - {PA_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D0 - {PB_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D1 - {PB_1, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D2 - {PB_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D7 - {PB_10, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D3 - {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D5 - {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D6 - {PC_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_STP - {PC_2, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_DIR - {PC_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_NXT - #endif // USE_USB_HS_IN_FS - */ - {NC, NP, 0} -}; -#endif diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/hal_conf_extra.h b/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/hal_conf_extra.h deleted file mode 100644 index e0e8239aac08..000000000000 --- a/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/hal_conf_extra.h +++ /dev/null @@ -1,52 +0,0 @@ -#pragma once - -#define HAL_MODULE_ENABLED -#define HAL_ADC_MODULE_ENABLED -#define HAL_CRC_MODULE_ENABLED -#define HAL_DMA_MODULE_ENABLED -#define HAL_GPIO_MODULE_ENABLED -#define HAL_I2C_MODULE_ENABLED -#define HAL_PWR_MODULE_ENABLED -#define HAL_RCC_MODULE_ENABLED -//#define HAL_RTC_MODULE_ENABLED Real Time Clock...do we use it? -#define HAL_SPI_MODULE_ENABLED -#define HAL_TIM_MODULE_ENABLED -#define HAL_USART_MODULE_ENABLED -#define HAL_CORTEX_MODULE_ENABLED -//#define HAL_UART_MODULE_ENABLED // by default -//#define HAL_PCD_MODULE_ENABLED // Since STM32 v3.10700.191028 this is automatically added if any type of USB is enabled (as in Arduino IDE) - -#undef HAL_SD_MODULE_ENABLED -#undef HAL_DAC_MODULE_ENABLED -#undef HAL_FLASH_MODULE_ENABLED -#undef HAL_CAN_MODULE_ENABLED -#undef HAL_CAN_LEGACY_MODULE_ENABLED -#undef HAL_CEC_MODULE_ENABLED -#undef HAL_CRYP_MODULE_ENABLED -#undef HAL_DCMI_MODULE_ENABLED -#undef HAL_DMA2D_MODULE_ENABLED -#undef HAL_ETH_MODULE_ENABLED -#undef HAL_NAND_MODULE_ENABLED -#undef HAL_NOR_MODULE_ENABLED -#undef HAL_PCCARD_MODULE_ENABLED -#undef HAL_SRAM_MODULE_ENABLED -#undef HAL_SDRAM_MODULE_ENABLED -#undef HAL_HASH_MODULE_ENABLED -#undef HAL_EXTI_MODULE_ENABLED -#undef HAL_SMBUS_MODULE_ENABLED -#undef HAL_I2S_MODULE_ENABLED -#undef HAL_IWDG_MODULE_ENABLED -#undef HAL_LTDC_MODULE_ENABLED -#undef HAL_DSI_MODULE_ENABLED -#undef HAL_QSPI_MODULE_ENABLED -#undef HAL_RNG_MODULE_ENABLED -#undef HAL_SAI_MODULE_ENABLED -#undef HAL_IRDA_MODULE_ENABLED -#undef HAL_SMARTCARD_MODULE_ENABLED -#undef HAL_WWDG_MODULE_ENABLED -#undef HAL_HCD_MODULE_ENABLED -#undef HAL_FMPI2C_MODULE_ENABLED -#undef HAL_SPDIFRX_MODULE_ENABLED -#undef HAL_DFSDM_MODULE_ENABLED -#undef HAL_LPTIM_MODULE_ENABLED -#undef HAL_MMC_MODULE_ENABLED diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/ldscript.ld b/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/ldscript.ld deleted file mode 100644 index 0c060d175180..000000000000 --- a/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/ldscript.ld +++ /dev/null @@ -1,204 +0,0 @@ -/* -***************************************************************************** -** - -** File : LinkerScript.ld -** -** Abstract : Linker script for STM32F407ZGTx Device with -** 1024KByte FLASH, 128KByte 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 = 0x20020000; /* 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 = 0x8008000, LENGTH = 1024K -RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K -CCMRAM (rw) : ORIGIN = 0x10000000, 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): - { - . = 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 - - _siccmram = LOADADDR(.ccmram); - - /* CCM-RAM section - * - * IMPORTANT NOTE! - * If initialized variables will be placed in this section, - * the startup code needs to be modified to copy the init-values. - */ - .ccmram : - { - . = ALIGN(4); - _sccmram = .; /* create a global symbol at ccmram start */ - *(.ccmram) - *(.ccmram*) - - . = ALIGN(4); - _eccmram = .; /* create a global symbol at ccmram end */ - } >CCMRAM AT> FLASH - - - /* Uninitialized data section */ - . = ALIGN(4); - .bss : - { - /* This is used by the startup in order to initialize the .bss secion */ - _sbss = .; /* define a global symbol at bss start */ - __bss_start__ = _sbss; - *(.bss) - *(.bss*) - *(COMMON) - - . = ALIGN(4); - _ebss = .; /* define a global symbol at bss end */ - __bss_end__ = _ebss; - } >RAM - - /* User_heap_stack section, used to check that there is enough RAM left */ - ._user_heap_stack : - { - . = ALIGN(4); - PROVIDE ( end = . ); - PROVIDE ( _end = . ); - . = . + _Min_Heap_Size; - . = . + _Min_Stack_Size; - . = ALIGN(4); - } >RAM - - /* Remove information from the standard libraries */ - /DISCARD/ : - { - libc.a ( * ) - libm.a ( * ) - libgcc.a ( * ) - } - - .ARM.attributes 0 : { *(.ARM.attributes) } -} diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/variant.h b/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/variant.h deleted file mode 100644 index 2da195c6cff0..000000000000 --- a/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/variant.h +++ /dev/null @@ -1,322 +0,0 @@ -/* - ******************************************************************************* - * Copyright (c) 2017, 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. - ******************************************************************************* - */ -#pragma once - -#ifdef __cplusplus -extern "C" { -#endif // __cplusplus - -/*---------------------------------------------------------------------------- - * Pins - *----------------------------------------------------------------------------*/ - -#ifdef STM32F405RX - #define STM32F4X_PIN_NUM 64 //64 pins mcu, 51 gpio - #define STM32F4X_GPIO_NUM 51 - #define STM32F4X_ADC_NUM 16 -#elif defined(STM32F407_5VX) - #define STM32F4X_PIN_NUM 100 //100 pins mcu, 82 gpio - #define STM32F4X_GPIO_NUM 82 - #define STM32F4X_ADC_NUM 16 -#elif defined(STM32F407_5ZX) - #define STM32F4X_PIN_NUM 144 //144 pins mcu, 114 gpio - #define STM32F4X_GPIO_NUM 114 - #define STM32F4X_ADC_NUM 24 -#elif defined(STM32F407IX) - #define STM32F4X_PIN_NUM 176 //176 pins mcu, 140 gpio - #define STM32F4X_GPIO_NUM 140 - #define STM32F4X_ADC_NUM 24 -#else - #error "no match MCU defined" -#endif - -#if STM32F4X_PIN_NUM >= 64 //64 pins mcu, 51 gpio - #define PC13 0 - #define PC14 1 //OSC32_IN - #define PC15 2 //OSC32_OUT - #define PH0 3 //OSC_IN - #define PH1 4 //OSC_OUT - #define PB2 5 //BOOT1 - #define PB10 6 //1:SPI2_SCK / I2C2_SCL / USART3_TX / TIM2_CH3 - #define PB11 7 //1:I2C2_SDA / USART3_RX / TIM2_CH4 - #define PB12 8 //1:SPI2_NSS / OTG_HS_ID - #define PB13 9 //1:SPI2_SCK 2:OTG_HS_VBUS - #define PB14 10 //1:SPI2_MISO / TIM12_CH1 / OTG_HS_DM - #define PB15 11 //SPI2_MOSI / TIM12_CH2 / OTG_HS_DP - #define PC6 12 //1:TIM8_CH1 / SDIO_D6 / USART6_TX / TIM3_CH1 - #define PC7 13 //1:TIM8_CH2 / SDIO_D7 / USART6_RX / TIM3_CH2 - #define PC8 14 //1:TIM8_CH3 / SDIO_D0 / TIM3_CH3 - #define PC9 15 //1:TIM8_CH4 / SDIO_D1 / TIM3_CH4 - #define PA8 16 //1:TIM1_CH1 / I2C3_SCL / OTG_FS_SOF - #define PA9 17 //1:USART1_TX / TIM1_CH2 2:OTG_FS_VBUS - #define PA10 18 //1:USART1_RX / TIM1_CH3 / OTG_FS_ID - #define PA11 19 //1:TIM1_CH4 / OTG_FS_DM - #define PA12 20 //1:OTG_FS_DP - #define PA13 21 //0:JTMS-SWDIO - #define PA14 22 //0:JTCK-SWCLK - #define PA15 23 //0:JTDI 1:SPI3_NSS / SPI1_NSS - #define PC10 24 //1:UART4_TX / SPI3_SCK / SDIO_D2 / USART3_TX - #define PC11 25 //1:UART4_RX / SPI3_MISO / SDIO_D3 / USART3_RX - #define PC12 26 //1:UART5_TX / SPI3_MOSI / SDIO_CK - #define PD2 27 //1:UART5_RX / SDIO_CMD - #define PB3 28 //0:JTDO 1:SPI3_SCK / TIM2_CH2 / SPI1_SCK - #define PB4 29 //0:NJTRST 1:SPI3_MISO / TIM3_CH1 / SPI1_MISO - #define PB5 30 //1:TIM3_CH2 / SPI1_MOSI / SPI3_MOSI - #define PB6 31 //1:I2C1_SCL / TIM4_CH1 / USART1_TX - #define PB7 32 //1:I2C1_SDA / TIM4_CH2 / USART1_RX - #define PB8 33 //1:I2C1_SCL / TIM4_CH3 / SDIO_D4 / TIM10_CH1 - #define PB9 34 //1:I2C1_SDA / TIM4_CH4 / SDIO_D5 / TIM11_CH1 / SPI2_NSS - #define PA0 35 //1:UART4_TX / TIM5_CH1 2:ADC123_IN0 - #define PA1 36 //1:UART4_RX / TIM5_CH2 / TIM2_CH2 2:ADC123_IN1 - #define PA2 37 //1:USART2_TX /TIM5_CH3 / TIM9_CH1 / TIM2_CH3 2:ADC123_IN2 - #define PA3 38 //1:USART2_RX /TIM5_CH4 / TIM9_CH2 / TIM2_CH4 2:ADC123_IN3 - #define PA4 39 //NOT FT 1:SPI1_NSS / SPI3_NSS / USART2_CK 2:ADC12_IN4 / DAC_OUT1 - #define PA5 40 //NOT FT 1:SPI1_SCK 2:ADC12_IN5 / DAC_OUT2 - #define PA6 41 //1:SPI1_MISO / TIM13_CH1 / TIM3_CH1 2:ADC12_IN6 - #define PA7 42 //1:SPI1_MOSI / TIM14_CH1 / TIM3_CH2 2:ADC12_IN7 - #define PB0 43 //1:TIM3_CH3 2:ADC12_IN8 - #define PB1 44 //1:TIM3_CH4 2:ADC12_IN9 - #define PC0 45 //1: 2:ADC123_IN10 - #define PC1 46 //1: 2:ADC123_IN11 - #define PC2 47 //1:SPI2_MISO 2:ADC123_IN12 - #define PC3 48 //1:SPI2_MOSI 2:ADC123_IN13 - #define PC4 49 //1: 2:ADC12_IN14 - #define PC5 50 //1: 2:ADC12_IN15 - #if STM32F4X_PIN_NUM >= 144 - #define PF3 51 //1:FSMC_A3 2:ADC3_IN9 - #define PF4 52 //1:FSMC_A4 2:ADC3_IN14 - #define PF5 53 //1:FSMC_A5 2:ADC3_IN15 - #define PF6 54 //1:TIM10_CH1 2:ADC3_IN4 - #define PF7 55 //1:TIM11_CH1 2:ADC3_IN5 - #define PF8 56 //1:TIM13_CH1 2:ADC3_IN6 - #define PF9 57 //1;TIM14_CH1 2:ADC3_IN7 - #define PF10 58 //2:ADC3_IN8 - #endif -#endif -#if STM32F4X_PIN_NUM >= 100 //100 pins mcu, 82 gpio - #define PE2 (35+STM32F4X_ADC_NUM) //1:FSMC_A23 - #define PE3 (36+STM32F4X_ADC_NUM) //1:FSMC_A19 - #define PE4 (37+STM32F4X_ADC_NUM) //1:FSMC_A20 - #define PE5 (38+STM32F4X_ADC_NUM) //1:FSMC_A21 - #define PE6 (39+STM32F4X_ADC_NUM) //1:FSMC_A22 - #define PE7 (40+STM32F4X_ADC_NUM) //1:FSMC_D4 - #define PE8 (41+STM32F4X_ADC_NUM) //1:FSMC_D5 - #define PE9 (42+STM32F4X_ADC_NUM) //1:FSMC_D6 / TIM1_CH1 - #define PE10 (43+STM32F4X_ADC_NUM) //1:FSMC_D7 - #define PE11 (44+STM32F4X_ADC_NUM) //1:FSMC_D8 / TIM1_CH2 - #define PE12 (45+STM32F4X_ADC_NUM) //1:FSMC_D9 - #define PE13 (46+STM32F4X_ADC_NUM) //1:FSMC_D10 / TIM1_CH3 - #define PE14 (47+STM32F4X_ADC_NUM) //1:FSMC_D11 / TIM1_CH4 - #define PE15 (48+STM32F4X_ADC_NUM) //1:FSMC_D12 - #define PD8 (49+STM32F4X_ADC_NUM) //1:FSMC_D13 / USART3_TX - #define PD9 (50+STM32F4X_ADC_NUM) //1:FSMC_D14 / USART3_RX - #define PD10 (51+STM32F4X_ADC_NUM) //1:FSMC_D15 - #define PD11 (52+STM32F4X_ADC_NUM) //1:FSMC_A16 - #define PD12 (53+STM32F4X_ADC_NUM) //1:FSMC_A17 / TIM4_CH1 - #define PD13 (54+STM32F4X_ADC_NUM) //1:FSMC_A18 / TIM4_CH2 - #define PD14 (55+STM32F4X_ADC_NUM) //1:FSMC_D0 / TIM4_CH3 - #define PD15 (56+STM32F4X_ADC_NUM) //1:FSMC_D1 / TIM4_CH4 - #define PD0 (57+STM32F4X_ADC_NUM) //1:FSMC_D2 - #define PD1 (58+STM32F4X_ADC_NUM) //1:FSMC_D3 - #define PD3 (59+STM32F4X_ADC_NUM) //1:FSMC_CLK - #define PD4 (60+STM32F4X_ADC_NUM) //1:FSMC_NOE - #define PD5 (61+STM32F4X_ADC_NUM) //1:USART2_TX - #define PD6 (62+STM32F4X_ADC_NUM) //1:USART2_RX - #define PD7 (63+STM32F4X_ADC_NUM) - #define PE0 (64+STM32F4X_ADC_NUM) - #define PE1 (65+STM32F4X_ADC_NUM) -#endif -#if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio - #define PF0 (66+STM32F4X_ADC_NUM) //1:FSMC_A0 / I2C2_SDA - #define PF1 (67+STM32F4X_ADC_NUM) //1:FSMC_A1 / I2C2_SCL - #define PF2 (68+STM32F4X_ADC_NUM) //1:FSMC_A2 - #define PF11 (69+STM32F4X_ADC_NUM) - #define PF12 (70+STM32F4X_ADC_NUM) //1:FSMC_A6 - #define PF13 (71+STM32F4X_ADC_NUM) //1:FSMC_A7 - #define PF14 (72+STM32F4X_ADC_NUM) //1:FSMC_A8 - #define PF15 (73+STM32F4X_ADC_NUM) //1:FSMC_A9 - #define PG0 (74+STM32F4X_ADC_NUM) //1:FSMC_A10 - #define PG1 (75+STM32F4X_ADC_NUM) //1:FSMC_A11 - #define PG2 (76+STM32F4X_ADC_NUM) //1:FSMC_A12 - #define PG3 (77+STM32F4X_ADC_NUM) //1:FSMC_A13 - #define PG4 (78+STM32F4X_ADC_NUM) //1:FSMC_A14 - #define PG5 (79+STM32F4X_ADC_NUM) //1:FSMC_A15 - #define PG6 (80+STM32F4X_ADC_NUM) - #define PG7 (81+STM32F4X_ADC_NUM) - #define PG8 (82+STM32F4X_ADC_NUM) - #define PG9 (83+STM32F4X_ADC_NUM) //1:USART6_RX - #define PG10 (84+STM32F4X_ADC_NUM) //1:FSMC_NE3 - #define PG11 (85+STM32F4X_ADC_NUM) - #define PG12 (86+STM32F4X_ADC_NUM) //1:FSMC_NE4 - #define PG13 (87+STM32F4X_ADC_NUM) //1:FSMC_A24 - #define PG14 (88+STM32F4X_ADC_NUM) //1:FSMC_A25 / USART6_TX - #define PG15 (89+STM32F4X_ADC_NUM) -#endif -#if STM32F4X_PIN_NUM >= 176 //176 pins mcu, 140 gpio - #define PI8 (90+STM32F4X_ADC_NUM) - #define PI9 (91+STM32F4X_ADC_NUM) - #define PI10 (92+STM32F4X_ADC_NUM) - #define PI11 (93+STM32F4X_ADC_NUM) - #define PH2 (94+STM32F4X_ADC_NUM) - #define PH3 (95+STM32F4X_ADC_NUM) - #define PH4 (96+STM32F4X_ADC_NUM) //1:I2C2_SCL - #define PH5 (97+STM32F4X_ADC_NUM) //1:I2C2_SDA - #define PH6 (98+STM32F4X_ADC_NUM) //1:TIM12_CH1 - #define PH7 (99+STM32F4X_ADC_NUM) //1:I2C3_SCL - #define PH8 (100+STM32F4X_ADC_NUM) //1:I2C3_SDA - #define PH9 (101+STM32F4X_ADC_NUM) //1:TIM12_CH2 - #define PH10 (102+STM32F4X_ADC_NUM) //1:TIM5_CH1 - #define PH11 (103+STM32F4X_ADC_NUM) //1:TIM5_CH2 - #define PH12 (104+STM32F4X_ADC_NUM) //1:TIM5_CH3 - #define PH13 (105+STM32F4X_ADC_NUM) - #define PH14 (106+STM32F4X_ADC_NUM) - #define PH15 (107+STM32F4X_ADC_NUM) - #define PI0 (108+STM32F4X_ADC_NUM) //1:TIM5_CH4 / SPI2_NSS - #define PI1 (109+STM32F4X_ADC_NUM) //1:SPI2_SCK - #define PI2 (110+STM32F4X_ADC_NUM) //1:TIM8_CH4 /SPI2_MISO - #define PI3 (111+STM32F4X_ADC_NUM) //1:SPI2_MOS - #define PI4 (112+STM32F4X_ADC_NUM) - #define PI5 (113+STM32F4X_ADC_NUM) //1:TIM8_CH1 - #define PI6 (114+STM32F4X_ADC_NUM) //1:TIM8_CH2 - #define PI7 (115+STM32F4X_ADC_NUM) //1:TIM8_CH3 -#endif - - -// This must be a literal -#define NUM_DIGITAL_PINS (STM32F4X_GPIO_NUM) -// This must be a literal with a value less than or equal to MAX_ANALOG_INPUTS -#define NUM_ANALOG_INPUTS (STM32F4X_ADC_NUM) -#define NUM_ANALOG_FIRST 35 - -// Below ADC, DAC and PWM definitions already done in the core -// Could be redefined here if needed -// ADC resolution is 12bits -//#define ADC_RESOLUTION 12 -//#define DACC_RESOLUTION 12 - -// PWM resolution -/* - * BEWARE: - * Changing this value from the default (1000) will affect the PWM output value of analogWrite (to a PWM pin) - * Since the pin is toggled on capture, if you change the frequency of the timer you have to adapt the compare value (analogWrite thinks you did) - */ -//#define PWM_FREQUENCY 20000 -//The bottom values are the default and don't need to be redefined -//#define PWM_RESOLUTION 8 -//#define PWM_MAX_DUTY_CYCLE 255 - -// On-board LED pin number -#define LED_BUILTIN PA7 -#define LED_GREEN LED_BUILTIN - -// Below SPI and I2C definitions already done in the core -// Could be redefined here if differs from the default one -// SPI Definitions -#define PIN_SPI_MOSI PB15 -#define PIN_SPI_MISO PB14 -#define PIN_SPI_SCK PB13 -#define PIN_SPI_SS PB12 - -// I2C Definitions -#if STM32F4X_PIN_NUM >= 176 - #define PIN_WIRE_SDA PH5 - #define PIN_WIRE_SCL PH4 -#else - #define PIN_WIRE_SDA PB7 - #define PIN_WIRE_SCL PB6 -#endif - -// Timer Definitions -//Do not use timer used by PWM pins when possible. See PinMap_PWM in PeripheralPins.c -#define TIMER_TONE TIM10 -#define TIMER_SERVO TIM5 -#define TIMER_SERIAL TIM7 - -// UART Definitions -//#define ENABLE_HWSERIAL1 done automatically by the #define SERIAL_UART_INSTANCE below -#define ENABLE_HWSERIAL3 -#define ENABLE_HWSERIAL6 - -// 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) - -// DEBUG_UART could be redefined to print on another instance than 'Serial' -//#define DEBUG_UART ((USART_TypeDef *) U(S)ARTX) // ex: USART3 -// DEBUG_UART baudrate, default: 9600 if not defined -//#define DEBUG_UART_BAUDRATE x -// DEBUG_UART Tx pin name, default: the first one found in PinMap_UART_TX for DEBUG_UART -//#define DEBUG_PINNAME_TX PX_n // PinName used for TX - -// Default pin used for 'Serial' instance (ex: ST-Link) -// Mandatory for Firmata -#define PIN_SERIAL_RX PA10 -#define PIN_SERIAL_TX PA9 - -// Optional PIN_SERIALn_RX and PIN_SERIALn_TX where 'n' is the U(S)ART number -// 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_SERIAL3_RX PD9 -#define PIN_SERIAL3_TX PD8 -#define PIN_SERIAL6_RX PC7 -#define PIN_SERIAL6_TX PC6 -//#define PIN_SERIALLP1_RX x // For LPUART1 RX -//#define PIN_SERIALLP1_TX x // For LPUART1 TX - -#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 Serial3 -#define SERIAL_PORT_HARDWARE_OPEN1 Serial6 -#endif diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/PeripheralPins.c b/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/PeripheralPins.c deleted file mode 100644 index 6dc8b05158b3..000000000000 --- a/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/PeripheralPins.c +++ /dev/null @@ -1,372 +0,0 @@ -/* - ******************************************************************************* - * 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 STM32F407Z(E-G)Tx.xml - */ -#include -#include - -/* ===== - * Note: Commented lines are alternative possibilities which are not used by default. - * If you change them, you should know what you're doing first. - * ===== - */ - -//*** ADC *** - -#ifdef HAL_ADC_MODULE_ENABLED -const PinMap PinMap_ADC[] = { - {PA_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0 E0_DIR - {PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1 BLTOUCH_2 - {PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2 BLTOUCH_4 - {PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3 E1_EN - {PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4 TF_SS - {PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5 TF_SCLK - {PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6 TF_MISO - {PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7 LED - {PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8 HEATER2 - {PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9 HEATER0 - {PC_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10 Z_EN - {PC_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11 EXP_14 - {PC_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12 Z_DIR - {PC_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13 E0_EN - {PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14 EXP_8 - {PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15 EXP_7 - - #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio, 24 ADC - {PF_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC3_IN9 TH_0 - {PF_4, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC3_IN14 TH_1 - {PF_5, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC3_IN15 TH_2 - {PF_6, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC3_IN4 TH_3 - {PF_7, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC3_IN5 EXP_13 - {PF_8, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC3_IN6 EXP_3 - {PF_9, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC3_IN7 EXP_6 - {PF_10, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC3_IN8 EXP_5 - #endif - {NC, NP, 0} -}; -#endif - -//*** DAC *** - -#ifdef HAL_DAC_MODULE_ENABLED -const PinMap PinMap_DAC[] = { - {PA_4, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // DAC_OUT1 - {PA_5, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // DAC_OUT2 - {NC, NP, 0} -}; -#endif - -//*** I2C *** - -#ifdef HAL_I2C_MODULE_ENABLED -const PinMap PinMap_I2C_SDA[] = { - {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)}, - {PB_11, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, - {PC_9, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, - #if STM32F4X_PIN_NUM >= 144 // 144 pins mcu, 114 gpio - #if STM32F4X_PIN_NUM >= 176 - {PH_5, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, - {PH_8, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, - #else - {PF_0, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, - #endif - #endif - {NC, NP, 0} -}; -#endif - -#ifdef HAL_I2C_MODULE_ENABLED -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)}, - #if STM32F4X_PIN_NUM >= 144 // 144 pins mcu, 114 gpio - #if STM32F4X_PIN_NUM >= 176 - //{PF_1, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, - {PH_4, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, - {PH_7, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, - #else - {PF_1, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, - #endif - #endif - {NC, NP, 0} -}; -#endif - -//*** PWM *** - -#ifdef HAL_TIM_MODULE_ENABLED -const PinMap PinMap_PWM[] = { - {PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 HEATER0 - {PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 HEATER1 - {PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 HEATER2 - {PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 BED - {PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 0)}, // TIM8_CH3 FAN0 - {PE_5, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 FAN1 - {PE_6, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2 FAN2 - {PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 4, 0)}, // TIM8_CH4 EXTENSION1-4 - {PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 BL-TOUCH-SERVO - - // These pins have been defined for something else on the board but they MIGHT be - // used by the user as PWM pins if they aren't used for their primary purpose. - {PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 ESP8266 connector. Available if 8266 isn't used - {PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 ESP8266 connector. Available if 8266 isn't used - {PB_7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 I2C connector, SDA pin. Available if I2C isn't used. - // TIM5_CH1 is used by the Servo Library - {PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3 BL-TOUCH port. Available if Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN - - /** - * Unused by specifications on SKR-Pro. - * Uncomment the corresponding line if you want to have HardwarePWM on some pins. - * WARNING: check timers' usage first to avoid conflicts. - * If you don't know what you're doing leave things as they are or you WILL break something (including hardware) - * If you alter this section DO NOT report bugs to Marlin team since they are most likely caused by you. Thank you. - */ - //{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 BLTOUCH is a "servo" - //{PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 BLTOUCH is a "servo" - //{PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 - //{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_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N - //{PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 - //{PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 - //{PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N - //{PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 - //{PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N - //{PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 - //{PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 - //{PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 - //{PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 - //{PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 - //{PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 - //{PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N - //{PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N - //{PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N - //{PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N - //{PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 - //{PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 - //{PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 - //{PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 - //{PB_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_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 - //{PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N - //{PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N - //{PB_14, 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 - //{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 - //{PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 - //{PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 - //{PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 - //{PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 - //{PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 - //{PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 - //{PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 - //{PE_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N - //{PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 - //{PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N - //{PE_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 - //{PE_12, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N - //{PE_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 - //{PE_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 - #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio - //{PF_6, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1 - //{PF_7, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 - //{PF_8, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 - //{PF_9, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 - #endif - #if STM32F4X_PIN_NUM >= 176 //176 pins mcu, 140 gpio - {PH_10, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1 - {PH_6, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 1, 0)}, // TIM12_CH1 - //{PH_11, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 - {PI_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 - {PI_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 - #endif - {NC, NP, 0} -}; -#endif - -//*** SERIAL *** - -#ifdef HAL_UART_MODULE_ENABLED -const PinMap PinMap_UART_TX[] = { - {PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, - {PD_8, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - {PC_6, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio - //{PG_14, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - #endif - //{PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, - //{PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - //{PD_5, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - //{PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - //{PC_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - //{PA_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, - //{PC_10, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, - //{PC_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, - {NC, NP, 0} -}; - -const PinMap PinMap_UART_RX[] = { - {PA_10, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, - {PD_9, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - {PC_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - //{PA_1, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, - //{PA_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - //{PB_7, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, - //{PB_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - //{PC_11, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, - //{PC_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - //{PD_2, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, - //{PD_6, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio - //{PG_9, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - #endif - {NC, NP, 0} -}; - -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)}, - //{PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - //{PD_4, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - //{PD_12, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio - //{PG_8, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - //{PG_12, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - #endif - {NC, NP, 0} -}; - -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)}, - //{PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - //{PD_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - //{PD_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio - //{PG_13, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - //{PG_15, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - #endif - {NC, NP, 0} -}; -#endif - -//*** SPI *** - -#ifdef HAL_SPI_MODULE_ENABLED -const PinMap PinMap_SPI_MOSI[] = { - {PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, - {PB_15, 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} -}; - -const PinMap PinMap_SPI_MISO[] = { - {PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, - {PB_14, 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} -}; - -const PinMap PinMap_SPI_SCLK[] = { - {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, - {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} -}; - -const PinMap PinMap_SPI_SSEL[] = { - {PA_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, - {PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, - {PA_15, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, - {NC, NP, 0} -}; -#endif - -//*** CAN *** - -#ifdef HAL_CAN_MODULE_ENABLED -#error "CAN bus isn't available on this board. Driver should be disabled." -#endif - -//*** ETHERNET *** -#ifdef HAL_ETH_MODULE_ENABLED -#error "Ethernet port isn't available on this board. Driver should be disabled." -#endif - -//*** No QUADSPI *** - -//*** USB *** -#ifdef HAL_PCD_MODULE_ENABLED -const PinMap PinMap_USB_OTG_FS[] = { - //{PA_8, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_SOF used by LCD - //{PA_9, USB_OTG_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_FS_VBUS available on wifi port, if empty - //{PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_ID available on UART1_RX if not used - {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} -}; - -const PinMap PinMap_USB_OTG_HS[] = { /* - #ifdef USE_USB_HS_IN_FS - {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_ID - {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_HS_VBUS - {PB_14, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DM - {PB_15, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DP - #else - #error "USB in HS mode isn't supported by the board" - {PA_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D0 - {PB_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D1 - {PB_1, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D2 - {PB_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D7 - {PB_10, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D3 - {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D5 - {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D6 - {PC_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_STP - {PC_2, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_DIR - {PC_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_NXT - #endif // USE_USB_HS_IN_FS - */ - {NC, NP, 0} -}; -#endif diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/hal_conf_extra.h b/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/hal_conf_extra.h deleted file mode 100644 index e0e8239aac08..000000000000 --- a/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/hal_conf_extra.h +++ /dev/null @@ -1,52 +0,0 @@ -#pragma once - -#define HAL_MODULE_ENABLED -#define HAL_ADC_MODULE_ENABLED -#define HAL_CRC_MODULE_ENABLED -#define HAL_DMA_MODULE_ENABLED -#define HAL_GPIO_MODULE_ENABLED -#define HAL_I2C_MODULE_ENABLED -#define HAL_PWR_MODULE_ENABLED -#define HAL_RCC_MODULE_ENABLED -//#define HAL_RTC_MODULE_ENABLED Real Time Clock...do we use it? -#define HAL_SPI_MODULE_ENABLED -#define HAL_TIM_MODULE_ENABLED -#define HAL_USART_MODULE_ENABLED -#define HAL_CORTEX_MODULE_ENABLED -//#define HAL_UART_MODULE_ENABLED // by default -//#define HAL_PCD_MODULE_ENABLED // Since STM32 v3.10700.191028 this is automatically added if any type of USB is enabled (as in Arduino IDE) - -#undef HAL_SD_MODULE_ENABLED -#undef HAL_DAC_MODULE_ENABLED -#undef HAL_FLASH_MODULE_ENABLED -#undef HAL_CAN_MODULE_ENABLED -#undef HAL_CAN_LEGACY_MODULE_ENABLED -#undef HAL_CEC_MODULE_ENABLED -#undef HAL_CRYP_MODULE_ENABLED -#undef HAL_DCMI_MODULE_ENABLED -#undef HAL_DMA2D_MODULE_ENABLED -#undef HAL_ETH_MODULE_ENABLED -#undef HAL_NAND_MODULE_ENABLED -#undef HAL_NOR_MODULE_ENABLED -#undef HAL_PCCARD_MODULE_ENABLED -#undef HAL_SRAM_MODULE_ENABLED -#undef HAL_SDRAM_MODULE_ENABLED -#undef HAL_HASH_MODULE_ENABLED -#undef HAL_EXTI_MODULE_ENABLED -#undef HAL_SMBUS_MODULE_ENABLED -#undef HAL_I2S_MODULE_ENABLED -#undef HAL_IWDG_MODULE_ENABLED -#undef HAL_LTDC_MODULE_ENABLED -#undef HAL_DSI_MODULE_ENABLED -#undef HAL_QSPI_MODULE_ENABLED -#undef HAL_RNG_MODULE_ENABLED -#undef HAL_SAI_MODULE_ENABLED -#undef HAL_IRDA_MODULE_ENABLED -#undef HAL_SMARTCARD_MODULE_ENABLED -#undef HAL_WWDG_MODULE_ENABLED -#undef HAL_HCD_MODULE_ENABLED -#undef HAL_FMPI2C_MODULE_ENABLED -#undef HAL_SPDIFRX_MODULE_ENABLED -#undef HAL_DFSDM_MODULE_ENABLED -#undef HAL_LPTIM_MODULE_ENABLED -#undef HAL_MMC_MODULE_ENABLED diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/ldscript.ld b/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/ldscript.ld deleted file mode 100644 index 0c060d175180..000000000000 --- a/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/ldscript.ld +++ /dev/null @@ -1,204 +0,0 @@ -/* -***************************************************************************** -** - -** File : LinkerScript.ld -** -** Abstract : Linker script for STM32F407ZGTx Device with -** 1024KByte FLASH, 128KByte 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 = 0x20020000; /* 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 = 0x8008000, LENGTH = 1024K -RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K -CCMRAM (rw) : ORIGIN = 0x10000000, 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): - { - . = 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 - - _siccmram = LOADADDR(.ccmram); - - /* CCM-RAM section - * - * IMPORTANT NOTE! - * If initialized variables will be placed in this section, - * the startup code needs to be modified to copy the init-values. - */ - .ccmram : - { - . = ALIGN(4); - _sccmram = .; /* create a global symbol at ccmram start */ - *(.ccmram) - *(.ccmram*) - - . = ALIGN(4); - _eccmram = .; /* create a global symbol at ccmram end */ - } >CCMRAM AT> FLASH - - - /* Uninitialized data section */ - . = ALIGN(4); - .bss : - { - /* This is used by the startup in order to initialize the .bss secion */ - _sbss = .; /* define a global symbol at bss start */ - __bss_start__ = _sbss; - *(.bss) - *(.bss*) - *(COMMON) - - . = ALIGN(4); - _ebss = .; /* define a global symbol at bss end */ - __bss_end__ = _ebss; - } >RAM - - /* User_heap_stack section, used to check that there is enough RAM left */ - ._user_heap_stack : - { - . = ALIGN(4); - PROVIDE ( end = . ); - PROVIDE ( _end = . ); - . = . + _Min_Heap_Size; - . = . + _Min_Stack_Size; - . = ALIGN(4); - } >RAM - - /* Remove information from the standard libraries */ - /DISCARD/ : - { - libc.a ( * ) - libm.a ( * ) - libgcc.a ( * ) - } - - .ARM.attributes 0 : { *(.ARM.attributes) } -} diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/variant.h b/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/variant.h deleted file mode 100644 index 1ba0a18d6af6..000000000000 --- a/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/variant.h +++ /dev/null @@ -1,322 +0,0 @@ -/* - ******************************************************************************* - * Copyright (c) 2017, 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. - ******************************************************************************* - */ -#pragma once - -#ifdef __cplusplus -extern "C" { -#endif // __cplusplus - -/*---------------------------------------------------------------------------- - * Pins - *----------------------------------------------------------------------------*/ - -#ifdef STM32F405RX - #define STM32F4X_PIN_NUM 64 //64 pins mcu, 51 gpio - #define STM32F4X_GPIO_NUM 51 - #define STM32F4X_ADC_NUM 16 -#elif defined(STM32F407_5VX) - #define STM32F4X_PIN_NUM 100 //100 pins mcu, 82 gpio - #define STM32F4X_GPIO_NUM 82 - #define STM32F4X_ADC_NUM 16 -#elif defined(STM32F407_5ZX) - #define STM32F4X_PIN_NUM 144 //144 pins mcu, 114 gpio - #define STM32F4X_GPIO_NUM 114 - #define STM32F4X_ADC_NUM 24 -#elif defined(STM32F407IX) - #define STM32F4X_PIN_NUM 176 //176 pins mcu, 140 gpio - #define STM32F4X_GPIO_NUM 140 - #define STM32F4X_ADC_NUM 24 -#else - #error "no match MCU defined" -#endif - -#if STM32F4X_PIN_NUM >= 64 //64 pins mcu, 51 gpio - #define PC13 0 - #define PC14 1 //OSC32_IN - #define PC15 2 //OSC32_OUT - #define PH0 3 //OSC_IN - #define PH1 4 //OSC_OUT - #define PB2 5 //BOOT1 - #define PB10 6 //1:SPI2_SCK / I2C2_SCL / USART3_TX / TIM2_CH3 - #define PB11 7 //1:I2C2_SDA / USART3_RX / TIM2_CH4 - #define PB12 8 //1:SPI2_NSS / OTG_HS_ID - #define PB13 9 //1:SPI2_SCK 2:OTG_HS_VBUS - #define PB14 10 //1:SPI2_MISO / TIM12_CH1 / OTG_HS_DM - #define PB15 11 //SPI2_MOSI / TIM12_CH2 / OTG_HS_DP - #define PC6 12 //1:TIM8_CH1 / SDIO_D6 / USART6_TX / TIM3_CH1 - #define PC7 13 //1:TIM8_CH2 / SDIO_D7 / USART6_RX / TIM3_CH2 - #define PC8 14 //1:TIM8_CH3 / SDIO_D0 / TIM3_CH3 - #define PC9 15 //1:TIM8_CH4 / SDIO_D1 / TIM3_CH4 - #define PA8 16 //1:TIM1_CH1 / I2C3_SCL / OTG_FS_SOF - #define PA9 17 //1:USART1_TX / TIM1_CH2 2:OTG_FS_VBUS - #define PA10 18 //1:USART1_RX / TIM1_CH3 / OTG_FS_ID - #define PA11 19 //1:TIM1_CH4 / OTG_FS_DM - #define PA12 20 //1:OTG_FS_DP - #define PA13 21 //0:JTMS-SWDIO - #define PA14 22 //0:JTCK-SWCLK - #define PA15 23 //0:JTDI 1:SPI3_NSS / SPI1_NSS - #define PC10 24 //1:UART4_TX / SPI3_SCK / SDIO_D2 / USART3_TX - #define PC11 25 //1:UART4_RX / SPI3_MISO / SDIO_D3 / USART3_RX - #define PC12 26 //1:UART5_TX / SPI3_MOSI / SDIO_CK - #define PD2 27 //1:UART5_RX / SDIO_CMD - #define PB3 28 //0:JTDO 1:SPI3_SCK / TIM2_CH2 / SPI1_SCK - #define PB4 29 //0:NJTRST 1:SPI3_MISO / TIM3_CH1 / SPI1_MISO - #define PB5 30 //1:TIM3_CH2 / SPI1_MOSI / SPI3_MOSI - #define PB6 31 //1:I2C1_SCL / TIM4_CH1 / USART1_TX - #define PB7 32 //1:I2C1_SDA / TIM4_CH2 / USART1_RX - #define PB8 33 //1:I2C1_SCL / TIM4_CH3 / SDIO_D4 / TIM10_CH1 - #define PB9 34 //1:I2C1_SDA / TIM4_CH4 / SDIO_D5 / TIM11_CH1 / SPI2_NSS - #define PA0 35 //1:UART4_TX / TIM5_CH1 2:ADC123_IN0 - #define PA1 36 //1:UART4_RX / TIM5_CH2 / TIM2_CH2 2:ADC123_IN1 - #define PA2 37 //1:USART2_TX /TIM5_CH3 / TIM9_CH1 / TIM2_CH3 2:ADC123_IN2 - #define PA3 38 //1:USART2_RX /TIM5_CH4 / TIM9_CH2 / TIM2_CH4 2:ADC123_IN3 - #define PA4 39 //NOT FT 1:SPI1_NSS / SPI3_NSS / USART2_CK 2:ADC12_IN4 / DAC_OUT1 - #define PA5 40 //NOT FT 1:SPI1_SCK 2:ADC12_IN5 / DAC_OUT2 - #define PA6 41 //1:SPI1_MISO / TIM13_CH1 / TIM3_CH1 2:ADC12_IN6 - #define PA7 42 //1:SPI1_MOSI / TIM14_CH1 / TIM3_CH2 2:ADC12_IN7 - #define PB0 43 //1:TIM3_CH3 2:ADC12_IN8 - #define PB1 44 //1:TIM3_CH4 2:ADC12_IN9 - #define PC0 45 //1: 2:ADC123_IN10 - #define PC1 46 //1: 2:ADC123_IN11 - #define PC2 47 //1:SPI2_MISO 2:ADC123_IN12 - #define PC3 48 //1:SPI2_MOSI 2:ADC123_IN13 - #define PC4 49 //1: 2:ADC12_IN14 - #define PC5 50 //1: 2:ADC12_IN15 - #if STM32F4X_PIN_NUM >= 144 - #define PF3 51 //1:FSMC_A3 2:ADC3_IN9 - #define PF4 52 //1:FSMC_A4 2:ADC3_IN14 - #define PF5 53 //1:FSMC_A5 2:ADC3_IN15 - #define PF6 54 //1:TIM10_CH1 2:ADC3_IN4 - #define PF7 55 //1:TIM11_CH1 2:ADC3_IN5 - #define PF8 56 //1:TIM13_CH1 2:ADC3_IN6 - #define PF9 57 //1;TIM14_CH1 2:ADC3_IN7 - #define PF10 58 //2:ADC3_IN8 - #endif -#endif -#if STM32F4X_PIN_NUM >= 100 //100 pins mcu, 82 gpio - #define PE2 (35+STM32F4X_ADC_NUM) //1:FSMC_A23 - #define PE3 (36+STM32F4X_ADC_NUM) //1:FSMC_A19 - #define PE4 (37+STM32F4X_ADC_NUM) //1:FSMC_A20 - #define PE5 (38+STM32F4X_ADC_NUM) //1:FSMC_A21 - #define PE6 (39+STM32F4X_ADC_NUM) //1:FSMC_A22 - #define PE7 (40+STM32F4X_ADC_NUM) //1:FSMC_D4 - #define PE8 (41+STM32F4X_ADC_NUM) //1:FSMC_D5 - #define PE9 (42+STM32F4X_ADC_NUM) //1:FSMC_D6 / TIM1_CH1 - #define PE10 (43+STM32F4X_ADC_NUM) //1:FSMC_D7 - #define PE11 (44+STM32F4X_ADC_NUM) //1:FSMC_D8 / TIM1_CH2 - #define PE12 (45+STM32F4X_ADC_NUM) //1:FSMC_D9 - #define PE13 (46+STM32F4X_ADC_NUM) //1:FSMC_D10 / TIM1_CH3 - #define PE14 (47+STM32F4X_ADC_NUM) //1:FSMC_D11 / TIM1_CH4 - #define PE15 (48+STM32F4X_ADC_NUM) //1:FSMC_D12 - #define PD8 (49+STM32F4X_ADC_NUM) //1:FSMC_D13 / USART3_TX - #define PD9 (50+STM32F4X_ADC_NUM) //1:FSMC_D14 / USART3_RX - #define PD10 (51+STM32F4X_ADC_NUM) //1:FSMC_D15 - #define PD11 (52+STM32F4X_ADC_NUM) //1:FSMC_A16 - #define PD12 (53+STM32F4X_ADC_NUM) //1:FSMC_A17 / TIM4_CH1 - #define PD13 (54+STM32F4X_ADC_NUM) //1:FSMC_A18 / TIM4_CH2 - #define PD14 (55+STM32F4X_ADC_NUM) //1:FSMC_D0 / TIM4_CH3 - #define PD15 (56+STM32F4X_ADC_NUM) //1:FSMC_D1 / TIM4_CH4 - #define PD0 (57+STM32F4X_ADC_NUM) //1:FSMC_D2 - #define PD1 (58+STM32F4X_ADC_NUM) //1:FSMC_D3 - #define PD3 (59+STM32F4X_ADC_NUM) //1:FSMC_CLK - #define PD4 (60+STM32F4X_ADC_NUM) //1:FSMC_NOE - #define PD5 (61+STM32F4X_ADC_NUM) //1:USART2_TX - #define PD6 (62+STM32F4X_ADC_NUM) //1:USART2_RX - #define PD7 (63+STM32F4X_ADC_NUM) - #define PE0 (64+STM32F4X_ADC_NUM) - #define PE1 (65+STM32F4X_ADC_NUM) -#endif -#if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio - #define PF0 (66+STM32F4X_ADC_NUM) //1:FSMC_A0 / I2C2_SDA - #define PF1 (67+STM32F4X_ADC_NUM) //1:FSMC_A1 / I2C2_SCL - #define PF2 (68+STM32F4X_ADC_NUM) //1:FSMC_A2 - #define PF11 (69+STM32F4X_ADC_NUM) - #define PF12 (70+STM32F4X_ADC_NUM) //1:FSMC_A6 - #define PF13 (71+STM32F4X_ADC_NUM) //1:FSMC_A7 - #define PF14 (72+STM32F4X_ADC_NUM) //1:FSMC_A8 - #define PF15 (73+STM32F4X_ADC_NUM) //1:FSMC_A9 - #define PG0 (74+STM32F4X_ADC_NUM) //1:FSMC_A10 - #define PG1 (75+STM32F4X_ADC_NUM) //1:FSMC_A11 - #define PG2 (76+STM32F4X_ADC_NUM) //1:FSMC_A12 - #define PG3 (77+STM32F4X_ADC_NUM) //1:FSMC_A13 - #define PG4 (78+STM32F4X_ADC_NUM) //1:FSMC_A14 - #define PG5 (79+STM32F4X_ADC_NUM) //1:FSMC_A15 - #define PG6 (80+STM32F4X_ADC_NUM) - #define PG7 (81+STM32F4X_ADC_NUM) - #define PG8 (82+STM32F4X_ADC_NUM) - #define PG9 (83+STM32F4X_ADC_NUM) //1:USART6_RX - #define PG10 (84+STM32F4X_ADC_NUM) //1:FSMC_NE3 - #define PG11 (85+STM32F4X_ADC_NUM) - #define PG12 (86+STM32F4X_ADC_NUM) //1:FSMC_NE4 - #define PG13 (87+STM32F4X_ADC_NUM) //1:FSMC_A24 - #define PG14 (88+STM32F4X_ADC_NUM) //1:FSMC_A25 / USART6_TX - #define PG15 (89+STM32F4X_ADC_NUM) -#endif -#if STM32F4X_PIN_NUM >= 176 //176 pins mcu, 140 gpio - #define PI8 (90+STM32F4X_ADC_NUM) - #define PI9 (91+STM32F4X_ADC_NUM) - #define PI10 (92+STM32F4X_ADC_NUM) - #define PI11 (93+STM32F4X_ADC_NUM) - #define PH2 (94+STM32F4X_ADC_NUM) - #define PH3 (95+STM32F4X_ADC_NUM) - #define PH4 (96+STM32F4X_ADC_NUM) //1:I2C2_SCL - #define PH5 (97+STM32F4X_ADC_NUM) //1:I2C2_SDA - #define PH6 (98+STM32F4X_ADC_NUM) //1:TIM12_CH1 - #define PH7 (99+STM32F4X_ADC_NUM) //1:I2C3_SCL - #define PH8 (100+STM32F4X_ADC_NUM) //1:I2C3_SDA - #define PH9 (101+STM32F4X_ADC_NUM) //1:TIM12_CH2 - #define PH10 (102+STM32F4X_ADC_NUM) //1:TIM5_CH1 - #define PH11 (103+STM32F4X_ADC_NUM) //1:TIM5_CH2 - #define PH12 (104+STM32F4X_ADC_NUM) //1:TIM5_CH3 - #define PH13 (105+STM32F4X_ADC_NUM) - #define PH14 (106+STM32F4X_ADC_NUM) - #define PH15 (107+STM32F4X_ADC_NUM) - #define PI0 (108+STM32F4X_ADC_NUM) //1:TIM5_CH4 / SPI2_NSS - #define PI1 (109+STM32F4X_ADC_NUM) //1:SPI2_SCK - #define PI2 (110+STM32F4X_ADC_NUM) //1:TIM8_CH4 /SPI2_MISO - #define PI3 (111+STM32F4X_ADC_NUM) //1:SPI2_MOS - #define PI4 (112+STM32F4X_ADC_NUM) - #define PI5 (113+STM32F4X_ADC_NUM) //1:TIM8_CH1 - #define PI6 (114+STM32F4X_ADC_NUM) //1:TIM8_CH2 - #define PI7 (115+STM32F4X_ADC_NUM) //1:TIM8_CH3 -#endif - - -// This must be a literal -#define NUM_DIGITAL_PINS (STM32F4X_GPIO_NUM) -// This must be a literal with a value less than or equal to MAX_ANALOG_INPUTS -#define NUM_ANALOG_INPUTS (STM32F4X_ADC_NUM) -#define NUM_ANALOG_FIRST 35 - -// Below ADC, DAC and PWM definitions already done in the core -// Could be redefined here if needed -// ADC resolution is 12bits -//#define ADC_RESOLUTION 12 -//#define DACC_RESOLUTION 12 - -// PWM resolution -/* - * BEWARE: - * Changing this value from the default (1000) will affect the PWM output value of analogWrite (to a PWM pin) - * Since the pin is toggled on capture, if you change the frequency of the timer you have to adapt the compare value (analogWrite thinks you did) - */ -//#define PWM_FREQUENCY 20000 -//The bottom values are the default and don't need to be redefined -//#define PWM_RESOLUTION 8 -//#define PWM_MAX_DUTY_CYCLE 255 - -// On-board LED pin number -#define LED_BUILTIN PA7 -#define LED_GREEN LED_BUILTIN - -// Below SPI and I2C definitions already done in the core -// Could be redefined here if differs from the default one -// SPI Definitions -#define PIN_SPI_MOSI PB15 -#define PIN_SPI_MISO PB14 -#define PIN_SPI_SCK PB13 -#define PIN_SPI_SS PB12 - -// I2C Definitions -#if STM32F4X_PIN_NUM >= 176 - #define PIN_WIRE_SDA PH5 - #define PIN_WIRE_SCL PH4 -#else - #define PIN_WIRE_SDA PB7 - #define PIN_WIRE_SCL PB6 -#endif - -// Timer Definitions -//Do not use timer used by PWM pins when possible. See PinMap_PWM in PeripheralPins.c -#define TIMER_TONE TIM2 -#define TIMER_SERVO TIM5 // Only 1 Servo PIN on SKR-PRO, so use the same timer as defined in PeripheralPins -#define TIMER_SERIAL TIM7 - -// UART Definitions -//#define ENABLE_HWSERIAL1 done automatically by the #define SERIAL_UART_INSTANCE below -#define ENABLE_HWSERIAL3 -#define ENABLE_HWSERIAL6 - -// 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) - -// DEBUG_UART could be redefined to print on another instance than 'Serial' -//#define DEBUG_UART ((USART_TypeDef *) U(S)ARTX) // ex: USART3 -// DEBUG_UART baudrate, default: 9600 if not defined -//#define DEBUG_UART_BAUDRATE x -// DEBUG_UART Tx pin name, default: the first one found in PinMap_UART_TX for DEBUG_UART -//#define DEBUG_PINNAME_TX PX_n // PinName used for TX - -// Default pin used for 'Serial' instance (ex: ST-Link) -// Mandatory for Firmata -#define PIN_SERIAL_RX PA10 -#define PIN_SERIAL_TX PA9 - -// Optional PIN_SERIALn_RX and PIN_SERIALn_TX where 'n' is the U(S)ART number -// 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_SERIAL3_RX PD9 -#define PIN_SERIAL3_TX PD8 -#define PIN_SERIAL6_RX PC7 -#define PIN_SERIAL6_TX PC6 -//#define PIN_SERIALLP1_RX x // For LPUART1 RX -//#define PIN_SERIALLP1_TX x // For LPUART1 TX - -#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 Serial3 -#define SERIAL_PORT_HARDWARE_OPEN1 Serial6 -#endif diff --git a/buildroot/share/PlatformIO/variants/CHITU_F103/wirish/boards.cpp b/buildroot/share/PlatformIO/variants/CHITU_F103/wirish/boards.cpp deleted file mode 100755 index 2210e9844c53..000000000000 --- a/buildroot/share/PlatformIO/variants/CHITU_F103/wirish/boards.cpp +++ /dev/null @@ -1,225 +0,0 @@ -/****************************************************************************** - * The MIT License - * - * Copyright (c) 2010 Perry Hung. - * Copyright (c) 2011, 2012 LeafLabs, LLC. - * - * Permission is hereby granted, free of charge, to any person - * obtaining a copy of this software and associated documentation - * files (the "Software"), to deal in the Software without - * restriction, including without limitation the rights to use, copy, - * modify, merge, publish, distribute, sublicense, and/or sell copies - * of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be - * included in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, - * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND - * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS - * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN - * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN - * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE - * SOFTWARE. - *****************************************************************************/ - -/** - * @file wirish/boards.cpp - * @brief init() and board routines. - * - * This file is mostly interesting for the init() function, which - * configures Flash, the core clocks, and a variety of other available - * peripherals on the board so the rest of Wirish doesn't have to turn - * things on before using them. - * - * Prior to returning, init() calls boardInit(), which allows boards - * to perform any initialization they need to. This file includes a - * weak no-op definition of boardInit(), so boards that don't need any - * special initialization don't have to define their own. - * - * How init() works is chip-specific. See the boards_setup.cpp files - * under e.g. wirish/stm32f1/, wirish/stmf32f2 for the details, but be - * advised: their contents are unstable, and can/will change without - * notice. - */ - -#include -#include -#include -#include -#include -#include "boards_private.h" - -static void setup_flash(void); -static void setup_clocks(void); -static void setup_nvic(void); -static void setup_adcs(void); -static void setup_timers(void); - -/* - * Exported functions - */ - -void init(void) { - setup_flash(); - setup_clocks(); - setup_nvic(); - systick_init(SYSTICK_RELOAD_VAL); - wirish::priv::board_setup_gpio(); - setup_adcs(); - setup_timers(); - wirish::priv::board_setup_usb(); - wirish::priv::series_init(); - boardInit(); -} - -/* Provide a default no-op boardInit(). */ -__weak void boardInit(void) { -} - -/* You could farm this out to the files in boards/ if e.g. it takes - * too long to test on boards with lots of pins. */ -bool boardUsesPin(uint8 pin) { - for (int i = 0; i < BOARD_NR_USED_PINS; i++) { - if (pin == boardUsedPins[i]) { - return true; - } - } - return false; -} - -/* - * Auxiliary routines - */ - -static void setup_flash(void) { - // Turn on as many Flash "go faster" features as - // possible. flash_enable_features() just ignores any flags it - // can't support. - flash_enable_features(FLASH_PREFETCH | FLASH_ICACHE | FLASH_DCACHE); - // Configure the wait states, assuming we're operating at "close - // enough" to 3.3V. - flash_set_latency(FLASH_SAFE_WAIT_STATES); -} - -static void setup_clocks(void) { - // Turn on HSI. We'll switch to and run off of this while we're - // setting up the main PLL. - rcc_turn_on_clk(RCC_CLK_HSI); - - // Turn off and reset the clock subsystems we'll be using, as well - // as the clock security subsystem (CSS). Note that resetting CFGR - // to its default value of 0 implies a switch to HSI for SYSCLK. - RCC_BASE->CFGR = 0x00000000; - rcc_disable_css(); - rcc_turn_off_clk(RCC_CLK_PLL); - rcc_turn_off_clk(RCC_CLK_HSE); - wirish::priv::board_reset_pll(); - // Clear clock readiness interrupt flags and turn off clock - // readiness interrupts. - RCC_BASE->CIR = 0x00000000; -#if !USE_HSI_CLOCK - // Enable HSE, and wait until it's ready. - rcc_turn_on_clk(RCC_CLK_HSE); - while(!rcc_is_clk_ready(RCC_CLK_HSE)) - ; -#endif - // Configure AHBx, APBx, etc. prescalers and the main PLL. - wirish::priv::board_setup_clock_prescalers(); - rcc_configure_pll(&wirish::priv::w_board_pll_cfg); - - // Enable the PLL, and wait until it's ready. - rcc_turn_on_clk(RCC_CLK_PLL); - while(!rcc_is_clk_ready(RCC_CLK_PLL)) - ; - - // Finally, switch to the now-ready PLL as the main clock source. - rcc_switch_sysclk(RCC_CLKSRC_PLL); -} - -/* - * These addresses are where usercode starts when a bootloader is - * present. If no bootloader is present, the user NVIC usually starts - * at the Flash base address, 0x08000000. - */ -#if defined(BOOTLOADER_maple) - #define USER_ADDR_ROM 0x08005000 -#else - #define USER_ADDR_ROM 0x08000000 -#endif -#define USER_ADDR_RAM 0x20000C00 -extern char __text_start__; - -static void setup_nvic(void) { - -nvic_init((uint32)VECT_TAB_ADDR, 0); - -/* Roger Clark. We now control nvic vector table in boards.txt using the build.vect paramater -#ifdef VECT_TAB_FLASH - nvic_init(USER_ADDR_ROM, 0); -#elif defined VECT_TAB_RAM - nvic_init(USER_ADDR_RAM, 0); -#elif defined VECT_TAB_BASE - nvic_init((uint32)0x08000000, 0); -#elif defined VECT_TAB_ADDR - // A numerically supplied value - nvic_init((uint32)VECT_TAB_ADDR, 0); -#else - // Use the __text_start__ value from the linker script; this - // should be the start of the vector table. - nvic_init((uint32)&__text_start__, 0); -#endif - -*/ -} - -static void adc_default_config(adc_dev *dev) { - adc_enable_single_swstart(dev); - adc_set_sample_rate(dev, wirish::priv::w_adc_smp); -} - -static void setup_adcs(void) { - adc_set_prescaler(wirish::priv::w_adc_pre); - adc_foreach(adc_default_config); -} - -static void timer_default_config(timer_dev *dev) { - timer_adv_reg_map *regs = (dev->regs).adv; - const uint16 full_overflow = 0xFFFF; - const uint16 half_duty = 0x8FFF; - - timer_init(dev); - timer_pause(dev); - - regs->CR1 = TIMER_CR1_ARPE; - regs->PSC = 1; - regs->SR = 0; - regs->DIER = 0; - regs->EGR = TIMER_EGR_UG; - switch (dev->type) { - case TIMER_ADVANCED: - regs->BDTR = TIMER_BDTR_MOE | TIMER_BDTR_LOCK_OFF; - // fall-through - case TIMER_GENERAL: - timer_set_reload(dev, full_overflow); - for (uint8 channel = 1; channel <= 4; channel++) { - if (timer_has_cc_channel(dev, channel)) { - timer_set_compare(dev, channel, half_duty); - timer_oc_set_mode(dev, channel, TIMER_OC_MODE_PWM_1, - TIMER_OC_PE); - } - } - // fall-through - case TIMER_BASIC: - break; - } - - timer_generate_update(dev); - timer_resume(dev); -} - -static void setup_timers(void) { - timer_foreach(timer_default_config); -} diff --git a/buildroot/share/PlatformIO/variants/FLY_F407ZG/ldscript.ld b/buildroot/share/PlatformIO/variants/FLY_F407ZG/ldscript.ld deleted file mode 100644 index 40abfe19b574..000000000000 --- a/buildroot/share/PlatformIO/variants/FLY_F407ZG/ldscript.ld +++ /dev/null @@ -1,207 +0,0 @@ -/* -***************************************************************************** -** - -** File : lscript.ld -** -** Abstract : Linker script for STM32F407(VZ)(EG)Tx Device with -** 512/1024KByte FLASH, 128KByte 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 = 0x20020000; /* 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 -{ -RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K -CCMRAM (rw) : ORIGIN = 0x10000000, LENGTH = 64K -FLASH (rx) : ORIGIN = 0x8008000, LENGTH = 1024K -32K -} - -/* 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): - { - . = 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 - - _siccmram = LOADADDR(.ccmram); - - /* CCM-RAM section - * - * IMPORTANT NOTE! - * If initialized variables will be placed in this section, - * the startup code needs to be modified to copy the init-values. - */ - .ccmram : - { - . = ALIGN(4); - _sccmram = .; /* create a global symbol at ccmram start */ - *(.ccmram) - *(.ccmram*) - - . = ALIGN(4); - _eccmram = .; /* create a global symbol at ccmram end */ - } >CCMRAM AT> FLASH - - - /* Uninitialized data section */ - . = ALIGN(4); - .bss : - { - /* This is used by the startup in order to initialize the .bss secion */ - _sbss = .; /* define a global symbol at bss start */ - __bss_start__ = _sbss; - *(.bss) - *(.bss*) - *(COMMON) - - . = ALIGN(4); - _ebss = .; /* define a global symbol at bss end */ - __bss_end__ = _ebss; - } >RAM - - /* User_heap_stack section, used to check that there is enough RAM left */ - ._user_heap_stack : - { - . = ALIGN(4); - PROVIDE ( end = . ); - PROVIDE ( _end = . ); - . = . + _Min_Heap_Size; - . = . + _Min_Stack_Size; - . = ALIGN(4); - } >RAM - - - /* Remove information from the standard libraries */ - /DISCARD/ : - { - libc.a ( * ) - libm.a ( * ) - libgcc.a ( * ) - } - - .ARM.attributes 0 : { *(.ARM.attributes) } -} - - diff --git a/buildroot/share/PlatformIO/variants/LERDGE/PeripheralPins.c b/buildroot/share/PlatformIO/variants/LERDGE/PeripheralPins.c deleted file mode 100644 index 8cb0776ffad1..000000000000 --- a/buildroot/share/PlatformIO/variants/LERDGE/PeripheralPins.c +++ /dev/null @@ -1,418 +0,0 @@ -/* - ******************************************************************************* - * 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 STM32F407Z(E-G)Tx.xml - */ -#include -#include - -/* ===== - * 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 -const PinMap PinMap_ADC[] = { - {PA_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0 - //{PA_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC2_IN0 - //{PA_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC3_IN0 - {PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1 - //{PA_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC2_IN1 - //{PA_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC3_IN1 - //{PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2 - {PA_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC2_IN2 - //{PA_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC3_IN2 - //{PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3 - //{PA_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC2_IN3 - {PA_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC3_IN3 - {PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4 - //{PA_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC2_IN4 - //{PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5 - {PA_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC2_IN5 - {PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6 - //{PA_6, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC2_IN6 - {PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7 - //{PA_7, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC2_IN7 - //{PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8 - {PB_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC2_IN8 - {PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9 - //{PB_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC2_IN9 - //{PC_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10 - //{PC_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC2_IN10 - {PC_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC3_IN10 - {PC_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11 - //{PC_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC2_IN11 - //{PC_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC3_IN11 - //{PC_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12 - {PC_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC2_IN12 - //{PC_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC3_IN12 - //{PC_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13 - //{PC_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC2_IN13 - {PC_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC3_IN13 - //{PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14 - {PC_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC2_IN14 - //{PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15 - {PC_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC2_IN15 - {PF_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC3_IN9 - {PF_4, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC3_IN14 - {PF_5, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC3_IN15 - {PF_6, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC3_IN4 - {PF_7, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC3_IN5 - {PF_8, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC3_IN6 - //{PF_9, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC3_IN7 - {PF_10, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC3_IN8 - {NC, NP, 0} -}; -#endif - -//*** DAC *** - -#ifdef HAL_DAC_MODULE_ENABLED -const PinMap PinMap_DAC[] = { - {PA_4, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // DAC_OUT1 - {PA_5, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // DAC_OUT2 - {NC, NP, 0} -}; -#endif - -//*** I2C *** - -#ifdef HAL_I2C_MODULE_ENABLED -const PinMap PinMap_I2C_SDA[] = { - {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)}, - {PB_11, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, - {PC_9, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, - {PF_0, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, - {NC, NP, 0} -}; -#endif - -#ifdef HAL_I2C_MODULE_ENABLED -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)}, - {PF_1, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, - {NC, NP, 0} -}; -#endif - -//*** PWM *** - -#ifdef HAL_TIM_MODULE_ENABLED -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_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N - {PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 - //{PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 - //{PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N - {PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 - //{PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N - //{PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 - {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 - {PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 - {PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 - {PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 - //{PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 - //{PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N - {PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 - //{PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N - //{PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N - {PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 - //{PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N - //{PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 - {PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 - {PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 - {PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 - {PB_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_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 - {PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N - {PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N - {PB_14, 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 - {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 - {PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 - {PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 - {PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 - {PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 - {PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 - {PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 0)}, // TIM8_CH3 - {PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 - {PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 4, 0)}, // TIM8_CH4 - {PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 - {PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 - {PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 - {PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 - {PE_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 - {PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 - {PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N - {PE_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 - {PE_12, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N - {PE_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 - {PE_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 - {PF_6, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1 - {PF_7, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 - {PF_8, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 - {PF_9, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 - {NC, NP, 0} -}; -#endif - -//*** SERIAL *** - -#ifdef HAL_UART_MODULE_ENABLED -const PinMap PinMap_UART_TX[] = { - {PA_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, - {PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - {PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, - {PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, - {PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - {PC_6, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - //{PC_10, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, - {PC_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - {PC_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, - {PD_5, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - {PD_8, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - {PG_14, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - {NC, NP, 0} -}; -#endif - -#ifdef HAL_UART_MODULE_ENABLED -const PinMap PinMap_UART_RX[] = { - {PA_1, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, - {PA_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - {PA_10, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, - {PB_7, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, - {PB_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - {PC_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - //{PC_11, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, - {PC_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - {PD_2, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, - {PD_6, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - {PD_9, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - {PG_9, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - {NC, NP, 0} -}; -#endif - -#ifdef HAL_UART_MODULE_ENABLED -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)}, - {PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - {PD_4, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - {PD_12, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - {PG_8, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - {PG_12, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - {NC, NP, 0} -}; -#endif - -#ifdef HAL_UART_MODULE_ENABLED -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)}, - {PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - {PD_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - {PD_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - {PG_13, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - {PG_15, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - {NC, NP, 0} -}; -#endif - -//*** SPI *** - -#ifdef HAL_SPI_MODULE_ENABLED -const PinMap PinMap_SPI_MOSI[] = { - {PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, - {PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, - {PB_5, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, - {PB_15, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, - {PC_3, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, - {PC_12, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, - {NC, NP, 0} -}; -#endif - -#ifdef HAL_SPI_MODULE_ENABLED -const PinMap PinMap_SPI_MISO[] = { - {PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, - {PB_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, - {PB_4, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, - {PB_14, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, - {PC_2, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, - {PC_11, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, - {NC, NP, 0} -}; -#endif - -#ifdef HAL_SPI_MODULE_ENABLED -const PinMap PinMap_SPI_SCLK[] = { - {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, - {PB_3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, - {PB_3, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, - {PB_10, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, - {PB_13, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, - {PC_10, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, - {NC, NP, 0} -}; -#endif - -#ifdef HAL_SPI_MODULE_ENABLED -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 - -//*** CAN *** - -#ifdef HAL_CAN_MODULE_ENABLED -const PinMap PinMap_CAN_RD[] = { - {PA_11, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, - {PB_5, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, - {PB_8, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, - {PB_12, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, - {PD_0, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, - {NC, NP, 0} -}; -#endif - -#ifdef HAL_CAN_MODULE_ENABLED -const PinMap PinMap_CAN_TD[] = { - {PA_12, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, - {PB_6, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, - {PB_9, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, - {PB_13, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, - {PD_1, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, - {NC, NP, 0} -}; -#endif - -//*** ETHERNET *** - -#ifdef HAL_ETH_MODULE_ENABLED -const PinMap PinMap_Ethernet[] = { - {PA_0, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_CRS - {PA_1, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_REF_CLK|ETH_RX_CLK - {PA_2, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_MDIO - {PA_3, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_COL - {PA_7, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_CRS_DV|ETH_RX_DV - {PB_0, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD2 - {PB_1, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD3 - {PB_5, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_PPS_OUT - {PB_8, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD3 - {PB_10, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RX_ER - {PB_11, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TX_EN - {PB_12, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD0 - {PB_13, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD1 - {PC_1, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_MDC - {PC_2, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD2 - {PC_3, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TX_CLK - {PC_4, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD0 - {PC_5, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD1 - {PE_2, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD3 - {PG_8, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_PPS_OUT - {PG_11, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TX_EN - {PG_13, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD0 - {PG_14, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD1 - {NC, NP, 0} -}; -#endif - -//*** No QUADSPI *** - -//*** USB *** - -#ifdef HAL_PCD_MODULE_ENABLED -const PinMap PinMap_USB_OTG_FS[] = { - //{PA_8, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_SOF - //{PA_9, USB_OTG_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_FS_VBUS - //{PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_ID - {PA_11, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DM - {PA_12, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DP - {NC, NP, 0} -}; -#endif - -#ifdef HAL_PCD_MODULE_ENABLED -const PinMap PinMap_USB_OTG_HS[] = { -#ifdef USE_USB_HS_IN_FS - {PA_4, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_SOF - {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_ID - {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_HS_VBUS - {PB_14, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DM - {PB_15, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DP -#else - {PA_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D0 - {PA_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_CK - {PB_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D1 - {PB_1, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D2 - {PB_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D7 - {PB_10, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D3 - {PB_11, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D4 - {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D5 - {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D6 - {PC_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_STP - {PC_2, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_DIR - {PC_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_NXT -#endif /* USE_USB_HS_IN_FS */ - {NC, NP, 0} -}; -#endif diff --git a/buildroot/share/PlatformIO/variants/archim/.gitignore b/buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/.gitignore similarity index 100% rename from buildroot/share/PlatformIO/variants/archim/.gitignore rename to buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/.gitignore diff --git a/buildroot/share/PlatformIO/variants/archim/build_gcc/Makefile b/buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/build_gcc/Makefile similarity index 100% rename from buildroot/share/PlatformIO/variants/archim/build_gcc/Makefile rename to buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/build_gcc/Makefile diff --git a/buildroot/share/PlatformIO/variants/archim/build_gcc/debug.mk b/buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/build_gcc/debug.mk similarity index 100% rename from buildroot/share/PlatformIO/variants/archim/build_gcc/debug.mk rename to buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/build_gcc/debug.mk diff --git a/buildroot/share/PlatformIO/variants/archim/build_gcc/gcc.mk b/buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/build_gcc/gcc.mk similarity index 100% rename from buildroot/share/PlatformIO/variants/archim/build_gcc/gcc.mk rename to buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/build_gcc/gcc.mk diff --git a/buildroot/share/PlatformIO/variants/archim/build_gcc/libvariant_arduino_due_x.mk b/buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/build_gcc/libvariant_arduino_due_x.mk similarity index 100% rename from buildroot/share/PlatformIO/variants/archim/build_gcc/libvariant_arduino_due_x.mk rename to buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/build_gcc/libvariant_arduino_due_x.mk diff --git a/buildroot/share/PlatformIO/variants/archim/build_gcc/release.mk b/buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/build_gcc/release.mk similarity index 100% rename from buildroot/share/PlatformIO/variants/archim/build_gcc/release.mk rename to buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/build_gcc/release.mk diff --git a/buildroot/share/PlatformIO/variants/archim/debug_scripts/gcc/arduino_due_x_flash.gdb b/buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/debug_scripts/gcc/arduino_due_x_flash.gdb similarity index 100% rename from buildroot/share/PlatformIO/variants/archim/debug_scripts/gcc/arduino_due_x_flash.gdb rename to buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/debug_scripts/gcc/arduino_due_x_flash.gdb diff --git a/buildroot/share/PlatformIO/variants/archim/debug_scripts/gcc/arduino_due_x_sram.gdb b/buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/debug_scripts/gcc/arduino_due_x_sram.gdb similarity index 100% rename from buildroot/share/PlatformIO/variants/archim/debug_scripts/gcc/arduino_due_x_sram.gdb rename to buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/debug_scripts/gcc/arduino_due_x_sram.gdb diff --git a/buildroot/share/PlatformIO/variants/archim/debug_scripts/iar/arduino_due_flash.mac b/buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/debug_scripts/iar/arduino_due_flash.mac similarity index 100% rename from buildroot/share/PlatformIO/variants/archim/debug_scripts/iar/arduino_due_flash.mac rename to buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/debug_scripts/iar/arduino_due_flash.mac diff --git a/buildroot/share/PlatformIO/variants/archim/debug_scripts/iar/arduino_due_sram.mac b/buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/debug_scripts/iar/arduino_due_sram.mac similarity index 100% rename from buildroot/share/PlatformIO/variants/archim/debug_scripts/iar/arduino_due_sram.mac rename to buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/debug_scripts/iar/arduino_due_sram.mac diff --git a/buildroot/share/PlatformIO/variants/archim/libsam_sam3x8e_gcc_rel.a b/buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/libsam_sam3x8e_gcc_rel.a similarity index 100% rename from buildroot/share/PlatformIO/variants/archim/libsam_sam3x8e_gcc_rel.a rename to buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/libsam_sam3x8e_gcc_rel.a diff --git a/buildroot/share/PlatformIO/variants/archim/libsam_sam3x8e_gcc_rel.a.txt b/buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/libsam_sam3x8e_gcc_rel.a.txt similarity index 100% rename from buildroot/share/PlatformIO/variants/archim/libsam_sam3x8e_gcc_rel.a.txt rename to buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/libsam_sam3x8e_gcc_rel.a.txt diff --git a/buildroot/share/PlatformIO/variants/archim/linker_scripts/gcc/flash.ld b/buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/linker_scripts/gcc/flash.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/archim/linker_scripts/gcc/flash.ld rename to buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/linker_scripts/gcc/flash.ld diff --git a/buildroot/share/PlatformIO/variants/archim/linker_scripts/gcc/sram.ld b/buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/linker_scripts/gcc/sram.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/archim/linker_scripts/gcc/sram.ld rename to buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/linker_scripts/gcc/sram.ld diff --git a/buildroot/share/PlatformIO/variants/archim/linker_scripts/iar/flash.icf b/buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/linker_scripts/iar/flash.icf similarity index 100% rename from buildroot/share/PlatformIO/variants/archim/linker_scripts/iar/flash.icf rename to buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/linker_scripts/iar/flash.icf diff --git a/buildroot/share/PlatformIO/variants/archim/linker_scripts/iar/sram.icf b/buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/linker_scripts/iar/sram.icf similarity index 100% rename from buildroot/share/PlatformIO/variants/archim/linker_scripts/iar/sram.icf rename to buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/linker_scripts/iar/sram.icf diff --git a/buildroot/share/PlatformIO/variants/archim/pins_arduino.h b/buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/pins_arduino.h similarity index 100% rename from buildroot/share/PlatformIO/variants/archim/pins_arduino.h rename to buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/pins_arduino.h diff --git a/buildroot/share/PlatformIO/variants/archim/variant.cpp b/buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/variant.cpp similarity index 100% rename from buildroot/share/PlatformIO/variants/archim/variant.cpp rename to buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/variant.cpp diff --git a/buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/variant.h new file mode 100644 index 000000000000..11f8f63bfb59 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_ARCHIM/variant.h @@ -0,0 +1,284 @@ +/* + 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_DUE_X_ +#define _VARIANT_ARDUINO_DUE_X_ + +/*---------------------------------------------------------------------------- + * Definitions + *----------------------------------------------------------------------------*/ + +/** Frequency of the board main oscillator */ +#define VARIANT_MAINOSC 12000000 + +/** Master clock frequency */ +#define VARIANT_MCK 84000000 + +/*---------------------------------------------------------------------------- + * Headers + *----------------------------------------------------------------------------*/ + +#include "Arduino.h" +#ifdef __cplusplus +#include "UARTClass.h" +#include "USARTClass.h" +#endif + +#ifdef __cplusplus +extern "C"{ +#endif // __cplusplus + +/** + * Libc porting layers + */ +#if defined ( __GNUC__ ) /* GCC CS3 */ +# include /** RedHat Newlib minimal stub */ +#endif + +/*---------------------------------------------------------------------------- + * Pins + *----------------------------------------------------------------------------*/ + +// Number of pins defined in PinDescription array +#define PINS_COUNT 79 +#define NUM_DIGITAL_PINS 66 +#define NUM_ANALOG_INPUTS 12 +#define analogInputToDigitalPin(p) ((p < 12) ? (p) + 54 : -1) + +#define digitalPinToPort(P) ( g_APinDescription[P].pPort ) +#define digitalPinToBitMask(P) ( g_APinDescription[P].ulPin ) +//#define analogInPinToBit(P) ( ) +#define portOutputRegister(port) ( &(port->PIO_ODSR) ) +#define portInputRegister(port) ( &(port->PIO_PDSR) ) +#define digitalPinHasPWM(P) ( g_APinDescription[P].ulPWMChannel != NOT_ON_PWM || g_APinDescription[P].ulTCChannel != NOT_ON_TIMER ) + +/* + * portModeRegister(..) should return a register to set pin mode + * INPUT or OUTPUT by setting the corresponding bit to 0 or 1. + * Unfortunately on SAM architecture the PIO_OSR register is + * read-only and can be set only through the enable/disable registers + * pair PIO_OER/PIO_ODR. + */ +// #define portModeRegister(port) ( &(port->PIO_OSR) ) + +/* + * digitalPinToTimer(..) is AVR-specific and is not defined for SAM + * architecture. If you need to check if a pin supports PWM you must + * use digitalPinHasPWM(..). + * + * https://github.com/arduino/Arduino/issues/1833 + */ +// #define digitalPinToTimer(P) + +// Interrupts +#define digitalPinToInterrupt(p) ((p) < NUM_DIGITAL_PINS ? (p) : -1) + +// LEDs +#define PIN_LED_13 (13U) +#define PIN_LED_RXL (72U) +#define PIN_LED_TXL (73U) +#define PIN_LED PIN_LED_13 +#define PIN_LED2 PIN_LED_RXL +#define PIN_LED3 PIN_LED_TXL +#define LED_BUILTIN 13 + +/* + * SPI Interfaces + */ +#define SPI_INTERFACES_COUNT 1 + +#define SPI_INTERFACE SPI0 +#define SPI_INTERFACE_ID ID_SPI0 +#define SPI_CHANNELS_NUM 4 +#define PIN_SPI_SS0 (77U) +#define PIN_SPI_SS1 (87U) +#define PIN_SPI_SS2 (86U) +#define PIN_SPI_SS3 (78U) +#define PIN_SPI_MOSI (75U) +#define PIN_SPI_MISO (74U) +#define PIN_SPI_SCK (76U) +#define BOARD_SPI_SS0 (77U) //(10U) +#define BOARD_SPI_SS1 (4U) +#define BOARD_SPI_SS2 (52U) +#define BOARD_SPI_SS3 PIN_SPI_SS3 +#define BOARD_SPI_DEFAULT_SS BOARD_SPI_SS3 + +#define BOARD_PIN_TO_SPI_PIN(x) \ + (x==BOARD_SPI_SS0 ? PIN_SPI_SS0 : \ + (x==BOARD_SPI_SS1 ? PIN_SPI_SS1 : \ + (x==BOARD_SPI_SS2 ? PIN_SPI_SS2 : PIN_SPI_SS3 ))) +#define BOARD_PIN_TO_SPI_CHANNEL(x) \ + (x==BOARD_SPI_SS0 ? 0 : \ + (x==BOARD_SPI_SS1 ? 1 : \ + (x==BOARD_SPI_SS2 ? 2 : 3))) + +static const uint8_t SS = BOARD_SPI_SS0; +static const uint8_t SS1 = BOARD_SPI_SS1; +static const uint8_t SS2 = BOARD_SPI_SS2; +static const uint8_t SS3 = BOARD_SPI_SS3; +static const uint8_t MOSI = PIN_SPI_MOSI; +static const uint8_t MISO = PIN_SPI_MISO; +static const uint8_t SCK = PIN_SPI_SCK; + +/* + * Wire Interfaces + */ +#define WIRE_INTERFACES_COUNT 2 + +#define PIN_WIRE_SDA (20U) +#define PIN_WIRE_SCL (21U) +#define WIRE_INTERFACE TWI1 +#define WIRE_INTERFACE_ID ID_TWI1 +#define WIRE_ISR_HANDLER TWI1_Handler +#define WIRE_ISR_ID TWI1_IRQn + +#define PIN_WIRE1_SDA (70U) +#define PIN_WIRE1_SCL (71U) +#define WIRE1_INTERFACE TWI0 +#define WIRE1_INTERFACE_ID ID_TWI0 +#define WIRE1_ISR_HANDLER TWI0_Handler +#define WIRE1_ISR_ID TWI0_IRQn + +static const uint8_t SDA = PIN_WIRE_SDA; +static const uint8_t SCL = PIN_WIRE_SCL; +static const uint8_t SDA1 = PIN_WIRE1_SDA; +static const uint8_t SCL1 = PIN_WIRE1_SCL; + +/* + * UART/USART Interfaces + */ +// Serial +#define PINS_UART (81U) +// Serial1 +#define PINS_USART0 (82U) +// Serial2 +#define PINS_USART1 (83U) +// Serial3 +#define PINS_USART3 (84U) + +/* + * USB Interfaces + */ +#define PINS_USB (85U) + +/* + * Analog pins + */ +static const uint8_t A0 = 54; +static const uint8_t A1 = 55; +static const uint8_t A2 = 56; +static const uint8_t A3 = 57; +static const uint8_t A4 = 58; +static const uint8_t A5 = 59; +static const uint8_t A6 = 60; +static const uint8_t A7 = 61; +static const uint8_t A8 = 62; +static const uint8_t A9 = 63; +static const uint8_t A10 = 64; +static const uint8_t A11 = 65; +static const uint8_t DAC0 = 66; +static const uint8_t DAC1 = 67; +static const uint8_t CANRX = 68; +static const uint8_t CANTX = 69; +#define ADC_RESOLUTION 12 + +/* + * Complementary CAN pins + */ +static const uint8_t CAN1RX = 88; +static const uint8_t CAN1TX = 89; + +// CAN0 +#define PINS_CAN0 (90U) +// CAN1 +#define PINS_CAN1 (91U) + + +/* + * DACC + */ +#define DACC_INTERFACE DACC +#define DACC_INTERFACE_ID ID_DACC +#define DACC_RESOLUTION 12 +#define DACC_ISR_HANDLER DACC_Handler +#define DACC_ISR_ID DACC_IRQn + +/* + * PWM + */ +#define PWM_INTERFACE PWM +#define PWM_INTERFACE_ID ID_PWM +#define PWM_FREQUENCY 31000 +#define PWM_MAX_DUTY_CYCLE 255 +#define PWM_MIN_DUTY_CYCLE 0 +#define PWM_RESOLUTION 8 + +/* + * TC + */ +#define TC_INTERFACE TC0 +#define TC_INTERFACE_ID ID_TC0 +#define TC_FREQUENCY 100000 +#define TC_MAX_DUTY_CYCLE 255 +#define TC_MIN_DUTY_CYCLE 0 +#define TC_RESOLUTION 8 + +#ifdef __cplusplus +} +#endif + +/*---------------------------------------------------------------------------- + * Arduino objects - C++ only + *----------------------------------------------------------------------------*/ + +#ifdef __cplusplus + +extern UARTClass Serial; +extern USARTClass Serial1; +extern USARTClass Serial2; +extern USARTClass Serial3; + +#endif + +// 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_USBVIRTUAL SerialUSB +#define SERIAL_PORT_HARDWARE_OPEN Serial1 +#define SERIAL_PORT_HARDWARE_OPEN1 Serial2 +#define SERIAL_PORT_HARDWARE_OPEN2 Serial3 +#define SERIAL_PORT_HARDWARE Serial +#define SERIAL_PORT_HARDWARE1 Serial1 +#define SERIAL_PORT_HARDWARE2 Serial2 +#define SERIAL_PORT_HARDWARE3 Serial3 + +#endif /* _VARIANT_ARDUINO_DUE_X_ */ + diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/PeripheralPins.c new file mode 100644 index 000000000000..933b62ae9be2 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/PeripheralPins.c @@ -0,0 +1,345 @@ +/* + ******************************************************************************* + * 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 STM32F407Z(E-G)Tx.xml + */ +#include +#include + +/* ===== + * Note: Commented lines are alternative possibilities which are not used by default. + * If you change them, you should know what you're doing first. + * ===== + */ + +//*** ADC *** + +#ifdef HAL_ADC_MODULE_ENABLED +const PinMap PinMap_ADC[] = { + {PA_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0 TEMP_1 + {PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1 TEMP_BED + {PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2 TEMP_0 + {PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3 EXP2-1 + {PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4 TF_SS SD_SS (CUSTOM_SPI_PINS) + {PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5 TF_SCLK SD_SCK + {PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6 TF_MISO SD_MISO + {PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7 LED SD_MOSI + {PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8 BTN_EN2 + {PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9 BTN_ENC + {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 TEMP_PROBE + {PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14 SD_DETECT + {PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15 BTN_EN1 + + #if STM32F4X_PIN_NUM >= 144 // 144 pins mcu, 114 gpio, 24 ADC + {PF_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC3_IN9 TH_0 + {PF_4, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC3_IN14 TH_1 + {PF_5, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC3_IN15 TH_2 + {PF_6, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC3_IN4 TH_3 + {PF_7, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC3_IN5 EXP_13 + {PF_8, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC3_IN6 EXP_3 + {PF_9, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC3_IN7 EXP_6 + {PF_10, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC3_IN8 EXP_5 + #endif + {NC, NP, 0} +}; +#endif + +//*** DAC *** + +#ifdef HAL_DAC_MODULE_ENABLED +const PinMap PinMap_DAC[] = { + {PA_4, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // DAC_OUT1 + {PA_5, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // DAC_OUT2 + {NC, NP, 0} +}; +#endif + +//*** I2C *** + +#ifdef HAL_I2C_MODULE_ENABLED +const PinMap PinMap_I2C_SDA[] = { + {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)}, + {PB_11, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + {PC_9, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + {PF_0, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + #endif + {NC, NP, 0} +}; + +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)}, + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + {PF_1, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + #endif + {NC, NP, 0} +}; +#endif + +//*** PWM *** + +#ifdef HAL_TIM_MODULE_ENABLED +const PinMap PinMap_PWM[] = { + {PE_5, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 BED + {PE_6, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2 HEATER0 + {PB_8, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1 FAN0 + {PB_9, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 FAN1 + + /** + * Unused by specifications on BTT002. (PLEASE CONFIRM) + * Uncomment the corresponding line if you want to have HardwarePWM on some pins. + * WARNING: check timers' usage first to avoid conflicts. + * If you don't know what you're doing leave things as they are or you WILL break something (including hardware) + * If you alter this section DO NOT report bugs to Marlin team since they are most likely caused by you. Thank you. + */ + //{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_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + //{PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + //{PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 + //{PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + //{PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + //{PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + //{PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 + //{PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 + //{PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 + //{PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 + //{PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 + //{PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + //{PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + //{PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 + //{PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N + //{PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + //{PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 + //{PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N + //{PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 + //{PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + //{PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + //{PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 + //{PB_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_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 + //{PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 + //{PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 + //{PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + //{PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + //{PB_14, 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 + //{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 + //{PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + //{PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 + //{PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + //{PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 + //{PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 + //{PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 0)}, // TIM8_CH3 + //{PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 + //{PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 4, 0)}, // TIM8_CH4 + //{PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 + //{PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 + //{PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 + //{PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 + //{PE_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + //{PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 + //{PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + //{PE_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 + //{PE_12, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + //{PE_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 + //{PE_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + //{PF_6, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1 + //{PF_7, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 + //{PF_8, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 + //{PF_9, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 + #endif + {NC, NP, 0} +}; +#endif + +//*** SERIAL *** + +#ifdef HAL_UART_MODULE_ENABLED +const PinMap PinMap_UART_TX[] = { + {PA_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PC_6, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + {PC_10, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PC_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PC_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + {PD_5, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PD_8, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + {PG_14, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + #endif + {NC, NP, 0} +}; + +const PinMap PinMap_UART_RX[] = { + {PA_1, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PA_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PA_10, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PB_7, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PB_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PC_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + {PC_11, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PC_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PD_2, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + {PD_6, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PD_9, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + {PG_9, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + #endif + {NC, NP, 0} +}; + +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)}, + {PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PD_4, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PD_12, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + {PG_8, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + {PG_12, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + #endif + {NC, NP, 0} +}; + +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)}, + {PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PD_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PD_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + {PG_13, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + {PG_15, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + #endif + {NC, NP, 0} +}; +#endif + +//*** SPI *** + +#ifdef HAL_SPI_MODULE_ENABLED +const PinMap PinMap_SPI_MOSI[] = { + {PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, + {PB_15, 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} +}; + +const PinMap PinMap_SPI_MISO[] = { + {PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, + {PB_14, 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} +}; + +const PinMap PinMap_SPI_SCLK[] = { + {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, + {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} +}; + +const PinMap PinMap_SPI_SSEL[] = { + {PA_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, + {PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PA_15, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {NC, NP, 0} +}; +#endif + +//*** CAN *** + +#ifdef HAL_CAN_MODULE_ENABLED +#error "CAN bus isn't available on this board. Driver should be disabled." +#endif + +//*** ETHERNET *** +#ifdef HAL_ETH_MODULE_ENABLED +#error "Ethernet port isn't available on this board. Driver should be disabled." +#endif + +//*** No QUADSPI *** + +//*** USB *** +#ifdef HAL_PCD_MODULE_ENABLED +const PinMap PinMap_USB_OTG_FS[] = { + //{PA_8, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_SOF used by LCD + //{PA_9, USB_OTG_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_FS_VBUS available on wifi port, if empty + //{PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_ID available on UART1_RX if not used + {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} +}; + +const PinMap PinMap_USB_OTG_HS[] = { /* + #ifdef USE_USB_HS_IN_FS + {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_ID + {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_HS_VBUS + {PB_14, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DM + {PB_15, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DP + #else + #error "USB in HS mode isn't supported by the board" + {PA_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D0 + {PB_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D1 + {PB_1, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D2 + {PB_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D7 + {PB_10, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D3 + {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D5 + {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D6 + {PC_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_STP + {PC_2, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_DIR + {PC_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_NXT + #endif // USE_USB_HS_IN_FS + */ + {NC, NP, 0} +}; +#endif diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_BTT002/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/PinNamesVar.h similarity index 100% rename from buildroot/share/PlatformIO/variants/BIGTREE_BTT002/PinNamesVar.h rename to buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/PinNamesVar.h diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/hal_conf_extra.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/hal_conf_extra.h new file mode 100644 index 000000000000..40b340c20560 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/hal_conf_extra.h @@ -0,0 +1,52 @@ +#pragma once + +#define HAL_MODULE_ENABLED +#define HAL_ADC_MODULE_ENABLED +#define HAL_CRC_MODULE_ENABLED +#define HAL_DMA_MODULE_ENABLED +#define HAL_GPIO_MODULE_ENABLED +#define HAL_I2C_MODULE_ENABLED +#define HAL_PWR_MODULE_ENABLED +#define HAL_RCC_MODULE_ENABLED +//#define HAL_RTC_MODULE_ENABLED // Real Time Clock...do we use it? +#define HAL_SPI_MODULE_ENABLED +#define HAL_TIM_MODULE_ENABLED +#define HAL_USART_MODULE_ENABLED +#define HAL_CORTEX_MODULE_ENABLED +//#define HAL_UART_MODULE_ENABLED // by default +//#define HAL_PCD_MODULE_ENABLED // Automatically added if any type of USB is enabled, as in Arduino IDE. (STM32 v3.10700.191028) + +//#define HAL_SD_MODULE_ENABLED +//#define HAL_DAC_MODULE_ENABLED +//#define HAL_FLASH_MODULE_ENABLED +//#define HAL_CAN_MODULE_ENABLED +//#define HAL_CAN_LEGACY_MODULE_ENABLED +//#define HAL_CEC_MODULE_ENABLED +//#define HAL_CRYP_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_IWDG_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_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 diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/ldscript.ld new file mode 100644 index 000000000000..6af296a521ff --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/ldscript.ld @@ -0,0 +1,204 @@ +/* +***************************************************************************** +** + +** File : LinkerScript.ld +** +** Abstract : Linker script for STM32F407ZGTx Device with +** 1024KByte FLASH, 128KByte 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 = 0x20020000; /* 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 = 0x8008000, LENGTH = 1024K +RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K +CCMRAM (rw) : ORIGIN = 0x10000000, 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): + { + . = 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 + + _siccmram = LOADADDR(.ccmram); + + /* CCM-RAM section + * + * IMPORTANT NOTE! + * If initialized variables will be placed in this section, + * the startup code needs to be modified to copy the init-values. + */ + .ccmram : + { + . = ALIGN(4); + _sccmram = .; /* create a global symbol at ccmram start */ + *(.ccmram) + *(.ccmram*) + + . = ALIGN(4); + _eccmram = .; /* create a global symbol at ccmram end */ + } >CCMRAM AT> FLASH + + + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss section */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* User_heap_stack section, used to check that there is enough RAM left */ + ._user_heap_stack : + { + . = ALIGN(4); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(4); + } >RAM + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_BTT002/variant.cpp b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/variant.cpp similarity index 100% rename from buildroot/share/PlatformIO/variants/BIGTREE_BTT002/variant.cpp rename to buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/variant.cpp diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/variant.h new file mode 100644 index 000000000000..59a7f24527ba --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/variant.h @@ -0,0 +1,297 @@ +/* + ******************************************************************************* + * Copyright (c) 2017, 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. + ******************************************************************************* + */ +#pragma once + +#ifdef __cplusplus +extern "C" { +#endif // __cplusplus + +/*---------------------------------------------------------------------------- + * Pins + *----------------------------------------------------------------------------*/ + +#ifdef STM32F405RX + #define STM32F4X_PIN_NUM 64 //64 pins mcu, 51 gpio + #define STM32F4X_GPIO_NUM 51 + #define STM32F4X_ADC_NUM 16 +#elif defined(STM32F407_5VX) + #define STM32F4X_PIN_NUM 100 //100 pins mcu, 82 gpio + #define STM32F4X_GPIO_NUM 82 + #define STM32F4X_ADC_NUM 16 +#elif defined(STM32F407_5ZX) + #define STM32F4X_PIN_NUM 144 //144 pins mcu, 114 gpio + #define STM32F4X_GPIO_NUM 114 + #define STM32F4X_ADC_NUM 24 +#elif defined(STM32F407IX) + #define STM32F4X_PIN_NUM 176 //176 pins mcu, 140 gpio + #define STM32F4X_GPIO_NUM 140 + #define STM32F4X_ADC_NUM 24 +#else + #error "no match MCU defined" +#endif + +#if STM32F4X_PIN_NUM >= 64 //64 pins mcu, 51 gpio + #define PC13 0 + #define PC14 1 //OSC32_IN + #define PC15 2 //OSC32_OUT + #define PH0 3 //OSC_IN + #define PH1 4 //OSC_OUT + #define PB2 5 //BOOT1 + #define PB10 6 //1:SPI2_SCK / I2C2_SCL / USART3_TX / TIM2_CH3 + #define PB11 7 //1:I2C2_SDA / USART3_RX / TIM2_CH4 + #define PB12 8 //1:SPI2_NSS / OTG_HS_ID + #define PB13 9 //1:SPI2_SCK 2:OTG_HS_VBUS + #define PB14 10 //1:SPI2_MISO / TIM12_CH1 / OTG_HS_DM + #define PB15 11 //SPI2_MOSI / TIM12_CH2 / OTG_HS_DP + #define PC6 12 //1:TIM8_CH1 / SDIO_D6 / USART6_TX / TIM3_CH1 + #define PC7 13 //1:TIM8_CH2 / SDIO_D7 / USART6_RX / TIM3_CH2 + #define PC8 14 //1:TIM8_CH3 / SDIO_D0 / TIM3_CH3 + #define PC9 15 //1:TIM8_CH4 / SDIO_D1 / TIM3_CH4 + #define PA8 16 //1:TIM1_CH1 / I2C3_SCL / OTG_FS_SOF + #define PA9 17 //1:USART1_TX / TIM1_CH2 2:OTG_FS_VBUS + #define PA10 18 //1:USART1_RX / TIM1_CH3 / OTG_FS_ID + #define PA11 19 //1:TIM1_CH4 / OTG_FS_DM + #define PA12 20 //1:OTG_FS_DP + #define PA13 21 //0:JTMS-SWDIO + #define PA14 22 //0:JTCK-SWCLK + #define PA15 23 //0:JTDI 1:SPI3_NSS / SPI1_NSS + #define PC10 24 //1:UART4_TX / SPI3_SCK / SDIO_D2 / USART3_TX + #define PC11 25 //1:UART4_RX / SPI3_MISO / SDIO_D3 / USART3_RX + #define PC12 26 //1:UART5_TX / SPI3_MOSI / SDIO_CK + #define PD2 27 //1:UART5_RX / SDIO_CMD + #define PB3 28 //0:JTDO 1:SPI3_SCK / TIM2_CH2 / SPI1_SCK + #define PB4 29 //0:NJTRST 1:SPI3_MISO / TIM3_CH1 / SPI1_MISO + #define PB5 30 //1:TIM3_CH2 / SPI1_MOSI / SPI3_MOSI + #define PB6 31 //1:I2C1_SCL / TIM4_CH1 / USART1_TX + #define PB7 32 //1:I2C1_SDA / TIM4_CH2 / USART1_RX + #define PB8 33 //1:I2C1_SCL / TIM4_CH3 / SDIO_D4 / TIM10_CH1 + #define PB9 34 //1:I2C1_SDA / TIM4_CH4 / SDIO_D5 / TIM11_CH1 / SPI2_NSS + #define PA0 35 //1:UART4_TX / TIM5_CH1 2:ADC123_IN0 + #define PA1 36 //1:UART4_RX / TIM5_CH2 / TIM2_CH2 2:ADC123_IN1 + #define PA2 37 //1:USART2_TX /TIM5_CH3 / TIM9_CH1 / TIM2_CH3 2:ADC123_IN2 + #define PA3 38 //1:USART2_RX /TIM5_CH4 / TIM9_CH2 / TIM2_CH4 2:ADC123_IN3 + #define PA4 39 //NOT FT 1:SPI1_NSS / SPI3_NSS / USART2_CK 2:ADC12_IN4 / DAC_OUT1 + #define PA5 40 //NOT FT 1:SPI1_SCK 2:ADC12_IN5 / DAC_OUT2 + #define PA6 41 //1:SPI1_MISO / TIM13_CH1 / TIM3_CH1 2:ADC12_IN6 + #define PA7 42 //1:SPI1_MOSI / TIM14_CH1 / TIM3_CH2 2:ADC12_IN7 + #define PB0 43 //1:TIM3_CH3 2:ADC12_IN8 + #define PB1 44 //1:TIM3_CH4 2:ADC12_IN9 + #define PC0 45 //1: 2:ADC123_IN10 + #define PC1 46 //1: 2:ADC123_IN11 + #define PC2 47 //1:SPI2_MISO 2:ADC123_IN12 + #define PC3 48 //1:SPI2_MOSI 2:ADC123_IN13 + #define PC4 49 //1: 2:ADC12_IN14 + #define PC5 50 //1: 2:ADC12_IN15 + #if STM32F4X_PIN_NUM >= 144 + #define PF3 51 //1:FSMC_A3 2:ADC3_IN9 + #define PF4 52 //1:FSMC_A4 2:ADC3_IN14 + #define PF5 53 //1:FSMC_A5 2:ADC3_IN15 + #define PF6 54 //1:TIM10_CH1 2:ADC3_IN4 + #define PF7 55 //1:TIM11_CH1 2:ADC3_IN5 + #define PF8 56 //1:TIM13_CH1 2:ADC3_IN6 + #define PF9 57 //1;TIM14_CH1 2:ADC3_IN7 + #define PF10 58 //2:ADC3_IN8 + #endif +#endif +#if STM32F4X_PIN_NUM >= 100 //100 pins mcu, 82 gpio + #define PE2 (35+STM32F4X_ADC_NUM) //1:FSMC_A23 + #define PE3 (36+STM32F4X_ADC_NUM) //1:FSMC_A19 + #define PE4 (37+STM32F4X_ADC_NUM) //1:FSMC_A20 + #define PE5 (38+STM32F4X_ADC_NUM) //1:FSMC_A21 + #define PE6 (39+STM32F4X_ADC_NUM) //1:FSMC_A22 + #define PE7 (40+STM32F4X_ADC_NUM) //1:FSMC_D4 + #define PE8 (41+STM32F4X_ADC_NUM) //1:FSMC_D5 + #define PE9 (42+STM32F4X_ADC_NUM) //1:FSMC_D6 / TIM1_CH1 + #define PE10 (43+STM32F4X_ADC_NUM) //1:FSMC_D7 + #define PE11 (44+STM32F4X_ADC_NUM) //1:FSMC_D8 / TIM1_CH2 + #define PE12 (45+STM32F4X_ADC_NUM) //1:FSMC_D9 + #define PE13 (46+STM32F4X_ADC_NUM) //1:FSMC_D10 / TIM1_CH3 + #define PE14 (47+STM32F4X_ADC_NUM) //1:FSMC_D11 / TIM1_CH4 + #define PE15 (48+STM32F4X_ADC_NUM) //1:FSMC_D12 + #define PD8 (49+STM32F4X_ADC_NUM) //1:FSMC_D13 / USART3_TX + #define PD9 (50+STM32F4X_ADC_NUM) //1:FSMC_D14 / USART3_RX + #define PD10 (51+STM32F4X_ADC_NUM) //1:FSMC_D15 + #define PD11 (52+STM32F4X_ADC_NUM) //1:FSMC_A16 + #define PD12 (53+STM32F4X_ADC_NUM) //1:FSMC_A17 / TIM4_CH1 + #define PD13 (54+STM32F4X_ADC_NUM) //1:FSMC_A18 / TIM4_CH2 + #define PD14 (55+STM32F4X_ADC_NUM) //1:FSMC_D0 / TIM4_CH3 + #define PD15 (56+STM32F4X_ADC_NUM) //1:FSMC_D1 / TIM4_CH4 + #define PD0 (57+STM32F4X_ADC_NUM) //1:FSMC_D2 + #define PD1 (58+STM32F4X_ADC_NUM) //1:FSMC_D3 + #define PD3 (59+STM32F4X_ADC_NUM) //1:FSMC_CLK + #define PD4 (60+STM32F4X_ADC_NUM) //1:FSMC_NOE + #define PD5 (61+STM32F4X_ADC_NUM) //1:USART2_TX + #define PD6 (62+STM32F4X_ADC_NUM) //1:USART2_RX + #define PD7 (63+STM32F4X_ADC_NUM) + #define PE0 (64+STM32F4X_ADC_NUM) + #define PE1 (65+STM32F4X_ADC_NUM) +#endif +#if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + #define PF0 (66+STM32F4X_ADC_NUM) //1:FSMC_A0 / I2C2_SDA + #define PF1 (67+STM32F4X_ADC_NUM) //1:FSMC_A1 / I2C2_SCL + #define PF2 (68+STM32F4X_ADC_NUM) //1:FSMC_A2 + #define PF11 (69+STM32F4X_ADC_NUM) + #define PF12 (70+STM32F4X_ADC_NUM) //1:FSMC_A6 + #define PF13 (71+STM32F4X_ADC_NUM) //1:FSMC_A7 + #define PF14 (72+STM32F4X_ADC_NUM) //1:FSMC_A8 + #define PF15 (73+STM32F4X_ADC_NUM) //1:FSMC_A9 + #define PG0 (74+STM32F4X_ADC_NUM) //1:FSMC_A10 + #define PG1 (75+STM32F4X_ADC_NUM) //1:FSMC_A11 + #define PG2 (76+STM32F4X_ADC_NUM) //1:FSMC_A12 + #define PG3 (77+STM32F4X_ADC_NUM) //1:FSMC_A13 + #define PG4 (78+STM32F4X_ADC_NUM) //1:FSMC_A14 + #define PG5 (79+STM32F4X_ADC_NUM) //1:FSMC_A15 + #define PG6 (80+STM32F4X_ADC_NUM) + #define PG7 (81+STM32F4X_ADC_NUM) + #define PG8 (82+STM32F4X_ADC_NUM) + #define PG9 (83+STM32F4X_ADC_NUM) //1:USART6_RX + #define PG10 (84+STM32F4X_ADC_NUM) //1:FSMC_NE3 + #define PG11 (85+STM32F4X_ADC_NUM) + #define PG12 (86+STM32F4X_ADC_NUM) //1:FSMC_NE4 + #define PG13 (87+STM32F4X_ADC_NUM) //1:FSMC_A24 + #define PG14 (88+STM32F4X_ADC_NUM) //1:FSMC_A25 / USART6_TX + #define PG15 (89+STM32F4X_ADC_NUM) +#endif +#if STM32F4X_PIN_NUM >= 176 //176 pins mcu, 140 gpio + #define PI8 (90+STM32F4X_ADC_NUM) + #define PI9 (91+STM32F4X_ADC_NUM) + #define PI10 (92+STM32F4X_ADC_NUM) + #define PI11 (93+STM32F4X_ADC_NUM) + #define PH2 (94+STM32F4X_ADC_NUM) + #define PH3 (95+STM32F4X_ADC_NUM) + #define PH4 (96+STM32F4X_ADC_NUM) //1:I2C2_SCL + #define PH5 (97+STM32F4X_ADC_NUM) //1:I2C2_SDA + #define PH6 (98+STM32F4X_ADC_NUM) //1:TIM12_CH1 + #define PH7 (99+STM32F4X_ADC_NUM) //1:I2C3_SCL + #define PH8 (100+STM32F4X_ADC_NUM) //1:I2C3_SDA + #define PH9 (101+STM32F4X_ADC_NUM) //1:TIM12_CH2 + #define PH10 (102+STM32F4X_ADC_NUM) //1:TIM5_CH1 + #define PH11 (103+STM32F4X_ADC_NUM) //1:TIM5_CH2 + #define PH12 (104+STM32F4X_ADC_NUM) //1:TIM5_CH3 + #define PH13 (105+STM32F4X_ADC_NUM) + #define PH14 (106+STM32F4X_ADC_NUM) + #define PH15 (107+STM32F4X_ADC_NUM) + #define PI0 (108+STM32F4X_ADC_NUM) //1:TIM5_CH4 / SPI2_NSS + #define PI1 (109+STM32F4X_ADC_NUM) //1:SPI2_SCK + #define PI2 (110+STM32F4X_ADC_NUM) //1:TIM8_CH4 /SPI2_MISO + #define PI3 (111+STM32F4X_ADC_NUM) //1:SPI2_MOS + #define PI4 (112+STM32F4X_ADC_NUM) + #define PI5 (113+STM32F4X_ADC_NUM) //1:TIM8_CH1 + #define PI6 (114+STM32F4X_ADC_NUM) //1:TIM8_CH2 + #define PI7 (115+STM32F4X_ADC_NUM) //1:TIM8_CH3 +#endif + +// This must be a literal +#define NUM_DIGITAL_PINS (STM32F4X_GPIO_NUM) +// This must be a literal with a value less than or equal to MAX_ANALOG_INPUTS +#define NUM_ANALOG_INPUTS (STM32F4X_ADC_NUM) +#define NUM_ANALOG_FIRST 35 + +// Below ADC, DAC and PWM definitions already done in the core +// Could be redefined here if needed +// ADC resolution is 12bits +//#define ADC_RESOLUTION 12 +//#define DACC_RESOLUTION 12 + +// PWM resolution +/* + * BEWARE: + * Changing this value from the default (1000) will affect the PWM output value of analogWrite (to a PWM pin) + * Since the pin is toggled on capture, if you change the frequency of the timer you have to adapt the compare value (analogWrite thinks you did) + */ +//#define PWM_FREQUENCY 20000 +//The bottom values are the default and don't need to be redefined +//#define PWM_RESOLUTION 8 +//#define PWM_MAX_DUTY_CYCLE 255 + +// Below SPI and I2C definitions already done in the core +// Could be redefined here if differs from the default one +// SPI Definitions +#define PIN_SPI_MOSI PB15 +#define PIN_SPI_MISO PB14 +#define PIN_SPI_SCK PB13 +#define PIN_SPI_SS PB12 + +// I2C Definitions +#define PIN_WIRE_SDA PB7 +#define PIN_WIRE_SCL PB6 + +// Timer Definitions +//Do not use timer used by PWM pins when possible. See PinMap_PWM in PeripheralPins.c +#define TIMER_TONE TIM7 +#define TIMER_SERVO TIM5 +#define TIMER_SERIAL TIM2 + +// UART Definitions +// Define here Serial instance number to map on Serial generic name +#define SERIAL_UART_INSTANCE 1 //ex: 2 for Serial2 (USART2) +// DEBUG_UART could be redefined to print on another instance than 'Serial' +//#define DEBUG_UART ((USART_TypeDef *) U(S)ARTX) // ex: USART3 +// DEBUG_UART baudrate, default: 9600 if not defined +//#define DEBUG_UART_BAUDRATE x +// DEBUG_UART Tx pin name, default: the first one found in PinMap_UART_TX for DEBUG_UART +//#define DEBUG_PINNAME_TX PX_n // PinName used for TX + +// Default pin used for 'Serial' instance (ex: ST-Link) +// Mandatory for Firmata +#define PIN_SERIAL_RX PA10 +#define PIN_SERIAL_TX PA9 + +// Serial Pins for the MMU2 +#define ENABLE_HWSERIAL4 +#define PIN_SERIAL4_RX PC11 +#define PIN_SERIAL4_TX PC10 + +#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 +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_E3_RRF/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_E3_RRF/PeripheralPins.c new file mode 100644 index 000000000000..9e42baf210bf --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_E3_RRF/PeripheralPins.c @@ -0,0 +1,363 @@ +/* + ******************************************************************************* + * 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 STM32F407Z(E-G)Tx.xml + */ +#include +#include + +/* ===== + * Note: Commented lines are alternative possibilities which are not used by default. + * If you change them, you should know what you're doing first. + * ===== + */ + +//*** ADC *** + +#ifdef HAL_ADC_MODULE_ENABLED +const PinMap PinMap_ADC[] = { + {PA_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0 TH0 + {PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1 TB + {PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2 IDEX TH1 + {PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3 IDEX INA826 PT100 + {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 + + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio, 24 ADC + {PF_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC3_IN9 + {PF_4, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC3_IN14 + {PF_5, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC3_IN15 + {PF_6, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC3_IN4 + {PF_7, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC3_IN5 + {PF_8, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC3_IN6 + {PF_9, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC3_IN7 + {PF_10, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC3_IN8 + #endif + {NC, NP, 0} +}; +#endif + +//*** DAC *** + +#ifdef HAL_DAC_MODULE_ENABLED +const PinMap PinMap_DAC[] = { + {PA_4, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // DAC_OUT1 + {PA_5, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // DAC_OUT2 + {NC, NP, 0} +}; +#endif + +//*** I2C *** + +#ifdef HAL_I2C_MODULE_ENABLED +const PinMap PinMap_I2C_SDA[] = { + {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)}, + {PB_11, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + {PC_9, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + {PF_0, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + #endif + {NC, NP, 0} +}; +#endif + +#ifdef HAL_I2C_MODULE_ENABLED +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)}, + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + {PF_1, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + #endif + {NC, NP, 0} +}; +#endif + +//*** PWM *** + +#ifdef HAL_TIM_MODULE_ENABLED +const PinMap PinMap_PWM[] = { + {PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 HE0 + {PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 BED + {PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 FAN0 + {PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 FAN1 + {PE_5, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 IDEX FAN0 + {PE_6, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2 IDEX FAN1 + + /** + * Unused by specifications on BTT E3 RRF. (PLEASE CONFIRM) + * Uncomment the corresponding line if you want to have HardwarePWM on some pins. + * WARNING: check timers' usage first to avoid conflicts. + * If you don't know what you're doing leave things as they are or you WILL break something (including hardware) + * If you alter this section DO NOT report bugs to Marlin team since they are most likely caused by you. Thank you. + */ + //{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_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + //{PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + //{PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)},// TIM13_CH1 + //{PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + //{PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + //{PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + //{PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)},// TIM14_CH1 + //{PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 + //{PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 + //{PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 + //{PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 + //{PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + //{PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + //{PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 + //{PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N + //{PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + //{PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 + //{PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N + //{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_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 + //{PB_8, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)},// TIM10_CH1 + //{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_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 + //{PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + //{PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + //{PB_14, 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 + //{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 + //{PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + //{PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 + //{PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + //{PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 + //{PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 + //{PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 0)}, // TIM8_CH3 + //{PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 + //{PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 4, 0)}, // TIM8_CH4 + //{PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 + //{PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 + //{PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 + //{PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 + //{PE_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + //{PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 + //{PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + //{PE_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 + //{PE_12, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + //{PE_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 + //{PE_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + //{PF_6, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1 + //{PF_7, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 + //{PF_8, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 + //{PF_9, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 + #endif + {NC, NP, 0} +}; +#endif + +//*** SERIAL *** + +#ifdef HAL_UART_MODULE_ENABLED +const PinMap PinMap_UART_TX[] = { + {PA_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PD_8, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PC_6, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + {PC_10, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PC_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PC_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + {PD_5, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + {PG_14, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + #endif + {NC, NP, 0} +}; + +const PinMap PinMap_UART_RX[] = { + {PA_1, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PA_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PA_10, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PB_7, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PD_9, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PB_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PC_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + {PC_11, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PC_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PD_2, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + {PD_6, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + {PG_9, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + #endif + {NC, NP, 0} +}; + +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)}, + {PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PD_4, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PD_12, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + {PG_8, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + {PG_12, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + #endif + {NC, NP, 0} +}; + +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)}, + {PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PD_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PD_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + {PG_13, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + {PG_15, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + #endif + {NC, NP, 0} +}; +#endif + +//*** SPI *** + +#ifdef HAL_SPI_MODULE_ENABLED +const PinMap PinMap_SPI_MOSI[] = { + {PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, + {PB_15, 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} +}; + +const PinMap PinMap_SPI_MISO[] = { + {PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, + {PB_14, 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} +}; + +const PinMap PinMap_SPI_SCLK[] = { + {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, + {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} +}; + +const PinMap PinMap_SPI_SSEL[] = { + {PA_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, + {PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PA_15, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {NC, NP, 0} +}; +#endif + +//*** CAN *** + +#ifdef HAL_CAN_MODULE_ENABLED +#error "CAN bus isn't available on this board. Driver should be disabled." +#endif + +//*** ETHERNET *** +#ifdef HAL_ETH_MODULE_ENABLED +#error "Ethernet port isn't available on this board. Driver should be disabled." +#endif + +//*** No QUADSPI *** + +//*** USB *** +#ifdef HAL_PCD_MODULE_ENABLED +const PinMap PinMap_USB_OTG_FS[] = { + //{PA_8, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_SOF + //{PA_9, USB_OTG_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_FS_VBUS + //{PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_ID + {PA_11, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DM + {PA_12, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DP + {NC, NP, 0} +}; + +const PinMap PinMap_USB_OTG_HS[] = { /* + #ifdef USE_USB_HS_IN_FS + {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_ID + {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_HS_VBUS + {PB_14, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DM + {PB_15, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DP + #else + #error "USB in HS mode isn't supported by the board" + {PA_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D0 + {PB_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D1 + {PB_1, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D2 + {PB_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D7 + {PB_10, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D3 + {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D5 + {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D6 + {PC_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_STP + {PC_2, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_DIR + {PC_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_NXT + #endif // USE_USB_HS_IN_FS + */ + {NC, NP, 0} +}; + +#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 +#endif diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_E3_RRF/PinNamesVar.h similarity index 100% rename from buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/PinNamesVar.h rename to buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_E3_RRF/PinNamesVar.h diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_E3_RRF/hal_conf_extra.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_E3_RRF/hal_conf_extra.h new file mode 100644 index 000000000000..6c4a991f33b8 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_E3_RRF/hal_conf_extra.h @@ -0,0 +1,52 @@ +#pragma once + +#define HAL_MODULE_ENABLED +#define HAL_ADC_MODULE_ENABLED +#define HAL_CRC_MODULE_ENABLED +#define HAL_DMA_MODULE_ENABLED +#define HAL_GPIO_MODULE_ENABLED +#define HAL_I2C_MODULE_ENABLED +#define HAL_PWR_MODULE_ENABLED +#define HAL_RCC_MODULE_ENABLED +//#define HAL_RTC_MODULE_ENABLED Real Time Clock...do we use it? +#define HAL_SPI_MODULE_ENABLED +#define HAL_TIM_MODULE_ENABLED +#define HAL_USART_MODULE_ENABLED +#define HAL_CORTEX_MODULE_ENABLED +//#define HAL_UART_MODULE_ENABLED // by default +//#define HAL_PCD_MODULE_ENABLED // Since STM32 v3.10700.191028 this is automatically added if any type of USB is enabled (as in Arduino IDE) +#define HAL_SD_MODULE_ENABLED + +#undef HAL_DAC_MODULE_ENABLED +#undef HAL_FLASH_MODULE_ENABLED +#undef HAL_CAN_MODULE_ENABLED +#undef HAL_CAN_LEGACY_MODULE_ENABLED +#undef HAL_CEC_MODULE_ENABLED +#undef HAL_CRYP_MODULE_ENABLED +#undef HAL_DCMI_MODULE_ENABLED +#undef HAL_DMA2D_MODULE_ENABLED +#undef HAL_ETH_MODULE_ENABLED +#undef HAL_NAND_MODULE_ENABLED +#undef HAL_NOR_MODULE_ENABLED +#undef HAL_PCCARD_MODULE_ENABLED +#undef HAL_SRAM_MODULE_ENABLED +#undef HAL_SDRAM_MODULE_ENABLED +#undef HAL_HASH_MODULE_ENABLED +#undef HAL_EXTI_MODULE_ENABLED +#undef HAL_SMBUS_MODULE_ENABLED +#undef HAL_I2S_MODULE_ENABLED +#undef HAL_IWDG_MODULE_ENABLED +#undef HAL_LTDC_MODULE_ENABLED +#undef HAL_DSI_MODULE_ENABLED +#undef HAL_QSPI_MODULE_ENABLED +#undef HAL_RNG_MODULE_ENABLED +#undef HAL_SAI_MODULE_ENABLED +#undef HAL_IRDA_MODULE_ENABLED +#undef HAL_SMARTCARD_MODULE_ENABLED +#undef HAL_WWDG_MODULE_ENABLED +#undef HAL_HCD_MODULE_ENABLED +#undef HAL_FMPI2C_MODULE_ENABLED +#undef HAL_SPDIFRX_MODULE_ENABLED +#undef HAL_DFSDM_MODULE_ENABLED +#undef HAL_LPTIM_MODULE_ENABLED +#undef HAL_MMC_MODULE_ENABLED diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_E3_RRF/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_E3_RRF/ldscript.ld new file mode 100644 index 000000000000..6af296a521ff --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_E3_RRF/ldscript.ld @@ -0,0 +1,204 @@ +/* +***************************************************************************** +** + +** File : LinkerScript.ld +** +** Abstract : Linker script for STM32F407ZGTx Device with +** 1024KByte FLASH, 128KByte 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 = 0x20020000; /* 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 = 0x8008000, LENGTH = 1024K +RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K +CCMRAM (rw) : ORIGIN = 0x10000000, 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): + { + . = 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 + + _siccmram = LOADADDR(.ccmram); + + /* CCM-RAM section + * + * IMPORTANT NOTE! + * If initialized variables will be placed in this section, + * the startup code needs to be modified to copy the init-values. + */ + .ccmram : + { + . = ALIGN(4); + _sccmram = .; /* create a global symbol at ccmram start */ + *(.ccmram) + *(.ccmram*) + + . = ALIGN(4); + _eccmram = .; /* create a global symbol at ccmram end */ + } >CCMRAM AT> FLASH + + + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss section */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* User_heap_stack section, used to check that there is enough RAM left */ + ._user_heap_stack : + { + . = ALIGN(4); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(4); + } >RAM + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/variant.cpp b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_E3_RRF/variant.cpp similarity index 100% rename from buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/variant.cpp rename to buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_E3_RRF/variant.cpp diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_E3_RRF/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_E3_RRF/variant.h new file mode 100644 index 000000000000..42f21ce5a6cb --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_E3_RRF/variant.h @@ -0,0 +1,292 @@ +/* + ******************************************************************************* + * Copyright (c) 2017, 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. + ******************************************************************************* + */ +#pragma once + +#ifdef __cplusplus +extern "C" { +#endif // __cplusplus + +/*---------------------------------------------------------------------------- + * Pins + *----------------------------------------------------------------------------*/ + +#ifdef STM32F405RX + #define STM32F4X_PIN_NUM 64 //64 pins mcu, 51 gpio + #define STM32F4X_GPIO_NUM 51 + #define STM32F4X_ADC_NUM 16 +#elif defined(STM32F407_5VX) + #define STM32F4X_PIN_NUM 100 //100 pins mcu, 82 gpio + #define STM32F4X_GPIO_NUM 82 + #define STM32F4X_ADC_NUM 16 +#elif defined(STM32F407_5ZX) + #define STM32F4X_PIN_NUM 144 //144 pins mcu, 114 gpio + #define STM32F4X_GPIO_NUM 114 + #define STM32F4X_ADC_NUM 24 +#elif defined(STM32F407IX) + #define STM32F4X_PIN_NUM 176 //176 pins mcu, 140 gpio + #define STM32F4X_GPIO_NUM 140 + #define STM32F4X_ADC_NUM 24 +#else + #error "no match MCU defined" +#endif + +#if STM32F4X_PIN_NUM >= 64 //64 pins mcu, 51 gpio + #define PC13 0 + #define PC14 1 //OSC32_IN + #define PC15 2 //OSC32_OUT + #define PH0 3 //OSC_IN + #define PH1 4 //OSC_OUT + #define PB2 5 //BOOT1 + #define PB10 6 //1:SPI2_SCK / I2C2_SCL / USART3_TX / TIM2_CH3 + #define PB11 7 //1:I2C2_SDA / USART3_RX / TIM2_CH4 + #define PB12 8 //1:SPI2_NSS / OTG_HS_ID + #define PB13 9 //1:SPI2_SCK 2:OTG_HS_VBUS + #define PB14 10 //1:SPI2_MISO / TIM12_CH1 / OTG_HS_DM + #define PB15 11 //SPI2_MOSI / TIM12_CH2 / OTG_HS_DP + #define PC6 12 //1:TIM8_CH1 / SDIO_D6 / USART6_TX / TIM3_CH1 + #define PC7 13 //1:TIM8_CH2 / SDIO_D7 / USART6_RX / TIM3_CH2 + #define PC8 14 //1:TIM8_CH3 / SDIO_D0 / TIM3_CH3 + #define PC9 15 //1:TIM8_CH4 / SDIO_D1 / TIM3_CH4 + #define PA8 16 //1:TIM1_CH1 / I2C3_SCL / OTG_FS_SOF + #define PA9 17 //1:USART1_TX / TIM1_CH2 2:OTG_FS_VBUS + #define PA10 18 //1:USART1_RX / TIM1_CH3 / OTG_FS_ID + #define PA11 19 //1:TIM1_CH4 / OTG_FS_DM + #define PA12 20 //1:OTG_FS_DP + #define PA13 21 //0:JTMS-SWDIO + #define PA14 22 //0:JTCK-SWCLK + #define PA15 23 //0:JTDI 1:SPI3_NSS / SPI1_NSS + #define PC10 24 //1:UART4_TX / SPI3_SCK / SDIO_D2 / USART3_TX + #define PC11 25 //1:UART4_RX / SPI3_MISO / SDIO_D3 / USART3_RX + #define PC12 26 //1:UART5_TX / SPI3_MOSI / SDIO_CK + #define PD2 27 //1:UART5_RX / SDIO_CMD + #define PB3 28 //0:JTDO 1:SPI3_SCK / TIM2_CH2 / SPI1_SCK + #define PB4 29 //0:NJTRST 1:SPI3_MISO / TIM3_CH1 / SPI1_MISO + #define PB5 30 //1:TIM3_CH2 / SPI1_MOSI / SPI3_MOSI + #define PB6 31 //1:I2C1_SCL / TIM4_CH1 / USART1_TX + #define PB7 32 //1:I2C1_SDA / TIM4_CH2 / USART1_RX + #define PB8 33 //1:I2C1_SCL / TIM4_CH3 / SDIO_D4 / TIM10_CH1 + #define PB9 34 //1:I2C1_SDA / TIM4_CH4 / SDIO_D5 / TIM11_CH1 / SPI2_NSS + #define PA0 35 //1:UART4_TX / TIM5_CH1 2:ADC123_IN0 + #define PA1 36 //1:UART4_RX / TIM5_CH2 / TIM2_CH2 2:ADC123_IN1 + #define PA2 37 //1:USART2_TX /TIM5_CH3 / TIM9_CH1 / TIM2_CH3 2:ADC123_IN2 + #define PA3 38 //1:USART2_RX /TIM5_CH4 / TIM9_CH2 / TIM2_CH4 2:ADC123_IN3 + #define PA4 39 //NOT FT 1:SPI1_NSS / SPI3_NSS / USART2_CK 2:ADC12_IN4 / DAC_OUT1 + #define PA5 40 //NOT FT 1:SPI1_SCK 2:ADC12_IN5 / DAC_OUT2 + #define PA6 41 //1:SPI1_MISO / TIM13_CH1 / TIM3_CH1 2:ADC12_IN6 + #define PA7 42 //1:SPI1_MOSI / TIM14_CH1 / TIM3_CH2 2:ADC12_IN7 + #define PB0 43 //1:TIM3_CH3 2:ADC12_IN8 + #define PB1 44 //1:TIM3_CH4 2:ADC12_IN9 + #define PC0 45 //1: 2:ADC123_IN10 + #define PC1 46 //1: 2:ADC123_IN11 + #define PC2 47 //1:SPI2_MISO 2:ADC123_IN12 + #define PC3 48 //1:SPI2_MOSI 2:ADC123_IN13 + #define PC4 49 //1: 2:ADC12_IN14 + #define PC5 50 //1: 2:ADC12_IN15 + #if STM32F4X_PIN_NUM >= 144 + #define PF3 51 //1:FSMC_A3 2:ADC3_IN9 + #define PF4 52 //1:FSMC_A4 2:ADC3_IN14 + #define PF5 53 //1:FSMC_A5 2:ADC3_IN15 + #define PF6 54 //1:TIM10_CH1 2:ADC3_IN4 + #define PF7 55 //1:TIM11_CH1 2:ADC3_IN5 + #define PF8 56 //1:TIM13_CH1 2:ADC3_IN6 + #define PF9 57 //1;TIM14_CH1 2:ADC3_IN7 + #define PF10 58 //2:ADC3_IN8 + #endif +#endif +#if STM32F4X_PIN_NUM >= 100 //100 pins mcu, 82 gpio + #define PE2 (35+STM32F4X_ADC_NUM) //1:FSMC_A23 + #define PE3 (36+STM32F4X_ADC_NUM) //1:FSMC_A19 + #define PE4 (37+STM32F4X_ADC_NUM) //1:FSMC_A20 + #define PE5 (38+STM32F4X_ADC_NUM) //1:FSMC_A21 + #define PE6 (39+STM32F4X_ADC_NUM) //1:FSMC_A22 + #define PE7 (40+STM32F4X_ADC_NUM) //1:FSMC_D4 + #define PE8 (41+STM32F4X_ADC_NUM) //1:FSMC_D5 + #define PE9 (42+STM32F4X_ADC_NUM) //1:FSMC_D6 / TIM1_CH1 + #define PE10 (43+STM32F4X_ADC_NUM) //1:FSMC_D7 + #define PE11 (44+STM32F4X_ADC_NUM) //1:FSMC_D8 / TIM1_CH2 + #define PE12 (45+STM32F4X_ADC_NUM) //1:FSMC_D9 + #define PE13 (46+STM32F4X_ADC_NUM) //1:FSMC_D10 / TIM1_CH3 + #define PE14 (47+STM32F4X_ADC_NUM) //1:FSMC_D11 / TIM1_CH4 + #define PE15 (48+STM32F4X_ADC_NUM) //1:FSMC_D12 + #define PD8 (49+STM32F4X_ADC_NUM) //1:FSMC_D13 / USART3_TX + #define PD9 (50+STM32F4X_ADC_NUM) //1:FSMC_D14 / USART3_RX + #define PD10 (51+STM32F4X_ADC_NUM) //1:FSMC_D15 + #define PD11 (52+STM32F4X_ADC_NUM) //1:FSMC_A16 + #define PD12 (53+STM32F4X_ADC_NUM) //1:FSMC_A17 / TIM4_CH1 + #define PD13 (54+STM32F4X_ADC_NUM) //1:FSMC_A18 / TIM4_CH2 + #define PD14 (55+STM32F4X_ADC_NUM) //1:FSMC_D0 / TIM4_CH3 + #define PD15 (56+STM32F4X_ADC_NUM) //1:FSMC_D1 / TIM4_CH4 + #define PD0 (57+STM32F4X_ADC_NUM) //1:FSMC_D2 + #define PD1 (58+STM32F4X_ADC_NUM) //1:FSMC_D3 + #define PD3 (59+STM32F4X_ADC_NUM) //1:FSMC_CLK + #define PD4 (60+STM32F4X_ADC_NUM) //1:FSMC_NOE + #define PD5 (61+STM32F4X_ADC_NUM) //1:USART2_TX + #define PD6 (62+STM32F4X_ADC_NUM) //1:USART2_RX + #define PD7 (63+STM32F4X_ADC_NUM) + #define PE0 (64+STM32F4X_ADC_NUM) + #define PE1 (65+STM32F4X_ADC_NUM) +#endif +#if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + #define PF0 (66+STM32F4X_ADC_NUM) //1:FSMC_A0 / I2C2_SDA + #define PF1 (67+STM32F4X_ADC_NUM) //1:FSMC_A1 / I2C2_SCL + #define PF2 (68+STM32F4X_ADC_NUM) //1:FSMC_A2 + #define PF11 (69+STM32F4X_ADC_NUM) + #define PF12 (70+STM32F4X_ADC_NUM) //1:FSMC_A6 + #define PF13 (71+STM32F4X_ADC_NUM) //1:FSMC_A7 + #define PF14 (72+STM32F4X_ADC_NUM) //1:FSMC_A8 + #define PF15 (73+STM32F4X_ADC_NUM) //1:FSMC_A9 + #define PG0 (74+STM32F4X_ADC_NUM) //1:FSMC_A10 + #define PG1 (75+STM32F4X_ADC_NUM) //1:FSMC_A11 + #define PG2 (76+STM32F4X_ADC_NUM) //1:FSMC_A12 + #define PG3 (77+STM32F4X_ADC_NUM) //1:FSMC_A13 + #define PG4 (78+STM32F4X_ADC_NUM) //1:FSMC_A14 + #define PG5 (79+STM32F4X_ADC_NUM) //1:FSMC_A15 + #define PG6 (80+STM32F4X_ADC_NUM) + #define PG7 (81+STM32F4X_ADC_NUM) + #define PG8 (82+STM32F4X_ADC_NUM) + #define PG9 (83+STM32F4X_ADC_NUM) //1:USART6_RX + #define PG10 (84+STM32F4X_ADC_NUM) //1:FSMC_NE3 + #define PG11 (85+STM32F4X_ADC_NUM) + #define PG12 (86+STM32F4X_ADC_NUM) //1:FSMC_NE4 + #define PG13 (87+STM32F4X_ADC_NUM) //1:FSMC_A24 + #define PG14 (88+STM32F4X_ADC_NUM) //1:FSMC_A25 / USART6_TX + #define PG15 (89+STM32F4X_ADC_NUM) +#endif +#if STM32F4X_PIN_NUM >= 176 //176 pins mcu, 140 gpio + #define PI8 (90+STM32F4X_ADC_NUM) + #define PI9 (91+STM32F4X_ADC_NUM) + #define PI10 (92+STM32F4X_ADC_NUM) + #define PI11 (93+STM32F4X_ADC_NUM) + #define PH2 (94+STM32F4X_ADC_NUM) + #define PH3 (95+STM32F4X_ADC_NUM) + #define PH4 (96+STM32F4X_ADC_NUM) //1:I2C2_SCL + #define PH5 (97+STM32F4X_ADC_NUM) //1:I2C2_SDA + #define PH6 (98+STM32F4X_ADC_NUM) //1:TIM12_CH1 + #define PH7 (99+STM32F4X_ADC_NUM) //1:I2C3_SCL + #define PH8 (100+STM32F4X_ADC_NUM) //1:I2C3_SDA + #define PH9 (101+STM32F4X_ADC_NUM) //1:TIM12_CH2 + #define PH10 (102+STM32F4X_ADC_NUM) //1:TIM5_CH1 + #define PH11 (103+STM32F4X_ADC_NUM) //1:TIM5_CH2 + #define PH12 (104+STM32F4X_ADC_NUM) //1:TIM5_CH3 + #define PH13 (105+STM32F4X_ADC_NUM) + #define PH14 (106+STM32F4X_ADC_NUM) + #define PH15 (107+STM32F4X_ADC_NUM) + #define PI0 (108+STM32F4X_ADC_NUM) //1:TIM5_CH4 / SPI2_NSS + #define PI1 (109+STM32F4X_ADC_NUM) //1:SPI2_SCK + #define PI2 (110+STM32F4X_ADC_NUM) //1:TIM8_CH4 /SPI2_MISO + #define PI3 (111+STM32F4X_ADC_NUM) //1:SPI2_MOS + #define PI4 (112+STM32F4X_ADC_NUM) + #define PI5 (113+STM32F4X_ADC_NUM) //1:TIM8_CH1 + #define PI6 (114+STM32F4X_ADC_NUM) //1:TIM8_CH2 + #define PI7 (115+STM32F4X_ADC_NUM) //1:TIM8_CH3 +#endif + +// This must be a literal +#define NUM_DIGITAL_PINS (STM32F4X_GPIO_NUM) +// This must be a literal with a value less than or equal to MAX_ANALOG_INPUTS +#define NUM_ANALOG_INPUTS (STM32F4X_ADC_NUM) +#define NUM_ANALOG_FIRST 35 + +// Below ADC, DAC and PWM definitions already done in the core +// Could be redefined here if needed +// ADC resolution is 12bits +//#define ADC_RESOLUTION 12 +//#define DACC_RESOLUTION 12 + +// PWM resolution +/* + * BEWARE: + * Changing this value from the default (1000) will affect the PWM output value of analogWrite (to a PWM pin) + * Since the pin is toggled on capture, if you change the frequency of the timer you have to adapt the compare value (analogWrite thinks you did) + */ +//#define PWM_FREQUENCY 20000 +//The bottom values are the default and don't need to be redefined +//#define PWM_RESOLUTION 8 +//#define PWM_MAX_DUTY_CYCLE 255 + +// Below SPI and I2C definitions already done in the core +// Could be redefined here if differs from the default one +// SPI Definitions +#define PIN_SPI_MOSI PA7 +#define PIN_SPI_MISO PA6 +#define PIN_SPI_SCK PA5 +#define PIN_SPI_SS PA4 + +// I2C Definitions +#define PIN_WIRE_SDA PB9 +#define PIN_WIRE_SCL PB8 + +// Timer Definitions +//Do not use timer used by PWM pins when possible. See PinMap_PWM in PeripheralPins.c +#define TIMER_TONE TIM7 +#define TIMER_SERVO TIM5 +#define TIMER_SERIAL TIM8 + +// UART Definitions +// Define here Serial instance number to map on Serial generic name +#define SERIAL_UART_INSTANCE 1 //ex: 2 for Serial2 (USART2) +// DEBUG_UART could be redefined to print on another instance than 'Serial' +//#define DEBUG_UART ((USART_TypeDef *) U(S)ARTX) // ex: USART3 +// DEBUG_UART baudrate, default: 9600 if not defined +//#define DEBUG_UART_BAUDRATE x +// DEBUG_UART Tx pin name, default: the first one found in PinMap_UART_TX for DEBUG_UART +//#define DEBUG_PINNAME_TX PX_n // PinName used for TX + +// Default pin used for 'Serial' instance (ex: ST-Link) +// Mandatory for Firmata +#define PIN_SERIAL_RX PA10 +#define PIN_SERIAL_TX PA9 + +#ifdef __cplusplus +} // extern "C" +#endif +/*---------------------------------------------------------------------------- + * Arduino objects - C++ only + *----------------------------------------------------------------------------*/ + +#ifdef __cplusplus +// These serial port names are intended to allow libraries and architecture-neutral +// sketches to automatically default to the correct port name for a particular type +// of use. For example, a GPS module would normally connect to SERIAL_PORT_HARDWARE_OPEN, +// the first hardware serial port whose RX/TX pins are not dedicated to another use. +// +// SERIAL_PORT_MONITOR Port which normally prints to the Arduino Serial Monitor +// +// SERIAL_PORT_USBVIRTUAL Port which is USB virtual serial +// +// SERIAL_PORT_LINUXBRIDGE Port which connects to a Linux system via Bridge library +// +// SERIAL_PORT_HARDWARE Hardware serial port, physical RX & TX pins. +// +// SERIAL_PORT_HARDWARE_OPEN Hardware serial ports which are open for use. Their RX & TX +// pins are NOT connected to anything by default. +#define SERIAL_PORT_MONITOR Serial +#define SERIAL_PORT_HARDWARE Serial1 +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/PeripheralPins.c new file mode 100644 index 000000000000..48e05e45ad0c --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/PeripheralPins.c @@ -0,0 +1,377 @@ +/* + ******************************************************************************* + * 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 STM32F407Z(E-G)Tx.xml + */ +#include +#include + +/* ===== + * Note: Commented lines are alternative possibilities which are not used by default. + * If you change them, you should know what you're doing first. + * ===== + */ + +//*** ADC *** + +#ifdef HAL_ADC_MODULE_ENABLED +const PinMap PinMap_ADC[] = { + {PA_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0 E0_DIR + {PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1 BLTOUCH_2 + {PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2 BLTOUCH_4 + {PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3 E1_EN + {PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4 TF_SS + {PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5 TF_SCLK + {PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6 TF_MISO + {PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7 LED (MOSI) + {PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8 HEATER2 + {PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9 HEATER0 + {PC_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10 Z_EN + {PC_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11 EXP_14 + {PC_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12 Z_DIR + {PC_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13 E0_EN + {PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14 EXP_8 + {PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15 EXP_7 + + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio, 24 ADC + {PF_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC3_IN9 TH_0 + {PF_4, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC3_IN14 TH_1 + {PF_5, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC3_IN15 TH_2 + {PF_6, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC3_IN4 TH_3 + {PF_7, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC3_IN5 EXP_13 + {PF_8, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC3_IN6 EXP_3 + {PF_9, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC3_IN7 EXP_6 + {PF_10, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC3_IN8 EXP_5 + #endif + {NC, NP, 0} +}; +#endif + +//*** DAC *** + +#ifdef HAL_DAC_MODULE_ENABLED +const PinMap PinMap_DAC[] = { + {PA_4, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // DAC_OUT1 + {PA_5, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // DAC_OUT2 + {NC, NP, 0} +}; +#endif + +//*** I2C *** + +#ifdef HAL_I2C_MODULE_ENABLED +const PinMap PinMap_I2C_SDA[] = { + {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)}, + {PB_11, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + {PC_9, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, + #if STM32F4X_PIN_NUM >= 144 // 144 pins mcu, 114 gpio + #if STM32F4X_PIN_NUM >= 176 + {PH_5, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + {PH_8, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, + #else + {PF_0, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + #endif + #endif + {NC, NP, 0} +}; + +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)}, + #if STM32F4X_PIN_NUM >= 144 // 144 pins mcu, 114 gpio + #if STM32F4X_PIN_NUM >= 176 + //{PF_1, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + {PH_4, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + {PH_7, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, + #else + {PF_1, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + #endif + #endif + {NC, NP, 0} +}; +#endif + +//*** PWM *** + +#ifdef HAL_TIM_MODULE_ENABLED +const PinMap PinMap_PWM[] = { + + // Some pins can perform PWM from more than one timer. These were selected to utilize as many channels as + // possible from timers which were already dedicated to PWM output. + // TIM1 = [FAN4, FAN5, HEATER6, FAN7] + // TIM2 = [, HEATER1, BED, ] + // TIM3 = [, , HEATER2, HEATER0] + // TIM4 = [HEATER5, HEATER4, , HEATER3] + // TIM8 = [FAN3, HEATER7, FAN2, FAN6] + // TIM9 = [FAN0, FAN1, , ] + + {PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 HEATER0 + {PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 HEATER1 + {PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 HEATER2 + {PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 HEATER3 + {PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 HEATER4 + {PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 HEATER5 + {PE_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 HEATER6 + {PI_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 HEATER7 + {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 BED + + {PE_5, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 FAN0 + {PE_6, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2 FAN1 + {PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 0)}, // TIM8_CH3 FAN2 + {PI_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 FAN3 + {PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 FAN4 + {PE_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 FAN5 + {PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 4, 0)}, // TIM8_CH4 FAN6 + {PE_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 FAN7 + + // Alternate timer assignments for pins commonly using PWM + //{PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N HEATER0 + //{PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N HEATER0 + //{PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 HEATER1 + //{PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N HEATER2 + //{PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N HEATER2 + //{PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3 BED + //{PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 BED + //{PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 FAN2 + //{PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 FAN6 + + // Pins with an available timer channel, on a timer already allocated for PWM. + // These can be freely used for purposes requiring PWM, without creating new timer conflicts. + // This pins are very likely already used for other purposes and enabling PWM on them won't be useful. + {PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 BLTouch / Probe Output + {PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 ESP8266 connector. Available if 8266 isn't used + {PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 ESP8266 connector. Available if 8266 isn't used + + /* + * Pins not utilizing hardware PWM on the GTR. + * Uncomment the corresponding line if you want to have HardwarePWM on some pins. + * WARNING: check timers' usage first to avoid conflicts. + * If you don't know what you're doing leave things as they are or you WILL break something (including hardware) + */ + //{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_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_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + //{PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + //{PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 + //{PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + //{PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + //{PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + //{PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 + //{PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 + //{PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 + //{PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 + //{PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 + //{PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + //{PB_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_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 + //{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 + //{PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 + //{PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + //{PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 + //{PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 + //{PE_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + //{PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + //{PE_12, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + //{PF_6, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1 + //{PF_7, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 + //{PF_8, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 + //{PF_9, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 + //{PH_10, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1 + //{PH_6, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 1, 0)}, // TIM12_CH1 + //{PH_11, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 + {NC, NP, 0} +}; +#endif + +//*** SERIAL *** + +#ifdef HAL_UART_MODULE_ENABLED +const PinMap PinMap_UART_TX[] = { + {PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PD_8, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PC_6, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + //{PG_14, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + #endif + //{PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + //{PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + //{PD_5, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + //{PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PC_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PA_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PC_10, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PC_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + {NC, NP, 0} +}; + +const PinMap PinMap_UART_RX[] = { + {PA_10, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PD_9, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PC_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + //{PA_1, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PA_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + //{PB_7, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + //{PB_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PC_11, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PC_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PD_2, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + //{PD_6, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + //{PG_9, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + #endif + {NC, NP, 0} +}; + +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)}, + //{PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PD_4, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + //{PD_12, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + //{PG_8, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + //{PG_12, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + #endif + {NC, NP, 0} +}; + +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)}, + //{PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PD_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + //{PD_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + //{PG_13, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + //{PG_15, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + #endif + {NC, NP, 0} +}; +#endif + +//*** SPI *** + +#ifdef HAL_SPI_MODULE_ENABLED +const PinMap PinMap_SPI_MOSI[] = { + //{PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, + {PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, + {PB_15, 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} +}; + +const PinMap PinMap_SPI_MISO[] = { + {PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, + {PB_14, 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} +}; + +const PinMap PinMap_SPI_SCLK[] = { + {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, + {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} +}; + +const PinMap PinMap_SPI_SSEL[] = { + {PA_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, + {PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PA_15, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {NC, NP, 0} +}; +#endif + +//*** CAN *** + +#ifdef HAL_CAN_MODULE_ENABLED +#error "CAN bus isn't available on this board. Driver should be disabled." +#endif + +//*** ETHERNET *** +#ifdef HAL_ETH_MODULE_ENABLED +#error "Ethernet port isn't available on this board. Driver should be disabled." +#endif + +//*** No QUADSPI *** + +//*** USB *** +#ifdef HAL_PCD_MODULE_ENABLED +const PinMap PinMap_USB_OTG_FS[] = { + //{PA_8, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_SOF used by LCD + //{PA_9, USB_OTG_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_FS_VBUS available on wifi port, if empty + //{PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_ID available on UART1_RX if not used + {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} +}; + +const PinMap PinMap_USB_OTG_HS[] = { /* + #ifdef USE_USB_HS_IN_FS + {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_ID + {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_HS_VBUS + {PB_14, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DM + {PB_15, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DP + #else + #error "USB in HS mode isn't supported by the board" + {PA_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D0 + {PB_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D1 + {PB_1, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D2 + {PB_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D7 + {PB_10, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D3 + {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D5 + {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D6 + {PC_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_STP + {PC_2, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_DIR + {PC_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_NXT + #endif // USE_USB_HS_IN_FS + */ + {NC, NP, 0} +}; +#endif diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/PinNamesVar.h similarity index 100% rename from buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/PinNamesVar.h rename to buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/PinNamesVar.h diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/hal_conf_extra.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/hal_conf_extra.h new file mode 100644 index 000000000000..e6d558b3e174 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/hal_conf_extra.h @@ -0,0 +1,52 @@ +#pragma once + +#define HAL_MODULE_ENABLED +#define HAL_ADC_MODULE_ENABLED +#define HAL_CRC_MODULE_ENABLED +#define HAL_DMA_MODULE_ENABLED +#define HAL_GPIO_MODULE_ENABLED +#define HAL_I2C_MODULE_ENABLED +#define HAL_PWR_MODULE_ENABLED +#define HAL_RCC_MODULE_ENABLED +//#define HAL_RTC_MODULE_ENABLED Real Time Clock...do we use it? +#define HAL_SPI_MODULE_ENABLED +#define HAL_TIM_MODULE_ENABLED +#define HAL_USART_MODULE_ENABLED +#define HAL_CORTEX_MODULE_ENABLED +//#define HAL_UART_MODULE_ENABLED // by default +//#define HAL_PCD_MODULE_ENABLED // Automatically added if any type of USB is enabled, as in Arduino IDE. (STM32 v3.10700.191028) + +//#define HAL_SD_MODULE_ENABLED +//#define HAL_DAC_MODULE_ENABLED +//#define HAL_FLASH_MODULE_ENABLED +//#define HAL_CAN_MODULE_ENABLED +//#define HAL_CAN_LEGACY_MODULE_ENABLED +//#define HAL_CEC_MODULE_ENABLED +//#define HAL_CRYP_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_IWDG_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_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 diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/ldscript.ld new file mode 100644 index 000000000000..6af296a521ff --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/ldscript.ld @@ -0,0 +1,204 @@ +/* +***************************************************************************** +** + +** File : LinkerScript.ld +** +** Abstract : Linker script for STM32F407ZGTx Device with +** 1024KByte FLASH, 128KByte 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 = 0x20020000; /* 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 = 0x8008000, LENGTH = 1024K +RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K +CCMRAM (rw) : ORIGIN = 0x10000000, 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): + { + . = 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 + + _siccmram = LOADADDR(.ccmram); + + /* CCM-RAM section + * + * IMPORTANT NOTE! + * If initialized variables will be placed in this section, + * the startup code needs to be modified to copy the init-values. + */ + .ccmram : + { + . = ALIGN(4); + _sccmram = .; /* create a global symbol at ccmram start */ + *(.ccmram) + *(.ccmram*) + + . = ALIGN(4); + _eccmram = .; /* create a global symbol at ccmram end */ + } >CCMRAM AT> FLASH + + + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss section */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* User_heap_stack section, used to check that there is enough RAM left */ + ._user_heap_stack : + { + . = ALIGN(4); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(4); + } >RAM + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/variant.cpp b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/variant.cpp similarity index 100% rename from buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/variant.cpp rename to buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/variant.cpp diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/variant.h new file mode 100644 index 000000000000..732e0c51f182 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/variant.h @@ -0,0 +1,322 @@ +/* + ******************************************************************************* + * Copyright (c) 2017, 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. + ******************************************************************************* + */ +#pragma once + +#ifdef __cplusplus +extern "C" { +#endif // __cplusplus + +/*---------------------------------------------------------------------------- + * Pins + *----------------------------------------------------------------------------*/ + +#ifdef STM32F405RX + #define STM32F4X_PIN_NUM 64 //64 pins mcu, 51 gpio + #define STM32F4X_GPIO_NUM 51 + #define STM32F4X_ADC_NUM 16 +#elif defined(STM32F407_5VX) + #define STM32F4X_PIN_NUM 100 //100 pins mcu, 82 gpio + #define STM32F4X_GPIO_NUM 82 + #define STM32F4X_ADC_NUM 16 +#elif defined(STM32F407_5ZX) + #define STM32F4X_PIN_NUM 144 //144 pins mcu, 114 gpio + #define STM32F4X_GPIO_NUM 114 + #define STM32F4X_ADC_NUM 24 +#elif defined(STM32F407IX) + #define STM32F4X_PIN_NUM 176 //176 pins mcu, 140 gpio + #define STM32F4X_GPIO_NUM 140 + #define STM32F4X_ADC_NUM 24 +#else + #error "no match MCU defined" +#endif + +#if STM32F4X_PIN_NUM >= 64 //64 pins mcu, 51 gpio + #define PC13 0 + #define PC14 1 //OSC32_IN + #define PC15 2 //OSC32_OUT + #define PH0 3 //OSC_IN + #define PH1 4 //OSC_OUT + #define PB2 5 //BOOT1 + #define PB10 6 //1:SPI2_SCK / I2C2_SCL / USART3_TX / TIM2_CH3 + #define PB11 7 //1:I2C2_SDA / USART3_RX / TIM2_CH4 + #define PB12 8 //1:SPI2_NSS / OTG_HS_ID + #define PB13 9 //1:SPI2_SCK 2:OTG_HS_VBUS + #define PB14 10 //1:SPI2_MISO / TIM12_CH1 / OTG_HS_DM + #define PB15 11 //SPI2_MOSI / TIM12_CH2 / OTG_HS_DP + #define PC6 12 //1:TIM8_CH1 / SDIO_D6 / USART6_TX / TIM3_CH1 + #define PC7 13 //1:TIM8_CH2 / SDIO_D7 / USART6_RX / TIM3_CH2 + #define PC8 14 //1:TIM8_CH3 / SDIO_D0 / TIM3_CH3 + #define PC9 15 //1:TIM8_CH4 / SDIO_D1 / TIM3_CH4 + #define PA8 16 //1:TIM1_CH1 / I2C3_SCL / OTG_FS_SOF + #define PA9 17 //1:USART1_TX / TIM1_CH2 2:OTG_FS_VBUS + #define PA10 18 //1:USART1_RX / TIM1_CH3 / OTG_FS_ID + #define PA11 19 //1:TIM1_CH4 / OTG_FS_DM + #define PA12 20 //1:OTG_FS_DP + #define PA13 21 //0:JTMS-SWDIO + #define PA14 22 //0:JTCK-SWCLK + #define PA15 23 //0:JTDI 1:SPI3_NSS / SPI1_NSS + #define PC10 24 //1:UART4_TX / SPI3_SCK / SDIO_D2 / USART3_TX + #define PC11 25 //1:UART4_RX / SPI3_MISO / SDIO_D3 / USART3_RX + #define PC12 26 //1:UART5_TX / SPI3_MOSI / SDIO_CK + #define PD2 27 //1:UART5_RX / SDIO_CMD + #define PB3 28 //0:JTDO 1:SPI3_SCK / TIM2_CH2 / SPI1_SCK + #define PB4 29 //0:NJTRST 1:SPI3_MISO / TIM3_CH1 / SPI1_MISO + #define PB5 30 //1:TIM3_CH2 / SPI1_MOSI / SPI3_MOSI + #define PB6 31 //1:I2C1_SCL / TIM4_CH1 / USART1_TX + #define PB7 32 //1:I2C1_SDA / TIM4_CH2 / USART1_RX + #define PB8 33 //1:I2C1_SCL / TIM4_CH3 / SDIO_D4 / TIM10_CH1 + #define PB9 34 //1:I2C1_SDA / TIM4_CH4 / SDIO_D5 / TIM11_CH1 / SPI2_NSS + #define PA0 35 //1:UART4_TX / TIM5_CH1 2:ADC123_IN0 + #define PA1 36 //1:UART4_RX / TIM5_CH2 / TIM2_CH2 2:ADC123_IN1 + #define PA2 37 //1:USART2_TX /TIM5_CH3 / TIM9_CH1 / TIM2_CH3 2:ADC123_IN2 + #define PA3 38 //1:USART2_RX /TIM5_CH4 / TIM9_CH2 / TIM2_CH4 2:ADC123_IN3 + #define PA4 39 //NOT FT 1:SPI1_NSS / SPI3_NSS / USART2_CK 2:ADC12_IN4 / DAC_OUT1 + #define PA5 40 //NOT FT 1:SPI1_SCK 2:ADC12_IN5 / DAC_OUT2 + #define PA6 41 //1:SPI1_MISO / TIM13_CH1 / TIM3_CH1 2:ADC12_IN6 + #define PA7 42 //1:SPI1_MOSI / TIM14_CH1 / TIM3_CH2 2:ADC12_IN7 + #define PB0 43 //1:TIM3_CH3 2:ADC12_IN8 + #define PB1 44 //1:TIM3_CH4 2:ADC12_IN9 + #define PC0 45 //1: 2:ADC123_IN10 + #define PC1 46 //1: 2:ADC123_IN11 + #define PC2 47 //1:SPI2_MISO 2:ADC123_IN12 + #define PC3 48 //1:SPI2_MOSI 2:ADC123_IN13 + #define PC4 49 //1: 2:ADC12_IN14 + #define PC5 50 //1: 2:ADC12_IN15 + #if STM32F4X_PIN_NUM >= 144 + #define PF3 51 //1:FSMC_A3 2:ADC3_IN9 + #define PF4 52 //1:FSMC_A4 2:ADC3_IN14 + #define PF5 53 //1:FSMC_A5 2:ADC3_IN15 + #define PF6 54 //1:TIM10_CH1 2:ADC3_IN4 + #define PF7 55 //1:TIM11_CH1 2:ADC3_IN5 + #define PF8 56 //1:TIM13_CH1 2:ADC3_IN6 + #define PF9 57 //1;TIM14_CH1 2:ADC3_IN7 + #define PF10 58 //2:ADC3_IN8 + #endif +#endif +#if STM32F4X_PIN_NUM >= 100 //100 pins mcu, 82 gpio + #define PE2 (35+STM32F4X_ADC_NUM) //1:FSMC_A23 + #define PE3 (36+STM32F4X_ADC_NUM) //1:FSMC_A19 + #define PE4 (37+STM32F4X_ADC_NUM) //1:FSMC_A20 + #define PE5 (38+STM32F4X_ADC_NUM) //1:FSMC_A21 + #define PE6 (39+STM32F4X_ADC_NUM) //1:FSMC_A22 + #define PE7 (40+STM32F4X_ADC_NUM) //1:FSMC_D4 + #define PE8 (41+STM32F4X_ADC_NUM) //1:FSMC_D5 + #define PE9 (42+STM32F4X_ADC_NUM) //1:FSMC_D6 / TIM1_CH1 + #define PE10 (43+STM32F4X_ADC_NUM) //1:FSMC_D7 + #define PE11 (44+STM32F4X_ADC_NUM) //1:FSMC_D8 / TIM1_CH2 + #define PE12 (45+STM32F4X_ADC_NUM) //1:FSMC_D9 + #define PE13 (46+STM32F4X_ADC_NUM) //1:FSMC_D10 / TIM1_CH3 + #define PE14 (47+STM32F4X_ADC_NUM) //1:FSMC_D11 / TIM1_CH4 + #define PE15 (48+STM32F4X_ADC_NUM) //1:FSMC_D12 + #define PD8 (49+STM32F4X_ADC_NUM) //1:FSMC_D13 / USART3_TX + #define PD9 (50+STM32F4X_ADC_NUM) //1:FSMC_D14 / USART3_RX + #define PD10 (51+STM32F4X_ADC_NUM) //1:FSMC_D15 + #define PD11 (52+STM32F4X_ADC_NUM) //1:FSMC_A16 + #define PD12 (53+STM32F4X_ADC_NUM) //1:FSMC_A17 / TIM4_CH1 + #define PD13 (54+STM32F4X_ADC_NUM) //1:FSMC_A18 / TIM4_CH2 + #define PD14 (55+STM32F4X_ADC_NUM) //1:FSMC_D0 / TIM4_CH3 + #define PD15 (56+STM32F4X_ADC_NUM) //1:FSMC_D1 / TIM4_CH4 + #define PD0 (57+STM32F4X_ADC_NUM) //1:FSMC_D2 + #define PD1 (58+STM32F4X_ADC_NUM) //1:FSMC_D3 + #define PD3 (59+STM32F4X_ADC_NUM) //1:FSMC_CLK + #define PD4 (60+STM32F4X_ADC_NUM) //1:FSMC_NOE + #define PD5 (61+STM32F4X_ADC_NUM) //1:USART2_TX + #define PD6 (62+STM32F4X_ADC_NUM) //1:USART2_RX + #define PD7 (63+STM32F4X_ADC_NUM) + #define PE0 (64+STM32F4X_ADC_NUM) + #define PE1 (65+STM32F4X_ADC_NUM) +#endif +#if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + #define PF0 (66+STM32F4X_ADC_NUM) //1:FSMC_A0 / I2C2_SDA + #define PF1 (67+STM32F4X_ADC_NUM) //1:FSMC_A1 / I2C2_SCL + #define PF2 (68+STM32F4X_ADC_NUM) //1:FSMC_A2 + #define PF11 (69+STM32F4X_ADC_NUM) + #define PF12 (70+STM32F4X_ADC_NUM) //1:FSMC_A6 + #define PF13 (71+STM32F4X_ADC_NUM) //1:FSMC_A7 + #define PF14 (72+STM32F4X_ADC_NUM) //1:FSMC_A8 + #define PF15 (73+STM32F4X_ADC_NUM) //1:FSMC_A9 + #define PG0 (74+STM32F4X_ADC_NUM) //1:FSMC_A10 + #define PG1 (75+STM32F4X_ADC_NUM) //1:FSMC_A11 + #define PG2 (76+STM32F4X_ADC_NUM) //1:FSMC_A12 + #define PG3 (77+STM32F4X_ADC_NUM) //1:FSMC_A13 + #define PG4 (78+STM32F4X_ADC_NUM) //1:FSMC_A14 + #define PG5 (79+STM32F4X_ADC_NUM) //1:FSMC_A15 + #define PG6 (80+STM32F4X_ADC_NUM) + #define PG7 (81+STM32F4X_ADC_NUM) + #define PG8 (82+STM32F4X_ADC_NUM) + #define PG9 (83+STM32F4X_ADC_NUM) //1:USART6_RX + #define PG10 (84+STM32F4X_ADC_NUM) //1:FSMC_NE3 + #define PG11 (85+STM32F4X_ADC_NUM) + #define PG12 (86+STM32F4X_ADC_NUM) //1:FSMC_NE4 + #define PG13 (87+STM32F4X_ADC_NUM) //1:FSMC_A24 + #define PG14 (88+STM32F4X_ADC_NUM) //1:FSMC_A25 / USART6_TX + #define PG15 (89+STM32F4X_ADC_NUM) +#endif +#if STM32F4X_PIN_NUM >= 176 //176 pins mcu, 140 gpio + #define PI8 (90+STM32F4X_ADC_NUM) + #define PI9 (91+STM32F4X_ADC_NUM) + #define PI10 (92+STM32F4X_ADC_NUM) + #define PI11 (93+STM32F4X_ADC_NUM) + #define PH2 (94+STM32F4X_ADC_NUM) + #define PH3 (95+STM32F4X_ADC_NUM) + #define PH4 (96+STM32F4X_ADC_NUM) //1:I2C2_SCL + #define PH5 (97+STM32F4X_ADC_NUM) //1:I2C2_SDA + #define PH6 (98+STM32F4X_ADC_NUM) //1:TIM12_CH1 + #define PH7 (99+STM32F4X_ADC_NUM) //1:I2C3_SCL + #define PH8 (100+STM32F4X_ADC_NUM) //1:I2C3_SDA + #define PH9 (101+STM32F4X_ADC_NUM) //1:TIM12_CH2 + #define PH10 (102+STM32F4X_ADC_NUM) //1:TIM5_CH1 + #define PH11 (103+STM32F4X_ADC_NUM) //1:TIM5_CH2 + #define PH12 (104+STM32F4X_ADC_NUM) //1:TIM5_CH3 + #define PH13 (105+STM32F4X_ADC_NUM) + #define PH14 (106+STM32F4X_ADC_NUM) + #define PH15 (107+STM32F4X_ADC_NUM) + #define PI0 (108+STM32F4X_ADC_NUM) //1:TIM5_CH4 / SPI2_NSS + #define PI1 (109+STM32F4X_ADC_NUM) //1:SPI2_SCK + #define PI2 (110+STM32F4X_ADC_NUM) //1:TIM8_CH4 /SPI2_MISO + #define PI3 (111+STM32F4X_ADC_NUM) //1:SPI2_MOS + #define PI4 (112+STM32F4X_ADC_NUM) + #define PI5 (113+STM32F4X_ADC_NUM) //1:TIM8_CH1 + #define PI6 (114+STM32F4X_ADC_NUM) //1:TIM8_CH2 + #define PI7 (115+STM32F4X_ADC_NUM) //1:TIM8_CH3 +#endif + + +// This must be a literal +#define NUM_DIGITAL_PINS (STM32F4X_GPIO_NUM) +// This must be a literal with a value less than or equal to MAX_ANALOG_INPUTS +#define NUM_ANALOG_INPUTS (STM32F4X_ADC_NUM) +#define NUM_ANALOG_FIRST 35 + +// Below ADC, DAC and PWM definitions already done in the core +// Could be redefined here if needed +// ADC resolution is 12bits +//#define ADC_RESOLUTION 12 +//#define DACC_RESOLUTION 12 + +// PWM resolution +/* + * BEWARE: + * Changing this value from the default (1000) will affect the PWM output value of analogWrite (to a PWM pin) + * Since the pin is toggled on capture, if you change the frequency of the timer you have to adapt the compare value (analogWrite thinks you did) + */ +//#define PWM_FREQUENCY 20000 +//The bottom values are the default and don't need to be redefined +//#define PWM_RESOLUTION 8 +//#define PWM_MAX_DUTY_CYCLE 255 + +// On-board LED pin number +#define LED_BUILTIN PA7 +#define LED_GREEN LED_BUILTIN + +// Below SPI and I2C definitions already done in the core +// Could be redefined here if differs from the default one +// SPI Definitions +#define PIN_SPI_MOSI PB15 +#define PIN_SPI_MISO PB14 +#define PIN_SPI_SCK PB13 +#define PIN_SPI_SS PB12 + +// I2C Definitions +#if STM32F4X_PIN_NUM >= 176 + #define PIN_WIRE_SDA PH5 + #define PIN_WIRE_SCL PH4 +#else + #define PIN_WIRE_SDA PB7 + #define PIN_WIRE_SCL PB6 +#endif + +// Timer Definitions +//Do not use timer used by PWM pins when possible. See PinMap_PWM in PeripheralPins.c +#define TIMER_TONE TIM10 +#define TIMER_SERVO TIM5 +#define TIMER_SERIAL TIM7 + +// UART Definitions +//#define ENABLE_HWSERIAL1 done automatically by the #define SERIAL_UART_INSTANCE below +#define ENABLE_HWSERIAL3 +#define ENABLE_HWSERIAL6 + +// 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) + +// DEBUG_UART could be redefined to print on another instance than 'Serial' +//#define DEBUG_UART ((USART_TypeDef *) U(S)ARTX) // ex: USART3 +// DEBUG_UART baudrate, default: 9600 if not defined +//#define DEBUG_UART_BAUDRATE x +// DEBUG_UART Tx pin name, default: the first one found in PinMap_UART_TX for DEBUG_UART +//#define DEBUG_PINNAME_TX PX_n // PinName used for TX + +// Default pin used for 'Serial' instance (ex: ST-Link) +// Mandatory for Firmata +#define PIN_SERIAL_RX PA10 +#define PIN_SERIAL_TX PA9 + +// Optional PIN_SERIALn_RX and PIN_SERIALn_TX where 'n' is the U(S)ART number +// Used when user instantiate 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_SERIAL3_RX PD9 +#define PIN_SERIAL3_TX PD8 +#define PIN_SERIAL6_RX PC7 +#define PIN_SERIAL6_TX PC6 +//#define PIN_SERIALLP1_RX x // For LPUART1 RX +//#define PIN_SERIALLP1_TX x // For LPUART1 TX + +#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 Serial3 +#define SERIAL_PORT_HARDWARE_OPEN1 Serial6 +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/PeripheralPins.c new file mode 100644 index 000000000000..a4f8f696ee82 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/PeripheralPins.c @@ -0,0 +1,437 @@ +/* + ******************************************************************************* + * Copyright (c) 2016, 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. + ******************************************************************************* + */ +#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 +const PinMap PinMap_ADC[] = { + {PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3 + {PA_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC2_IN4 + {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 + {PF_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC3_IN9 TH_0 + {PF_4, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC3_IN14 TH_1 + {PF_5, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC3_IN15 TH_2 + {PF_6, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC3_IN4 TH_3 + {PF_7, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC3_IN5 EXP_13 + {PF_8, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC3_IN6 PT100 + {NC, NP, 0} + + // {PA_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0 + // {PA_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC2_IN0 + // {PA_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC3_IN0 + // {PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1 + // {PA_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC2_IN1 + // {PA_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC3_IN1 + // {PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2 + // {PA_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC2_IN2 + // {PA_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC3_IN2 + // {PA_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC2_IN3 + // {PA_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC3_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_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC2_IN5 + // {PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6 + // {PA_6, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC2_IN6 + // {PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7 + // {PA_7, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC2_IN7 + // {PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8 + // {PB_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC2_IN8 + // {PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9 + // {PB_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC2_IN9 + // {PC_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC2_IN10 + // {PC_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC3_IN10 + // {PC_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC2_IN11 + // {PC_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC3_IN11 + // {PC_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC2_IN12 + // {PC_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC3_IN12 + // {PC_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC2_IN13 + // {PC_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC3_IN13 + // {PC_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC2_IN14 + // {PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15 + // {PC_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC2_IN15 + +}; +#endif + +//*** DAC *** + +#ifdef HAL_DAC_MODULE_ENABLED +const PinMap PinMap_DAC[] = { + // {PA_4, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // DAC_OUT1 + // {PA_5, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // DAC_OUT2 - LD2 + {NC, NP, 0} +}; +#endif + +//*** I2C *** + +#ifdef HAL_I2C_MODULE_ENABLED +const PinMap PinMap_I2C_SDA[] = { + // {PB_3, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + // {PB_4, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_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_7, FMPI2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_FMPI2C1)}, + // {PC_9, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, + // {PC_12, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_I2C_MODULE_ENABLED +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)}, + // {PC_6, FMPI2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_FMPI2C1)}, + {NC, NP, 0} +}; +#endif + +//*** PWM *** + +#ifdef HAL_TIM_MODULE_ENABLED +const PinMap PinMap_PWM[] = { + {PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 BED + {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 HEATER0 + {PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 HEATER1 + {PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 HEATER2 + {PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 HEATER3 + {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 FAN0 + {PE_5, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 FAN1 + {PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 FAN2 + {PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 FAN3 + {PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 FAN4 + {PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 FAN5 + + /** + * Unused by specifications on Octopus. + * Uncomment the corresponding line if you want to have HardwarePWM on some pins. + * WARNING: check timers' usage first to avoid conflicts. + * If you don't know what you're doing leave things as they are or you WILL break something (including hardware) + * If you alter this section DO NOT report bugs to Marlin team since they are most likely caused by you. Thank you. + */ + //{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 BLTOUCH is a "servo" + //{PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 BLTOUCH is a "servo" + //{PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 + //{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_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + //{PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + //{PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 + //{PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + //{PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + //{PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + //{PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 + //{PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 + //{PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 + //{PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 + //{PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 + //{PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + //{PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + //{PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N + //{PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + //{PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N + //{PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 + //{PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + //{PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + //{PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 + //{PB_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_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 + //{PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + //{PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + //{PB_14, 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 + //{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 + //{PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 + //{PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + //{PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 + //{PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 + //{PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 + //{PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 + //{PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 + //{PE_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + //{PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 + //{PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + //{PE_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 + //{PE_12, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + //{PE_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 + //{PE_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 + //144 pins mcu, 114 gpio + //{PF_6, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1 + //{PF_7, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 + //{PF_8, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 + //{PF_9, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 + + //176 pins mcu, 140 gpio + //{PH_10, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1 + //{PH_6, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 1, 0)}, // TIM12_CH1 + //{PH_11, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 + //{PI_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 + //{PI_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 + + {NC, NP, 0} +}; +#endif + +//*** SERIAL *** + +#ifdef HAL_UART_MODULE_ENABLED +const PinMap PinMap_UART_TX[] = { + // {PA_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + // {PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PD_5, 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)}, + {PD_8, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + // {PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + // {PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + // {PC_6, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + // {PC_10, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PC_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + // {PC_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_UART_MODULE_ENABLED +const PinMap PinMap_UART_RX[] = { + // {PA_1, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + // {PA_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PD_6, 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)}, + {PD_9, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + // {PB_7, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + // {PC_5, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + // {PC_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + // {PC_11, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PC_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + // {PD_2, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_UART_MODULE_ENABLED +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)}, + // {PA_15, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + // {PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + // {PC_8, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART5)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_UART_MODULE_ENABLED +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)}, + // {PB_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + // {PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + // {PC_9, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART5)}, + {NC, NP, 0} +}; +#endif + +//*** SPI *** + +#ifdef HAL_SPI_MODULE_ENABLED +const PinMap PinMap_SPI_MOSI[] = { + {PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + // {PB_0, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI3)}, + // {PB_2, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI3)}, + // {PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + // {PB_5, 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_1, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI2)}, + // {PC_1, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI3)}, + // {PC_3, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + // {PC_12, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_SPI_MODULE_ENABLED +const PinMap PinMap_SPI_MISO[] = { + {PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + // {PB_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + // {PB_4, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + // {PB_14, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + // {PC_2, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + // {PC_11, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_SPI_MODULE_ENABLED +const PinMap PinMap_SPI_SCLK[] = { + {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + // {PA_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + // {PB_3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + // {PB_3, 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_7, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + // {PC_10, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_SPI_MODULE_ENABLED +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_4, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI2)}, + // {PB_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + // {PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {NC, NP, 0} +}; +#endif + +//*** CAN *** + +#ifdef HAL_CAN_MODULE_ENABLED +const PinMap PinMap_CAN_RD[] = { + // {PA_11, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, + // {PB_5, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, + // {PB_8, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, + // {PB_12, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_CAN_MODULE_ENABLED +const PinMap PinMap_CAN_TD[] = { + // {PA_12, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, + // {PB_6, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, + // {PB_9, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, + // {PB_13, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, + {NC, NP, 0} +}; +#endif + +//*** ETHERNET *** + +//*** No Ethernet *** + +//*** QUADSPI *** + +#ifdef HAL_QSPI_MODULE_ENABLED +const PinMap PinMap_QUADSPI[] = { + // {PA_1, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK1_IO3 + // {PB_2, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_CLK + // {PB_6, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_QSPI)}, // QUADSPI_BK1_NCS + // {PC_9, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK1_IO0 + // {PC_10, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK1_IO1 + // {PC_11, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK2_NCS + {NC, NP, 0} +}; +#endif + +//*** USB *** + +#ifdef HAL_PCD_MODULE_ENABLED +const PinMap PinMap_USB_OTG_FS[] = { + // {PA_8, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_SOF + // {PA_9, USB_OTG_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, 0)}, // USB_OTG_FS_VBUS + // {PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_ID + {PA_11, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DM + {PA_12, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DP + {NC, NP, 0} +}; +#endif + +#ifdef HAL_PCD_MODULE_ENABLED +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 + //{PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_HS_VBUS + {PB_14, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DM + {PB_15, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DP + + /*#error "USB in HS mode isn't supported by the board" + {PA_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D0 + {PB_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D1 + {PB_1, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D2 + {PB_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D7 + {PB_10, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D3 + {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D5 + {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D6 + {PC_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_STP + {PC_2, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_DIR + {PC_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_NXT + */ + {NC, NP, 0} +}; + + +#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 +#endif + + diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/PinNamesVar.h new file mode 100644 index 000000000000..bff3f2134987 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/PinNamesVar.h @@ -0,0 +1,30 @@ +/* SYS_WKUP */ +#ifdef PWR_WAKEUP_PIN1 + SYS_WKUP1 = PA_0, /* SYS_WKUP0 */ +#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_DM = PA_11, + USB_OTG_FS_DP = PA_12, +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/hal_conf_extra.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/hal_conf_extra.h new file mode 100644 index 000000000000..da974b1ba761 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/hal_conf_extra.h @@ -0,0 +1,53 @@ +#pragma once + +#define HAL_MODULE_ENABLED +#define HAL_ADC_MODULE_ENABLED +#define HAL_CRC_MODULE_ENABLED +#define HAL_DMA_MODULE_ENABLED +#define HAL_GPIO_MODULE_ENABLED +#define HAL_I2C_MODULE_ENABLED +#define HAL_PWR_MODULE_ENABLED +#define HAL_RCC_MODULE_ENABLED +//#define HAL_RTC_MODULE_ENABLED Real Time Clock...do we use it? +#define HAL_SPI_MODULE_ENABLED +#define HAL_TIM_MODULE_ENABLED +#define HAL_USART_MODULE_ENABLED +#define HAL_CORTEX_MODULE_ENABLED +//#define HAL_UART_MODULE_ENABLED // by default +//#define HAL_PCD_MODULE_ENABLED // Since STM32 v3.10700.191028 this is automatically added if any type of USB is enabled (as in Arduino IDE) +#define HAL_SD_MODULE_ENABLED + +//#undef HAL_SD_MODULE_ENABLED +#undef HAL_DAC_MODULE_ENABLED +#undef HAL_FLASH_MODULE_ENABLED +#undef HAL_CAN_MODULE_ENABLED +#undef HAL_CAN_LEGACY_MODULE_ENABLED +#undef HAL_CEC_MODULE_ENABLED +#undef HAL_CRYP_MODULE_ENABLED +#undef HAL_DCMI_MODULE_ENABLED +#undef HAL_DMA2D_MODULE_ENABLED +#undef HAL_ETH_MODULE_ENABLED +#undef HAL_NAND_MODULE_ENABLED +#undef HAL_NOR_MODULE_ENABLED +#undef HAL_PCCARD_MODULE_ENABLED +#undef HAL_SRAM_MODULE_ENABLED +#undef HAL_SDRAM_MODULE_ENABLED +#undef HAL_HASH_MODULE_ENABLED +#undef HAL_EXTI_MODULE_ENABLED +#undef HAL_SMBUS_MODULE_ENABLED +#undef HAL_I2S_MODULE_ENABLED +#undef HAL_IWDG_MODULE_ENABLED +#undef HAL_LTDC_MODULE_ENABLED +#undef HAL_DSI_MODULE_ENABLED +#undef HAL_QSPI_MODULE_ENABLED +#undef HAL_RNG_MODULE_ENABLED +#undef HAL_SAI_MODULE_ENABLED +#undef HAL_IRDA_MODULE_ENABLED +#undef HAL_SMARTCARD_MODULE_ENABLED +#undef HAL_WWDG_MODULE_ENABLED +//#undef HAL_HCD_MODULE_ENABLED +#undef HAL_FMPI2C_MODULE_ENABLED +#undef HAL_SPDIFRX_MODULE_ENABLED +#undef HAL_DFSDM_MODULE_ENABLED +#undef HAL_LPTIM_MODULE_ENABLED +#undef HAL_MMC_MODULE_ENABLED diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/ldscript.ld new file mode 100644 index 000000000000..ca21498cd2d9 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/ldscript.ld @@ -0,0 +1,187 @@ +/* +***************************************************************************** +** + +** File : LinkerScript.ld +** +** Abstract : Linker script for STM32F407VETx Device with +** 512KByte FLASH, 128KByte 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 = 0x20020000; /* 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 = 0x8008000, LENGTH = 512K +RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K +} + +/* 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): + { + . = 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 + + /*_siccmram = LOADADDR(.ccmram);*/ + + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss section */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* User_heap_stack section, used to check that there is enough RAM left */ + ._user_heap_stack : + { + . = ALIGN(4); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(4); + } >RAM + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} + + diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/variant.cpp b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/variant.cpp new file mode 100644 index 000000000000..5ed098aab962 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/variant.cpp @@ -0,0 +1,239 @@ +/* + Copyright (c) 2011 Arduino. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include "pins_arduino.h" + +#ifdef __cplusplus +extern "C" { +#endif + +// Pin number +const PinName digitalPin[] = { + PA_0, //D0 + PA_1, //D1 + PA_2, //D2 + PA_3, //D3 + PA_4, //D4 + PA_5, //D5 + PA_6, //D6 + PA_7, //D7 + PA_8, //D8 + PA_9, //D9 + PA_10, //D10 + PA_11, //D11 + PA_12, //D12 + PA_13, //D13 + PA_14, //D14 + PA_15, //D15 + PB_0, //D16 + PB_1, //D17 + PB_2, //D18 + PB_3, //D19 + PB_4, //D20 + PB_5, //D21 + PB_6, //D22 + PB_7, //D23 + PB_8, //D24 + PB_9, //D25 + PB_10, //D26 + PB_11, //D27 + PB_12, //D28 + PB_13, //D29 + PB_14, //D30 + PB_15, //D31 + PC_0, //D32 + PC_1, //D33 + PC_2, //D34 + PC_3, //D35 + PC_4, //D36 + PC_5, //D37 + PC_6, //D38 + PC_7, //D39 + PC_8, //D40 + PC_9, //D41 + PC_10, //D42 + PC_11, //D43 + PC_12, //D44 + PC_13, //D45 + PC_14, //D46 + PC_15, //D47 + PD_0, //D48 + PD_1, //D49 + PD_2, //D50 + PD_3, //D51 + PD_4, //D52 + PD_5, //D53 + PD_6, //D54 + PD_7, //D55 + PD_8, //D56 + PD_9, //D57 + PD_10, //D58 + PD_11, //D59 + PD_12, //D60 + PD_13, //D61 + PD_14, //D62 + PD_15, //D63 + PE_0, //D64 + PE_1, //D65 + PE_2, //D66 + PE_3, //D67 + PE_4, //D68 + PE_5, //D69 + PE_6, //D70 + PE_7, //D71 + PE_8, //D72 + PE_9, //D73 + PE_10, //D74 + PE_11, //D75 + PE_12, //D76 + PE_13, //D77 + PE_14, //D78 + PE_15, //D79 + PF_0, //D80 + PF_1, //D81 + PF_2, //D82 + PF_3, //D83 + PF_4, //D84 + PF_5, //D85 + PF_6, //D86 + PF_7, //D87 + PF_8, //D88 + PF_9, //D89 + PF_10, //D90 + PF_11, //D91 + PF_12, //D92 + PF_13, //D93 + PF_14, //D94 + PF_15, //D95 + PG_0, //D96 + PG_1, //D97 + PG_2, //D98 + PG_3, //D99 + PG_4, //D100 + PG_5, //D101 + PG_6, //D102 + PG_7, //D103 + PG_8, //D104 + PG_9, //D105 + PG_10, //D106 + PG_11, //D107 + PG_12, //D108 + PG_13, //D109 + PG_14, //D110 + PG_15, //D111 + + //Duplicated ADC Pins + PA_3, //D112/A0 + PA_4, //D113/A1 + PC_0, //D114/A2 + PC_1, //D115/A3 + PC_2, //D116/A4 + PC_3, //D117/A5 + PC_4, //D118/A6 + PF_3, //D119/A16 - 1:FSMC_A3 2:ADC3_IN9 + PF_4, //D120/A17 - 1:FSMC_A4 2:ADC3_IN14 + PF_5, //D121/A18 - 1:FSMC_A5 2:ADC3_IN15 + PF_6, //D122/A19 - 1:TIM10_CH1 2:ADC3_IN4 + PF_7, //D123/A20 - 1:TIM11_CH1 2:ADC3_IN5 + PF_8, //D124/A20 - 1:TIM11_CH1 2:ADC3_IN6 +}; + +#ifdef __cplusplus +} +#endif + +// ---------------------------------------------------------------------------- + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @brief System Clock Configuration + * The system Clock is configured as follow : + * System Clock source = PLL (HSE) + * SYSCLK(Hz) = 180000000 + * HCLK(Hz) = 180000000 + * AHB Prescaler = 1 + * APB1 Prescaler = 4 + * APB2 Prescaler = 2 + * HSE Frequency(Hz) = 12000000 + * PLL_M = 6 + * PLL_N = 180 + * PLL_P = 2 + * PLL_Q = 7 + * VDD(V) = 3.3 + * Main regulator output voltage = Scale1 mode + * Flash Latency(WS) = 5 + * @param None + * @retval None + */ +WEAK void SystemClock_Config(void) +{ + RCC_ClkInitTypeDef RCC_ClkInitStruct; + RCC_OscInitTypeDef RCC_OscInitStruct; + RCC_PeriphCLKInitTypeDef PeriphClkInitStruct; + + + /* Enable Power Control clock */ + __HAL_RCC_PWR_CLK_ENABLE(); + +#ifdef HAL_PWR_MODULE_ENABLED + /* The voltage scaling allows optimizing the power consumption when the device is + clocked below the maximum system frequency, to update the voltage scaling value + regarding system frequency refer to product datasheet. */ + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); +#endif + + /* Enable HSE Oscillator and activate PLL with HSE as source */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_ON; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLM = 6; + RCC_OscInitStruct.PLL.PLLN = 180; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; + RCC_OscInitStruct.PLL.PLLQ = 7; + RCC_OscInitStruct.PLL.PLLR = 2; + HAL_RCC_OscConfig(&RCC_OscInitStruct); + + HAL_PWREx_EnableOverDrive(); + + /* 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_PLLRCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; + HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5); + + PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_CLK48; + PeriphClkInitStruct.PLLSAI.PLLSAIM = 6; + PeriphClkInitStruct.PLLSAI.PLLSAIN = 96; + PeriphClkInitStruct.PLLSAI.PLLSAIQ = 2; + PeriphClkInitStruct.PLLSAI.PLLSAIP = RCC_PLLSAIP_DIV4; + PeriphClkInitStruct.PLLSAIDivQ = 1; + PeriphClkInitStruct.Clk48ClockSelection = RCC_CLK48CLKSOURCE_PLLSAIP; + HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct); +} + +#ifdef __cplusplus +} +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/variant.h new file mode 100644 index 000000000000..f512a311e32c --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/variant.h @@ -0,0 +1,216 @@ +/* + Copyright (c) 2011 Arduino. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _VARIANT_ARDUINO_STM32_ +#define _VARIANT_ARDUINO_STM32_ + +#ifdef __cplusplus +extern "C" { +#endif // __cplusplus + +/*---------------------------------------------------------------------------- + * Pins + *----------------------------------------------------------------------------*/ + +#define PA0 0 //D0 +#define PA1 1 //D1 +#define PA2 2 //D2 +#define PA3 3 //D3 +#define PA4 4 //D4 +#define PA5 5 //D5 +#define PA6 6 //D6 +#define PA7 7 //D7 +#define PA8 8 //D8 +#define PA9 9 //D9 +#define PA10 10 //D10 +#define PA11 11 //D11 +#define PA12 12 //D12 +#define PA13 13 //D13 +#define PA14 14 //D14 +#define PA15 15 //D15 +#define PB0 16 //D16 +#define PB1 17 //D17 +#define PB2 18 //D18 +#define PB3 19 //D19 +#define PB4 20 //D20 +#define PB5 21 //D21 +#define PB6 22 //D22 +#define PB7 23 //D23 +#define PB8 24 //D24 +#define PB9 25 //D25 +#define PB10 26 //D26 +#define 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 + +// This must be a literal with the same value as PEND +#define NUM_DIGITAL_PINS 125 +// This must be a literal with a value less than or equal to to MAX_ANALOG_INPUTS +#define NUM_ANALOG_INPUTS 13 +#define NUM_ANALOG_FIRST 112 + +//#define ADC_RESOLUTION 12 + +// PWM resolution +//#define PWM_RESOLUTION 12 +#define PWM_FREQUENCY 1000 // >= 20 Khz => inaudible noise for fans +#define PWM_MAX_DUTY_CYCLE 255 + +// SPI Definitions +#define PIN_SPI_SS PA4 +#define PIN_SPI_MOSI PA7 +#define PIN_SPI_MISO PA6 +#define PIN_SPI_SCK PA5 + +// I2C Definitions +#define PIN_WIRE_SDA PB9 +#define PIN_WIRE_SCL PB8 + +// Timer Definitions +// Do not use timer used by PWM pin. See PinMap_PWM. +#define TIMER_TONE TIM6 +#define TIMER_SERVO TIM5 +#define TIMER_SERIAL TIM7 + +// UART Definitions +//#define SERIAL_UART_INSTANCE 1 // Connected to EXP3 header +/* Enable Serial 3 */ +#define HAVE_HWSERIAL1 +#define HAVE_HWSERIAL3 + +// Default pin used for 'Serial' instance (ex: ST-Link) +// Mandatory for Firmata +#define PIN_SERIAL_RX PA10 +#define PIN_SERIAL_TX PA9 + +/* HAL configuration */ +#define HSE_VALUE 12000000U + +#define FLASH_PAGE_SIZE (4U * 1024U) + +#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_OPEN Serial +#endif + +#endif /* _VARIANT_ARDUINO_STM32_ */ diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/PeripheralPins.c new file mode 100644 index 000000000000..4ea275d4cf7e --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/PeripheralPins.c @@ -0,0 +1,370 @@ +/* + ******************************************************************************* + * 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 STM32F407Z(E-G)Tx.xml + */ +#include +#include + +/* ===== + * Note: Commented lines are alternative possibilities which are not used by default. + * If you change them, you should know what you're doing first. + * ===== + */ + +//*** ADC *** + +#ifdef HAL_ADC_MODULE_ENABLED +const PinMap PinMap_ADC[] = { + {PA_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0 E0_DIR + {PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1 BLTOUCH_2 + {PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2 BLTOUCH_4 + {PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3 E1_EN + {PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4 TF_SS + {PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5 TF_SCLK + {PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6 TF_MISO + {PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7 LED + {PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8 HEATER2 + {PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9 HEATER0 + {PC_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10 Z_EN + {PC_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11 EXP_14 + {PC_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12 Z_DIR + {PC_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13 E0_EN + {PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14 EXP_8 + {PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15 EXP_7 + + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio, 24 ADC + {PF_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC3_IN9 TH_0 + {PF_4, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC3_IN14 TH_1 + {PF_5, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC3_IN15 TH_2 + {PF_6, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC3_IN4 TH_3 + {PF_7, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC3_IN5 EXP_13 + {PF_8, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC3_IN6 EXP_3 + {PF_9, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC3_IN7 EXP_6 + {PF_10, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC3_IN8 EXP_5 + #endif + {NC, NP, 0} +}; +#endif + +//*** DAC *** + +#ifdef HAL_DAC_MODULE_ENABLED +const PinMap PinMap_DAC[] = { + {PA_4, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // DAC_OUT1 + {PA_5, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // DAC_OUT2 + {NC, NP, 0} +}; +#endif + +//*** I2C *** + +#ifdef HAL_I2C_MODULE_ENABLED +const PinMap PinMap_I2C_SDA[] = { + {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)}, + {PB_11, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + {PC_9, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, + #if STM32F4X_PIN_NUM >= 144 // 144 pins mcu, 114 gpio + #if STM32F4X_PIN_NUM >= 176 + {PH_5, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + {PH_8, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, + #else + {PF_0, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + #endif + #endif + {NC, NP, 0} +}; + +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)}, + #if STM32F4X_PIN_NUM >= 144 // 144 pins mcu, 114 gpio + #if STM32F4X_PIN_NUM >= 176 + //{PF_1, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + {PH_4, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + {PH_7, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, + #else + {PF_1, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + #endif + #endif + {NC, NP, 0} +}; +#endif + +//*** PWM *** + +#ifdef HAL_TIM_MODULE_ENABLED +const PinMap PinMap_PWM[] = { + {PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 HEATER0 + {PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 HEATER1 + {PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 HEATER2 + {PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 BED + {PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 0)}, // TIM8_CH3 FAN0 + {PE_5, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 FAN1 + {PE_6, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2 FAN2 + {PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 4, 0)}, // TIM8_CH4 EXTENSION1-4 + {PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 BL-TOUCH-SERVO + + // These pins have been defined for something else on the board but they MIGHT be + // used by the user as PWM pins if they aren't used for their primary purpose. + {PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 ESP8266 connector. Available if 8266 isn't used + {PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 ESP8266 connector. Available if 8266 isn't used + {PB_7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 I2C connector, SDA pin. Available if I2C isn't used. + // TIM5_CH1 is used by the Servo Library + {PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3 BL-TOUCH port. Available if Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN + + /** + * Unused by specifications on SKR-Pro. + * Uncomment the corresponding line if you want to have HardwarePWM on some pins. + * WARNING: check timers' usage first to avoid conflicts. + * If you don't know what you're doing leave things as they are or you WILL break something (including hardware) + * If you alter this section DO NOT report bugs to Marlin team since they are most likely caused by you. Thank you. + */ + //{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 BLTOUCH is a "servo" + //{PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 BLTOUCH is a "servo" + //{PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 + //{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_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + //{PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + //{PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 + //{PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + //{PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + //{PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + //{PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 + //{PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 + //{PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 + //{PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 + //{PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 + //{PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + //{PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + //{PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N + //{PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + //{PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N + //{PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 + //{PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + //{PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + //{PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 + //{PB_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_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 + //{PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + //{PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + //{PB_14, 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 + //{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 + //{PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 + //{PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + //{PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 + //{PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 + //{PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 + //{PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 + //{PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 + //{PE_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + //{PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 + //{PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + //{PE_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 + //{PE_12, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + //{PE_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 + //{PE_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + //{PF_6, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1 + //{PF_7, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 + //{PF_8, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 + //{PF_9, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 + #endif + #if STM32F4X_PIN_NUM >= 176 //176 pins mcu, 140 gpio + {PH_10, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1 + {PH_6, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 1, 0)}, // TIM12_CH1 + //{PH_11, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 + {PI_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 + {PI_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 + #endif + {NC, NP, 0} +}; +#endif + +//*** SERIAL *** + +#ifdef HAL_UART_MODULE_ENABLED +const PinMap PinMap_UART_TX[] = { + {PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PD_8, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PC_6, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + //{PG_14, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + #endif + //{PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + //{PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + //{PD_5, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + //{PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PC_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PA_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PC_10, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PC_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + {NC, NP, 0} +}; + +const PinMap PinMap_UART_RX[] = { + {PA_10, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PD_9, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PC_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + //{PA_1, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PA_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + //{PB_7, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + //{PB_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PC_11, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PC_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PD_2, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + //{PD_6, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + //{PG_9, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + #endif + {NC, NP, 0} +}; + +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)}, + //{PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PD_4, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + //{PD_12, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + //{PG_8, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + //{PG_12, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + #endif + {NC, NP, 0} +}; + +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)}, + //{PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PD_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + //{PD_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + //{PG_13, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + //{PG_15, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + #endif + {NC, NP, 0} +}; +#endif + +//*** SPI *** + +#ifdef HAL_SPI_MODULE_ENABLED +const PinMap PinMap_SPI_MOSI[] = { + {PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, + {PB_15, 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} +}; + +const PinMap PinMap_SPI_MISO[] = { + {PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, + {PB_14, 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} +}; + +const PinMap PinMap_SPI_SCLK[] = { + {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, + {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} +}; + +const PinMap PinMap_SPI_SSEL[] = { + {PA_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, + {PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PA_15, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {NC, NP, 0} +}; +#endif + +//*** CAN *** + +#ifdef HAL_CAN_MODULE_ENABLED +#error "CAN bus isn't available on this board. Driver should be disabled." +#endif + +//*** ETHERNET *** +#ifdef HAL_ETH_MODULE_ENABLED +#error "Ethernet port isn't available on this board. Driver should be disabled." +#endif + +//*** No QUADSPI *** + +//*** USB *** +#ifdef HAL_PCD_MODULE_ENABLED +const PinMap PinMap_USB_OTG_FS[] = { + //{PA_8, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_SOF used by LCD + //{PA_9, USB_OTG_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_FS_VBUS available on wifi port, if empty + //{PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_ID available on UART1_RX if not used + {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} +}; + +const PinMap PinMap_USB_OTG_HS[] = { /* + #ifdef USE_USB_HS_IN_FS + {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_ID + {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_HS_VBUS + {PB_14, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DM + {PB_15, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DP + #else + #error "USB in HS mode isn't supported by the board" + {PA_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D0 + {PB_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D1 + {PB_1, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D2 + {PB_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D7 + {PB_10, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D3 + {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D5 + {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D6 + {PC_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_STP + {PC_2, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_DIR + {PC_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_NXT + #endif // USE_USB_HS_IN_FS + */ + {NC, NP, 0} +}; +#endif diff --git a/buildroot/share/PlatformIO/variants/FLY_F407ZG/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/PinNamesVar.h similarity index 100% rename from buildroot/share/PlatformIO/variants/FLY_F407ZG/PinNamesVar.h rename to buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/PinNamesVar.h diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/hal_conf_extra.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/hal_conf_extra.h new file mode 100644 index 000000000000..e6d558b3e174 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/hal_conf_extra.h @@ -0,0 +1,52 @@ +#pragma once + +#define HAL_MODULE_ENABLED +#define HAL_ADC_MODULE_ENABLED +#define HAL_CRC_MODULE_ENABLED +#define HAL_DMA_MODULE_ENABLED +#define HAL_GPIO_MODULE_ENABLED +#define HAL_I2C_MODULE_ENABLED +#define HAL_PWR_MODULE_ENABLED +#define HAL_RCC_MODULE_ENABLED +//#define HAL_RTC_MODULE_ENABLED Real Time Clock...do we use it? +#define HAL_SPI_MODULE_ENABLED +#define HAL_TIM_MODULE_ENABLED +#define HAL_USART_MODULE_ENABLED +#define HAL_CORTEX_MODULE_ENABLED +//#define HAL_UART_MODULE_ENABLED // by default +//#define HAL_PCD_MODULE_ENABLED // Automatically added if any type of USB is enabled, as in Arduino IDE. (STM32 v3.10700.191028) + +//#define HAL_SD_MODULE_ENABLED +//#define HAL_DAC_MODULE_ENABLED +//#define HAL_FLASH_MODULE_ENABLED +//#define HAL_CAN_MODULE_ENABLED +//#define HAL_CAN_LEGACY_MODULE_ENABLED +//#define HAL_CEC_MODULE_ENABLED +//#define HAL_CRYP_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_IWDG_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_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 diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/ldscript.ld new file mode 100644 index 000000000000..6af296a521ff --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/ldscript.ld @@ -0,0 +1,204 @@ +/* +***************************************************************************** +** + +** File : LinkerScript.ld +** +** Abstract : Linker script for STM32F407ZGTx Device with +** 1024KByte FLASH, 128KByte 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 = 0x20020000; /* 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 = 0x8008000, LENGTH = 1024K +RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K +CCMRAM (rw) : ORIGIN = 0x10000000, 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): + { + . = 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 + + _siccmram = LOADADDR(.ccmram); + + /* CCM-RAM section + * + * IMPORTANT NOTE! + * If initialized variables will be placed in this section, + * the startup code needs to be modified to copy the init-values. + */ + .ccmram : + { + . = ALIGN(4); + _sccmram = .; /* create a global symbol at ccmram start */ + *(.ccmram) + *(.ccmram*) + + . = ALIGN(4); + _eccmram = .; /* create a global symbol at ccmram end */ + } >CCMRAM AT> FLASH + + + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss section */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* User_heap_stack section, used to check that there is enough RAM left */ + ._user_heap_stack : + { + . = ALIGN(4); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(4); + } >RAM + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/variant.cpp b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/variant.cpp new file mode 100644 index 000000000000..1486b21830a1 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/variant.cpp @@ -0,0 +1,260 @@ +/* + ******************************************************************************* + * Copyright (c) 2017, 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. + ******************************************************************************* + */ + +#include "pins_arduino.h" + +#ifdef __cplusplus +extern "C" { +#endif + +// Pin number +// This array allows to wrap Arduino pin number(Dx or x) +// to STM32 PinName (PX_n) +const PinName digitalPin[] = { +#if STM32F4X_PIN_NUM >= 64 //64 pins mcu, 51 gpio + PC_13, //D0 + PC_14, //D1 - OSC32_IN + PC_15, //D2 - OSC32_OUT + PH_0, //D3 - OSC_IN + PH_1, //D4 - OSC_OUT + PB_2, //D5 - BOOT1 + PB_10, //D6 - 1:SPI2_SCK / I2C2_SCL / USART3_TX / TIM2_CH3 + PB_11, //D7 - 1:I2C2_SDA / USART3_RX / TIM2_CH4 + PB_12, //D8 - 1:SPI2_NSS / OTG_HS_ID + PB_13, //D9 - 1:SPI2_SCK 2:OTG_HS_VBUS + PB_14, //D10 - 1:SPI2_MISO / TIM12_CH1 / OTG_HS_DM + PB_15, //D11 - SPI2_MOSI / TIM12_CH2 / OTG_HS_DP + PC_6, //D12 - 1:TIM8_CH1 / SDIO_D6 / USART6_TX / TIM3_CH1 + PC_7, //D13 - 1:TIM8_CH2 / SDIO_D7 / USART6_RX / TIM3_CH2 + PC_8, //D14 - 1:TIM8_CH3 / SDIO_D0 / TIM3_CH3 + PC_9, //D15 - 1:TIM8_CH4 / SDIO_D1 / TIM3_CH4 + PA_8, //D16 - 1:TIM1_CH1 / I2C3_SCL / OTG_FS_SOF + PA_9, //D17 - 1:USART1_TX / TIM1_CH2 2:OTG_FS_VBUS + PA_10, //D18 - 1:USART1_RX / TIM1_CH3 / OTG_FS_ID + PA_11, //D19 - 1:TIM1_CH4 / OTG_FS_DM + PA_12, //D20 - 1:OTG_FS_DP + PA_13, //D21 - 0:JTMS-SWDIO + PA_14, //D22 - 0:JTCK-SWCLK + PA_15, //D23 - 0:JTDI 1:SPI3_NSS / SPI1_NSS + PC_10, //D24 - 1:UART4_TX / SPI3_SCK / SDIO_D2 / USART3_TX + PC_11, //D25 - 1:UART4_RX / SPI3_MISO / SDIO_D3 / USART3_RX + PC_12, //D26 - 1:UART5_TX / SPI3_MOSI / SDIO_CK + PD_2, //D27 - 1:UART5_RX / SDIO_CMD + PB_3, //D28 - 0:JTDO 1:SPI3_SCK / TIM2_CH2 / SPI1_SCK + PB_4, //D29 - 0:NJTRST 1:SPI3_MISO / TIM3_CH1 / SPI1_MISO + PB_5, //D30 - 1:TIM3_CH2 / SPI1_MOSI / SPI3_MOSI + PB_6, //D31 - 1:I2C1_SCL / TIM4_CH1 / USART1_TX + PB_7, //D32 - 1:I2C1_SDA / TIM4_CH2 / USART1_RX + PB_8, //D33 - 1:I2C1_SCL / TIM4_CH3 / SDIO_D4 / TIM10_CH1 + PB_9, //D34 - 1:I2C1_SDA / TIM4_CH4 / SDIO_D5 / TIM11_CH1 / SPI2_NSS + PA_0, //D35/A0 - 1:UART4_TX / TIM5_CH1 2:ADC123_IN0 + PA_1, //D36/A1 - 1:UART4_RX / TIM5_CH2 / TIM2_CH2 2:ADC123_IN1 + PA_2, //D37/A2 - 1:USART2_TX /TIM5_CH3 / TIM9_CH1 / TIM2_CH3 2:ADC123_IN2 + PA_3, //D38/A3 - 1:USART2_RX /TIM5_CH4 / TIM9_CH2 / TIM2_CH4 2:ADC123_IN3 + PA_4, //D39/A4 - NOT FT 1:SPI1_NSS / SPI3_NSS / USART2_CK 2:ADC12_IN4 / DAC_OUT1 + PA_5, //D40/A5 - NOT FT 1:SPI1_SCK 2:ADC12_IN5 / DAC_OUT2 + PA_6, //D41/A6 - 1:SPI1_MISO / TIM13_CH1 / TIM3_CH1 2:ADC12_IN6 + PA_7, //D42/A7 - 1:SPI1_MOSI / TIM14_CH1 / TIM3_CH2 2:ADC12_IN7 + PB_0, //D43/A8 - 1:TIM3_CH3 2:ADC12_IN8 + PB_1, //D44/A9 - 1:TIM3_CH4 2:ADC12_IN9 + PC_0, //D45/A10 - 1: 2:ADC123_IN10 + PC_1, //D46/A11 - 1: 2:ADC123_IN11 + PC_2, //D47/A12 - 1:SPI2_MISO 2:ADC123_IN12 + PC_3, //D48/A13 - 1:SPI2_MOSI 2:ADC123_IN13 + PC_4, //D49/A14 - 1: 2:ADC12_IN14 + PC_5, //D50/A15 - 1: 2:ADC12_IN15 + #if STM32F4X_PIN_NUM >= 144 + PF_3, //D51/A16 - 1:FSMC_A3 2:ADC3_IN9 + PF_4, //D52/A17 - 1:FSMC_A4 2:ADC3_IN14 + PF_5, //D53/A18 - 1:FSMC_A5 2:ADC3_IN15 + PF_6, //D54/A19 - 1:TIM10_CH1 2:ADC3_IN4 + PF_7, //D55/A20 - 1:TIM11_CH1 2:ADC3_IN5 + PF_8, //D56/A21 - 1:TIM13_CH1 2:ADC3_IN6 + PF_9, //D57/A22 - 1;TIM14_CH1 2:ADC3_IN7 + PF_10, //D58/A23 - 2:ADC3_IN8 + #endif +#endif +#if STM32F4X_PIN_NUM >= 100 //100 pins mcu, 82 gpio + PE_2, //D59 - 1:FSMC_A23 + PE_3, //D60 - 1:FSMC_A19 + PE_4, //D61 - 1:FSMC_A20 + PE_5, //D62 - 1:FSMC_A21 + PE_6, //D63 - 1:FSMC_A22 + PE_7, //D64 - 1:FSMC_D4 + PE_8, //D65 - 1:FSMC_D5 + PE_9, //D66 - 1:FSMC_D6 / TIM1_CH1 + PE_10, //D67 - 1:FSMC_D7 + PE_11, //D68 - 1:FSMC_D8 / TIM1_CH2 + PE_12, //D69 - 1:FSMC_D9 + PE_13, //D70 - 1:FSMC_D10 / TIM1_CH3 + PE_14, //D71 - 1:FSMC_D11 / TIM1_CH4 + PE_15, //D72 - 1:FSMC_D12 + PD_8, //D73 - 1:FSMC_D13 / USART3_TX + PD_9, //D74 - 1:FSMC_D14 / USART3_RX + PD_10, //D75 - 1:FSMC_D15 + PD_11, //D76 - 1:FSMC_A16 + PD_12, //D77 - 1:FSMC_A17 / TIM4_CH1 + PD_13, //D78 - 1:FSMC_A18 / TIM4_CH2 + PD_14, //D79 - 1:FSMC_D0 / TIM4_CH3 + PD_15, //D80 - 1:FSMC_D1 / TIM4_CH4 + PD_0, //D81 - 1:FSMC_D2 + PD_1, //D82 - 1:FSMC_D3 + PD_3, //D83 - 1:FSMC_CLK + PD_4, //D84 - 1:FSMC_NOE + PD_5, //D85 - 1:USART2_TX + PD_6, //D86 - 1:USART2_RX + PD_7, //D87 + PE_0, //D88 + PE_1, //D89 +#endif +#if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + PF_0, //D90 - 1:FSMC_A0 / I2C2_SDA + PF_1, //D91 - 1:FSMC_A1 / I2C2_SCL + PF_2, //D92 - 1:FSMC_A2 + PF_11, //D93 + PF_12, //D94 - 1:FSMC_A6 + PF_13, //D95 - 1:FSMC_A7 + PF_14, //D96 - 1:FSMC_A8 + PF_15, //D97 - 1:FSMC_A9 + PG_0, //D98 - 1:FSMC_A10 + PG_1, //D99 - 1:FSMC_A11 + PG_2, //D100 - 1:FSMC_A12 + PG_3, //D101 - 1:FSMC_A13 + PG_4, //D102 - 1:FSMC_A14 + PG_5, //D103 - 1:FSMC_A15 + PG_6, //D104 + PG_7, //D105 + PG_8, //D106 + PG_9, //D107 - 1:USART6_RX + PG_10, //D108 - 1:FSMC_NE3 + PG_11, //D109 + PG_12, //D110 - 1:FSMC_NE4 + PG_13, //D111 - 1:FSMC_A24 + PG_14, //D112 - 1:FSMC_A25 / USART6_TX + PG_15, //D113 +#endif +#if STM32F4X_PIN_NUM >= 176 //176 pins mcu, 140 gpio + PI_8, //D114 + PI_9, //D115 + PI_10, //D116 + PI_11, //D117 + PH_2, //D118 + PH_3, //D119 + PH_4, //D120 - 1:I2C2_SCL + PH_5, //D121 - 1:I2C2_SDA + PH_6, //D122 - 1:TIM12_CH1 + PH_7, //D123 - 1:I2C3_SCL + PH_8, //D124 - 1:I2C3_SDA + PH_9, //D125 - 1:TIM12_CH2 + PH_10, //D126 - 1:TIM5_CH1 + PH_11, //D127 - 1:TIM5_CH2 + PH_12, //D128 - 1:TIM5_CH3 + PH_13, //D129 + PH_14, //D130 + PH_15, //D131 + PI_0, //D132 - 1:TIM5_CH4 / SPI2_NSS + PI_1, //D133 - 1:SPI2_SCK + PI_2, //D134 - 1:TIM8_CH4 /SPI2_MISO + PI_3, //D135 - 1:SPI2_MOS + PI_4, //D136 + PI_5, //D137 - 1:TIM8_CH1 + PI_6, //D138 - 1:TIM8_CH2 + PI_7, //D139 - 1:TIM8_CH3 +#endif +}; + +#ifdef __cplusplus +} +#endif + +// ------------------------ + +#ifdef __cplusplus +extern "C" { +#endif + + /** + * @brief System Clock Configuration + * @param None + * @retval None + */ +WEAK void SystemClock_Config() { + + RCC_OscInitTypeDef RCC_OscInitStruct; + RCC_ClkInitTypeDef RCC_ClkInitStruct; + + /**Configure the main internal regulator output voltage + */ + __HAL_RCC_PWR_CLK_ENABLE(); + + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); + + /**Initializes the CPU, AHB and APB busses clocks + */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_ON; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLM = 8; + RCC_OscInitStruct.PLL.PLLN = 336; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; + RCC_OscInitStruct.PLL.PLLQ = 7; + if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) { + _Error_Handler(__FILE__, __LINE__); + } + + /**Initializes the CPU, AHB and APB busses clocks + */ + RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_SYSCLK + | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2; + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; + + if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5) != HAL_OK) { + _Error_Handler(__FILE__, __LINE__); + } + + /**Configure the Systick interrupt time + */ + HAL_SYSTICK_Config(HAL_RCC_GetHCLKFreq() / 1000); + + /**Configure the Systick + */ + HAL_SYSTICK_CLKSourceConfig(SYSTICK_CLKSOURCE_HCLK); + + /* SysTick_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0); +} + +#ifdef __cplusplus +} +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/variant.h new file mode 100644 index 000000000000..f9091a4f9182 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/variant.h @@ -0,0 +1,322 @@ +/* + ******************************************************************************* + * Copyright (c) 2017, 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. + ******************************************************************************* + */ +#pragma once + +#ifdef __cplusplus +extern "C" { +#endif // __cplusplus + +/*---------------------------------------------------------------------------- + * Pins + *----------------------------------------------------------------------------*/ + +#ifdef STM32F405RX + #define STM32F4X_PIN_NUM 64 //64 pins mcu, 51 gpio + #define STM32F4X_GPIO_NUM 51 + #define STM32F4X_ADC_NUM 16 +#elif defined(STM32F407_5VX) + #define STM32F4X_PIN_NUM 100 //100 pins mcu, 82 gpio + #define STM32F4X_GPIO_NUM 82 + #define STM32F4X_ADC_NUM 16 +#elif defined(STM32F407_5ZX) + #define STM32F4X_PIN_NUM 144 //144 pins mcu, 114 gpio + #define STM32F4X_GPIO_NUM 114 + #define STM32F4X_ADC_NUM 24 +#elif defined(STM32F407IX) + #define STM32F4X_PIN_NUM 176 //176 pins mcu, 140 gpio + #define STM32F4X_GPIO_NUM 140 + #define STM32F4X_ADC_NUM 24 +#else + #error "no match MCU defined" +#endif + +#if STM32F4X_PIN_NUM >= 64 //64 pins mcu, 51 gpio + #define PC13 0 + #define PC14 1 //OSC32_IN + #define PC15 2 //OSC32_OUT + #define PH0 3 //OSC_IN + #define PH1 4 //OSC_OUT + #define PB2 5 //BOOT1 + #define PB10 6 //1:SPI2_SCK / I2C2_SCL / USART3_TX / TIM2_CH3 + #define PB11 7 //1:I2C2_SDA / USART3_RX / TIM2_CH4 + #define PB12 8 //1:SPI2_NSS / OTG_HS_ID + #define PB13 9 //1:SPI2_SCK 2:OTG_HS_VBUS + #define PB14 10 //1:SPI2_MISO / TIM12_CH1 / OTG_HS_DM + #define PB15 11 //SPI2_MOSI / TIM12_CH2 / OTG_HS_DP + #define PC6 12 //1:TIM8_CH1 / SDIO_D6 / USART6_TX / TIM3_CH1 + #define PC7 13 //1:TIM8_CH2 / SDIO_D7 / USART6_RX / TIM3_CH2 + #define PC8 14 //1:TIM8_CH3 / SDIO_D0 / TIM3_CH3 + #define PC9 15 //1:TIM8_CH4 / SDIO_D1 / TIM3_CH4 + #define PA8 16 //1:TIM1_CH1 / I2C3_SCL / OTG_FS_SOF + #define PA9 17 //1:USART1_TX / TIM1_CH2 2:OTG_FS_VBUS + #define PA10 18 //1:USART1_RX / TIM1_CH3 / OTG_FS_ID + #define PA11 19 //1:TIM1_CH4 / OTG_FS_DM + #define PA12 20 //1:OTG_FS_DP + #define PA13 21 //0:JTMS-SWDIO + #define PA14 22 //0:JTCK-SWCLK + #define PA15 23 //0:JTDI 1:SPI3_NSS / SPI1_NSS + #define PC10 24 //1:UART4_TX / SPI3_SCK / SDIO_D2 / USART3_TX + #define PC11 25 //1:UART4_RX / SPI3_MISO / SDIO_D3 / USART3_RX + #define PC12 26 //1:UART5_TX / SPI3_MOSI / SDIO_CK + #define PD2 27 //1:UART5_RX / SDIO_CMD + #define PB3 28 //0:JTDO 1:SPI3_SCK / TIM2_CH2 / SPI1_SCK + #define PB4 29 //0:NJTRST 1:SPI3_MISO / TIM3_CH1 / SPI1_MISO + #define PB5 30 //1:TIM3_CH2 / SPI1_MOSI / SPI3_MOSI + #define PB6 31 //1:I2C1_SCL / TIM4_CH1 / USART1_TX + #define PB7 32 //1:I2C1_SDA / TIM4_CH2 / USART1_RX + #define PB8 33 //1:I2C1_SCL / TIM4_CH3 / SDIO_D4 / TIM10_CH1 + #define PB9 34 //1:I2C1_SDA / TIM4_CH4 / SDIO_D5 / TIM11_CH1 / SPI2_NSS + #define PA0 35 //1:UART4_TX / TIM5_CH1 2:ADC123_IN0 + #define PA1 36 //1:UART4_RX / TIM5_CH2 / TIM2_CH2 2:ADC123_IN1 + #define PA2 37 //1:USART2_TX /TIM5_CH3 / TIM9_CH1 / TIM2_CH3 2:ADC123_IN2 + #define PA3 38 //1:USART2_RX /TIM5_CH4 / TIM9_CH2 / TIM2_CH4 2:ADC123_IN3 + #define PA4 39 //NOT FT 1:SPI1_NSS / SPI3_NSS / USART2_CK 2:ADC12_IN4 / DAC_OUT1 + #define PA5 40 //NOT FT 1:SPI1_SCK 2:ADC12_IN5 / DAC_OUT2 + #define PA6 41 //1:SPI1_MISO / TIM13_CH1 / TIM3_CH1 2:ADC12_IN6 + #define PA7 42 //1:SPI1_MOSI / TIM14_CH1 / TIM3_CH2 2:ADC12_IN7 + #define PB0 43 //1:TIM3_CH3 2:ADC12_IN8 + #define PB1 44 //1:TIM3_CH4 2:ADC12_IN9 + #define PC0 45 //1: 2:ADC123_IN10 + #define PC1 46 //1: 2:ADC123_IN11 + #define PC2 47 //1:SPI2_MISO 2:ADC123_IN12 + #define PC3 48 //1:SPI2_MOSI 2:ADC123_IN13 + #define PC4 49 //1: 2:ADC12_IN14 + #define PC5 50 //1: 2:ADC12_IN15 + #if STM32F4X_PIN_NUM >= 144 + #define PF3 51 //1:FSMC_A3 2:ADC3_IN9 + #define PF4 52 //1:FSMC_A4 2:ADC3_IN14 + #define PF5 53 //1:FSMC_A5 2:ADC3_IN15 + #define PF6 54 //1:TIM10_CH1 2:ADC3_IN4 + #define PF7 55 //1:TIM11_CH1 2:ADC3_IN5 + #define PF8 56 //1:TIM13_CH1 2:ADC3_IN6 + #define PF9 57 //1;TIM14_CH1 2:ADC3_IN7 + #define PF10 58 //2:ADC3_IN8 + #endif +#endif +#if STM32F4X_PIN_NUM >= 100 //100 pins mcu, 82 gpio + #define PE2 (35+STM32F4X_ADC_NUM) //1:FSMC_A23 + #define PE3 (36+STM32F4X_ADC_NUM) //1:FSMC_A19 + #define PE4 (37+STM32F4X_ADC_NUM) //1:FSMC_A20 + #define PE5 (38+STM32F4X_ADC_NUM) //1:FSMC_A21 + #define PE6 (39+STM32F4X_ADC_NUM) //1:FSMC_A22 + #define PE7 (40+STM32F4X_ADC_NUM) //1:FSMC_D4 + #define PE8 (41+STM32F4X_ADC_NUM) //1:FSMC_D5 + #define PE9 (42+STM32F4X_ADC_NUM) //1:FSMC_D6 / TIM1_CH1 + #define PE10 (43+STM32F4X_ADC_NUM) //1:FSMC_D7 + #define PE11 (44+STM32F4X_ADC_NUM) //1:FSMC_D8 / TIM1_CH2 + #define PE12 (45+STM32F4X_ADC_NUM) //1:FSMC_D9 + #define PE13 (46+STM32F4X_ADC_NUM) //1:FSMC_D10 / TIM1_CH3 + #define PE14 (47+STM32F4X_ADC_NUM) //1:FSMC_D11 / TIM1_CH4 + #define PE15 (48+STM32F4X_ADC_NUM) //1:FSMC_D12 + #define PD8 (49+STM32F4X_ADC_NUM) //1:FSMC_D13 / USART3_TX + #define PD9 (50+STM32F4X_ADC_NUM) //1:FSMC_D14 / USART3_RX + #define PD10 (51+STM32F4X_ADC_NUM) //1:FSMC_D15 + #define PD11 (52+STM32F4X_ADC_NUM) //1:FSMC_A16 + #define PD12 (53+STM32F4X_ADC_NUM) //1:FSMC_A17 / TIM4_CH1 + #define PD13 (54+STM32F4X_ADC_NUM) //1:FSMC_A18 / TIM4_CH2 + #define PD14 (55+STM32F4X_ADC_NUM) //1:FSMC_D0 / TIM4_CH3 + #define PD15 (56+STM32F4X_ADC_NUM) //1:FSMC_D1 / TIM4_CH4 + #define PD0 (57+STM32F4X_ADC_NUM) //1:FSMC_D2 + #define PD1 (58+STM32F4X_ADC_NUM) //1:FSMC_D3 + #define PD3 (59+STM32F4X_ADC_NUM) //1:FSMC_CLK + #define PD4 (60+STM32F4X_ADC_NUM) //1:FSMC_NOE + #define PD5 (61+STM32F4X_ADC_NUM) //1:USART2_TX + #define PD6 (62+STM32F4X_ADC_NUM) //1:USART2_RX + #define PD7 (63+STM32F4X_ADC_NUM) + #define PE0 (64+STM32F4X_ADC_NUM) + #define PE1 (65+STM32F4X_ADC_NUM) +#endif +#if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + #define PF0 (66+STM32F4X_ADC_NUM) //1:FSMC_A0 / I2C2_SDA + #define PF1 (67+STM32F4X_ADC_NUM) //1:FSMC_A1 / I2C2_SCL + #define PF2 (68+STM32F4X_ADC_NUM) //1:FSMC_A2 + #define PF11 (69+STM32F4X_ADC_NUM) + #define PF12 (70+STM32F4X_ADC_NUM) //1:FSMC_A6 + #define PF13 (71+STM32F4X_ADC_NUM) //1:FSMC_A7 + #define PF14 (72+STM32F4X_ADC_NUM) //1:FSMC_A8 + #define PF15 (73+STM32F4X_ADC_NUM) //1:FSMC_A9 + #define PG0 (74+STM32F4X_ADC_NUM) //1:FSMC_A10 + #define PG1 (75+STM32F4X_ADC_NUM) //1:FSMC_A11 + #define PG2 (76+STM32F4X_ADC_NUM) //1:FSMC_A12 + #define PG3 (77+STM32F4X_ADC_NUM) //1:FSMC_A13 + #define PG4 (78+STM32F4X_ADC_NUM) //1:FSMC_A14 + #define PG5 (79+STM32F4X_ADC_NUM) //1:FSMC_A15 + #define PG6 (80+STM32F4X_ADC_NUM) + #define PG7 (81+STM32F4X_ADC_NUM) + #define PG8 (82+STM32F4X_ADC_NUM) + #define PG9 (83+STM32F4X_ADC_NUM) //1:USART6_RX + #define PG10 (84+STM32F4X_ADC_NUM) //1:FSMC_NE3 + #define PG11 (85+STM32F4X_ADC_NUM) + #define PG12 (86+STM32F4X_ADC_NUM) //1:FSMC_NE4 + #define PG13 (87+STM32F4X_ADC_NUM) //1:FSMC_A24 + #define PG14 (88+STM32F4X_ADC_NUM) //1:FSMC_A25 / USART6_TX + #define PG15 (89+STM32F4X_ADC_NUM) +#endif +#if STM32F4X_PIN_NUM >= 176 //176 pins mcu, 140 gpio + #define PI8 (90+STM32F4X_ADC_NUM) + #define PI9 (91+STM32F4X_ADC_NUM) + #define PI10 (92+STM32F4X_ADC_NUM) + #define PI11 (93+STM32F4X_ADC_NUM) + #define PH2 (94+STM32F4X_ADC_NUM) + #define PH3 (95+STM32F4X_ADC_NUM) + #define PH4 (96+STM32F4X_ADC_NUM) //1:I2C2_SCL + #define PH5 (97+STM32F4X_ADC_NUM) //1:I2C2_SDA + #define PH6 (98+STM32F4X_ADC_NUM) //1:TIM12_CH1 + #define PH7 (99+STM32F4X_ADC_NUM) //1:I2C3_SCL + #define PH8 (100+STM32F4X_ADC_NUM) //1:I2C3_SDA + #define PH9 (101+STM32F4X_ADC_NUM) //1:TIM12_CH2 + #define PH10 (102+STM32F4X_ADC_NUM) //1:TIM5_CH1 + #define PH11 (103+STM32F4X_ADC_NUM) //1:TIM5_CH2 + #define PH12 (104+STM32F4X_ADC_NUM) //1:TIM5_CH3 + #define PH13 (105+STM32F4X_ADC_NUM) + #define PH14 (106+STM32F4X_ADC_NUM) + #define PH15 (107+STM32F4X_ADC_NUM) + #define PI0 (108+STM32F4X_ADC_NUM) //1:TIM5_CH4 / SPI2_NSS + #define PI1 (109+STM32F4X_ADC_NUM) //1:SPI2_SCK + #define PI2 (110+STM32F4X_ADC_NUM) //1:TIM8_CH4 /SPI2_MISO + #define PI3 (111+STM32F4X_ADC_NUM) //1:SPI2_MOS + #define PI4 (112+STM32F4X_ADC_NUM) + #define PI5 (113+STM32F4X_ADC_NUM) //1:TIM8_CH1 + #define PI6 (114+STM32F4X_ADC_NUM) //1:TIM8_CH2 + #define PI7 (115+STM32F4X_ADC_NUM) //1:TIM8_CH3 +#endif + + +// This must be a literal +#define NUM_DIGITAL_PINS (STM32F4X_GPIO_NUM) +// This must be a literal with a value less than or equal to MAX_ANALOG_INPUTS +#define NUM_ANALOG_INPUTS (STM32F4X_ADC_NUM) +#define NUM_ANALOG_FIRST 35 + +// Below ADC, DAC and PWM definitions already done in the core +// Could be redefined here if needed +// ADC resolution is 12bits +//#define ADC_RESOLUTION 12 +//#define DACC_RESOLUTION 12 + +// PWM resolution +/* + * BEWARE: + * Changing this value from the default (1000) will affect the PWM output value of analogWrite (to a PWM pin) + * Since the pin is toggled on capture, if you change the frequency of the timer you have to adapt the compare value (analogWrite thinks you did) + */ +//#define PWM_FREQUENCY 20000 +//The bottom values are the default and don't need to be redefined +//#define PWM_RESOLUTION 8 +//#define PWM_MAX_DUTY_CYCLE 255 + +// On-board LED pin number +#define LED_BUILTIN PA7 +#define LED_GREEN LED_BUILTIN + +// Below SPI and I2C definitions already done in the core +// Could be redefined here if differs from the default one +// SPI Definitions +#define PIN_SPI_MOSI PB15 +#define PIN_SPI_MISO PB14 +#define PIN_SPI_SCK PB13 +#define PIN_SPI_SS PB12 + +// I2C Definitions +#if STM32F4X_PIN_NUM >= 176 + #define PIN_WIRE_SDA PH5 + #define PIN_WIRE_SCL PH4 +#else + #define PIN_WIRE_SDA PB7 + #define PIN_WIRE_SCL PB6 +#endif + +// Timer Definitions +//Do not use timer used by PWM pins when possible. See PinMap_PWM in PeripheralPins.c +#define TIMER_TONE TIM2 +#define TIMER_SERVO TIM5 // Only 1 Servo PIN on SKR-PRO, so use the same timer as defined in PeripheralPins +#define TIMER_SERIAL TIM7 + +// UART Definitions +//#define ENABLE_HWSERIAL1 done automatically by the #define SERIAL_UART_INSTANCE below +#define ENABLE_HWSERIAL3 +#define ENABLE_HWSERIAL6 + +// 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) + +// DEBUG_UART could be redefined to print on another instance than 'Serial' +//#define DEBUG_UART ((USART_TypeDef *) U(S)ARTX) // ex: USART3 +// DEBUG_UART baudrate, default: 9600 if not defined +//#define DEBUG_UART_BAUDRATE x +// DEBUG_UART Tx pin name, default: the first one found in PinMap_UART_TX for DEBUG_UART +//#define DEBUG_PINNAME_TX PX_n // PinName used for TX + +// Default pin used for 'Serial' instance (ex: ST-Link) +// Mandatory for Firmata +#define PIN_SERIAL_RX PA10 +#define PIN_SERIAL_TX PA9 + +// Optional PIN_SERIALn_RX and PIN_SERIALn_TX where 'n' is the U(S)ART number +// Used when user instantiate 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_SERIAL3_RX PD9 +#define PIN_SERIAL3_TX PD8 +#define PIN_SERIAL6_RX PC7 +#define PIN_SERIAL6_TX PC6 +//#define PIN_SERIALLP1_RX x // For LPUART1 RX +//#define PIN_SERIALLP1_TX x // For LPUART1 TX + +#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 Serial3 +#define SERIAL_PORT_HARDWARE_OPEN1 Serial6 +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BTT_SKR_SE_BX/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_BTT_SKR_SE_BX/PeripheralPins.c new file mode 100644 index 000000000000..c9194cc29349 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BTT_SKR_SE_BX/PeripheralPins.c @@ -0,0 +1,473 @@ +/* + ******************************************************************************* + * 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 STM32H743ZITx.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_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_INP15 + {PH_4, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC3_INP15 + {PH_5, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 16, 0)}, // ADC3_INP16 + {PA_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 16, 0)}, // ADC1_INP16 + {PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 17, 0)}, // ADC1_INP17 + {PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_INP14 + {PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 18, 0)}, // ADC1_INP18 + {PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 19, 0)}, // ADC1_INP19 + {PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_INP3 + {PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_INP7 + {PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_INP9 + {PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_INP5 + {PC_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC3_INP10 + {PC_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_INN10 + {PC_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC3_INN0 + {PC_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC3_INP1 + {PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_INP4 + {PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_INP8 + {PF_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC3_INP5 + {PF_4, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC3_INP9 + {PF_5, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC3_INP4 + {PF_6, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC3_INP8 + {PF_7, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC3_INP3 + {PF_8, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC3_INP7 + {PF_9, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC3_INP2 + {PF_10, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC3_INP6 + {PF_11, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_INP2 + {PF_12, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_INP6 + {PF_13, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC2_INP2 + {PF_14, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC2_INP6 + {NC, NP, 0} +}; +#endif + +//*** DAC *** + +#ifdef HAL_DAC_MODULE_ENABLED +WEAK const PinMap PinMap_DAC[] = { + {PA_4, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // DAC1_OUT1 + {PA_5, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // DAC1_OUT2 + {NC, NP, 0} +}; +#endif + +//*** I2C *** + +#ifdef HAL_I2C_MODULE_ENABLED +WEAK const PinMap PinMap_I2C_SDA[] = { + //{PB_7, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, // LD2 LED_BLUE (ZI) + {PB_9, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, + {PB_7, I2C4, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C4)}, // LD2 LED_BLUE (ZI) + //{PB_9, I2C4, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C4)}, + {PB_11, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + //{PC_9, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, + {PD_13, I2C4, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C4)}, + {PF_0, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + {PF_15, I2C4, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C4)}, + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_I2C_SCL[] = { + //{PA_8, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, // USB SOF + //{PB_6, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, // QSPI_CS + {PB_8, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, + {PB_6, I2C4, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C4)}, // QSPI_CS + //{PB_8, I2C4, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C4)}, + {PB_10, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + {PD_12, I2C4, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C4)}, + {PF_1, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + {PF_14, I2C4, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C4)}, + {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 - ETH RMII Ref Clk + //{PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 - ETH RMII Ref Clk + //{PA_1, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_TIM15, 1, 1)}, // TIM15_CH1N - ETH RMII Ref Clk + //{PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 - ETH RMII MDIO + {PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3 - ETH RMII MDIO + //{PA_2, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_TIM15, 1, 0)}, // TIM15_CH1 - ETH RMII MDIO + //{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, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_TIM15, 2, 0)}, // TIM15_CH2 + //{PA_5, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + {PA_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + //{PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + {PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 + //{PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N - Used by ETH when JP6(ZI)/SB31(ZI2) ON + //{PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 - Used by ETH when JP6(ZI)/SB31(ZI2) ON + //{PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N - Used by ETH when JP6(ZI)/SB31(ZI2) ON + {PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 - Used by ETH when JP6(ZI)/SB31(ZI2) ON + //{PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 - USB SOF + //{PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 - USB VBUS + //{PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 - USB ID + //{PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 - USB DM + //{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 - LD1 LED_GREEN + //{PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 - LD1 LED_GREEN + //{PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N - LD1 LED_GREEN + //{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_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N + //{PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 - SWO + {PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + {PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + //{PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 + {PB_6, TIM16, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM16, 1, 1)}, // TIM16_CH1N + //{PB_7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 - LD2 LED_BLUE (ZI) + {PB_7, TIM17, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM17, 1, 1)}, // TIM17_CH1N - LD2 LED_BLUE (ZI) + {PB_8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 + //{PB_8, TIM16, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM16, 1, 0)}, // TIM16_CH1 + //{PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 + {PB_9, TIM17, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM17, 1, 0)}, // TIM17_CH1 + //{PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 + //{PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 + //{PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N - Used by ETH when JP7(ZI)/JP6(ZI2) ON + {PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N - LD3 LED_RED + //{PB_14, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N - LD3 LED_RED + //{PB_14, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM12, 1, 0)}, // TIM12_CH1 - LD3 LED_RED + //{PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + {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_AF2_TIM12, 2, 0)}, // TIM12_CH2 + //{PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + {PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 + {PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + //{PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 + //{PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 + {PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 0)}, // TIM8_CH3 + {PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 + //{PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 4, 0)}, // TIM8_CH4 + {PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 + {PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 + {PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 + {PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 + {PE_4, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_TIM15, 1, 1)}, // TIM15_CH1N + {PE_5, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_TIM15, 1, 0)}, // TIM15_CH1 + {PE_6, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_TIM15, 2, 0)}, // TIM15_CH2 + {PE_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + {PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 + {PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + {PE_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 + {PE_12, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + {PE_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 + {PE_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 + {PF_6, TIM16, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM16, 1, 0)}, // TIM16_CH1 + {PF_7, TIM17, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM17, 1, 0)}, // TIM17_CH1 + {PF_8, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 + //{PF_8, TIM16, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM16, 1, 1)}, // TIM16_CH1N + {PF_9, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 + //{PF_9, TIM17, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM17, 1, 1)}, // TIM17_CH1N + {NC, NP, 0} +}; +#endif + +//*** SERIAL *** + +#ifdef HAL_UART_MODULE_ENABLED +WEAK const PinMap PinMap_UART_TX[] = { + {PA_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, // ETH RMII MDIO + //{PA_9, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_LPUART)}, // USB VBUS + {PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, // USB VBUS + //{PA_12, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_UART4)}, // USB DP + //{PA_15, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_UART7)}, + //{PB_4, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_UART7)}, + //{PB_6, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_LPUART)}, + //{PB_6, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_UART5)}, + //{PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + //{PB_9, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PB_13, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_UART5)}, // Used by ETH when JP7(ZI)/JP6(ZI2) ON + //{PB_14, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART1)}, // LD3 LED_RED + //{PC_6, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART6)}, + //{PC_10, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PC_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PC_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + //{PD_1, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PD_5, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + //{PD_8, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, // STLink TX + //{PE_1, UART8, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART8)}, //LD2 LED_YELLOW (ZI2) + //{PE_8, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART7)}, + //{PF_7, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART7)}, + //{PG_14, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART6)}, + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_UART_RX[] = { + {PA_1, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, // ETH RMII Ref Clk + //{PA_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + //{PA_8, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_UART7)}, // USB SOF + //{PA_10, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_LPUART)}, // USB ID + {PA_10, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, // USB ID + //{PA_11, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_UART4)}, // USB DM + //{PB_3, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_UART7)}, // SWO + //{PB_5, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_UART5)}, + //{PB_7, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_LPUART)}, // LD2 LED_BLUE (ZI) + //{PB_7, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, // LD2 LED_BLUE (ZI) + //{PB_8, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PB_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PB_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_UART5)}, + //{PB_15, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART1)}, + //{PC_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART6)}, + //{PC_11, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PC_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PD_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PD_2, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + //{PD_6, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + //{PD_9, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, // STLink RX + //{PE_0, UART8, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART8)}, + //{PE_7, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART7)}, + //{PF_6, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART7)}, + //{PG_9, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_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)}, // ETH RMII Ref Clk + //{PA_12, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_LPUART)}, // USB DP + //{PA_12, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, // USB DP + {PA_15, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PB_14, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, // LD3 LED_RED + //{PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, // LD3 LED_RED + {PC_8, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + {PD_4, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PD_12, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PD_15, UART8, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART8)}, + {PE_9, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART7)}, + {PF_8, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART7)}, + {PG_8, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART6)}, + {PG_12, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART6)}, + {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, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_LPUART)}, // USB DM + //{PA_11, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, // USB DM + //{PB_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, // LD1 LED_GREEN + //{PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, // Used by ETH when JP7(ZI)/JP6(ZI2) ON + {PB_15, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PC_9, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + {PD_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PD_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PD_14, UART8, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART8)}, + {PE_10, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART7)}, + {PF_9, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART7)}, + //{PG_13, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART6)}, + {PG_15, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART6)}, + {NC, NP, 0} +}; +#endif + +//*** SPI *** + +#ifdef HAL_SPI_MODULE_ENABLED +WEAK const PinMap PinMap_SPI_MOSI[] = { + {PC_12, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + //{PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, // Used by ETH when JP6(ZI)/SB31(ZI2) ON + //{PA_7, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_SPI6)}, // Used by ETH when JP6(ZI)/SB31(ZI2) ON + //{PB_2, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI3)}, + //{PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + //{PB_5, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI3)}, + //{PB_5, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_SPI6)}, + //{PB_15, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + //{PC_1, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, // ETH RMII MDC + //{PC_3, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + //{PD_6, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI3)}, + //{PD_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + //{PE_6, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + //{PE_14, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + //{PF_9, SPI5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI5)}, + //{PF_11, SPI5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI5)}, + //{PG_14, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI6)}, + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_SPI_MISO[] = { + {PC_11, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + //{PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + //{PA_6, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_SPI6)}, + //{PB_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + //{PB_4, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + //{PB_4, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_SPI6)}, + //{PB_14, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, // LD3 LED_RED + //{PC_2, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + //{PE_5, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + //{PE_13, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + //{PF_8, SPI5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI5)}, + //{PG_9, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + //{PG_12, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI6)}, + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_SPI_SCLK[] = { + {PC_10, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + //{PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + //{PA_5, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_SPI6)}, + //{PA_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, // USB VBUS + //{PA_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, // USB DP + //{PB_3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, // SWO + //{PB_3, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, // SWO + //{PB_3, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_SPI6)}, // SWO + //{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)}, // Used by ETH when JP7(ZI)/JP6(ZI2) ON + //{PD_3, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + //{PE_2, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + //{PE_12, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + //{PF_7, SPI5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI5)}, + //{PG_11, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, // ETH RMII TX Enable + //{PG_13, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI6)}, // ETH RXII TXD0 + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_SPI_SSEL[] = { + {PA_15, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + //{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_4, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_SPI6)}, + //{PA_11, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, // USB DM + //{PA_15, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + //{PA_15, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI6)}, + //{PB_4, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI2)}, + //{PB_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + //{PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + //{PE_4, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + //{PE_11, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + //{PF_6, SPI5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI5)}, + //{PG_8, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI6)}, + //{PG_10, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + {NC, NP, 0} +}; +#endif + +//*** CAN *** + +#ifdef HAL_CAN_MODULE_ENABLED +WEAK const PinMap PinMap_CAN_RD[] = { + //{PA_11, CANFD1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN1)}, // USB DM + {PB_5, CANFD2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN2)}, + {PB_8, CANFD1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN1)}, + {PB_12, CANFD2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN2)}, + {PD_0, CANFD1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN1)}, + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_CAN_TD[] = { + //{PA_12, CANFD1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN1)}, // USB DP + {PB_6, CANFD2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN2)}, // QSPI_CS + {PB_7, CANFD2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN2)}, // LD2 LED_BLUE (ZI) + {PB_9, CANFD1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN1)}, + //{PB_13, CANFD2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN2)}, // Used by ETH when JP7(ZI)/JP6(ZI2) ON + {PD_1, CANFD1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN1)}, + {NC, NP, 0} +}; +#endif + +//*** ETHERNET *** + +#ifdef HAL_ETH_MODULE_ENABLED +WEAK const PinMap PinMap_Ethernet[] = { + //{PA_0, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_CRS + {PA_1, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_REF_CLK|ETH_RX_CLK + {PA_2, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_MDIO + //{PA_3, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_COL + {PA_7, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_CRS_DV|ETH_RX_DV + //{PB_0, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD2 + //{PB_1, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD3 + //{PB_5, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_PPS_OUT + //{PB_8, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD3 + //{PB_10, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RX_ER + //{PB_11, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TX_EN + //{PB_12, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD0 + {PB_13, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD1 + {PC_1, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_MDC + //{PC_2, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD2 + //{PC_3, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TX_CLK + {PC_4, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD0 + {PC_5, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD1 + //{PE_2, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD3 + //{PG_8, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_PPS_OUT + {PG_11, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TX_EN + //{PG_12, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD1 + {PG_13, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD0 + //{PG_14, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD1 + {NC, NP, 0} +}; +#endif + +//*** USB *** + +#ifdef HAL_PCD_MODULE_ENABLED +WEAK const PinMap PinMap_USB_OTG_FS[] = { + //{PA_8, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG1_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_OTG1_FS)}, // USB_OTG_FS_ID + {PA_11, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG1_FS)}, // USB_OTG_FS_DM + {PA_12, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG1_FS)}, // USB_OTG_FS_DP + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_USB_OTG_HS[] = { +#ifdef USE_USB_HS_IN_FS + //{PA_4, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG2_FS)}, // USB_OTG_HS_SOF + //{PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF12_OTG2_FS)}, // USB_OTG_HS_ID + //{PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_HS_VBUS - Used by ETH when JP7(ZI)/JP6(ZI2) ON + {PB_14, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG2_FS)}, // USB_OTG_HS_DM + {PB_15, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG2_FS)}, // USB_OTG_HS_DP +#else + {PA_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG2_HS)}, // USB_OTG_HS_ULPI_D0 + {PA_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG2_HS)}, // USB_OTG_HS_ULPI_CK + {PB_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG2_HS)}, // USB_OTG_HS_ULPI_D1 + {PB_1, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG2_HS)}, // USB_OTG_HS_ULPI_D2 + {PB_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG2_HS)}, // USB_OTG_HS_ULPI_D7 + {PB_10, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG2_HS)}, // USB_OTG_HS_ULPI_D3 + {PB_11, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG2_HS)}, // USB_OTG_HS_ULPI_D4 + {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG2_HS)}, // USB_OTG_HS_ULPI_D5 + {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG2_HS)}, // USB_OTG_HS_ULPI_D6 - Used by ETH when JP7(ZI)/JP6(ZI2) ON + {PC_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG2_HS)}, // USB_OTG_HS_ULPI_STP + {PC_2, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG2_HS)}, // USB_OTG_HS_ULPI_DIR + {PC_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG2_HS)}, // USB_OTG_HS_ULPI_NXT +#endif /* USE_USB_HS_IN_FS */ + {NC, NP, 0} +}; +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BTT_SKR_SE_BX/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_BTT_SKR_SE_BX/PinNamesVar.h new file mode 100644 index 000000000000..118bc92f7ea1 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BTT_SKR_SE_BX/PinNamesVar.h @@ -0,0 +1,50 @@ +/* SYS_WKUP */ +#ifdef PWR_WAKEUP_PIN1 +SYS_WKUP1 = PA_0, /* SYS_WKUP0 */ +#endif +#ifdef PWR_WAKEUP_PIN2 +SYS_WKUP2 = PA_2, /* SYS_WKUP1 */ +#endif +#ifdef PWR_WAKEUP_PIN3 +SYS_WKUP3 = PC_13, /* SYS_WKUP2 */ +#endif +#ifdef PWR_WAKEUP_PIN4 +SYS_WKUP4 = PI_8, /* SYS_WKUP3 - Manually added */ +#endif +#ifdef PWR_WAKEUP_PIN5 +SYS_WKUP5 = PI_11, /* SYS_WKUP4 - Manually added */ +#endif +#ifdef PWR_WAKEUP_PIN6 +SYS_WKUP6 = PC_1, /* SYS_WKUP5 */ +#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, +USB_OTG_HS_ULPI_D0 = PA_3, +USB_OTG_HS_SOF = PA_4, +USB_OTG_HS_ULPI_CK = PA_5, +USB_OTG_HS_ULPI_D1 = PB_0, +USB_OTG_HS_ULPI_D2 = PB_1, +USB_OTG_HS_ULPI_D7 = PB_5, +USB_OTG_HS_ULPI_D3 = PB_10, +USB_OTG_HS_ULPI_D4 = PB_11, +USB_OTG_HS_ID = PB_12, +USB_OTG_HS_ULPI_D5 = PB_12, +USB_OTG_HS_ULPI_D6 = PB_13, +USB_OTG_HS_VBUS = PB_13, +USB_OTG_HS_DM = PB_14, +USB_OTG_HS_DP = PB_15, +USB_OTG_HS_ULPI_STP = PC_0, +USB_OTG_HS_ULPI_DIR = PC_2, +USB_OTG_HS_ULPI_NXT = PC_3, +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BTT_SKR_SE_BX/hal_conf_extra.h b/buildroot/share/PlatformIO/variants/MARLIN_BTT_SKR_SE_BX/hal_conf_extra.h new file mode 100644 index 000000000000..4050fe810f9d --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BTT_SKR_SE_BX/hal_conf_extra.h @@ -0,0 +1,479 @@ +/** + ****************************************************************************** + * @file stm32h7xx_hal_conf_default.h + * @brief HAL default 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 __STM32H7xx_HAL_CONF_DEFAULT_H +#define __STM32H7xx_HAL_CONF_DEFAULT_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/* ########################## Module Selection ############################## */ +/** + * @brief Include the default list of modules to be used in the HAL driver + * and manage module deactivation + */ +#include "stm32yyxx_hal_conf.h" +#if 0 +/** + * @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_CEC_MODULE_ENABLED +#define HAL_COMP_MODULE_ENABLED +#define HAL_CORTEX_MODULE_ENABLED +#define HAL_CRC_MODULE_ENABLED +#define HAL_CRYP_MODULE_ENABLED +#define HAL_DAC_MODULE_ENABLED +#define HAL_DCMI_MODULE_ENABLED +#define HAL_DFSDM_MODULE_ENABLED +#define HAL_DMA_MODULE_ENABLED +#define HAL_DMA2D_MODULE_ENABLED +#define HAL_DSI_MODULE_ENABLED +#define HAL_ETH_MODULE_ENABLED +#define HAL_EXTI_MODULE_ENABLED +#define HAL_FDCAN_MODULE_ENABLED +#define HAL_FLASH_MODULE_ENABLED +#define HAL_GPIO_MODULE_ENABLED +#define HAL_HASH_MODULE_ENABLED +#define HAL_HCD_MODULE_ENABLED +#define HAL_HRTIM_MODULE_ENABLED +#define HAL_HSEM_MODULE_ENABLED +#define HAL_I2C_MODULE_ENABLED +#define HAL_I2S_MODULE_ENABLED +#define HAL_IRDA_MODULE_ENABLED +#define HAL_IWDG_MODULE_ENABLED +#define HAL_JPEG_MODULE_ENABLED +#define HAL_LPTIM_MODULE_ENABLED +#define HAL_LTDC_MODULE_ENABLED +#define HAL_MDIOS_MODULE_ENABLED +#define HAL_MDMA_MODULE_ENABLED +#define HAL_MMC_MODULE_ENABLED +#define HAL_NAND_MODULE_ENABLED +#define HAL_NOR_MODULE_ENABLED +#define HAL_OPAMP_MODULE_ENABLED +#define HAL_PCD_MODULE_ENABLED +#define HAL_PWR_MODULE_ENABLED +#define HAL_QSPI_MODULE_ENABLED +#define HAL_RAMECC_MODULE_ENABLED +#define HAL_RCC_MODULE_ENABLED +#define HAL_RNG_MODULE_ENABLED +#define HAL_RTC_MODULE_ENABLED +#define HAL_SAI_MODULE_ENABLED +#define HAL_SD_MODULE_ENABLED +#define HAL_SDRAM_MODULE_ENABLED +#define HAL_SMARTCARD_MODULE_ENABLED +#define HAL_SMBUS_MODULE_ENABLED +#define HAL_SPDIFRX_MODULE_ENABLED +#define HAL_SPI_MODULE_ENABLED +#define HAL_SRAM_MODULE_ENABLED +#define HAL_SWPMI_MODULE_ENABLED +#define HAL_TIM_MODULE_ENABLED +#define HAL_UART_MODULE_ENABLED +#define HAL_USART_MODULE_ENABLED +#define HAL_WWDG_MODULE_ENABLED +#endif + +/* ########################## Oscillator 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). + */ +#if !defined (HSE_VALUE) +#define HSE_VALUE ((uint32_t)25000000) /*!< Value of the External oscillator in Hz */ +#endif /* HSE_VALUE */ + +#if !defined (HSE_STARTUP_TIMEOUT) +#define HSE_STARTUP_TIMEOUT ((uint32_t)5000) /*!< Time out for HSE start up, in ms */ +#endif /* HSE_STARTUP_TIMEOUT */ + +/** + * @brief Internal oscillator (CSI) default value. + * This value is the default CSI value after Reset. + */ +#if !defined (CSI_VALUE) +#define CSI_VALUE ((uint32_t)4000000) /*!< Value of the Internal oscillator in Hz*/ +#endif /* CSI_VALUE */ + +/** + * @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). + */ +#if !defined (HSI_VALUE) +#define HSI_VALUE ((uint32_t)64000000) /*!< Value of the Internal oscillator in Hz*/ +#endif /* HSI_VALUE */ + +/** + * @brief External Low Speed oscillator (LSE) value. + * This value is used by the UART, RTC HAL module to compute the system frequency + */ +#if !defined (LSE_VALUE) +#define LSE_VALUE ((uint32_t)32768) /*!< Value of the External oscillator in Hz*/ +#endif /* LSE_VALUE */ + + +#if !defined (LSE_STARTUP_TIMEOUT) +#define LSE_STARTUP_TIMEOUT ((uint32_t)5000) /*!< Time out for LSE start up, in ms */ +#endif /* LSE_STARTUP_TIMEOUT */ + +#if !defined (LSI_VALUE) +#define LSI_VALUE ((uint32_t)32000) /*!< 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 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. + */ +#if !defined (EXTERNAL_CLOCK_VALUE) +#define EXTERNAL_CLOCK_VALUE 12288000U /*!< Value of the External clock 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 ((uint32_t)3300) /*!< Value of VDD in mv */ +#endif +#if !defined (TICK_INT_PRIORITY) +#define TICK_INT_PRIORITY ((uint32_t)0x00) /*!< tick interrupt priority */ +#endif +#if !defined (USE_RTOS) +#define USE_RTOS 0 +#endif +#if !defined (USE_SD_TRANSCEIVER) +#define USE_SD_TRANSCEIVER 1U /*!< use uSD Transceiver */ +#endif +#if !defined (USE_SPI_CRC) +#define USE_SPI_CRC 0U /*!< use CRC in SPI */ +#endif + +#define USE_HAL_ADC_REGISTER_CALLBACKS 0U /* ADC register callback disabled */ +#define USE_HAL_CEC_REGISTER_CALLBACKS 0U /* CEC register callback disabled */ +#define USE_HAL_COMP_REGISTER_CALLBACKS 0U /* COMP 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_FDCAN_REGISTER_CALLBACKS 0U /* FDCAN 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_SDRAM_REGISTER_CALLBACKS 0U /* SDRAM register callback disabled */ +#define USE_HAL_SRAM_REGISTER_CALLBACKS 0U /* SRAM register callback disabled */ +#define USE_HAL_HASH_REGISTER_CALLBACKS 0U /* HASH register callback disabled */ +#define USE_HAL_HCD_REGISTER_CALLBACKS 1U /* HCD register callback disabled */ +#define USE_HAL_HRTIM_REGISTER_CALLBACKS 0U /* HRTIM register callback disabled */ +#define USE_HAL_I2C_REGISTER_CALLBACKS 0U /* I2C register callback disabled */ +#define USE_HAL_I2S_REGISTER_CALLBACKS 0U /* I2S register callback disabled */ +#define USE_HAL_JPEG_REGISTER_CALLBACKS 0U /* JPEG 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_MDIOS_REGISTER_CALLBACKS 0U /* MDIO register callback disabled */ +#define USE_HAL_OPAMP_REGISTER_CALLBACKS 0U /* MDIO 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_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_SWPMI_REGISTER_CALLBACKS 0U /* SWPMI register callback disabled */ +#define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */ +#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */ + +/* ########################### Ethernet Configuration ######################### */ +#define ETH_TX_DESC_CNT 4 /* number of Ethernet Tx DMA descriptors */ +#define ETH_RX_DESC_CNT 4 /* number of Ethernet Rx DMA descriptors */ + +#define ETH_MAC_ADDR0 ((uint8_t)0x02) +#define ETH_MAC_ADDR1 ((uint8_t)0x00) +#define ETH_MAC_ADDR2 ((uint8_t)0x00) +#define ETH_MAC_ADDR3 ((uint8_t)0x00) +#define ETH_MAC_ADDR4 ((uint8_t)0x00) +#define ETH_MAC_ADDR5 ((uint8_t)0x00) + + +/* ########################## Assert Selection ############################## */ +/** + * @brief Uncomment the line below to expanse the "assert_param" macro in the + * HAL drivers code + */ +/* #define USE_FULL_ASSERT 1 */ + +/* Includes ------------------------------------------------------------------*/ +/** + * @brief Include module's header file + */ + +#ifdef HAL_RCC_MODULE_ENABLED +#include "stm32h7xx_hal_rcc.h" +#endif /* HAL_RCC_MODULE_ENABLED */ + +#ifdef HAL_GPIO_MODULE_ENABLED +#include "stm32h7xx_hal_gpio.h" +#endif /* HAL_GPIO_MODULE_ENABLED */ + +#ifdef HAL_DMA_MODULE_ENABLED +#include "stm32h7xx_hal_dma.h" +#endif /* HAL_DMA_MODULE_ENABLED */ + +#ifdef HAL_MDMA_MODULE_ENABLED +#include "stm32h7xx_hal_mdma.h" +#endif /* HAL_MDMA_MODULE_ENABLED */ + +#ifdef HAL_HASH_MODULE_ENABLED +#include "stm32h7xx_hal_hash.h" +#endif /* HAL_HASH_MODULE_ENABLED */ + +#ifdef HAL_DCMI_MODULE_ENABLED +#include "stm32h7xx_hal_dcmi.h" +#endif /* HAL_DCMI_MODULE_ENABLED */ + +#ifdef HAL_DMA2D_MODULE_ENABLED +#include "stm32h7xx_hal_dma2d.h" +#endif /* HAL_DMA2D_MODULE_ENABLED */ + +#ifdef HAL_DSI_MODULE_ENABLED +#include "stm32h7xx_hal_dsi.h" +#endif /* HAL_DSI_MODULE_ENABLED */ + +#ifdef HAL_DFSDM_MODULE_ENABLED +#include "stm32h7xx_hal_dfsdm.h" +#endif /* HAL_DFSDM_MODULE_ENABLED */ + +#ifdef HAL_ETH_MODULE_ENABLED +#include "stm32h7xx_hal_eth.h" +#endif /* HAL_ETH_MODULE_ENABLED */ + +#ifdef HAL_EXTI_MODULE_ENABLED +#include "stm32h7xx_hal_exti.h" +#endif /* HAL_EXTI_MODULE_ENABLED */ + +#ifdef HAL_CORTEX_MODULE_ENABLED +#include "stm32h7xx_hal_cortex.h" +#endif /* HAL_CORTEX_MODULE_ENABLED */ + +#ifdef HAL_ADC_MODULE_ENABLED +#include "stm32h7xx_hal_adc.h" +#endif /* HAL_ADC_MODULE_ENABLED */ + +#ifdef HAL_FDCAN_MODULE_ENABLED +#include "stm32h7xx_hal_fdcan.h" +#endif /* HAL_FDCAN_MODULE_ENABLED */ + +#ifdef HAL_CEC_MODULE_ENABLED +#include "stm32h7xx_hal_cec.h" +#endif /* HAL_CEC_MODULE_ENABLED */ + +#ifdef HAL_COMP_MODULE_ENABLED +#include "stm32h7xx_hal_comp.h" +#endif /* HAL_COMP_MODULE_ENABLED */ + +#ifdef HAL_CRC_MODULE_ENABLED +#include "stm32h7xx_hal_crc.h" +#endif /* HAL_CRC_MODULE_ENABLED */ + +#ifdef HAL_CRYP_MODULE_ENABLED +#include "stm32h7xx_hal_cryp.h" +#endif /* HAL_CRYP_MODULE_ENABLED */ + +#ifdef HAL_DAC_MODULE_ENABLED +#include "stm32h7xx_hal_dac.h" +#endif /* HAL_DAC_MODULE_ENABLED */ + +#ifdef HAL_FLASH_MODULE_ENABLED +#include "stm32h7xx_hal_flash.h" +#endif /* HAL_FLASH_MODULE_ENABLED */ + +#ifdef HAL_HRTIM_MODULE_ENABLED +#include "stm32h7xx_hal_hrtim.h" +#endif /* HAL_HRTIM_MODULE_ENABLED */ + +#ifdef HAL_HSEM_MODULE_ENABLED +#include "stm32h7xx_hal_hsem.h" +#endif /* HAL_HSEM_MODULE_ENABLED */ + +#ifdef HAL_SRAM_MODULE_ENABLED +#include "stm32h7xx_hal_sram.h" +#endif /* HAL_SRAM_MODULE_ENABLED */ + +#ifdef HAL_NOR_MODULE_ENABLED +#include "stm32h7xx_hal_nor.h" +#endif /* HAL_NOR_MODULE_ENABLED */ + +#ifdef HAL_NAND_MODULE_ENABLED +#include "stm32h7xx_hal_nand.h" +#endif /* HAL_NAND_MODULE_ENABLED */ + +#ifdef HAL_I2C_MODULE_ENABLED +#include "stm32h7xx_hal_i2c.h" +#endif /* HAL_I2C_MODULE_ENABLED */ + +#ifdef HAL_I2S_MODULE_ENABLED +#include "stm32h7xx_hal_i2s.h" +#endif /* HAL_I2S_MODULE_ENABLED */ + +#ifdef HAL_IWDG_MODULE_ENABLED +#include "stm32h7xx_hal_iwdg.h" +#endif /* HAL_IWDG_MODULE_ENABLED */ + +#ifdef HAL_JPEG_MODULE_ENABLED +#include "stm32h7xx_hal_jpeg.h" +#endif /* HAL_JPEG_MODULE_ENABLED */ + +#ifdef HAL_MDIOS_MODULE_ENABLED +#include "stm32h7xx_hal_mdios.h" +#endif /* HAL_MDIOS_MODULE_ENABLED */ + +#ifdef HAL_MMC_MODULE_ENABLED +#include "stm32h7xx_hal_mmc.h" +#endif /* HAL_MMC_MODULE_ENABLED */ + +#ifdef HAL_LPTIM_MODULE_ENABLED +#include "stm32h7xx_hal_lptim.h" +#endif /* HAL_LPTIM_MODULE_ENABLED */ + +#ifdef HAL_LTDC_MODULE_ENABLED +#include "stm32h7xx_hal_ltdc.h" +#endif /* HAL_LTDC_MODULE_ENABLED */ + +#ifdef HAL_OPAMP_MODULE_ENABLED +#include "stm32h7xx_hal_opamp.h" +#endif /* HAL_OPAMP_MODULE_ENABLED */ + +#ifdef HAL_PWR_MODULE_ENABLED +#include "stm32h7xx_hal_pwr.h" +#endif /* HAL_PWR_MODULE_ENABLED */ + +#ifdef HAL_QSPI_MODULE_ENABLED +#include "stm32h7xx_hal_qspi.h" +#endif /* HAL_QSPI_MODULE_ENABLED */ + +#ifdef HAL_RAMECC_MODULE_ENABLED +#include "stm32h7xx_hal_ramecc.h" +#endif /* HAL_HCD_MODULE_ENABLED */ + +#ifdef HAL_RNG_MODULE_ENABLED +#include "stm32h7xx_hal_rng.h" +#endif /* HAL_RNG_MODULE_ENABLED */ + +#ifdef HAL_RTC_MODULE_ENABLED +#include "stm32h7xx_hal_rtc.h" +#endif /* HAL_RTC_MODULE_ENABLED */ + +#ifdef HAL_SAI_MODULE_ENABLED +#include "stm32h7xx_hal_sai.h" +#endif /* HAL_SAI_MODULE_ENABLED */ + +#ifdef HAL_SD_MODULE_ENABLED +#include "stm32h7xx_hal_sd.h" +#endif /* HAL_SD_MODULE_ENABLED */ + +#ifdef HAL_SDRAM_MODULE_ENABLED +#include "stm32h7xx_hal_sdram.h" +#endif /* HAL_SDRAM_MODULE_ENABLED */ + +#ifdef HAL_SPI_MODULE_ENABLED +#include "stm32h7xx_hal_spi.h" +#endif /* HAL_SPI_MODULE_ENABLED */ + +#ifdef HAL_SPDIFRX_MODULE_ENABLED +#include "stm32h7xx_hal_spdifrx.h" +#endif /* HAL_SPDIFRX_MODULE_ENABLED */ + +#ifdef HAL_SWPMI_MODULE_ENABLED +#include "stm32h7xx_hal_swpmi.h" +#endif /* HAL_SWPMI_MODULE_ENABLED */ + +#ifdef HAL_TIM_MODULE_ENABLED +#include "stm32h7xx_hal_tim.h" +#endif /* HAL_TIM_MODULE_ENABLED */ + +#ifdef HAL_UART_MODULE_ENABLED +#include "stm32h7xx_hal_uart.h" +#endif /* HAL_UART_MODULE_ENABLED */ + +#ifdef HAL_USART_MODULE_ENABLED +#include "stm32h7xx_hal_usart.h" +#endif /* HAL_USART_MODULE_ENABLED */ + +#ifdef HAL_IRDA_MODULE_ENABLED +#include "stm32h7xx_hal_irda.h" +#endif /* HAL_IRDA_MODULE_ENABLED */ + +#ifdef HAL_SMARTCARD_MODULE_ENABLED +#include "stm32h7xx_hal_smartcard.h" +#endif /* HAL_SMARTCARD_MODULE_ENABLED */ + +#ifdef HAL_SMBUS_MODULE_ENABLED +#include "stm32h7xx_hal_smbus.h" +#endif /* HAL_SMBUS_MODULE_ENABLED */ + +#ifdef HAL_WWDG_MODULE_ENABLED +#include "stm32h7xx_hal_wwdg.h" +#endif /* HAL_WWDG_MODULE_ENABLED */ + +#ifdef HAL_PCD_MODULE_ENABLED +#include "stm32h7xx_hal_pcd.h" +#endif /* HAL_PCD_MODULE_ENABLED */ + +#ifdef HAL_HCD_MODULE_ENABLED +#include "stm32h7xx_hal_hcd.h" +#endif /* HAL_HCD_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 /* __STM32H7xx_HAL_CONF_DEFAULT_H */ + + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BTT_SKR_SE_BX/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_BTT_SKR_SE_BX/ldscript.ld new file mode 100644 index 000000000000..006c87a17a18 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BTT_SKR_SE_BX/ldscript.ld @@ -0,0 +1,208 @@ +/* +****************************************************************************** +** +** File : LinkerScript.ld +** +** Author : Auto-generated by STM32CubeIDE +** +** Abstract : Linker script for NUCLEO-H743II(2) Board embedding STM32H743IITx Device from STM32H7 series +** 2048Kbytes FLASH +** 128Kbytes DTCMRAM +** 64Kbytes ITCMRAM +** 512Kbytes RAM_D1 +** 288Kbytes RAM_D2 +** 64Kbytes RAM_D3 +** +** 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) 2019 STMicroelectronics

+** +** Redistribution and use in source and binary forms, with or without modification, +** are permitted provided that the following conditions are met: +** 1. Redistributions of source code must retain the above copyright notice, +** this list of conditions and the following disclaimer. +** 2. Redistributions in binary form must reproduce the above copyright notice, +** this list of conditions and the following disclaimer in the documentation +** and/or other materials provided with the distribution. +** 3. Neither the name of STMicroelectronics nor the names of its contributors +** may be used to endorse or promote products derived from this software +** without specific prior written permission. +** +** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +** AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +** IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +** FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +** DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +** SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +** CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +** OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +** OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = 0x24080000; /* end of "RAM_D1" Ram type memory */ + +_Min_Heap_Size = 0x200; /* required amount of heap */ +_Min_Stack_Size = 0x400; /* required amount of stack */ + +/* Memories definition */ +MEMORY +{ + DTCMRAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K + ITCMRAM (xrw) : ORIGIN = 0x00000000, LENGTH = 64K + RAM_D1 (xrw) : ORIGIN = 0x24000000, LENGTH = 512K + RAM_D2 (xrw) : ORIGIN = 0x30000000, LENGTH = 288K + RAM_D3 (xrw) : ORIGIN = 0x38000000, LENGTH = 64K + FLASH (rx) : ORIGIN = 0x8020000, LENGTH = 2048K - 128K +} + +/* Sections */ +SECTIONS +{ + /* The startup code into "FLASH" Rom type memory */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + /* The program code and other data into "FLASH" Rom type memory */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >FLASH + + /* Constant data into "FLASH" Rom type memory */ + .rodata : + { + . = ALIGN(4); + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + . = ALIGN(4); + } >FLASH + + .ARM.extab : { + . = ALIGN(4); + *(.ARM.extab* .gnu.linkonce.armextab.*) + . = ALIGN(4); + } >FLASH + + .ARM : { + . = ALIGN(4); + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + . = ALIGN(4); + } >FLASH + + .preinit_array : + { + . = ALIGN(4); + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + . = ALIGN(4); + } >FLASH + + .init_array : + { + . = ALIGN(4); + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + . = ALIGN(4); + } >FLASH + + .fini_array : + { + . = ALIGN(4); + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(SORT(.fini_array.*))) + KEEP (*(.fini_array*)) + PROVIDE_HIDDEN (__fini_array_end = .); + . = ALIGN(4); + } >FLASH + + /* Used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* Initialized data sections into "RAM_D1" Ram type memory */ + .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_D1 AT> FLASH + + /* Uninitialized data section into "RAM_D1" Ram type memory */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss section */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM_D1 + + /* User_heap_stack section, used to check that there is enough "RAM_D1" Ram type memory left */ + ._user_heap_stack : + { + . = ALIGN(8); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(8); + } >RAM_D1 + + /* Remove information from the compiler libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BTT_SKR_SE_BX/variant.cpp b/buildroot/share/PlatformIO/variants/MARLIN_BTT_SKR_SE_BX/variant.cpp new file mode 100644 index 000000000000..203e9fc9b8f8 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BTT_SKR_SE_BX/variant.cpp @@ -0,0 +1,332 @@ +#include "pins_arduino.h" + +#ifdef __cplusplus +extern "C" { +#endif + +// Pin number +const PinName digitalPin[] = { + PE_2, // D0 + PE_3, // D1 + PE_4, // D2 + PE_5, // D3 + PE_6, // D4 + PI_8, // D5 + PC_13, // D6 + PC_14, // D7 + PC_15, // D8 + PI_9, // D9 + PI_10, // D10 + PI_11, // D11 + PF_0, // D12 + PF_1, // D13 + PF_2, // D14 + PH_0, // D15 + PH_1, // D16 + PB_2, // D17 + PF_15, // D18 + PG_0, // D19 + PG_1, // D20 + PE_7, // D21 + PE_8, // D22 + PE_9, // D23 + PE_10, // D24 + PE_11, // D25 + PE_12, // D26 + PE_13, // D27 + PE_14, // D28 + PE_15, // D29 + PB_10, // D30 + PB_11, // D31 + PH_6, // D32 + PH_7, // D33 + PH_8, // D34 + PH_9, // D35 + PH_10, // D36 + PH_11, // D37 + PH_12, // D38 + PB_12, // D39 + PB_13, // D40 + PB_14, // D41 + PB_15, // D42 + PD_8, // D43 + PD_9, // D44 + PD_10, // D45 + PD_11, // D46 + PD_12, // D47 + PD_13, // D48 + PD_14, // D49 + PD_15, // D50 + PG_2, // D51 + PG_3, // D52 + PG_4, // D53 + PG_5, // D54 + PG_6, // D55 + PG_7, // D56 + PG_8, // D57 + PC_6, // D58 + PC_7, // D59 + PC_8, // D60 + PC_9, // D61 + PA_8, // D62 + PA_9, // D63 + PA_10, // D64 + PA_11, // D65 + PA_12, // D66 + PA_13, // D67 + PH_13, // D68 + PH_14, // D69 + PH_15, // D70 + PI_0, // D71 + PI_1, // D72 + PI_2, // D73 + PI_3, // D74 + PA_14, // D75 + PA_15, // D76 + PC_10, // D77 + PC_11, // D78 + PC_12, // D79 + PD_0, // D80 + PD_1, // D81 + PD_2, // D82 + PD_3, // D83 + PD_4, // D84 + PD_5, // D85 + PD_6, // D86 + PD_7, // D87 + PG_9, // D88 + PG_10, // D89 + PG_11, // D90 + PG_12, // D91 + PG_13, // D92 + PG_14, // D93 + PG_15, // D94 + PB_3, // D95 + PB_4, // D96 + PB_5, // D97 + PB_6, // D98 + PB_7, // D99 + PB_8, // D100 + PB_9, // D101 + PE_0, // D102 + PE_1, // D103 + PI_4, // D104 + PI_5, // D105 + PI_6, // D106 + PI_7, // D107 + PA_0, // D108 / A0 + PA_1, // D109 / A1 + PA_2, // D110 / A2 + PA_3, // D111 / A3 + PA_4, // D112 / A4 + PA_5, // D113 / A5 + PA_6, // D114 / A6 + PA_7, // D115 / A7 + PB_0, // D116 / A8 + PB_1, // D117 / A9 + PH_2, // D118 / A10 + PH_3, // D119 / A11 + PH_4, // D120 / A12 + PH_5, // D121 / A13 + PC_0, // D122 / A14 + PC_1, // D123 / A15 + PC_2, // D124 / A16 + PC_3, // D125 / A17 + PC_4, // D126 / A18 + PC_5, // D127 / A19 + PF_3, // D128 / A20 + PF_4, // D129 / A21 + PF_5, // D130 / A22 + PF_6, // D131 / A23 + PF_7, // D132 / A24 + PF_8, // D133 / A25 + PF_9, // D134 / A26 + PF_10, // D135 / A27 + PF_11, // D136 / A28 + PF_12, // D137 / A29 + PF_13, // D138 / A30 + PF_14, // D139 / A31 +}; + +#ifdef __cplusplus +} +#endif + +// ---------------------------------------------------------------------------- + +#ifdef __cplusplus +extern "C" { +#endif + +void SystemClockStartupInit() { + // Confirm is called only once time to avoid hang up caused by repeated calls in USB wakeup interrupt + static bool first_call = true; + if (!first_call) return; + first_call = false; + + // Clear all clock setting register + RCC->CR = 0x00000001; + RCC->CFGR = 0x00000000; + RCC->D1CFGR = 0x00000000; + RCC->D2CFGR = 0x00000000; + RCC->D3CFGR = 0x00000000; + RCC->PLLCKSELR = 0x00000000; + RCC->PLLCFGR = 0x00000000; + RCC->CIER = 0x00000000; + + // AXI_TARG7_FN_MOD for SRAM + *((volatile uint32_t*)0x51008108)=0x00000001; + + // Enable L1-Cache + SCB_EnableICache(); + SCB_EnableDCache(); + SCB->CACR |= 1<<2; + + PWR->CR3 &= ~(1 << 2); // SCUEN=0 + PWR->D3CR |= 3 << 14; // VOS=3,Scale1,1.15~1.26V core voltage + while((PWR->D3CR & (1 << 13)) == 0); // Wait for the voltage to stabilize + RCC->CR |= 1<<16; // Enable HSE + + uint16_t timeout = 0; + while(((RCC->CR & (1 << 17)) == 0) && (timeout < 0X7FFF)) { + timeout++; // Wait for HSE RDY + } + + if(timeout == 0X7FFF) { + Error_Handler(); + } else { + RCC->PLLCKSELR |= 2 << 0; // PLLSRC[1:0] = 2, HSE for PLL clock source + RCC->PLLCKSELR |= 5 << 4; // DIVM1[5:0] = pllm, Prescaler for PLL1 + RCC->PLL1DIVR |= (160 - 1) << 0; // DIVN1[8:0] = plln - 1, Multiplication factor for PLL1 VCO + RCC->PLL1DIVR |= (2 - 1) << 9; // DIVP1[6:0] = pllp - 1, PLL1 DIVP division factor + RCC->PLL1DIVR |= (4 - 1) << 16; // DIVQ1[6:0] = pllq - 1, PLL1 DIVQ division factor + RCC->PLL1DIVR |= 1 << 24; // DIVR1[6:0] = pllr - 1, PLL1 DIVR division factor + RCC->PLLCFGR |= 2 << 2; // PLL1 input (ref1_ck) clock range frequency is between 4 and 8 MHz + RCC->PLLCFGR |= 0 << 1; // PLL1 VCO selection, 0: 192 to 836 MHz, 1 : 150 to 420 MHz + RCC->PLLCFGR |= 3 << 16; // pll1_q_ck and pll1_p_ck output is enabled + RCC->CR |= 1 << 24; // PLL1 enable + while((RCC->CR & (1 << 25)) == 0); // PLL1 clock ready flag + + // PLL2 DIVR clock frequency = 220MHz, so that SDRAM clock can be set to 110MHz + RCC->PLLCKSELR |= 25 << 12; // DIVM2[5:0] = 25, Prescaler for PLL2 + RCC->PLL2DIVR |= (440 - 1) << 0; // DIVN2[8:0] = 440 - 1, Multiplication factor for PLL2 VCO + RCC->PLL2DIVR |= (2 - 1) << 9; // DIVP2[6:0] = 2-1, PLL2 DIVP division factor + RCC->PLL2DIVR |= (2 - 1) << 24; // DIVR2[6:0] = 2-1, PLL2 DIVR division factor + RCC->PLLCFGR |= 0 << 6; // PLL2RGE[1:0]=0, PLL2 input (ref2_ck) clock range frequency is between 1 and 2 MHz + RCC->PLLCFGR |= 0 << 5; // PLL2 VCO selection, 0: 192 to 836 MHz, 1: 150 to 420 MHz + RCC->PLLCFGR |= 1 << 19; // pll2_p_ck output is enabled + RCC->PLLCFGR |= 1 << 21; // pll2_r_ck output is enabled + RCC->D1CCIPR &= ~(3 << 0); // clear FMC kernel clock source selection + RCC->D1CCIPR |= 2 << 0; // pll2_r_ck clock selected as kernel peripheral clock + RCC->CR |= 1 << 26; // PLL2 enable + while((RCC->CR&(1<<27)) == 0); // PLL2 clock ready flag + + RCC->D1CFGR |= 8 << 0; // rcc_hclk3 = sys_d1cpre_ck / 2 = 400 / 2 = 200MHz. AHB1/2/3/4 + RCC->D1CFGR |= 0 << 8; // sys_ck not divided, sys_d1cpre_ck = sys_clk / 1 = 400 / 1 = 400MHz, System Clock = 400MHz + RCC->CFGR |= 3 << 0; // PLL1 selected as system clock (pll1_p_ck). 400MHz + while(1) { + timeout = (RCC->CFGR & (7 << 3)) >> 3; // System clock switch status + if(timeout == 3) break; // Wait for SW[2:0] = 3 (011: PLL1 selected as system clock (pll1_p_ck)) + } + + FLASH->ACR |= 2 << 0; // LATENCY[2:0] = 2 (@VOS1 Level,maxclock=210MHz) + FLASH->ACR |= 2 << 4; // WRHIGHFREQ[1:0] = 2, flash access frequency < 285MHz + + RCC->D1CFGR |= 4 << 4; // D1PPRE[2:0] = 4, rcc_pclk3 = rcc_hclk3 / 2 = 100MHz, APB3. + RCC->D2CFGR |= 4 << 4; // D2PPRE1[2:0] = 4, rcc_pclk1 = rcc_hclk1 / 2 = 100MHz, APB1. + RCC->D2CFGR |= 4 << 8; // D2PPRE2[2:0] = 4, rcc_pclk2 = rcc_hclk1 / 2 = 100MHz, APB2. + RCC->D3CFGR |= 4 << 4; // D3PPRE[2:0] = 4, rcc_pclk4 = rcc_hclk4 / 2 = 100MHz, APB4. + + RCC->CR |= 1 << 7; // CSI clock enable + RCC->APB4ENR |= 1 << 1; // SYSCFG peripheral clock enable + SYSCFG->CCCSR |= 1 << 0; + } + + // USB clock, (use HSI48 clock) + RCC->CR |= 1 << 12; // HSI48 clock enabl + while((RCC->CR & (1 << 13)) == 0);// 1: HSI48 clock is ready + RCC->APB1HENR |= 1 << 1; // CRS peripheral clock enabled + RCC->APB1HRSTR |= 1 << 1; // Resets CRS + RCC->APB1HRSTR &= ~(1 << 1); // Does not reset CRS + CRS->CFGR &= ~(3 << 28); // USB2 SOF selected as SYNC signal source + CRS->CR |= 3 << 5; // Automatic trimming and Frequency error counter enabled + RCC->D2CCIP2R &= ~(3 << 20); // Clear USBOTG 1 and 2 kernel clock source selection + RCC->D2CCIP2R |= 3 << 20; // HSI48_ck clock is selected as kernel clock +} + +uint8_t MPU_Convert_Bytes_To_POT(uint32_t nbytes) +{ + uint8_t count = 0; + while(nbytes != 1) + { + nbytes >>= 1; + count++; + } + return count; +} + +uint8_t MPU_Set_Protection(uint32_t baseaddr, uint32_t size, uint32_t rnum, uint8_t ap, uint8_t sen, uint8_t cen, uint8_t ben) +{ + uint32_t tempreg = 0; + uint8_t rnr = 0; + if ((size % 32) || size == 0) return 1; + rnr = MPU_Convert_Bytes_To_POT(size) - 1; + SCB->SHCSR &= ~(1 << 16); //disable MemManage + MPU->CTRL &= ~(1 << 0); //disable MPU + MPU->RNR = rnum; + MPU->RBAR = baseaddr; + tempreg |= 0 << 28; + tempreg |= ((uint32_t)ap) << 24; + tempreg |= 0 << 19; + tempreg |= ((uint32_t)sen) << 18; + tempreg |= ((uint32_t)cen) << 17; + tempreg |= ((uint32_t)ben) << 16; + tempreg |= 0 << 8; + tempreg |= rnr << 1; + tempreg |= 1 << 0; + MPU->RASR = tempreg; + MPU->CTRL = (1 << 2) | (1 << 0); //enable PRIVDEFENA + SCB->SHCSR |= 1 << 16; //enable MemManage + return 0; +} + +void MPU_Memory_Protection(void) +{ + MPU_Set_Protection(0x20000000, 128 * 1024, 1, MPU_REGION_FULL_ACCESS, 0, 1, 1); // protect DTCM 128k, Sharing is prohibited, cache is allowed, and buffering is allowed + + MPU_Set_Protection(0x24000000, 512 * 1024, 2, MPU_REGION_FULL_ACCESS, 0, 1, 1); // protect AXI SRAM, Sharing is prohibited, cache is allowed, and buffering is allowed + MPU_Set_Protection(0x30000000, 512 * 1024, 3, MPU_REGION_FULL_ACCESS, 0, 1, 1); // protect SRAM1~SRAM3, Sharing is prohibited, cache is allowed, and buffering is allowed + MPU_Set_Protection(0x38000000, 64 * 1024, 4, MPU_REGION_FULL_ACCESS, 0, 1, 1); // protect SRAM4, Sharing is prohibited, cache is allowed, and buffering is allowed + + MPU_Set_Protection(0x60000000, 64 * 1024 * 1024, 5, MPU_REGION_FULL_ACCESS, 0, 0, 0); // protect LCD FMC 64M, No sharing, no cache, no buffering + MPU_Set_Protection(0XC0000000, 32 * 1024 * 1024, 6, MPU_REGION_FULL_ACCESS, 0, 1, 1); // protect SDRAM 32M, Sharing is prohibited, cache is allowed, and buffering is allowed + MPU_Set_Protection(0X80000000, 256 * 1024 * 1024, 7, MPU_REGION_FULL_ACCESS, 0, 0, 0); // protect NAND FLASH 256M, No sharing, no cache, no buffering +} + +/** + * @brief System Clock Configuration + * @param None + * @retval None + */ +WEAK void SystemClock_Config(void) +{ + SystemClockStartupInit(); + + MPU_Memory_Protection(); + + /* Update current SystemCoreClock value */ + SystemCoreClockUpdate(); + + /* Configure the Systick interrupt time */ + HAL_SYSTICK_Config(SystemCoreClock/1000); + + /* Configure the Systick */ + HAL_SYSTICK_CLKSourceConfig(SYSTICK_CLKSOURCE_HCLK); + + /* SysTick_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0); +} + +#ifdef __cplusplus +} +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BTT_SKR_SE_BX/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_BTT_SKR_SE_BX/variant.h new file mode 100644 index 000000000000..5be18f9aa448 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BTT_SKR_SE_BX/variant.h @@ -0,0 +1,222 @@ +#ifndef _VARIANT_ARDUINO_STM32_ +#define _VARIANT_ARDUINO_STM32_ +#ifdef __cplusplus + +extern "C" { +#endif // __cplusplus +/*---------------------------------------------------------------------------- + * Pins + *----------------------------------------------------------------------------*/ +#define PE2 0 +#define PE3 1 +#define PE4 2 +#define PE5 3 +#define PE6 4 +#define PI8 5 +#define PC13 6 +#define PC14 7 +#define PC15 8 +#define PI9 9 +#define PI10 10 +#define PI11 11 +#define PF0 12 +#define PF1 13 +#define PF2 14 +#define PH0 15 +#define PH1 16 +#define PB2 17 +#define PF15 18 +#define PG0 19 +#define PG1 20 +#define PE7 21 +#define PE8 22 +#define PE9 23 +#define PE10 24 +#define PE11 25 +#define PE12 26 +#define PE13 27 +#define PE14 28 +#define PE15 29 +#define PB10 30 +#define PB11 31 +#define PH6 32 +#define PH7 33 +#define PH8 34 +#define PH9 35 +#define PH10 36 +#define PH11 37 +#define PH12 38 +#define PB12 39 +#define PB13 40 +#define PB14 41 +#define PB15 42 +#define PD8 43 +#define PD9 44 +#define PD10 45 +#define PD11 46 +#define PD12 47 +#define PD13 48 +#define PD14 49 +#define PD15 50 +#define PG2 51 +#define PG3 52 +#define PG4 53 +#define PG5 54 +#define PG6 55 +#define PG7 56 +#define PG8 57 +#define PC6 58 +#define PC7 59 +#define PC8 60 +#define PC9 61 +#define PA8 62 +#define PA9 63 +#define PA10 64 +#define PA11 65 +#define PA12 66 +#define PA13 67 +#define PH13 68 +#define PH14 69 +#define PH15 70 +#define PI0 71 +#define PI1 72 +#define PI2 73 +#define PI3 74 +#define PA14 75 +#define PA15 76 +#define PC10 77 +#define PC11 78 +#define PC12 79 +#define PD0 80 +#define PD1 81 +#define PD2 82 +#define PD3 83 +#define PD4 84 +#define PD5 85 +#define PD6 86 +#define PD7 87 +#define PG9 88 +#define PG10 89 +#define PG11 90 +#define PG12 91 +#define PG13 92 +#define PG14 93 +#define PG15 94 +#define PB3 95 +#define PB4 96 +#define PB5 97 +#define PB6 98 +#define PB7 99 +#define PB8 100 +#define PB9 101 +#define PE0 102 +#define PE1 103 +#define PI4 104 +#define PI5 105 +#define PI6 106 +#define PI7 107 +#define PA0 108 +#define PA1 109 +#define PA2 110 +#define PA3 111 +#define PA4 112 +#define PA5 113 +#define PA6 114 +#define PA7 115 +#define PB0 116 +#define PB1 117 +#define PH2 118 +#define PH3 119 +#define PH4 120 +#define PH5 121 +#define PC0 122 +#define PC1 123 +#define PC2 124 +#define PC3 125 +#define PC4 126 +#define PC5 127 +#define PF3 128 +#define PF4 129 +#define PF5 130 +#define PF6 131 +#define PF7 132 +#define PF8 133 +#define PF9 134 +#define PF10 135 +#define PF11 136 +#define PF12 137 +#define PF13 138 +#define PF14 139 + +// This must be a literal with the same value as PEND +#define NUM_DIGITAL_PINS 140 + +// This must be a literal with a value less than or equal to to MAX_ANALOG_INPUTS +#define NUM_ANALOG_INPUTS 24 +#define NUM_ANALOG_FIRST 108 + +// Timer Definitions +//Do not use timer used by PWM pins when possible. See PinMap_PWM in PeripheralPins.c +#define TIMER_TONE TIM2 +#define TIMER_SERVO TIM5 +#define TIMER_SERIAL TIM7 + +// UART1 for TFT port +#define ENABLE_HWSERIAL1 +#define PIN_SERIAL1_RX PA10 +#define PIN_SERIAL1_TX PA9 + +// UART4 for ESP-01 port +#define ENABLE_HWSERIAL4 +#define PIN_SERIAL4_RX PA1 +#define PIN_SERIAL4_TX PA0 + +// IIC1 for onboard 24C32 EEPROM +#define PIN_WIRE_SDA PB9 +#define PIN_WIRE_SCL PB8 + +// SPI3 for onboard SD card +// #define PIN_SPI_MOSI PC12 +// #define PIN_SPI_MISO PC11 +// #define PIN_SPI_SCK PC10 + +// HSE default value is 25MHz in HAL +// HSE_BYPASS is 25MHz +#ifndef HSE_BYPASS_NOT_USED + #define HSE_VALUE 25000000 +#endif + +// #define USE_USB_FS +/* Extra HAL modules */ +//#define HAL_HCD_MODULE_ENABLED +//#define HAL_DAC_MODULE_ENABLED +//#define HAL_ETH_MODULE_ENABLED + +#ifdef __cplusplus +} // extern "C" +#endif +/*---------------------------------------------------------------------------- + * Arduino objects - C++ only + *----------------------------------------------------------------------------*/ + +#ifdef __cplusplus +// These serial port names are intended to allow libraries and architecture-neutral +// sketches to automatically default to the correct port name for a particular type +// of use. For example, a GPS module would normally connect to SERIAL_PORT_HARDWARE_OPEN, +// the first hardware serial port whose RX/TX pins are not dedicated to another use. +// +// SERIAL_PORT_MONITOR Port which normally prints to the Arduino Serial Monitor +// +// SERIAL_PORT_USBVIRTUAL Port which is USB virtual serial +// +// SERIAL_PORT_LINUXBRIDGE Port which connects to a Linux system via Bridge library +// +// SERIAL_PORT_HARDWARE Hardware serial port, physical RX & TX pins. +// +// SERIAL_PORT_HARDWARE_OPEN Hardware serial ports which are open for use. Their RX & TX +// pins are NOT connected to anything by default. +#define SERIAL_PORT_MONITOR Serial +#define SERIAL_PORT_HARDWARE Serial +#endif + +#endif /* _VARIANT_ARDUINO_STM32_ */ diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/PeripheralPins.c new file mode 100755 index 000000000000..56ae00b41b59 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/PeripheralPins.c @@ -0,0 +1,423 @@ +/* + ******************************************************************************* + * Copyright (c) 2020, STMicroelectronics + * All rights reserved. + * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ******************************************************************************* + * Automatically generated from STM32F103R(F-G)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_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC2_IN0 +#if defined(STM32F103xE) || defined(STM32F103xG) + // {PA_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC3_IN0 +#endif + {PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1 + // {PA_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC2_IN1 +#if defined(STM32F103xE) || defined(STM32F103xG) + // {PA_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC3_IN1 +#endif + {PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2 + // {PA_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC2_IN2 +#if defined(STM32F103xE) || defined(STM32F103xG) + // {PA_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC3_IN2 +#endif + {PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3 + // {PA_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC2_IN3 +#if defined(STM32F103xE) || defined(STM32F103xG) + // {PA_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC3_IN3 +#endif + {PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4 + // {PA_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC2_IN4 + {PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5 + // {PA_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC2_IN5 + {PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6 + // {PA_6, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC2_IN6 + {PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7 + // {PA_7, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC2_IN7 + {PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8 + // {PB_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC2_IN8 + {PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9 + // {PB_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC2_IN9 + {PC_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10 + // {PC_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC2_IN10 +#if defined(STM32F103xE) || defined(STM32F103xG) + // {PC_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC3_IN10 +#endif + {PC_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11 + // {PC_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC2_IN11 +#if defined(STM32F103xE) || defined(STM32F103xG) + // {PC_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC3_IN11 +#endif + {PC_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12 + // {PC_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC2_IN12 +#if defined(STM32F103xE) || defined(STM32F103xG) + // {PC_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC3_IN12 +#endif + {PC_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13 + // {PC_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC2_IN13 +#if defined(STM32F103xE) || defined(STM32F103xG) + // {PC_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC3_IN13 +#endif + {PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14 + // {PC_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC2_IN14 + {PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15 + // {PC_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC2_IN15 + {NC, NP, 0} +}; +#endif + +//*** DAC *** + +#if defined(STM32F103xE) || defined(STM32F103xG) +#ifdef HAL_DAC_MODULE_ENABLED +WEAK const PinMap PinMap_DAC[] = { + {PA_4, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // DAC_OUT1 + {PA_5, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // DAC_OUT2 + {NC, NP, 0} +}; +#endif +#endif + +//*** I2C *** + +#ifdef HAL_I2C_MODULE_ENABLED +WEAK const PinMap PinMap_I2C_SDA[] = { + {PB_7, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, AFIO_NONE)}, + {PB_9, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, AFIO_I2C1_ENABLE)}, +#if defined(STM32F103xB) || defined(STM32F103xE) || defined(STM32F103xG) + {PB_11, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, AFIO_NONE)}, +#endif + {NC, NP, 0} +}; +#endif + +#ifdef HAL_I2C_MODULE_ENABLED +WEAK const PinMap PinMap_I2C_SCL[] = { + {PB_6, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, AFIO_NONE)}, + {PB_8, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, AFIO_I2C1_ENABLE)}, +#if defined(STM32F103xB) || defined(STM32F103xE) || defined(STM32F103xG) + {PB_10, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, AFIO_NONE)}, +#endif + {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, AFIO_NONE, 1, 0)}, // TIM2_CH1 + // {PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_2, 1, 0)}, // TIM2_CH1 +#if defined(STM32F103xE) || defined(STM32F103xG) + // {PA_0, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM5_CH1 +#endif + {PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM2_CH2 + // {PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_2, 2, 0)}, // TIM2_CH2 +#if defined(STM32F103xE) || defined(STM32F103xG) + // {PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM5_CH2 +#endif + {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM2_CH3 + // {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_1, 3, 0)}, // TIM2_CH3 +#if defined(STM32F103xG) + // {PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM5_CH3 +#endif +#if defined(STM32F103xE) || defined(STM32F103xG) + // {PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM9_CH1 +#endif + // {PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_1, 4, 0)}, // TIM2_CH4 +#if defined(STM32F103xE) || defined(STM32F103xG) + {PA_3, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM5_CH4 +#else + {PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM2_CH4 +#endif +#if defined(STM32F103xG) + // {PA_3, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM9_CH2 +#endif + {PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM3_CH1 +#if defined(STM32F103xG) + // {PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM13_CH1 +#endif + // {PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM3_CH2 +#if defined(STM32F103xE) || defined(STM32F103xG) + {PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 1)}, // TIM8_CH1N +#else + {PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 1, 1)}, // TIM1_CH1N +#endif +#if defined(STM32F103xG) + // {PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM14_CH1 +#endif + {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM1_CH1 + // {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 1, 0)}, // TIM1_CH1 + {PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM1_CH2 + // {PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 2, 0)}, // TIM1_CH2 + {PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM1_CH3 + // {PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 3, 0)}, // TIM1_CH3 + {PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM1_CH4 + // {PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 4, 0)}, // TIM1_CH4 + {PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_1, 1, 0)}, // TIM2_CH1 + // {PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_ENABLE, 1, 0)}, // TIM2_CH1 + // {PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 2, 1)}, // TIM1_CH2N + {PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM3_CH3 + // {PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_PARTIAL, 3, 0)}, // TIM3_CH3 +#if defined(STM32F103xE) || defined(STM32F103xG) + // {PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 1)}, // TIM8_CH2N +#endif + {PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 3, 1)}, // TIM1_CH3N + // {PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM3_CH4 + // {PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_PARTIAL, 4, 0)}, // TIM3_CH4 +#if defined(STM32F103xE) || defined(STM32F103xG) + // {PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 1)}, // TIM8_CH3N +#endif + {PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_1, 2, 0)}, // TIM2_CH2 + // {PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_ENABLE, 2, 0)}, // TIM2_CH2 + {PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_PARTIAL, 1, 0)}, // TIM3_CH1 + {PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_PARTIAL, 2, 0)}, // TIM3_CH2 +#if defined(STM32F103xB) || defined(STM32F103xE) || defined(STM32F103xG) + {PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM4_CH1 + {PB_7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM4_CH2 + {PB_8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM4_CH3 + {PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM4_CH4 +#endif +#if defined(STM32F103xG) + // {PB_8, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM10_CH1 +#endif +#if defined(STM32F103xG) + // {PB_9, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM11_CH1 +#endif + {PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_2, 3, 0)}, // TIM2_CH3 + // {PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_ENABLE, 3, 0)}, // TIM2_CH3 + {PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_2, 4, 0)}, // TIM2_CH4 + // {PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_ENABLE, 4, 0)}, // TIM2_CH4 + {PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 1)}, // TIM1_CH1N + {PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 1)}, // TIM1_CH2N +#if defined(STM32F103xG) + // {PB_14, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM12_CH1 +#endif + {PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 1)}, // TIM1_CH3N +#if defined(STM32F103xG) + // {PB_15, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM12_CH2 +#endif + {PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_ENABLE, 1, 0)}, // TIM3_CH1 +#if defined(STM32F103xE) || defined(STM32F103xG) + // {PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM8_CH1 +#endif + {PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_ENABLE, 2, 0)}, // TIM3_CH2 +#if defined(STM32F103xE) || defined(STM32F103xG) + // {PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM8_CH2 +#endif +#if defined(STM32F103xE) || defined(STM32F103xG) + {PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM8_CH3 +#else + {PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_ENABLE, 3, 0)}, // TIM3_CH3 +#endif + {PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_ENABLE, 4, 0)}, // TIM3_CH4 +#if defined(STM32F103xE) || defined(STM32F103xG) + // {PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM8_CH4 +#endif + {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, AFIO_NONE)}, + {PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, + {PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART1_ENABLE)}, +#if defined(STM32F103xB) || defined(STM32F103xE) || defined(STM32F103xG) + {PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +#endif +#if defined(STM32F103xE) || defined(STM32F103xG) + {PC_10, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +#endif +#if defined(STM32F103xB) + {PC_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART3_PARTIAL)}, +#endif +#if defined(STM32F103xE) || defined(STM32F103xG) + {PC_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +#endif + {NC, NP, 0} +}; +#endif + +#ifdef HAL_UART_MODULE_ENABLED +WEAK const PinMap PinMap_UART_RX[] = { + {PA_3, USART2, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_NONE)}, + {PA_10, USART1, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_NONE)}, + {PB_7, USART1, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_USART1_ENABLE)}, +#if defined(STM32F103xB) || defined(STM32F103xE) || defined(STM32F103xG) + {PB_11, USART3, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_NONE)}, +#endif +#if defined(STM32F103xE) || defined(STM32F103xG) + {PC_11, UART4, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_NONE)}, +#endif +#if defined(STM32F103xB) + {PC_11, USART3, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_USART3_PARTIAL)}, +#endif +#if defined(STM32F103xE) || defined(STM32F103xG) + {PD_2, UART5, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_NONE)}, +#endif + {NC, NP, 0} +}; +#endif + +#ifdef HAL_UART_MODULE_ENABLED +WEAK const PinMap PinMap_UART_RTS[] = { + {PA_1, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, + {PA_12, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +#if defined(STM32F103xB) || defined(STM32F103xE) || defined(STM32F103xG) + {PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, + {PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART3_PARTIAL)}, +#endif + {NC, NP, 0} +}; +#endif + +#ifdef HAL_UART_MODULE_ENABLED +WEAK const PinMap PinMap_UART_CTS[] = { + {PA_0, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, + {PA_11, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +#if defined(STM32F103xB) || defined(STM32F103xE) || defined(STM32F103xG) + {PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, + {PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART3_PARTIAL)}, +#endif + {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, AFIO_NONE)}, +#if defined(STM32F103xE) || defined(STM32F103xG) + {PB_5, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +#else + {PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_SPI1_ENABLE)}, +#endif +#if defined(STM32F103xB) || defined(STM32F103xE) || defined(STM32F103xG) + {PB_15, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +#endif + {NC, NP, 0} +}; +#endif + +#ifdef HAL_SPI_MODULE_ENABLED +WEAK const PinMap PinMap_SPI_MISO[] = { + {PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +#if defined(STM32F103xE) || defined(STM32F103xG) + {PB_4, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +#else + {PB_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_SPI1_ENABLE)}, +#endif +#if defined(STM32F103xB) || defined(STM32F103xE) || defined(STM32F103xG) + {PB_14, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +#endif + {NC, NP, 0} +}; +#endif + +#ifdef HAL_SPI_MODULE_ENABLED +WEAK const PinMap PinMap_SPI_SCLK[] = { + {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +#if defined(STM32F103xE) || defined(STM32F103xG) + {PB_3, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +#else + {PB_3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_SPI1_ENABLE)}, +#endif +#if defined(STM32F103xB) || defined(STM32F103xE) || defined(STM32F103xG) + {PB_13, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +#endif + {NC, NP, 0} +}; +#endif + +#ifdef HAL_SPI_MODULE_ENABLED +WEAK const PinMap PinMap_SPI_SSEL[] = { + {PA_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +#if defined(STM32F103xE) || defined(STM32F103xG) + {PA_15, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +#else + {PA_15, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_SPI1_ENABLE)}, +#endif +#if defined(STM32F103xB) || defined(STM32F103xE) || defined(STM32F103xG) + {PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +#endif + {NC, NP, 0} +}; +#endif + +//*** CAN *** + +#ifdef HAL_CAN_MODULE_ENABLED +WEAK const PinMap PinMap_CAN_RD[] = { + {PA_11, CAN1, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, AFIO_NONE)}, + {PB_8, CAN1, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, AFIO_CAN1_2)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_CAN_MODULE_ENABLED +WEAK const PinMap PinMap_CAN_TD[] = { + {PA_12, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, AFIO_NONE)}, + {PB_9, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, AFIO_CAN1_2)}, + {NC, NP, 0} +}; +#endif + +//*** No ETHERNET *** + +//*** No QUADSPI *** + +//*** USB *** + +#ifdef HAL_PCD_MODULE_ENABLED +WEAK const PinMap PinMap_USB[] = { + {PA_11, USB, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, AFIO_NONE)}, // USB_DM + {PA_12, USB, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, AFIO_NONE)}, // USB_DP + {NC, NP, 0} +}; +#endif + +//*** No USB_OTG_FS *** + +//*** No USB_OTG_HS *** + +//*** SD *** + +#if defined(STM32F103xE) || defined(STM32F103xG) +#ifdef HAL_SD_MODULE_ENABLED +WEAK const PinMap PinMap_SD[] = { + {PB_8, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D4 + {PB_9, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D5 + {PC_6, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D6 + {PC_7, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D7 + {PC_8, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D0 + {PC_9, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D1 + {PC_10, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D2 + {PC_11, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D3 + {PC_12, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, AFIO_NONE)}, // SDIO_CK + {PD_2, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, AFIO_NONE)}, // SDIO_CMD + {NC, NP, 0} +}; +#endif +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/PinNamesVar.h new file mode 100644 index 000000000000..d9e759f5d0cd --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/PinNamesVar.h @@ -0,0 +1,30 @@ +/* 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_DM = PA_11, + USB_DP = PA_12, +#endif \ No newline at end of file diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/ldscript.ld new file mode 100644 index 000000000000..cd7503b3a51d --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/ldscript.ld @@ -0,0 +1,200 @@ +/* +****************************************************************************** +** + +** File : LinkerScript.ld +** +** Author : Auto-generated by STM32CubeIDE +** +** Abstract : Linker script for STM32F103R(8/B/C/ETx Device from STM32F1 series +** 64/128/256/512Kbytes FLASH +** 20/20/48/64Kbytes 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) 2019 STMicroelectronics

+** +** Redistribution and use in source and binary forms, with or without modification, +** are permitted provided that the following conditions are met: +** 1. Redistributions of source code must retain the above copyright notice, +** this list of conditions and the following disclaimer. +** 2. Redistributions in binary form must reproduce the above copyright notice, +** this list of conditions and the following disclaimer in the documentation +** and/or other materials provided with the distribution. +** 3. Neither the name of STMicroelectronics nor the names of its contributors +** may be used to endorse or promote products derived from this software +** without specific prior written permission. +** +** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +** AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +** IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +** FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +** DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +** SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +** CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +** OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +** OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = 0x20000000 + LD_MAX_DATA_SIZE; /* end of "RAM" Ram type memory */ +_Min_Heap_Size = 0x200; /* required amount of heap */ +_Min_Stack_Size = 0x400; /* required amount of stack */ + +/* Memories definition */ +MEMORY +{ + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = LD_MAX_DATA_SIZE + FLASH (rx) : ORIGIN = 0x8000000 + LD_FLASH_OFFSET, LENGTH = LD_MAX_SIZE - LD_FLASH_OFFSET +} + +/* Sections */ +SECTIONS +{ + /* The startup code into "FLASH" Rom type memory */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + /* The program code and other data into "FLASH" Rom type memory */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >FLASH + + /* Constant data into "FLASH" Rom type memory */ + .rodata : + { + . = ALIGN(4); + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + . = ALIGN(4); + } >FLASH + + .ARM.extab : { + . = ALIGN(4); + *(.ARM.extab* .gnu.linkonce.armextab.*) + . = ALIGN(4); + } >FLASH + .ARM : { + . = ALIGN(4); + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + . = ALIGN(4); + } >FLASH + + .preinit_array : + { + . = ALIGN(4); + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + . = ALIGN(4); + } >FLASH + .init_array : + { + . = ALIGN(4); + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + . = ALIGN(4); + } >FLASH + .fini_array : + { + . = ALIGN(4); + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(SORT(.fini_array.*))) + KEEP (*(.fini_array*)) + PROVIDE_HIDDEN (__fini_array_end = .); + . = ALIGN(4); + } >FLASH + + /* Used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* Initialized data sections into "RAM" Ram type memory */ + .data : + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >RAM AT> FLASH + + + /* Uninitialized data section into "RAM" Ram type memory */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss section */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* User_heap_stack section, used to check that there is enough "RAM" Ram type memory left */ + ._user_heap_stack : + { + . = ALIGN(8); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(8); + } >RAM + + + + /* Remove information from the compiler libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} + diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/variant.cpp b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/variant.cpp new file mode 100644 index 000000000000..4d815a34d7f2 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/variant.cpp @@ -0,0 +1,152 @@ +/* + 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 + +const PinName digitalPin[] = { + PA_0, + PA_1, + PA_2, + PA_3, + PA_4, + PA_5, + PA_6, + PA_7, + PA_8, + PA_9, // RXD + PA_10, // TXD + PA_11, // USB D- + PA_12, // USB D+ + PA_13, // JTDI + PA_14, // JTCK + PA_15, + PB_0, + PB_1, + PB_2, + PB_3, // JTDO + PB_4, // JTRST + PB_5, + PB_6, + PB_7, + PB_8, + PB_9, + PB_10, + PB_11, // LED + PB_12, + PB_13, + PB_14, + PB_15, + PC_0, + PC_1, + PC_2, + PC_3, + PC_4, + PC_5, + PC_6, + PC_7, + PC_8, + PC_9, + PC_10, + PC_11, + PC_12, + PC_13, + PC_14, // OSC32_1 + PC_15, // OSC32_2 + PD_0, // OSCIN + PD_1, // OSCOUT + PD_2 +}; + +// Analog (Ax) pin number array +const uint32_t analogInputPin[] = { + 0, // A0, PA0 + 1, // A1, PA1 + 2, // A2, PA2 + 3, // A3, PA3 + 4, // A4, PA4 + 5, // A5, PA5 + 6, // A6, PA6 + 7, // A7, PA7 + 16, // A8, PB0 + 17, // A9, PB1 + 32, // A10, PC0 + 33, // A11, PC1 + 34, // A12, PC2 + 35, // A13, PC3 + 36, // A14, PC4 + 37 // A15, PC5 +}; + +#ifdef __cplusplus +} +#endif + +// ---------------------------------------------------------------------------- + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @brief System Clock Configuration + * @param None + * @retval None + */ +WEAK void SystemClock_Config(void) +{ + RCC_OscInitTypeDef RCC_OscInitStruct = {}; + RCC_ClkInitTypeDef RCC_ClkInitStruct = {}; + RCC_PeriphCLKInitTypeDef PeriphClkInit = {}; + + /* Initializes the CPU, AHB and APB busses clocks */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_ON; + RCC_OscInitStruct.HSEPredivValue = RCC_HSE_PREDIV_DIV1; + RCC_OscInitStruct.HSIState = RCC_HSI_ON; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL9; + if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) { + Error_Handler(); + } + /* Initializes the CPU, AHB and APB busses clocks */ + RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_SYSCLK + | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2; + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; + + if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) != HAL_OK) { + Error_Handler(); + } + PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC | RCC_PERIPHCLK_USB; + PeriphClkInit.AdcClockSelection = RCC_ADCPCLK2_DIV6; + PeriphClkInit.UsbClockSelection = RCC_USBCLKSOURCE_PLL_DIV1_5; + if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK) { + Error_Handler(); + } +} + +#ifdef __cplusplus +} +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/variant.h new file mode 100644 index 000000000000..41b194abe031 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/variant.h @@ -0,0 +1,175 @@ +/* + 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 + + +// * = F103R8-B-C-D-E-F-G +// ** = F103RC-D-E-F-G +// | 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 | | | | +#define PA3 PIN_A3 // | 2 | A2, DAC_OUT1** | USART2_RX | | | | +#define PA4 PIN_A4 // | 4 | A4, DAC_OUT2** | | | SPI1_SS | | +#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 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 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** | | | | +// |---------|----------------|--------------------------|-----------|-----------------------|-----------| + +// This must be a literal +#define NUM_DIGITAL_PINS 51 +// This must be a literal with a value less than or equal to to MAX_ANALOG_INPUTS +#define NUM_ANALOG_INPUTS 16 + +// On-board LED pin number +#ifndef LED_BUILTIN +#define LED_BUILTIN PB11 +#endif +#define LED_GREEN LED_BUILTIN + +// On-board user button +#ifndef USER_BTN +#define USER_BTN PC13 +#endif + +// Override default Arduino configuration + +// SPI Definitions +#if DEFAULT_SPI == 3 + #define PIN_SPI_SS PA15 + #define PIN_SPI_MOSI PB3 + #define PIN_SPI_MISO PB4 + #define PIN_SPI_SCK PB5 +#elif DEFAULT_SPI == 2 + #define PIN_SPI_SS PB12 + #define PIN_SPI_MOSI PB13 + #define PIN_SPI_MISO PB14 + #define PIN_SPI_SCK PB15 +#else + #define PIN_SPI_SS PA4 + #define PIN_SPI_MOSI PA7 + #define PIN_SPI_MISO PA6 + #define PIN_SPI_SCK PA5 +#endif + +// I2C Definitions +#define PIN_WIRE_SDA PB7 +#define PIN_WIRE_SCL PB6 + +// Timer Definitions +#ifndef TIMER_TONE + #define TIMER_TONE TIM3 +#endif +#ifndef TIMER_SERVO + #define TIMER_SERVO TIM2 +#endif + +// UART Definitions +// Define here Serial instance number to map on Serial generic name +#define SERIAL_UART_INSTANCE 1 + +// Default pin used for 'Serial1' instance +#define PIN_SERIAL_RX PA10 +#define PIN_SERIAL_TX PA9 + +// Extra HAL modules +#if defined(STM32F103xE) || defined(STM32F103xG) +#define HAL_DAC_MODULE_ENABLED +#endif + +#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 +#endif + +#endif /* _VARIANT_ARDUINO_STM32_ */ diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/PeripheralPins.c new file mode 100644 index 000000000000..99226a739d80 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/PeripheralPins.c @@ -0,0 +1,263 @@ +/* + ******************************************************************************* + * Copyright (c) 2020, STMicroelectronics + * All rights reserved. + * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ******************************************************************************* + * Automatically generated from STM32F103V(F-G)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_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC2_IN0 +//{PA_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC3_IN0 + {PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1 +//{PA_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC2_IN1 +//{PA_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC3_IN1 + {NC, NP, 0} +}; +#endif + +//*** DAC *** + +#if defined(STM32F103xE) || defined(STM32F103xG) +#ifdef HAL_DAC_MODULE_ENABLED +WEAK const PinMap PinMap_DAC[] = { +//{PA_4, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // DAC_OUT1 +//{PA_5, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // DAC_OUT2 + {NC, NP, 0} +}; +#endif +#endif + +//*** I2C *** + +#ifdef HAL_I2C_MODULE_ENABLED +WEAK const PinMap PinMap_I2C_SDA[] = { + {PB_11, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, AFIO_NONE)}, + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_I2C_SCL[] = { + {PB_10, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, AFIO_NONE)}, + {NC, NP, 0} +}; +#endif + +//*** PWM *** + +#ifdef HAL_TIM_MODULE_ENABLED +WEAK const PinMap PinMap_PWM[] = { +#if 0 + {PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM2_CH1 + //{PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_2, 1, 0)}, // TIM2_CH1 +#if defined(STM32F103xE) || defined(STM32F103xG) + //{PA_0, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM5_CH1 +#endif + {PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM2_CH2 + //{PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_2, 2, 0)}, // TIM2_CH2 +#if defined(STM32F103xE) || defined(STM32F103xG) + //{PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM5_CH2 +#endif + {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM2_CH3 + //{PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_1, 3, 0)}, // TIM2_CH3 +#if defined(STM32F103xE) || defined(STM32F103xG) + //{PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM5_CH3 +#endif + //{PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_1, 4, 0)}, // TIM2_CH4 +#if defined(STM32F103xE) || defined(STM32F103xG) + //{PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM2_CH4 + {PA_3, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM5_CH4 +#else + {PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM2_CH4 +#endif + {PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM3_CH1 + {PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 1, 1)}, // TIM1_CH1N + //{PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM3_CH2 + //{PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 1)}, // TIM8_CH1N + {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM1_CH1 + //{PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 1, 0)}, // TIM1_CH1 + {PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM1_CH2 + //{PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 2, 0)}, // TIM1_CH2 + {PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM1_CH3 + //{PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 3, 0)}, // TIM1_CH3 + {PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM1_CH4 + //{PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 4, 0)}, // TIM1_CH4 + {PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_1, 1, 0)}, // TIM2_CH1 + //{PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_ENABLE, 1, 0)}, // TIM2_CH1 + //{PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 2, 1)}, // TIM1_CH2N + {PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM3_CH3 + //{PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_PARTIAL, 3, 0)}, // TIM3_CH3 +#if defined(STM32F103xE) || defined(STM32F103xG) + //{PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 1)}, // TIM8_CH2N +#endif + {PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 3, 1)}, // TIM1_CH3N + //{PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM3_CH4 + //{PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_PARTIAL, 4, 0)}, // TIM3_CH4 +#if defined(STM32F103xE) || defined(STM32F103xG) + //{PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 1)}, // TIM8_CH3N +#endif + {PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_1, 2, 0)}, // TIM2_CH2 + //{PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_ENABLE, 2, 0)}, // TIM2_CH2 + {PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_PARTIAL, 1, 0)}, // TIM3_CH1 + {PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_PARTIAL, 2, 0)}, // TIM3_CH2 + {PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM4_CH1 + {PB_7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM4_CH2 + {PB_8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM4_CH3 + {PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM4_CH4 + {PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_2, 3, 0)}, // TIM2_CH3 + //{PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_ENABLE, 3, 0)}, // TIM2_CH3 + {PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_2, 4, 0)}, // TIM2_CH4 + //{PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_ENABLE, 4, 0)}, // TIM2_CH4 + {PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 1)}, // TIM1_CH1N + {PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 1)}, // TIM1_CH2N + {PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 1)}, // TIM1_CH3N + {PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_ENABLE, 1, 0)}, // TIM3_CH1 +#if defined(STM32F103xE) || defined(STM32F103xG) + //{PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM8_CH1 +#endif + {PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_ENABLE, 2, 0)}, // TIM3_CH2 +#if defined(STM32F103xE) || defined(STM32F103xG) + //{PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM8_CH2 +#endif + {PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_ENABLE, 3, 0)}, // TIM3_CH3 + //{PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM8_CH3 + {PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_ENABLE, 4, 0)}, // TIM3_CH4 +#if defined(STM32F103xE) || defined(STM32F103xG) + //{PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM8_CH4 +#endif + {PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM4_ENABLE, 1, 0)}, // TIM4_CH1 + {PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM4_ENABLE, 2, 0)}, // TIM4_CH2 + {PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM4_ENABLE, 3, 0)}, // TIM4_CH3 + {PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM4_ENABLE, 4, 0)}, // TIM4_CH4 + {PE_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_ENABLE, 1, 1)}, // TIM1_CH1N + {PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_ENABLE, 1, 0)}, // TIM1_CH1 + {PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_ENABLE, 2, 1)}, // TIM1_CH2N + {PE_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_ENABLE, 2, 0)}, // TIM1_CH2 + {PE_12, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_ENABLE, 3, 1)}, // TIM1_CH3N + {PE_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_ENABLE, 3, 0)}, // TIM1_CH3 + {PE_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_ENABLE, 4, 0)}, // TIM1_CH4 +#endif // if 0 + {PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM4_ENABLE, 1, 0)}, // TIM4_CH1 TFT Backlight + {PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM4_ENABLE, 2, 0)}, // TIM4_CH2 Servo connector + {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, AFIO_NONE)}, + {PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +//{PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_UART_RX[] = { + {PA_3, USART2, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_NONE)}, + {PA_10, USART1, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_NONE)}, +//{PB_11, USART3, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_NONE)}, + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_UART_RTS[] = { + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_UART_CTS[] = { + {NC, NP, 0} +}; +#endif + +//*** SPI *** + +WEAK const PinMap PinMap_SPI_MOSI[] = { + {PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +//{PB_15, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_SPI_MISO[] = { + {PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +//{PB_14, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_SPI_SCLK[] = { + {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +//{PB_13, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_SPI_SSEL[] = { +//{PA_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +//{PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, + {NC, NP, 0} +}; + +//*** No CAN *** + +#ifdef HAL_CAN_MODULE_ENABLED +WEAK const PinMap PinMap_CAN_RD[] = { + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_CAN_TD[] = { + {NC, NP, 0} +}; +#endif + +//*** No ETHERNET *** + +//*** No QUADSPI *** + +//*** USB *** + +#ifdef HAL_PCD_MODULE_ENABLED +WEAK const PinMap PinMap_USB[] = { + {PA_11, USB, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, AFIO_NONE)}, // USB_DM + {PA_12, USB, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, AFIO_NONE)}, // USB_DP + {NC, NP, 0} +}; +#endif + +//*** No USB_OTG_FS *** + +//*** No USB_OTG_HS *** + +//*** SD *** + +#if defined(STM32F103xE) || defined(STM32F103xG) +#ifdef HAL_SD_MODULE_ENABLED +WEAK const PinMap PinMap_SD[] = { +//{PB_8, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D4 +//{PB_9, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D5 +//{PC_6, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D6 +//{PC_7, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D7 + {PC_8, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D0 + {PC_9, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D1 + {PC_10, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D2 + {PC_11, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D3 + {PC_12, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, AFIO_NONE)}, // SDIO_CK + {PD_2, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, AFIO_NONE)}, // SDIO_CMD + {NC, NP, 0} +}; +#endif +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/PinNamesVar.h new file mode 100644 index 000000000000..9c07918364a5 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/PinNamesVar.h @@ -0,0 +1,32 @@ +/* SYS_WKUP */ +#if defined(PWR_WAKEUP_PIN1) && defined(HAL_PWR_MODULE_ENABLED) && !defined(HAL_PWR_MODULE_ONLY) + #error PA0 is used by thermal sensor, disable low power wake with -DHAL_PWR_MODULE_ONLY + 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 + #warning USB feature is not required with a CH340 chip + USB_DM = PA_11, + USB_DP = PA_12, +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/hal_conf_custom.h b/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/hal_conf_custom.h new file mode 100644 index 000000000000..e2247addb964 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/hal_conf_custom.h @@ -0,0 +1,348 @@ +/** + ****************************************************************************** + * @file hal_conf_custom.h for Longer3D STM32F103VE board + * @brief Overrides HAL default configuration file. + ****************************************************************************** + */ +#pragma once + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/* ########################## Module Selection ############################## */ +/** + * @brief Include the default list of modules to be used in the HAL driver + * and manage module deactivation + */ +#include "stm32yyxx_hal_conf.h" + +#ifdef HAL_PWR_MODULE_ENABLED + #undef HAL_PWR_MODULE_ENABLED // only way to disable it +#endif + +#if defined(HAL_PWR_MODULE_ENABLED) && !defined(HAL_PWR_MODULE_ONLY) + #define HAL_PWR_MODULE_ONLY // disable low power & PA0 wakeup pin (its T°c pin) +#endif + +#ifndef HAL_IWDG_MODULE_ENABLED + #define HAL_IWDG_MODULE_ENABLED // USE_WATCHDOG +#endif + +#ifdef HAL_PCD_MODULE_ENABLED + #warning No direct STM32 USB pins on Longer3D board + #undef HAL_PCD_MODULE_ENABLED // USB Device +#endif + +#ifdef HAL_HCD_MODULE_ENABLED + #warning No direct STM32 USB pins on Longer3D board + #undef HAL_HCD_MODULE_ENABLED // USB Host +#endif + +#ifndef HAL_USART_MODULE_ENABLED + //#define HAL_USART_MODULE_ENABLED // Useless.... UART_MODULE do it +#endif + +#ifdef HAL_CAN_LEGACY_MODULE_ENABLED + #undef HAL_CAN_LEGACY_MODULE_ENABLED +#endif + +#ifdef HAL_CAN_MODULE_ENABLED + #undef HAL_CAN_MODULE_ENABLED +#endif + +#ifdef HAL_DAC_MODULE_ENABLED + #undef HAL_DAC_MODULE_ENABLED +#endif + +#ifdef HAL_RTC_MODULE_ENABLED + #undef HAL_RTC_MODULE_ENABLED +#endif + +#ifndef HAL_EXTI_MODULE_ENABLED + #define HAL_EXTI_MODULE_ENABLED // for ENDSTOP_INTERRUPTS_FEATURE +#endif + +/** + * @brief List of modules in the framework (first ones enabled by default) + */ +//#define HAL_MODULE_ENABLED +//#define HAL_ADC_MODULE_ENABLED +//#define HAL_CORTEX_MODULE_ENABLED +//#define HAL_DAC_MODULE_ENABLED +//#define HAL_DMA_MODULE_ENABLED +//#define HAL_FLASH_MODULE_ENABLED +//#define HAL_GPIO_MODULE_ENABLED +//#define HAL_I2C_MODULE_ENABLED +//#define HAL_PCD_MODULE_ENABLED +//#define HAL_PWR_MODULE_ENABLED +//#define HAL_RCC_MODULE_ENABLED +//#define HAL_RTC_MODULE_ENABLED +//#define HAL_SD_MODULE_ENABLED +//#define HAL_SPI_MODULE_ENABLED +//#define HAL_SRAM_MODULE_ENABLED +//#define HAL_TIM_MODULE_ENABLED +//#define HAL_UART_MODULE_ENABLED + +//#define HAL_CAN_MODULE_ENABLED +//#define HAL_CAN_LEGACY_MODULE_ENABLED +//#define HAL_CEC_MODULE_ENABLED +//#define HAL_CRC_MODULE_ENABLED +//#define HAL_ETH_MODULE_ENABLED +//#define HAL_EXTI_MODULE_ENABLED +//#define HAL_HCD_MODULE_ENABLED +//#define HAL_I2S_MODULE_ENABLED +//#define HAL_IRDA_MODULE_ENABLED +//#define HAL_IWDG_MODULE_ENABLED +//#define HAL_NAND_MODULE_ENABLED +//#define HAL_NOR_MODULE_ENABLED +//#define HAL_PCCARD_MODULE_ENABLED +//#define HAL_SMARTCARD_MODULE_ENABLED +//#define HAL_USART_MODULE_ENABLED +//#define HAL_WWDG_MODULE_ENABLED +//#define HAL_MMC_MODULE_ENABLED + +/* ########################## Oscillator 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 (8 MHz) +#endif + +#ifndef HSE_STARTUP_TIMEOUT + #define HSE_STARTUP_TIMEOUT 100U // Time out for HSE start up, in ms +#endif + +/** + * @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 8000000U // Value of the Internal oscillator in Hz +#endif + +/** + * @brief Internal Low Speed oscillator (LSI) value. + */ +#ifndef LSI_VALUE + #define LSI_VALUE 40000U // LSI Typical Value in Hz +#endif /*!< 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. + * This value is used by the UART, RTC HAL module to compute the system frequency + */ +#ifndef LSE_VALUE + #define LSE_VALUE 32768U // Value of the External Low Speed oscillator in Hz +#endif + +#ifndef LSE_STARTUP_TIMEOUT + #define LSE_STARTUP_TIMEOUT 50U // No 32.7KHz LSE on this board, reduced to avoid delays +#endif + +/* 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 + */ +#ifndef VDD_VALUE + #define VDD_VALUE 3300U // Value of VDD in mv +#endif +#ifndef TICK_INT_PRIORITY + #define TICK_INT_PRIORITY 0x00U // tick interrupt priority +#endif +#ifndef USE_RTOS + #define USE_RTOS 0U +#endif +#ifndef PREFETCH_ENABLE + #define PREFETCH_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_DAC_REGISTER_CALLBACKS 0U /* DAC register callback disabled */ +#define USE_HAL_ETH_REGISTER_CALLBACKS 0U /* ETH 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_I2S_REGISTER_CALLBACKS 0U /* I2S 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_RTC_REGISTER_CALLBACKS 0U /* RTC 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_IRDA_REGISTER_CALLBACKS 0U /* IRDA register callback disabled */ +#define USE_HAL_SRAM_REGISTER_CALLBACKS 0U /* SRAM 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 */ + +/* ################## 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 +*/ +#if !defined(USE_SPI_CRC) +#define USE_SPI_CRC 0 +#endif + +/* Includes ------------------------------------------------------------------*/ +/** + * @brief Include module's header file + */ + +#ifdef HAL_RCC_MODULE_ENABLED + #include "stm32f1xx_hal_rcc.h" +#endif /* HAL_RCC_MODULE_ENABLED */ + +#ifdef HAL_GPIO_MODULE_ENABLED + #include "stm32f1xx_hal_gpio.h" +#endif /* HAL_GPIO_MODULE_ENABLED */ + +#ifdef HAL_EXTI_MODULE_ENABLED + #include "stm32f1xx_hal_exti.h" +#endif /* HAL_EXTI_MODULE_ENABLED */ + +#ifdef HAL_DMA_MODULE_ENABLED + #include "stm32f1xx_hal_dma.h" +#endif /* HAL_DMA_MODULE_ENABLED */ + +#ifdef HAL_ETH_MODULE_ENABLED + #include "stm32f1xx_hal_eth.h" +#endif /* HAL_ETH_MODULE_ENABLED */ + +#ifdef HAL_CAN_MODULE_ENABLED + #include "stm32f1xx_hal_can.h" +#endif /* HAL_CAN_MODULE_ENABLED */ + +#ifdef HAL_CAN_LEGACY_MODULE_ENABLED + #include "Legacy/stm32f1xx_hal_can_legacy.h" +#endif /* HAL_CAN_LEGACY_MODULE_ENABLED */ + +#ifdef HAL_CEC_MODULE_ENABLED + #include "stm32f1xx_hal_cec.h" +#endif /* HAL_CEC_MODULE_ENABLED */ + +#ifdef HAL_CORTEX_MODULE_ENABLED + #include "stm32f1xx_hal_cortex.h" +#endif /* HAL_CORTEX_MODULE_ENABLED */ + +#ifdef HAL_ADC_MODULE_ENABLED + #include "stm32f1xx_hal_adc.h" +#endif /* HAL_ADC_MODULE_ENABLED */ + +#ifdef HAL_CRC_MODULE_ENABLED + #include "stm32f1xx_hal_crc.h" +#endif /* HAL_CRC_MODULE_ENABLED */ + +#ifdef HAL_DAC_MODULE_ENABLED + #include "stm32f1xx_hal_dac.h" +#endif /* HAL_DAC_MODULE_ENABLED */ + +#ifdef HAL_FLASH_MODULE_ENABLED + #include "stm32f1xx_hal_flash.h" +#endif /* HAL_FLASH_MODULE_ENABLED */ + +#ifdef HAL_SRAM_MODULE_ENABLED + #include "stm32f1xx_hal_sram.h" +#endif /* HAL_SRAM_MODULE_ENABLED */ + +#ifdef HAL_NOR_MODULE_ENABLED + #include "stm32f1xx_hal_nor.h" +#endif /* HAL_NOR_MODULE_ENABLED */ + +#ifdef HAL_I2C_MODULE_ENABLED + #include "stm32f1xx_hal_i2c.h" +#endif /* HAL_I2C_MODULE_ENABLED */ + +#ifdef HAL_I2S_MODULE_ENABLED + #include "stm32f1xx_hal_i2s.h" +#endif /* HAL_I2S_MODULE_ENABLED */ + +#ifdef HAL_IWDG_MODULE_ENABLED + #include "stm32f1xx_hal_iwdg.h" +#endif /* HAL_IWDG_MODULE_ENABLED */ + +#ifdef HAL_PWR_MODULE_ENABLED + #include "stm32f1xx_hal_pwr.h" +#endif /* HAL_PWR_MODULE_ENABLED */ + +#ifdef HAL_RTC_MODULE_ENABLED + #include "stm32f1xx_hal_rtc.h" +#endif /* HAL_RTC_MODULE_ENABLED */ + +#ifdef HAL_PCCARD_MODULE_ENABLED + #include "stm32f1xx_hal_pccard.h" +#endif /* HAL_PCCARD_MODULE_ENABLED */ + +#ifdef HAL_SD_MODULE_ENABLED + #include "stm32f1xx_hal_sd.h" +#endif /* HAL_SD_MODULE_ENABLED */ + +#ifdef HAL_NAND_MODULE_ENABLED + #include "stm32f1xx_hal_nand.h" +#endif /* HAL_NAND_MODULE_ENABLED */ + +#ifdef HAL_SPI_MODULE_ENABLED + #include "stm32f1xx_hal_spi.h" +#endif /* HAL_SPI_MODULE_ENABLED */ + +#ifdef HAL_TIM_MODULE_ENABLED + #include "stm32f1xx_hal_tim.h" +#endif /* HAL_TIM_MODULE_ENABLED */ + +#ifdef HAL_UART_MODULE_ENABLED + #include "stm32f1xx_hal_uart.h" +#endif /* HAL_UART_MODULE_ENABLED */ + +#ifdef HAL_USART_MODULE_ENABLED + #include "stm32f1xx_hal_usart.h" +#endif /* HAL_USART_MODULE_ENABLED */ + +#ifdef HAL_IRDA_MODULE_ENABLED + #include "stm32f1xx_hal_irda.h" +#endif /* HAL_IRDA_MODULE_ENABLED */ + +#ifdef HAL_SMARTCARD_MODULE_ENABLED + #include "stm32f1xx_hal_smartcard.h" +#endif /* HAL_SMARTCARD_MODULE_ENABLED */ + +#ifdef HAL_WWDG_MODULE_ENABLED + #include "stm32f1xx_hal_wwdg.h" +#endif /* HAL_WWDG_MODULE_ENABLED */ + +#ifdef HAL_PCD_MODULE_ENABLED + #include "stm32f1xx_hal_pcd.h" +#endif /* HAL_PCD_MODULE_ENABLED */ + +#ifdef HAL_HCD_MODULE_ENABLED + #include "stm32f1xx_hal_hcd.h" +#endif /* HAL_HCD_MODULE_ENABLED */ + +#ifdef HAL_MMC_MODULE_ENABLED + #include "stm32f1xx_hal_mmc.h" +#endif /* HAL_MMC_MODULE_ENABLED */ + + +#define assert_param(expr) ((void)0U) + +#ifdef __cplusplus +} +#endif + diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/ldscript.ld new file mode 100644 index 000000000000..6bc577236a9c --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/ldscript.ld @@ -0,0 +1,189 @@ +/* +****************************************************************************** +** +** File : LinkerScript.ld +** +** Author : Auto-generated by STM32CubeIDE +** +** Abstract : Linker script for STM32F103V(8/B/C/E/F/GTx Device from STM32F1 series +** 64/128/256/512/768/1024Kbytes FLASH +** 20/20/48/64/64/96/96Kbytes 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) 2019 STMicroelectronics

+** +** Redistribution and use in source and binary forms, with or without modification, +** are permitted provided that the following conditions are met: +** 1. Redistributions of source code must retain the above copyright notice, +** this list of conditions and the following disclaimer. +** 2. Redistributions in binary form must reproduce the above copyright notice, +** this list of conditions and the following disclaimer in the documentation +** and/or other materials provided with the distribution. +** 3. Neither the name of STMicroelectronics nor the names of its contributors +** may be used to endorse or promote products derived from this software +** without specific prior written permission. +** +** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +** AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +** IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +** FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +** DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +** SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +** CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +** OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +** OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = 0x20000000 + LD_MAX_DATA_SIZE; /* end of "RAM" Ram type memory */ +_Min_Heap_Size = 0x200; /* required amount of heap */ +_Min_Stack_Size = 0x400; /* required amount of stack */ + +/* Memories definition */ +MEMORY +{ + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = LD_MAX_DATA_SIZE + FLASH (rx) : ORIGIN = 0x8000000 + LD_FLASH_OFFSET, LENGTH = LD_MAX_SIZE - LD_FLASH_OFFSET +} + +/* Sections */ +SECTIONS +{ + /* The startup code into "FLASH" Rom type memory */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + /* The program code and other data into "FLASH" Rom type memory */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >FLASH + + /* Constant data into "FLASH" Rom type memory */ + .rodata : { + . = ALIGN(4); + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + . = ALIGN(4); + } >FLASH + + .ARM.extab : { + . = ALIGN(4); + *(.ARM.extab* .gnu.linkonce.armextab.*) + . = ALIGN(4); + } >FLASH + + .ARM : { + . = ALIGN(4); + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + . = ALIGN(4); + } >FLASH + + .preinit_array : { + . = ALIGN(4); + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + . = ALIGN(4); + } >FLASH + + .init_array : { + . = ALIGN(4); + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + . = ALIGN(4); + } >FLASH + + .fini_array : { + . = ALIGN(4); + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(SORT(.fini_array.*))) + KEEP (*(.fini_array*)) + PROVIDE_HIDDEN (__fini_array_end = .); + . = ALIGN(4); + } >FLASH + + /* Used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* Initialized data sections into "RAM" Ram type memory */ + .data : { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >RAM AT> FLASH + + /* Uninitialized data section into "RAM" Ram type memory */ + . = ALIGN(4); + .bss : { + /* This is used by the startup in order to initialize the .bss 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" Ram type memory left */ + ._user_heap_stack : { + . = ALIGN(8); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(8); + } >RAM + + /* Remove information from the compiler libraries */ + /DISCARD/ : { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/variant.cpp b/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/variant.cpp new file mode 100644 index 000000000000..007ef81065bf --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/variant.cpp @@ -0,0 +1,249 @@ +/* + ******************************************************************************* + * Copyright (c) 2019, STMicroelectronics + * All rights reserved. + * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ******************************************************************************* + */ + +#include "pins_arduino.h" + +#ifdef __cplusplus +extern "C" { +#endif + +// Digital PinName array +const PinName digitalPin[] = { + PA_0, //D0 + PA_1, //D1 + PA_2, //D2 + PA_3, //D3 + PA_4, //D4 + PA_5, //D5 + PA_6, //D6 + PA_7, //D7 + PA_8, //D8 + PA_9, //D9 + PA_10, //D10 + PA_11, //D11 + PA_12, //D12 + PA_13, //D13 + PA_14, //D14 + PA_15, //D15 + + PB_0, //D16 + PB_1, //D17 + PB_2, //D18 + PB_3, //D19 + PB_4, //D20 + PB_5, //D21 + PB_6, //D22 + PB_7, //D23 + PB_8, //D24 + PB_9, //D25 + PB_10, //D26 + PB_11, //D27 + PB_12, //D28 + PB_13, //D29 + PB_14, //D30 + PB_15, //D31 + + PC_0, //D32 + PC_1, //D33 + PC_2, //D34 + PC_3, //D35 + PC_4, //D36 + PC_5, //D37 + PC_6, //D38 + PC_7, //D39 + PC_8, //D40 + PC_9, //D41 + PC_10, //D42 + PC_11, //D43 + PC_12, //D44 + PC_13, //D45 + PC_14, //D46 + PC_15, //D47 + + PD_0, //D48 + PD_1, //D49 + PD_2, //D50 + PD_3, //D51 + PD_4, //D52 + PD_5, //D53 + PD_6, //D54 + PD_7, //D55 + PD_8, //D56 + PD_9, //D57 + PD_10, //D58 + PD_11, //D59 + PD_12, //D60 + PD_13, //D61 + PD_14, //D62 + PD_15, //D63 + + PE_0, //D64 + PE_1, //D65 + PE_2, //D66 + PE_3, //D67 + PE_4, //D68 + PE_5, //D69 + PE_6, //D70 + PE_7, //D71 + PE_8, //D72 + PE_9, //D73 + PE_10, //D74 + PE_11, //D75 + PE_12, //D76 + PE_13, //D77 + PE_14, //D78 + PE_15, //D79 +}; + +// Analog (Ax) pin number array +const uint32_t analogInputPin[] = { + 0, // A0, PA0 + 1, // A1, PA1 + 2, // A2, PA2 + 3, // A3, PA3 + 4, // A4, PA4 + 5, // A5, PA5 + 6, // A6, PA6 + 7, // A7, PA7 + 16, // A8, PB0 + 17, // A9, PB1 + 32, // A10, PC0 + 33, // A11, PC1 + 34, // A12, PC2 + 35, // A13, PC3 + 36, // A14, PC4 + 37, // A15, PC5 +}; + +/******************************************************************************/ +/* PLL (clocked by HSE) used as System clock source */ +/******************************************************************************/ +static bool SetSysClock_PLL_HSE(bool bypass) +{ + RCC_OscInitTypeDef RCC_OscInitStruct = {}; + RCC_ClkInitTypeDef RCC_ClkInitStruct = {}; + RCC_PeriphCLKInitTypeDef PeriphClkInit = {}; + bool ret = false; + + // Initializes the CPU, AHB and APB busses clocks + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + if (bypass == false) { + RCC_OscInitStruct.HSEState = RCC_HSE_ON; + } else { + RCC_OscInitStruct.HSEState = RCC_HSE_BYPASS; + } + RCC_OscInitStruct.HSEPredivValue = RCC_HSE_PREDIV_DIV1; + RCC_OscInitStruct.HSIState = RCC_HSI_ON; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL9; // 8Mhz x 9 = 72MHz + + if (HAL_RCC_OscConfig(&RCC_OscInitStruct) == HAL_OK) { + // Initializes the CPU, AHB and APB busses clocks + RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_SYSCLK + | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2; + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; + + if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) == HAL_OK) { + PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC | RCC_PERIPHCLK_USB; + PeriphClkInit.AdcClockSelection = RCC_ADCPCLK2_DIV6; + PeriphClkInit.UsbClockSelection = RCC_USBCLKSOURCE_PLL_DIV1_5; // 72/1.5 = 48MHz + #ifndef USBCON + PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC; + #endif + if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) == HAL_OK) { + ret = true; + } + } + } + return ret; +} + +/******************************************************************************/ +/* PLL (clocked by HSI) used as System clock source (64MHz max) */ +/******************************************************************************/ +bool SetSysClock_PLL_HSI(void) +{ + RCC_OscInitTypeDef RCC_OscInitStruct = {}; + RCC_ClkInitTypeDef RCC_ClkInitStruct = {}; + RCC_PeriphCLKInitTypeDef PeriphClkInit = {}; + bool ret = false; + + // Initializes the CPU, AHB and APB busses clocks + 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_DIV2; // 4 MHz + RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL12; // 48 MHz + #ifndef USBCON + // When the HSI is used as a PLL clock input, the maximum + // system clock frequency that can be achieved is 64 MHz. + RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL16; // 64 MHz, stay close to 72 for delay() + #endif + if (HAL_RCC_OscConfig(&RCC_OscInitStruct) == HAL_OK) { + // Initializes the CPU, AHB and APB busses clocks + RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_SYSCLK + | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2; + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; + + // FLASH_LATENCY_1 may cause boot loops + if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) == HAL_OK) { + PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC | RCC_PERIPHCLK_USB; + PeriphClkInit.AdcClockSelection = RCC_ADCPCLK2_DIV4; + PeriphClkInit.UsbClockSelection = RCC_USBCLKSOURCE_PLL; // requires 48 MHz + #ifndef USBCON + PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC;// No USB, RTC nor I2S + PeriphClkInit.AdcClockSelection = RCC_ADCPCLK2_DIV6; // 2 4 6 8 + #endif + if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) == HAL_OK) { + ret = true; + } + } + } + return ret; +} + +void SystemClock_Config(void) +{ + /* + * If HSE_VALUE is not 8MHz and you want use it, then: + * - Redefine HSE_VALUE to the correct HSE_VALUE + * - Redefine SystemClock_Config() with the correct settings + */ +#if HSE_VALUE == 8000000U + // 1- Try to start with HSE and external 8MHz xtal + if (SetSysClock_PLL_HSE(false) == false) { + // 2- If fail try to start with HSE and external clock + if (SetSysClock_PLL_HSE(true) == false) { +#endif + // 3- If fail start with HSI clock + if (SetSysClock_PLL_HSI() == false) { + Error_Handler(); + } +#if HSE_VALUE == 8000000U + } + } +#endif +} + +#ifdef __cplusplus +} +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/variant.h new file mode 100644 index 000000000000..b0f2ddf0c22c --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/variant.h @@ -0,0 +1,175 @@ +#pragma once + +#ifdef __cplusplus +extern "C" { +#endif // __cplusplus + +// STM32F103VET6 | DIGITAL | ANALOG | USART | TWI | SPI | SPECIAL | +//------------------|-------------|---------------|------------|-----------|----------------------|------------| +#define PA0 0 // | | A0 Nozzle T°c | | | | | +#define PA1 1 // | | A1 Bed T°c | | | | | +#define PA2 2 // | | | USART2_TX | | | | +#define PA3 3 // | | DAC_OUT1** | USART2_RX | | | | +#define PA4 4 // | | DAC_OUT2** | | | SPI1_SS*(wired?) | | +#define PA5 5 // | O | | | | SPI1_SCK EEPROM | | +#define PA6 6 // | I | | | | SPI1_MISO EEPROM | | +#define PA7 7 // | O | | | | SPI1_MOSI EEPROM | | +#define PA8 8 // | Od BED | | | | | | +#define PA9 9 // | | | USART1_TX | | | | +#define PA10 10 // | | | USART1_RX | | | | +#define PA11 11 // | I | | | | | USB_DM | +#define PA12 12 // | I | | | | | USB_DP | +#define PA13 13 // | I | | | | | SWD_SWDIO | +#define PA14 14 // | I | | | | | SWD_SWCLK | +#define PA15 15 // | Od FAN | | | | | | +// |-------------|---------------|------------|-----------|----------------------|------------| +#define PB0 16 // | | | | | | | +#define PB1 17 // | | | | | | | +#define PB2 18 // | I+ | | | | | BOOT1 | +#define PB3 19 // | O X_DIR | | | | | | +#define PB4 20 // | O X_STEP | | | | | | +#define PB5 21 // | O X_EN | | | | | | +#define PB6 22 // | O Y_DIR | | | | | | +#define PB7 23 // | O Y_STEP | | | | | | +#define PB8 24 // | O Y_EN | | | | | | +#define PB9 25 // | O Z_DIR | | | | | | +#define PB10 26 // | I+ | | USART3_TX* | TWI2_SCL* | | | +#define PB11 27 // | I+ | | USART3_RX* | TWI2_SDA* | | | +#define PB12 28 // | O TFT | | | | SPI2_SS | TOUCH_CS | +#define PB13 29 // | O TFT | | | | SPI2_SCK | TOUCH_SCK | +#define PB14 30 // | O TFT | | | | SPI2_MISO (bad>MOSI) | TOUCH_MOSI | +#define PB15 31 // | I TFT | | | | SPI2_MOSI (bad>MISO) | TOUCH_MISO | +// |-------------|---------------|------------|-----------|----------------------|------------| +#define PC0 32 // | I E_OUT | | | | | | +#define PC1 33 // | I+ X_MIN | | | | | | +#define PC2 34 // | O LED | | | | | | +#define PC3 35 // | I+ | | | | | | +#define PC4 36 // | O TFT | | | | | TFT RESET | +#define PC5 37 // | O CS1 | | | | for SPI1 EEPROM CS | | +#define PC6 38 // | I TFT | | | | | TOUCH_INT | +#define PC7 39 // | | | | | | | +#define PC8 40 // | x SDIO | | | | | SD_D0 | +#define PC9 41 // | x SDIO | | | | | SD_D1 | +#define PC10 42 // | x SDIO | | | | | SD_D2 | +#define PC11 43 // | x SDIO | | | | | SD_D3 | +#define PC12 44 // | O SDIO | | | | | SD_CLK | +#define PC13 45 // | I | | | | | | +#define PC14 46 // | I+ Y_MAX | | | | | | +#define PC15 47 // | I+ Y_MIN | | | | | | +// |-------------|---------------|------------|-----------|----------------------|------------| +#define PD0 48 // | O TFT | | | | | OSC_IN D2 | +#define PD1 49 // | O TFT | | | | | OSC_OUT D3 | +#define PD2 50 // | O SDIO | | | | | SD_CMD | +#define PD3 51 // | Od NOZZLE | | | | | | +#define PD4 52 // | O TFT | | | | | FSMC_NOE | +#define PD5 53 // | O TFT | | | | | FSMC_NWE | +#define PD6 54 // | I wired?* | | | | | FSMC_NWAIT*| +#define PD7 55 // | O TFT | | | | | FSMC_NE1/CS| +#define PD8 56 // | O TFT | | | | | FSMC_D13 | +#define PD9 57 // | O TFT | | | | | FSMC_D14 | +#define PD10 58 // | O TFT | | | | | FSMC_D15 | +#define PD11 59 // | O TFT | | | | | FSMC_A16 | +#define PD12 60 // | O TFT | | | | | TFT BL | +#define PD13 61 // | Od PWM* | | | | | SERVO0 | +#define PD14 62 // | O TFT | | | | | FSMC_D00 | +#define PD15 63 // | O TFT | | | | | FSMC_D01 | +// |-------------|---------------|------------|-----------|----------------------|------------| +#define PE0 64 // | O Z_STEP | | | | | | +#define PE1 65 // | O Z_EN | | | | | | +#define PE2 66 // | O E0_DIR | | | | | | +#define PE3 67 // | O E0_STEP | | | | | | +#define PE4 68 // | O E0_EN | | | | | | +#define PE5 69 // | I+ Z_MAX | | | | | | +#define PE6 70 // | I+ Z_MIN | | | | | | +#define PE7 71 // | O TFT | | | | | FSMC_D04 | +#define PE8 72 // | O TFT | | | | | FSMC_D05 | +#define PE9 73 // | O TFT | | | | | FSMC_D06 | +#define PE10 74 // | O TFT | | | | | FSMC_D07 | +#define PE11 75 // | O TFT | | | | | FSMC_D08 | +#define PE12 76 // | O TFT | | | | | FSMC_D09 | +#define PE13 77 // | O TFT | | | | | FSMC_D10 | +#define PE14 78 // | O TFT | | | | | FSMC_D11 | +#define PE15 79 // | O TFT | | | | | FSMC_D12 | +//------------------|-------------|---------------|------------|-----------|----------------------|------------| + +// This must be a literal +#define NUM_DIGITAL_PINS 80 +#define NUM_ANALOG_INPUTS 16 // 2 first are used, but cant be reduced to 2... + +// On-board LED pin number +#ifndef LED_BUILTIN +#define LED_BUILTIN PC2 +#endif + +// On-board user button (not wired) +#ifndef USER_BTN +#define USER_BTN PC13 +#endif + +// SPI Definition (SPI1 EEPROM) +#define PIN_SPI_SS PC5 +#define PIN_SPI_MOSI PA7 +#define PIN_SPI_MISO PA6 +#define PIN_SPI_SCK PA5 + +// I2C Definition (Unused) +#define PIN_WIRE_SDA PB11 +#define PIN_WIRE_SCL PB10 + +// Timer Definitions +// Use TIM6/TIM7 when possible as servo and tone don't need GPIO output pin +#ifndef TIMER_TONE + #define TIMER_TONE TIM6 +#endif +#ifndef TIMER_SERVO + #define TIMER_SERVO TIM7 +#endif + +// UART Definitions +// Define here Serial instance number to map on Serial generic name +#define SERIAL_UART_INSTANCE 1 + +// Default pin used for 'Serial' instance (linked to CH340 USB port) +#define PIN_SERIAL_RX PA10 +#define PIN_SERIAL_TX PA9 +#define PIN_SERIAL1_RX PA10 +#define PIN_SERIAL1_TX PA9 +// Default pin used for 'Serial2' instance (connector exists but unsoldered) +#define PIN_SERIAL2_RX PA3 +#define PIN_SERIAL2_TX PA2 + +// Extra HAL modules +#if defined(STM32F103xE) +//#define HAL_DAC_MODULE_ENABLED (unused or maybe for the eeprom write?) +#define HAL_SD_MODULE_ENABLED +#define HAL_SRAM_MODULE_ENABLED +#endif + +#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 Serial1 + #define SERIAL_PORT_HARDWARE Serial1 + #define SERIAL_PORT_HARDWARE_OPEN Serial2 +#endif + diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103Vx/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_F103Vx/PeripheralPins.c index c9d2bb88b87a..339a55916c14 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F103Vx/PeripheralPins.c +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103Vx/PeripheralPins.c @@ -25,61 +25,61 @@ #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_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC2_IN0 + //{PA_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC2_IN0 #if defined(STM32F103xE) || defined(STM32F103xG) - // {PA_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC3_IN0 + //{PA_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC3_IN0 #endif {PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1 - // {PA_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC2_IN1 + //{PA_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC2_IN1 #if defined(STM32F103xE) || defined(STM32F103xG) - // {PA_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC3_IN1 + //{PA_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC3_IN1 #endif {PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2 - // {PA_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC2_IN2 + //{PA_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC2_IN2 #if defined(STM32F103xE) || defined(STM32F103xG) - // {PA_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC3_IN2 + //{PA_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC3_IN2 #endif {PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3 - // {PA_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC2_IN3 + //{PA_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC2_IN3 #if defined(STM32F103xE) || defined(STM32F103xG) - // {PA_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC3_IN3 + //{PA_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC3_IN3 #endif {PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4 - // {PA_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC2_IN4 + //{PA_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC2_IN4 {PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5 - // {PA_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC2_IN5 + //{PA_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC2_IN5 {PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6 - // {PA_6, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC2_IN6 + //{PA_6, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC2_IN6 {PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7 - // {PA_7, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC2_IN7 + //{PA_7, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC2_IN7 {PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8 - // {PB_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC2_IN8 + //{PB_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC2_IN8 {PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9 - // {PB_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC2_IN9 + //{PB_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC2_IN9 {PC_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10 - // {PC_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC2_IN10 + //{PC_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC2_IN10 #if defined(STM32F103xE) || defined(STM32F103xG) - // {PC_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC3_IN10 + //{PC_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC3_IN10 #endif {PC_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11 - // {PC_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC2_IN11 + //{PC_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC2_IN11 #if defined(STM32F103xE) || defined(STM32F103xG) - // {PC_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC3_IN11 + //{PC_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC3_IN11 #endif {PC_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12 - // {PC_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC2_IN12 + //{PC_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC2_IN12 #if defined(STM32F103xE) || defined(STM32F103xG) - // {PC_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC3_IN12 + //{PC_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC3_IN12 #endif {PC_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13 - // {PC_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC2_IN13 + //{PC_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC2_IN13 #if defined(STM32F103xE) || defined(STM32F103xG) - // {PC_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC3_IN13 + //{PC_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC3_IN13 #endif {PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14 - // {PC_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC2_IN14 + //{PC_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC2_IN14 {PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15 - // {PC_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC2_IN15 + //{PC_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC2_IN15 {NC, NP, 0} }; #endif @@ -105,9 +105,7 @@ WEAK const PinMap PinMap_I2C_SDA[] = { {PB_11, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, AFIO_NONE)}, {NC, NP, 0} }; -#endif -#ifdef HAL_I2C_MODULE_ENABLED WEAK const PinMap PinMap_I2C_SCL[] = { {PB_6, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, AFIO_NONE)}, {PB_8, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, AFIO_I2C1_ENABLE)}, @@ -121,105 +119,105 @@ WEAK const PinMap PinMap_I2C_SCL[] = { #ifdef HAL_TIM_MODULE_ENABLED WEAK const PinMap PinMap_PWM[] = { {PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM2_CH1 - // {PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_2, 1, 0)}, // TIM2_CH1 + //{PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_2, 1, 0)}, // TIM2_CH1 #if defined(STM32F103xE) || defined(STM32F103xG) - // {PA_0, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM5_CH1 + //{PA_0, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM5_CH1 #endif {PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM2_CH2 - // {PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_2, 2, 0)}, // TIM2_CH2 + //{PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_2, 2, 0)}, // TIM2_CH2 #if defined(STM32F103xE) || defined(STM32F103xG) - // {PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM5_CH2 + //{PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM5_CH2 #endif {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM2_CH3 - // {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_1, 3, 0)}, // TIM2_CH3 + //{PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_1, 3, 0)}, // TIM2_CH3 #if defined(STM32F103xE) || defined(STM32F103xG) - // {PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM5_CH3 + //{PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM5_CH3 #endif #ifdef STM32F103xG - // {PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM9_CH1 + //{PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM9_CH1 #endif - // {PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_1, 4, 0)}, // TIM2_CH4 + //{PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_1, 4, 0)}, // TIM2_CH4 #if defined(STM32F103xE) || defined(STM32F103xG) - // {PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM2_CH4 + //{PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM2_CH4 {PA_3, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM5_CH4 #else {PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM2_CH4 #endif #if defined(STM32F103xG) - // {PA_3, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM9_CH2 + //{PA_3, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM9_CH2 #endif {PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM3_CH1 #if defined(STM32F103xG) - // {PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM13_CH1 + //{PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM13_CH1 #endif {PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 1, 1)}, // TIM1_CH1N - // {PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM3_CH2 - // {PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 1)}, // TIM8_CH1N + //{PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM3_CH2 + //{PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 1)}, // TIM8_CH1N #if defined(STM32F103xG) - // {PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM14_CH1 + //{PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM14_CH1 #endif {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM1_CH1 - // {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 1, 0)}, // TIM1_CH1 + //{PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 1, 0)}, // TIM1_CH1 {PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM1_CH2 - // {PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 2, 0)}, // TIM1_CH2 + //{PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 2, 0)}, // TIM1_CH2 {PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM1_CH3 - // {PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 3, 0)}, // TIM1_CH3 + //{PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 3, 0)}, // TIM1_CH3 {PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM1_CH4 - // {PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 4, 0)}, // TIM1_CH4 + //{PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 4, 0)}, // TIM1_CH4 {PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_1, 1, 0)}, // TIM2_CH1 - // {PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_ENABLE, 1, 0)}, // TIM2_CH1 - // {PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 2, 1)}, // TIM1_CH2N + //{PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_ENABLE, 1, 0)}, // TIM2_CH1 + //{PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 2, 1)}, // TIM1_CH2N {PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM3_CH3 - // {PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_PARTIAL, 3, 0)}, // TIM3_CH3 + //{PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_PARTIAL, 3, 0)}, // TIM3_CH3 #if defined(STM32F103xE) || defined(STM32F103xG) - // {PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 1)}, // TIM8_CH2N + //{PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 1)}, // TIM8_CH2N #endif {PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 3, 1)}, // TIM1_CH3N - // {PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM3_CH4 - // {PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_PARTIAL, 4, 0)}, // TIM3_CH4 + //{PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM3_CH4 + //{PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_PARTIAL, 4, 0)}, // TIM3_CH4 #if defined(STM32F103xE) || defined(STM32F103xG) - // {PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 1)}, // TIM8_CH3N + //{PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 1)}, // TIM8_CH3N #endif {PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_1, 2, 0)}, // TIM2_CH2 - // {PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_ENABLE, 2, 0)}, // TIM2_CH2 + //{PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_ENABLE, 2, 0)}, // TIM2_CH2 {PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_PARTIAL, 1, 0)}, // TIM3_CH1 {PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_PARTIAL, 2, 0)}, // TIM3_CH2 {PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM4_CH1 {PB_7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM4_CH2 {PB_8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM4_CH3 #if defined(STM32F103xG) - // {PB_8, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM10_CH1 + //{PB_8, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM10_CH1 #endif {PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM4_CH4 #if defined(STM32F103xG) - // {PB_9, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM11_CH1 + //{PB_9, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM11_CH1 #endif {PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_2, 3, 0)}, // TIM2_CH3 - // {PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_ENABLE, 3, 0)}, // TIM2_CH3 + //{PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_ENABLE, 3, 0)}, // TIM2_CH3 {PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_2, 4, 0)}, // TIM2_CH4 - // {PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_ENABLE, 4, 0)}, // TIM2_CH4 + //{PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_ENABLE, 4, 0)}, // TIM2_CH4 {PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 1)}, // TIM1_CH1N {PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 1)}, // TIM1_CH2N #if defined(STM32F103xG) - // {PB_14, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM12_CH1 + //{PB_14, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM12_CH1 #endif {PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 1)}, // TIM1_CH3N #if defined(STM32F103xG) - // {PB_15, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM12_CH2 + //{PB_15, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM12_CH2 #endif {PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_ENABLE, 1, 0)}, // TIM3_CH1 #if defined(STM32F103xE) || defined(STM32F103xG) - // {PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM8_CH1 + //{PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM8_CH1 #endif {PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_ENABLE, 2, 0)}, // TIM3_CH2 #if defined(STM32F103xE) || defined(STM32F103xG) - // {PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM8_CH2 + //{PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM8_CH2 #endif {PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_ENABLE, 3, 0)}, // TIM3_CH3 - // {PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM8_CH3 + //{PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM8_CH3 {PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_ENABLE, 4, 0)}, // TIM3_CH4 #if defined(STM32F103xE) || defined(STM32F103xG) - // {PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM8_CH4 + //{PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM8_CH4 #endif {PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM4_ENABLE, 1, 0)}, // TIM4_CH1 {PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM4_ENABLE, 2, 0)}, // TIM4_CH2 @@ -248,29 +246,27 @@ WEAK const PinMap PinMap_UART_TX[] = { {PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, {PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART1_ENABLE)}, {PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, -#if defined(STM32F103xE) || defined(STM32F103xG) - // {PC_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART3_PARTIAL)}, - {PC_10, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, -#else - {PC_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART3_PARTIAL)}, -#endif -#if defined(STM32F103xE) || defined(STM32F103xG) - {PC_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, -#endif + #if defined(STM32F103xE) || defined(STM32F103xG) + //{PC_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART3_PARTIAL)}, + {PC_10, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, + #else + {PC_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART3_PARTIAL)}, + #endif + #if defined(STM32F103xE) || defined(STM32F103xG) + {PC_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, + #endif {PD_5, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART2_ENABLE)}, {PD_8, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART3_ENABLE)}, {NC, NP, 0} }; -#endif -#ifdef HAL_UART_MODULE_ENABLED WEAK const PinMap PinMap_UART_RX[] = { {PA_3, USART2, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_NONE)}, {PA_10, USART1, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_NONE)}, {PB_7, USART1, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_USART1_ENABLE)}, {PB_11, USART3, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_NONE)}, #if defined(STM32F103xE) || defined(STM32F103xG) - // {PC_11, USART3, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_USART3_PARTIAL)}, + //{PC_11, USART3, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_USART3_PARTIAL)}, {PC_11, UART4, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_NONE)}, #else {PC_11, USART3, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_USART3_PARTIAL)}, @@ -282,26 +278,22 @@ WEAK const PinMap PinMap_UART_RX[] = { {PD_9, USART3, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_USART3_ENABLE)}, {NC, NP, 0} }; -#endif -#ifdef HAL_UART_MODULE_ENABLED WEAK const PinMap PinMap_UART_RTS[] = { {PA_1, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, {PA_12, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, {PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, - // {PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART3_PARTIAL)}, + //{PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART3_PARTIAL)}, {PD_4, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART2_ENABLE)}, {PD_12, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART3_ENABLE)}, {NC, NP, 0} }; -#endif -#ifdef HAL_UART_MODULE_ENABLED WEAK const PinMap PinMap_UART_CTS[] = { {PA_0, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, {PA_11, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, {PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, - // {PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART3_PARTIAL)}, + //{PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART3_PARTIAL)}, {PD_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART2_ENABLE)}, {PD_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART3_ENABLE)}, {NC, NP, 0} @@ -314,7 +306,7 @@ WEAK const PinMap PinMap_UART_CTS[] = { WEAK const PinMap PinMap_SPI_MOSI[] = { {PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, #if defined(STM32F103xE) || defined(STM32F103xG) - // {PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_SPI1_ENABLE)}, + //{PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_SPI1_ENABLE)}, {PB_5, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, #else {PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_SPI1_ENABLE)}, @@ -322,13 +314,11 @@ WEAK const PinMap PinMap_SPI_MOSI[] = { {PB_15, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, {NC, NP, 0} }; -#endif -#ifdef HAL_SPI_MODULE_ENABLED WEAK const PinMap PinMap_SPI_MISO[] = { {PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, #if defined(STM32F103xE) || defined(STM32F103xG) - // {PB_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_SPI1_ENABLE)}, + //{PB_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_SPI1_ENABLE)}, {PB_4, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, #else {PB_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_SPI1_ENABLE)}, @@ -336,13 +326,11 @@ WEAK const PinMap PinMap_SPI_MISO[] = { {PB_14, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, {NC, NP, 0} }; -#endif -#ifdef HAL_SPI_MODULE_ENABLED WEAK const PinMap PinMap_SPI_SCLK[] = { {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, #if defined(STM32F103xE) || defined(STM32F103xG) - // {PB_3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_SPI1_ENABLE)}, + //{PB_3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_SPI1_ENABLE)}, {PB_3, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, #else {PB_3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_SPI1_ENABLE)}, @@ -350,13 +338,11 @@ WEAK const PinMap PinMap_SPI_SCLK[] = { {PB_13, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, {NC, NP, 0} }; -#endif -#ifdef HAL_SPI_MODULE_ENABLED WEAK const PinMap PinMap_SPI_SSEL[] = { {PA_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, #if defined(STM32F103xE) || defined(STM32F103xG) - // {PA_15, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_SPI1_ENABLE)}, + //{PA_15, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_SPI1_ENABLE)}, {PA_15, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, #else {PA_15, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_SPI1_ENABLE)}, @@ -375,9 +361,7 @@ WEAK const PinMap PinMap_CAN_RD[] = { {PD_0, CAN1, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, AFIO_CAN1_3)}, {NC, NP, 0} }; -#endif -#ifdef HAL_CAN_MODULE_ENABLED WEAK const PinMap PinMap_CAN_TD[] = { {PA_12, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, AFIO_NONE)}, {PB_9, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, AFIO_CAN1_2)}, diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103Vx/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_F103Vx/ldscript.ld index c9197c8b451a..a65b07d61c5f 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F103Vx/ldscript.ld +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103Vx/ldscript.ld @@ -162,7 +162,7 @@ SECTIONS . = ALIGN(4); .bss : { - /* This is used by the startup in order to initialize the .bss secion */ + /* This is used by the startup in order to initialize the .bss section */ _sbss = .; /* define a global symbol at bss start */ __bss_start__ = _sbss; *(.bss) diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103Vx/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_F103Vx/variant.h index b622b39376b9..496d8817a181 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F103Vx/variant.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103Vx/variant.h @@ -132,8 +132,12 @@ extern "C" { // Timer Definitions (optional) // Use TIM6/TIM7 when possible as servo and tone don't need GPIO output pin -#define TIMER_TONE TIM3 -#define TIMER_SERVO TIM2 +#ifndef TIMER_TONE + #define TIMER_TONE TIM6 +#endif +#ifndef TIMER_SERVO + #define TIMER_SERVO TIM7 +#endif // UART Definitions // Define here Serial instance number to map on Serial generic name diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103Zx/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_F103Zx/PeripheralPins.c index 5736e5206e09..0d7365c9c5ab 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F103Zx/PeripheralPins.c +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103Zx/PeripheralPins.c @@ -25,45 +25,45 @@ #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_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC2_IN0 - // {PA_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC3_IN0 + //{PA_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC2_IN0 + //{PA_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC3_IN0 {PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1 - // {PA_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC2_IN1 - // {PA_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC3_IN1 - // {PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2 + //{PA_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC2_IN1 + //{PA_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC3_IN1 + //{PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2 {PA_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC2_IN2 - // {PA_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC3_IN2 + //{PA_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC3_IN2 {PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3 - // {PA_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC2_IN3 - // {PA_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC3_IN3 - // {PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4 + //{PA_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC2_IN3 + //{PA_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC3_IN3 + //{PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4 {PA_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC2_IN4 {PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5 - // {PA_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC2_IN5 - // {PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6 + //{PA_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC2_IN5 + //{PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6 {PA_6, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC2_IN6 {PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7 - // {PA_7, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC2_IN7 - // {PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8 + //{PA_7, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC2_IN7 + //{PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8 {PB_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC2_IN8 {PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9 - // {PB_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC2_IN9 - // {PC_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10 + //{PB_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC2_IN9 + //{PC_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10 {PC_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC2_IN10 - // {PC_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC3_IN10 + //{PC_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC3_IN10 {PC_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11 - // {PC_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC2_IN11 - // {PC_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC3_IN11 - // {PC_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12 + //{PC_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC2_IN11 + //{PC_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC3_IN11 + //{PC_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12 {PC_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC2_IN12 - // {PC_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC3_IN12 + //{PC_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC3_IN12 {PC_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13 - // {PC_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC2_IN13 - // {PC_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC3_IN13 - // {PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14 + //{PC_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC2_IN13 + //{PC_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC3_IN13 + //{PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14 {PC_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC2_IN14 {PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15 - // {PC_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC2_IN15 + //{PC_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC2_IN15 {PF_6, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC3_IN4 {PF_7, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC3_IN5 {PF_8, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC3_IN6 @@ -92,9 +92,7 @@ WEAK const PinMap PinMap_I2C_SDA[] = { {PB_11, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, AFIO_NONE)}, {NC, NP, 0} }; -#endif -#ifdef HAL_I2C_MODULE_ENABLED WEAK const PinMap PinMap_I2C_SCL[] = { {PB_6, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, AFIO_NONE)}, {PB_8, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, AFIO_I2C1_ENABLE)}, @@ -108,86 +106,86 @@ WEAK const PinMap PinMap_I2C_SCL[] = { #ifdef HAL_TIM_MODULE_ENABLED WEAK const PinMap PinMap_PWM[] = { {PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM2_CH1 - // {PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_2, 1, 0)}, // TIM2_CH1 - // {PA_0, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM5_CH1 - // {PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM2_CH2 - // {PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_2, 2, 0)}, // TIM2_CH2 + //{PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_2, 1, 0)}, // TIM2_CH1 + //{PA_0, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM5_CH1 + //{PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM2_CH2 + //{PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_2, 2, 0)}, // TIM2_CH2 {PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM5_CH2 {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM2_CH3 - // {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_1, 3, 0)}, // TIM2_CH3 - // {PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM5_CH3 + //{PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_1, 3, 0)}, // TIM2_CH3 + //{PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM5_CH3 #ifdef STM32F103xG - // {PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM9_CH1 + //{PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM9_CH1 #endif - // {PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM2_CH4 - // {PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_1, 4, 0)}, // TIM2_CH4 + //{PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM2_CH4 + //{PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_1, 4, 0)}, // TIM2_CH4 {PA_3, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM5_CH4 #ifdef STM32F103xG - // {PA_3, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM9_CH2 + //{PA_3, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM9_CH2 #endif {PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM3_CH1 #ifdef STM32F103xG - // {PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM13_CH1 + //{PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM13_CH1 #endif - // {PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 1, 1)}, // TIM1_CH1N - // {PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM3_CH2 + //{PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 1, 1)}, // TIM1_CH1N + //{PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM3_CH2 {PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 1)}, // TIM8_CH1N #ifdef STM32F103xG - // {PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM14_CH1 + //{PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM14_CH1 #endif {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM1_CH1 - // {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 1, 0)}, // TIM1_CH1 + //{PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 1, 0)}, // TIM1_CH1 {PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM1_CH2 - // {PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 2, 0)}, // TIM1_CH2 + //{PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 2, 0)}, // TIM1_CH2 {PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM1_CH3 - // {PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 3, 0)}, // TIM1_CH3 + //{PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 3, 0)}, // TIM1_CH3 {PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM1_CH4 - // {PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 4, 0)}, // TIM1_CH4 + //{PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 4, 0)}, // TIM1_CH4 {PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_1, 1, 0)}, // TIM2_CH1 - // {PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_ENABLE, 1, 0)}, // TIM2_CH1 - // {PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 2, 1)}, // TIM1_CH2N + //{PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_ENABLE, 1, 0)}, // TIM2_CH1 + //{PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 2, 1)}, // TIM1_CH2N {PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM3_CH3 - // {PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_PARTIAL, 3, 0)}, // TIM3_CH3 + //{PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_PARTIAL, 3, 0)}, // TIM3_CH3 {PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 1)}, // TIM8_CH2N {PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 3, 1)}, // TIM1_CH3N - // {PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM3_CH4 - // {PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_PARTIAL, 4, 0)}, // TIM3_CH4 - // {PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 1)}, // TIM8_CH3N + //{PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM3_CH4 + //{PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_PARTIAL, 4, 0)}, // TIM3_CH4 + //{PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 1)}, // TIM8_CH3N {PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_1, 2, 0)}, // TIM2_CH2 - // {PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_ENABLE, 2, 0)}, // TIM2_CH2 + //{PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_ENABLE, 2, 0)}, // TIM2_CH2 {PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_PARTIAL, 1, 0)}, // TIM3_CH1 {PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_PARTIAL, 2, 0)}, // TIM3_CH2 {PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM4_CH1 {PB_7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM4_CH2 {PB_8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM4_CH3 #ifdef STM32F103xG - // {PB_8, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM10_CH1 + //{PB_8, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM10_CH1 #endif {PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM4_CH4 #ifdef STM32F103xG - // {PB_9, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM11_CH1 + //{PB_9, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM11_CH1 #endif - // {PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_2, 3, 0)}, // TIM2_CH3 + //{PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_2, 3, 0)}, // TIM2_CH3 {PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_ENABLE, 3, 0)}, // TIM2_CH3 - // {PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_2, 4, 0)}, // TIM2_CH4 + //{PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_2, 4, 0)}, // TIM2_CH4 {PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_ENABLE, 4, 0)}, // TIM2_CH4 {PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 1)}, // TIM1_CH1N {PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 1)}, // TIM1_CH2N #ifdef STM32F103xG - // {PB_14, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM12_CH1 + //{PB_14, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM12_CH1 #endif {PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 1)}, // TIM1_CH3N #ifdef STM32F103xG - // {PB_15, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM12_CH2 + //{PB_15, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM12_CH2 #endif - // {PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_ENABLE, 1, 0)}, // TIM3_CH1 + //{PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_ENABLE, 1, 0)}, // TIM3_CH1 {PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM8_CH1 - // {PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_ENABLE, 2, 0)}, // TIM3_CH2 + //{PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_ENABLE, 2, 0)}, // TIM3_CH2 {PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM8_CH2 {PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_ENABLE, 3, 0)}, // TIM3_CH3 - // {PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM8_CH3 + //{PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM8_CH3 {PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_ENABLE, 4, 0)}, // TIM3_CH4 - // {PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM8_CH4 + //{PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM8_CH4 {PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM4_ENABLE, 1, 0)}, // TIM4_CH1 {PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM4_ENABLE, 2, 0)}, // TIM4_CH2 {PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM4_ENABLE, 3, 0)}, // TIM4_CH3 @@ -222,47 +220,41 @@ WEAK const PinMap PinMap_UART_TX[] = { {PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART1_ENABLE)}, {PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, {PC_10, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, - // {PC_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART3_PARTIAL)}, + //{PC_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART3_PARTIAL)}, {PC_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, {PD_5, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART2_ENABLE)}, {PD_8, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART3_ENABLE)}, {NC, NP, 0} }; -#endif -#ifdef HAL_UART_MODULE_ENABLED WEAK const PinMap PinMap_UART_RX[] = { {PA_3, USART2, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_NONE)}, {PA_10, USART1, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_NONE)}, {PB_7, USART1, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_USART1_ENABLE)}, {PB_11, USART3, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_NONE)}, {PC_11, UART4, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_NONE)}, - // {PC_11, USART3, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_USART3_PARTIAL)}, + //{PC_11, USART3, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_USART3_PARTIAL)}, {PD_2, UART5, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_NONE)}, {PD_6, USART2, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_USART2_ENABLE)}, {PD_9, USART3, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_USART3_ENABLE)}, {NC, NP, 0} }; -#endif -#ifdef HAL_UART_MODULE_ENABLED WEAK const PinMap PinMap_UART_RTS[] = { {PA_1, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, {PA_12, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, {PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, - // {PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART3_PARTIAL)}, + //{PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART3_PARTIAL)}, {PD_4, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART2_ENABLE)}, {PD_12, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART3_ENABLE)}, {NC, NP, 0} }; -#endif -#ifdef HAL_UART_MODULE_ENABLED WEAK const PinMap PinMap_UART_CTS[] = { {PA_0, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, {PA_11, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, {PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, - // {PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART3_PARTIAL)}, + //{PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART3_PARTIAL)}, {PD_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART2_ENABLE)}, {PD_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART3_ENABLE)}, {NC, NP, 0} @@ -274,37 +266,31 @@ WEAK const PinMap PinMap_UART_CTS[] = { #ifdef HAL_SPI_MODULE_ENABLED WEAK const PinMap PinMap_SPI_MOSI[] = { {PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, - // {PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_SPI1_ENABLE)}, + //{PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_SPI1_ENABLE)}, {PB_5, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, {PB_15, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, {NC, NP, 0} }; -#endif -#ifdef HAL_SPI_MODULE_ENABLED WEAK const PinMap PinMap_SPI_MISO[] = { {PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, - // {PB_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_SPI1_ENABLE)}, + //{PB_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_SPI1_ENABLE)}, {PB_4, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, {PB_14, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, {NC, NP, 0} }; -#endif -#ifdef HAL_SPI_MODULE_ENABLED WEAK const PinMap PinMap_SPI_SCLK[] = { {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, - // {PB_3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_SPI1_ENABLE)}, + //{PB_3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_SPI1_ENABLE)}, {PB_3, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, {PB_13, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, {NC, NP, 0} }; -#endif -#ifdef HAL_SPI_MODULE_ENABLED WEAK const PinMap PinMap_SPI_SSEL[] = { {PA_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, - // {PA_15, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_SPI1_ENABLE)}, + //{PA_15, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_SPI1_ENABLE)}, {PA_15, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, {PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, {NC, NP, 0} @@ -320,9 +306,7 @@ WEAK const PinMap PinMap_CAN_RD[] = { {PD_0, CAN1, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, AFIO_CAN1_3)}, {NC, NP, 0} }; -#endif -#ifdef HAL_CAN_MODULE_ENABLED WEAK const PinMap PinMap_CAN_TD[] = { {PA_12, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, AFIO_NONE)}, {PB_9, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, AFIO_CAN1_2)}, @@ -353,10 +337,10 @@ WEAK const PinMap PinMap_USB[] = { #ifdef HAL_SD_MODULE_ENABLED WEAK const PinMap PinMap_SD[] = { - // {PB_8, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D4 - // {PB_9, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D5 - // {PC_6, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D6 - // {PC_7, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D7 + //{PB_8, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D4 + //{PB_9, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D5 + //{PC_6, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D6 + //{PC_7, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D7 {PC_8, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D0 {PC_9, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D1 {PC_10, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D2 diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103Zx/hal_conf_custom.h b/buildroot/share/PlatformIO/variants/MARLIN_F103Zx/hal_conf_custom.h index 014943f311ed..4e55fe1240f3 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F103Zx/hal_conf_custom.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103Zx/hal_conf_custom.h @@ -33,45 +33,44 @@ extern "C" { * and manage module deactivation */ #include "stm32yyxx_hal_conf.h" -#if 0 + /** * @brief This is the list of modules to be used in the HAL driver */ -#define HAL_MODULE_ENABLED -#define HAL_ADC_MODULE_ENABLED -#define HAL_CAN_MODULE_ENABLED -/*#define HAL_CAN_LEGACY_MODULE_ENABLED*/ -#define HAL_CEC_MODULE_ENABLED -#define HAL_CORTEX_MODULE_ENABLED -#define HAL_CRC_MODULE_ENABLED -#define HAL_DAC_MODULE_ENABLED -#define HAL_DMA_MODULE_ENABLED -#define HAL_ETH_MODULE_ENABLED -#define HAL_EXTI_MODULE_ENABLED -#define HAL_FLASH_MODULE_ENABLED -#define HAL_GPIO_MODULE_ENABLED -#define HAL_HCD_MODULE_ENABLED -#define HAL_I2C_MODULE_ENABLED -#define HAL_I2S_MODULE_ENABLED -#define HAL_IRDA_MODULE_ENABLED -#define HAL_IWDG_MODULE_ENABLED -#define HAL_NAND_MODULE_ENABLED -#define HAL_NOR_MODULE_ENABLED -#define HAL_PCCARD_MODULE_ENABLED -#define HAL_PCD_MODULE_ENABLED -#define HAL_PWR_MODULE_ENABLED -#define HAL_RCC_MODULE_ENABLED -#define HAL_RTC_MODULE_ENABLED -#define HAL_SD_MODULE_ENABLED -#define HAL_SMARTCARD_MODULE_ENABLED -#define HAL_SPI_MODULE_ENABLED -#define HAL_SRAM_MODULE_ENABLED -#define HAL_TIM_MODULE_ENABLED -#define HAL_UART_MODULE_ENABLED -#define HAL_USART_MODULE_ENABLED -#define HAL_WWDG_MODULE_ENABLED -#define HAL_MMC_MODULE_ENABLED -#endif +//#define HAL_MODULE_ENABLED +//#define HAL_ADC_MODULE_ENABLED +//#define HAL_CAN_MODULE_ENABLED +//#define HAL_CAN_LEGACY_MODULE_ENABLED +//#define HAL_CEC_MODULE_ENABLED +//#define HAL_CORTEX_MODULE_ENABLED +//#define HAL_CRC_MODULE_ENABLED +//#define HAL_DAC_MODULE_ENABLED +//#define HAL_DMA_MODULE_ENABLED +//#define HAL_ETH_MODULE_ENABLED +//#define HAL_EXTI_MODULE_ENABLED +//#define HAL_FLASH_MODULE_ENABLED +//#define HAL_GPIO_MODULE_ENABLED +//#define HAL_HCD_MODULE_ENABLED +//#define HAL_I2C_MODULE_ENABLED +//#define HAL_I2S_MODULE_ENABLED +//#define HAL_IRDA_MODULE_ENABLED +//#define HAL_IWDG_MODULE_ENABLED +//#define HAL_NAND_MODULE_ENABLED +//#define HAL_NOR_MODULE_ENABLED +//#define HAL_PCCARD_MODULE_ENABLED +//#define HAL_PCD_MODULE_ENABLED +//#define HAL_PWR_MODULE_ENABLED +//#define HAL_RCC_MODULE_ENABLED +//#define HAL_RTC_MODULE_ENABLED +//#define HAL_SD_MODULE_ENABLED +//#define HAL_SMARTCARD_MODULE_ENABLED +//#define HAL_SPI_MODULE_ENABLED +//#define HAL_SRAM_MODULE_ENABLED +//#define HAL_TIM_MODULE_ENABLED +//#define HAL_UART_MODULE_ENABLED +//#define HAL_USART_MODULE_ENABLED +//#define HAL_WWDG_MODULE_ENABLED +//#define HAL_MMC_MODULE_ENABLED /* ########################## Oscillator Values adaptation ####################*/ /** diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103Zx/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_F103Zx/ldscript.ld index 09088b622c87..cc4b323f763a 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F103Zx/ldscript.ld +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103Zx/ldscript.ld @@ -162,7 +162,7 @@ SECTIONS . = ALIGN(4); .bss : { - /* This is used by the startup in order to initialize the .bss secion */ + /* This is used by the startup in order to initialize the .bss section */ _sbss = .; /* define a global symbol at bss start */ __bss_start__ = _sbss; *(.bss) diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F407VE/hal_conf_custom.h b/buildroot/share/PlatformIO/variants/MARLIN_F407VE/hal_conf_custom.h index 92e9fecb4d63..1252bc705952 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F407VE/hal_conf_custom.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_F407VE/hal_conf_custom.h @@ -33,55 +33,54 @@ extern "C" { */ #define HAL_MODULE_ENABLED #define HAL_ADC_MODULE_ENABLED -/* #define HAL_CAN_MODULE_ENABLED */ -/* #define HAL_CAN_LEGACY_MODULE_ENABLED */ #define HAL_CRC_MODULE_ENABLED -/* #define HAL_CEC_MODULE_ENABLED */ -/* #define HAL_CRYP_MODULE_ENABLED */ #define HAL_DAC_MODULE_ENABLED -/* #define HAL_DCMI_MODULE_ENABLED */ #define HAL_DMA_MODULE_ENABLED -/* #define HAL_DMA2D_MODULE_ENABLED */ -/* #define HAL_ETH_MODULE_ENABLED */ #define HAL_FLASH_MODULE_ENABLED -/* #define HAL_NAND_MODULE_ENABLED */ -/* #define HAL_NOR_MODULE_ENABLED */ -/* #define HAL_PCCARD_MODULE_ENABLED */ -/* #define HAL_SRAM_MODULE_ENABLED */ -/* #define HAL_SDRAM_MODULE_ENABLED */ -/* #define HAL_HASH_MODULE_ENABLED */ #define HAL_GPIO_MODULE_ENABLED -/* #define HAL_EXTI_MODULE_ENABLED */ #define HAL_I2C_MODULE_ENABLED -/* #define HAL_SMBUS_MODULE_ENABLED */ -/* #define HAL_I2S_MODULE_ENABLED */ -/* #define HAL_IWDG_MODULE_ENABLED */ -/* #define HAL_LTDC_MODULE_ENABLED */ -/* #define HAL_DSI_MODULE_ENABLED */ #define HAL_PWR_MODULE_ENABLED -/* #define HAL_QSPI_MODULE_ENABLED */ #define HAL_RCC_MODULE_ENABLED -/* #define HAL_RNG_MODULE_ENABLED */ #define HAL_RTC_MODULE_ENABLED -/* #define HAL_SAI_MODULE_ENABLED */ #define HAL_SD_MODULE_ENABLED #define HAL_SPI_MODULE_ENABLED #define HAL_TIM_MODULE_ENABLED -/* #define HAL_UART_MODULE_ENABLED */ -/* #define HAL_USART_MODULE_ENABLED */ -/* #define HAL_IRDA_MODULE_ENABLED */ -/* #define HAL_SMARTCARD_MODULE_ENABLED */ -/* #define HAL_WWDG_MODULE_ENABLED */ #define HAL_CORTEX_MODULE_ENABLED -#ifndef HAL_PCD_MODULE_ENABLED - #define HAL_PCD_MODULE_ENABLED //Since STM32 v3.10700.191028 this is automatically added if any type of USB is enabled (as in Arduino IDE) -#endif -/* #define HAL_HCD_MODULE_ENABLED */ -/* #define HAL_FMPI2C_MODULE_ENABLED */ -/* #define HAL_SPDIFRX_MODULE_ENABLED */ -/* #define HAL_DFSDM_MODULE_ENABLED */ -/* #define HAL_LPTIM_MODULE_ENABLED */ -/* #define HAL_MMC_MODULE_ENABLED */ +//#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_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_IWDG_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_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 ##################### */ /** @@ -204,7 +203,7 @@ in voltage and temperature. */ * @brief Uncomment the line below to expanse the "assert_param" macro in the * HAL drivers code */ -/* #define USE_FULL_ASSERT 1U */ +//#define USE_FULL_ASSERT 1U /* ################## Ethernet peripheral configuration ##################### */ @@ -492,5 +491,4 @@ void assert_failed(uint8_t *file, uint32_t line); #endif /* __STM32F4xx_HAL_CONF_CUSTOM_H */ - /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F407VE/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_F407VE/ldscript.ld index efe2db5cd472..68b65973226f 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F407VE/ldscript.ld +++ b/buildroot/share/PlatformIO/variants/MARLIN_F407VE/ldscript.ld @@ -169,7 +169,7 @@ SECTIONS . = ALIGN(4); .bss : { - /* This is used by the startup in order to initialize the .bss secion */ + /* This is used by the startup in order to initialize the .bss section */ _sbss = .; /* define a global symbol at bss start */ __bss_start__ = _sbss; *(.bss) diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F446VE/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_F446VE/PeripheralPins.c new file mode 100644 index 000000000000..54439083d4c7 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_F446VE/PeripheralPins.c @@ -0,0 +1,426 @@ +/* + ******************************************************************************* + * Copyright (c) 2020, STMicroelectronics + * All rights reserved. + * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ******************************************************************************* + * Automatically generated from STM32F446V(C-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_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC2_IN0 + //{PA_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC3_IN0 + {PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1 + //{PA_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC2_IN1 + //{PA_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC3_IN1 + {PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2 + //{PA_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC2_IN2 + //{PA_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC3_IN2 + {PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3 + //{PA_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC2_IN3 + //{PA_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC3_IN3 + {PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4 + //{PA_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC2_IN4 + {PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5 + //{PA_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC2_IN5 + {PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6 + //{PA_6, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC2_IN6 + {PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7 + //{PA_7, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC2_IN7 + {PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8 + //{PB_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC2_IN8 + {PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9 + //{PB_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC2_IN9 + {PC_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10 + //{PC_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC2_IN10 + //{PC_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC3_IN10 + {PC_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11 + //{PC_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC2_IN11 + //{PC_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC3_IN11 + {PC_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12 + //{PC_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC2_IN12 + //{PC_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC3_IN12 + {PC_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13 + //{PC_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC2_IN13 + //{PC_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC3_IN13 + {PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14 + //{PC_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC2_IN14 + {PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15 + //{PC_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC2_IN15 + {NC, NP, 0} +}; +#endif + +//*** DAC *** + +#ifdef HAL_DAC_MODULE_ENABLED +WEAK const PinMap PinMap_DAC[] = { + //{PA_4, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // DAC_OUT1 + //{PA_5, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // DAC_OUT2 - LD2 + {NC, NP, 0} +}; +#endif + +//*** 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_AF4_I2C2)}, + //{PB_4, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_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)}, + //{PC_12, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + {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_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + //{PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + //{PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 + //{PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + //{PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + //{PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + //{PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 + {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 + {PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 + {PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 + //{PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 + {PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + //{PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + //{PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 + //{PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N + //{PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + //{PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 + //{PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N + {PB_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_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, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + //{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, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 + //{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_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 + //{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 + {PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + //{PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 + {PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + //{PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 + {PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 + //{PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 0)}, // TIM8_CH3 + {PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 + //{PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 4, 0)}, // TIM8_CH4 + {PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 + {PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 + {PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 + {PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 + //{PE_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 + //{PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 + //{PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + //{PE_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 + //{PE_12, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + //{PE_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 + {PE_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 + {NC, NP, 0} +}; +#endif + +//*** SERIAL *** + +#ifdef HAL_UART_MODULE_ENABLED +WEAK const PinMap PinMap_UART_TX[] = { + //{PA_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + //{PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + //{PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PC_6, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + //{PC_10, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PC_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PC_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + //{PD_5, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + //{PD_8, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PE_8, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_UART_RX[] = { + //{PA_1, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PA_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PA_10, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + //{PB_7, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + //{PC_5, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PC_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + //{PC_11, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PC_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PD_2, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + //{PD_6, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + //{PD_9, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PE_7, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + {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)}, + //{PA_15, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PC_8, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART5)}, + //{PD_4, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + //{PD_12, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {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)}, + //{PB_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PC_9, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART5)}, + //{PD_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + //{PD_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {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_0, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI3)}, + //{PB_2, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI3)}, + //{PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + //{PB_5, 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_1, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI2)}, + //{PC_1, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI3)}, + //{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)}, + //{PD_0, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + //{PD_6, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI3)}, + //{PE_6, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + //{PE_14, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + {NC, NP, 0} +}; + +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)}, + //{PD_0, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + //{PE_5, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + //{PE_13, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_SPI_SCLK[] = { + {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + //{PA_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + //{PB_3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + //{PB_3, 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_7, 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)}, + //{PD_3, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + //{PE_2, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + //{PE_12, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + {NC, NP, 0} +}; + +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_4, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI2)}, + //{PB_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + //{PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + //{PD_1, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI2)}, + //{PE_4, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + //{PE_11, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + {NC, NP, 0} +}; +#endif + +//*** CAN *** + +#ifdef HAL_CAN_MODULE_ENABLED +WEAK const PinMap PinMap_CAN_RD[] = { + //{PA_11, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, + //{PB_5, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, + //{PB_8, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, + //{PB_12, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, + //{PD_0, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_CAN_TD[] = { + //{PA_12, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, + //{PB_6, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, + //{PB_9, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, + //{PB_13, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, + //{PD_1, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, + {NC, NP, 0} +}; +#endif + +//*** No ETHERNET *** + +//*** QUADSPI *** + +#ifdef HAL_QSPI_MODULE_ENABLED +WEAK const PinMap PinMap_QUADSPI_DATA0[] = { + //{PC_9, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK1_IO0 + //{PD_11, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK1_IO0 + //{PE_7, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_QSPI)}, // QUADSPI_BK2_IO0 + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_QUADSPI_DATA1[] = { + //{PC_10, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK1_IO1 + //{PD_12, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK1_IO1 + //{PE_8, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_QSPI)}, // QUADSPI_BK2_IO1 + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_QUADSPI_DATA2[] = { + //{PE_2, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK1_IO2 + //{PE_9, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_QSPI)}, // QUADSPI_BK2_IO2 + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_QUADSPI_DATA3[] = { + {PA_1, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK1_IO3 + //{PD_13, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK1_IO3 + //{PE_10, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_QSPI)}, // QUADSPI_BK2_IO3 + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_QUADSPI_SCLK[] = { + //{PB_2, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_CLK + //{PD_3, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_CLK + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_QUADSPI_SSEL[] = { + //{PB_6, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_QSPI)}, // QUADSPI_BK1_NCS + //{PC_11, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK2_NCS + {NC, NP, 0} +}; +#endif + +//*** USB *** + +#ifdef HAL_PCD_MODULE_ENABLED +WEAK const PinMap PinMap_USB_OTG_FS[] = { + //{PA_8, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_SOF + //{PA_9, USB_OTG_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_FS_VBUS + //{PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_ID + {PA_11, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DM + {PA_12, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DP + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_USB_OTG_HS[] = { +#ifdef USE_USB_HS_IN_FS + //{PA_4, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_SOF + //{PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_ID + //{PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_HS_VBUS + //{PB_14, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DM + //{PB_15, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DP +#else + //{PA_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D0 + //{PA_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_CK + //{PB_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D1 + //{PB_1, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D2 + //{PB_2, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D4 + //{PB_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D7 + //{PB_10, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D3 + //{PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D5 + //{PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D6 + //{PC_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_STP + //{PC_2, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_DIR + //{PC_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_NXT +#endif /* USE_USB_HS_IN_FS */ + {NC, NP, 0} +}; +#endif + +//*** SD *** + +#ifdef HAL_SD_MODULE_ENABLED +WEAK const PinMap PinMap_SD[] = { + //{PB_0, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D1 + //{PB_1, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D2 + //{PB_2, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF12_SDIO)}, // SDIO_CK + //{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_F446VE/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_F446VE/PinNamesVar.h new file mode 100644 index 000000000000..bff3f2134987 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_F446VE/PinNamesVar.h @@ -0,0 +1,30 @@ +/* SYS_WKUP */ +#ifdef PWR_WAKEUP_PIN1 + SYS_WKUP1 = PA_0, /* SYS_WKUP0 */ +#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_DM = PA_11, + USB_OTG_FS_DP = PA_12, +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F446VE/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_F446VE/ldscript.ld new file mode 100644 index 000000000000..a375232d5981 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_F446VE/ldscript.ld @@ -0,0 +1,184 @@ +/* +***************************************************************************** +** +** File : lscript.ld +** +** Abstract : Linker script for STM32F446VE Device with +** 512KByte FLASH, 128KByte 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 = 0x20000000 + LD_MAX_DATA_SIZE; /* 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 +{ +RAM (xrw) : ORIGIN = 0x20000000, LENGTH = LD_MAX_DATA_SIZE +FLASH (rx) : ORIGIN = 0x08000000 + LD_FLASH_OFFSET, LENGTH = LD_MAX_SIZE - LD_FLASH_OFFSET +} + +/* 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): + { + . = 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 + + /*_siccmram = LOADADDR(.ccmram);*/ + + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss section */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* User_heap_stack section, used to check that there is enough RAM left */ + ._user_heap_stack : + { + . = ALIGN(4); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(4); + } >RAM + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F446VE/variant.cpp b/buildroot/share/PlatformIO/variants/MARLIN_F446VE/variant.cpp new file mode 100644 index 000000000000..16e11f0a91ee --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_F446VE/variant.cpp @@ -0,0 +1,212 @@ +/* + Copyright (c) 2011 Arduino. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include "pins_arduino.h" + +#ifdef __cplusplus +extern "C" { +#endif + +// Pin number +const PinName digitalPin[] = { + PA_0, //D0 //A7 + PA_1, //D1 //A8 + PA_2, //D2 //A9 + PA_3, //D3 //A0 + PA_4, //D4 //A1 + PA_5, //D5 //A10 + PA_6, //D6 //A11 + PA_7, //D7 //A12 + PA_8, //D8 + PA_9, //D9 + PA_10, //D10 + PA_11, //D11 + PA_12, //D12 + PA_13, //D13 + PA_14, //D14 + PA_15, //D15 + PB_0, //D16 //A13 + PB_1, //D17 //A14 + PB_2, //D18 + PB_3, //D19 + PB_4, //D20 + PB_5, //D21 + PB_6, //D22 + PB_7, //D23 + PB_8, //D24 + PB_9, //D25 + PB_10, //D26 + PB_11, //D27 + PB_12, //D28 + PB_13, //D29 + PB_14, //D30 + PB_15, //D31 + PC_0, //D32 //A2 + PC_1, //D33 //A3 + PC_2, //D34 //A4 + PC_3, //D35 //A5 + PC_4, //D36 //A6 + PC_5, //D37 //A15 + PC_6, //D38 + PC_7, //D39 + PC_8, //D40 + PC_9, //D41 + PC_10, //D42 + PC_11, //D43 + PC_12, //D44 + PC_13, //D45 + PC_14, //D46 + PC_15, //D47 + PD_0, //D48 + PD_1, //D49 + PD_2, //D50 + PD_3, //D51 + PD_4, //D52 + PD_5, //D53 + PD_6, //D54 + PD_7, //D55 + PD_8, //D56 + PD_9, //D57 + PD_10, //D58 + PD_11, //D59 + PD_12, //D60 + PD_13, //D61 + PD_14, //D62 + PD_15, //D63 + PE_0, //D64 + PE_1, //D65 + PE_2, //D66 + PE_3, //D67 + PE_4, //D68 + PE_5, //D69 + PE_6, //D70 + PE_7, //D71 + PE_8, //D72 + PE_9, //D73 + PE_10, //D74 + PE_11, //D75 + PE_12, //D76 + PE_13, //D77 + PE_14, //D78 + PE_15 //D79 +}; + +// Analog (Ax) pin number array +const uint32_t analogInputPin[] = { + 3, //D3 //A0 + 4, //D4 //A1 + 32, //D32 //A2 + 33, //D33 //A3 + 34, //D34 //A4 + 35, //D35 //A5 + 36, //D36 //A6 + 0, //D0 //A7 + 1, //D1 //A8 + 2, //D2 //A9 + 5, //D5 //A10 + 6, //D6 //A11 + 7, //D7 //A12 + 16, //D16 //A13 + 17, //D17 //A14 + 37 //D37 //A15 +}; + +#ifdef __cplusplus +} +#endif + +// ---------------------------------------------------------------------------- + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @brief System Clock Configuration + * The system Clock is configured as follow : + * System Clock source = PLL (HSE) + * SYSCLK(Hz) = 168000000 + * HCLK(Hz) = 168000000 + * AHB Prescaler = 1 + * APB1 Prescaler = 4 + * APB2 Prescaler = 2 + * HSE Frequency(Hz) = 8000000 + * PLL_M = 8 + * PLL_N = 336 + * PLL_P = 2 + * PLL_Q = 7 + * VDD(V) = 3.3 + * Main regulator output voltage = Scale1 mode + * Flash Latency(WS) = 5 + * @param None + * @retval None + */ +WEAK void SystemClock_Config(void) +{ + RCC_ClkInitTypeDef RCC_ClkInitStruct; + RCC_OscInitTypeDef RCC_OscInitStruct; + RCC_PeriphCLKInitTypeDef PeriphClkInitStruct; + + + /* Enable Power Control clock */ + __HAL_RCC_PWR_CLK_ENABLE(); + +#ifdef HAL_PWR_MODULE_ENABLED + /* The voltage scaling allows optimizing the power consumption when the device is + clocked below the maximum system frequency, to update the voltage scaling value + regarding system frequency refer to product datasheet. */ + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); +#endif + + /* Enable HSE Oscillator and activate PLL with HSE as source */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_ON; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLM = 6; + RCC_OscInitStruct.PLL.PLLN = 180; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; + RCC_OscInitStruct.PLL.PLLQ = 7; + RCC_OscInitStruct.PLL.PLLR = 2; + HAL_RCC_OscConfig(&RCC_OscInitStruct); + + HAL_PWREx_EnableOverDrive(); + + /* 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_PLLRCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; + HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5); + + PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_CLK48; + PeriphClkInitStruct.PLLSAI.PLLSAIM = 6; + PeriphClkInitStruct.PLLSAI.PLLSAIN = 96; + PeriphClkInitStruct.PLLSAI.PLLSAIQ = 2; + PeriphClkInitStruct.PLLSAI.PLLSAIP = RCC_PLLSAIP_DIV4; + PeriphClkInitStruct.PLLSAIDivQ = 1; + PeriphClkInitStruct.Clk48ClockSelection = RCC_CLK48CLKSOURCE_PLLSAIP; + HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct); +} + +#ifdef __cplusplus +} +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F446VE/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_F446VE/variant.h new file mode 100644 index 000000000000..f00cc5f61235 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_F446VE/variant.h @@ -0,0 +1,186 @@ +/* + Copyright (c) 2011 Arduino. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _VARIANT_ARDUINO_STM32_ +#define _VARIANT_ARDUINO_STM32_ + +#ifdef __cplusplus +extern "C" { +#endif // __cplusplus + +/*---------------------------------------------------------------------------- + * Pins + *----------------------------------------------------------------------------*/ + +#define PA0 PIN_A7 //D0 +#define PA1 PIN_A8 //D1 +#define PA2 PIN_A9 //D2 +#define PA3 PIN_A0 //D3 +#define PA4 PIN_A1 //D4 +#define PA5 PIN_A10 //D5 +#define PA6 PIN_A11 //D6 +#define PA7 PIN_A12 //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 PIN_A13 //D16 +#define PB1 PIN_A14 //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 PIN_A2 //D32 +#define PC1 PIN_A3 //D33 +#define PC2 PIN_A4 //D34 +#define PC3 PIN_A5 //D35 +#define PC4 PIN_A6 //D36 +#define PC5 PIN_A15 //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 + +// This must be a literal +#define NUM_DIGITAL_PINS 80 +// This must be a literal with a value less than or equal to to MAX_ANALOG_INPUTS +#define NUM_ANALOG_INPUTS 16 + +// PWM resolution +#define PWM_FREQUENCY 20000 // >= 20 Khz => inaudible noise for fans +#define PWM_MAX_DUTY_CYCLE 255 + +// On-board LED pin number +#define LED_BUILTIN PB14 +#define LED_HEARTBEAT LED_BUILTIN + +// SPI Definitions +#define PIN_SPI_SS PA4 +#define PIN_SPI_MOSI PA7 +#define PIN_SPI_MISO PA6 +#define PIN_SPI_SCK PA5 + +// I2C Definitions +#define PIN_WIRE_SDA PB9 +#define PIN_WIRE_SCL PB8 + +// Timer Definitions +// Use TIM6/TIM7 when possible as servo and tone don't need GPIO output pin +#ifndef TIMER_TONE +#define TIMER_TONE TIM6 +#endif + +#ifndef TIMER_SERVO +#define TIMER_SERVO TIM7 +#endif + +#ifndef TIMER_SERIAL +#define TIMER_SERIAL TIM9 +#endif + +// UART Definitions +#define SERIAL_UART_INSTANCE 1 // Connected to EXP3 header + +// Default pin used for 'Serial' instance (ex: ST-Link) +// Mandatory for Firmata +#define PIN_SERIAL_RX PA10 +#define PIN_SERIAL_TX PA9 + +/* HAL configuration */ +#define HSE_VALUE 12000000U + +#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_OPEN Serial +#endif + +#endif /* _VARIANT_ARDUINO_STM32_ */ diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F4x7Vx/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_F4x7Vx/PeripheralPins.c new file mode 100644 index 000000000000..83e71035fad5 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_F4x7Vx/PeripheralPins.c @@ -0,0 +1,394 @@ +/* + ******************************************************************************* + * Copyright (c) 2019, STMicroelectronics + * All rights reserved. + * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ******************************************************************************* + * Automatically generated from STM32F407V(E-G)Tx.xml + */ +#include "Arduino.h" +#include "PeripheralPins.h" + +/** + * Variant for: mks_robin_pro2, mks_robin_nano_v3, Anet_ET4_OpenBLT + */ + +/* ===== + * 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_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC2_IN0 + //{PA_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC3_IN0 + {PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1 + //{PA_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC2_IN1 + //{PA_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC3_IN1 + {PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2 + //{PA_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC2_IN2 + //{PA_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC3_IN2 + {PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3 + //{PA_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC2_IN3 + //{PA_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC3_IN3 + {PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4 + //{PA_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC2_IN4 + {PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5 + //{PA_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC2_IN5 + {PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6 + //{PA_6, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC2_IN6 + {PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7 + //{PA_7, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC2_IN7 + {PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8 + //{PB_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC2_IN8 + {PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9 + //{PB_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC2_IN9 + {PC_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10 + //{PC_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC2_IN10 + //{PC_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC3_IN10 + {PC_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11 + //{PC_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC2_IN11 + //{PC_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC3_IN11 + {PC_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12 + //{PC_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC2_IN12 + //{PC_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC3_IN12 + {PC_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13 + //{PC_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC2_IN13 + //{PC_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC3_IN13 + {PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14 + //{PC_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC2_IN14 + {PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15 + //{PC_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC2_IN15 + {NC, NP, 0} +}; +#endif + +//*** DAC *** + +#ifdef HAL_DAC_MODULE_ENABLED +WEAK const PinMap PinMap_DAC[] = { + {PA_4, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // DAC_OUT1 + {PA_5, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // DAC_OUT2 + {NC, NP, 0} +}; +#endif + +//*** I2C *** + +#ifdef HAL_I2C_MODULE_ENABLED +WEAK const PinMap PinMap_I2C_SDA[] = { + {PB_7, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, + {PB_9, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, + {PB_11, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + {PC_9, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, + {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 +// Some pins can perform PWM from more than one timer. These were selected to utilize as many channels as +// possible from timers which were already dedicated to PWM output. + +// TIM1 = Pins are using for OTG FS +// TIM2 = [HEATER_BED], TIM2 is used OTG HS SOF +// TIM6 = Tone +// TIM8 = [FAN0, HEATER_1] OTG HS +// TIM7 = Servo +// TIM9 = [HEATER_0, ] +// TIM1, TIM8, TIM12 = Pins are using for OTG HS +// No timer = [FAN1 ] + +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_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + //{PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + {PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 + //{PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + //{PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + //{PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + {PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 + {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 + {PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 + {PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 + //{PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 + {PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + //{PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + //{PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 + {PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N + //{PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + //{PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 + {PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N + {PB_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_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_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 + {PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + //{PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + //{PB_14, 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 + //{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 + {PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + //{PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 + //{PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + {PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 + {PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 + //{PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 0)}, // TIM8_CH3 + //{PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 + {PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 4, 0)}, // TIM8_CH4 + {PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 + {PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 + {PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 + {PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 + {PE_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 + {PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 + {PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + {PE_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 + {PE_12, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + {PE_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 + {PE_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 + {NC, NP, 0} +}; +#endif + +//*** SERIAL *** + +#ifdef HAL_UART_MODULE_ENABLED +WEAK const PinMap PinMap_UART_TX[] = { + {PA_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PC_6, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + {PC_10, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PC_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PC_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + {PD_5, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PD_8, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_UART_RX[] = { + {PA_1, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PA_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PA_10, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PB_7, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PB_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PC_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + //{PC_11, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PC_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PD_2, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + {PD_6, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PD_9, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {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)}, + //{PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PD_4, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PD_12, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {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)}, + {PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PD_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PD_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {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 + +//*** CAN *** + +#ifdef HAL_CAN_MODULE_ENABLED +WEAK const PinMap PinMap_CAN_RD[] = { + {PA_11, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, + {PB_5, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, + {PB_8, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, + {PB_12, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, + {PD_0, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_CAN_TD[] = { + {PA_12, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, + {PB_6, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, + {PB_9, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, + {PB_13, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, + {PD_1, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, + {NC, NP, 0} +}; +#endif + +//*** ETHERNET *** + +#ifdef HAL_ETH_MODULE_ENABLED +WEAK const PinMap PinMap_Ethernet[] = { + {PA_0, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_CRS + {PA_1, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_REF_CLK|ETH_RX_CLK + {PA_2, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_MDIO + {PA_3, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_COL + {PA_7, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_CRS_DV|ETH_RX_DV + {PB_0, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD2 + {PB_1, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD3 + {PB_5, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_PPS_OUT + {PB_8, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD3 + {PB_10, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RX_ER + {PB_11, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TX_EN + {PB_12, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD0 + {PB_13, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD1 + {PC_1, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_MDC + {PC_2, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD2 + {PC_3, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TX_CLK + {PC_4, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD0 + {PC_5, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD1 + {PE_2, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD3 + {NC, NP, 0} +}; +#endif + +//*** No QUADSPI *** + +//*** USB *** + +#ifdef HAL_PCD_MODULE_ENABLED +WEAK const PinMap PinMap_USB_OTG_FS[] = { + //{PA_8, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_SOF + //{PA_9, USB_OTG_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_FS_VBUS + //{PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_ID + {PA_11, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DM + {PA_12, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DP + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_USB_OTG_HS[] = { +#ifdef USE_USB_HS_IN_FS + //{PA_4, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_SOF + //{PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_ID + //{PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_HS_VBUS + {PB_14, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DM + {PB_15, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DP +#else + {PA_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D0 + {PA_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_CK + {PB_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D1 + {PB_1, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D2 + {PB_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D7 + {PB_10, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D3 + {PB_11, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D4 + {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D5 + {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D6 + {PC_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_STP + {PC_2, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_DIR + {PC_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_NXT +#endif /* USE_USB_HS_IN_FS */ + {NC, NP, 0} +}; +#endif + +//*** SD *** + +#ifdef HAL_SD_MODULE_ENABLED +WEAK const PinMap PinMap_SD[] = { + {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_F4x7Vx/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_F4x7Vx/PinNamesVar.h new file mode 100644 index 000000000000..24248859373b --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_F4x7Vx/PinNamesVar.h @@ -0,0 +1,50 @@ +/* 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, + USB_OTG_HS_ULPI_D0 = PA_3, + USB_OTG_HS_SOF = PA_4, + USB_OTG_HS_ULPI_CK = PA_5, + USB_OTG_HS_ULPI_D1 = PB_0, + USB_OTG_HS_ULPI_D2 = PB_1, + USB_OTG_HS_ULPI_D7 = PB_5, + USB_OTG_HS_ULPI_D3 = PB_10, + USB_OTG_HS_ULPI_D4 = PB_11, + USB_OTG_HS_ID = PB_12, + USB_OTG_HS_ULPI_D5 = PB_12, + USB_OTG_HS_ULPI_D6 = PB_13, + USB_OTG_HS_VBUS = PB_13, + USB_OTG_HS_DM = PB_14, + USB_OTG_HS_DP = PB_15, + USB_OTG_HS_ULPI_STP = PC_0, + USB_OTG_HS_ULPI_DIR = PC_2, + USB_OTG_HS_ULPI_NXT = PC_3, +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F4x7Vx/hal_conf_extra.h b/buildroot/share/PlatformIO/variants/MARLIN_F4x7Vx/hal_conf_extra.h new file mode 100644 index 000000000000..0c44f0874224 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_F4x7Vx/hal_conf_extra.h @@ -0,0 +1,496 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_conf_template.h + * @author MCD Application Team + * @brief HAL configuration template file. + * This file should be copied to the application folder and renamed + * to stm32f4xx_hal_conf.h. + ****************************************************************************** + * @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_H +#define __STM32F4xx_HAL_CONF_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/* ########################## Module Selection ############################## */ +/** + * @brief This is the list of modules to be used in the HAL driver + */ +#define HAL_MODULE_ENABLED +#define HAL_ADC_MODULE_ENABLED +#define HAL_CAN_LEGACY_MODULE_ENABLED +#define HAL_CRC_MODULE_ENABLED +#define HAL_DAC_MODULE_ENABLED +#define HAL_DMA_MODULE_ENABLED +#define HAL_GPIO_MODULE_ENABLED +#define HAL_I2C_MODULE_ENABLED +#define HAL_PWR_MODULE_ENABLED +#define HAL_RCC_MODULE_ENABLED +#define HAL_SPI_MODULE_ENABLED +#define HAL_TIM_MODULE_ENABLED +#define HAL_USART_MODULE_ENABLED +#define HAL_CORTEX_MODULE_ENABLED +//#define HAL_UART_MODULE_ENABLED +//#define HAL_PCD_MODULE_ENABLED + +//#define HAL_CAN_MODULE_ENABLED +//#define HAL_CEC_MODULE_ENABLED +//#define HAL_CRYP_MODULE_ENABLED +//#define HAL_DCMI_MODULE_ENABLED +//#define HAL_DMA2D_MODULE_ENABLED +//#define HAL_ETH_MODULE_ENABLED +//#define HAL_FLASH_MODULE_ENABLED +//#define HAL_NAND_MODULE_ENABLED +//#define HAL_NOR_MODULE_ENABLED +//#define HAL_PCCARD_MODULE_ENABLED +//#define HAL_SRAM_MODULE_ENABLED +//#define HAL_SDRAM_MODULE_ENABLED +//#define HAL_HASH_MODULE_ENABLED +//#define HAL_EXTI_MODULE_ENABLED +//#define HAL_SMBUS_MODULE_ENABLED +//#define HAL_I2S_MODULE_ENABLED +//#define HAL_IWDG_MODULE_ENABLED +//#define HAL_LTDC_MODULE_ENABLED +//#define HAL_DSI_MODULE_ENABLED +//#define HAL_QSPI_MODULE_ENABLED +//#define HAL_RNG_MODULE_ENABLED +//#define HAL_RTC_MODULE_ENABLED +//#define HAL_SAI_MODULE_ENABLED +//#define HAL_SD_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). + */ +#if !defined (HSE_VALUE) + #define HSE_VALUE 25000000U /*!< Value of the External oscillator in Hz */ +#endif /* HSE_VALUE */ + +#if !defined (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). + */ +#if !defined (HSI_VALUE) + #define HSI_VALUE 16000000U /*!< Value of the Internal oscillator in Hz */ +#endif /* HSI_VALUE */ + +/** + * @brief Internal Low Speed oscillator (LSI) value. + */ +#if !defined (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. + */ +#if !defined (LSE_VALUE) + #define LSE_VALUE 32768U /*!< Value of the External Low Speed oscillator in Hz */ +#endif /* LSE_VALUE */ + +#if !defined (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. + */ +#if !defined (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 + */ +#define VDD_VALUE 3300U /*!< Value of VDD in mv */ +#define TICK_INT_PRIORITY 0x0FU /*!< tick interrupt priority */ +#define USE_RTOS 0U +#define PREFETCH_ENABLE 1U +#define INSTRUCTION_CACHE_ENABLE 1U +#define DATA_CACHE_ENABLE 1U + +#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 4U /* 4 Rx buffers of size ETH_RX_BUF_SIZE */ +#define ETH_TXBUFNB 4U /* 4 Tx buffers of size ETH_TX_BUF_SIZE */ + +/* Section 2: PHY configuration section */ + +/* DP83848 PHY 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)0x0010) /*!< PHY status register Offset */ +#define PHY_MICR ((uint16_t)0x0011) /*!< MII Interrupt Control Register */ +#define PHY_MISR ((uint16_t)0x0012) /*!< MII Interrupt Status and Misc. Control Register */ + +#define PHY_LINK_STATUS ((uint16_t)0x0001) /*!< PHY Link mask */ +#define PHY_SPEED_STATUS ((uint16_t)0x0002) /*!< PHY Speed mask */ +#define PHY_DUPLEX_STATUS ((uint16_t)0x0004) /*!< PHY Duplex mask */ + +#define PHY_MICR_INT_EN ((uint16_t)0x0002) /*!< PHY Enable interrupts */ +#define PHY_MICR_INT_OE ((uint16_t)0x0001) /*!< PHY Enable output interrupt events */ + +#define PHY_MISR_LINK_INT_EN ((uint16_t)0x0020) /*!< Enable Interrupt on change of link status */ +#define PHY_LINK_INTERRUPT ((uint16_t)0x2000) /*!< PHY link status interrupt 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 +*/ + +#define USE_SPI_CRC 0U + +/* 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_H */ + + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F4x7Vx/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_F4x7Vx/ldscript.ld new file mode 100644 index 000000000000..8b38135a2a51 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_F4x7Vx/ldscript.ld @@ -0,0 +1,203 @@ +/* +****************************************************************************** +** +** File : LinkerScript.ld +** +** Abstract : Linker script for STM32F4x7Vx Device with +** 512/1024KByte FLASH, 192KByte 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) 2019 STMicroelectronics

+** +** Redistribution and use in source and binary forms, with or without modification, +** are permitted provided that the following conditions are met: +** 1. Redistributions of source code must retain the above copyright notice, +** this list of conditions and the following disclaimer. +** 2. Redistributions in binary form must reproduce the above copyright notice, +** this list of conditions and the following disclaimer in the documentation +** and/or other materials provided with the distribution. +** 3. Neither the name of STMicroelectronics nor the names of its contributors +** may be used to endorse or promote products derived from this software +** without specific prior written permission. +** +** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +** AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +** IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +** FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +** DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +** SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +** CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +** OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +** OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = 0x20000000 + LD_MAX_DATA_SIZE; /* 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 +{ +RAM (xrw) : ORIGIN = 0x20000000, LENGTH = LD_MAX_DATA_SIZE +CCMRAM (rw) : ORIGIN = 0x10000000, LENGTH = 64K +FLASH (rx) : ORIGIN = 0x08000000 + LD_FLASH_OFFSET, LENGTH = LD_MAX_SIZE - LD_FLASH_OFFSET +} + +/* Define output sections */ +SECTIONS +{ + /* The startup code goes first into FLASH */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + /* The program code and other data goes into FLASH */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >FLASH + + /* Constant data goes into FLASH */ + .rodata : + { + . = ALIGN(4); + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + . = ALIGN(4); + } >FLASH + + .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH + .ARM : { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } >FLASH + + .preinit_array : + { + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + } >FLASH + .init_array : + { + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + } >FLASH + .fini_array : + { + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(SORT(.fini_array.*))) + KEEP (*(.fini_array*)) + PROVIDE_HIDDEN (__fini_array_end = .); + } >FLASH + + /* used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* Initialized data sections goes into RAM, load LMA copy after code */ + .data : + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >RAM AT> FLASH + + _siccmram = LOADADDR(.ccmram); + + /* CCM-RAM section + * + * IMPORTANT NOTE! + * If initialized variables will be placed in this section, + * the startup code needs to be modified to copy the init-values. + */ + .ccmram : + { + . = ALIGN(4); + _sccmram = .; /* create a global symbol at ccmram start */ + *(.ccmram) + *(.ccmram*) + + . = ALIGN(4); + _eccmram = .; /* create a global symbol at ccmram end */ + } >CCMRAM AT> FLASH + + + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss section */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* 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) } +} diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F4x7Vx/variant.cpp b/buildroot/share/PlatformIO/variants/MARLIN_F4x7Vx/variant.cpp new file mode 100644 index 000000000000..3721d4f5b5aa --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_F4x7Vx/variant.cpp @@ -0,0 +1,275 @@ +/* + 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_11, // Digital pin 27 + PB_12, // Digital pin 28 + PB_13, // Digital pin 29 + PB_14, // Digital pin 30 + PB_15, // Digital pin 31 + + PC_0, // Digital pin 32 + PC_1, // Digital pin 33 + PC_2, // Digital pin 34 + PC_3, // Digital pin 35 + PC_4, // Digital pin 36 + PC_5, // Digital pin 37 + PC_6, // Digital pin 38 + PC_7, // Digital pin 39 + PC_8, // Digital pin 40 + PC_9, // Digital pin 41 + PC_10, // Digital pin 42 + PC_11, // Digital pin 43 + PC_12, // Digital pin 44 + PC_13, // Digital pin 45 + PC_14, // Digital pin 46 + PC_15, // Digital pin 47 + + PD_0, // Digital pin 48 + PD_1, // Digital pin 49 + PD_2, // Digital pin 50 + PD_3, // Digital pin 51 + PD_4, // Digital pin 52 + PD_5, // Digital pin 53 + PD_6, // Digital pin 54 + PD_7, // Digital pin 55 + PD_8, // Digital pin 56 + PD_9, // Digital pin 57 + PD_10, // Digital pin 58 + PD_11, // Digital pin 59 + PD_12, // Digital pin 60 + PD_13, // Digital pin 61 + PD_14, // Digital pin 62 + PD_15, // Digital pin 63 + + PE_0, // Digital pin 64 + PE_1, // Digital pin 65 + PE_2, // Digital pin 66 + PE_3, // Digital pin 67 + PE_4, // Digital pin 68 + PE_5, // Digital pin 69 + PE_6, // Digital pin 70 + PE_7, // Digital pin 71 + PE_8, // Digital pin 72 + PE_9, // Digital pin 73 + PE_10, // Digital pin 74 + PE_11, // Digital pin 75 + PE_12, // Digital pin 76 + PE_13, // Digital pin 77 + PE_14, // Digital pin 78 + PE_15, // Digital pin 79 + + PH_0, // Digital pin 80, used by the external oscillator + PH_1 // Digital pin 81, 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 + 32, // A10, PC0 + 33, // A11, PC1 + 34, // A12, PC2 + 35, // A13, PC3 + 36, // A14, PC4 + 37 // 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_SCALE1); + + // 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_DIV2; // PLLCLK = 168 MHz (336 MHz / 2) + RCC_OscInitStruct.PLL.PLLQ = 7; + 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; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; // 168 MHz + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; // 42 MHz + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; // 84 MHz + if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5) != 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_SCALE1); + + // 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_DIV2; // PLLCLK = 168 MHz (336 MHz / 2) + RCC_OscInitStruct.PLL.PLLQ = 7; + 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; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; // 168 MHz + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; // 42 MHz + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; // 84 MHz + if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5) != 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(); + } + } + } + + /* Ensure CCM RAM clock is enabled */ + __HAL_RCC_CCMDATARAMEN_CLK_ENABLE(); + + /* 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_F4x7Vx/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_F4x7Vx/variant.h new file mode 100644 index 000000000000..94fa79c065d8 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_F4x7Vx/variant.h @@ -0,0 +1,203 @@ +/* + Copyright (c) 2011 Arduino. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _VARIANT_ARDUINO_STM32_ +#define _VARIANT_ARDUINO_STM32_ + +#ifdef __cplusplus +extern "C" { +#endif // __cplusplus + +/*---------------------------------------------------------------------------- + * Pins + *----------------------------------------------------------------------------*/ + +// | 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 | | | | +#define PA3 PIN_A3 // | 3 | A3 (ADC1) | | USART2_RX | | | | +#define PA4 PIN_A4 // | 4 | A4 (ADC1) | DAC_OUT1 | | | SPI1_SS, (SPI3_SS) | | +#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 | | | | +#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, (UART4_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) | | USART3_RX | | | | +#define PC6 38 // | 38 | | | USART6_TX | | | | +#define PC7 39 // | 39 | | | USART6_RX | | | | +#define PC8 40 // | 40 | | | | | | | +#define PC9 41 // | 41 | | | USART3_TX | TWI3_SDA | | | +#define PC10 42 // | 42 | | | | | 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 PD0 48 // | 48 | | | | | | | +#define PD1 49 // | 49 | | | | | | | +#define PD2 50 // | 50 | | | UART5_RX | | | | +#define PD3 51 // | 51 | | | | | | | +#define PD4 52 // | 52 | | | | | | | +#define PD5 53 // | 53 | | | USART2_TX | | | | +#define PD6 54 // | 54 | | | USART2_RX | | | | +#define PD7 55 // | 55 | | | | | | | +#define PD8 56 // | 56 | | | USART3_TX | | | | +#define PD9 57 // | 57 | | | USART3_RX | | | | +#define PD10 58 // | 58 | | | | | | | +#define PD11 59 // | 59 | | | | | | | +#define PD12 60 // | 60 | | | | | | | +#define PD13 61 // | 61 | | | | | | | +#define PD14 62 // | 62 | | | | | | | +#define PD15 63 // | 63 | | | | | | | +// |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------| +#define PE0 64 // | 64 | | | | | | | +#define PE1 65 // | 65 | | | | | | | +#define PE2 66 // | 66 | | | | | | | +#define PE3 67 // | 67 | | | | | | | +#define PE4 68 // | 68 | | | | | | | +#define PE5 69 // | 69 | | | | | | | +#define PE6 70 // | 70 | | | | | | | +#define PE7 71 // | 71 | | | | | | | +#define PE8 72 // | 72 | | | | | | | +#define PE9 73 // | 73 | | | | | | | +#define PE10 74 // | 74 | | | | | | | +#define PE11 75 // | 75 | | | | | | | +#define PE12 76 // | 76 | | | | | | | +#define PE13 77 // | 77 | | | | | | | +#define PE14 78 // | 78 | | | | | | | +#define PE15 79 // | 79 | | | | | | | +// |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------| +#define PH0 80 // | 80 | | | | | | OSC_IN | +#define PH1 81 // | 81 | | | | | | OSC_OUT | +// |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------| + +/// This must be a literal +#define NUM_DIGITAL_PINS 82 +#define NUM_ANALOG_INPUTS 16 + +// On-board LED pin number +#ifndef LED_BUILTIN +#define LED_BUILTIN PA5 +#endif +#define LED_GREEN LED_BUILTIN + +// On-board user button +#ifndef USER_BTN +#define USER_BTN PC13 +#endif + +// SPI definitions +#define PIN_SPI_SS PA4 +#define PIN_SPI_SS1 PA4 +#define PIN_SPI_SS2 PB12 +#define PIN_SPI_SS3 PA15 +#define PIN_SPI_MOSI PA7 +#define PIN_SPI_MISO PA6 +#define PIN_SPI_SCK PA5 + +// I2C definitions +#ifndef PIN_WIRE_SDA + #define PIN_WIRE_SDA PB9 +#endif +#ifndef PIN_WIRE_SCL + #define PIN_WIRE_SCL PB8 +#endif + +// Timer Definitions +// Use TIM6/TIM7 when possible as servo and tone don't need GPIO output pin +#ifndef TIMER_TONE + #define TIMER_TONE TIM6 +#endif +#ifndef TIMER_SERVO + #define TIMER_SERVO TIM7 +#endif +#ifndef TIMER_SERIAL + #define TIMER_SERIAL TIM5 +#endif + +// UART Definitions +#define SERIAL_UART_INSTANCE 2 + +// Default pin used for 'Serial' instance +// Mandatory for Firmata +#define PIN_SERIAL_RX PA3 +#define PIN_SERIAL_TX PA2 + +/* Extra HAL modules */ +#define HAL_DAC_MODULE_ENABLED + +#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 +#endif + +#endif /* _VARIANT_ARDUINO_STM32_ */ diff --git a/buildroot/share/PlatformIO/variants/FLY_F407ZG/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_FLY_F407ZG/PeripheralPins.c similarity index 100% rename from buildroot/share/PlatformIO/variants/FLY_F407ZG/PeripheralPins.c rename to buildroot/share/PlatformIO/variants/MARLIN_FLY_F407ZG/PeripheralPins.c diff --git a/buildroot/share/PlatformIO/variants/LERDGE/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_FLY_F407ZG/PinNamesVar.h similarity index 100% rename from buildroot/share/PlatformIO/variants/LERDGE/PinNamesVar.h rename to buildroot/share/PlatformIO/variants/MARLIN_FLY_F407ZG/PinNamesVar.h diff --git a/buildroot/share/PlatformIO/variants/MARLIN_FLY_F407ZG/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_FLY_F407ZG/ldscript.ld new file mode 100644 index 000000000000..d644d49beb1d --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_FLY_F407ZG/ldscript.ld @@ -0,0 +1,207 @@ +/* +***************************************************************************** +** + +** File : lscript.ld +** +** Abstract : Linker script for STM32F407(VZ)(EG)Tx Device with +** 512/1024KByte FLASH, 128KByte 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 = 0x20020000; /* 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 +{ +RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K +CCMRAM (rw) : ORIGIN = 0x10000000, LENGTH = 64K +FLASH (rx) : ORIGIN = 0x8008000, LENGTH = 1024K -32K +} + +/* 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): + { + . = 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 + + _siccmram = LOADADDR(.ccmram); + + /* CCM-RAM section + * + * IMPORTANT NOTE! + * If initialized variables will be placed in this section, + * the startup code needs to be modified to copy the init-values. + */ + .ccmram : + { + . = ALIGN(4); + _sccmram = .; /* create a global symbol at ccmram start */ + *(.ccmram) + *(.ccmram*) + + . = ALIGN(4); + _eccmram = .; /* create a global symbol at ccmram end */ + } >CCMRAM AT> FLASH + + + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss section */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* User_heap_stack section, used to check that there is enough RAM left */ + ._user_heap_stack : + { + . = ALIGN(4); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(4); + } >RAM + + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} + + diff --git a/buildroot/share/PlatformIO/variants/FLY_F407ZG/variant.cpp b/buildroot/share/PlatformIO/variants/MARLIN_FLY_F407ZG/variant.cpp similarity index 100% rename from buildroot/share/PlatformIO/variants/FLY_F407ZG/variant.cpp rename to buildroot/share/PlatformIO/variants/MARLIN_FLY_F407ZG/variant.cpp diff --git a/buildroot/share/PlatformIO/variants/FLY_F407ZG/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_FLY_F407ZG/variant.h similarity index 100% rename from buildroot/share/PlatformIO/variants/FLY_F407ZG/variant.h rename to buildroot/share/PlatformIO/variants/MARLIN_FLY_F407ZG/variant.h diff --git a/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_CHEETAH_V20/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_CHEETAH_V20/PeripheralPins.c new file mode 100644 index 000000000000..418ef5aa7abc --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_CHEETAH_V20/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_FYSETC_CHEETAH_V20/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_CHEETAH_V20/PinNamesVar.h new file mode 100644 index 000000000000..e1536bcf30f4 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_CHEETAH_V20/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 \ No newline at end of file diff --git a/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_CHEETAH_V20/hal_conf_custom.h b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_CHEETAH_V20/hal_conf_custom.h new file mode 100644 index 000000000000..395bfcd4b764 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_CHEETAH_V20/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_FYSETC_CHEETAH_V20/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_CHEETAH_V20/ldscript.ld new file mode 100644 index 000000000000..9565cd89c69b --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_CHEETAH_V20/ldscript.ld @@ -0,0 +1,187 @@ +/* +***************************************************************************** +** + +** File : LinkerScript.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 = 0x800C000, LENGTH = 256K +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 section */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* User_heap_stack section, used to check that there is enough RAM 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_FYSETC_CHEETAH_V20/variant.cpp b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_CHEETAH_V20/variant.cpp new file mode 100644 index 000000000000..71f3509ed57b --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_CHEETAH_V20/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 \ No newline at end of file diff --git a/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_CHEETAH_V20/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_CHEETAH_V20/variant.h new file mode 100644 index 000000000000..bcd5aa378edf --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_CHEETAH_V20/variant.h @@ -0,0 +1,151 @@ +/* + 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 A0 // | 0 | A0 | | | | | +#define PA1 A1 // | 1 | A1 | | | | | +#define PA2 A2 // | 2 | A2 | USART2_TX | | | | +#define PA3 A3 // | 3 | A3 | USART2_RX | | | | +#define PA4 A4 // | 4 | A4 | | | SPI1_SS, (SPI3_SS) | | +#define PA5 A5 // | 5 | A5 | | | SPI1_SCK | | +#define PA6 A6 // | 6 | A6 | | | SPI1_MISO | | +#define PA7 A7 // | 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 A8 // | 16 | A8 | | | | | +#define PB1 A9 // | 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 A10 // | 31 | A10 | | | | | +#define PC1 A11 // | 32 | A11 | | | | | +#define PC2 A12 // | 33 | A12 | | | SPI2_MISO | | +#define PC3 A13 // | 34 | A13 | | | SPI2_MOSI | | +#define PC4 A14 // | 35 | A14 | | | | | +#define PC5 A15 // | 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 TIM5 +#define TIMER_SERIAL TIM11 + +// 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 instantiate 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_ */ \ No newline at end of file diff --git a/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_S6/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_S6/PeripheralPins.c index cc700201aaea..ec28776ebe66 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_S6/PeripheralPins.c +++ b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_S6/PeripheralPins.c @@ -40,46 +40,46 @@ #ifdef HAL_ADC_MODULE_ENABLED const PinMap PinMap_ADC[] = { - // {PA_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0 - // {PA_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC2_IN0 - // {PA_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC3_IN0 - // {PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1 - // {PA_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC2_IN1 - // {PA_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC3_IN1 - // {PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2 - // {PA_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC2_IN2 - // {PA_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC3_IN2 + //{PA_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0 + //{PA_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC2_IN0 + //{PA_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC3_IN0 + //{PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1 + //{PA_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC2_IN1 + //{PA_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC3_IN1 + //{PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2 + //{PA_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC2_IN2 + //{PA_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC3_IN2 {PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3 - // {PA_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC2_IN3 - // {PA_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC3_IN3 + //{PA_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC2_IN3 + //{PA_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC3_IN3 {PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4 - // {PA_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC2_IN4 - // {PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5 - // {PA_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC2_IN5 - // {PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6 - // {PA_6, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC2_IN6 - // {PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7 - // {PA_7, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC2_IN7 - // {PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8 - // {PB_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC2_IN8 - // {PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9 - // {PB_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC2_IN9 + //{PA_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC2_IN4 + //{PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5 + //{PA_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC2_IN5 + //{PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6 + //{PA_6, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC2_IN6 + //{PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7 + //{PA_7, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC2_IN7 + //{PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8 + //{PB_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC2_IN8 + //{PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9 + //{PB_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC2_IN9 {PC_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10 - // {PC_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC2_IN10 - // {PC_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC3_IN10 + //{PC_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC2_IN10 + //{PC_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC3_IN10 {PC_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11 - // {PC_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC2_IN11 - // {PC_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC3_IN11 + //{PC_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC2_IN11 + //{PC_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC3_IN11 {PC_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12 - // {PC_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC2_IN12 - // {PC_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC3_IN12 + //{PC_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC2_IN12 + //{PC_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC3_IN12 {PC_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13 - // {PC_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC2_IN13 - // {PC_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC3_IN13 + //{PC_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC2_IN13 + //{PC_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC3_IN13 {PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14 - // {PC_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC2_IN14 - // {PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15 - // {PC_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC2_IN15 + //{PC_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC2_IN14 + //{PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15 + //{PC_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC2_IN15 {NC, NP, 0} }; #endif @@ -88,8 +88,8 @@ const PinMap PinMap_ADC[] = { #ifdef HAL_DAC_MODULE_ENABLED const PinMap PinMap_DAC[] = { - // {PA_4, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // DAC_OUT1 - // {PA_5, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // DAC_OUT2 - LD2 + //{PA_4, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // DAC_OUT1 + //{PA_5, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // DAC_OUT2 - LD2 {NC, NP, 0} }; #endif @@ -98,24 +98,22 @@ const PinMap PinMap_DAC[] = { #ifdef HAL_I2C_MODULE_ENABLED const PinMap PinMap_I2C_SDA[] = { - // {PB_3, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, - // {PB_4, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, - // {PB_7, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, + //{PB_3, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + //{PB_4, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_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_7, FMPI2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_FMPI2C1)}, - // {PC_9, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, - // {PC_12, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + //{PC_7, FMPI2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_FMPI2C1)}, + //{PC_9, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, + //{PC_12, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, {NC, NP, 0} }; -#endif -#ifdef HAL_I2C_MODULE_ENABLED 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)}, + //{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)}, - // {PC_6, FMPI2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_FMPI2C1)}, + //{PB_10, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + //{PC_6, FMPI2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_FMPI2C1)}, {NC, NP, 0} }; #endif @@ -125,33 +123,33 @@ const PinMap PinMap_I2C_SCL[] = { #ifdef HAL_TIM_MODULE_ENABLED 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_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 - STLink Tx - // {PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3 - STLink Tx - // {PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 - STLink Tx - // {PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 - STLink Rx - // {PA_3, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 4, 0)}, // TIM5_CH4 - STLink Rx - // {PA_3, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2 - STLink Rx + //{PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 - STLink Tx + //{PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3 - STLink Tx + //{PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 - STLink Tx + //{PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 - STLink Rx + //{PA_3, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 4, 0)}, // TIM5_CH4 - STLink Rx + //{PA_3, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2 - STLink Rx {PA_5, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 - // {PA_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + //{PA_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N {PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 - // {PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + //{PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 //{PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_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_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N - // {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_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_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + //{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_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_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // Fan0, TIM8_CH2N - // {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_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_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // Fan1, TIM8_CH3N {PB_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // Fan2, TIM2_CH4 {PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // E0 Heater, TIM2_CH2 @@ -159,27 +157,27 @@ const PinMap PinMap_PWM[] = { {PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // LED G, TIM3_CH2 {PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // LED R, TIM4_CH1 {PB_7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // LED B, TIM4_CH2 - // {PB_8, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1 - // {PB_8, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + //{PB_8, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1 + //{PB_8, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 {PB_8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 {PB_9, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 - // {PB_9, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 - // {PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 + //{PB_9, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 + //{PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 {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, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 1, 0)}, // TIM12_CH1 - // {PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N - // {PB_14, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N + //{PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + //{PB_14, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N {PB_15, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 2, 0)}, // TIM12_CH2 - // {PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N - // {PB_15, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N + //{PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + //{PB_15, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N {PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 - // {PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 - // {PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + //{PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 + //{PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 {PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 {PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 - // {PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 0)}, // TIM8_CH3 - // {PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 + //{PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 0)}, // TIM8_CH3 + //{PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 {PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 4, 0)}, // TIM8_CH4 {PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 {PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 @@ -192,52 +190,46 @@ const PinMap PinMap_PWM[] = { #ifdef HAL_UART_MODULE_ENABLED const PinMap PinMap_UART_TX[] = { - // {PA_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, - // {PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + //{PA_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, {PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, - // {PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, - // {PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - // {PC_6, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - // {PC_10, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + //{PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PC_6, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + //{PC_10, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, {PC_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - // {PC_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + //{PC_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, {NC, NP, 0} }; -#endif -#ifdef HAL_UART_MODULE_ENABLED const PinMap PinMap_UART_RX[] = { - // {PA_1, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, - // {PA_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + //{PA_1, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PA_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, {PA_10, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, - // {PB_7, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, - // {PC_5, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - // {PC_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - // {PC_11, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PB_7, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + //{PC_5, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PC_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + //{PC_11, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, {PC_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - // {PD_2, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + //{PD_2, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, {NC, NP, 0} }; -#endif -#ifdef HAL_UART_MODULE_ENABLED 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)}, - // {PA_15, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, - // {PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - // {PC_8, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART5)}, + //{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)}, + //{PA_15, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PC_8, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART5)}, {NC, NP, 0} }; -#endif -#ifdef HAL_UART_MODULE_ENABLED 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)}, - // {PB_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, - // {PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - // {PC_9, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART5)}, + //{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)}, + //{PB_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PC_9, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART5)}, {NC, NP, 0} }; #endif @@ -247,54 +239,48 @@ const PinMap PinMap_UART_CTS[] = { #ifdef HAL_SPI_MODULE_ENABLED const PinMap PinMap_SPI_MOSI[] = { {PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, - // {PB_0, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI3)}, - // {PB_2, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI3)}, - // {PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, - // {PB_5, 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_1, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI2)}, - // {PC_1, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI3)}, - // {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)}, + //{PB_0, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI3)}, + //{PB_2, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI3)}, + //{PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + //{PB_5, 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_1, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI2)}, + //{PC_1, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI3)}, + //{PC_3, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + //{PC_12, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, {NC, NP, 0} }; -#endif -#ifdef HAL_SPI_MODULE_ENABLED 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)}, + //{PB_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + //{PB_4, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + //{PB_14, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + //{PC_2, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + //{PC_11, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, {NC, NP, 0} }; -#endif -#ifdef HAL_SPI_MODULE_ENABLED const PinMap PinMap_SPI_SCLK[] = { {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, - // {PA_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, - // {PB_3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, - // {PB_3, 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_7, 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)}, + //{PA_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + //{PB_3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + //{PB_3, 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_7, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + //{PC_10, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, {NC, NP, 0} }; -#endif -#ifdef HAL_SPI_MODULE_ENABLED 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_4, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI2)}, - // {PB_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, - // {PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + //{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_4, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI2)}, + //{PB_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + //{PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, {NC, NP, 0} }; #endif @@ -303,20 +289,18 @@ const PinMap PinMap_SPI_SSEL[] = { #ifdef HAL_CAN_MODULE_ENABLED const PinMap PinMap_CAN_RD[] = { - // {PA_11, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, - // {PB_5, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, - // {PB_8, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, - // {PB_12, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, + //{PA_11, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, + //{PB_5, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, + //{PB_8, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, + //{PB_12, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, {NC, NP, 0} }; -#endif -#ifdef HAL_CAN_MODULE_ENABLED const PinMap PinMap_CAN_TD[] = { - // {PA_12, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, - // {PB_6, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, - // {PB_9, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, - // {PB_13, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, + //{PA_12, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, + //{PB_6, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, + //{PB_9, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, + //{PB_13, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, {NC, NP, 0} }; #endif @@ -329,12 +313,12 @@ const PinMap PinMap_CAN_TD[] = { #ifdef HAL_QSPI_MODULE_ENABLED const PinMap PinMap_QUADSPI[] = { - // {PA_1, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK1_IO3 - // {PB_2, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_CLK - // {PB_6, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_QSPI)}, // QUADSPI_BK1_NCS - // {PC_9, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK1_IO0 - // {PC_10, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK1_IO1 - // {PC_11, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK2_NCS + //{PA_1, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK1_IO3 + //{PB_2, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_CLK + //{PB_6, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_QSPI)}, // QUADSPI_BK1_NCS + //{PC_9, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK1_IO0 + //{PC_10, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK1_IO1 + //{PC_11, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK2_NCS {NC, NP, 0} }; #endif @@ -343,19 +327,15 @@ const PinMap PinMap_QUADSPI[] = { #ifdef HAL_PCD_MODULE_ENABLED const PinMap PinMap_USB_OTG_FS[] = { - // {PA_8, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_SOF - // {PA_9, USB_OTG_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, 0)}, // USB_OTG_FS_VBUS - // {PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_ID + //{PA_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, 0)}, // USB_OTG_FS_VBUS + //{PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_ID {PA_11, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DM {PA_12, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DP {NC, NP, 0} }; -#endif -#ifdef HAL_PCD_MODULE_ENABLED const PinMap PinMap_USB_OTG_HS[] = { {NC, NP, 0} }; #endif - - diff --git a/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_S6/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_S6/ldscript.ld index 2a61072cb17e..900ef0639101 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_S6/ldscript.ld +++ b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_S6/ldscript.ld @@ -60,8 +60,8 @@ _Min_Stack_Size = 0x400;; /* required amount of stack */ /* Specify the memory areas */ MEMORY { -FLASH (rx) : ORIGIN = 0x8010000, LENGTH = 512K -RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K +RAM (xrw) : ORIGIN = 0x20000000, LENGTH = LD_MAX_DATA_SIZE +FLASH (rx) : ORIGIN = 0x8000000 + LD_FLASH_OFFSET, LENGTH = LD_MAX_SIZE - LD_FLASH_OFFSET } /* Define output sections */ @@ -150,7 +150,7 @@ SECTIONS . = ALIGN(4); .bss : { - /* This is used by the startup in order to initialize the .bss secion */ + /* This is used by the startup in order to initialize the .bss section */ _sbss = .; /* define a global symbol at bss start */ __bss_start__ = _sbss; *(.bss) diff --git a/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_S6/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_S6/variant.h index ee4b1ef29608..4bd5b63dfe56 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_S6/variant.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_S6/variant.h @@ -114,8 +114,10 @@ extern "C" { #define NUM_ANALOG_INPUTS 7 #define NUM_ANALOG_FIRST 80 +//#define ADC_RESOLUTION 12 + // PWM resolution -// #define PWM_RESOLUTION 12 +//#define PWM_RESOLUTION 12 #define PWM_FREQUENCY 20000 // >= 20 Khz => inaudible noise for fans #define PWM_MAX_DUTY_CYCLE 255 diff --git a/buildroot/share/PlatformIO/variants/MARLIN_LERDGE/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_LERDGE/PeripheralPins.c new file mode 100644 index 000000000000..044f555a4105 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_LERDGE/PeripheralPins.c @@ -0,0 +1,400 @@ +/* + ******************************************************************************* + * 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 STM32F407Z(E-G)Tx.xml + */ +#include +#include + +/* ===== + * 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 +const PinMap PinMap_ADC[] = { + {PA_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0 + //{PA_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC2_IN0 + //{PA_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC3_IN0 + {PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1 + //{PA_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC2_IN1 + //{PA_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC3_IN1 + //{PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2 + {PA_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC2_IN2 + //{PA_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC3_IN2 + //{PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3 + //{PA_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC2_IN3 + {PA_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC3_IN3 + {PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4 + //{PA_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC2_IN4 + //{PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5 + {PA_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC2_IN5 + {PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6 + //{PA_6, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC2_IN6 + {PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7 + //{PA_7, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC2_IN7 + //{PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8 + {PB_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC2_IN8 + {PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9 + //{PB_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC2_IN9 + //{PC_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10 + //{PC_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC2_IN10 + {PC_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC3_IN10 + {PC_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11 + //{PC_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC2_IN11 + //{PC_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC3_IN11 + //{PC_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12 + {PC_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC2_IN12 + //{PC_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC3_IN12 + //{PC_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13 + //{PC_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC2_IN13 + {PC_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC3_IN13 + //{PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14 + {PC_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC2_IN14 + //{PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15 + {PC_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC2_IN15 + {PF_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC3_IN9 + {PF_4, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC3_IN14 + {PF_5, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC3_IN15 + {PF_6, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC3_IN4 + {PF_7, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC3_IN5 + {PF_8, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC3_IN6 + //{PF_9, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC3_IN7 + {PF_10, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC3_IN8 + {NC, NP, 0} +}; +#endif + +//*** DAC *** + +#ifdef HAL_DAC_MODULE_ENABLED +const PinMap PinMap_DAC[] = { + {PA_4, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // DAC_OUT1 + {PA_5, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // DAC_OUT2 + {NC, NP, 0} +}; +#endif + +//*** I2C *** + +#ifdef HAL_I2C_MODULE_ENABLED +const PinMap PinMap_I2C_SDA[] = { + {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)}, + {PB_11, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + {PC_9, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, + {PF_0, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + {NC, NP, 0} +}; + +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)}, + {PF_1, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + {NC, NP, 0} +}; +#endif + +//*** PWM *** + +#ifdef HAL_TIM_MODULE_ENABLED +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_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + {PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + //{PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 + //{PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + {PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + //{PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + //{PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 + {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 + {PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 + {PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 + {PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 + //{PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + //{PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + {PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 + //{PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N + //{PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + {PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 + //{PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N + //{PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 + {PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + {PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + {PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 + {PB_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_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 + {PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + {PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + {PB_14, 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 + {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 + {PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + {PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 + {PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + {PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 + {PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 + {PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 0)}, // TIM8_CH3 + {PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 + {PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 4, 0)}, // TIM8_CH4 + {PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 + {PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 + {PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 + {PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 + {PE_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 + {PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 + {PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + {PE_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 + {PE_12, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + {PE_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 + {PE_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 + {PF_6, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1 + {PF_7, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 + {PF_8, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 + {PF_9, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 + {NC, NP, 0} +}; +#endif + +//*** SERIAL *** + +#ifdef HAL_UART_MODULE_ENABLED +const PinMap PinMap_UART_TX[] = { + {PA_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PC_6, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + //{PC_10, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PC_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PC_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + {PD_5, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PD_8, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PG_14, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + {NC, NP, 0} +}; + +const PinMap PinMap_UART_RX[] = { + {PA_1, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PA_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PA_10, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PB_7, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PB_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PC_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + //{PC_11, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PC_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PD_2, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + {PD_6, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PD_9, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PG_9, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + {NC, NP, 0} +}; + +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)}, + {PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PD_4, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PD_12, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PG_8, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + {PG_12, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + {NC, NP, 0} +}; + +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)}, + {PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PD_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PD_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PG_13, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + {PG_15, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + {NC, NP, 0} +}; +#endif + +//*** SPI *** + +#ifdef HAL_SPI_MODULE_ENABLED +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} +}; + +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} +}; + +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} +}; + +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 + +//*** CAN *** + +#ifdef HAL_CAN_MODULE_ENABLED +const PinMap PinMap_CAN_RD[] = { + {PA_11, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, + {PB_5, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, + {PB_8, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, + {PB_12, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, + {PD_0, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, + {NC, NP, 0} +}; + +const PinMap PinMap_CAN_TD[] = { + {PA_12, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, + {PB_6, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, + {PB_9, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, + {PB_13, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, + {PD_1, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, + {NC, NP, 0} +}; +#endif + +//*** ETHERNET *** + +#ifdef HAL_ETH_MODULE_ENABLED +const PinMap PinMap_Ethernet[] = { + {PA_0, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_CRS + {PA_1, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_REF_CLK|ETH_RX_CLK + {PA_2, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_MDIO + {PA_3, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_COL + {PA_7, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_CRS_DV|ETH_RX_DV + {PB_0, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD2 + {PB_1, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD3 + {PB_5, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_PPS_OUT + {PB_8, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD3 + {PB_10, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RX_ER + {PB_11, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TX_EN + {PB_12, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD0 + {PB_13, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD1 + {PC_1, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_MDC + {PC_2, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD2 + {PC_3, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TX_CLK + {PC_4, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD0 + {PC_5, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD1 + {PE_2, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD3 + {PG_8, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_PPS_OUT + {PG_11, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TX_EN + {PG_13, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD0 + {PG_14, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD1 + {NC, NP, 0} +}; +#endif + +//*** No QUADSPI *** + +//*** USB *** + +#ifdef HAL_PCD_MODULE_ENABLED +const PinMap PinMap_USB_OTG_FS[] = { + //{PA_8, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_SOF + //{PA_9, USB_OTG_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_FS_VBUS + //{PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_ID + {PA_11, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DM + {PA_12, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DP + {NC, NP, 0} +}; + +const PinMap PinMap_USB_OTG_HS[] = { +#ifdef USE_USB_HS_IN_FS + {PA_4, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_SOF + {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_ID + {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_HS_VBUS + {PB_14, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DM + {PB_15, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DP +#else + {PA_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D0 + {PA_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_CK + {PB_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D1 + {PB_1, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D2 + {PB_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D7 + {PB_10, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D3 + {PB_11, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D4 + {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D5 + {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D6 + {PC_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_STP + {PC_2, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_DIR + {PC_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_NXT +#endif /* USE_USB_HS_IN_FS */ + {NC, NP, 0} +}; +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_LERDGE/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_LERDGE/PinNamesVar.h new file mode 100644 index 000000000000..b4bb9d45f8ac --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_LERDGE/PinNamesVar.h @@ -0,0 +1,50 @@ +/* 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, + USB_OTG_HS_ULPI_D0 = PA_3, + USB_OTG_HS_SOF = PA_4, + USB_OTG_HS_ULPI_CK = PA_5, + USB_OTG_HS_ULPI_D1 = PB_0, + USB_OTG_HS_ULPI_D2 = PB_1, + USB_OTG_HS_ULPI_D7 = PB_5, + USB_OTG_HS_ULPI_D3 = PB_10, + USB_OTG_HS_ULPI_D4 = PB_11, + USB_OTG_HS_ID = PB_12, + USB_OTG_HS_ULPI_D5 = PB_12, + USB_OTG_HS_ULPI_D6 = PB_13, + USB_OTG_HS_VBUS = PB_13, + USB_OTG_HS_DM = PB_14, + USB_OTG_HS_DP = PB_15, + USB_OTG_HS_ULPI_STP = PC_0, + USB_OTG_HS_ULPI_DIR = PC_2, + USB_OTG_HS_ULPI_NXT = PC_3, +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_LERDGE/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_LERDGE/ldscript.ld new file mode 100644 index 000000000000..ef151075b779 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_LERDGE/ldscript.ld @@ -0,0 +1,186 @@ +/* +***************************************************************************** +** +** File : LinkerScript.ld +** +** Abstract : Linker script for STM32F407VGTx Device with +** 1024KByte FLASH, 128KByte 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. +** +** (c)Copyright Ac6. +** You may use this file as-is or modify it according to the needs of your +** project. Distribution of this file (unmodified or modified) is not +** permitted. Ac6 permit registered System Workbench for MCU users the +** rights to distribute the assembled, compiled & linked contents of this +** file as part of an application binary file, provided that it is built +** using the System Workbench for MCU toolchain. +** +***************************************************************************** +*/ + +/* 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 = 0x08000000 + LD_FLASH_OFFSET, LENGTH = LD_MAX_SIZE - LD_FLASH_OFFSET +RAM (xrw) : ORIGIN = 0x20000000, LENGTH = LD_MAX_DATA_SIZE +CCMRAM (rw) : ORIGIN = 0x10000000, 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): + { + . = 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 + + _siccmram = LOADADDR(.ccmram); + + /* CCM-RAM section + * + * IMPORTANT NOTE! + * If initialized variables will be placed in this section, + * the startup code needs to be modified to copy the init-values. + */ + .ccmram : + { + . = ALIGN(4); + _sccmram = .; /* create a global symbol at ccmram start */ + *(.ccmram) + *(.ccmram*) + + . = ALIGN(4); + _eccmram = .; /* create a global symbol at ccmram end */ + } >CCMRAM AT> FLASH + + + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss section */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* User_heap_stack section, used to check that there is enough RAM left */ + ._user_heap_stack : + { + . = ALIGN(4); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(4); + } >RAM + + + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/buildroot/share/PlatformIO/variants/LERDGE/variant.cpp b/buildroot/share/PlatformIO/variants/MARLIN_LERDGE/variant.cpp similarity index 100% rename from buildroot/share/PlatformIO/variants/LERDGE/variant.cpp rename to buildroot/share/PlatformIO/variants/MARLIN_LERDGE/variant.cpp diff --git a/buildroot/share/PlatformIO/variants/LERDGE/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_LERDGE/variant.h similarity index 100% rename from buildroot/share/PlatformIO/variants/LERDGE/variant.h rename to buildroot/share/PlatformIO/variants/MARLIN_LERDGE/variant.h diff --git a/buildroot/share/PlatformIO/variants/megaextendedpins/pins_arduino.h b/buildroot/share/PlatformIO/variants/MARLIN_MEGA_EXTENDED/pins_arduino.h old mode 100755 new mode 100644 similarity index 99% rename from buildroot/share/PlatformIO/variants/megaextendedpins/pins_arduino.h rename to buildroot/share/PlatformIO/variants/MARLIN_MEGA_EXTENDED/pins_arduino.h index 81f2ae3e19a1..dbbb7b48327a --- a/buildroot/share/PlatformIO/variants/megaextendedpins/pins_arduino.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_MEGA_EXTENDED/pins_arduino.h @@ -89,7 +89,7 @@ static const uint8_t A15 = PIN_A15; #define digitalPinToPCICR(p) ( (((p) >= 10) && ((p) <= 13)) || \ (((p) >= 50) && ((p) <= 53)) || \ - (((p) >= 62) && ((p) <= 69)) ? (&PCICR) : ((uint8_t *)0) ) + (((p) >= 62) && ((p) <= 69)) ? (&PCICR) : nullptr ) #define digitalPinToPCICRbit(p) ( (((p) >= 10) && ((p) <= 13)) || (((p) >= 50) && ((p) <= 53)) ? 0 : \ ( (((p) >= 62) && ((p) <= 69)) ? 2 : \ @@ -97,7 +97,7 @@ static const uint8_t A15 = PIN_A15; #define digitalPinToPCMSK(p) ( (((p) >= 10) && ((p) <= 13)) || (((p) >= 50) && ((p) <= 53)) ? (&PCMSK0) : \ ( (((p) >= 62) && ((p) <= 69)) ? (&PCMSK2) : \ - ((uint8_t *)0) ) ) + nullptr ) ) #define digitalPinToPCMSKbit(p) ( (((p) >= 10) && ((p) <= 13)) ? ((p) - 6) : \ ( ((p) == 50) ? 3 : \ diff --git a/buildroot/share/PlatformIO/variants/MARLIN_STEVAL_F401VE/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_STEVAL_F401VE/PeripheralPins.c new file mode 100644 index 000000000000..d3d754b689ee --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_STEVAL_F401VE/PeripheralPins.c @@ -0,0 +1,260 @@ + +/* + ******************************************************************************* + * Copyright (c) 2019, STMicroelectronics + * All rights reserved. + * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ******************************************************************************* + * Automatically generated from STM32F401V(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 + {PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 + {PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 + {PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 + {PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 + {PE_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 + //{PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 + //{PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + //{PE_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 + //{PE_12, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + //{PE_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 + {PE_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 + {NC, NP, 0} +}; +#endif + +//*** 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)}, + {PD_5, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {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)}, + {PD_6, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {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)}, + {PD_4, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {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)}, + {PD_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {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)}, + //{PD_6, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + //{PE_6, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + //{PE_14, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + {NC, NP, 0} +}; + +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)}, + //{PE_5, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + //{PE_13, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + {NC, NP, 0} +}; + +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)}, + //{PD_3, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + //{PE_2, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + //{PE_12, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + {NC, NP, 0} +}; + +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)}, + //{PE_4, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + //{PE_11, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + {NC, NP, 0} +}; +#endif + +//*** No CAN *** + +//*** No ETHERNET *** + +//*** No QUADSPI *** + +//*** USB *** + +#ifdef HAL_PCD_MODULE_ENABLED +WEAK const PinMap PinMap_USB_OTG_FS[] = { + //{PA_8, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_SOF + //{PA_9, USB_OTG_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_FS_VBUS + //{PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_ID + {PA_11, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DM + {PA_12, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DP + {NC, NP, 0} +}; +#endif + +//*** No USB_OTG_HS *** +//*** SD *** + +#ifdef HAL_SD_MODULE_ENABLED +WEAK const PinMap PinMap_SD[] = { + //{PB_8, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D4 + //{PB_9, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D5 + //{PC_6, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D6 + //{PC_7, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D7 + {PC_8, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D0 + {PC_9, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D1 + {PC_10, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D2 + {PC_11, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D3 + {PC_12, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF12_SDIO)}, // SDIO_CK + {PD_2, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF12_SDIO)}, // SDIO_CMD + {NC, NP, 0} +}; +#endif diff --git a/buildroot/share/PlatformIO/variants/STEVAL_F401VE/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_STEVAL_F401VE/PinNamesVar.h similarity index 100% rename from buildroot/share/PlatformIO/variants/STEVAL_F401VE/PinNamesVar.h rename to buildroot/share/PlatformIO/variants/MARLIN_STEVAL_F401VE/PinNamesVar.h diff --git a/buildroot/share/PlatformIO/variants/MARLIN_STEVAL_F401VE/hal_conf_custom.h b/buildroot/share/PlatformIO/variants/MARLIN_STEVAL_F401VE/hal_conf_custom.h new file mode 100644 index 000000000000..aeaaf890f24b --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_STEVAL_F401VE/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_SD_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_UART_MODULE_ENABLED // by default +//#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_STEVAL_F401VE/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_STEVAL_F401VE/ldscript.ld new file mode 100644 index 000000000000..c5788dbebe6c --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_STEVAL_F401VE/ldscript.ld @@ -0,0 +1,187 @@ +/* +***************************************************************************** +** +** 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 = 0x20018000; /* 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 = 0x08000000, LENGTH = 512K +RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 96K +} + +/* Define output sections */ +SECTIONS +{ + /* The startup code goes first into FLASH */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + /* The program code and other data goes into FLASH */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >FLASH + + /* Constant data goes into FLASH */ + .rodata : + { + . = ALIGN(4); + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + . = ALIGN(4); + } >FLASH + + .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH + .ARM : { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } >FLASH + + .preinit_array : + { + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + } >FLASH + .init_array : + { + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + } >FLASH + .fini_array : + { + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(SORT(.fini_array.*))) + KEEP (*(.fini_array*)) + PROVIDE_HIDDEN (__fini_array_end = .); + } >FLASH + + /* used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* Initialized data sections goes into RAM, load LMA copy after code */ + .data : + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = 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 section */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* User_heap_stack section, used to check that there is enough RAM left */ + ._user_heap_stack : + { + . = ALIGN(4); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(4); + } >RAM + + + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} + + diff --git a/buildroot/share/PlatformIO/variants/STEVAL_F401VE/variant.cpp b/buildroot/share/PlatformIO/variants/MARLIN_STEVAL_F401VE/variant.cpp similarity index 100% rename from buildroot/share/PlatformIO/variants/STEVAL_F401VE/variant.cpp rename to buildroot/share/PlatformIO/variants/MARLIN_STEVAL_F401VE/variant.cpp diff --git a/buildroot/share/PlatformIO/variants/STEVAL_F401VE/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_STEVAL_F401VE/variant.h similarity index 100% rename from buildroot/share/PlatformIO/variants/STEVAL_F401VE/variant.h rename to buildroot/share/PlatformIO/variants/MARLIN_STEVAL_F401VE/variant.h diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/boards.cpp b/buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/boards.cpp deleted file mode 100644 index 12321229defb..000000000000 --- a/buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/boards.cpp +++ /dev/null @@ -1,225 +0,0 @@ -/****************************************************************************** - * The MIT License - * - * Copyright (c) 2010 Perry Hung. - * Copyright (c) 2011, 2012 LeafLabs, LLC. - * - * Permission is hereby granted, free of charge, to any person - * obtaining a copy of this software and associated documentation - * files (the "Software"), to deal in the Software without - * restriction, including without limitation the rights to use, copy, - * modify, merge, publish, distribute, sublicense, and/or sell copies - * of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be - * included in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, - * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND - * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS - * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN - * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN - * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE - * SOFTWARE. - *****************************************************************************/ - -/** - * @file wirish/boards.cpp - * @brief init() and board routines. - * - * This file is mostly interesting for the init() function, which - * configures Flash, the core clocks, and a variety of other available - * peripherals on the board so the rest of Wirish doesn't have to turn - * things on before using them. - * - * Prior to returning, init() calls boardInit(), which allows boards - * to perform any initialization they need to. This file includes a - * weak no-op definition of boardInit(), so boards that don't need any - * special initialization don't have to define their own. - * - * How init() works is chip-specific. See the boards_setup.cpp files - * under e.g. wirish/stm32f1/, wirish/stmf32f2 for the details, but be - * advised: their contents are unstable, and can/will change without - * notice. - */ - -#include -#include -#include -#include -#include -#include "boards_private.h" - -static void setup_flash(void); -static void setup_clocks(void); -static void setup_nvic(void); -static void setup_adcs(void); -static void setup_timers(void); - -/* - * Exported functions - */ - -void init(void) { - setup_flash(); - setup_clocks(); - setup_nvic(); - systick_init(SYSTICK_RELOAD_VAL); - wirish::priv::board_setup_gpio(); - setup_adcs(); - setup_timers(); - wirish::priv::board_setup_usb(); - wirish::priv::series_init(); - boardInit(); -} - -/* Provide a default no-op boardInit(). */ -__weak void boardInit(void) { -} - -/* You could farm this out to the files in boards/ if e.g. it takes - * too long to test on boards with lots of pins. */ -bool boardUsesPin(uint8 pin) { - for (int i = 0; i < BOARD_NR_USED_PINS; i++) { - if (pin == boardUsedPins[i]) { - return true; - } - } - return false; -} - -/* - * Auxiliary routines - */ - -static void setup_flash(void) { - // Turn on as many Flash "go faster" features as - // possible. flash_enable_features() just ignores any flags it - // can't support. - flash_enable_features(FLASH_PREFETCH | FLASH_ICACHE | FLASH_DCACHE); - // Configure the wait states, assuming we're operating at "close - // enough" to 3.3V. - flash_set_latency(FLASH_SAFE_WAIT_STATES); -} - -static void setup_clocks(void) { - // Turn on HSI. We'll switch to and run off of this while we're - // setting up the main PLL. - rcc_turn_on_clk(RCC_CLK_HSI); - - // Turn off and reset the clock subsystems we'll be using, as well - // as the clock security subsystem (CSS). Note that resetting CFGR - // to its default value of 0 implies a switch to HSI for SYSCLK. - RCC_BASE->CFGR = 0x00000000; - rcc_disable_css(); - rcc_turn_off_clk(RCC_CLK_PLL); - rcc_turn_off_clk(RCC_CLK_HSE); - wirish::priv::board_reset_pll(); - // Clear clock readiness interrupt flags and turn off clock - // readiness interrupts. - RCC_BASE->CIR = 0x00000000; -#if !USE_HSI_CLOCK - // Enable HSE, and wait until it's ready. - rcc_turn_on_clk(RCC_CLK_HSE); - while (!rcc_is_clk_ready(RCC_CLK_HSE)) - ; -#endif - // Configure AHBx, APBx, etc. prescalers and the main PLL. - wirish::priv::board_setup_clock_prescalers(); - rcc_configure_pll(&wirish::priv::w_board_pll_cfg); - - // Enable the PLL, and wait until it's ready. - rcc_turn_on_clk(RCC_CLK_PLL); - while(!rcc_is_clk_ready(RCC_CLK_PLL)) - ; - - // Finally, switch to the now-ready PLL as the main clock source. - rcc_switch_sysclk(RCC_CLKSRC_PLL); -} - -/* - * These addresses are where usercode starts when a bootloader is - * present. If no bootloader is present, the user NVIC usually starts - * at the Flash base address, 0x08000000. - */ -#if defined(BOOTLOADER_maple) - #define USER_ADDR_ROM 0x08002000 -#else - #define USER_ADDR_ROM 0x08000000 -#endif -#define USER_ADDR_RAM 0x20000C00 -extern char __text_start__; - -static void setup_nvic(void) { - -nvic_init((uint32)VECT_TAB_ADDR, 0); - -/* Roger Clark. We now control nvic vector table in boards.txt using the build.vect paramater -#ifdef VECT_TAB_FLASH - nvic_init(USER_ADDR_ROM, 0); -#elif defined VECT_TAB_RAM - nvic_init(USER_ADDR_RAM, 0); -#elif defined VECT_TAB_BASE - nvic_init((uint32)0x08000000, 0); -#elif defined VECT_TAB_ADDR - // A numerically supplied value - nvic_init((uint32)VECT_TAB_ADDR, 0); -#else - // Use the __text_start__ value from the linker script; this - // should be the start of the vector table. - nvic_init((uint32)&__text_start__, 0); -#endif - -*/ -} - -static void adc_default_config(adc_dev *dev) { - adc_enable_single_swstart(dev); - adc_set_sample_rate(dev, wirish::priv::w_adc_smp); -} - -static void setup_adcs(void) { - adc_set_prescaler(wirish::priv::w_adc_pre); - adc_foreach(adc_default_config); -} - -static void timer_default_config(timer_dev *dev) { - timer_adv_reg_map *regs = (dev->regs).adv; - const uint16 full_overflow = 0xFFFF; - const uint16 half_duty = 0x8FFF; - - timer_init(dev); - timer_pause(dev); - - regs->CR1 = TIMER_CR1_ARPE; - regs->PSC = 1; - regs->SR = 0; - regs->DIER = 0; - regs->EGR = TIMER_EGR_UG; - switch (dev->type) { - case TIMER_ADVANCED: - regs->BDTR = TIMER_BDTR_MOE | TIMER_BDTR_LOCK_OFF; - // fall-through - case TIMER_GENERAL: - timer_set_reload(dev, full_overflow); - for (uint8 channel = 1; channel <= 4; channel++) { - if (timer_has_cc_channel(dev, channel)) { - timer_set_compare(dev, channel, half_duty); - timer_oc_set_mode(dev, channel, TIMER_OC_MODE_PWM_1, - TIMER_OC_PE); - } - } - // fall-through - case TIMER_BASIC: - break; - } - - timer_generate_update(dev); - timer_resume(dev); -} - -static void setup_timers(void) { - timer_foreach(timer_default_config); -} diff --git a/buildroot/share/PlatformIO/variants/STEVAL_F401VE/PeripheralPins.c b/buildroot/share/PlatformIO/variants/STEVAL_F401VE/PeripheralPins.c deleted file mode 100644 index 5335361a6aef..000000000000 --- a/buildroot/share/PlatformIO/variants/STEVAL_F401VE/PeripheralPins.c +++ /dev/null @@ -1,274 +0,0 @@ - -/* - ******************************************************************************* - * Copyright (c) 2019, STMicroelectronics - * All rights reserved. - * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ******************************************************************************* - * Automatically generated from STM32F401V(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} -}; -#endif - -#ifdef HAL_I2C_MODULE_ENABLED -WEAK const PinMap PinMap_I2C_SCL[] = { - // {PA_8, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, - {PB_6, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, - // {PB_8, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, - // {PB_10, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, - {NC, NP, 0} -}; -#endif - -//*** PWM *** - -#ifdef HAL_TIM_MODULE_ENABLED -WEAK const PinMap PinMap_PWM[] = { - // {PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 - // {PA_0, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1 - // {PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 - // {PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 - // {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 - // {PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3 - // {PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 - // {PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 - // {PA_3, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 4, 0)}, // TIM5_CH4 - // {PA_3, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2 - // {PA_5, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 - // {PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 - // {PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N - // {PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 - // {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 - // {PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 - // {PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 - // {PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 - // {PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 - // {PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N - {PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 - // {PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N - {PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 - // {PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 - // {PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 - // {PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 - // {PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 - // {PB_7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 - // {PB_8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 - // {PB_8, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1 - // {PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 - // {PB_9, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 - {PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 - // {PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N - // {PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N - // {PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N - {PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 - {PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 - // {PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 - // {PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 - {PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 - {PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 - {PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 - {PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 - {PE_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 - // {PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 - // {PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N - // {PE_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 - // {PE_12, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N - // {PE_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 - {PE_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 - {NC, NP, 0} -}; -#endif - -//*** 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)}, - {PD_5, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - {NC, NP, 0} -}; -#endif - -#ifdef HAL_UART_MODULE_ENABLED -WEAK const PinMap PinMap_UART_RX[] = { - // {PA_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - {PA_10, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, - // {PA_12, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - // {PB_7, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, - // {PC_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - {PD_6, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - {NC, NP, 0} -}; -#endif - -#ifdef HAL_UART_MODULE_ENABLED -WEAK const PinMap PinMap_UART_RTS[] = { - // {PA_1, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - // {PA_12, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, - {PD_4, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - {NC, NP, 0} -}; -#endif - -#ifdef HAL_UART_MODULE_ENABLED -WEAK const PinMap PinMap_UART_CTS[] = { - // {PA_0, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - // {PA_11, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, - {PD_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - {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)}, - // {PD_6, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, - // {PE_6, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, - // {PE_14, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, - {NC, NP, 0} -}; -#endif - -#ifdef HAL_SPI_MODULE_ENABLED -WEAK const PinMap PinMap_SPI_MISO[] = { - {PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, - // {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)}, - // {PE_5, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, - // {PE_13, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, - {NC, NP, 0} -}; -#endif - -#ifdef HAL_SPI_MODULE_ENABLED -WEAK const PinMap PinMap_SPI_SCLK[] = { - {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, - // {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)}, - // {PD_3, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, - // {PE_2, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, - // {PE_12, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, - {NC, NP, 0} -}; -#endif - -#ifdef HAL_SPI_MODULE_ENABLED -WEAK const PinMap PinMap_SPI_SSEL[] = { - {PA_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)}, - // {PE_4, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, - // {PE_11, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, - {NC, NP, 0} -}; -#endif - -//*** No CAN *** - -//*** No ETHERNET *** - -//*** No QUADSPI *** - -//*** USB *** - -#ifdef HAL_PCD_MODULE_ENABLED -WEAK const PinMap PinMap_USB_OTG_FS[] = { - // {PA_8, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_SOF - // {PA_9, USB_OTG_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_FS_VBUS - // {PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_ID - {PA_11, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DM - {PA_12, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DP - {NC, NP, 0} -}; -#endif - -//*** No USB_OTG_HS *** -//*** SD *** - -#ifdef HAL_SD_MODULE_ENABLED -WEAK const PinMap PinMap_SD[] = { - // {PB_8, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D4 - // {PB_9, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D5 - // {PC_6, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D6 - // {PC_7, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D7 - {PC_8, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D0 - {PC_9, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D1 - {PC_10, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D2 - {PC_11, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D3 - {PC_12, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF12_SDIO)}, // SDIO_CK - {PD_2, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF12_SDIO)}, // SDIO_CMD - {NC, NP, 0} -}; -#endif diff --git a/buildroot/share/PlatformIO/variants/STEVAL_F401VE/hal_conf_custom.h b/buildroot/share/PlatformIO/variants/STEVAL_F401VE/hal_conf_custom.h deleted file mode 100644 index 0c7781997fef..000000000000 --- a/buildroot/share/PlatformIO/variants/STEVAL_F401VE/hal_conf_custom.h +++ /dev/null @@ -1,496 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_conf.h - * @brief HAL configuration file. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_CONF_CUSTOM -#define __STM32F4xx_HAL_CONF_CUSTOM - -#ifdef __cplusplus -extern "C" { -#endif - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ - -/* ########################## Module Selection ############################## */ - /** - * @brief This is the list of modules to be used in the HAL driver - */ -#define HAL_MODULE_ENABLED -#define HAL_ADC_MODULE_ENABLED -/* #define HAL_CAN_MODULE_ENABLED */ -/* #define HAL_CAN_LEGACY_MODULE_ENABLED */ -#define HAL_CRC_MODULE_ENABLED -/* #define HAL_CEC_MODULE_ENABLED */ -/* #define HAL_CRYP_MODULE_ENABLED */ -//#define HAL_DAC_MODULE_ENABLED -/* #define HAL_DCMI_MODULE_ENABLED */ -#define HAL_DMA_MODULE_ENABLED -/* #define HAL_DMA2D_MODULE_ENABLED */ -/* #define HAL_ETH_MODULE_ENABLED */ -#define HAL_FLASH_MODULE_ENABLED -/* #define HAL_NAND_MODULE_ENABLED */ -/* #define HAL_NOR_MODULE_ENABLED */ -/* #define HAL_PCCARD_MODULE_ENABLED */ -/* #define HAL_SRAM_MODULE_ENABLED */ -/* #define HAL_SDRAM_MODULE_ENABLED */ -/* #define HAL_HASH_MODULE_ENABLED */ -#define HAL_GPIO_MODULE_ENABLED -/* #define HAL_EXTI_MODULE_ENABLED */ -#define HAL_I2C_MODULE_ENABLED -/* #define HAL_SMBUS_MODULE_ENABLED */ -/* #define HAL_I2S_MODULE_ENABLED */ -#define HAL_IWDG_MODULE_ENABLED -/* #define HAL_LTDC_MODULE_ENABLED */ -/* #define HAL_DSI_MODULE_ENABLED */ -#define HAL_PWR_MODULE_ENABLED -/* #define HAL_QSPI_MODULE_ENABLED */ -#define HAL_RCC_MODULE_ENABLED -/* #define HAL_RNG_MODULE_ENABLED */ -#define HAL_RTC_MODULE_ENABLED -/* #define HAL_SAI_MODULE_ENABLED */ -#define HAL_SD_MODULE_ENABLED -#define HAL_SPI_MODULE_ENABLED -#define HAL_TIM_MODULE_ENABLED -/* #define HAL_UART_MODULE_ENABLED */ -/* #define HAL_USART_MODULE_ENABLED */ -/* #define HAL_IRDA_MODULE_ENABLED */ -/* #define HAL_SMARTCARD_MODULE_ENABLED */ -/* #define HAL_WWDG_MODULE_ENABLED */ -#define HAL_CORTEX_MODULE_ENABLED -#ifndef HAL_PCD_MODULE_ENABLED - #define HAL_PCD_MODULE_ENABLED //Since STM32 v3.10700.191028 this is automatically added if any type of USB is enabled (as in Arduino IDE) -#endif -/* #define HAL_HCD_MODULE_ENABLED */ -/* #define HAL_FMPI2C_MODULE_ENABLED */ -/* #define HAL_SPDIFRX_MODULE_ENABLED */ -/* #define HAL_DFSDM_MODULE_ENABLED */ -/* #define HAL_LPTIM_MODULE_ENABLED */ -/* #define HAL_MMC_MODULE_ENABLED */ - -/* ########################## HSE/HSI Values adaptation ##################### */ -/** - * @brief Adjust the value of External High Speed oscillator (HSE) used in your application. - * This value is used by the RCC HAL module to compute the system frequency - * (when HSE is used as system clock source, directly or through the PLL). - */ -#ifndef HSE_VALUE -#define HSE_VALUE 8000000U /*!< Value of the External oscillator in Hz */ -#endif /* HSE_VALUE */ - -#ifndef HSE_STARTUP_TIMEOUT -#define HSE_STARTUP_TIMEOUT 100U /*!< Time out for HSE start up, in ms */ -#endif /* HSE_STARTUP_TIMEOUT */ - -/** - * @brief Internal High Speed oscillator (HSI) value. - * This value is used by the RCC HAL module to compute the system frequency - * (when HSI is used as system clock source, directly or through the PLL). - */ -#ifndef HSI_VALUE -#define HSI_VALUE 16000000U /*!< Value of the Internal oscillator in Hz */ -#endif /* HSI_VALUE */ - -/** - * @brief Internal Low Speed oscillator (LSI) value. - */ -#ifndef LSI_VALUE -#define LSI_VALUE 32000U /*!< LSI Typical Value in Hz */ -#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz -The real value may vary depending on the variations -in voltage and temperature. */ -/** - * @brief External Low Speed oscillator (LSE) value. - */ -#ifndef LSE_VALUE -#define LSE_VALUE 32768U /*!< Value of the External Low Speed oscillator in Hz */ -#endif /* LSE_VALUE */ - -#ifndef LSE_STARTUP_TIMEOUT -#define LSE_STARTUP_TIMEOUT 5000U /*!< Time out for LSE start up, in ms */ -#endif /* LSE_STARTUP_TIMEOUT */ - -/** - * @brief External clock source for I2S peripheral - * This value is used by the I2S HAL module to compute the I2S clock source - * frequency, this source is inserted directly through I2S_CKIN pad. - */ -#ifndef EXTERNAL_CLOCK_VALUE -#define EXTERNAL_CLOCK_VALUE 12288000U /*!< Value of the External oscillator in Hz*/ -#endif /* EXTERNAL_CLOCK_VALUE */ - -/* Tip: To avoid modifying this file each time you need to use different HSE, - === you can define the HSE value in your toolchain compiler preprocessor. */ - -/* ########################### System Configuration ######################### */ -/** - * @brief This is the HAL system configuration section - */ -#if !defined (VDD_VALUE) -#define VDD_VALUE 3300U /*!< Value of VDD in mv */ -#endif -#if !defined (TICK_INT_PRIORITY) -#define TICK_INT_PRIORITY 0x00U /*!< tick interrupt priority */ -#endif -#if !defined (USE_RTOS) -#define USE_RTOS 0U -#endif -#if !defined (PREFETCH_ENABLE) -#define PREFETCH_ENABLE 1U -#endif -#if !defined (INSTRUCTION_CACHE_ENABLE) -#define INSTRUCTION_CACHE_ENABLE 1U -#endif -#if !defined (DATA_CACHE_ENABLE) -#define DATA_CACHE_ENABLE 1U -#endif - -#define USE_HAL_ADC_REGISTER_CALLBACKS 0U /* ADC register callback disabled */ -#define USE_HAL_CAN_REGISTER_CALLBACKS 0U /* CAN register callback disabled */ -#define USE_HAL_CEC_REGISTER_CALLBACKS 0U /* CEC register callback disabled */ -#define USE_HAL_CRYP_REGISTER_CALLBACKS 0U /* CRYP register callback disabled */ -#define USE_HAL_DAC_REGISTER_CALLBACKS 0U /* DAC register callback disabled */ -#define USE_HAL_DCMI_REGISTER_CALLBACKS 0U /* DCMI register callback disabled */ -#define USE_HAL_DFSDM_REGISTER_CALLBACKS 0U /* DFSDM register callback disabled */ -#define USE_HAL_DMA2D_REGISTER_CALLBACKS 0U /* DMA2D register callback disabled */ -#define USE_HAL_DSI_REGISTER_CALLBACKS 0U /* DSI register callback disabled */ -#define USE_HAL_ETH_REGISTER_CALLBACKS 0U /* ETH register callback disabled */ -#define USE_HAL_HASH_REGISTER_CALLBACKS 0U /* HASH register callback disabled */ -#define USE_HAL_HCD_REGISTER_CALLBACKS 0U /* HCD register callback disabled */ -#define USE_HAL_I2C_REGISTER_CALLBACKS 0U /* I2C register callback disabled */ -#define USE_HAL_FMPI2C_REGISTER_CALLBACKS 0U /* FMPI2C register callback disabled */ -#define USE_HAL_I2S_REGISTER_CALLBACKS 0U /* I2S register callback disabled */ -#define USE_HAL_IRDA_REGISTER_CALLBACKS 0U /* IRDA register callback disabled */ -#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0U /* LPTIM register callback disabled */ -#define USE_HAL_LTDC_REGISTER_CALLBACKS 0U /* LTDC register callback disabled */ -#define USE_HAL_MMC_REGISTER_CALLBACKS 0U /* MMC register callback disabled */ -#define USE_HAL_NAND_REGISTER_CALLBACKS 0U /* NAND register callback disabled */ -#define USE_HAL_NOR_REGISTER_CALLBACKS 0U /* NOR register callback disabled */ -#define USE_HAL_PCCARD_REGISTER_CALLBACKS 0U /* PCCARD register callback disabled */ -#define USE_HAL_PCD_REGISTER_CALLBACKS 0U /* PCD register callback disabled */ -#define USE_HAL_QSPI_REGISTER_CALLBACKS 0U /* QSPI register callback disabled */ -#define USE_HAL_RNG_REGISTER_CALLBACKS 0U /* RNG register callback disabled */ -#define USE_HAL_RTC_REGISTER_CALLBACKS 0U /* RTC register callback disabled */ -#define USE_HAL_SAI_REGISTER_CALLBACKS 0U /* SAI register callback disabled */ -#define USE_HAL_SD_REGISTER_CALLBACKS 0U /* SD register callback disabled */ -#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0U /* SMARTCARD register callback disabled */ -#define USE_HAL_SDRAM_REGISTER_CALLBACKS 0U /* SDRAM register callback disabled */ -#define USE_HAL_SRAM_REGISTER_CALLBACKS 0U /* SRAM register callback disabled */ -#define USE_HAL_SPDIFRX_REGISTER_CALLBACKS 0U /* SPDIFRX register callback disabled */ -#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U /* SMBUS register callback disabled */ -#define USE_HAL_SPI_REGISTER_CALLBACKS 0U /* SPI register callback disabled */ -#define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */ -#define USE_HAL_UART_REGISTER_CALLBACKS 0U /* UART register callback disabled */ -#define USE_HAL_USART_REGISTER_CALLBACKS 0U /* USART register callback disabled */ -#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */ - -/* ########################## Assert Selection ############################## */ -/** - * @brief Uncomment the line below to expanse the "assert_param" macro in the - * HAL drivers code - */ -/* #define USE_FULL_ASSERT 1U */ - -/* ################## Ethernet peripheral configuration ##################### */ - -/* Section 1 : Ethernet peripheral configuration */ - -/* MAC ADDRESS: MAC_ADDR0:MAC_ADDR1:MAC_ADDR2:MAC_ADDR3:MAC_ADDR4:MAC_ADDR5 */ -#define MAC_ADDR0 2U -#define MAC_ADDR1 0U -#define MAC_ADDR2 0U -#define MAC_ADDR3 0U -#define MAC_ADDR4 0U -#define MAC_ADDR5 0U - -/* Definition of the Ethernet driver buffers size and count */ -#define ETH_RX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for receive */ -#define ETH_TX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for transmit */ -#define ETH_RXBUFNB ((uint32_t)4U) /* 4 Rx buffers of size ETH_RX_BUF_SIZE */ -#define ETH_TXBUFNB ((uint32_t)4U) /* 4 Tx buffers of size ETH_TX_BUF_SIZE */ - -/* Section 2: PHY configuration section */ - -/* DP83848_PHY_ADDRESS Address*/ -#define DP83848_PHY_ADDRESS 0x01U -/* PHY Reset delay these values are based on a 1 ms Systick interrupt*/ -#define PHY_RESET_DELAY 0x000000FFU -/* PHY Configuration delay */ -#define PHY_CONFIG_DELAY 0x00000FFFU - -#define PHY_READ_TO 0x0000FFFFU -#define PHY_WRITE_TO 0x0000FFFFU - -/* Section 3: Common PHY Registers */ - -#define PHY_BCR ((uint16_t)0x0000) /*!< Transceiver Basic Control Register */ -#define PHY_BSR ((uint16_t)0x0001) /*!< Transceiver Basic Status Register */ - -#define PHY_RESET ((uint16_t)0x8000) /*!< PHY Reset */ -#define PHY_LOOPBACK ((uint16_t)0x4000) /*!< Select loop-back mode */ -#define PHY_FULLDUPLEX_100M ((uint16_t)0x2100) /*!< Set the full-duplex mode at 100 Mb/s */ -#define PHY_HALFDUPLEX_100M ((uint16_t)0x2000) /*!< Set the half-duplex mode at 100 Mb/s */ -#define PHY_FULLDUPLEX_10M ((uint16_t)0x0100) /*!< Set the full-duplex mode at 10 Mb/s */ -#define PHY_HALFDUPLEX_10M ((uint16_t)0x0000) /*!< Set the half-duplex mode at 10 Mb/s */ -#define PHY_AUTONEGOTIATION ((uint16_t)0x1000) /*!< Enable auto-negotiation function */ -#define PHY_RESTART_AUTONEGOTIATION ((uint16_t)0x0200) /*!< Restart auto-negotiation function */ -#define PHY_POWERDOWN ((uint16_t)0x0800) /*!< Select the power down mode */ -#define PHY_ISOLATE ((uint16_t)0x0400) /*!< Isolate PHY from MII */ - -#define PHY_AUTONEGO_COMPLETE ((uint16_t)0x0020) /*!< Auto-Negotiation process completed */ -#define PHY_LINKED_STATUS ((uint16_t)0x0004) /*!< Valid link established */ -#define PHY_JABBER_DETECTION ((uint16_t)0x0002) /*!< Jabber condition detected */ - -/* Section 4: Extended PHY Registers */ -#define PHY_SR ((uint16_t)0x10U) /*!< PHY status register Offset */ - -#define PHY_SPEED_STATUS ((uint16_t)0x0002U) /*!< PHY Speed mask */ -#define PHY_DUPLEX_STATUS ((uint16_t)0x0004U) /*!< PHY Duplex mask */ - -/* ################## SPI peripheral configuration ########################## */ - -/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver - * Activated: CRC code is present inside driver - * Deactivated: CRC code cleaned from driver - */ -#ifndef USE_SPI_CRC -#define USE_SPI_CRC 0U -#endif - -/* Includes ------------------------------------------------------------------*/ -/** - * @brief Include module's header file - */ - -#ifdef HAL_RCC_MODULE_ENABLED -#include "stm32f4xx_hal_rcc.h" -#endif /* HAL_RCC_MODULE_ENABLED */ - -#ifdef HAL_GPIO_MODULE_ENABLED -#include "stm32f4xx_hal_gpio.h" -#endif /* HAL_GPIO_MODULE_ENABLED */ - -#ifdef HAL_EXTI_MODULE_ENABLED -#include "stm32f4xx_hal_exti.h" -#endif /* HAL_EXTI_MODULE_ENABLED */ - -#ifdef HAL_DMA_MODULE_ENABLED -#include "stm32f4xx_hal_dma.h" -#endif /* HAL_DMA_MODULE_ENABLED */ - -#ifdef HAL_CORTEX_MODULE_ENABLED -#include "stm32f4xx_hal_cortex.h" -#endif /* HAL_CORTEX_MODULE_ENABLED */ - -#ifdef HAL_ADC_MODULE_ENABLED -#include "stm32f4xx_hal_adc.h" -#endif /* HAL_ADC_MODULE_ENABLED */ - -#ifdef HAL_CAN_MODULE_ENABLED -#include "stm32f4xx_hal_can.h" -#endif /* HAL_CAN_MODULE_ENABLED */ - -#ifdef HAL_CAN_LEGACY_MODULE_ENABLED -#include "stm32f4xx_hal_can_legacy.h" -#endif /* HAL_CAN_LEGACY_MODULE_ENABLED */ - -#ifdef HAL_CRC_MODULE_ENABLED -#include "stm32f4xx_hal_crc.h" -#endif /* HAL_CRC_MODULE_ENABLED */ - -#ifdef HAL_CRYP_MODULE_ENABLED -#include "stm32f4xx_hal_cryp.h" -#endif /* HAL_CRYP_MODULE_ENABLED */ - -#ifdef HAL_DMA2D_MODULE_ENABLED -#include "stm32f4xx_hal_dma2d.h" -#endif /* HAL_DMA2D_MODULE_ENABLED */ - -#ifdef HAL_DAC_MODULE_ENABLED -#include "stm32f4xx_hal_dac.h" -#endif /* HAL_DAC_MODULE_ENABLED */ - -#ifdef HAL_DCMI_MODULE_ENABLED -#include "stm32f4xx_hal_dcmi.h" -#endif /* HAL_DCMI_MODULE_ENABLED */ - -#ifdef HAL_ETH_MODULE_ENABLED -#include "stm32f4xx_hal_eth.h" -#endif /* HAL_ETH_MODULE_ENABLED */ - -#ifdef HAL_FLASH_MODULE_ENABLED -#include "stm32f4xx_hal_flash.h" -#endif /* HAL_FLASH_MODULE_ENABLED */ - -#ifdef HAL_SRAM_MODULE_ENABLED -#include "stm32f4xx_hal_sram.h" -#endif /* HAL_SRAM_MODULE_ENABLED */ - -#ifdef HAL_NOR_MODULE_ENABLED -#include "stm32f4xx_hal_nor.h" -#endif /* HAL_NOR_MODULE_ENABLED */ - -#ifdef HAL_NAND_MODULE_ENABLED -#include "stm32f4xx_hal_nand.h" -#endif /* HAL_NAND_MODULE_ENABLED */ - -#ifdef HAL_PCCARD_MODULE_ENABLED -#include "stm32f4xx_hal_pccard.h" -#endif /* HAL_PCCARD_MODULE_ENABLED */ - -#ifdef HAL_SDRAM_MODULE_ENABLED -#include "stm32f4xx_hal_sdram.h" -#endif /* HAL_SDRAM_MODULE_ENABLED */ - -#ifdef HAL_HASH_MODULE_ENABLED -#include "stm32f4xx_hal_hash.h" -#endif /* HAL_HASH_MODULE_ENABLED */ - -#ifdef HAL_I2C_MODULE_ENABLED -#include "stm32f4xx_hal_i2c.h" -#endif /* HAL_I2C_MODULE_ENABLED */ - -#ifdef HAL_SMBUS_MODULE_ENABLED -#include "stm32f4xx_hal_smbus.h" -#endif /* HAL_SMBUS_MODULE_ENABLED */ - -#ifdef HAL_I2S_MODULE_ENABLED -#include "stm32f4xx_hal_i2s.h" -#endif /* HAL_I2S_MODULE_ENABLED */ - -#ifdef HAL_IWDG_MODULE_ENABLED -#include "stm32f4xx_hal_iwdg.h" -#endif /* HAL_IWDG_MODULE_ENABLED */ - -#ifdef HAL_LTDC_MODULE_ENABLED -#include "stm32f4xx_hal_ltdc.h" -#endif /* HAL_LTDC_MODULE_ENABLED */ - -#ifdef HAL_PWR_MODULE_ENABLED -#include "stm32f4xx_hal_pwr.h" -#endif /* HAL_PWR_MODULE_ENABLED */ - -#ifdef HAL_RNG_MODULE_ENABLED -#include "stm32f4xx_hal_rng.h" -#endif /* HAL_RNG_MODULE_ENABLED */ - -#ifdef HAL_RTC_MODULE_ENABLED -#include "stm32f4xx_hal_rtc.h" -#endif /* HAL_RTC_MODULE_ENABLED */ - -#ifdef HAL_SAI_MODULE_ENABLED -#include "stm32f4xx_hal_sai.h" -#endif /* HAL_SAI_MODULE_ENABLED */ - -#ifdef HAL_SD_MODULE_ENABLED -#include "stm32f4xx_hal_sd.h" -#endif /* HAL_SD_MODULE_ENABLED */ - -#ifdef HAL_SPI_MODULE_ENABLED -#include "stm32f4xx_hal_spi.h" -#endif /* HAL_SPI_MODULE_ENABLED */ - -#ifdef HAL_TIM_MODULE_ENABLED -#include "stm32f4xx_hal_tim.h" -#endif /* HAL_TIM_MODULE_ENABLED */ - -#ifdef HAL_UART_MODULE_ENABLED -#include "stm32f4xx_hal_uart.h" -#endif /* HAL_UART_MODULE_ENABLED */ - -#ifdef HAL_USART_MODULE_ENABLED -#include "stm32f4xx_hal_usart.h" -#endif /* HAL_USART_MODULE_ENABLED */ - -#ifdef HAL_IRDA_MODULE_ENABLED -#include "stm32f4xx_hal_irda.h" -#endif /* HAL_IRDA_MODULE_ENABLED */ - -#ifdef HAL_SMARTCARD_MODULE_ENABLED -#include "stm32f4xx_hal_smartcard.h" -#endif /* HAL_SMARTCARD_MODULE_ENABLED */ - -#ifdef HAL_WWDG_MODULE_ENABLED -#include "stm32f4xx_hal_wwdg.h" -#endif /* HAL_WWDG_MODULE_ENABLED */ - -#ifdef HAL_PCD_MODULE_ENABLED -#include "stm32f4xx_hal_pcd.h" -#endif /* HAL_PCD_MODULE_ENABLED */ - -#ifdef HAL_HCD_MODULE_ENABLED -#include "stm32f4xx_hal_hcd.h" -#endif /* HAL_HCD_MODULE_ENABLED */ - -#ifdef HAL_DSI_MODULE_ENABLED -#include "stm32f4xx_hal_dsi.h" -#endif /* HAL_DSI_MODULE_ENABLED */ - -#ifdef HAL_QSPI_MODULE_ENABLED -#include "stm32f4xx_hal_qspi.h" -#endif /* HAL_QSPI_MODULE_ENABLED */ - -#ifdef HAL_CEC_MODULE_ENABLED -#include "stm32f4xx_hal_cec.h" -#endif /* HAL_CEC_MODULE_ENABLED */ - -#ifdef HAL_FMPI2C_MODULE_ENABLED -#include "stm32f4xx_hal_fmpi2c.h" -#endif /* HAL_FMPI2C_MODULE_ENABLED */ - -#ifdef HAL_SPDIFRX_MODULE_ENABLED -#include "stm32f4xx_hal_spdifrx.h" -#endif /* HAL_SPDIFRX_MODULE_ENABLED */ - -#ifdef HAL_DFSDM_MODULE_ENABLED -#include "stm32f4xx_hal_dfsdm.h" -#endif /* HAL_DFSDM_MODULE_ENABLED */ - -#ifdef HAL_LPTIM_MODULE_ENABLED -#include "stm32f4xx_hal_lptim.h" -#endif /* HAL_LPTIM_MODULE_ENABLED */ - -#ifdef HAL_MMC_MODULE_ENABLED -#include "stm32f4xx_hal_mmc.h" -#endif /* HAL_MMC_MODULE_ENABLED */ - -/* Exported macro ------------------------------------------------------------*/ -#ifdef USE_FULL_ASSERT -/** - * @brief The assert_param macro is used for function's parameters check. - * @param expr If expr is false, it calls assert_failed function - * which reports the name of the source file and the source - * line number of the call that failed. - * If expr is true, it returns no value. - * @retval None - */ -#define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__)) -/* Exported functions ------------------------------------------------------- */ -void assert_failed(uint8_t *file, uint32_t line); -#else -#define assert_param(expr) ((void)0U) -#endif /* USE_FULL_ASSERT */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_CONF_CUSTOM_H */ - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/buildroot/share/PlatformIO/variants/STEVAL_F401VE/ldscript.ld b/buildroot/share/PlatformIO/variants/STEVAL_F401VE/ldscript.ld deleted file mode 100644 index f20a047c6574..000000000000 --- a/buildroot/share/PlatformIO/variants/STEVAL_F401VE/ldscript.ld +++ /dev/null @@ -1,187 +0,0 @@ -/* -***************************************************************************** -** -** 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 = 0x20018000; /* 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 = 0x08000000, LENGTH = 512K -RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Define output sections */ -SECTIONS -{ - /* The startup code goes first into FLASH */ - .isr_vector : - { - . = ALIGN(4); - KEEP(*(.isr_vector)) /* Startup code */ - . = ALIGN(4); - } >FLASH - - /* The program code and other data goes into FLASH */ - .text : - { - . = ALIGN(4); - *(.text) /* .text sections (code) */ - *(.text*) /* .text* sections (code) */ - *(.glue_7) /* glue arm to thumb code */ - *(.glue_7t) /* glue thumb to arm code */ - *(.eh_frame) - - KEEP (*(.init)) - KEEP (*(.fini)) - - . = ALIGN(4); - _etext = .; /* define a global symbols at end of code */ - } >FLASH - - /* Constant data goes into FLASH */ - .rodata : - { - . = ALIGN(4); - *(.rodata) /* .rodata sections (constants, strings, etc.) */ - *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ - . = ALIGN(4); - } >FLASH - - .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH - .ARM : { - __exidx_start = .; - *(.ARM.exidx*) - __exidx_end = .; - } >FLASH - - .preinit_array : - { - PROVIDE_HIDDEN (__preinit_array_start = .); - KEEP (*(.preinit_array*)) - PROVIDE_HIDDEN (__preinit_array_end = .); - } >FLASH - .init_array : - { - PROVIDE_HIDDEN (__init_array_start = .); - KEEP (*(SORT(.init_array.*))) - KEEP (*(.init_array*)) - PROVIDE_HIDDEN (__init_array_end = .); - } >FLASH - .fini_array : - { - PROVIDE_HIDDEN (__fini_array_start = .); - KEEP (*(SORT(.fini_array.*))) - KEEP (*(.fini_array*)) - PROVIDE_HIDDEN (__fini_array_end = .); - } >FLASH - - /* used by the startup to initialize data */ - _sidata = LOADADDR(.data); - - /* Initialized data sections goes into RAM, load LMA copy after code */ - .data : - { - . = ALIGN(4); - _sdata = .; /* create a global symbol at data start */ - *(.data) /* .data sections */ - *(.data*) /* .data* sections */ - - . = ALIGN(4); - _edata = .; /* define a global symbol at data end */ - } >RAM AT> FLASH - - - /* Uninitialized data section */ - . = ALIGN(4); - .bss : - { - /* This is used by the startup in order to initialize the .bss secion */ - _sbss = .; /* define a global symbol at bss start */ - __bss_start__ = _sbss; - *(.bss) - *(.bss*) - *(COMMON) - - . = ALIGN(4); - _ebss = .; /* define a global symbol at bss end */ - __bss_end__ = _ebss; - } >RAM - - /* User_heap_stack section, used to check that there is enough RAM left */ - ._user_heap_stack : - { - . = ALIGN(4); - PROVIDE ( end = . ); - PROVIDE ( _end = . ); - . = . + _Min_Heap_Size; - . = . + _Min_Stack_Size; - . = ALIGN(4); - } >RAM - - - - /* Remove information from the standard libraries */ - /DISCARD/ : - { - libc.a ( * ) - libm.a ( * ) - libgcc.a ( * ) - } - - .ARM.attributes 0 : { *(.ARM.attributes) } -} - - diff --git a/buildroot/share/PlatformIO/variants/archim/variant.h b/buildroot/share/PlatformIO/variants/archim/variant.h deleted file mode 100644 index 179a13735376..000000000000 --- a/buildroot/share/PlatformIO/variants/archim/variant.h +++ /dev/null @@ -1,284 +0,0 @@ -/* - 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_DUE_X_ -#define _VARIANT_ARDUINO_DUE_X_ - -/*---------------------------------------------------------------------------- - * Definitions - *----------------------------------------------------------------------------*/ - -/** Frequency of the board main oscillator */ -#define VARIANT_MAINOSC 12000000 - -/** Master clock frequency */ -#define VARIANT_MCK 84000000 - -/*---------------------------------------------------------------------------- - * Headers - *----------------------------------------------------------------------------*/ - -#include "Arduino.h" -#ifdef __cplusplus -#include "UARTClass.h" -#include "USARTClass.h" -#endif - -#ifdef __cplusplus -extern "C"{ -#endif // __cplusplus - -/** - * Libc porting layers - */ -#if defined ( __GNUC__ ) /* GCC CS3 */ -# include /** RedHat Newlib minimal stub */ -#endif - -/*---------------------------------------------------------------------------- - * Pins - *----------------------------------------------------------------------------*/ - -// Number of pins defined in PinDescription array -#define PINS_COUNT (79U) -#define NUM_DIGITAL_PINS (66U) -#define NUM_ANALOG_INPUTS (12U) -#define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) - -#define digitalPinToPort(P) ( g_APinDescription[P].pPort ) -#define digitalPinToBitMask(P) ( g_APinDescription[P].ulPin ) -//#define analogInPinToBit(P) ( ) -#define portOutputRegister(port) ( &(port->PIO_ODSR) ) -#define portInputRegister(port) ( &(port->PIO_PDSR) ) -#define digitalPinHasPWM(P) ( g_APinDescription[P].ulPWMChannel != NOT_ON_PWM || g_APinDescription[P].ulTCChannel != NOT_ON_TIMER ) - -/* - * portModeRegister(..) should return a register to set pin mode - * INPUT or OUTPUT by setting the corresponding bit to 0 or 1. - * Unfortunately on SAM architecture the PIO_OSR register is - * read-only and can be set only through the enable/disable registers - * pair PIO_OER/PIO_ODR. - */ -// #define portModeRegister(port) ( &(port->PIO_OSR) ) - -/* - * digitalPinToTimer(..) is AVR-specific and is not defined for SAM - * architecture. If you need to check if a pin supports PWM you must - * use digitalPinHasPWM(..). - * - * https://github.com/arduino/Arduino/issues/1833 - */ -// #define digitalPinToTimer(P) - -// Interrupts -#define digitalPinToInterrupt(p) ((p) < NUM_DIGITAL_PINS ? (p) : -1) - -// LEDs -#define PIN_LED_13 (13U) -#define PIN_LED_RXL (72U) -#define PIN_LED_TXL (73U) -#define PIN_LED PIN_LED_13 -#define PIN_LED2 PIN_LED_RXL -#define PIN_LED3 PIN_LED_TXL -#define LED_BUILTIN 13 - -/* - * SPI Interfaces - */ -#define SPI_INTERFACES_COUNT 1 - -#define SPI_INTERFACE SPI0 -#define SPI_INTERFACE_ID ID_SPI0 -#define SPI_CHANNELS_NUM 4 -#define PIN_SPI_SS0 (77U) -#define PIN_SPI_SS1 (87U) -#define PIN_SPI_SS2 (86U) -#define PIN_SPI_SS3 (78U) -#define PIN_SPI_MOSI (75U) -#define PIN_SPI_MISO (74U) -#define PIN_SPI_SCK (76U) -#define BOARD_SPI_SS0 (77U) //(10U) -#define BOARD_SPI_SS1 (4U) -#define BOARD_SPI_SS2 (52U) -#define BOARD_SPI_SS3 PIN_SPI_SS3 -#define BOARD_SPI_DEFAULT_SS BOARD_SPI_SS3 - -#define BOARD_PIN_TO_SPI_PIN(x) \ - (x==BOARD_SPI_SS0 ? PIN_SPI_SS0 : \ - (x==BOARD_SPI_SS1 ? PIN_SPI_SS1 : \ - (x==BOARD_SPI_SS2 ? PIN_SPI_SS2 : PIN_SPI_SS3 ))) -#define BOARD_PIN_TO_SPI_CHANNEL(x) \ - (x==BOARD_SPI_SS0 ? 0 : \ - (x==BOARD_SPI_SS1 ? 1 : \ - (x==BOARD_SPI_SS2 ? 2 : 3))) - -static const uint8_t SS = BOARD_SPI_SS0; -static const uint8_t SS1 = BOARD_SPI_SS1; -static const uint8_t SS2 = BOARD_SPI_SS2; -static const uint8_t SS3 = BOARD_SPI_SS3; -static const uint8_t MOSI = PIN_SPI_MOSI; -static const uint8_t MISO = PIN_SPI_MISO; -static const uint8_t SCK = PIN_SPI_SCK; - -/* - * Wire Interfaces - */ -#define WIRE_INTERFACES_COUNT 2 - -#define PIN_WIRE_SDA (20U) -#define PIN_WIRE_SCL (21U) -#define WIRE_INTERFACE TWI1 -#define WIRE_INTERFACE_ID ID_TWI1 -#define WIRE_ISR_HANDLER TWI1_Handler -#define WIRE_ISR_ID TWI1_IRQn - -#define PIN_WIRE1_SDA (70U) -#define PIN_WIRE1_SCL (71U) -#define WIRE1_INTERFACE TWI0 -#define WIRE1_INTERFACE_ID ID_TWI0 -#define WIRE1_ISR_HANDLER TWI0_Handler -#define WIRE1_ISR_ID TWI0_IRQn - -static const uint8_t SDA = PIN_WIRE_SDA; -static const uint8_t SCL = PIN_WIRE_SCL; -static const uint8_t SDA1 = PIN_WIRE1_SDA; -static const uint8_t SCL1 = PIN_WIRE1_SCL; - -/* - * UART/USART Interfaces - */ -// Serial -#define PINS_UART (81U) -// Serial1 -#define PINS_USART0 (82U) -// Serial2 -#define PINS_USART1 (83U) -// Serial3 -#define PINS_USART3 (84U) - -/* - * USB Interfaces - */ -#define PINS_USB (85U) - -/* - * Analog pins - */ -static const uint8_t A0 = 54; -static const uint8_t A1 = 55; -static const uint8_t A2 = 56; -static const uint8_t A3 = 57; -static const uint8_t A4 = 58; -static const uint8_t A5 = 59; -static const uint8_t A6 = 60; -static const uint8_t A7 = 61; -static const uint8_t A8 = 62; -static const uint8_t A9 = 63; -static const uint8_t A10 = 64; -static const uint8_t A11 = 65; -static const uint8_t DAC0 = 66; -static const uint8_t DAC1 = 67; -static const uint8_t CANRX = 68; -static const uint8_t CANTX = 69; -#define ADC_RESOLUTION 12 - -/* - * Complementary CAN pins - */ -static const uint8_t CAN1RX = 88; -static const uint8_t CAN1TX = 89; - -// CAN0 -#define PINS_CAN0 (90U) -// CAN1 -#define PINS_CAN1 (91U) - - -/* - * DACC - */ -#define DACC_INTERFACE DACC -#define DACC_INTERFACE_ID ID_DACC -#define DACC_RESOLUTION 12 -#define DACC_ISR_HANDLER DACC_Handler -#define DACC_ISR_ID DACC_IRQn - -/* - * PWM - */ -#define PWM_INTERFACE PWM -#define PWM_INTERFACE_ID ID_PWM -#define PWM_FREQUENCY 31000 -#define PWM_MAX_DUTY_CYCLE 255 -#define PWM_MIN_DUTY_CYCLE 0 -#define PWM_RESOLUTION 8 - -/* - * TC - */ -#define TC_INTERFACE TC0 -#define TC_INTERFACE_ID ID_TC0 -#define TC_FREQUENCY 100000 -#define TC_MAX_DUTY_CYCLE 255 -#define TC_MIN_DUTY_CYCLE 0 -#define TC_RESOLUTION 8 - -#ifdef __cplusplus -} -#endif - -/*---------------------------------------------------------------------------- - * Arduino objects - C++ only - *----------------------------------------------------------------------------*/ - -#ifdef __cplusplus - -extern UARTClass Serial; -extern USARTClass Serial1; -extern USARTClass Serial2; -extern USARTClass Serial3; - -#endif - -// 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_USBVIRTUAL SerialUSB -#define SERIAL_PORT_HARDWARE_OPEN Serial1 -#define SERIAL_PORT_HARDWARE_OPEN1 Serial2 -#define SERIAL_PORT_HARDWARE_OPEN2 Serial3 -#define SERIAL_PORT_HARDWARE Serial -#define SERIAL_PORT_HARDWARE1 Serial1 -#define SERIAL_PORT_HARDWARE2 Serial2 -#define SERIAL_PORT_HARDWARE3 Serial3 - -#endif /* _VARIANT_ARDUINO_DUE_X_ */ - diff --git a/buildroot/share/PlatformIO/variants/CHITU_F103/board.cpp b/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/board.cpp old mode 100755 new mode 100644 similarity index 100% rename from buildroot/share/PlatformIO/variants/CHITU_F103/board.cpp rename to buildroot/share/PlatformIO/variants/marlin_CHITU_F103/board.cpp diff --git a/buildroot/share/PlatformIO/variants/CHITU_F103/board/board.h b/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/board/board.h old mode 100755 new mode 100644 similarity index 99% rename from buildroot/share/PlatformIO/variants/CHITU_F103/board/board.h rename to buildroot/share/PlatformIO/variants/marlin_CHITU_F103/board/board.h index 20fd9d379f19..a1e33467434a --- a/buildroot/share/PlatformIO/variants/CHITU_F103/board/board.h +++ b/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/board/board.h @@ -69,14 +69,11 @@ #define BOARD_SPI1_MISO_PIN PA6 #define BOARD_SPI1_MOSI_PIN PA7 - - #define BOARD_SPI2_NSS_PIN PB12 #define BOARD_SPI2_SCK_PIN PB13 #define BOARD_SPI2_MISO_PIN PB14 #define BOARD_SPI2_MOSI_PIN PB15 - #define BOARD_SPI3_NSS_PIN PA15 #define BOARD_SPI3_SCK_PIN PB3 #define BOARD_SPI3_MISO_PIN PB4 diff --git a/buildroot/share/PlatformIO/variants/CHITU_F103/ld/common.inc b/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/ld/common.inc similarity index 100% rename from buildroot/share/PlatformIO/variants/CHITU_F103/ld/common.inc rename to buildroot/share/PlatformIO/variants/marlin_CHITU_F103/ld/common.inc diff --git a/buildroot/share/PlatformIO/variants/CHITU_F103/ld/extra_libs.inc b/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/ld/extra_libs.inc similarity index 100% rename from buildroot/share/PlatformIO/variants/CHITU_F103/ld/extra_libs.inc rename to buildroot/share/PlatformIO/variants/marlin_CHITU_F103/ld/extra_libs.inc diff --git a/buildroot/share/PlatformIO/ldscripts/chitu_f103.ld b/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/ld/flash.ld similarity index 100% rename from buildroot/share/PlatformIO/ldscripts/chitu_f103.ld rename to buildroot/share/PlatformIO/variants/marlin_CHITU_F103/ld/flash.ld diff --git a/buildroot/share/PlatformIO/variants/CHITU_F103/ld/stm32f103z_dfu.ld b/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/ld/stm32f103z_dfu.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/CHITU_F103/ld/stm32f103z_dfu.ld rename to buildroot/share/PlatformIO/variants/marlin_CHITU_F103/ld/stm32f103z_dfu.ld diff --git a/buildroot/share/PlatformIO/variants/CHITU_F103/ld/stm32f103zc.ld b/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/ld/stm32f103zc.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/CHITU_F103/ld/stm32f103zc.ld rename to buildroot/share/PlatformIO/variants/marlin_CHITU_F103/ld/stm32f103zc.ld diff --git a/buildroot/share/PlatformIO/variants/CHITU_F103/ld/stm32f103zd.ld b/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/ld/stm32f103zd.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/CHITU_F103/ld/stm32f103zd.ld rename to buildroot/share/PlatformIO/variants/marlin_CHITU_F103/ld/stm32f103zd.ld diff --git a/buildroot/share/PlatformIO/variants/CHITU_F103/ld/stm32f103ze.ld b/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/ld/stm32f103ze.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/CHITU_F103/ld/stm32f103ze.ld rename to buildroot/share/PlatformIO/variants/marlin_CHITU_F103/ld/stm32f103ze.ld diff --git a/buildroot/share/PlatformIO/variants/CHITU_F103/ld/vector_symbols.inc b/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/ld/vector_symbols.inc similarity index 100% rename from buildroot/share/PlatformIO/variants/CHITU_F103/ld/vector_symbols.inc rename to buildroot/share/PlatformIO/variants/marlin_CHITU_F103/ld/vector_symbols.inc diff --git a/buildroot/share/PlatformIO/variants/CHITU_F103/pins_arduino.h b/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/pins_arduino.h old mode 100755 new mode 100644 similarity index 100% rename from buildroot/share/PlatformIO/variants/CHITU_F103/pins_arduino.h rename to buildroot/share/PlatformIO/variants/marlin_CHITU_F103/pins_arduino.h diff --git a/buildroot/share/PlatformIO/variants/CHITU_F103/variant.h b/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/variant.h old mode 100755 new mode 100644 similarity index 100% rename from buildroot/share/PlatformIO/variants/CHITU_F103/variant.h rename to buildroot/share/PlatformIO/variants/marlin_CHITU_F103/variant.h diff --git a/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/wirish/boards.cpp b/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/wirish/boards.cpp new file mode 100644 index 000000000000..f22cf354e208 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/wirish/boards.cpp @@ -0,0 +1,225 @@ +/****************************************************************************** + * The MIT License + * + * Copyright (c) 2010 Perry Hung. + * Copyright (c) 2011, 2012 LeafLabs, LLC. + * + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without + * restriction, including without limitation the rights to use, copy, + * modify, merge, publish, distribute, sublicense, and/or sell copies + * of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS + * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN + * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + *****************************************************************************/ + +/** + * @file wirish/boards.cpp + * @brief init() and board routines. + * + * This file is mostly interesting for the init() function, which + * configures Flash, the core clocks, and a variety of other available + * peripherals on the board so the rest of Wirish doesn't have to turn + * things on before using them. + * + * Prior to returning, init() calls boardInit(), which allows boards + * to perform any initialization they need to. This file includes a + * weak no-op definition of boardInit(), so boards that don't need any + * special initialization don't have to define their own. + * + * How init() works is chip-specific. See the boards_setup.cpp files + * under e.g. wirish/stm32f1/, wirish/stmf32f2 for the details, but be + * advised: their contents are unstable, and can/will change without + * notice. + */ + +#include +#include +#include +#include +#include +#include "boards_private.h" + +static void setup_flash(void); +static void setup_clocks(void); +static void setup_nvic(void); +static void setup_adcs(void); +static void setup_timers(void); + +/* + * Exported functions + */ + +void init(void) { + setup_flash(); + setup_clocks(); + setup_nvic(); + systick_init(SYSTICK_RELOAD_VAL); + wirish::priv::board_setup_gpio(); + setup_adcs(); + setup_timers(); + wirish::priv::board_setup_usb(); + wirish::priv::series_init(); + boardInit(); +} + +/* Provide a default no-op boardInit(). */ +__weak void boardInit(void) { +} + +/* You could farm this out to the files in boards/ if e.g. it takes + * too long to test on boards with lots of pins. */ +bool boardUsesPin(uint8 pin) { + for (int i = 0; i < BOARD_NR_USED_PINS; i++) { + if (pin == boardUsedPins[i]) { + return true; + } + } + return false; +} + +/* + * Auxiliary routines + */ + +static void setup_flash(void) { + // Turn on as many Flash "go faster" features as + // possible. flash_enable_features() just ignores any flags it + // can't support. + flash_enable_features(FLASH_PREFETCH | FLASH_ICACHE | FLASH_DCACHE); + // Configure the wait states, assuming we're operating at "close + // enough" to 3.3V. + flash_set_latency(FLASH_SAFE_WAIT_STATES); +} + +static void setup_clocks(void) { + // Turn on HSI. We'll switch to and run off of this while we're + // setting up the main PLL. + rcc_turn_on_clk(RCC_CLK_HSI); + + // Turn off and reset the clock subsystems we'll be using, as well + // as the clock security subsystem (CSS). Note that resetting CFGR + // to its default value of 0 implies a switch to HSI for SYSCLK. + RCC_BASE->CFGR = 0x00000000; + rcc_disable_css(); + rcc_turn_off_clk(RCC_CLK_PLL); + rcc_turn_off_clk(RCC_CLK_HSE); + wirish::priv::board_reset_pll(); + // Clear clock readiness interrupt flags and turn off clock + // readiness interrupts. + RCC_BASE->CIR = 0x00000000; +#if !USE_HSI_CLOCK + // Enable HSE, and wait until it's ready. + rcc_turn_on_clk(RCC_CLK_HSE); + while(!rcc_is_clk_ready(RCC_CLK_HSE)) + ; +#endif + // Configure AHBx, APBx, etc. prescalers and the main PLL. + wirish::priv::board_setup_clock_prescalers(); + rcc_configure_pll(&wirish::priv::w_board_pll_cfg); + + // Enable the PLL, and wait until it's ready. + rcc_turn_on_clk(RCC_CLK_PLL); + while(!rcc_is_clk_ready(RCC_CLK_PLL)) + ; + + // Finally, switch to the now-ready PLL as the main clock source. + rcc_switch_sysclk(RCC_CLKSRC_PLL); +} + +/* + * These addresses are where usercode starts when a bootloader is + * present. If no bootloader is present, the user NVIC usually starts + * at the Flash base address, 0x08000000. + */ +#if defined(BOOTLOADER_maple) + #define USER_ADDR_ROM 0x08005000 +#else + #define USER_ADDR_ROM 0x08000000 +#endif +#define USER_ADDR_RAM 0x20000C00 +extern char __text_start__; + +static void setup_nvic(void) { + +nvic_init((uint32)VECT_TAB_ADDR, 0); + +/* Roger Clark. We now control nvic vector table in boards.txt using the build.vect parameter +#ifdef VECT_TAB_FLASH + nvic_init(USER_ADDR_ROM, 0); +#elif defined VECT_TAB_RAM + nvic_init(USER_ADDR_RAM, 0); +#elif defined VECT_TAB_BASE + nvic_init((uint32)0x08000000, 0); +#elif defined VECT_TAB_ADDR + // A numerically supplied value + nvic_init((uint32)VECT_TAB_ADDR, 0); +#else + // Use the __text_start__ value from the linker script; this + // should be the start of the vector table. + nvic_init((uint32)&__text_start__, 0); +#endif + +*/ +} + +static void adc_default_config(adc_dev *dev) { + adc_enable_single_swstart(dev); + adc_set_sample_rate(dev, wirish::priv::w_adc_smp); +} + +static void setup_adcs(void) { + adc_set_prescaler(wirish::priv::w_adc_pre); + adc_foreach(adc_default_config); +} + +static void timer_default_config(timer_dev *dev) { + timer_adv_reg_map *regs = (dev->regs).adv; + const uint16 full_overflow = 0xFFFF; + const uint16 half_duty = 0x8FFF; + + timer_init(dev); + timer_pause(dev); + + regs->CR1 = TIMER_CR1_ARPE; + regs->PSC = 1; + regs->SR = 0; + regs->DIER = 0; + regs->EGR = TIMER_EGR_UG; + switch (dev->type) { + case TIMER_ADVANCED: + regs->BDTR = TIMER_BDTR_MOE | TIMER_BDTR_LOCK_OFF; + // fall-through + case TIMER_GENERAL: + timer_set_reload(dev, full_overflow); + for (uint8 channel = 1; channel <= 4; channel++) { + if (timer_has_cc_channel(dev, channel)) { + timer_set_compare(dev, channel, half_duty); + timer_oc_set_mode(dev, channel, TIMER_OC_MODE_PWM_1, + TIMER_OC_PE); + } + } + // fall-through + case TIMER_BASIC: + break; + } + + timer_generate_update(dev); + timer_resume(dev); +} + +static void setup_timers(void) { + timer_foreach(timer_default_config); +} diff --git a/buildroot/share/PlatformIO/variants/CHITU_F103/wirish/boards_setup.cpp b/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/wirish/boards_setup.cpp old mode 100755 new mode 100644 similarity index 100% rename from buildroot/share/PlatformIO/variants/CHITU_F103/wirish/boards_setup.cpp rename to buildroot/share/PlatformIO/variants/marlin_CHITU_F103/wirish/boards_setup.cpp diff --git a/buildroot/share/PlatformIO/variants/CHITU_F103/wirish/start.S b/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/wirish/start.S similarity index 100% rename from buildroot/share/PlatformIO/variants/CHITU_F103/wirish/start.S rename to buildroot/share/PlatformIO/variants/marlin_CHITU_F103/wirish/start.S diff --git a/buildroot/share/PlatformIO/variants/CHITU_F103/wirish/start_c.c b/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/wirish/start_c.c similarity index 100% rename from buildroot/share/PlatformIO/variants/CHITU_F103/wirish/start_c.c rename to buildroot/share/PlatformIO/variants/marlin_CHITU_F103/wirish/start_c.c diff --git a/buildroot/share/PlatformIO/variants/CHITU_F103/wirish/syscalls.c b/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/wirish/syscalls.c similarity index 100% rename from buildroot/share/PlatformIO/variants/CHITU_F103/wirish/syscalls.c rename to buildroot/share/PlatformIO/variants/marlin_CHITU_F103/wirish/syscalls.c diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/board.cpp b/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/board.cpp similarity index 100% rename from buildroot/share/PlatformIO/variants/MEEB_3DP/board.cpp rename to buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/board.cpp diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/board/board.h b/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/board/board.h similarity index 100% rename from buildroot/share/PlatformIO/variants/MEEB_3DP/board/board.h rename to buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/board/board.h diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/bootloader.ld b/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/bootloader.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/MEEB_3DP/ld/bootloader.ld rename to buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/bootloader.ld diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/common.inc b/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/common.inc similarity index 100% rename from buildroot/share/PlatformIO/variants/MEEB_3DP/ld/common.inc rename to buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/common.inc diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/extra_libs.inc b/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/extra_libs.inc similarity index 100% rename from buildroot/share/PlatformIO/variants/MEEB_3DP/ld/extra_libs.inc rename to buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/extra_libs.inc diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/flash.ld b/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/flash.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/MEEB_3DP/ld/flash.ld rename to buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/flash.ld diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/jtag.ld b/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/jtag.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/MEEB_3DP/ld/jtag.ld rename to buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/jtag.ld diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/mem-flash.inc b/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/mem-flash.inc similarity index 100% rename from buildroot/share/PlatformIO/variants/MEEB_3DP/ld/mem-flash.inc rename to buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/mem-flash.inc diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/mem-jtag.inc b/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/mem-jtag.inc similarity index 100% rename from buildroot/share/PlatformIO/variants/MEEB_3DP/ld/mem-jtag.inc rename to buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/mem-jtag.inc diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/mem-ram.inc b/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/mem-ram.inc similarity index 100% rename from buildroot/share/PlatformIO/variants/MEEB_3DP/ld/mem-ram.inc rename to buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/mem-ram.inc diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/ram.ld b/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/ram.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/MEEB_3DP/ld/ram.ld rename to buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/ram.ld diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103rb.ld b/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/stm32f103rb.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103rb.ld rename to buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/stm32f103rb.ld diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103rb_bootloader.ld b/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/stm32f103rb_bootloader.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103rb_bootloader.ld rename to buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/stm32f103rb_bootloader.ld diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103rc.ld b/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/stm32f103rc.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103rc.ld rename to buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/stm32f103rc.ld diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103rc_bootloader.ld b/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/stm32f103rc_bootloader.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103rc_bootloader.ld rename to buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/stm32f103rc_bootloader.ld diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103re.ld b/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/stm32f103re.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103re.ld rename to buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/stm32f103re.ld diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/vector_symbols.inc b/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/vector_symbols.inc similarity index 100% rename from buildroot/share/PlatformIO/variants/MEEB_3DP/ld/vector_symbols.inc rename to buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/vector_symbols.inc diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/pins_arduino.h b/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/pins_arduino.h similarity index 100% rename from buildroot/share/PlatformIO/variants/MEEB_3DP/pins_arduino.h rename to buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/pins_arduino.h diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/variant.h b/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/variant.h similarity index 100% rename from buildroot/share/PlatformIO/variants/MEEB_3DP/variant.h rename to buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/variant.h diff --git a/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/wirish/boards.cpp b/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/wirish/boards.cpp new file mode 100644 index 000000000000..77dcbcf848d3 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/wirish/boards.cpp @@ -0,0 +1,225 @@ +/****************************************************************************** + * The MIT License + * + * Copyright (c) 2010 Perry Hung. + * Copyright (c) 2011, 2012 LeafLabs, LLC. + * + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without + * restriction, including without limitation the rights to use, copy, + * modify, merge, publish, distribute, sublicense, and/or sell copies + * of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS + * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN + * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + *****************************************************************************/ + +/** + * @file wirish/boards.cpp + * @brief init() and board routines. + * + * This file is mostly interesting for the init() function, which + * configures Flash, the core clocks, and a variety of other available + * peripherals on the board so the rest of Wirish doesn't have to turn + * things on before using them. + * + * Prior to returning, init() calls boardInit(), which allows boards + * to perform any initialization they need to. This file includes a + * weak no-op definition of boardInit(), so boards that don't need any + * special initialization don't have to define their own. + * + * How init() works is chip-specific. See the boards_setup.cpp files + * under e.g. wirish/stm32f1/, wirish/stmf32f2 for the details, but be + * advised: their contents are unstable, and can/will change without + * notice. + */ + +#include +#include +#include +#include +#include +#include "boards_private.h" + +static void setup_flash(void); +static void setup_clocks(void); +static void setup_nvic(void); +static void setup_adcs(void); +static void setup_timers(void); + +/* + * Exported functions + */ + +void init(void) { + setup_flash(); + setup_clocks(); + setup_nvic(); + systick_init(SYSTICK_RELOAD_VAL); + wirish::priv::board_setup_gpio(); + setup_adcs(); + setup_timers(); + wirish::priv::board_setup_usb(); + wirish::priv::series_init(); + boardInit(); +} + +/* Provide a default no-op boardInit(). */ +__weak void boardInit(void) { +} + +/* You could farm this out to the files in boards/ if e.g. it takes + * too long to test on boards with lots of pins. */ +bool boardUsesPin(uint8 pin) { + for (int i = 0; i < BOARD_NR_USED_PINS; i++) { + if (pin == boardUsedPins[i]) { + return true; + } + } + return false; +} + +/* + * Auxiliary routines + */ + +static void setup_flash(void) { + // Turn on as many Flash "go faster" features as + // possible. flash_enable_features() just ignores any flags it + // can't support. + flash_enable_features(FLASH_PREFETCH | FLASH_ICACHE | FLASH_DCACHE); + // Configure the wait states, assuming we're operating at "close + // enough" to 3.3V. + flash_set_latency(FLASH_SAFE_WAIT_STATES); +} + +static void setup_clocks(void) { + // Turn on HSI. We'll switch to and run off of this while we're + // setting up the main PLL. + rcc_turn_on_clk(RCC_CLK_HSI); + + // Turn off and reset the clock subsystems we'll be using, as well + // as the clock security subsystem (CSS). Note that resetting CFGR + // to its default value of 0 implies a switch to HSI for SYSCLK. + RCC_BASE->CFGR = 0x00000000; + rcc_disable_css(); + rcc_turn_off_clk(RCC_CLK_PLL); + rcc_turn_off_clk(RCC_CLK_HSE); + wirish::priv::board_reset_pll(); + // Clear clock readiness interrupt flags and turn off clock + // readiness interrupts. + RCC_BASE->CIR = 0x00000000; +#if !USE_HSI_CLOCK + // Enable HSE, and wait until it's ready. + rcc_turn_on_clk(RCC_CLK_HSE); + while (!rcc_is_clk_ready(RCC_CLK_HSE)) + ; +#endif + // Configure AHBx, APBx, etc. prescalers and the main PLL. + wirish::priv::board_setup_clock_prescalers(); + rcc_configure_pll(&wirish::priv::w_board_pll_cfg); + + // Enable the PLL, and wait until it's ready. + rcc_turn_on_clk(RCC_CLK_PLL); + while(!rcc_is_clk_ready(RCC_CLK_PLL)) + ; + + // Finally, switch to the now-ready PLL as the main clock source. + rcc_switch_sysclk(RCC_CLKSRC_PLL); +} + +/* + * These addresses are where usercode starts when a bootloader is + * present. If no bootloader is present, the user NVIC usually starts + * at the Flash base address, 0x08000000. + */ +#if defined(BOOTLOADER_maple) + #define USER_ADDR_ROM 0x08002000 +#else + #define USER_ADDR_ROM 0x08000000 +#endif +#define USER_ADDR_RAM 0x20000C00 +extern char __text_start__; + +static void setup_nvic(void) { + +nvic_init((uint32)VECT_TAB_ADDR, 0); + +/* Roger Clark. We now control nvic vector table in boards.txt using the build.vect parameter +#ifdef VECT_TAB_FLASH + nvic_init(USER_ADDR_ROM, 0); +#elif defined VECT_TAB_RAM + nvic_init(USER_ADDR_RAM, 0); +#elif defined VECT_TAB_BASE + nvic_init((uint32)0x08000000, 0); +#elif defined VECT_TAB_ADDR + // A numerically supplied value + nvic_init((uint32)VECT_TAB_ADDR, 0); +#else + // Use the __text_start__ value from the linker script; this + // should be the start of the vector table. + nvic_init((uint32)&__text_start__, 0); +#endif + +*/ +} + +static void adc_default_config(adc_dev *dev) { + adc_enable_single_swstart(dev); + adc_set_sample_rate(dev, wirish::priv::w_adc_smp); +} + +static void setup_adcs(void) { + adc_set_prescaler(wirish::priv::w_adc_pre); + adc_foreach(adc_default_config); +} + +static void timer_default_config(timer_dev *dev) { + timer_adv_reg_map *regs = (dev->regs).adv; + const uint16 full_overflow = 0xFFFF; + const uint16 half_duty = 0x8FFF; + + timer_init(dev); + timer_pause(dev); + + regs->CR1 = TIMER_CR1_ARPE; + regs->PSC = 1; + regs->SR = 0; + regs->DIER = 0; + regs->EGR = TIMER_EGR_UG; + switch (dev->type) { + case TIMER_ADVANCED: + regs->BDTR = TIMER_BDTR_MOE | TIMER_BDTR_LOCK_OFF; + // fall-through + case TIMER_GENERAL: + timer_set_reload(dev, full_overflow); + for (uint8 channel = 1; channel <= 4; channel++) { + if (timer_has_cc_channel(dev, channel)) { + timer_set_compare(dev, channel, half_duty); + timer_oc_set_mode(dev, channel, TIMER_OC_MODE_PWM_1, + TIMER_OC_PE); + } + } + // fall-through + case TIMER_BASIC: + break; + } + + timer_generate_update(dev); + timer_resume(dev); +} + +static void setup_timers(void) { + timer_foreach(timer_default_config); +} diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/boards_setup.cpp b/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/wirish/boards_setup.cpp similarity index 100% rename from buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/boards_setup.cpp rename to buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/wirish/boards_setup.cpp diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/start.S b/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/wirish/start.S similarity index 100% rename from buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/start.S rename to buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/wirish/start.S diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/start_c.c b/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/wirish/start_c.c similarity index 100% rename from buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/start_c.c rename to buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/wirish/start_c.c diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/syscalls.c b/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/wirish/syscalls.c similarity index 100% rename from buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/syscalls.c rename to buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/wirish/syscalls.c diff --git a/buildroot/share/extras/header.h b/buildroot/share/extras/header.h index 5d2c73dfbeef..e40471dface9 100644 --- a/buildroot/share/extras/header.h +++ b/buildroot/share/extras/header.h @@ -1,6 +1,6 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2021 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/fonts/genallfont.sh b/buildroot/share/fonts/genallfont.sh index 66f8e2c84f78..d5cad54361ed 100755 --- a/buildroot/share/fonts/genallfont.sh +++ b/buildroot/share/fonts/genallfont.sh @@ -57,12 +57,12 @@ OLDWD=`pwd` # # Compile the 'genpages' command in-place # -(cd ${DN_EXEC}; gcc -o genpages genpages.c getline.c) +(cd ${DN_EXEC}; cc -o genpages genpages.c getline.c) # # By default loop through all languages # -LANGS_DEFAULT="an bg ca cz da de el el_gr en es eu fi fr gl hr hu it jp_kana ko_KR nl pl pt pt_br ro ru sk tr uk vi zh_CN zh_TW test" +LANGS_DEFAULT="an bg ca cz da de el el_gr en es eu fi fr gl hr hu it jp_kana ko_KR nl pl pt pt_br ro ru sk sv tr uk vi zh_CN zh_TW test" # # Generate data for language list MARLIN_LANGS or all if not provided @@ -119,7 +119,7 @@ if [ 1 = 1 ]; then * along with this program. If not, see . * */ -#include +#include #if defined(__AVR__) && ENABLED(NOT_EXTENDED_ISO10646_1_5X7) // reduced font (only symbols 1 - 127) - saves about 1278 bytes of FLASH diff --git a/buildroot/share/fonts/genpages.c b/buildroot/share/fonts/genpages.c index 2a87b19d47f7..dea5b05c5c80 100644 --- a/buildroot/share/fonts/genpages.c +++ b/buildroot/share/fonts/genpages.c @@ -71,63 +71,49 @@ uint8_t* get_utf8_value(uint8_t *pstart, wchar_t *pval) { assert(NULL != pstart); + #define NEXT_6_BITS() do{ val <<= 6; p++; val |= (*p & 0x3F); }while(0) + if (0 == (0x80 & *p)) { val = (size_t)*p; p++; } else if (0xC0 == (0xE0 & *p)) { val = *p & 0x1F; - val <<= 6; - p++; - val |= (*p & 0x3F); + NEXT_6_BITS(); p++; assert((wchar_t)val == get_val_utf82uni(pstart)); } else if (0xE0 == (0xF0 & *p)) { val = *p & 0x0F; - val <<= 6; p++; - val |= (*p & 0x3F); - val <<= 6; p++; - val |= (*p & 0x3F); + NEXT_6_BITS(); + NEXT_6_BITS(); p++; assert((wchar_t)val == get_val_utf82uni(pstart)); } else if (0xF0 == (0xF8 & *p)) { val = *p & 0x07; - val <<= 6; p++; - val |= (*p & 0x3F); - val <<= 6; p++; - val |= (*p & 0x3F); - val <<= 6; p++; - val |= (*p & 0x3F); + NEXT_6_BITS(); + NEXT_6_BITS(); + NEXT_6_BITS(); p++; assert((wchar_t)val == get_val_utf82uni(pstart)); } else if (0xF8 == (0xFC & *p)) { val = *p & 0x03; - val <<= 6; p++; - val |= (*p & 0x3F); - val <<= 6; p++; - val |= (*p & 0x3F); - val <<= 6; p++; - val |= (*p & 0x3F); - val <<= 6; p++; - val |= (*p & 0x3F); + NEXT_6_BITS(); + NEXT_6_BITS(); + NEXT_6_BITS(); + NEXT_6_BITS(); p++; assert((wchar_t)val == get_val_utf82uni(pstart)); } else if (0xFC == (0xFE & *p)) { val = *p & 0x01; - val <<= 6; p++; - val |= (*p & 0x3F); - val <<= 6; p++; - val |= (*p & 0x3F); - val <<= 6; p++; - val |= (*p & 0x3F); - val <<= 6; p++; - val |= (*p & 0x3F); - val <<= 6; p++; - val |= (*p & 0x3F); + NEXT_6_BITS(); + NEXT_6_BITS(); + NEXT_6_BITS(); + NEXT_6_BITS(); + NEXT_6_BITS(); p++; assert((wchar_t)val == get_val_utf82uni(pstart)); } @@ -156,12 +142,12 @@ uint8_t* get_utf8_value(uint8_t *pstart, wchar_t *pval) { return p; } -void usage(char* progname) { +void usage(char *progname) { fprintf(stderr, "usage: %s\n", progname); fprintf(stderr, " read data from stdin\n"); } -void utf8_parse(const char* msg, unsigned int len) { +void utf8_parse(const char *msg, unsigned int len) { uint8_t *pend = NULL; uint8_t *p; uint8_t *pre; diff --git a/buildroot/share/fonts/uxggenpages.sh b/buildroot/share/fonts/uxggenpages.sh index a99fd9902463..047d3ae661b9 100755 --- a/buildroot/share/fonts/uxggenpages.sh +++ b/buildroot/share/fonts/uxggenpages.sh @@ -169,7 +169,7 @@ cat <fontutf8-data.h * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#include $TMPA #define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {$TMPB}; diff --git a/buildroot/share/git/mfconfig b/buildroot/share/git/mfconfig new file mode 100755 index 000000000000..70642a5d39cb --- /dev/null +++ b/buildroot/share/git/mfconfig @@ -0,0 +1,193 @@ +#!/usr/bin/env bash +# +# mfconfig init source dest +# mfconfig manual source dest +# +# The MarlinFirmware/Configurations layout could be broken up into branches, +# but this makes management more complicated and requires more commits to +# perform the same operation, so this uses a single branch with subfolders. +# +# init - Initialize the repo with a base commit and changes: +# - Source will be an 'import' branch containing all current configs. +# - Create an empty 'BASE' branch from 'init-repo'. +# - Add Marlin config files, but reset all to defaults. +# - Commit this so changes will be clear in following commits. +# - Add changed Marlin config files and commit. +# +# manual - Manually import changes from the Marlin repo +# - Replace 'default' configs with those from the Marlin repo. +# - Wait for manual propagation to the rest of the configs. +# - Run init with the given 'source' and 'dest' +# + +REPOHOME="`dirname ~/Projects/Maker/Firmware/.`" +MARLINREPO="$REPOHOME/MarlinFirmware" +CONFIGREPO="$REPOHOME/Configurations" + +CEXA=config/examples +CDEF=config/default +BC=Configuration.h +AC=Configuration_adv.h + +COMMIT_STEPS=0 + +#cd "$CONFIGREPO" 2>/dev/null || { echo "Can't find Configurations repo!" ; exit 1; } + +ACTION=${1:-init} +IMPORT=${2:-"import-2.0.x"} +EXPORT=${3:-"bugfix-2.0.x"} + +echo -n "Doing grhh ... " ; grhh ; echo + +if [[ $ACTION == "manual" ]]; then + + # + # Copy the latest default configs from MarlinFirmware/Marlin + # or one of the import branches here, then use them to construct + # a 'BASE' branch with only defaults as a starting point. + # + + echo "- Updating '$IMPORT' from Marlin..." + + git checkout $IMPORT || exit + + # Reset from the latest complete state + #git reset --hard bugfix-2.0.x + + cp "$MARLINREPO/Marlin/"Configuration*.h "$CDEF/" + #git add . && git commit -m "Changes from Marlin ($(date '+%Y-%m-%d %H:%M'))." + + echo "- Fix up the import branch and come back." + + read -p "- Ready to init [y/N] ?" INIT_YES + echo + + [[ $INIT_YES == 'Y' || $INIT_YES == 'y' ]] || { echo "Done." ; exit ; } + + ACTION='init' +fi + +if [[ $ACTION == "init" ]]; then + # + # Copy all configs from a source such as MarlinFirmware/Marlin + # or one of the import branches here, then use them to construct + # a 'BASE' branch with only defaults as a starting point. + # + + echo "- Initializing BASE branch..." + + # Use the import branch as the source + git checkout $IMPORT || exit + + # Copy to a temporary location + TEMP=$( mktemp -d ) ; cp -R config $TEMP + + # Make sure we're not on the 'BASE' branch... + git checkout init-repo >/dev/null 2>&1 || exit + + # Create 'BASE' as a copy of 'init-repo' (README, LICENSE, etc.) + git branch -D BASE 2>/dev/null + git checkout init-repo -b BASE || exit + + # Copy all config files into place + echo "- Copying all configs from fresh $IMPORT..." + cp -R "$TEMP/config" . + + # Delete anything that's not a Configuration file + find config -type f \! -name "Configuration*" -exec rm "{}" \; + + # DEBUG: Commit the original config files for comparison + ((COMMIT_STEPS)) && git add . >/dev/null && git commit -m "Commit for comparison" >/dev/null + + # Init Cartesian/SCARA/TPARA configurations to default + echo "- Initializing Cartesian/SCARA/TPARA configs to default state..." + + find "$CEXA" -name $BC ! -path */delta/* -print0 \ + | while read -d $'\0' F ; do cp "$CDEF/$BC" "$F" ; done + find "$CEXA" -name $AC ! -path */delta/* -print0 \ + | while read -d $'\0' F ; do cp "$CDEF/$AC" "$F" ; done + + # DEBUG: Commit the reset for review + ((COMMIT_STEPS)) && git add . >/dev/null && git commit -m "Reset Cartesian/SCARA/TPARA configs..." >/dev/null + + # Create base Delta configurations + cp "$CDEF"/* "$CEXA/delta/generic" + + # DEBUG: Commit the reset for review + ((COMMIT_STEPS)) && git add . >/dev/null && git commit -m "Reset Generic Delta..." >/dev/null + + cp -R "$TEMP/$CEXA/delta/generic"/Conf* "$CEXA/delta/generic" + + # DEBUG: Commit Generic Delta changes for review + ((COMMIT_STEPS)) && git add . >/dev/null && git commit -m "Apply Generic Delta..." >/dev/null + + # Reset all Delta configs to the generic version + find "$CEXA/delta" -name $BC ! -path */generic/* -print0 \ + | while read -d $'\0' F ; do cp "$CEXA/delta/generic/$BC" "$F" ; done + find "$CEXA/delta" -name $AC ! -path */generic/* -print0 \ + | while read -d $'\0' F ; do cp "$CEXA/delta/generic/$AC" "$F" ; done + + # DEBUG: Commit the Delta reset for review + ((COMMIT_STEPS)) && git add . >/dev/null && git commit -m "Reset Delta configs..." >/dev/null + + # Reset all SCARA configs to the default cartesian + find "$CEXA/SCARA" -name $BC \ + | while read -d $'\0' F ; do cp "$CDEF/$BC" "$F" ; done + find "$CEXA/SCARA" -name $AC \ + | while read -d $'\0' F ; do cp "$CDEF/$AC" "$F" ; done + + # DEBUG: Commit the SCARA reset for review + ((COMMIT_STEPS)) && git add . >/dev/null && git commit -m "Reset SCARA..." >/dev/null + + # Reset all TPARA configs to the default cartesian + find "$CEXA/TPARA" -name $BC \ + | while read -d $'\0' F ; do cp "$CDEF/$BC" "$F" ; done + find "$CEXA/TPARA" -name $AC \ + | while read -d $'\0' F ; do cp "$CDEF/$AC" "$F" ; done + + # DEBUG: Commit the TPARA reset for review + ((COMMIT_STEPS)) && git add . >/dev/null && git commit -m "Reset TPARA..." >/dev/null + + # Update the %VERSION% in the README.md file + SED=$(which gsed sed | head -n1) + VERS=$( echo $EXPORT | $SED 's/release-//' ) + eval "${SED} -E -i~ -e 's/%VERSION%/$VERS/g' README.md" + rm -f README.md~ + + # NOT DEBUGGING: Commit the 'BASE', ready for customizations + ((COMMIT_STEPS)) || git add . >/dev/null && git commit --amend --no-edit >/dev/null + + # Create a new branch from 'BASE' for the final result + echo "- Creating '$EXPORT' branch for the result..." + git branch -D $EXPORT 2>/dev/null + git checkout -b $EXPORT || exit + + # Delete temporary branch + git branch -D BASE 2>/dev/null + + echo "- Applying example config customizations..." + cp -R "$TEMP/config" . + find config -type f \! -name "Configuration*" -exec rm "{}" \; + + echo "- Adding path labels to all configs..." + config-labels.py >/dev/null 2>&1 + + git add . >/dev/null && git commit -m "Examples Customizations" >/dev/null + + echo "- Copying extras from Marlin..." + cp -R "$TEMP/config" . + + # Apply labels again! + config-labels.py >/dev/null 2>&1 + + git add . >/dev/null && git commit -m "Examples Extras" >/dev/null + + rm -rf $TEMP + + git push -f --set-upstream upstream "$EXPORT" + +else + + echo "Usage: mfconfig init|manual|rebase" + +fi diff --git a/buildroot/share/git/mfqp b/buildroot/share/git/mfqp index 5650d08252a2..f0c4446a211e 100755 --- a/buildroot/share/git/mfqp +++ b/buildroot/share/git/mfqp @@ -4,7 +4,7 @@ # # - git add . # - git commit --amend -# - ghpc +# - git push -f # MFINFO=$(mfinfo "$@") || exit 1 @@ -17,6 +17,7 @@ IND=6 while [ $IND -lt ${#INFO[@]} ]; do ARG=${INFO[$IND]} case "$ARG" in + -f|--force ) FORCE=1 ;; -h|--help ) USAGE=1 ;; * ) USAGE=1 ; echo "unknown option: $ARG" ;; esac @@ -25,6 +26,6 @@ done [[ $USAGE == 1 ]] && { echo "usage: `basename $0` [1|2|3]" 1>&2 ; exit 1 ; } -[[ $CURR == $TARG && $REPO != "MarlinDocumentation" ]] && { echo "Don't alter the PR Target branch."; exit 1 ; } +[[ $FORCE != 1 && $CURR == $TARG && $REPO != "MarlinDocumentation" ]] && { echo "Don't alter the PR Target branch."; exit 1 ; } git add . && git commit --amend && git push -f diff --git a/buildroot/share/git/mftest b/buildroot/share/git/mftest deleted file mode 100755 index cfb5dd05f357..000000000000 --- a/buildroot/share/git/mftest +++ /dev/null @@ -1,236 +0,0 @@ -#!/usr/bin/env bash -# -# mftest Select a test to apply and build -# mftest -b [#] Build the auto-detected environment -# mftest -u [#] Upload the auto-detected environment -# mftest [name] [index] [-y] Set config options and optionally build a test -# - -MFINFO=$(mfinfo) || exit 1 -[[ -d Marlin/src ]] || { echo "Please 'cd' up to repo root." ; exit 1 ; } - -TESTPATH=buildroot/tests - -STATE_FILE=$( echo ./.pio/.mftestrc ) -SED=$(which gsed || which sed) - -shopt -s extglob nocasematch - -# Matching patterns -ISNUM='^[0-9]+$' -ISCMD='^(restore|opt|exec|use|pins|env)_' -ISEXEC='^exec_' -ISCONT='\\ *$' - -# Get the environment and test number from the command -TESTENV=${1:-'-'} -CHOICE=${2:-0} -AUTOENV=0 - -# Allow shorthand for test name -case $TESTENV in - tree) pio run -d . -e include_tree ; exit 1 ;; - due) TESTENV='DUE' ;; - esp) TESTENV='esp32' ;; - lin*) TESTENV='linux_native' ;; - lpc?(8)) TESTENV='LPC1768' ;; - lpc9) TESTENV='LPC1769' ;; - m128) TESTENV='mega1280' ;; - m256) TESTENV='mega2560' ;; - mega) TESTENV='mega2560' ;; - stm) TESTENV='STM32F103RE' ;; - f1) TESTENV='STM32F103RE' ;; - f4) TESTENV='STM32F4' ;; - f7) TESTENV='STM32F7' ;; - s6) TESTENV='FYSETC_S6' ;; - teensy) TESTENV='teensy31' ;; - t31) TESTENV='teensy31' ;; - t32) TESTENV='teensy31' ;; - t35) TESTENV='teensy35' ;; - t36) TESTENV='teensy35' ;; - t40) TESTENV='teensy41' ;; - t41) TESTENV='teensy41' ;; - --h|--help) echo -e "$(basename $0) : Marlin Firmware test, build, and upload\n" - echo "Usage: $(basename $0) ................. Select env and test to apply / run" - echo " $(basename $0) [-y] env ........ Select a test for env to apply / run" - echo " $(basename $0) [-y] env test ... Apply / run the specified env test" - echo " $(basename $0) -b [variant] .... Auto-build the specified variant" - echo " $(basename $0) -u [variant] .... Auto-build and upload the specified variant" - echo - echo "env shortcuts: tree due esp lin lpc|lpc8 lpc9 m128 m256|mega stm|f1 f4 f7 s6 teensy|t31|t32 t35|t36 t40|t41" - exit - ;; - - # Build with the last-built env - -r) [[ -f "$STATE_FILE" ]] || { echo "No previous (-r) build state found." ; exit 1 ; } - read TESTENV <"$STATE_FILE" - pio run -d . -e $TESTENV - exit - ;; - - -[bu]) MB=$( grep -E "^\s*#define MOTHERBOARD" Marlin/Configuration.h | awk '{ print $3 }' | $SED 's/BOARD_//' ) - [[ -z $MB ]] && { echo "Error - Can't read MOTHERBOARD setting." ; exit 1 ; } - BLINE=$( grep -E "define\s+BOARD_$MB\b" Marlin/src/core/boards.h ) - BNUM=$( $SED -E 's/^.+BOARD_[^ ]+ +([0-9]+).+$/\1/' <<<"$BLINE" ) - BDESC=$( $SED -E 's/^.+\/\/ *(.+)$/\1/' <<<"$BLINE" ) - [[ -z $BNUM ]] && { echo "Error - Can't find $MB in boards list." ; exit 1 ; } - readarray -t ENVS <<< $( grep -EA1 "MB\(.*\b$MB\b.*\)" Marlin/src/pins/pins.h | grep -E '#include.+//.+env:.+' | grep -oE 'env:[^ ]+' | $SED -E 's/env://' ) - [[ -z $ENVS ]] && { echo "Error - Can't find target(s) for $MB ($BNUM)." ; exit 1 ; } - ECOUNT=${#ENVS[*]} - - if [[ $ECOUNT == 1 ]]; then - TARGET=$ENVS - else - if [[ $CHOICE == 0 ]]; then - # - # List env names and numbers. Get selection. - # - echo "Available targets for \"$BDESC\" | $MB ($BNUM):" - - IND=0 ; for ENV in "${ENVS[@]}"; do let IND++ ; echo " $IND) $ENV" ; done - - if [[ $ECOUNT > 1 ]]; then - for (( ; ; )) - do - read -p "Select a target for '$MB' (1-$ECOUNT) : " CHOICE - [[ -z "$CHOICE" ]] && { echo '(canceled)' ; exit 1 ; } - [[ $CHOICE =~ $ISNUM ]] && ((CHOICE >= 1 && CHOICE <= ECOUNT)) && break - echo ">>> Invalid environment choice '$CHOICE'." - done - echo - fi - else - echo "Detected \"$BDESC\" | $MB ($BNUM)." - [[ $CHOICE > $ECOUNT ]] && { echo "Environment selection out of range." ; exit 1 ; } - fi - TARGET="${ENVS[$CHOICE-1]}" - echo "Selected $TARGET" - fi - - echo "$TARGET" >"$STATE_FILE" - - if [[ $TESTENV == "-u" ]]; then - echo "Build/Uploading environment $TARGET for board $MB ($BNUM)..." ; echo - pio run -t upload -e $TARGET - else - echo "Building environment $TARGET for board $MB ($BNUM)..." ; echo - pio run -e $TARGET - fi - exit - ;; - - # The -y flag may come first - -y) TESTENV=${2:-'-'} ; CHOICE=${3:-0} ;; - - -[a-z]) echo "Unknown flag $TESTENV" ; exit 1 ;; - -) ;; -esac - -# -# List available tests and ask for selection -# - -if [[ $TESTENV == '-' ]]; then - IND=0 - NAMES=() - for FILE in $( ls -1 $TESTPATH/*-tests ) - do - let IND++ - TNAME=${FILE/-tests/} - TNAME=${TNAME/$TESTPATH\//} - NAMES+=($TNAME) - (( IND < 10 )) && echo -n " " - echo " $IND) $TNAME" - done - - echo - for (( ; ; )) - do - read -p "Select a test to apply (1-$IND) : " NAMEIND - [[ -z "$NAMEIND" ]] && { echo '(canceled)' ; exit 1 ; } - [[ $NAMEIND =~ $ISNUM ]] && ((NAMEIND >= 1 && NAMEIND <= IND)) && { TESTENV=${NAMES[$NAMEIND-1]} ; echo ; break ; } - echo "Invalid selection." - done -fi - -# Get the contents of the test file -OUT=$( cat $TESTPATH/$TESTENV-tests 2>/dev/null ) || { echo "Can't find test '$TESTENV'." ; exit 1 ; } - -# Count up the number of tests -TESTCOUNT=$( awk "/$ISEXEC/{a++}END{print a}" <<<"$OUT" ) - -# User entered a number? -(( CHOICE && CHOICE > TESTCOUNT )) && { echo "Invalid test selection '$CHOICE' (1-$TESTCOUNT)." ; exit 1 ; } - -if [[ $CHOICE == 0 ]]; then - # - # List test descriptions with numbers and get selection - # - echo "Available '$TESTENV' tests:" ; echo "$OUT" | { - IND=0 - while IFS= read -r LINE - do - if [[ $LINE =~ $ISEXEC ]]; then - DESC=$( "$SED" -E 's/^.+"(.*)".*$/\1/g' <<<"$LINE" ) - (( ++IND < 10 )) && echo -n " " - echo " $IND) $DESC" - fi - done - } - CHOICE=1 - if [[ $TESTCOUNT > 1 ]]; then - for (( ; ; )) - do - read -p "Select a '$TESTENV' test (1-$TESTCOUNT) : " CHOICE - [[ -z "$CHOICE" ]] && { echo '(canceled)' ; exit 1 ; } - [[ $CHOICE =~ $ISNUM ]] && ((CHOICE >= 1 && CHOICE <= TESTCOUNT)) && break - echo ">>> Invalid test selection '$CHOICE'." - done - fi -fi - -# -# Run the specified test lines -# -echo "$OUT" | { - IND=0 - GOTX=0 - CMD="" - while IFS= read -r LINE - do - if [[ $LINE =~ $ISCMD || $GOTX == 1 ]]; then - ((!IND)) && let IND++ - if [[ $LINE =~ $ISEXEC ]]; then - ((IND++ > CHOICE)) && break - else - ((!HEADER)) && { - HEADER=1 - echo -e "\n#\n# Test $TESTENV ($CHOICE) $DESC\n#" - } - ((IND == CHOICE)) && { - GOTX=1 - [[ $CMD == "" ]] && CMD="$LINE" || CMD=$( echo -e "$CMD$LINE" | $SED -e 's/\\//g' ) - [[ $LINE =~ $ISCONT ]] || { echo $CMD ; eval "$CMD" ; CMD="" ; } - } - fi - fi - done -} - -# Make clear it's a TEST -opt_set CUSTOM_MACHINE_NAME "\"$TESTENV-tests ($CHOICE)\"" - -# Get a -y parameter the lazy way -[[ "$2" == "-y" || "$3" == "-y" ]] && BUILD_YES='Y' - -# Build the test too? -if [[ $BUILD_YES != 'Y' ]]; then - echo - read -p "Build $TESTENV test #$CHOICE (y/N) ? " BUILD_YES -fi - -[[ $BUILD_YES == 'Y' || $BUILD_YES == 'Yes' ]] && { - pio run -d . -e $TESTENV - echo "$TESTENV" >"$STATE_FILE" -} diff --git a/buildroot/share/scripts/config-labels.py b/buildroot/share/scripts/config-labels.py index 267aa2d27353..700604e45284 100755 --- a/buildroot/share/scripts/config-labels.py +++ b/buildroot/share/scripts/config-labels.py @@ -22,8 +22,7 @@ # 2020-06-05 SRL style tweaks #----------------------------------- # -import sys -import os +import sys,os from pathlib import Path from distutils.dir_util import copy_tree # for copy_tree, because shutil.copytree can't handle existing files, dirs diff --git a/buildroot/share/scripts/createTemperatureLookupMarlin.py b/buildroot/share/scripts/createTemperatureLookupMarlin.py index b2d8964f556c..02981f1015aa 100755 --- a/buildroot/share/scripts/createTemperatureLookupMarlin.py +++ b/buildroot/share/scripts/createTemperatureLookupMarlin.py @@ -22,8 +22,7 @@ from __future__ import division from math import * -import sys -import getopt +import sys,getopt "Constants" ZERO = 273.15 # zero point of Kelvin scale @@ -74,7 +73,7 @@ def resist(self, adc): return r def temp(self, adc): - "Convert ADC reading into a temperature in Celcius" + "Convert ADC reading into a temperature in Celsius" l = log(self.resist(adc)) Tinv = self.c1 + self.c2*l + self.c3* l**3 # inverse temperature return (1/Tinv) - ZERO # temperature diff --git a/buildroot/share/scripts/g29_auto.py b/buildroot/share/scripts/g29_auto.py index ffcb0d9f316c..ca36346dd9dd 100755 --- a/buildroot/share/scripts/g29_auto.py +++ b/buildroot/share/scripts/g29_auto.py @@ -119,7 +119,7 @@ def z_parse(gcode, start_at_line=0, end_at_line=0): # last_z = z last_i = i if 0 < end_at_line <= i or temp_line >= min_g1: - # print('break at line {} at heigth {}'.format(i, z)) + # print('break at line {} at height {}'.format(i, z)) break line_between_z = line_between_z[1:] diff --git a/buildroot/share/scripts/gen-tft-image.py b/buildroot/share/scripts/gen-tft-image.py new file mode 100644 index 000000000000..d89245fea41d --- /dev/null +++ b/buildroot/share/scripts/gen-tft-image.py @@ -0,0 +1,64 @@ +#!/usr/bin/env python3 +# +# 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 . +# + +# Generate Marlin TFT Images from bitmaps/PNG/JPG + +import sys,re,struct +from PIL import Image,ImageDraw + +def image2bin(image, output_file): + if output_file.endswith(('.c', '.cpp')): + f = open(output_file, 'wt') + is_cpp = True + f.write("const uint16_t image[%d] = {\n" % (image.size[1] * image.size[0])) + else: + f = open(output_file, 'wb') + is_cpp = False + pixs = image.load() + for y in range(image.size[1]): + for x in range(image.size[0]): + R = pixs[x, y][0] >> 3 + G = pixs[x, y][1] >> 2 + B = pixs[x, y][2] >> 3 + rgb = (R << 11) | (G << 5) | B + if is_cpp: + strHex = '0x{0:04X}, '.format(rgb) + f.write(strHex) + else: + f.write(struct.pack("B", (rgb & 0xFF))) + f.write(struct.pack("B", (rgb >> 8) & 0xFF)) + if is_cpp: + f.write("\n") + if is_cpp: + f.write("};\n") + f.close() + +if len(sys.argv) <= 2: + print("Utility to export a image in Marlin TFT friendly format.") + print("It will dump a raw bin RGB565 image or create a CPP file with an array of 16 bit image pixels.") + print("Usage: gen-tft-image.py INPUT_IMAGE.(png|bmp|jpg) OUTPUT_FILE.(cpp|bin)") + print("Author: rhapsodyv") + exit(1) + +output_img = sys.argv[2] +img = Image.open(sys.argv[1]) +image2bin(img, output_img) diff --git a/buildroot/share/sublime/MarlinFirmware.sublime-project b/buildroot/share/sublime/MarlinFirmware.sublime-project index 9b5234f7a13c..e0cf953fa813 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" ], + [ "*.psd", "*.png", "*.jpg", "*.jpeg", "*.bdf", "*.patch", "avrdude_5.*", "*.svg", "*.bin", "*.woff" ], "file_exclude_patterns": [ "Marlin/platformio.ini", @@ -19,7 +19,8 @@ "Marlin/.gitignore", "Marlin/*/platformio.ini", "Marlin/*/.travis.yml", - "Marlin/*/.gitignore" + "Marlin/*/.gitignore", + "*.d" ], "path": "../../.." } diff --git a/buildroot/share/vscode/auto_build.py b/buildroot/share/vscode/auto_build.py index 5dd2d0d8a3fc..ac8432729f0a 100644 --- a/buildroot/share/vscode/auto_build.py +++ b/buildroot/share/vscode/auto_build.py @@ -72,13 +72,12 @@ from __future__ import print_function from __future__ import division -import sys -import os +import sys,os pwd = os.getcwd() # make sure we're executing from the correct directory level pwd = pwd.replace('\\', '/') -if 0 <= pwd.find('buildroot/share/atom'): - pwd = pwd[:pwd.find('buildroot/share/atom')] +if 0 <= pwd.find('buildroot/share/vscode'): + pwd = pwd[:pwd.find('buildroot/share/vscode')] os.chdir(pwd) print('pwd: ', pwd) diff --git a/buildroot/share/vscode/create_custom_upload_command_CDC.py b/buildroot/share/vscode/create_custom_upload_command_CDC.py index acfd1787fb24..4662dd26cb49 100644 --- a/buildroot/share/vscode/create_custom_upload_command_CDC.py +++ b/buildroot/share/vscode/create_custom_upload_command_CDC.py @@ -13,11 +13,9 @@ from __future__ import print_function from __future__ import division -import subprocess -import os -import sys +import subprocess,os,sys,platform from SCons.Script import DefaultEnvironment -import platform + current_OS = platform.system() env = DefaultEnvironment() @@ -92,9 +90,9 @@ def get_com_port(com_search_text, descr_search_text, start): get_com_port('COM', 'Hardware ID:', 13) # avrdude_conf_path = env.get("PIOHOME_DIR") + '\\packages\\toolchain-atmelavr\\etc\\avrdude.conf' - avrdude_conf_path = 'buildroot\\share\\atom\\avrdude.conf' + avrdude_conf_path = 'buildroot\\share\\vscode\\avrdude.conf' - avrdude_exe_path = 'buildroot\\share\\atom\\avrdude_5.10.exe' + avrdude_exe_path = 'buildroot\\share\\vscode\\avrdude_5.10.exe' # source_path = env.get("PROJECTBUILD_DIR") + '\\' + env.get("PIOENV") + '\\firmware.hex' source_path = '.pio\\build\\' + env.get("PIOENV") + '\\firmware.hex' diff --git a/buildroot/share/vscode/create_custom_upload_command_DFU.py b/buildroot/share/vscode/create_custom_upload_command_DFU.py index 9082699bf459..562e284e63c2 100644 --- a/buildroot/share/vscode/create_custom_upload_command_DFU.py +++ b/buildroot/share/vscode/create_custom_upload_command_DFU.py @@ -9,8 +9,7 @@ # Will continue on if a COM port isn't found so that the compilation can be done. # -import os -import sys +import os,sys from SCons.Script import DefaultEnvironment import platform current_OS = platform.system() diff --git a/buildroot/test-gcode/M808-loops.gcode b/buildroot/test-gcode/M808-loops.gcode new file mode 100644 index 000000000000..6248c9cc3146 --- /dev/null +++ b/buildroot/test-gcode/M808-loops.gcode @@ -0,0 +1,16 @@ +; +; M808 Repeat Marker Test +; + +M808 L3 ; Marker at 54 + +M118 Outer Loop +M300 S220 P100 + +M808 L5 ; Marker at 111 + +M118 Inner Loop +M300 S110 P100 + +M808 +M808 diff --git a/buildroot/tests/ARMED b/buildroot/tests/ARMED new file mode 100755 index 000000000000..7b9fef1eeb49 --- /dev/null +++ b/buildroot/tests/ARMED @@ -0,0 +1,19 @@ +#!/usr/bin/env bash +# +# Build tests for STM32F1 ARMED +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +restore_configs +use_example_configs ArmEd +opt_set X_DRIVER_TYPE TMC2130 Y_DRIVER_TYPE TMC2208 +opt_enable LASER_SYNCHRONOUS_M106_M107 +exec_test $1 $2 "ArmEd Example Configuration with mixed TMC Drivers" "$3" + +# clean up +restore_configs diff --git a/buildroot/tests/ARMED-tests b/buildroot/tests/ARMED-tests deleted file mode 100644 index e5959a4383a7..000000000000 --- a/buildroot/tests/ARMED-tests +++ /dev/null @@ -1,19 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for STM32F1 ARMED -# - -# exit on first failure -set -e - -# -# Build with the default configurations -# -restore_configs -use_example_configs ArmEd -opt_set X_DRIVER_TYPE TMC2130 -opt_set Y_DRIVER_TYPE TMC2208 -exec_test $1 $2 "ArmEd Example Configuration with mixed TMC Drivers" - -# clean up -restore_configs diff --git a/buildroot/tests/BIGTREE_BTT002 b/buildroot/tests/BIGTREE_BTT002 new file mode 100755 index 000000000000..7288c5ef5260 --- /dev/null +++ b/buildroot/tests/BIGTREE_BTT002 @@ -0,0 +1,26 @@ +#!/usr/bin/env bash +# +# Build tests for STM32F407VGT6 BigTreeTech BTT002 V1.0 +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +restore_configs +opt_set MOTHERBOARD BOARD_BTT_BTT002_V1_0 \ + SERIAL_PORT 1 \ + X_DRIVER_TYPE TMC2209 \ + Y_DRIVER_TYPE TMC2130 +exec_test $1 $2 "BigTreeTech BTT002 Default Configuration plus TMC steppers" "$3" + +# +# A test with Probe Temperature Compensation enabled +# +use_example_configs Prusa/MK3S-BigTreeTech-BTT002 +exec_test $1 $2 "BigTreeTech BTT002 with Prusa MK3S and related options" "$3" + +# clean up +restore_configs diff --git a/buildroot/tests/BIGTREE_BTT002-tests b/buildroot/tests/BIGTREE_BTT002-tests deleted file mode 100644 index 64e6322ecad4..000000000000 --- a/buildroot/tests/BIGTREE_BTT002-tests +++ /dev/null @@ -1,20 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for STM32F407VGT6 BigTreeTech BTT002 V1.0 -# - -# exit on first failure -set -e - -# -# Build with the default configurations -# -restore_configs -opt_set MOTHERBOARD BOARD_BTT_BTT002_V1_0 -opt_set SERIAL_PORT 1 -opt_set X_DRIVER_TYPE TMC2209 -opt_set Y_DRIVER_TYPE TMC2130 -exec_test $1 $2 "BigTreeTech BTT002 Default Configuration plus TMC steppers" - -# clean up -restore_configs diff --git a/buildroot/tests/BIGTREE_GTR_V1_0 b/buildroot/tests/BIGTREE_GTR_V1_0 new file mode 100755 index 000000000000..58cbe4a142ba --- /dev/null +++ b/buildroot/tests/BIGTREE_GTR_V1_0 @@ -0,0 +1,38 @@ +#!/usr/bin/env bash +# +# Build tests for BigTreeTech GTR 1.0 +# + +# exit on first failure +set -e + +restore_configs +opt_set MOTHERBOARD BOARD_BTT_GTR_V1_0 SERIAL_PORT -1 \ + EXTRUDERS 8 TEMP_SENSOR_1 1 TEMP_SENSOR_2 1 TEMP_SENSOR_3 1 TEMP_SENSOR_4 1 TEMP_SENSOR_5 1 TEMP_SENSOR_6 1 TEMP_SENSOR_7 1 +# Not necessary to enable auto-fan for all extruders to hit problematic code paths +opt_set E0_AUTO_FAN_PIN PC10 E1_AUTO_FAN_PIN PC11 E2_AUTO_FAN_PIN PC12 NEOPIXEL_PIN PF13 \ + X_DRIVER_TYPE TMC2208 Y_DRIVER_TYPE TMC2130 \ + FIL_RUNOUT_PIN 3 FIL_RUNOUT2_PIN 4 FIL_RUNOUT3_PIN 5 FIL_RUNOUT4_PIN 6 FIL_RUNOUT5_PIN 7 FIL_RUNOUT6_PIN 8 FIL_RUNOUT7_PIN 9 FIL_RUNOUT8_PIN 10 \ + FIL_RUNOUT4_STATE HIGH FIL_RUNOUT8_STATE HIGH +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 +exec_test $1 $2 "BigTreeTech GTR | 8 Extruders | Auto-Fan | Mixed TMC Drivers | Runout Sensors w/ distinct states" "$3" + +restore_configs +opt_set MOTHERBOARD BOARD_BTT_GTR_V1_0 SERIAL_PORT -1 \ + EXTRUDERS 5 TEMP_SENSOR_1 1 TEMP_SENSOR_2 1 TEMP_SENSOR_3 1 TEMP_SENSOR_4 1 \ + NUM_Z_STEPPER_DRIVERS 4 \ + 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_INIT_BEFORE_SWAP TOOLCHANGE_FS_PRIME_FIRST_USED \ + 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 \ + SERVO_DELAY '{ 300, 300, 300 }' +opt_enable SWITCHING_TOOLHEAD TOOL_SENSOR +exec_test $1 $2 "BigTreeTech GTR | Switching Toolhead | Tool Sensors" "$3" + +# clean up +restore_configs diff --git a/buildroot/tests/BIGTREE_GTR_V1_0-tests b/buildroot/tests/BIGTREE_GTR_V1_0-tests deleted file mode 100644 index e8d47562aa61..000000000000 --- a/buildroot/tests/BIGTREE_GTR_V1_0-tests +++ /dev/null @@ -1,46 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for BigTreeTech GTR 1.0 -# - -# exit on first failure -set -e - -restore_configs -opt_set MOTHERBOARD BOARD_BTT_GTR_V1_0 -opt_set SERIAL_PORT -1 -opt_set EXTRUDERS 8 -opt_set TEMP_SENSOR_1 1 -opt_set TEMP_SENSOR_2 1 -opt_set TEMP_SENSOR_3 1 -opt_set TEMP_SENSOR_4 1 -opt_set TEMP_SENSOR_5 1 -opt_set TEMP_SENSOR_6 1 -opt_set TEMP_SENSOR_7 1 -# Not necessary to enable auto-fan for all extruders to hit problematic code paths -opt_set E0_AUTO_FAN_PIN PC10 -opt_set E1_AUTO_FAN_PIN PC11 -opt_set E2_AUTO_FAN_PIN PC12 -opt_set X_DRIVER_TYPE TMC2208 -opt_set Y_DRIVER_TYPE TMC2130 -opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER -exec_test $1 $2 "BigTreeTech GTR 8 Extruders with Auto-Fan and Mixed TMC Drivers" - -restore_configs -opt_set MOTHERBOARD BOARD_BTT_GTR_V1_0 -opt_set SERIAL_PORT -1 -opt_set EXTRUDERS 6 -opt_set TEMP_SENSOR_1 1 -opt_set TEMP_SENSOR_2 1 -opt_set TEMP_SENSOR_3 1 -opt_set TEMP_SENSOR_4 1 -opt_set TEMP_SENSOR_5 1 -opt_set NUM_Z_STEPPER_DRIVERS 3 -opt_set DEFAULT_Kp_LIST "{ 22.2, 20.0, 21.0, 19.0, 18.0, 17.0 }" -opt_set DEFAULT_Ki_LIST "{ 1.08 }" -opt_set DEFAULT_Kd_LIST "{ 114.0, 112.0, 110.0, 108.0 }" -opt_enable TOOLCHANGE_FILAMENT_SWAP TOOLCHANGE_MIGRATION_FEATURE TOOLCHANGE_FS_INIT_BEFORE_SWAP TOOLCHANGE_FS_PRIME_FIRST_USED PID_PARAMS_PER_HOTEND -exec_test $1 $2 "BigTreeTech GTR 6 Extruders Triple Z" - -# clean up -restore_configs diff --git a/buildroot/tests/BIGTREE_GTR_V1_0_usb_flash_drive b/buildroot/tests/BIGTREE_GTR_V1_0_usb_flash_drive new file mode 100755 index 000000000000..197ece5dfd66 --- /dev/null +++ b/buildroot/tests/BIGTREE_GTR_V1_0_usb_flash_drive @@ -0,0 +1,24 @@ +#!/usr/bin/env bash +# +# Build tests for BigTreeTech GTR 1.0 +# + +# exit on first failure +set -e + +restore_configs +opt_set MOTHERBOARD BOARD_BTT_GTR_V1_0 SERIAL_PORT 3 \ + EXTRUDERS 8 TEMP_SENSOR_1 1 TEMP_SENSOR_2 1 TEMP_SENSOR_3 1 TEMP_SENSOR_4 1 TEMP_SENSOR_5 1 TEMP_SENSOR_6 1 TEMP_SENSOR_7 1 +opt_enable SDSUPPORT USB_FLASH_DRIVE_SUPPORT USE_OTG_USB_HOST \ + REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER BLTOUCH NEOPIXEL_LED Z_SAFE_HOMING \ + FILAMENT_RUNOUT_SENSOR NOZZLE_PARK_FEATURE ADVANCED_PAUSE_FEATURE +# Not necessary to enable auto-fan for all extruders to hit problematic code paths +opt_set E0_AUTO_FAN_PIN PC10 E1_AUTO_FAN_PIN PC11 E2_AUTO_FAN_PIN PC12 NEOPIXEL_PIN PF13 \ + X_DRIVER_TYPE TMC2208 Y_DRIVER_TYPE TMC2130 \ + FIL_RUNOUT_PIN 3 FIL_RUNOUT2_PIN 4 FIL_RUNOUT3_PIN 5 FIL_RUNOUT4_PIN 6 FIL_RUNOUT5_PIN 7 FIL_RUNOUT6_PIN 8 FIL_RUNOUT7_PIN 9 FIL_RUNOUT8_PIN 10 \ + FIL_RUNOUT4_STATE HIGH FIL_RUNOUT8_STATE HIGH +opt_enable FIL_RUNOUT4_PULLUP FIL_RUNOUT8_PULLUP +exec_test $1 $2 "GTT GTR | OTG USB Flash Drive | 8 Extruders | Auto-Fan | Mixed TMC Drivers | Runout Sensors (distinct)" "$3" + +# clean up +restore_configs diff --git a/buildroot/tests/BIGTREE_SKR_PRO b/buildroot/tests/BIGTREE_SKR_PRO new file mode 100755 index 000000000000..2503b28544ad --- /dev/null +++ b/buildroot/tests/BIGTREE_SKR_PRO @@ -0,0 +1,33 @@ +#!/usr/bin/env bash +# +# Build tests for STM32F407ZG BigTreeTech SKR Pro +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +restore_configs +opt_set MOTHERBOARD BOARD_BTT_SKR_PRO_V1_1 SERIAL_PORT 1 +exec_test $1 $2 "BigTreeTech SKR Pro | Default Configuration" "$3" + +restore_configs +opt_set MOTHERBOARD BOARD_BTT_SKR_PRO_V1_1 SERIAL_PORT -1 \ + EXTRUDERS 3 TEMP_SENSOR_1 1 TEMP_SENSOR_2 1 \ + E0_AUTO_FAN_PIN PC10 E1_AUTO_FAN_PIN PC11 E2_AUTO_FAN_PIN PC12 \ + X_DRIVER_TYPE TMC2209 Y_DRIVER_TYPE TMC2130 +opt_enable BLTOUCH EEPROM_SETTINGS AUTO_BED_LEVELING_3POINT Z_SAFE_HOMING PINS_DEBUGGING +exec_test $1 $2 "BigTreeTech SKR Pro | 3 Extruders | Auto-Fan | BLTOUCH | Mixed TMC" "$3" + +restore_configs +opt_set MOTHERBOARD BOARD_BTT_SKR_PRO_V1_1 SERIAL_PORT -1 \ + CUTTER_POWER_UNIT PERCENT \ + SPINDLE_LASER_PWM_PIN HEATER_1_PIN SPINDLE_LASER_ENA_PIN HEATER_2_PIN \ + TEMP_SENSOR_COOLER 1000 TEMP_COOLER_PIN PD13 +opt_enable LASER_FEATURE REPRAP_DISCOUNT_SMART_CONTROLLER +exec_test $1 $2 "BigTreeTech SKR Pro | Laser (Percent) | Cooling | LCD" "$3" + +# clean up +restore_configs diff --git a/buildroot/tests/BIGTREE_SKR_PRO-tests b/buildroot/tests/BIGTREE_SKR_PRO-tests deleted file mode 100644 index 1295f5858c7e..000000000000 --- a/buildroot/tests/BIGTREE_SKR_PRO-tests +++ /dev/null @@ -1,32 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for STM32F407ZG BigTreeTech SKR Pro -# - -# exit on first failure -set -e - -# -# Build with the default configurations -# -restore_configs -opt_set MOTHERBOARD BOARD_BTT_SKR_PRO_V1_1 -opt_set SERIAL_PORT 1 -exec_test $1 $2 "BigTreeTech SKR Pro Default Configuration" - -restore_configs -opt_set MOTHERBOARD BOARD_BTT_SKR_PRO_V1_1 -opt_set SERIAL_PORT -1 -opt_set EXTRUDERS 3 -opt_set TEMP_SENSOR_1 1 -opt_set TEMP_SENSOR_2 1 -opt_set E0_AUTO_FAN_PIN PC10 -opt_set E1_AUTO_FAN_PIN PC11 -opt_set E2_AUTO_FAN_PIN PC12 -opt_set X_DRIVER_TYPE TMC2209 -opt_set Y_DRIVER_TYPE TMC2130 -opt_enable BLTOUCH EEPROM_SETTINGS AUTO_BED_LEVELING_3POINT Z_SAFE_HOMING -exec_test $1 $2 "BigTreeTech SKR Pro 3 Extruders, Auto-Fan, BLTOUCH, mixed TMC drivers" - -# clean up -restore_configs diff --git a/buildroot/tests/BTT_SKR_SE_BX b/buildroot/tests/BTT_SKR_SE_BX new file mode 100755 index 000000000000..b5d6f6de8398 --- /dev/null +++ b/buildroot/tests/BTT_SKR_SE_BX @@ -0,0 +1,18 @@ +#!/usr/bin/env bash +# +# Build tests for BTT_SKR_SE_BX +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +restore_configs +opt_set MOTHERBOARD BOARD_BTT_SKR_SE_BX +opt_set SERIAL_PORT 1 +exec_test $1 $2 "Default Configuration" "$3" + +# clean up +restore_configs diff --git a/buildroot/tests/DUE b/buildroot/tests/DUE new file mode 100755 index 000000000000..9eb2157428e4 --- /dev/null +++ b/buildroot/tests/DUE @@ -0,0 +1,51 @@ +#!/usr/bin/env bash +# +# Build tests for DUE (Atmel SAM3X8E ARM Cortex-M3) +# + +# exit on first failure +set -e + +restore_configs +opt_set MOTHERBOARD BOARD_RAMPS4DUE_EFB \ + LCD_LANGUAGE bg \ + 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 +opt_enable S_CURVE_ACCELERATION EEPROM_SETTINGS GCODE_MACROS \ + FIX_MOUNTED_PROBE Z_SAFE_HOMING CODEPENDENT_XY_HOMING \ + ASSISTED_TRAMMING ASSISTED_TRAMMING_WIZARD REPORT_TRAMMING_MM ASSISTED_TRAMMING_WAIT_POSITION \ + EEPROM_SETTINGS SDSUPPORT BINARY_FILE_TRANSFER \ + BLINKM PCA9533 PCA9632 RGB_LED RGB_LED_R_PIN RGB_LED_G_PIN RGB_LED_B_PIN LED_CONTROL_MENU \ + NEOPIXEL_LED NEOPIXEL_PIN CASE_LIGHT_ENABLE CASE_LIGHT_USE_NEOPIXEL CASE_LIGHT_USE_RGB_LED CASE_LIGHT_MENU \ + NOZZLE_PARK_FEATURE ADVANCED_PAUSE_FEATURE FILAMENT_RUNOUT_DISTANCE_MM FILAMENT_RUNOUT_SENSOR \ + AUTO_BED_LEVELING_BILINEAR Z_MIN_PROBE_REPEATABILITY_TEST DEBUG_LEVELING_FEATURE \ + SKEW_CORRECTION SKEW_CORRECTION_FOR_Z SKEW_CORRECTION_GCODE CALIBRATION_GCODE \ + BACKLASH_COMPENSATION BACKLASH_GCODE BAUD_RATE_GCODE BEZIER_CURVE_SUPPORT \ + FWRETRACT ARC_SUPPORT ARC_P_CIRCLES CNC_WORKSPACE_PLANES CNC_COORDINATE_SYSTEMS \ + PSU_CONTROL AUTO_POWER_CONTROL E_DUAL_STEPPER_DRIVERS \ + PIDTEMPBED SLOW_PWM_HEATERS THERMAL_PROTECTION_CHAMBER \ + PINS_DEBUGGING MAX7219_DEBUG M114_DETAIL \ + EXTENSIBLE_UI +opt_add EXTUI_EXAMPLE +exec_test $1 $2 "RAMPS4DUE_EFB with ABL (Bilinear), ExtUI, S-Curve, many options." "$3" + +# +# RADDS with BLTouch, ABL(B), 3 x Z auto-align +# +restore_configs +opt_set MOTHERBOARD BOARD_RADDS NUM_Z_STEPPER_DRIVERS 3 +opt_enable USE_XMAX_PLUG USE_YMAX_PLUG ENDSTOPPULLUPS BLTOUCH AUTO_BED_LEVELING_BILINEAR \ + Z_STEPPER_AUTO_ALIGN Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS Z_SAFE_HOMING +pins_set ramps/RAMPS X_MAX_PIN -1 +pins_set ramps/RAMPS Y_MAX_PIN -1 +exec_test $1 $2 "RADDS with ABL (Bilinear), Triple Z Axis, Z_STEPPER_AUTO_ALIGN, E_DUAL_STEPPER_DRIVERS" "$3" + +# +# Test SWITCHING_EXTRUDER +# +restore_configs +opt_set MOTHERBOARD BOARD_RAMPS4DUE_EEF LCD_LANGUAGE fi EXTRUDERS 2 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-tests b/buildroot/tests/DUE-tests deleted file mode 100755 index 7f488f6126cb..000000000000 --- a/buildroot/tests/DUE-tests +++ /dev/null @@ -1,62 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for DUE (Atmel SAM3X8E ARM Cortex-M3) -# - -# exit on first failure -set -e - -restore_configs -opt_set LCD_LANGUAGE bg -opt_set MOTHERBOARD BOARD_RAMPS4DUE_EFB -opt_set TEMP_SENSOR_0 -2 -opt_set TEMP_SENSOR_BED 2 -opt_set GRID_MAX_POINTS_X 16 -opt_set FANMUX0_PIN 53 -opt_enable S_CURVE_ACCELERATION EEPROM_SETTINGS GCODE_MACROS \ - FIX_MOUNTED_PROBE Z_SAFE_HOMING CODEPENDENT_XY_HOMING ASSISTED_TRAMMING \ - EEPROM_SETTINGS SDSUPPORT BINARY_FILE_TRANSFER \ - BLINKM PCA9533 PCA9632 RGB_LED RGB_LED_R_PIN RGB_LED_G_PIN RGB_LED_B_PIN LED_CONTROL_MENU \ - NEOPIXEL_LED CASE_LIGHT_ENABLE CASE_LIGHT_USE_NEOPIXEL CASE_LIGHT_MENU \ - NOZZLE_PARK_FEATURE ADVANCED_PAUSE_FEATURE FILAMENT_RUNOUT_DISTANCE_MM FILAMENT_RUNOUT_SENSOR \ - AUTO_BED_LEVELING_BILINEAR Z_MIN_PROBE_REPEATABILITY_TEST DEBUG_LEVELING_FEATURE \ - SKEW_CORRECTION SKEW_CORRECTION_FOR_Z SKEW_CORRECTION_GCODE CALIBRATION_GCODE \ - BACKLASH_COMPENSATION BACKLASH_GCODE BAUD_RATE_GCODE BEZIER_CURVE_SUPPORT \ - FWRETRACT ARC_SUPPORT ARC_P_CIRCLES CNC_WORKSPACE_PLANES CNC_COORDINATE_SYSTEMS \ - PSU_CONTROL AUTO_POWER_CONTROL \ - PIDTEMPBED SLOW_PWM_HEATERS THERMAL_PROTECTION_CHAMBER \ - PINS_DEBUGGING MAX7219_DEBUG M114_DETAIL \ - EXTENSIBLE_UI -opt_add EXTUI_EXAMPLE -opt_set E0_AUTO_FAN_PIN 8 -opt_set EXTRUDER_AUTO_FAN_SPEED 100 -opt_set TEMP_SENSOR_CHAMBER 3 -opt_add TEMP_CHAMBER_PIN 6 -opt_set HEATER_CHAMBER_PIN 45 -exec_test $1 $2 "RAMPS4DUE_EFB with ABL (Bilinear), ExtUI, S-Curve, many options." - -restore_configs -opt_set MOTHERBOARD BOARD_RADDS -opt_enable USE_XMAX_PLUG USE_YMAX_PLUG ENDSTOPPULLUPS BLTOUCH AUTO_BED_LEVELING_BILINEAR \ - Z_MULTI_ENDSTOPS Z_STEPPER_AUTO_ALIGN Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS \ - Z_SAFE_HOMING - #TOUCH_UI_FTDI_EVE LCD_ALEPHOBJECTS_CLCD_UI OTHER_PIN_LAYOUT -opt_set NUM_Z_STEPPER_DRIVERS 3 -opt_add Z2_MAX_ENDSTOP_INVERTING false -opt_add Z3_MAX_ENDSTOP_INVERTING false -opt_add Z2_MAX_PIN 2 -opt_add Z3_MAX_PIN 3 -pins_set ramps/RAMPS X_MAX_PIN -1 -pins_set ramps/RAMPS Y_MAX_PIN -1 -exec_test $1 $2 "RADDS with ABL (Bilinear), Triple Z Axis, Z_STEPPER_AUTO_ALIGN" - -# -# Test SWITCHING_EXTRUDER -# -restore_configs -opt_set LCD_LANGUAGE fi -opt_set MOTHERBOARD BOARD_RAMPS4DUE_EEF -opt_set EXTRUDERS 2 -opt_set 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" diff --git a/buildroot/tests/DUE_archim b/buildroot/tests/DUE_archim new file mode 100755 index 000000000000..f1711a8f3d70 --- /dev/null +++ b/buildroot/tests/DUE_archim @@ -0,0 +1,21 @@ +#!/usr/bin/env bash +# +# Build tests for DUE (Atmel SAM3X8E ARM Cortex-M3) +# + +# exit on first failure +set -e + +# +# Test Archim 1 +# +use_example_configs UltiMachine/Archim1 +exec_test $1 $2 "Archim 1 base configuration" "$3" + +# +# Test Archim 2 +# +use_example_configs UltiMachine/Archim2 +exec_test $1 $2 "Archim 2 base configuration" "$3" + +restore_configs diff --git a/buildroot/tests/FLYF407ZG b/buildroot/tests/FLYF407ZG new file mode 100755 index 000000000000..22dd3488c8e1 --- /dev/null +++ b/buildroot/tests/FLYF407ZG @@ -0,0 +1,15 @@ +#!/usr/bin/env bash +# +# Build tests for FLYF407ZG +# + +# exit on first failure +set -e + +# Build examples +restore_configs +opt_set MOTHERBOARD BOARD_FLYF407ZG SERIAL_PORT -1 X_DRIVER_TYPE TMC2208 Y_DRIVER_TYPE TMC2130 +exec_test $1 $2 "FLYF407ZG Default Config with mixed TMC Drivers" "$3" + +# cleanup +restore_configs diff --git a/buildroot/tests/FLYF407ZG-tests b/buildroot/tests/FLYF407ZG-tests deleted file mode 100644 index f1a65da6cbb3..000000000000 --- a/buildroot/tests/FLYF407ZG-tests +++ /dev/null @@ -1,18 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for FLYF407ZG -# - -# exit on first failure -set -e - -# Build examples -restore_configs -opt_set MOTHERBOARD BOARD_FLYF407ZG -opt_set SERIAL_PORT -1 -opt_set X_DRIVER_TYPE TMC2208 -opt_set Y_DRIVER_TYPE TMC2130 -exec_test $1 $2 "FLYF407ZG Default Config with mixed TMC Drivers" - -# cleanup -restore_configs diff --git a/buildroot/tests/FYSETC_F6 b/buildroot/tests/FYSETC_F6 new file mode 100755 index 000000000000..9306686af5ce --- /dev/null +++ b/buildroot/tests/FYSETC_F6 @@ -0,0 +1,67 @@ +#!/usr/bin/env bash +# +# Build tests for AVR ATmega FYSETC F6 1.3 +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +restore_configs +opt_set MOTHERBOARD BOARD_FYSETC_F6_13 +opt_enable DGUS_LCD_UI_FYSETC +exec_test $1 $2 "FYSETC F6 1.3 with DGUS" "$3" + +# +# Delta Config (generic) + UBL + ALLEN_KEY + EEPROM_SETTINGS + OLED_PANEL_TINYBOY2 +# +use_example_configs delta/generic +opt_set MOTHERBOARD BOARD_FYSETC_F6_13 \ + LCD_LANGUAGE ko_KR \ + X_DRIVER_TYPE L6470 Y_DRIVER_TYPE L6470 Z_DRIVER_TYPE L6470 \ + L6470_CHAIN_SCK_PIN 53 L6470_CHAIN_MISO_PIN 49 L6470_CHAIN_MOSI_PIN 40 L6470_CHAIN_SS_PIN 42 \ + 'ENABLE_RESET_L64XX_CHIPS(V)' NOOP +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, RAMPS, L6470, UBL, Allen Key, EEPROM, OLED_PANEL_TINYBOY2..." "$3" + +# +# Test mixed TMC config +# +restore_configs +opt_set MOTHERBOARD BOARD_FYSETC_F6_13 \ + LCD_LANGUAGE vi LCD_LANGUAGE_2 fr \ + X_DRIVER_TYPE TMC2160 Y_DRIVER_TYPE TMC5160 Z_DRIVER_TYPE TMC2208_STANDALONE E0_DRIVER_TYPE TMC2130 \ + X_MIN_ENDSTOP_INVERTING true Y_MIN_ENDSTOP_INVERTING true +opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER \ + MARLIN_BRICKOUT MARLIN_INVADERS MARLIN_SNAKE \ + MONITOR_DRIVER_STATUS STEALTHCHOP_XY STEALTHCHOP_Z STEALTHCHOP_E HYBRID_THRESHOLD \ + USE_ZMIN_PLUG SENSORLESS_HOMING TMC_DEBUG M114_DETAIL +exec_test $1 $2 "RAMPS | Mixed TMC | Sensorless | RRDFGSC | Games" "$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 "RAMPS 1.3 | DELTA | FLSUN AC Config" "$3" + +# +# SCARA with Mixed TMC +# +use_example_configs SCARA/Morgan +opt_set MOTHERBOARD BOARD_FYSETC_F6_13 \ + LCD_LANGUAGE es \ + X_MAX_ENDSTOP_INVERTING false \ + X_DRIVER_TYPE TMC2209 Y_DRIVER_TYPE TMC2130 Z_DRIVER_TYPE TMC2130_STANDALONE E0_DRIVER_TYPE TMC2660 \ + X_HARDWARE_SERIAL Serial2 +opt_enable USE_ZMIN_PLUG FIX_MOUNTED_PROBE AUTO_BED_LEVELING_BILINEAR PAUSE_BEFORE_DEPLOY_STOW \ + FYSETC_242_OLED_12864 EEPROM_SETTINGS EEPROM_CHITCHAT M114_DETAIL Z_SAFE_HOMING \ + STEALTHCHOP_XY STEALTHCHOP_Z STEALTHCHOP_E HYBRID_THRESHOLD SENSORLESS_HOMING SQUARE_WAVE_STEPPING +exec_test $1 $2 "FYSETC_F6 | SCARA | Mixed TMC | EEPROM" "$3" + +# clean up +restore_configs diff --git a/buildroot/tests/FYSETC_F6_13-tests b/buildroot/tests/FYSETC_F6_13-tests deleted file mode 100644 index 631a11778502..000000000000 --- a/buildroot/tests/FYSETC_F6_13-tests +++ /dev/null @@ -1,18 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for AVR ATmega FYSETC F6 1.3 -# - -# exit on first failure -set -e - -# -# Build with the default configurations -# -restore_configs -opt_set MOTHERBOARD BOARD_FYSETC_F6_13 -opt_enable DGUS_LCD_UI_FYSETC -exec_test $1 $2 "FYSETC F6 1.3 with DGUS" - -# clean up -restore_configs diff --git a/buildroot/tests/FYSETC_S6 b/buildroot/tests/FYSETC_S6 new file mode 100755 index 000000000000..4794e11354d4 --- /dev/null +++ b/buildroot/tests/FYSETC_S6 @@ -0,0 +1,17 @@ +#!/usr/bin/env bash +# +# Build tests for FYSETC_S6 +# + +# exit on first failure +set -e + +# Build examples +restore_configs +use_example_configs FYSETC/S6 +opt_enable MEATPACK_ON_SERIAL_PORT_1 +opt_set Y_DRIVER_TYPE TMC2209 Z_DRIVER_TYPE TMC2130 +exec_test $1 $2 "FYSETC S6 Example" "$3" + +# cleanup +restore_configs diff --git a/buildroot/tests/FYSETC_S6-tests b/buildroot/tests/FYSETC_S6-tests deleted file mode 100644 index c75629156b08..000000000000 --- a/buildroot/tests/FYSETC_S6-tests +++ /dev/null @@ -1,17 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for FYSETC_S6 -# - -# exit on first failure -set -e - -# Build examples -restore_configs -use_example_configs FYSETC/S6 -opt_set Y_DRIVER_TYPE TMC2209 -opt_set Z_DRIVER_TYPE TMC2130 -exec_test $1 $2 "FYSETC S6 Example" - -# cleanup -restore_configs diff --git a/buildroot/tests/LERDGEK b/buildroot/tests/LERDGEK new file mode 100755 index 000000000000..1aca42c18aba --- /dev/null +++ b/buildroot/tests/LERDGEK @@ -0,0 +1,18 @@ +#!/usr/bin/env bash +# +# Build tests for LERDGEK environment +# + +# exit on first failure +set -e + +# +# Build with the typical configuration +# +restore_configs +opt_set MOTHERBOARD BOARD_LERDGE_K SERIAL_PORT 1 +opt_enable TFT_GENERIC TFT_INTERFACE_FSMC TFT_COLOR_UI +exec_test $1 $2 "LERDGE K with Generic FSMC TFT with ColorUI" "$3" + +# clean up +restore_configs diff --git a/buildroot/tests/LERDGEX b/buildroot/tests/LERDGEX new file mode 100755 index 000000000000..cf7dfebfeabb --- /dev/null +++ b/buildroot/tests/LERDGEX @@ -0,0 +1,17 @@ +#!/usr/bin/env bash +# +# Build tests for LERDGEX environment +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +restore_configs +opt_set MOTHERBOARD BOARD_LERDGE_X SERIAL_PORT 1 +exec_test $1 $2 "LERDGE X with Default Configuration" "$3" + +# clean up +restore_configs diff --git a/buildroot/tests/LERDGEX-tests b/buildroot/tests/LERDGEX-tests deleted file mode 100644 index c2d72e0d77e6..000000000000 --- a/buildroot/tests/LERDGEX-tests +++ /dev/null @@ -1,18 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for LERDGEX environment -# - -# exit on first failure -set -e - -# -# Build with the default configurations -# -restore_configs -opt_set MOTHERBOARD BOARD_LERDGE_X -opt_set SERIAL_PORT 1 -exec_test $1 $2 "LERDGE X with Default Configuration" - -# clean up -restore_configs diff --git a/buildroot/tests/LPC1768 b/buildroot/tests/LPC1768 new file mode 100755 index 000000000000..b4e489d31018 --- /dev/null +++ b/buildroot/tests/LPC1768 @@ -0,0 +1,54 @@ +#!/usr/bin/env bash +# +# Build tests for LPC1768 (NXP ARM Cortex-M3) +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +#restore_configs +#opt_set MOTHERBOARD BOARD_RAMPS_14_RE_ARM_EFB +#exec_test $1 $2 "Default Configuration" "$3" + +restore_configs +opt_set MOTHERBOARD BOARD_RAMPS_14_RE_ARM_EFB SERIAL_PORT_3 3 \ + NEOPIXEL_TYPE NEO_GRB RGB_LED_R_PIN P2_12 RGB_LED_G_PIN P1_23 RGB_LED_B_PIN P1_22 RGB_LED_W_PIN P1_24 +opt_enable FYSETC_MINI_12864_2_1 SDSUPPORT SDCARD_READONLY SERIAL_PORT_2 RGBW_LED E_DUAL_STEPPER_DRIVERS \ + NEOPIXEL_LED NEOPIXEL_IS_SEQUENTIAL NEOPIXEL_STARTUP_TEST NEOPIXEL_BKGD_INDEX_FIRST NEOPIXEL_BKGD_INDEX_LAST NEOPIXEL_BKGD_COLOR NEOPIXEL_BKGD_ALWAYS_ON +exec_test $1 $2 "ReARM EFB VIKI2, SDSUPPORT, 2 Serial ports (USB CDC + UART0), NeoPixel" "$3" + +#restore_configs +#use_example_configs Mks/Sbase +#exec_test $1 $2 "MKS SBASE Example Config" "$3" + +restore_configs +opt_set MOTHERBOARD BOARD_MKS_SBASE \ + EXTRUDERS 2 TEMP_SENSOR_1 1 \ + NUM_SERVOS 2 SERVO_DELAY '{ 300, 300 }' +opt_enable SWITCHING_NOZZLE SWITCHING_NOZZLE_E1_SERVO_NR 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 \ + GRID_MAX_POINTS_X 16 \ + NOZZLE_TO_PROBE_OFFSET '{ 0, 0, 0 }' \ + NOZZLE_CLEAN_MIN_TEMP 170 \ + 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 ADAPTIVE_FAN_SLOWING NO_FAN_SLOWING_IN_PID_TUNING \ + FILAMENT_WIDTH_SENSOR FILAMENT_LCD_DISPLAY PID_EXTRUSION_SCALING SOUND_MENU_ITEM \ + NOZZLE_AS_PROBE AUTO_BED_LEVELING_BILINEAR PREHEAT_BEFORE_LEVELING G29_RETRY_AND_RECOVER 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 \ + Z_SAFE_HOMING ADVANCED_PAUSE_FEATURE PARK_HEAD_ON_PAUSE \ + HOST_KEEPALIVE_FEATURE HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT \ + 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" + +# clean up +restore_configs diff --git a/buildroot/tests/LPC1768-tests b/buildroot/tests/LPC1768-tests deleted file mode 100755 index 2f206f02f2e6..000000000000 --- a/buildroot/tests/LPC1768-tests +++ /dev/null @@ -1,53 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for LPC1768 (NXP ARM Cortex-M3) -# - -# exit on first failure -set -e - -# -# Build with the default configurations -# -#restore_configs -#opt_set MOTHERBOARD BOARD_RAMPS_14_RE_ARM_EFB -#exec_test $1 $2 "Default Configuration" - -restore_configs -opt_set MOTHERBOARD BOARD_RAMPS_14_RE_ARM_EFB -opt_enable VIKI2 SDSUPPORT SDCARD_READONLY SERIAL_PORT_2 NEOPIXEL_LED -opt_set NEOPIXEL_PIN P1_16 -exec_test $1 $2 "ReARM EFB VIKI2, SDSUPPORT, 2 Serial ports (USB CDC + UART0), NeoPixel" - -#restore_configs -#use_example_configs Mks/Sbase -#exec_test $1 $2 "MKS SBASE Example Config" - -restore_configs -opt_set MOTHERBOARD BOARD_MKS_SBASE -opt_set EXTRUDERS 2 -opt_set TEMP_SENSOR_1 1 -opt_set NUM_SERVOS 2 -opt_set SERVO_DELAY "{ 300, 300 }" -opt_enable SWITCHING_NOZZLE SWITCHING_NOZZLE_E1_SERVO_NR ULTIMAKERCONTROLLER -exec_test $1 $2 "MKS SBASE with SWITCHING_NOZZLE" - -restore_configs -opt_set MOTHERBOARD BOARD_RAMPS_14_RE_ARM_EEB -opt_set EXTRUDERS 2 -opt_set TEMP_SENSOR_1 -1 -opt_set TEMP_SENSOR_BED 5 -opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER SDSUPPORT ADAPTIVE_FAN_SLOWING NO_FAN_SLOWING_IN_PID_TUNING \ - FILAMENT_WIDTH_SENSOR FILAMENT_LCD_DISPLAY PID_EXTRUSION_SCALING \ - NOZZLE_AS_PROBE AUTO_BED_LEVELING_BILINEAR G29_RETRY_AND_RECOVER 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 \ - Z_SAFE_HOMING ADVANCED_PAUSE_FEATURE PARK_HEAD_ON_PAUSE \ - HOST_KEEPALIVE_FEATURE HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT \ - LCD_INFO_MENU ARC_SUPPORT BEZIER_CURVE_SUPPORT EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES SDCARD_SORT_ALPHA EMERGENCY_PARSER -opt_set GRID_MAX_POINTS_X 16 -opt_set NOZZLE_TO_PROBE_OFFSET "{ 0, 0, 0 }" -exec_test $1 $2 "Re-ARM with NOZZLE_AS_PROBE and many features." - -# clean up -restore_configs diff --git a/buildroot/tests/LPC1769 b/buildroot/tests/LPC1769 new file mode 100755 index 000000000000..f0dab630e5e5 --- /dev/null +++ b/buildroot/tests/LPC1769 @@ -0,0 +1,54 @@ +#!/usr/bin/env bash +# +# Build tests for LPC1769 (NXP ARM Cortex-M3) +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +use_example_configs Azteeg/X5GT +exec_test $1 $2 "Azteeg X5GT Example Configuration" "$3" + +restore_configs +opt_set MOTHERBOARD BOARD_SMOOTHIEBOARD \ + EXTRUDERS 2 TEMP_SENSOR_1 -1 TEMP_SENSOR_BED 5 \ + GRID_MAX_POINTS_X 16 \ + NOZZLE_CLEAN_START_POINT "{ { 10, 10, 3 }, { 10, 10, 3 } }" \ + NOZZLE_CLEAN_END_POINT "{ { 10, 20, 3 }, { 10, 20, 3 } }" +opt_enable TFTGLCD_PANEL_SPI SDSUPPORT ADAPTIVE_FAN_SLOWING NO_FAN_SLOWING_IN_PID_TUNING \ + FIX_MOUNTED_PROBE AUTO_BED_LEVELING_BILINEAR G29_RETRY_AND_RECOVER Z_MIN_PROBE_REPEATABILITY_TEST DEBUG_LEVELING_FEATURE \ + BABYSTEPPING BABYSTEP_XY BABYSTEP_ZPROBE_OFFSET LEVEL_CORNERS_USE_PROBE LEVEL_CORNERS_VERIFY_RAISED \ + PRINTCOUNTER NOZZLE_PARK_FEATURE NOZZLE_CLEAN_FEATURE SLOW_PWM_HEATERS PIDTEMPBED EEPROM_SETTINGS INCH_MODE_SUPPORT TEMPERATURE_UNITS_SUPPORT \ + Z_SAFE_HOMING ADVANCED_PAUSE_FEATURE PARK_HEAD_ON_PAUSE \ + LCD_INFO_MENU ARC_SUPPORT BEZIER_CURVE_SUPPORT EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES SDCARD_SORT_ALPHA EMERGENCY_PARSER +exec_test $1 $2 "Smoothieboard with TFTGLCD_PANEL_SPI and many features" "$3" + +#restore_configs +#opt_set MOTHERBOARD BOARD_AZTEEG_X5_MINI_WIFI +#opt_enable COREYX USE_XMAX_PLUG DAC_MOTOR_CURRENT_DEFAULT \ +# REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT BABYSTEPPING \ +# AUTO_BED_LEVELING_UBL RESTORE_LEVELING_AFTER_G28 EEPROM_SETTINGS \ +# FILAMENT_LCD_DISPLAY FILAMENT_WIDTH_SENSOR FAN_SOFT_PWM \ +# SHOW_TEMP_ADC_VALUES HOME_Y_BEFORE_X EMERGENCY_PARSER FAN_KICKSTART_TIME \ +# SD_ABORT_ON_ENDSTOP_HIT ADVANCED_OK GCODE_MACROS \ +# VOLUMETRIC_DEFAULT_ON NO_WORKSPACE_OFFSETS \ +# EXTRA_FAN_SPEED FWRETRACT MENU_ADDAUTOSTART SDCARD_SORT_ALPHA +#opt_set FAN_MIN_PWM 50 FAN_KICKSTART_TIME 100 XY_FREQUENCY_LIMIT 15 +#exec_test $1 $2 "Azteeg X5 MINI WIFI Many less common options" "$3" + +restore_configs +use_example_configs delta/generic +opt_set MOTHERBOARD BOARD_COHESION3D_REMIX \ + X_DRIVER_TYPE TMC2130 Y_DRIVER_TYPE TMC2130 Z_DRIVER_TYPE TMC2130 +opt_enable AUTO_BED_LEVELING_BILINEAR EEPROM_SETTINGS EEPROM_CHITCHAT MECHANICAL_GANTRY_CALIBRATION \ + TMC_USE_SW_SPI MONITOR_DRIVER_STATUS STEALTHCHOP_XY STEALTHCHOP_Z HYBRID_THRESHOLD \ + SENSORLESS_PROBING Z_SAFE_HOMING X_STALL_SENSITIVITY Y_STALL_SENSITIVITY Z_STALL_SENSITIVITY TMC_DEBUG \ + EXPERIMENTAL_I2CBUS +opt_disable PSU_CONTROL Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN +exec_test $1 $2 "Cohesion3D Remix DELTA + ABL Bilinear + EEPROM + SENSORLESS_PROBING" "$3" + +# clean up +restore_configs diff --git a/buildroot/tests/LPC1769-tests b/buildroot/tests/LPC1769-tests deleted file mode 100755 index 4314b0d5ff8d..000000000000 --- a/buildroot/tests/LPC1769-tests +++ /dev/null @@ -1,72 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for LPC1769 (NXP ARM Cortex-M3) -# - -# exit on first failure -set -e - -# -# Build with the default configurations -# -use_example_configs Azteeg/X5GT -exec_test $1 $2 "Azteeg X5GT Example Configuration" - -restore_configs -opt_set MOTHERBOARD BOARD_SMOOTHIEBOARD -opt_set EXTRUDERS 2 -opt_set TEMP_SENSOR_1 -1 -opt_set TEMP_SENSOR_BED 5 -opt_enable VIKI2 SDSUPPORT ADAPTIVE_FAN_SLOWING NO_FAN_SLOWING_IN_PID_TUNING \ - FIX_MOUNTED_PROBE AUTO_BED_LEVELING_BILINEAR G29_RETRY_AND_RECOVER Z_MIN_PROBE_REPEATABILITY_TEST DEBUG_LEVELING_FEATURE \ - BABYSTEPPING BABYSTEP_XY BABYSTEP_ZPROBE_OFFSET 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 \ - LCD_INFO_MENU ARC_SUPPORT BEZIER_CURVE_SUPPORT EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES SDCARD_SORT_ALPHA EMERGENCY_PARSER -opt_set GRID_MAX_POINTS_X 16 -exec_test $1 $2 "Smoothieboard with many features" - -restore_configs -opt_set MOTHERBOARD BOARD_SMOOTHIEBOARD -opt_set EXTRUDERS 2 -opt_set TEMP_SENSOR_1 -1 -opt_set TEMP_SENSOR_BED 5 -opt_enable TFTGLCD_PANEL_SPI SDSUPPORT ADAPTIVE_FAN_SLOWING NO_FAN_SLOWING_IN_PID_TUNING \ - FIX_MOUNTED_PROBE AUTO_BED_LEVELING_BILINEAR G29_RETRY_AND_RECOVER Z_MIN_PROBE_REPEATABILITY_TEST DEBUG_LEVELING_FEATURE \ - BABYSTEPPING BABYSTEP_XY BABYSTEP_ZPROBE_OFFSET \ - 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 \ - LCD_INFO_MENU ARC_SUPPORT BEZIER_CURVE_SUPPORT EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES SDCARD_SORT_ALPHA EMERGENCY_PARSER -opt_set GRID_MAX_POINTS_X 16 -exec_test $1 $2 "Smoothieboard with TFTGLCD_PANEL_SPI" - -#restore_configs -#opt_set MOTHERBOARD BOARD_AZTEEG_X5_MINI_WIFI -#opt_enable COREYX USE_XMAX_PLUG DAC_MOTOR_CURRENT_DEFAULT \ -# REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT BABYSTEPPING \ -# AUTO_BED_LEVELING_UBL RESTORE_LEVELING_AFTER_G28 EEPROM_SETTINGS \ -# FILAMENT_LCD_DISPLAY FILAMENT_WIDTH_SENSOR FAN_SOFT_PWM \ -# SHOW_TEMP_ADC_VALUES HOME_Y_BEFORE_X EMERGENCY_PARSER FAN_KICKSTART_TIME \ -# SD_ABORT_ON_ENDSTOP_HIT ADVANCED_OK GCODE_MACROS \ -# VOLUMETRIC_DEFAULT_ON NO_WORKSPACE_OFFSETS \ -# EXTRA_FAN_SPEED FWRETRACT MENU_ADDAUTOSTART SDCARD_SORT_ALPHA -#opt_set FAN_MIN_PWM 50 -#opt_set FAN_KICKSTART_TIME 100 -#opt_set XY_FREQUENCY_LIMIT 15 -#exec_test $1 $2 "Azteeg X5 MINI WIFI Many less common options" - -restore_configs -use_example_configs delta/generic -opt_set MOTHERBOARD BOARD_COHESION3D_REMIX -opt_set X_DRIVER_TYPE TMC2130 -opt_set Y_DRIVER_TYPE TMC2130 -opt_set Z_DRIVER_TYPE TMC2130 -opt_enable AUTO_BED_LEVELING_BILINEAR EEPROM_SETTINGS EEPROM_CHITCHAT MECHANICAL_GANTRY_CALIBRATION \ - TMC_USE_SW_SPI MONITOR_DRIVER_STATUS STEALTHCHOP_XY STEALTHCHOP_Z HYBRID_THRESHOLD \ - SENSORLESS_PROBING Z_SAFE_HOMING X_STALL_SENSITIVITY Y_STALL_SENSITIVITY Z_STALL_SENSITIVITY TMC_DEBUG \ - EXPERIMENTAL_I2CBUS -opt_disable PSU_CONTROL -exec_test $1 $2 "Cohesion3D Remix DELTA + ABL Bilinear + EEPROM + SENSORLESS_PROBING" - -# clean up -restore_configs diff --git a/buildroot/tests/NUCLEO_F767ZI b/buildroot/tests/NUCLEO_F767ZI new file mode 100755 index 000000000000..9e2324660695 --- /dev/null +++ b/buildroot/tests/NUCLEO_F767ZI @@ -0,0 +1,18 @@ +#!/usr/bin/env bash +# +# Build tests for NUCLEO_F767ZI +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +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 +exec_test $1 $2 "Mixed timer usage" "$3" + +# clean up +restore_configs diff --git a/buildroot/tests/REMRAM_V1 b/buildroot/tests/REMRAM_V1 new file mode 100755 index 000000000000..f5944ff5af84 --- /dev/null +++ b/buildroot/tests/REMRAM_V1 @@ -0,0 +1,18 @@ +#!/usr/bin/env bash +# +# Build tests for REMRAM_V1 +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +restore_configs +opt_set MOTHERBOARD BOARD_REMRAM_V1 +opt_set SERIAL_PORT 1 +exec_test $1 $2 "Default Configuration" "$3" + +# clean up +restore_configs diff --git a/buildroot/tests/SAMD51_grandcentral_m4 b/buildroot/tests/SAMD51_grandcentral_m4 new file mode 100755 index 000000000000..92a62c9d37a4 --- /dev/null +++ b/buildroot/tests/SAMD51_grandcentral_m4 @@ -0,0 +1,33 @@ +#!/usr/bin/env bash +# +# Build tests for Adafruit Grand Central M4 (ATMEL ARM Cortex-M4) +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +restore_configs +opt_set MOTHERBOARD BOARD_AGCM4_RAMPS_144 SERIAL_PORT -1 \ + TEMP_SENSOR_0 11 TEMP_SENSOR_BED 11 \ + X_DRIVER_TYPE TMC2209 Y_DRIVER_TYPE TMC2209 Z_DRIVER_TYPE TMC2209 Z2_DRIVER_TYPE TMC2209 E0_DRIVER_TYPE TMC2209 \ + RESTORE_LEVELING_AFTER_G28 false \ + LCD_LANGUAGE it \ + SDCARD_CONNECTION LCD \ + NUM_Z_STEPPER_DRIVERS 2 \ + HOMING_BUMP_MM '{ 0, 0, 0 }' +opt_enable ENDSTOP_INTERRUPTS_FEATURE S_CURVE_ACCELERATION BLTOUCH Z_MIN_PROBE_REPEATABILITY_TEST \ + FILAMENT_RUNOUT_SENSOR G26_MESH_VALIDATION MESH_EDIT_GFX_OVERLAY Z_SAFE_HOMING \ + EEPROM_SETTINGS NOZZLE_PARK_FEATURE SDSUPPORT SD_CHECK_AND_RETRY \ + REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER Z_STEPPER_AUTO_ALIGN ADAPTIVE_STEP_SMOOTHING \ + STATUS_MESSAGE_SCROLLING LCD_SET_PROGRESS_MANUALLY SHOW_REMAINING_TIME USE_M73_REMAINING_TIME \ + LONG_FILENAME_HOST_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 +exec_test $1 $2 "Build Grand Central M4 Default Configuration" "$3" + +# clean up +restore_configs diff --git a/buildroot/tests/SAMD51_grandcentral_m4-tests b/buildroot/tests/SAMD51_grandcentral_m4-tests deleted file mode 100644 index fbaf5fb7e55b..000000000000 --- a/buildroot/tests/SAMD51_grandcentral_m4-tests +++ /dev/null @@ -1,39 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for Adafruit Grand Central M4 (ATMEL ARM Cortex-M4) -# - -# exit on first failure -set -e - -# -# Build with the default configurations -# -restore_configs -opt_set SERIAL_PORT -1 -opt_set MOTHERBOARD BOARD_AGCM4_RAMPS_144 -opt_set TEMP_SENSOR_0 11 -opt_set TEMP_SENSOR_BED 11 -opt_set X_DRIVER_TYPE TMC2209 -opt_set Y_DRIVER_TYPE TMC2209 -opt_set Z_DRIVER_TYPE TMC2209 -opt_set Z2_DRIVER_TYPE TMC2209 -opt_set E0_DRIVER_TYPE TMC2209 -opt_set RESTORE_LEVELING_AFTER_G28 false -opt_set LCD_LANGUAGE it -opt_set NUM_Z_STEPPER_DRIVERS 2 -opt_set HOMING_BUMP_MM "{ 0, 0, 0 }" -opt_set SDCARD_CONNECTION LCD -opt_enable ENDSTOP_INTERRUPTS_FEATURE S_CURVE_ACCELERATION BLTOUCH Z_MIN_PROBE_REPEATABILITY_TEST \ - FILAMENT_RUNOUT_SENSOR G26_MESH_VALIDATION MESH_EDIT_GFX_OVERLAY Z_SAFE_HOMING \ - EEPROM_SETTINGS NOZZLE_PARK_FEATURE SDSUPPORT SD_CHECK_AND_RETRY \ - REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER Z_STEPPER_AUTO_ALIGN ADAPTIVE_STEP_SMOOTHING \ - STATUS_MESSAGE_SCROLLING LCD_SET_PROGRESS_MANUALLY SHOW_REMAINING_TIME USE_M73_REMAINING_TIME \ - LONG_FILENAME_HOST_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 -exec_test $1 $2 "Build Grand Central M4 Default Configuration" - -# clean up -restore_configs diff --git a/buildroot/tests/STM32F070CB_malyan b/buildroot/tests/STM32F070CB_malyan new file mode 100755 index 000000000000..060d707b04e5 --- /dev/null +++ b/buildroot/tests/STM32F070CB_malyan @@ -0,0 +1,14 @@ +#!/usr/bin/env bash +# +# Build tests for STM32F070CB Malyan M200 v2 +# + +# exit on first failure +set -e + +restore_configs +opt_set MOTHERBOARD BOARD_MALYAN_M200_V2 SERIAL_PORT -1 +exec_test $1 $2 "Malyan M200 v2 Default Config" "$3" + +# cleanup +restore_configs diff --git a/buildroot/tests/STM32F070CB_malyan-tests b/buildroot/tests/STM32F070CB_malyan-tests deleted file mode 100644 index 20bd111fa9c0..000000000000 --- a/buildroot/tests/STM32F070CB_malyan-tests +++ /dev/null @@ -1,15 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for STM32F070CB Malyan M200 v2 -# - -# exit on first failure -set -e - -restore_configs -opt_set MOTHERBOARD BOARD_MALYAN_M200_V2 -opt_set SERIAL_PORT -1 -exec_test $1 $2 "Malyan M200 v2 Default Config" - -# cleanup -restore_configs diff --git a/buildroot/tests/STM32F070RB_malyan b/buildroot/tests/STM32F070RB_malyan new file mode 100755 index 000000000000..493dd5fdbd00 --- /dev/null +++ b/buildroot/tests/STM32F070RB_malyan @@ -0,0 +1,15 @@ +#!/usr/bin/env bash +# +# Build tests for STM32F070RB Malyan M200 v2 +# + +# exit on first failure +set -e + +restore_configs +opt_set MOTHERBOARD BOARD_MALYAN_M200_V2 +opt_set SERIAL_PORT -1 +exec_test $1 $2 "Malyan M200 v2 Default Config" "$3" + +# cleanup +restore_configs diff --git a/buildroot/tests/STM32F070RB_malyan-tests b/buildroot/tests/STM32F070RB_malyan-tests deleted file mode 100644 index 58237a70eb5f..000000000000 --- a/buildroot/tests/STM32F070RB_malyan-tests +++ /dev/null @@ -1,15 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for STM32F070RB Malyan M200 v2 -# - -# exit on first failure -set -e - -restore_configs -opt_set MOTHERBOARD BOARD_MALYAN_M200_V2 -opt_set SERIAL_PORT -1 -exec_test $1 $2 "Malyan M200 v2 Default Config" - -# cleanup -restore_configs diff --git a/buildroot/tests/STM32F103CB_malyan b/buildroot/tests/STM32F103CB_malyan new file mode 100755 index 000000000000..6624b6c3c263 --- /dev/null +++ b/buildroot/tests/STM32F103CB_malyan @@ -0,0 +1,13 @@ +#!/usr/bin/env bash +# +# Build tests for STM32F103CB Malyan M200 +# + +# exit on first failure +set -e + +use_example_configs Malyan/M200 +exec_test $1 $2 "Malyan M200" "$3" + +# cleanup +restore_configs diff --git a/buildroot/tests/STM32F103CB_malyan-tests b/buildroot/tests/STM32F103CB_malyan-tests deleted file mode 100644 index e594cb43dbae..000000000000 --- a/buildroot/tests/STM32F103CB_malyan-tests +++ /dev/null @@ -1,13 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for STM32F103CB Malyan M200 -# - -# exit on first failure -set -e - -use_example_configs Malyan/M200 -exec_test $1 $2 "Malyan M200" - -# cleanup -restore_configs diff --git a/buildroot/tests/STM32F103RC_btt b/buildroot/tests/STM32F103RC_btt new file mode 100755 index 000000000000..e76060aee82f --- /dev/null +++ b/buildroot/tests/STM32F103RC_btt @@ -0,0 +1,20 @@ +#!/usr/bin/env bash +# +# Build tests for STM32F103RC BigTreeTech (SKR Mini E3) +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +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" + +# clean up +restore_configs diff --git a/buildroot/tests/STM32F103RC_btt-tests b/buildroot/tests/STM32F103RC_btt-tests deleted file mode 100644 index ad15ee723767..000000000000 --- a/buildroot/tests/STM32F103RC_btt-tests +++ /dev/null @@ -1,28 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for STM32F103RC BigTreeTech (SKR Mini E3) -# - -# exit on first failure -set -e - -# -# Build with the default configurations -# -restore_configs -opt_set MOTHERBOARD BOARD_BTT_SKR_MINI_E3_V1_0 -opt_set SERIAL_PORT 1 -opt_set SERIAL_PORT_2 -1 -opt_set X_DRIVER_TYPE TMC2209 -opt_set Y_DRIVER_TYPE TMC2209 -opt_set Z_DRIVER_TYPE TMC2209 -opt_set E0_DRIVER_TYPE TMC2209 -opt_set X_SLAVE_ADDRESS 0 -opt_set Y_SLAVE_ADDRESS 1 -opt_set Z_SLAVE_ADDRESS 2 -opt_set E0_SLAVE_ADDRESS 3 - -exec_test $1 $2 "BigTreeTech SKR Mini E3 1.0 - Basic Config with TMC2209 HW Serial" - -# clean up -restore_configs diff --git a/buildroot/tests/STM32F103RC_btt_USB b/buildroot/tests/STM32F103RC_btt_USB new file mode 100755 index 000000000000..8381de0ea6e4 --- /dev/null +++ b/buildroot/tests/STM32F103RC_btt_USB @@ -0,0 +1,17 @@ +#!/usr/bin/env bash +# +# Build tests for STM32F103RC BigTreeTech (SKR Mini v1.1) +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +restore_configs +opt_set MOTHERBOARD BOARD_BTT_SKR_MINI_V1_1 SERIAL_PORT 1 SERIAL_PORT_2 -1 +exec_test $1 $2 "BigTreeTech SKR Mini v1.1 - Basic Configuration" "$3" + +# clean up +restore_configs diff --git a/buildroot/tests/STM32F103RC_btt_USB-tests b/buildroot/tests/STM32F103RC_btt_USB-tests deleted file mode 100644 index 8f7fff0b322a..000000000000 --- a/buildroot/tests/STM32F103RC_btt_USB-tests +++ /dev/null @@ -1,19 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for STM32F103RC BigTreeTech (SKR Mini v1.1) -# - -# exit on first failure -set -e - -# -# Build with the default configurations -# -restore_configs -opt_set MOTHERBOARD BOARD_BTT_SKR_MINI_V1_1 -opt_set SERIAL_PORT 1 -opt_set SERIAL_PORT_2 -1 -exec_test $1 $2 "BigTreeTech SKR Mini v1.1 - Basic Configuration" - -# clean up -restore_configs diff --git a/buildroot/tests/STM32F103RC_btt_USB_maple b/buildroot/tests/STM32F103RC_btt_USB_maple new file mode 100755 index 000000000000..eeb460911acb --- /dev/null +++ b/buildroot/tests/STM32F103RC_btt_USB_maple @@ -0,0 +1,17 @@ +#!/usr/bin/env bash +# +# Build tests for STM32F103RC BigTreeTech (SKR Mini v1.1) with LibMaple STM32F1 HAL +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +restore_configs +opt_set MOTHERBOARD BOARD_BTT_SKR_MINI_V1_1 SERIAL_PORT 1 SERIAL_PORT_2 -1 BAUDRATE_2 115200 +exec_test $1 $2 "BigTreeTech SKR Mini v1.1 - Basic Configuration" "$3" + +# clean up +restore_configs diff --git a/buildroot/tests/STM32F103RC_btt_maple b/buildroot/tests/STM32F103RC_btt_maple new file mode 100755 index 000000000000..e74e5902132c --- /dev/null +++ b/buildroot/tests/STM32F103RC_btt_maple @@ -0,0 +1,20 @@ +#!/usr/bin/env bash +# +# Build tests for STM32F103RC BigTreeTech (SKR Mini E3) with LibMaple STM32F1 HAL +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +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" + +# clean up +restore_configs diff --git a/buildroot/tests/STM32F103RC_fysetc-tests b/buildroot/tests/STM32F103RC_fysetc-tests deleted file mode 100644 index dfa85d9bb616..000000000000 --- a/buildroot/tests/STM32F103RC_fysetc-tests +++ /dev/null @@ -1,16 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for STM32F103RC FYSETC -# - -# exit on first failure -set -e - -# -# Build with the default configurations -# -use_example_configs "Creality/Ender-3/FYSETC Cheetah 1.2/base" -exec_test $1 $2 "Cheetah 1.2 Configuration" - -# clean up -restore_configs diff --git a/buildroot/tests/STM32F103RC_fysetc_maple b/buildroot/tests/STM32F103RC_fysetc_maple new file mode 100755 index 000000000000..0e78c731888c --- /dev/null +++ b/buildroot/tests/STM32F103RC_fysetc_maple @@ -0,0 +1,16 @@ +#!/usr/bin/env bash +# +# Build tests for STM32F103RC FYSETC +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +use_example_configs "Creality/Ender-3/FYSETC Cheetah 1.2/base" +exec_test $1 $2 "Cheetah 1.2 Configuration" "$3" + +# clean up +restore_configs diff --git a/buildroot/tests/STM32F103RC_meeb b/buildroot/tests/STM32F103RC_meeb new file mode 100755 index 000000000000..3a191b4e7e2d --- /dev/null +++ b/buildroot/tests/STM32F103RC_meeb @@ -0,0 +1,18 @@ +#!/usr/bin/env bash +# +# Build tests for STM32F103RC MEEB_3DP (ccrobot-online.com) +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +restore_configs +opt_set MOTHERBOARD BOARD_CCROBOT_MEEB_3DP SERIAL_PORT 1 SERIAL_PORT_2 -1 \ + X_DRIVER_TYPE TMC2208 Y_DRIVER_TYPE TMC2208 Z_DRIVER_TYPE TMC2208 E0_DRIVER_TYPE TMC2208 +exec_test $1 $2 "MEEB_3DP - Basic Config with TMC2208 SW Serial" "$3" + +# clean up +restore_configs diff --git a/buildroot/tests/STM32F103RC_meeb-tests b/buildroot/tests/STM32F103RC_meeb-tests deleted file mode 100644 index 74e770d3c895..000000000000 --- a/buildroot/tests/STM32F103RC_meeb-tests +++ /dev/null @@ -1,23 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for STM32F103RC MEEB_3DP (ccrobot-online.com) -# - -# exit on first failure -set -e - -# -# Build with the default configurations -# -restore_configs -opt_set MOTHERBOARD BOARD_CCROBOT_MEEB_3DP -opt_set SERIAL_PORT 1 -opt_set SERIAL_PORT_2 -1 -opt_set X_DRIVER_TYPE TMC2208 -opt_set Y_DRIVER_TYPE TMC2208 -opt_set Z_DRIVER_TYPE TMC2208 -opt_set E0_DRIVER_TYPE TMC2208 -exec_test $1 $2 "MEEB_3DP - Basic Config with TMC2208 SW Serial" - -# clean up -restore_configs diff --git a/buildroot/tests/STM32F103RE b/buildroot/tests/STM32F103RE new file mode 100755 index 000000000000..641f1fa56c80 --- /dev/null +++ b/buildroot/tests/STM32F103RE @@ -0,0 +1,22 @@ +#!/usr/bin/env bash +# +# Build tests for STM32F103RE +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +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 \ + 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" + +# cleanup +restore_configs diff --git a/buildroot/tests/STM32F103RE-tests b/buildroot/tests/STM32F103RE-tests deleted file mode 100755 index 63fe5ba393b8..000000000000 --- a/buildroot/tests/STM32F103RE-tests +++ /dev/null @@ -1,22 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for STM32F103RE -# - -# exit on first failure -set -e - -# -# Build with the default configurations -# -restore_configs -opt_set MOTHERBOARD BOARD_STM32F103RE -opt_set EXTRUDERS 2 -opt_set SERIAL_PORT -1 -opt_enable EEPROM_SETTINGS EEPROM_CHITCHAT REPRAP_DISCOUNT_SMART_CONTROLLER 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" - -# cleanup -restore_configs diff --git a/buildroot/tests/STM32F103RET6_creality b/buildroot/tests/STM32F103RET6_creality new file mode 100755 index 000000000000..4914bbfd70be --- /dev/null +++ b/buildroot/tests/STM32F103RET6_creality @@ -0,0 +1,30 @@ +#!/usr/bin/env bash +# +# Build tests for STM32F103RET6_creality +# + +# exit on first failure +set -e + +# +# Build with configs included in the PR +# +use_example_configs "Creality/Ender-3 V2/CrealityUI" +opt_enable MARLIN_DEV_MODE +exec_test $1 $2 "Ender 3 v2" "$3" + +use_example_configs "Creality/Ender-3 V2/CrealityUI" +opt_disable CLASSIC_JERK +opt_add SDCARD_EEPROM_EMULATION +opt_set TEMP_SENSOR_BED 0 +exec_test $1 $2 "Ender 3 v2, SD EEPROM, no CLASSIC_JERK, no Bed" "$3" + +restore_configs +opt_set MOTHERBOARD BOARD_CREALITY_V452 SERIAL_PORT 1 +opt_disable NOZZLE_TO_PROBE_OFFSET +opt_enable NOZZLE_AS_PROBE Z_SAFE_HOMING Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN \ + PROBE_ACTIVATION_SWITCH PROBE_TARE PROBE_TARE_ONLY_WHILE_INACTIVE +exec_test $1 $2 "Creality V4.5.2 PROBE_ACTIVATION_SWITCH, Probe Tare" "$3" + +# clean up +restore_configs diff --git a/buildroot/tests/STM32F103RET6_creality-tests b/buildroot/tests/STM32F103RET6_creality-tests deleted file mode 100644 index ca723c7aa229..000000000000 --- a/buildroot/tests/STM32F103RET6_creality-tests +++ /dev/null @@ -1,16 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for STM32F103RET6_creality -# - -# exit on first failure -set -e - -# -# Build with configs included in the PR -# -use_example_configs "Creality/Ender-3 V2" -opt_enable MARLIN_DEV_MODE -exec_test $1 $2 "Ender 3 v2" - -restore_configs diff --git a/buildroot/tests/STM32F103RE_btt b/buildroot/tests/STM32F103RE_btt new file mode 100755 index 000000000000..97d7ffec4bdd --- /dev/null +++ b/buildroot/tests/STM32F103RE_btt @@ -0,0 +1,19 @@ +#!/usr/bin/env bash +# +# Build tests for STM32F103RE BigTreeTech (SKR E3 DIP v1.0) +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +restore_configs +opt_set MOTHERBOARD BOARD_BTT_SKR_E3_DIP \ + SERIAL_PORT 1 SERIAL_PORT_2 -1 \ + X_DRIVER_TYPE TMC2209 Y_DRIVER_TYPE TMC2130 +exec_test $1 $2 "BTT SKR E3 DIP 1.0 | Mixed TMC Drivers" "$3" + +# clean up +restore_configs diff --git a/buildroot/tests/STM32F103RE_btt-tests b/buildroot/tests/STM32F103RE_btt-tests deleted file mode 100644 index 9a829a553efe..000000000000 --- a/buildroot/tests/STM32F103RE_btt-tests +++ /dev/null @@ -1,21 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for STM32F103RE BigTreeTech (SKR E3 DIP v1.0) -# - -# exit on first failure -set -e - -# -# Build with the default configurations -# -restore_configs -opt_set MOTHERBOARD BOARD_BTT_SKR_E3_DIP -opt_set SERIAL_PORT 1 -opt_set SERIAL_PORT_2 -1 -opt_set X_DRIVER_TYPE TMC2209 -opt_set Y_DRIVER_TYPE TMC2130 -exec_test $1 $2 "BigTreeTech SKR E3 DIP v1.0 - Basic Config with mixed TMC Drivers" - -# clean up -restore_configs diff --git a/buildroot/tests/STM32F103RE_btt_USB b/buildroot/tests/STM32F103RE_btt_USB new file mode 100755 index 000000000000..c63a90e43681 --- /dev/null +++ b/buildroot/tests/STM32F103RE_btt_USB @@ -0,0 +1,26 @@ +#!/usr/bin/env bash +# +# Build tests for STM32F103RE BigTreeTech (SKR E3 DIP v1.0) +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +restore_configs +opt_set MOTHERBOARD BOARD_BTT_SKR_E3_DIP SERIAL_PORT 1 SERIAL_PORT_2 -1 +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 \ + 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 +opt_disable NOZZLE_TO_PROBE_OFFSET +exec_test $1 $2 "BigTreeTech SKR CR6 PROBE_ACTIVATION_SWITCH, Probe Tare" "$3" + +# clean up +restore_configs diff --git a/buildroot/tests/STM32F103RE_btt_USB-tests b/buildroot/tests/STM32F103RE_btt_USB-tests deleted file mode 100644 index 77751d776e9c..000000000000 --- a/buildroot/tests/STM32F103RE_btt_USB-tests +++ /dev/null @@ -1,19 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for STM32F103RE BigTreeTech (SKR E3 DIP v1.0) -# - -# exit on first failure -set -e - -# -# Build with the default configurations -# -restore_configs -opt_set MOTHERBOARD BOARD_BTT_SKR_E3_DIP -opt_set SERIAL_PORT 1 -opt_set SERIAL_PORT_2 -1 -exec_test $1 $2 "BigTreeTech SKR E3 DIP v1.0 - Basic Configuration" - -# clean up -restore_configs diff --git a/buildroot/tests/STM32F103VE_ZM3E4V2_USB_maple b/buildroot/tests/STM32F103VE_ZM3E4V2_USB_maple new file mode 100755 index 000000000000..8cbb84fb807d --- /dev/null +++ b/buildroot/tests/STM32F103VE_ZM3E4V2_USB_maple @@ -0,0 +1,14 @@ +#!/usr/bin/env bash +# +# Build tests for STM32F103VE_ZM3E4V2_USB +# + +# exit on first failure +set -e + +restore_configs +opt_set MOTHERBOARD BOARD_ZONESTAR_ZM3E4V2 SERIAL_PORT 1 +exec_test $1 $2 "Zonestar ZM3E4 V2.0" "$3" + +# cleanup +restore_configs diff --git a/buildroot/tests/STM32F103VE_longer b/buildroot/tests/STM32F103VE_longer new file mode 100755 index 000000000000..1c90744c0110 --- /dev/null +++ b/buildroot/tests/STM32F103VE_longer @@ -0,0 +1,23 @@ +#!/usr/bin/env bash +# +# Build tests for STM32F103VET6 +# + +# exit on first failure +set -e + +use_example_configs Alfawise/U20 +opt_enable BAUD_RATE_GCODE +exec_test $1 $2 "CLASSIC_UI U20 config" "$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 "COLOR_UI U20 config" "$3" + +use_example_configs Alfawise/U20-bltouch +opt_enable BAUD_RATE_GCODE +exec_test $1 $2 "BLTouch U20 config" + +# cleanup +restore_configs diff --git a/buildroot/tests/STM32F103VE_longer-tests b/buildroot/tests/STM32F103VE_longer-tests deleted file mode 100755 index 85b22c1284dd..000000000000 --- a/buildroot/tests/STM32F103VE_longer-tests +++ /dev/null @@ -1,16 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for STM32F103VET6 -# - -# exit on first failure -set -e - -use_example_configs Alfawise/U20 -opt_set MOTHERBOARD BOARD_LONGER3D_LK -opt_set SERIAL_PORT 1 -opt_enable BAUD_RATE_GCODE -exec_test $1 $2 "Full-featured U20 config" - -# cleanup -restore_configs diff --git a/buildroot/tests/STM32F103VE_longer_maple b/buildroot/tests/STM32F103VE_longer_maple new file mode 100755 index 000000000000..4570a3214d17 --- /dev/null +++ b/buildroot/tests/STM32F103VE_longer_maple @@ -0,0 +1,23 @@ +#!/usr/bin/env bash +# +# Build tests for STM32F103VET6 (using maple STM32F1 framework) +# + +# exit on first failure +set -e + +use_example_configs Alfawise/U20 +opt_enable BAUD_RATE_GCODE +exec_test $1 $2 "maple CLASSIC_UI U20 config" "$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" + +use_example_configs Alfawise/U20-bltouch +opt_enable BAUD_RATE_GCODE +exec_test $1 $2 "maple BLTouch U20 config" + +# cleanup +restore_configs diff --git a/buildroot/tests/STM32F4-tests b/buildroot/tests/STM32F4-tests deleted file mode 100644 index b5beb7366377..000000000000 --- a/buildroot/tests/STM32F4-tests +++ /dev/null @@ -1,16 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for STM32F4 disco_f407vg -# - -# exit on first failure -set -e - -# -# Build with the default configurations -# -use_example_configs STM32/STM32F4 -exec_test $1 $2 "STM32F4 Default Configuration" - -# clean up -restore_configs diff --git a/buildroot/tests/STM32F401VE_STEVAL b/buildroot/tests/STM32F401VE_STEVAL new file mode 100755 index 000000000000..1704f3d2f004 --- /dev/null +++ b/buildroot/tests/STM32F401VE_STEVAL @@ -0,0 +1,15 @@ +#!/usr/bin/env bash +# +# Build tests for STM32F401VE_STEVAL +# + +# exit on first failure +set -e + +# Build examples +restore_configs +opt_set MOTHERBOARD BOARD_STEVAL_3DP001V1 SERIAL_PORT -1 +exec_test $1 $2 "STM32F401VE_STEVAL Default Config" "$3" + +# cleanup +restore_configs diff --git a/buildroot/tests/STM32F401VE_STEVAL-tests b/buildroot/tests/STM32F401VE_STEVAL-tests deleted file mode 100644 index 2811014c13b2..000000000000 --- a/buildroot/tests/STM32F401VE_STEVAL-tests +++ /dev/null @@ -1,16 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for STM32F401VE_STEVAL -# - -# exit on first failure -set -e - -# Build examples -restore_configs -opt_set MOTHERBOARD BOARD_STEVAL_3DP001V1 -opt_set SERIAL_PORT -1 -exec_test $1 $2 "STM32F401VE_STEVAL Default Config" - -# cleanup -restore_configs diff --git a/buildroot/tests/STM32F407VE_black b/buildroot/tests/STM32F407VE_black new file mode 100755 index 000000000000..6b7a3cfe7c67 --- /dev/null +++ b/buildroot/tests/STM32F407VE_black @@ -0,0 +1,15 @@ +#!/usr/bin/env bash +# +# Build tests for STM32F407VET6 +# + +# exit on first failure +set -e + +restore_configs +use_example_configs STM32/Black_STM32F407VET6 +opt_enable BAUD_RATE_GCODE +exec_test $1 $2 "Full-featured Sample Black STM32F407VET6 config" "$3" + +# cleanup +restore_configs diff --git a/buildroot/tests/STM32F407VE_black-tests b/buildroot/tests/STM32F407VE_black-tests deleted file mode 100755 index 908382ec2a04..000000000000 --- a/buildroot/tests/STM32F407VE_black-tests +++ /dev/null @@ -1,15 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for STM32F407VET6 -# - -# exit on first failure -set -e - -restore_configs -use_example_configs STM32/Black_STM32F407VET6 -opt_enable BAUD_RATE_GCODE -exec_test $1 $2 "Full-featured Sample Black STM32F407VET6 config" - -# cleanup -restore_configs diff --git a/buildroot/tests/STM32F7-tests b/buildroot/tests/STM32F7-tests deleted file mode 100644 index 281222f15634..000000000000 --- a/buildroot/tests/STM32F7-tests +++ /dev/null @@ -1,18 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for STM32F7 -# - -# exit on first failure -set -e - -# -# Build with the default configurations -# -restore_configs -opt_set MOTHERBOARD BOARD_REMRAM_V1 -opt_set SERIAL_PORT 1 -exec_test $1 $2 "Default Configuration" - -# clean up -restore_configs diff --git a/buildroot/tests/at90usb1286_cdc b/buildroot/tests/at90usb1286_cdc new file mode 100755 index 000000000000..01d752db8b4c --- /dev/null +++ b/buildroot/tests/at90usb1286_cdc @@ -0,0 +1,17 @@ +#!/usr/bin/env bash +# +# Build tests for AT90USB1286 ARMED +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +restore_configs +opt_set MOTHERBOARD BOARD_BRAINWAVE_PRO +exec_test $1 $2 "Default Configuration" "$3" + +# clean up +restore_configs diff --git a/buildroot/tests/at90usb1286_cdc-tests b/buildroot/tests/at90usb1286_cdc-tests deleted file mode 100644 index 812e2ebcae32..000000000000 --- a/buildroot/tests/at90usb1286_cdc-tests +++ /dev/null @@ -1,17 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for AT90USB1286 ARMED -# - -# exit on first failure -set -e - -# -# Build with the default configurations -# -restore_configs -opt_set MOTHERBOARD BOARD_BRAINWAVE_PRO -exec_test $1 $2 "Default Configuration" - -# clean up -restore_configs diff --git a/buildroot/tests/at90usb1286_dfu b/buildroot/tests/at90usb1286_dfu new file mode 100755 index 000000000000..75672a6a5150 --- /dev/null +++ b/buildroot/tests/at90usb1286_dfu @@ -0,0 +1,22 @@ +#!/usr/bin/env bash +# +# Build tests for AT90USB1286 ARMED +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +restore_configs +opt_set MOTHERBOARD BOARD_PRINTRBOARD +exec_test $1 $2 "Printrboard Configuration" "$3" + +restore_configs +opt_set MOTHERBOARD BOARD_PRINTRBOARD_REVF +opt_enable MINIPANEL +exec_test $1 $2 "Printrboard RevF with MiniPanel and Stepper DAC (in pins file)" "$3" + +# clean up +restore_configs diff --git a/buildroot/tests/at90usb1286_dfu-tests b/buildroot/tests/at90usb1286_dfu-tests deleted file mode 100644 index 7571994ec47e..000000000000 --- a/buildroot/tests/at90usb1286_dfu-tests +++ /dev/null @@ -1,17 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for AT90USB1286 ARMED -# - -# exit on first failure -set -e - -# -# Build with the default configurations -# -restore_configs -opt_set MOTHERBOARD BOARD_PRINTRBOARD -exec_test $1 $2 "Default Configuration" - -# clean up -restore_configs diff --git a/buildroot/tests/chitu_f103 b/buildroot/tests/chitu_f103 new file mode 100755 index 000000000000..139c480e3e85 --- /dev/null +++ b/buildroot/tests/chitu_f103 @@ -0,0 +1,16 @@ +#!/usr/bin/env bash +# +# Build tests for chitu_f103 (STM32F103ZE) +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +use_example_configs Tronxy/X5SA +exec_test $1 $2 "Tronxy/X5SA" "$3" + +# clean up +restore_configs diff --git a/buildroot/tests/esp32 b/buildroot/tests/esp32 new file mode 100755 index 000000000000..a0f79107cf2f --- /dev/null +++ b/buildroot/tests/esp32 @@ -0,0 +1,30 @@ +#!/usr/bin/env bash +# +# Build tests for ESP32 +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +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" + +# +# Build with TMC drivers using hardware serial +# +restore_configs +opt_set MOTHERBOARD BOARD_ESPRESSIF_ESP32 \ + X_DRIVER_TYPE TMC2209 Y_DRIVER_TYPE TMC2208 Z_DRIVER_TYPE TMC2209 E0_DRIVER_TYPE TMC2209 \ + X_HARDWARE_SERIAL Serial1 Y_HARDWARE_SERIAL Serial1 Z_HARDWARE_SERIAL Serial1 E0_HARDWARE_SERIAL Serial1 \ + X_SLAVE_ADDRESS 0 Y_SLAVE_ADDRESS 1 Z_SLAVE_ADDRESS 2 E0_SLAVE_ADDRESS 3 +opt_enable HOTEND_IDLE_TIMEOUT SOFTWARE_DRIVER_ENABLE +exec_test $1 $2 "ESP32, TMC HW Serial, Hotend Idle" "$3" + +# cleanup +restore_configs diff --git a/buildroot/tests/esp32-tests b/buildroot/tests/esp32-tests deleted file mode 100755 index 204e7aa708eb..000000000000 --- a/buildroot/tests/esp32-tests +++ /dev/null @@ -1,41 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for ESP32 -# - -# exit on first failure -set -e - -# -# Build with the default configurations -# -restore_configs -opt_set MOTHERBOARD BOARD_ESPRESSIF_ESP32 -opt_enable WIFISUPPORT WEBSUPPORT GCODE_MACROS BAUD_RATE_GCODE M115_GEOMETRY_REPORT REPETIER_GCODE_M360 -opt_add WIFI_SSID "\"ssid\"" -opt_add WIFI_PWD "\"password\"" -opt_set TX_BUFFER_SIZE 64 -exec_test $1 $2 "ESP32 with WIFISUPPORT and WEBSUPPORT" - -# -# Build with TMC drivers using hardware serial -# -restore_configs -opt_set MOTHERBOARD BOARD_ESPRESSIF_ESP32 -opt_set X_DRIVER_TYPE TMC2209 -opt_set Y_DRIVER_TYPE TMC2208 -opt_set Z_DRIVER_TYPE TMC2209 -opt_set E0_DRIVER_TYPE TMC2209 -opt_set X_HARDWARE_SERIAL Serial1 -opt_set Y_HARDWARE_SERIAL Serial1 -opt_set Z_HARDWARE_SERIAL Serial1 -opt_set E0_HARDWARE_SERIAL Serial1 -opt_set X_SLAVE_ADDRESS 0 -opt_set Y_SLAVE_ADDRESS 1 -opt_set Z_SLAVE_ADDRESS 2 -opt_set E0_SLAVE_ADDRESS 3 -opt_enable HOTEND_IDLE_TIMEOUT -exec_test $1 $2 "ESP32, TMC HW Serial, Hotend Idle" - -# cleanup -restore_configs diff --git a/buildroot/tests/jgaurora_a5s_a1-tests b/buildroot/tests/jgaurora_a5s_a1-tests deleted file mode 100644 index c6cc9e3f9c9e..000000000000 --- a/buildroot/tests/jgaurora_a5s_a1-tests +++ /dev/null @@ -1,16 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for STM32F103ZE JGAurora A5S A1 -# - -# exit on first failure -set -e - -# -# Build with the default configurations -# -use_example_configs JGAurora/A5S -exec_test $1 $2 "JGAurora/A5S Configuration" - -# clean up -restore_configs diff --git a/buildroot/tests/jgaurora_a5s_a1_maple b/buildroot/tests/jgaurora_a5s_a1_maple new file mode 100755 index 000000000000..e9be89eb30b8 --- /dev/null +++ b/buildroot/tests/jgaurora_a5s_a1_maple @@ -0,0 +1,16 @@ +#!/usr/bin/env bash +# +# Build tests for STM32F103ZE JGAurora A5S A1 +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +use_example_configs JGAurora/A5S +exec_test $1 $2 "JGAurora/A5S Configuration" "$3" + +# clean up +restore_configs diff --git a/buildroot/tests/linux_native b/buildroot/tests/linux_native new file mode 100755 index 000000000000..0153687eacb7 --- /dev/null +++ b/buildroot/tests/linux_native @@ -0,0 +1,18 @@ +#!/usr/bin/env bash +# +# Build tests for Linux x86_64 +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +restore_configs +opt_set MOTHERBOARD BOARD_LINUX_RAMPS TEMP_SENSOR_BED 1 +opt_enable PIDTEMPBED EEPROM_SETTINGS BAUD_RATE_GCODE +exec_test $1 $2 "Linux with EEPROM" "$3" + +# cleanup +restore_configs diff --git a/buildroot/tests/linux_native-tests b/buildroot/tests/linux_native-tests deleted file mode 100755 index 38f531dadc4d..000000000000 --- a/buildroot/tests/linux_native-tests +++ /dev/null @@ -1,19 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for Linux x86_64 -# - -# exit on first failure -set -e - -# -# Build with the default configurations -# -restore_configs -opt_set MOTHERBOARD BOARD_LINUX_RAMPS -opt_set TEMP_SENSOR_BED 1 -opt_enable PIDTEMPBED EEPROM_SETTINGS BAUD_RATE_GCODE -exec_test $1 $2 "Linux with EEPROM" - -# cleanup -restore_configs diff --git a/buildroot/tests/malyan_M300 b/buildroot/tests/malyan_M300 new file mode 100755 index 000000000000..27bdcfb05901 --- /dev/null +++ b/buildroot/tests/malyan_M300 @@ -0,0 +1,16 @@ +#!/usr/bin/env bash +# +# Build tests for STM32F070CB Malyan M300 +# + +# exit on first failure +set -e + +restore_configs +use_example_configs "delta/Malyan M300" +opt_disable AUTO_BED_LEVELING_3POINT +opt_set LCD_SERIAL_PORT 1 +exec_test $1 $2 "Malyan M300 (delta)" "$3" + +# cleanup +restore_configs diff --git a/buildroot/tests/malyan_M300-tests b/buildroot/tests/malyan_M300-tests deleted file mode 100755 index 1955accaa5f6..000000000000 --- a/buildroot/tests/malyan_M300-tests +++ /dev/null @@ -1,16 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for STM32F070CB Malyan M300 -# - -# exit on first failure -set -e - -restore_configs -use_example_configs "delta/Malyan M300" -opt_disable AUTO_BED_LEVELING_3POINT -opt_set LCD_SERIAL_PORT 1 -exec_test $1 $2 "Malyan M300 (delta)" - -# cleanup -restore_configs diff --git a/buildroot/tests/mega1280 b/buildroot/tests/mega1280 new file mode 100755 index 000000000000..d8cefbaf8145 --- /dev/null +++ b/buildroot/tests/mega1280 @@ -0,0 +1,57 @@ +#!/usr/bin/env bash +# +# Build tests for AVR ATmega1280 +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +#restore_configs +#exec_test $1 $2 "Default Configuration" "$3" + +# +# Test MESH_BED_LEVELING feature, with LCD +# +restore_configs +opt_set LCD_LANGUAGE an \ + POWER_MONITOR_CURRENT_PIN 14 POWER_MONITOR_VOLTAGE_PIN 15 \ + CLOSED_LOOP_ENABLE_PIN 44 CLOSED_LOOP_MOVE_COMPLETE_PIN 45 +opt_enable SPINDLE_FEATURE ULTIMAKERCONTROLLER LCD_BED_LEVELING \ + EEPROM_SETTINGS EEPROM_BOOT_SILENT EEPROM_AUTO_INIT \ + SENSORLESS_BACKOFF_MM HOMING_BACKOFF_POST_MM HOME_Y_BEFORE_X CODEPENDENT_XY_HOMING \ + MESH_BED_LEVELING ENABLE_LEVELING_FADE_HEIGHT MESH_G28_REST_ORIGIN \ + G26_MESH_VALIDATION MESH_EDIT_MENU GCODE_QUOTED_STRINGS \ + EXTERNAL_CLOSED_LOOP_CONTROLLER POWER_MONITOR_CURRENT POWER_MONITOR_VOLTAGE +exec_test $1 $2 "Spindle, MESH_BED_LEVELING, closed loop, Power Monitor, and LCD" "$3" + +# +# Test DUAL_X_CARRIAGE +# +restore_configs +opt_set MOTHERBOARD BOARD_ZRIB_V52 \ + LCD_LANGUAGE pt REPRAPWORLD_KEYPAD_MOVE_STEP 10.0 \ + EXTRUDERS 2 TEMP_SENSOR_1 1 +opt_enable USE_XMAX_PLUG DUAL_X_CARRIAGE REPRAPWORLD_KEYPAD +exec_test $1 $2 "ZRIB_V52 | DUAL_X_CARRIAGE" "$3" + +# +# Delta Config (generic) + Probeless +# +use_example_configs delta/generic +opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER DELTA_AUTO_CALIBRATION DELTA_CALIBRATION_MENU +exec_test $1 $2 "RAMPS | DELTA | RRD LCD | DELTA_AUTO_CALIBRATION | DELTA_CALIBRATION_MENU" "$3" + +# +# Delta Config (generic) + ABL bilinear + BLTOUCH +use_example_configs delta/generic +opt_set LCD_LANGUAGE cz \ + Z_MIN_PROBE_ENDSTOP_INVERTING false \ + Z_MIN_ENDSTOP_INVERTING false +opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER DELTA_CALIBRATION_MENU AUTO_BED_LEVELING_BILINEAR BLTOUCH +exec_test $1 $2 "DELTA | RRD LCD | ABL Bilinear | BLTOUCH" "$3" + +# clean up +restore_configs diff --git a/buildroot/tests/mega1280-tests b/buildroot/tests/mega1280-tests deleted file mode 100644 index ce13d4a6e8bb..000000000000 --- a/buildroot/tests/mega1280-tests +++ /dev/null @@ -1,59 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for AVR ATmega1280 -# - -# exit on first failure -set -e - -# -# Build with the default configurations -# -#restore_configs -#exec_test $1 $2 "Default Configuration" - -# -# Test MESH_BED_LEVELING feature, with LCD -# -restore_configs -opt_set LCD_LANGUAGE an -opt_enable SPINDLE_FEATURE ULTIMAKERCONTROLLER LCD_BED_LEVELING \ - EEPROM_SETTINGS EEPROM_BOOT_SILENT EEPROM_AUTO_INIT \ - SENSORLESS_BACKOFF_MM HOMING_BACKOFF_POST_MM HOME_Y_BEFORE_X CODEPENDENT_XY_HOMING \ - MESH_BED_LEVELING ENABLE_LEVELING_FADE_HEIGHT MESH_G28_REST_ORIGIN \ - G26_MESH_VALIDATION MESH_EDIT_MENU GCODE_QUOTED_STRINGS \ - EXTERNAL_CLOSED_LOOP_CONTROLLER POWER_MONITOR_CURRENT POWER_MONITOR_VOLTAGE -opt_set POWER_MONITOR_CURRENT_PIN 14 -opt_set POWER_MONITOR_VOLTAGE_PIN 15 -opt_set CLOSED_LOOP_ENABLE_PIN 44 -opt_set CLOSED_LOOP_MOVE_COMPLETE_PIN 45 -exec_test $1 $2 "Spindle, MESH_BED_LEVELING, closed loop, Power Monitor, and LCD" - -# -# Test DUAL_X_CARRIAGE -# -restore_configs -opt_set MOTHERBOARD BOARD_TT_OSCAR -opt_set LCD_LANGUAGE pt -opt_set EXTRUDERS 2 -opt_set TEMP_SENSOR_1 1 -opt_enable USE_XMAX_PLUG DUAL_X_CARRIAGE REPRAPWORLD_KEYPAD -opt_set REPRAPWORLD_KEYPAD_MOVE_STEP 10.0 -exec_test $1 $2 "TT Oscar | DUAL_X_CARRIAGE" - -# -# Delta Config (generic) + Probeless -# -use_example_configs delta/generic -opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER DELTA_AUTO_CALIBRATION DELTA_CALIBRATION_MENU -exec_test $1 $2 "RAMPS | DELTA | RRD LCD | DELTA_AUTO_CALIBRATION | DELTA_CALIBRATION_MENU" - -# -# Delta Config (generic) + ABL bilinear + BLTOUCH -use_example_configs delta/generic -opt_set LCD_LANGUAGE cz -opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER DELTA_CALIBRATION_MENU AUTO_BED_LEVELING_BILINEAR BLTOUCH -exec_test $1 $2 "DELTA | RRD LCD | ABL Bilinear | BLTOUCH" - -# clean up -restore_configs diff --git a/buildroot/tests/mega2560 b/buildroot/tests/mega2560 new file mode 100755 index 000000000000..d757a6c96fad --- /dev/null +++ b/buildroot/tests/mega2560 @@ -0,0 +1,239 @@ +#!/usr/bin/env bash +# +# Build tests for AVR ATmega2560 +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +#restore_configs +#exec_test $1 $2 "Default Configuration" "$3" + +# +# Test a probeless build of AUTO_BED_LEVELING_UBL, with lots of extruders +# +use_example_configs AnimationExample +opt_set MOTHERBOARD BOARD_AZTEEG_X3_PRO LCD_LANGUAGE fr SAVED_POSITIONS 4 DEFAULT_EJERK 10 \ + EXTRUDERS 5 TEMP_SENSOR_1 1 TEMP_SENSOR_2 5 TEMP_SENSOR_3 20 TEMP_SENSOR_4 1000 TEMP_SENSOR_BED 1 +opt_enable AUTO_BED_LEVELING_UBL RESTORE_LEVELING_AFTER_G28 DEBUG_LEVELING_FEATURE G26_MESH_VALIDATION ENABLE_LEVELING_FADE_HEIGHT SKEW_CORRECTION \ + 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 EXTRA_LIN_ADVANCE_K QUICK_HOME \ + LCD_SET_PROGRESS_MANUALLY PRINT_PROGRESS_SHOW_DECIMALS SHOW_REMAINING_TIME \ + BABYSTEPPING BABYSTEP_XY NANODLP_Z_SYNC I2C_POSITION_ENCODERS M114_DETAIL +exec_test $1 $2 "Azteeg X3 Pro | EXTRUDERS 5 | RRDFGSC | UBL | LIN_ADVANCE ..." "$3" + +# +# Add a Sled Z Probe, use UBL Cartesian moves, use Japanese language +# +use_example_configs AnimationExample +opt_set MOTHERBOARD BOARD_AZTEEG_X3_PRO LCD_LANGUAGE jp_kana DEFAULT_EJERK 10 \ + EXTRUDERS 5 TEMP_SENSOR_1 1 TEMP_SENSOR_2 5 TEMP_SENSOR_3 20 TEMP_SENSOR_4 1000 TEMP_SENSOR_BED 1 +opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER LIGHTWEIGHT_UI SHOW_CUSTOM_BOOTSCREEN BOOT_MARLIN_LOGO_SMALL \ + LCD_SET_PROGRESS_MANUALLY PRINT_PROGRESS_SHOW_DECIMALS SHOW_REMAINING_TIME STATUS_MESSAGE_SCROLLING SCROLL_LONG_FILENAMES \ + SDSUPPORT SDCARD_SORT_ALPHA NO_SD_AUTOSTART USB_FLASH_DRIVE_SUPPORT CANCEL_OBJECTS \ + Z_PROBE_SLED AUTO_BED_LEVELING_UBL UBL_HILBERT_CURVE RESTORE_LEVELING_AFTER_G28 DEBUG_LEVELING_FEATURE G26_MESH_VALIDATION ENABLE_LEVELING_FADE_HEIGHT \ + EEPROM_SETTINGS EEPROM_CHITCHAT GCODE_MACROS CUSTOM_MENU_MAIN \ + MULTI_NOZZLE_DUPLICATION CLASSIC_JERK LIN_ADVANCE QUICK_HOME \ + NANODLP_Z_SYNC I2C_POSITION_ENCODERS M114_DETAIL \ + SKEW_CORRECTION SKEW_CORRECTION_FOR_Z SKEW_CORRECTION_GCODE \ + BABYSTEPPING BABYSTEP_XY BABYSTEP_ZPROBE_OFFSET DOUBLECLICK_FOR_Z_BABYSTEPPING BABYSTEP_HOTEND_Z_OFFSET BABYSTEP_DISPLAY_TOTAL +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 \ + FIL_RUNOUT3_STATE HIGH +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 \ + EEPROM_SETTINGS EEPROM_CHITCHAT M114_DETAIL AUTO_REPORT_POSITION \ + 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" + + +# +# Mixing Extruder with 5 steppers, Greek +# +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 \ + 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 +opt_disable DISABLE_INACTIVE_EXTRUDER +exec_test $1 $2 "Azteeg X3 | Mixing Extruder (x5) | Gradient Mix | Greek" "$3" + +# +# Test SPEAKER with BOARD_BQ_ZUM_MEGA_3D and BQ_LCD_SMART_CONTROLLER +# +#restore_configs +#opt_set MOTHERBOARD BOARD_BQ_ZUM_MEGA_3D \ +# LCD_FEEDBACK_FREQUENCY_DURATION_MS 10 LCD_FEEDBACK_FREQUENCY_HZ 100 +#opt_enable BQ_LCD_SMART_CONTROLLER SPEAKER + +# +# Enable COREXY +# +#restore_configs +#opt_enable COREXY +#exec_test $1 $2 "Stuff" "$3" + +######## Other Standard LCD/Panels ############## +# +# ULTRA_LCD +# +#restore_configs +#opt_enable ULTRA_LCD +#exec_test $1 $2 "Stuff" "$3" +# +# DOGLCD +# +#restore_configs +#opt_enable DOGLCD +#exec_test $1 $2 "Stuff" "$3" +# +# MAKRPANEL +# Needs to use Melzi and Sanguino hardware +# +#restore_configs +#opt_enable MAKRPANEL +#exec_test $1 $2 "Stuff" "$3" +# +# REPRAP_DISCOUNT_SMART_CONTROLLER, SDSUPPORT, BABYSTEPPING, RIGIDBOARD_V2, and DAC_MOTOR_CURRENT_DEFAULT +# +#restore_configs +#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 +#opt_enable G3D_PANEL SDSUPPORT SDCARD_SORT_ALPHA STATUS_MESSAGE_SCROLLING SCROLL_LONG_FILENAMES +#opt_set SDSORT_GCODE true SDSORT_USES_RAM true SDSORT_USES_STACK true SDSORT_CACHE_NAMES true +#exec_test $1 $2 "Stuff" "$3" +# +# REPRAPWORLD_KEYPAD +# +# Can't find configuration details to get it to compile +#restore_configs +#opt_enable ULTRA_LCD REPRAPWORLD_KEYPAD REPRAPWORLD_KEYPAD_MOVE_STEP +#exec_test $1 $2 "Stuff" "$3" +# +# RA_CONTROL_PANEL +# +#restore_configs +#opt_enable RA_CONTROL_PANEL PINS_DEBUGGING +#exec_test $1 $2 "Stuff" "$3" + +######## I2C LCD/PANELS ############## +# +# !!!ATTENTION!!! +# Most I2C configurations are failing at the moment because they require +# a different Liquid Crystal library "LiquidTWI2". +# +# LCD_SAINSMART_I2C_1602 +# +#restore_configs +#opt_enable LCD_SAINSMART_I2C_1602 +#exec_test $1 $2 "Stuff" "$3" +# +# LCD_I2C_PANELOLU2 +# +#restore_configs +#opt_enable LCD_I2C_PANELOLU2 +#exec_test $1 $2 "Stuff" "$3" +# +# LCD_I2C_VIKI +# +#restore_configs +#opt_enable LCD_I2C_VIKI +#exec_test $1 $2 "Stuff" "$3" +# +# LCM1602 +# +#restore_configs +#opt_enable LCM1602 +#exec_test $1 $2 "Stuff" "$3" + +# +# 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 }' \ + DEFAULT_MAX_FEEDRATE '{ 300, 300, 5 }' \ + DEFAULT_MAX_ACCELERATION '{ 3000, 3000, 100 }' \ + MANUAL_FEEDRATE '{ 50*60, 50*60, 4*60 }' \ + AXIS_RELATIVE_MODES '{ false, false, false }' +opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER SDSUPPORT EEPROM_SETTINGS EEPROM_BOOT_SILENT EEPROM_AUTO_INIT \ + LASER_FEATURE AIR_EVACUATION AIR_EVACUATION_PIN AIR_ASSIST AIR_ASSIST_PIN LASER_COOLANT_FLOW_METER MEATPACK_ON_SERIAL_PORT_1 + +exec_test $1 $2 "REPRAP MEGA2560 RAMPS | Laser Feature | Air Evacuation | Air Assist | Cooler | Flowmeter | 12864 LCD | meatpack | SERIAL_PORT_2 " "$3" + +# +# 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 }' \ + DEFAULT_MAX_FEEDRATE '{ 300, 300, 5 }' \ + DEFAULT_MAX_ACCELERATION '{ 3000, 3000, 100 }' \ + MANUAL_FEEDRATE '{ 50*60, 50*60, 4*60 }' \ + AXIS_RELATIVE_MODES '{ false, false, false }' +opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT EEPROM_SETTINGS EEPROM_BOOT_SILENT EEPROM_AUTO_INIT \ + LASER_FEATURE AIR_EVACUATION AIR_EVACUATION_PIN AIR_ASSIST AIR_ASSIST_PIN LASER_COOLANT_FLOW_METER I2C_AMMETER + +exec_test $1 $2 "REPRAP MEGA2560 RAMPS | Laser Feature | Air Evacuation | Air Assist | Cooler | Flowmeter | 44780 LCD " "$3" + +# +# Language files test with REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER +# +#restore_configs +#opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER SDSUPPORT +#for lang in an bg ca cz da de el el_gr en es eu fi fr gl hr hu it jp_kana nl pl pt pt_br ro ru sk sv tr uk vi zh_CN zh_TW test; do opt_set LCD_LANGUAGE $lang; echo "compile with language $lang ..."; exec_test $1 $2 "Stuff" "$3"; done +# +#restore_configs +#opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT +#for lang in an bg ca cz da de el el_gr en es eu fi fr gl hr hu it jp_kana nl pl pt pt_br ro ru sk sv tr uk vi zh_CN zh_TW test; do opt_set LCD_LANGUAGE $lang; echo "compile with language $lang ..."; exec_test $1 $2 "Stuff" "$3"; done + +######## Example Configurations ############## +# +# Test a basic DUAL_X_CARRIAGE configuration +# +use_example_configs Formbot/T_Rex_3 +exec_test $1 $2 "Formbot/T_Rex_3 example configuration." "$3" + +# +# BQ Hephestos 2 +#restore_configs +#use_example_configs BQ/Hephestos_2 +#exec_test $1 $2 "Stuff" "$3" + +# +# Makibox Config need to check board type for Teensy++ 2.0 +# +#use_example_configs makibox +#exec_test $1 $2 "Stuff" "$3" + +# +# tvrrug Config need to check board type for sanguino atmega644p +# +#use_example_configs tvrrug/Round2 +#exec_test $1 $2 "Stuff" "$3" + +# clean up +restore_configs diff --git a/buildroot/tests/mega2560-tests b/buildroot/tests/mega2560-tests deleted file mode 100755 index d3fd5c0192b9..000000000000 --- a/buildroot/tests/mega2560-tests +++ /dev/null @@ -1,327 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for AVR ATmega2560 -# - -# exit on first failure -set -e - -# -# Build with the default configurations -# -#restore_configs -#exec_test $1 $2 "Default Configuration" - -# -# Test a probeless build of AUTO_BED_LEVELING_UBL, with lots of extruders -# -use_example_configs AnimationExample -opt_set SHOW_CUSTOM_BOOTSCREEN -opt_set MOTHERBOARD BOARD_AZTEEG_X3_PRO -opt_set LCD_LANGUAGE fr -opt_set EXTRUDERS 5 -opt_set TEMP_SENSOR_1 1 -opt_set TEMP_SENSOR_2 5 -opt_set TEMP_SENSOR_3 20 -opt_set TEMP_SENSOR_4 1000 -opt_set TEMP_SENSOR_BED 1 -opt_enable AUTO_BED_LEVELING_UBL RESTORE_LEVELING_AFTER_G28 DEBUG_LEVELING_FEATURE G26_MESH_VALIDATION ENABLE_LEVELING_FADE_HEIGHT SKEW_CORRECTION \ - REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER LIGHTWEIGHT_UI STATUS_MESSAGE_SCROLLING BOOT_MARLIN_LOGO_SMALL \ - SDSUPPORT SDCARD_SORT_ALPHA USB_FLASH_DRIVE_SUPPORT SCROLL_LONG_FILENAMES CANCEL_OBJECTS \ - EEPROM_SETTINGS EEPROM_CHITCHAT GCODE_MACROS CUSTOM_USER_MENUS \ - MULTI_NOZZLE_DUPLICATION CLASSIC_JERK LIN_ADVANCE EXTRA_LIN_ADVANCE_K QUICK_HOME \ - LCD_SET_PROGRESS_MANUALLY PRINT_PROGRESS_SHOW_DECIMALS SHOW_REMAINING_TIME \ - BABYSTEPPING BABYSTEP_XY NANODLP_Z_SYNC I2C_POSITION_ENCODERS M114_DETAIL -exec_test $1 $2 "Azteeg X3 Pro | EXTRUDERS 5 | RRDFGSC | UBL | LIN_ADVANCE ..." - -# -# Add a Sled Z Probe, use UBL Cartesian moves, use Japanese language -# -use_example_configs AnimationExample -opt_set SHOW_CUSTOM_BOOTSCREEN -opt_set MOTHERBOARD BOARD_AZTEEG_X3_PRO -opt_set LCD_LANGUAGE fr -opt_set EXTRUDERS 5 -opt_set TEMP_SENSOR_1 1 -opt_set TEMP_SENSOR_2 5 -opt_set TEMP_SENSOR_3 20 -opt_set TEMP_SENSOR_4 1000 -opt_set TEMP_SENSOR_BED 1 -opt_enable AUTO_BED_LEVELING_UBL RESTORE_LEVELING_AFTER_G28 DEBUG_LEVELING_FEATURE G26_MESH_VALIDATION ENABLE_LEVELING_FADE_HEIGHT SKEW_CORRECTION \ - REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER LIGHTWEIGHT_UI STATUS_MESSAGE_SCROLLING BOOT_MARLIN_LOGO_SMALL \ - SDSUPPORT SDCARD_SORT_ALPHA USB_FLASH_DRIVE_SUPPORT SCROLL_LONG_FILENAMES CANCEL_OBJECTS \ - EEPROM_SETTINGS EEPROM_CHITCHAT GCODE_MACROS CUSTOM_USER_MENUS \ - MULTI_NOZZLE_DUPLICATION CLASSIC_JERK LIN_ADVANCE QUICK_HOME \ - LCD_SET_PROGRESS_MANUALLY PRINT_PROGRESS_SHOW_DECIMALS SHOW_REMAINING_TIME \ - BABYSTEPPING BABYSTEP_XY NANODLP_Z_SYNC I2C_POSITION_ENCODERS M114_DETAIL \ - Z_PROBE_SLED SKEW_CORRECTION SKEW_CORRECTION_FOR_Z SKEW_CORRECTION_GCODE -opt_set LCD_LANGUAGE jp_kana -opt_disable SEGMENT_LEVELED_MOVES -opt_enable BABYSTEPPING BABYSTEP_XY BABYSTEP_ZPROBE_OFFSET DOUBLECLICK_FOR_Z_BABYSTEPPING BABYSTEP_HOTEND_Z_OFFSET BABYSTEP_DISPLAY_TOTAL M114_DETAIL -exec_test $1 $2 "Azteeg X3 Pro | EXTRUDERS 5 | RRDFGSC | UBL | LIN_ADVANCE | Sled Probe | Skew | JP-Kana | Babystep offsets ..." - -# -# Test a Servo Probe -# ...with AUTO_BED_LEVELING_3POINT, DEBUG_LEVELING_FEATURE, EEPROM_SETTINGS, EEPROM_CHITCHAT, EXTENDED_CAPABILITIES_REPORT, and AUTO_REPORT_TEMPERATURES -# -restore_configs -opt_set LCD_LANGUAGE zh_CN -opt_set EXTRUDERS 5 -opt_set NUM_SERVOS 1 -opt_enable ZONESTAR_LCD Z_PROBE_SERVO_NR Z_SERVO_ANGLES DEACTIVATE_SERVOS_AFTER_MOVE BOOT_MARLIN_LOGO_ANIMATED \ - AUTO_BED_LEVELING_3POINT DEBUG_LEVELING_FEATURE EEPROM_SETTINGS EEPROM_CHITCHAT M114_DETAIL \ - NO_VOLUMETRICS EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES AUTOTEMP G38_PROBE_TARGET JOYSTICK \ - PRUSA_MMU2 MMU2_MENUS PRUSA_MMU2_S_MODE DIRECT_STEPPING DETECT_BROKEN_ENDSTOP \ - FILAMENT_RUNOUT_SENSOR NOZZLE_PARK_FEATURE ADVANCED_PAUSE_FEATURE Z_SAFE_HOMING -exec_test $1 $2 "RAMPS | ZONESTAR + Chinese | MMU2 | Servo | 3-Point + Debug | G38 ..." - -# -# Test MINIRAMBO with PWM_MOTOR_CURRENT and many features -# -restore_configs -opt_set MOTHERBOARD BOARD_MEGACONTROLLER -opt_set LCD_LANGUAGE de -opt_enable EEPROM_SETTINGS EEPROM_CHITCHAT \ - MINIPANEL SDSUPPORT PCA9632 LCD_INFO_MENU \ - AUTO_BED_LEVELING_BILINEAR PROBE_MANUALLY LCD_BED_LEVELING G26_MESH_VALIDATION MESH_EDIT_MENU \ - LIN_ADVANCE EXTRA_LIN_ADVANCE_K \ - INCH_MODE_SUPPORT TEMPERATURE_UNITS_SUPPORT EXPERIMENTAL_I2CBUS M100_FREE_MEMORY_WATCHER \ - NOZZLE_PARK_FEATURE NOZZLE_CLEAN_FEATURE \ - ADVANCED_PAUSE_FEATURE PARK_HEAD_ON_PAUSE ADVANCED_PAUSE_CONTINUOUS_PURGE FILAMENT_LOAD_UNLOAD_GCODES \ - PRINTCOUNTER SERVICE_NAME_1 SERVICE_INTERVAL_1 M114_DETAIL \ - USE_CONTROLLER_FAN CONTROLLER_FAN_EDITABLE -opt_set CONTROLLERFAN_SPEED_IDLE 128 -opt_add M100_FREE_MEMORY_DUMPER -opt_add M100_FREE_MEMORY_CORRUPTOR -opt_set PWM_MOTOR_CURRENT "{ 1300, 1300, 1250 }" -opt_set I2C_SLAVE_ADDRESS 63 -exec_test $1 $2 "MEGACONTROLLER | Minipanel | M100 | PWM_MOTOR_CURRENT | PRINTCOUNTER | Advanced Pause ..." - -# -# Mixing Extruder with 5 steppers, Greek -# -restore_configs -opt_set MOTHERBOARD BOARD_AZTEEG_X3_PRO -opt_set LCD_LANGUAGE el_gr -opt_enable MIXING_EXTRUDER GRADIENT_MIX GRADIENT_VTOOL CR10_STOCKDISPLAY \ - USE_CONTROLLER_FAN CONTROLLER_FAN_EDITABLE CONTROLLER_FAN_IGNORE_Z -opt_set MIXING_STEPPERS 5 -opt_set LCD_LANGUAGE ru -exec_test $1 $2 "Azteeg X3 | Mixing Extruder (x5) | Gradient Mix | Greek" - -# -# Test SPEAKER with BOARD_BQ_ZUM_MEGA_3D and BQ_LCD_SMART_CONTROLLER -# -#restore_configs -#opt_set MOTHERBOARD BOARD_BQ_ZUM_MEGA_3D -#opt_set LCD_FEEDBACK_FREQUENCY_DURATION_MS 10 -#opt_set LCD_FEEDBACK_FREQUENCY_HZ 100 -#opt_enable BQ_LCD_SMART_CONTROLLER SPEAKER - -# -# Enable COREXY -# -#restore_configs -#opt_enable COREXY -#exec_test $1 $2 "Stuff" - -# -# Test many less common options -# -restore_configs -opt_set MOTHERBOARD BOARD_MIGHTYBOARD_REVE -opt_set TEMP_SENSOR_0 -2 -opt_set DIGIPOT_I2C_NUM_CHANNELS 5 -opt_set LCD_LANGUAGE it -opt_set MIXING_STEPPERS 2 -opt_set SERVO_DELAY "{ 300, 300, 300 }" -opt_enable COREYX USE_XMAX_PLUG MIXING_EXTRUDER GRADIENT_MIX \ - BABYSTEPPING BABYSTEP_DISPLAY_TOTAL FILAMENT_LCD_DISPLAY \ - REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER MENU_ADDAUTOSTART SDSUPPORT SDCARD_SORT_ALPHA \ - ENDSTOP_NOISE_THRESHOLD FAN_SOFT_PWM \ - FIX_MOUNTED_PROBE AUTO_BED_LEVELING_LINEAR DEBUG_LEVELING_FEATURE FILAMENT_WIDTH_SENSOR PROBE_OFFSET_WIZARD \ - Z_SAFE_HOMING SHOW_TEMP_ADC_VALUES HOME_Y_BEFORE_X EMERGENCY_PARSER \ - SD_ABORT_ON_ENDSTOP_HIT HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT 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_set FAN_MIN_PWM 50 -opt_set FAN_KICKSTART_TIME 100 -opt_set XY_FREQUENCY_LIMIT 15 -opt_add FILWIDTH_PIN 5 -exec_test $1 $2 "Mightyboard Rev. E | CoreXY, Gradient Mix | Endstop Int. | Home Y > X | FW Retract ..." - -######## Other Standard LCD/Panels ############## -# -# ULTRA_LCD -# -#restore_configs -#opt_enable ULTRA_LCD -#exec_test $1 $2 "Stuff" -# -# DOGLCD -# -#restore_configs -#opt_enable DOGLCD -#exec_test $1 $2 "Stuff" -# -# MAKRPANEL -# Needs to use Melzi and Sanguino hardware -# -#restore_configs -#opt_enable MAKRPANEL -#exec_test $1 $2 "Stuff" -# -# REPRAP_DISCOUNT_SMART_CONTROLLER, SDSUPPORT, BABYSTEPPING, RIGIDBOARD_V2, and DAC_MOTOR_CURRENT_DEFAULT -# -#restore_configs -#opt_set MOTHERBOARD BOARD_RIGIDBOARD_V2 -#opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT BABYSTEPPING DAC_MOTOR_CURRENT_DEFAULT -#exec_test $1 $2 "Stuff" -# # -# G3D_PANEL with SDCARD_SORT_ALPHA and STATUS_MESSAGE_SCROLLING -# -#restore_configs -#opt_enable G3D_PANEL SDSUPPORT SDCARD_SORT_ALPHA STATUS_MESSAGE_SCROLLING SCROLL_LONG_FILENAMES -#opt_set SDSORT_GCODE true -#opt_set SDSORT_USES_RAM true -#opt_set SDSORT_USES_STACK true -#opt_set SDSORT_CACHE_NAMES true -#exec_test $1 $2 "Stuff" -# -# REPRAPWORLD_KEYPAD -# -# Cant find configuration details to get it to compile -#restore_configs -#opt_enable ULTRA_LCD REPRAPWORLD_KEYPAD REPRAPWORLD_KEYPAD_MOVE_STEP -#exec_test $1 $2 "Stuff" -# -# RA_CONTROL_PANEL -# -#restore_configs -#opt_enable RA_CONTROL_PANEL PINS_DEBUGGING -#exec_test $1 $2 "Stuff" - -######## I2C LCD/PANELS ############## -# -# !!!ATTENTION!!! -# Most I2C configurations are failing at the moment because they require -# a different Liquid Crystal library "LiquidTWI2". -# -# LCD_SAINSMART_I2C_1602 -# -#restore_configs -#opt_enable LCD_SAINSMART_I2C_1602 -#exec_test $1 $2 "Stuff" -# -# LCD_I2C_PANELOLU2 -# -#restore_configs -#opt_enable LCD_I2C_PANELOLU2 -#exec_test $1 $2 "Stuff" -# -# LCD_I2C_VIKI -# -#restore_configs -#opt_enable LCD_I2C_VIKI -#exec_test $1 $2 "Stuff" -# -# LCM1602 -# -#restore_configs -#opt_enable LCM1602 -#exec_test $1 $2 "Stuff" - -# -# Language files test with REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER -# -#restore_configs -#opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER SDSUPPORT -#for lang in an bg ca cz da de el el_gr en es eu fi fr gl hr hu it jp_kana nl pl pt pt_br ro ru sk tr uk vi zh_CN zh_TW test; do opt_set LCD_LANGUAGE $lang; echo "compile with language $lang ..."; exec_test $1 $2 "Stuff"; done -# -#restore_configs -#opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT -#for lang in an bg ca cz da de el el_gr en es eu fi fr gl hr hu it jp_kana nl pl pt pt_br ro ru sk tr uk vi zh_CN zh_TW test; do opt_set LCD_LANGUAGE $lang; echo "compile with language $lang ..."; exec_test $1 $2 "Stuff"; done - -######## Example Configurations ############## -# -# Test a full-featured CR-10S config -# -use_example_configs Creality/CR-10S -exec_test $1 $2 "Full-featured CR-10S config" - -# -# BQ Hephestos 2 -#restore_configs -#use_example_configs Hephestos_2 -#exec_test $1 $2 "Stuff" - -# -# Delta Config (generic) + UBL + ALLEN_KEY + EEPROM_SETTINGS + OLED_PANEL_TINYBOY2 -# -use_example_configs delta/generic -opt_enable RESTORE_LEVELING_AFTER_G28 EEPROM_SETTINGS EEPROM_CHITCHAT \ - Z_PROBE_ALLEN_KEY AUTO_BED_LEVELING_UBL \ - OLED_PANEL_TINYBOY2 MESH_EDIT_GFX_OVERLAY DELTA_CALIBRATION_MENU -opt_set LCD_LANGUAGE ko_KR -opt_set X_DRIVER_TYPE L6470 -opt_set Y_DRIVER_TYPE L6470 -opt_set Z_DRIVER_TYPE L6470 -opt_add L6470_CHAIN_SCK_PIN 53 -opt_add L6470_CHAIN_MISO_PIN 49 -opt_add L6470_CHAIN_MOSI_PIN 40 -opt_add L6470_CHAIN_SS_PIN 42 -opt_add "ENABLE_RESET_L64XX_CHIPS(V) NOOP" -exec_test $1 $2 "DELTA, RAMPS, L6470, UBL, Allen Key, EEPROM, OLED_PANEL_TINYBOY2..." - -# -# Delta Config (FLSUN AC because it's complex) -# -use_example_configs delta/FLSUN/auto_calibrate -exec_test $1 $2 "RAMPS 1.3 | DELTA | FLSUN AC Config" - -# -# Makibox Config need to check board type for Teensy++ 2.0 -# -#use_example_configs makibox -#exec_test $1 $2 "Stuff" - -# -# Test mixed TMC config -# -restore_configs -opt_set LCD_LANGUAGE vi -opt_set X_DRIVER_TYPE TMC2160 -opt_set Y_DRIVER_TYPE TMC5160 -opt_set Z_DRIVER_TYPE TMC2208_STANDALONE -opt_set E0_DRIVER_TYPE TMC2130 -opt_set X_MIN_ENDSTOP_INVERTING true -opt_set Y_MIN_ENDSTOP_INVERTING true -opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER \ - MARLIN_BRICKOUT MARLIN_INVADERS MARLIN_SNAKE \ - MONITOR_DRIVER_STATUS STEALTHCHOP_XY STEALTHCHOP_Z STEALTHCHOP_E HYBRID_THRESHOLD \ - USE_ZMIN_PLUG SENSORLESS_HOMING TMC_DEBUG M114_DETAIL -exec_test $1 $2 "RAMPS | Mixed TMC | Sensorless | RRDFGSC | Games" - -# -# SCARA with Mixed TMC -# -use_example_configs SCARA/Morgan -opt_set LCD_LANGUAGE es -opt_enable USE_ZMIN_PLUG FIX_MOUNTED_PROBE AUTO_BED_LEVELING_BILINEAR PAUSE_BEFORE_DEPLOY_STOW \ - MKS_12864OLED EEPROM_SETTINGS EEPROM_CHITCHAT M114_DETAIL Z_SAFE_HOMING \ - STEALTHCHOP_XY STEALTHCHOP_Z STEALTHCHOP_E HYBRID_THRESHOLD SENSORLESS_HOMING SQUARE_WAVE_STEPPING -opt_set X_MAX_ENDSTOP_INVERTING false -opt_set X_DRIVER_TYPE TMC2209 -opt_set Y_DRIVER_TYPE TMC2130 -opt_set Z_DRIVER_TYPE TMC2130_STANDALONE -opt_set E0_DRIVER_TYPE TMC2660 -exec_test $1 $2 "RAMPS | SCARA | Mixed TMC | EEPROM" - -# -# tvrrug Config need to check board type for sanguino atmega644p -# -#use_example_configs tvrrug/Round2 -#exec_test $1 $2 "Stuff" - -# clean up -restore_configs diff --git a/buildroot/tests/mks_robin b/buildroot/tests/mks_robin new file mode 100755 index 000000000000..e250dceca255 --- /dev/null +++ b/buildroot/tests/mks_robin @@ -0,0 +1,13 @@ +#!/usr/bin/env bash +# +# Build tests for MKS Robin (HAL/STM32) +# + +# exit on first failure +set -e + +use_example_configs Mks/Robin +exec_test $1 $2 "MKS Robin base configuration" "$3" + +# cleanup +restore_configs diff --git a/buildroot/tests/mks_robin-tests b/buildroot/tests/mks_robin-tests deleted file mode 100644 index d6350622052c..000000000000 --- a/buildroot/tests/mks_robin-tests +++ /dev/null @@ -1,16 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for MKS Robin -# (STM32F1 genericSTM32F103ZE) -# - -# exit on first failure -set -e - -use_example_configs Mks/Robin -opt_disable TFT_320x240 -opt_enable FSMC_GRAPHICAL_TFT -exec_test $1 $2 "MKS Robin base configuration" - -# cleanup -restore_configs diff --git a/buildroot/tests/mks_robin_lite-tests b/buildroot/tests/mks_robin_lite-tests deleted file mode 100644 index 34809641eca9..000000000000 --- a/buildroot/tests/mks_robin_lite-tests +++ /dev/null @@ -1,17 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for STM32F1 genericSTM32F103RC -# - -# exit on first failure -set -e - -restore_configs -opt_set MOTHERBOARD BOARD_MKS_ROBIN_LITE -opt_set SERIAL_PORT -1 -opt_enable EEPROM_SETTINGS -opt_enable SDSUPPORT -exec_test $1 $2 "Default Configuration with Fallback SD EEPROM" - -# cleanup -restore_configs diff --git a/buildroot/tests/mks_robin_lite_maple b/buildroot/tests/mks_robin_lite_maple new file mode 100755 index 000000000000..49ef0048716b --- /dev/null +++ b/buildroot/tests/mks_robin_lite_maple @@ -0,0 +1,15 @@ +#!/usr/bin/env bash +# +# Build tests for STM32F1 genericSTM32F103RC +# + +# exit on first failure +set -e + +restore_configs +opt_set MOTHERBOARD BOARD_MKS_ROBIN_LITE SERIAL_PORT 1 +opt_enable EEPROM_SETTINGS SDSUPPORT +exec_test $1 $2 "Default Configuration with Fallback SD EEPROM" "$3" + +# cleanup +restore_configs diff --git a/buildroot/tests/mks_robin_maple b/buildroot/tests/mks_robin_maple new file mode 100755 index 000000000000..fcb51183076e --- /dev/null +++ b/buildroot/tests/mks_robin_maple @@ -0,0 +1,22 @@ +#!/usr/bin/env bash +# +# Build tests for MKS Robin with LibMaple STM32F1 HAL +# (STM32F1 genericSTM32F103ZE) +# + +# exit on first failure +set -e + +use_example_configs Mks/Robin +exec_test $1 $2 "MKS Robin config (FSMC Color UI)" "$3" + +# +# MKS Robin LVGL FSMC +# +use_example_configs Mks/Robin +opt_disable TFT_CLASSIC_UI TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 +opt_enable TFT_LVGL_UI TFT_RES_480x320 +exec_test $1 $2 "MKS Robin nano v1.2 LVGL FSMC" "$3" + +# cleanup +restore_configs diff --git a/buildroot/tests/mks_robin_mini b/buildroot/tests/mks_robin_mini new file mode 100755 index 000000000000..29baee8818d6 --- /dev/null +++ b/buildroot/tests/mks_robin_mini @@ -0,0 +1,15 @@ +#!/usr/bin/env bash +# +# Build tests for MKS Robin mini +# (STM32F1 genericSTM32F103VE) +# + +# exit on first failure +set -e + +use_example_configs Mks/Robin +opt_set MOTHERBOARD BOARD_MKS_ROBIN_MINI EXTRUDERS 1 TEMP_SENSOR_1 0 +exec_test $1 $2 "MKS Robin mini" "$3" + +# cleanup +restore_configs diff --git a/buildroot/tests/mks_robin_mini-tests b/buildroot/tests/mks_robin_mini-tests deleted file mode 100644 index 1c40ea453554..000000000000 --- a/buildroot/tests/mks_robin_mini-tests +++ /dev/null @@ -1,17 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for MKS Robin mini -# (STM32F1 genericSTM32F103VE) -# - -# exit on first failure -set -e - -use_example_configs Mks/Robin -opt_set MOTHERBOARD BOARD_MKS_ROBIN_MINI -opt_set EXTRUDERS 1 -opt_set TEMP_SENSOR_1 0 -exec_test $1 $2 "MKS Robin mini" - -# cleanup -restore_configs diff --git a/buildroot/tests/mks_robin_nano35 b/buildroot/tests/mks_robin_nano35 new file mode 100755 index 000000000000..bd16fe48e934 --- /dev/null +++ b/buildroot/tests/mks_robin_nano35 @@ -0,0 +1,68 @@ +#!/usr/bin/env bash +# +# Build tests for MKS Robin nano +# (STM32F1 genericSTM32F103VE) +# + +# exit on first failure +set -e + +# +# MKS Robin nano v1.2 Emulated DOGM FSMC +# +use_example_configs Mks/Robin +opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO +exec_test $1 $2 "MKS Robin nano v1.2 Emulated DOGM FSMC" "$3" + +# +# MKS Robin v2 nano Emulated DOGM SPI +# (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 +opt_enable TFT_INTERFACE_SPI MKS_WIFI_MODULE +opt_add MKS_TEST +exec_test $1 $2 "MKS Robin v2 nano Emulated DOGM SPI, MKS_WIFI_MODULE" "$3" + +# +# MKS Robin nano v1.2 LVGL FSMC +# +# use_example_configs Mks/Robin +# opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO +# opt_disable TFT_CLASSIC_UI TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 +# opt_enable TFT_LVGL_UI TFT_RES_480x320 +# exec_test $1 $2 "MKS Robin nano v1.2 LVGL FSMC" "$3" + +# +# MKS Robin v2 nano LVGL SPI +# (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_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 +# opt_enable TFT_INTERFACE_SPI TFT_LVGL_UI TFT_RES_480x320 +# exec_test $1 $2 "MKS Robin v2 nano LVGL SPI" "$3" + +# +# MKS Robin v2 nano New Color UI 480x320 SPI +# (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 +exec_test $1 $2 "MKS Robin v2 nano New Color UI 480x320 SPI" "$3" + +# +# MKS Robin v2 nano LVGL SPI + TMC +# (Robin v2 nano has no FSMC interface) +# +# use_example_configs Mks/Robin +# opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 X_DRIVER_TYPE TMC2209 Y_DRIVER_TYPE TMC2209 +# opt_disable TFT_INTERFACE_FSMC TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 +# opt_enable TFT_INTERFACE_SPI TFT_LVGL_UI TFT_RES_480x320 +# exec_test $1 $2 "MKS Robin v2 nano LVGL SPI + TMC" "$3" + +# cleanup +restore_configs diff --git a/buildroot/tests/mks_robin_nano35-tests b/buildroot/tests/mks_robin_nano35-tests deleted file mode 100644 index 92c97be756cd..000000000000 --- a/buildroot/tests/mks_robin_nano35-tests +++ /dev/null @@ -1,46 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for MKS Robin nano -# (STM32F1 genericSTM32F103VE) -# - -# exit on first failure -set -e - -use_example_configs Mks/Robin -opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO -opt_disable TFT_320x240 -opt_enable TOUCH_SCREEN -opt_enable FSMC_GRAPHICAL_TFT -exec_test $1 $2 "MKS Robin nano v1.2 Emulated DOGM FSMC" - -use_example_configs Mks/Robin -opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 -opt_disable TFT_320x240 -opt_enable TOUCH_SCREEN -opt_enable SPI_GRAPHICAL_TFT -exec_test $1 $2 "MKS Robin v2 nano Emulated DOGM SPI" - -use_example_configs Mks/Robin -opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO -opt_disable TFT_320x240 -opt_disable TOUCH_SCREEN -opt_enable TFT_LVGL_UI_FSMC -exec_test $1 $2 "MKS Robin nano v1.2 LVGL FSMC" - -use_example_configs Mks/Robin -opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 -opt_disable TFT_320x240 -opt_disable TOUCH_SCREEN -opt_enable TFT_LVGL_UI_SPI -exec_test $1 $2 "MKS Robin v2 nano LVGL SPI" - -use_example_configs Mks/Robin -opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 -opt_disable TFT_320x240 -opt_enable TOUCH_SCREEN -opt_enable TFT_480x320_SPI -exec_test $1 $2 "MKS Robin v2 nano New Color UI 480x320 SPI" - -# cleanup -restore_configs diff --git a/buildroot/tests/mks_robin_nano35_maple b/buildroot/tests/mks_robin_nano35_maple new file mode 100755 index 000000000000..ebd5466ce61c --- /dev/null +++ b/buildroot/tests/mks_robin_nano35_maple @@ -0,0 +1,69 @@ +#!/usr/bin/env bash +# +# Build tests for MKS Robin nano with LibMaple STM32F1 HAL +# (STM32F1 genericSTM32F103VE) +# + +# exit on first failure +set -e + +# +# MKS Robin nano v1.2 Emulated DOGM FSMC +# +use_example_configs Mks/Robin +opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO +exec_test $1 $2 "MKS Robin nano v1.2 Emulated DOGM FSMC" "$3" + +# +# MKS Robin v2 nano Emulated DOGM SPI +# (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 +opt_enable TFT_INTERFACE_SPI +exec_test $1 $2 "MKS Robin v2 nano Emulated DOGM SPI" "$3" + +# +# MKS Robin v2 nano LVGL SPI +# (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_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 SERIAL_PORT_2 +opt_enable TFT_INTERFACE_SPI TFT_LVGL_UI TFT_RES_480x320 MKS_WIFI_MODULE +opt_add MKS_TEST +exec_test $1 $2 "MKS Robin v2 nano LVGL SPI w/ WiFi" "$3" + +# +# MKS Robin v2 nano New Color UI 480x320 SPI +# (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" + +# +# MKS Robin v2 nano LVGL SPI + TMC +# (Robin v2 nano has no FSMC interface) +# +use_example_configs Mks/Robin +opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 X_DRIVER_TYPE TMC2209 Y_DRIVER_TYPE TMC2209 +opt_disable TFT_INTERFACE_FSMC TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 +opt_enable TFT_INTERFACE_SPI TFT_LVGL_UI TFT_RES_480x320 +exec_test $1 $2 "MKS Robin v2 nano LVGL SPI + TMC" "$3" + +# +# MKS Robin v2 nano New Color UI 480x320 SPI Without Touch Screen +# +use_example_configs Mks/Robin +opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 +opt_disable TFT_INTERFACE_FSMC TFT_RES_320x240 TOUCH_SCREEN +opt_enable TFT_INTERFACE_SPI TFT_RES_480x320 TFT_COLOR_UI +exec_test $1 $2 "MKS Robin v2 nano New Color UI 480x320 SPI without TOUCH_SCREEN" "$3" + +# cleanup +restore_configs diff --git a/buildroot/tests/mks_robin_pro-tests b/buildroot/tests/mks_robin_pro-tests deleted file mode 100644 index 7ae4670fedac..000000000000 --- a/buildroot/tests/mks_robin_pro-tests +++ /dev/null @@ -1,19 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for MKS Robin Pro -# - -# exit on first failure -set -e - -use_example_configs Mks/Robin_Pro -opt_enable EMERGENCY_PARSER -opt_set SDCARD_CONNECTION LCD -opt_set X_DRIVER_TYPE TMC2209 -opt_set Y_DRIVER_TYPE TMC2130 -opt_set TEMP_SENSOR_BED 1 -opt_disable THERMAL_PROTECTION_HOTENDS -exec_test $1 $2 "MKS Robin Pro with TMC Drivers, hotend thermal protection disabled" - -# cleanup -#restore_configs diff --git a/buildroot/tests/mks_robin_pro_maple b/buildroot/tests/mks_robin_pro_maple new file mode 100755 index 000000000000..4b38ab97b6bf --- /dev/null +++ b/buildroot/tests/mks_robin_pro_maple @@ -0,0 +1,19 @@ +#!/usr/bin/env bash +# +# Build tests for MKS Robin Pro +# + +# exit on first failure +set -e + +use_example_configs Mks/Robin_Pro +opt_enable EMERGENCY_PARSER +opt_set SERIAL_PORT 3 \ + SDCARD_CONNECTION LCD \ + X_DRIVER_TYPE TMC2209 Y_DRIVER_TYPE TMC2130 \ + TEMP_SENSOR_BED 1 +opt_disable SERIAL_PORT_2 THERMAL_PROTECTION_HOTENDS +exec_test $1 $2 "MKS Robin Pro, TMC Drivers, no thermal protection" "$3" + +# cleanup +restore_configs diff --git a/buildroot/tests/mks_robin_stm32-tests b/buildroot/tests/mks_robin_stm32-tests deleted file mode 100644 index 4aa146fa5288..000000000000 --- a/buildroot/tests/mks_robin_stm32-tests +++ /dev/null @@ -1,13 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for MKS Robin (HAL/STM32) -# - -# exit on first failure -set -e - -use_example_configs Mks/Robin -exec_test $1 $2 "MKS Robin base configuration" - -# cleanup -restore_configs diff --git a/buildroot/tests/rambo b/buildroot/tests/rambo new file mode 100755 index 000000000000..0555a068e271 --- /dev/null +++ b/buildroot/tests/rambo @@ -0,0 +1,129 @@ +#!/usr/bin/env bash +# +# Build tests for AVR ATmega2560 RAMBo +# + +# exit on first failure +set -e + +# +# Lots of options - Formerly the first Mega2560 test +# +restore_configs +opt_set MOTHERBOARD BOARD_RAMBO \ + EXTRUDERS 2 TEMP_SENSOR_0 -2 TEMP_SENSOR_1 1 TEMP_SENSOR_BED 2 \ + TEMP_SENSOR_PROBE 1 TEMP_PROBE_PIN 12 \ + TEMP_SENSOR_CHAMBER 3 TEMP_CHAMBER_PIN 3 HEATER_CHAMBER_PIN 45 \ + GRID_MAX_POINTS_X 16 \ + FANMUX0_PIN 53 +opt_disable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN USE_WATCHDOG +opt_enable USE_ZMAX_PLUG REPRAP_DISCOUNT_SMART_CONTROLLER LCD_PROGRESS_BAR LCD_PROGRESS_BAR_TEST \ + FIX_MOUNTED_PROBE CODEPENDENT_XY_HOMING PIDTEMPBED PROBE_TEMP_COMPENSATION \ + PREHEAT_BEFORE_PROBING PROBING_HEATERS_OFF PROBING_FANS_OFF PROBING_STEPPERS_OFF WAIT_FOR_BED_HEATER \ + EEPROM_SETTINGS SDSUPPORT SD_REPRINT_LAST_SELECTED_FILE BINARY_FILE_TRANSFER \ + BLINKM PCA9533 PCA9632 RGB_LED RGB_LED_R_PIN RGB_LED_G_PIN RGB_LED_B_PIN LED_CONTROL_MENU \ + NEOPIXEL_LED NEOPIXEL_PIN CASE_LIGHT_ENABLE CASE_LIGHT_USE_NEOPIXEL CASE_LIGHT_MENU \ + PID_PARAMS_PER_HOTEND PID_AUTOTUNE_MENU PID_EDIT_MENU LCD_SHOW_E_TOTAL \ + PRINTCOUNTER SERVICE_NAME_1 SERVICE_INTERVAL_1 LEVEL_BED_CORNERS LEVEL_CENTER_TOO \ + NOZZLE_PARK_FEATURE FILAMENT_RUNOUT_SENSOR FILAMENT_RUNOUT_DISTANCE_MM \ + ADVANCED_PAUSE_FEATURE FILAMENT_LOAD_UNLOAD_GCODES FILAMENT_UNLOAD_ALL_EXTRUDERS \ + PASSWORD_FEATURE PASSWORD_ON_STARTUP PASSWORD_ON_SD_PRINT_MENU PASSWORD_AFTER_SD_PRINT_END PASSWORD_AFTER_SD_PRINT_ABORT \ + AUTO_BED_LEVELING_BILINEAR Z_MIN_PROBE_REPEATABILITY_TEST DISTINCT_E_FACTORS \ + SKEW_CORRECTION SKEW_CORRECTION_FOR_Z SKEW_CORRECTION_GCODE \ + BACKLASH_COMPENSATION BACKLASH_GCODE BAUD_RATE_GCODE BEZIER_CURVE_SUPPORT \ + FWRETRACT ARC_P_CIRCLES CNC_WORKSPACE_PLANES CNC_COORDINATE_SYSTEMS \ + PSU_CONTROL AUTO_POWER_CONTROL POWER_LOSS_RECOVERY POWER_LOSS_PIN POWER_LOSS_STATE POWER_LOSS_RECOVER_ZHOME POWER_LOSS_ZHOME_POS \ + SLOW_PWM_HEATERS THERMAL_PROTECTION_CHAMBER LIN_ADVANCE EXTRA_LIN_ADVANCE_K \ + HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT PINS_DEBUGGING MAX7219_DEBUG M114_DETAIL +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" + +# +# Full size Rambo Dual Endstop CNC +# +restore_configs +opt_set MOTHERBOARD BOARD_RAMBO \ + EXTRUDERS 0 TEMP_SENSOR_0 999 DUMMY_THERMISTOR_999_VALUE 170 Z_HOME_DIR 1 \ + DIGIPOT_MOTOR_CURRENT '{ 120, 120, 120, 120, 120 }' \ + DEFAULT_AXIS_STEPS_PER_UNIT '{ 80, 80, 4000 }' \ + DEFAULT_MAX_FEEDRATE '{ 300, 300, 5 }' \ + DEFAULT_MAX_ACCELERATION '{ 3000, 3000, 100 }' \ + MANUAL_FEEDRATE '{ 50*60, 50*60, 4*60 }' \ + AXIS_RELATIVE_MODES '{ false, false, false }' \ + LEVEL_CORNERS_LEVELING_ORDER '{ LF, RF }' +opt_enable USE_XMAX_PLUG USE_YMAX_PLUG USE_ZMAX_PLUG \ + REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER REVERSE_ENCODER_DIRECTION SDSUPPORT EEPROM_SETTINGS \ + S_CURVE_ACCELERATION X_DUAL_STEPPER_DRIVERS X_DUAL_ENDSTOPS Y_DUAL_STEPPER_DRIVERS Y_DUAL_ENDSTOPS \ + ADAPTIVE_STEP_SMOOTHING CNC_COORDINATE_SYSTEMS GCODE_MOTION_MODES \ + LEVEL_BED_CORNERS LEVEL_CENTER_TOO +opt_disable MIN_SOFTWARE_ENDSTOP_Z MAX_SOFTWARE_ENDSTOPS +exec_test $1 $2 "Rambo CNC Configuration" "$3" + +# +# Rambo heated bed only +# +restore_configs +opt_set MOTHERBOARD BOARD_RAMBO EXTRUDERS 0 TEMP_SENSOR_BED 1 \ + DEFAULT_AXIS_STEPS_PER_UNIT '{ 80, 80, 4000 }' \ + DEFAULT_MAX_FEEDRATE '{ 300, 300, 5 }' \ + DEFAULT_MAX_ACCELERATION '{ 3000, 3000, 100 }' \ + MANUAL_FEEDRATE '{ 50*60, 50*60, 4*60 }' \ + AXIS_RELATIVE_MODES '{ false, false, false }' +opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER +exec_test $1 $2 "Rambo heated bed only" "$3" + +# +# Build with the default configurations +# +restore_configs +opt_set MOTHERBOARD BOARD_EINSY_RAMBO \ + X_DRIVER_TYPE TMC2130 Y_DRIVER_TYPE TMC2130 Z_DRIVER_TYPE TMC2130 E0_DRIVER_TYPE TMC2130 +exec_test $1 $2 "Einsy RAMBo with TMC2130" "$3" + +# +# Test MINIRAMBO with PWM_MOTOR_CURRENT and many features +# +restore_configs +opt_set MOTHERBOARD BOARD_MINIRAMBO \ + CONTROLLERFAN_SPEED_IDLE 128 \ + PWM_MOTOR_CURRENT '{ 1300, 1300, 1250 }' \ + I2C_SLAVE_ADDRESS 63 +opt_enable EEPROM_SETTINGS EEPROM_CHITCHAT REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER \ + SDSUPPORT PCA9632 SOUND_MENU_ITEM GCODE_REPEAT_MARKERS \ + AUTO_BED_LEVELING_BILINEAR PROBE_MANUALLY LCD_BED_LEVELING G26_MESH_VALIDATION MESH_EDIT_MENU \ + LIN_ADVANCE EXTRA_LIN_ADVANCE_K \ + INCH_MODE_SUPPORT TEMPERATURE_UNITS_SUPPORT EXPERIMENTAL_I2CBUS M100_FREE_MEMORY_WATCHER \ + NOZZLE_PARK_FEATURE NOZZLE_CLEAN_FEATURE \ + ADVANCED_PAUSE_FEATURE PARK_HEAD_ON_PAUSE ADVANCED_PAUSE_CONTINUOUS_PURGE FILAMENT_LOAD_UNLOAD_GCODES \ + PRINTCOUNTER SERVICE_NAME_1 SERVICE_INTERVAL_1 M114_DETAIL +opt_add M100_FREE_MEMORY_DUMPER +opt_add M100_FREE_MEMORY_CORRUPTOR +exec_test $1 $2 "MINIRAMBO | RRDGFSC | ABL Bilinear Manual | M100 | PWM_MOTOR_CURRENT | M600..." "$3" + +# +# Test many less common options +# +restore_configs +opt_set MOTHERBOARD BOARD_RAMBO \ + TEMP_SENSOR_0 -2 \ + DIGIPOT_I2C_NUM_CHANNELS 5 \ + LCD_LANGUAGE it \ + MIXING_STEPPERS 2 \ + SERVO_DELAY '{ 300, 300, 300 }' \ + CONTROLLER_FAN_PIN X_MAX_PIN FILWIDTH_PIN 5 \ + FAN_MIN_PWM 50 FAN_KICKSTART_TIME 100 \ + XY_FREQUENCY_LIMIT 15 +opt_enable COREYX USE_XMAX_PLUG MIXING_EXTRUDER GRADIENT_MIX \ + BABYSTEPPING BABYSTEP_DISPLAY_TOTAL FILAMENT_LCD_DISPLAY FILAMENT_WIDTH_SENSOR \ + REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER MENU_ADDAUTOSTART SDSUPPORT SDCARD_SORT_ALPHA \ + ENDSTOP_NOISE_THRESHOLD FAN_SOFT_PWM \ + FIX_MOUNTED_PROBE PROBING_ESTEPPERS_OFF AUTO_BED_LEVELING_LINEAR DEBUG_LEVELING_FEATURE PROBE_OFFSET_WIZARD \ + Z_SAFE_HOMING SHOW_TEMP_ADC_VALUES HOME_Y_BEFORE_X EMERGENCY_PARSER \ + SD_ABORT_ON_ENDSTOP_HIT HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT 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 +exec_test $1 $2 "Rambo | CoreXY, Gradient Mix | Endstop Int. | Home Y > X | FW Retract ..." "$3" + +# clean up +restore_configs diff --git a/buildroot/tests/rambo-tests b/buildroot/tests/rambo-tests deleted file mode 100644 index ec8af16c23b4..000000000000 --- a/buildroot/tests/rambo-tests +++ /dev/null @@ -1,75 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for AVR ATmega2560 RAMBo -# - -# exit on first failure -set -e - -# -# Lots of options - Formerly the first Mega2560 test -# -restore_configs -opt_set MOTHERBOARD BOARD_RAMBO -opt_set EXTRUDERS 2 -opt_set TEMP_SENSOR_0 -2 -opt_set TEMP_SENSOR_1 1 -opt_set TEMP_SENSOR_BED 2 -opt_set TEMP_SENSOR_PROBE 1 -opt_add TEMP_PROBE_PIN 12 -opt_set TEMP_SENSOR_CHAMBER 3 -opt_add TEMP_CHAMBER_PIN 3 -opt_add HEATER_CHAMBER_PIN 45 -opt_set GRID_MAX_POINTS_X 16 -opt_set FANMUX0_PIN 53 -opt_disable USE_WATCHDOG -opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER LCD_PROGRESS_BAR LCD_PROGRESS_BAR_TEST \ - FIX_MOUNTED_PROBE Z_SAFE_HOMING CODEPENDENT_XY_HOMING PIDTEMPBED PROBE_TEMP_COMPENSATION \ - PROBING_HEATERS_OFF PROBING_FANS_OFF PROBING_STEPPERS_OFF WAIT_FOR_BED_HEATER \ - EEPROM_SETTINGS SDSUPPORT SD_REPRINT_LAST_SELECTED_FILE BINARY_FILE_TRANSFER \ - BLINKM PCA9533 PCA9632 RGB_LED RGB_LED_R_PIN RGB_LED_G_PIN RGB_LED_B_PIN LED_CONTROL_MENU \ - NEOPIXEL_LED CASE_LIGHT_ENABLE CASE_LIGHT_USE_NEOPIXEL CASE_LIGHT_MENU \ - PID_PARAMS_PER_HOTEND PID_AUTOTUNE_MENU PID_EDIT_MENU LCD_SHOW_E_TOTAL \ - PRINTCOUNTER SERVICE_NAME_1 SERVICE_INTERVAL_1 LEVEL_BED_CORNERS \ - NOZZLE_PARK_FEATURE FILAMENT_RUNOUT_SENSOR FILAMENT_RUNOUT_DISTANCE_MM \ - ADVANCED_PAUSE_FEATURE FILAMENT_LOAD_UNLOAD_GCODES FILAMENT_UNLOAD_ALL_EXTRUDERS \ - PASSWORD_FEATURE PASSWORD_ON_STARTUP PASSWORD_ON_SD_PRINT_MENU PASSWORD_AFTER_SD_PRINT_END PASSWORD_AFTER_SD_PRINT_ABORT \ - AUTO_BED_LEVELING_BILINEAR Z_MIN_PROBE_REPEATABILITY_TEST DISTINCT_E_FACTORS \ - SKEW_CORRECTION SKEW_CORRECTION_FOR_Z SKEW_CORRECTION_GCODE \ - BACKLASH_COMPENSATION BACKLASH_GCODE BAUD_RATE_GCODE BEZIER_CURVE_SUPPORT \ - FWRETRACT ARC_P_CIRCLES CNC_WORKSPACE_PLANES CNC_COORDINATE_SYSTEMS \ - PSU_CONTROL AUTO_POWER_CONTROL POWER_LOSS_RECOVERY POWER_LOSS_PIN POWER_LOSS_STATE \ - SLOW_PWM_HEATERS THERMAL_PROTECTION_CHAMBER LIN_ADVANCE EXTRA_LIN_ADVANCE_K \ - HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT 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 ..." - -# -# Full size Rambo Dual Endstop CNC -# -restore_configs -opt_set MOTHERBOARD BOARD_RAMBO -opt_set EXTRUDERS 0 -opt_set TEMP_SENSOR_0 999 -opt_set DUMMY_THERMISTOR_999_VALUE 170 -opt_set DIGIPOT_MOTOR_CURRENT '{ 120, 120, 120, 120, 120 }' -opt_enable USE_XMAX_PLUG USE_YMAX_PLUG USE_ZMAX_PLUG \ - REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER REVERSE_ENCODER_DIRECTION SDSUPPORT EEPROM_SETTINGS \ - S_CURVE_ACCELERATION X_DUAL_STEPPER_DRIVERS X_DUAL_ENDSTOPS Y_DUAL_STEPPER_DRIVERS Y_DUAL_ENDSTOPS \ - ADAPTIVE_STEP_SMOOTHING CNC_COORDINATE_SYSTEMS GCODE_MOTION_MODES -opt_disable MIN_SOFTWARE_ENDSTOP_Z MAX_SOFTWARE_ENDSTOPS -exec_test $1 $2 "Rambo CNC Configuration" - -# -# Build with the default configurations -# -restore_configs -opt_set MOTHERBOARD BOARD_EINSY_RAMBO -opt_set X_DRIVER_TYPE TMC2130 -opt_set Y_DRIVER_TYPE TMC2130 -opt_set Z_DRIVER_TYPE TMC2130 -opt_set E0_DRIVER_TYPE TMC2130 -exec_test $1 $2 "Einsy RAMBo with TMC2130" - -# clean up -restore_configs diff --git a/buildroot/tests/rumba32 b/buildroot/tests/rumba32 new file mode 100755 index 000000000000..f26af33610c6 --- /dev/null +++ b/buildroot/tests/rumba32 @@ -0,0 +1,31 @@ +#!/usr/bin/env bash +# +# Build tests for rumba32 +# + +# exit on first failure +set -e + +# Build examples +restore_configs +opt_set MOTHERBOARD BOARD_RUMBA32_V1_0 SERIAL_PORT -1 \ + TEMP_SENSOR_BED 1 X_DRIVER_TYPE TMC2130 +opt_disable PIDTEMP +opt_enable PIDTEMPBED +opt_disable THERMAL_PROTECTION_BED +exec_test $1 $2 "RUMBA32 V1.0 with TMC2130, PID Bed, and bed thermal protection disabled" "$3" + +# Build examples +restore_configs +opt_set MOTHERBOARD BOARD_RUMBA32_V1_1 SERIAL_PORT -1 \ + TEMP_SENSOR_BED 1 X_DRIVER_TYPE TMC2130 Y_DRIVER_TYPE TMC2208 +opt_enable PIDTEMPBED EEPROM_SETTINGS EEPROM_CHITCHAT REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER +exec_test $1 $2 "RUMBA32 V1.1 with TMC2130, TMC2208, PID Bed, EEPROM settings, and graphic LCD controller" "$3" + +# Build examples +restore_configs +opt_set MOTHERBOARD BOARD_RUMBA32_MKS SERIAL_PORT -1 X_DRIVER_TYPE TMC2130 Y_DRIVER_TYPE TMC2208 +exec_test $1 $2 "RUMBA32 MKS Default Config with Mixed TMC Drivers" "$3" + +# cleanup +restore_configs diff --git a/buildroot/tests/rumba32-tests b/buildroot/tests/rumba32-tests deleted file mode 100644 index 42f9beb9afde..000000000000 --- a/buildroot/tests/rumba32-tests +++ /dev/null @@ -1,39 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for rumba32 -# - -# exit on first failure -set -e - -# Build examples -restore_configs -opt_set MOTHERBOARD BOARD_RUMBA32_V1_0 -opt_set SERIAL_PORT -1 -opt_disable PIDTEMP -opt_enable PIDTEMPBED -opt_set TEMP_SENSOR_BED 1 -opt_disable THERMAL_PROTECTION_BED -opt_set X_DRIVER_TYPE TMC2130 -exec_test $1 $2 "RUMBA32 V1.0 with TMC2130, PID Bed, and bed thermal protection disabled" - -# Build examples -restore_configs -opt_set MOTHERBOARD BOARD_RUMBA32_V1_1 -opt_set SERIAL_PORT -1 -opt_enable PIDTEMPBED EEPROM_SETTINGS EEPROM_CHITCHAT REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER -opt_set TEMP_SENSOR_BED 1 -opt_set X_DRIVER_TYPE TMC2130 -opt_set Y_DRIVER_TYPE TMC2208 -exec_test $1 $2 "RUMBA32 V1.1 with TMC2130, TMC2208, PID Bed, EEPROM settings, and graphic LCD controller" - -# Build examples -restore_configs -opt_set MOTHERBOARD BOARD_RUMBA32_MKS -opt_set SERIAL_PORT -1 -opt_set X_DRIVER_TYPE TMC2130 -opt_set Y_DRIVER_TYPE TMC2208 -exec_test $1 $2 "RUMBA32 MKS Default Config with Mixed TMC Drivers" - -# cleanup -restore_configs diff --git a/buildroot/tests/run_tests b/buildroot/tests/run_tests deleted file mode 100755 index d01107f45a15..000000000000 --- a/buildroot/tests/run_tests +++ /dev/null @@ -1,41 +0,0 @@ -#!/usr/bin/env bash -# -# run_tests -# -export PATH="$PATH:$( cd "$(dirname "${BASH_SOURCE[0]}")" ; pwd -P )" -export PATH="$PATH:./buildroot/bin" - -# exit on first failure -set -e - -exec_test () { - printf "\n\033[0;32m[Test $2] \033[0m$3...\n" - if platformio run --project-dir $1 -e $2 --silent; then - printf "\033[0;32mPassed\033[0m\n" - return 0 - else - git reset --hard HEAD - printf "\033[0;31mFailed!\033[0m\n" - return 1 - fi -} -export -f exec_test - -printf "Running \033[0;32m$2\033[0m Tests\n" - -if [[ $2 = "ALL" ]]; then - dir_list=("$(dirname "${BASH_SOURCE[0]}")"/*) - declare -a tests=(${dir_list[@]/*run_tests/}) - for f in "${tests[@]}"; do - testenv=$(basename $f | cut -d"-" -f1) - printf "Running \033[0;32m$f\033[0m Tests\n" - exec_test $1 "$testenv --target clean" "Setup Build Environment" - $f $1 $testenv - git reset --hard HEAD - done -else - exec_test $1 "$2 --target clean" "Setup Build Environment" - $2-tests $1 $2 - git reset --hard HEAD -fi -printf "\033[0;32mAll tests completed successfully\033[0m\n" diff --git a/buildroot/tests/sanguino1284p b/buildroot/tests/sanguino1284p new file mode 100755 index 000000000000..7c2aa61f69be --- /dev/null +++ b/buildroot/tests/sanguino1284p @@ -0,0 +1,28 @@ +#!/usr/bin/env bash +# +# Build tests for AVR ATmega 1284p +# + +# exit on first failure +set -e + +# +# Start with default configurations... +# +restore_configs +opt_set MOTHERBOARD BOARD_SANGUINOLOLU_12 \ + LCD_LANGUAGE de \ + CONTROLLER_FAN_PIN 27 +opt_enable MINIPANEL USE_CONTROLLER_FAN CONTROLLER_FAN_EDITABLE +exec_test $1 $2 "Default Configuration | MINIPANAL | CONTROLLER_FAN" "$3" + +# +# Start with default configurations... +# +restore_configs +opt_set MOTHERBOARD BOARD_MELZI +opt_enable ZONESTAR_LCD +exec_test $1 $2 "Default Configuration | ZONESTAR_LCD " "$3" + +# clean up +restore_configs diff --git a/buildroot/tests/sanguino1284p-tests b/buildroot/tests/sanguino1284p-tests deleted file mode 100644 index 7181f961c483..000000000000 --- a/buildroot/tests/sanguino1284p-tests +++ /dev/null @@ -1,17 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for AVR ATmega 1284p -# - -# exit on first failure -set -e - -# -# Build with the default configurations -# -restore_configs -opt_set MOTHERBOARD BOARD_SANGUINOLOLU_12 -exec_test $1 $2 "Default Configuration" - -# clean up -restore_configs diff --git a/buildroot/tests/sanguino644p b/buildroot/tests/sanguino644p new file mode 100755 index 000000000000..12910a76fab8 --- /dev/null +++ b/buildroot/tests/sanguino644p @@ -0,0 +1,17 @@ +#!/usr/bin/env bash +# +# Build tests for AVR ATmega 644p +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +restore_configs +opt_set MOTHERBOARD BOARD_SANGUINOLOLU_12 +exec_test $1 $2 "Default Configuration" "$3" + +# clean up +restore_configs diff --git a/buildroot/tests/sanguino644p-tests b/buildroot/tests/sanguino644p-tests deleted file mode 100644 index 41626b23f705..000000000000 --- a/buildroot/tests/sanguino644p-tests +++ /dev/null @@ -1,17 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for AVR ATmega 644p -# - -# exit on first failure -set -e - -# -# Build with the default configurations -# -restore_configs -opt_set MOTHERBOARD BOARD_SANGUINOLOLU_12 -exec_test $1 $2 "Default Configuration" - -# clean up -restore_configs diff --git a/buildroot/tests/teensy31 b/buildroot/tests/teensy31 new file mode 100755 index 000000000000..10dde2be99ad --- /dev/null +++ b/buildroot/tests/teensy31 @@ -0,0 +1,37 @@ +#!/usr/bin/env bash +# +# Build tests for Teensy 3.1/3.2 (ARM Cortex-M4) +# + +# exit on first failure +set -e + +restore_configs +opt_set MOTHERBOARD BOARD_TEENSY31_32 +exec_test $1 $2 "Teensy3.1 with default config" "$3" + +# +# Zero endstops, as with a CNC +# +restore_configs +opt_set MOTHERBOARD BOARD_TEENSY31_32 +opt_disable USE_XMIN_PLUG USE_YMIN_PLUG USE_ZMIN_PLUG +exec_test $1 $2 "Teensy3.1 with Zero Endstops" "$3" + +# +# Test many features together +# +restore_configs +opt_set MOTHERBOARD BOARD_TEENSY31_32 \ + TEMP_SENSOR_0 1 TEMP_SENSOR_BED 1 \ + I2C_SLAVE_ADDRESS 63 \ + GRID_MAX_POINTS_X 16 +opt_enable EEPROM_SETTINGS FILAMENT_WIDTH_SENSOR CALIBRATION_GCODE BAUD_RATE_GCODE \ + FIX_MOUNTED_PROBE Z_SAFE_HOMING AUTO_BED_LEVELING_BILINEAR DEBUG_LEVELING_FEATURE Z_MIN_PROBE_REPEATABILITY_TEST \ + BABYSTEPPING BABYSTEP_XY BABYSTEP_ZPROBE_OFFSET PRINTCOUNTER SLOW_PWM_HEATERS PIDTEMPBED \ + INCH_MODE_SUPPORT TEMPERATURE_UNITS_SUPPORT M100_FREE_MEMORY_WATCHER \ + 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 +exec_test $1 $2 "Teensy3.1 with many features" "$3" diff --git a/buildroot/tests/teensy31-tests b/buildroot/tests/teensy31-tests deleted file mode 100755 index be377b15afa5..000000000000 --- a/buildroot/tests/teensy31-tests +++ /dev/null @@ -1,30 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for Teensy 3.1/3.2 (ARM Cortex-M4) -# - -# exit on first failure -set -e - -restore_configs -opt_set MOTHERBOARD BOARD_TEENSY31_32 -exec_test $1 $2 "Teensy3.1 with default config" - -# -# Test many features together -# -restore_configs -opt_set MOTHERBOARD BOARD_TEENSY31_32 -opt_set TEMP_SENSOR_0 1 -opt_set TEMP_SENSOR_BED 1 -opt_enable EEPROM_SETTINGS FILAMENT_WIDTH_SENSOR CALIBRATION_GCODE BAUD_RATE_GCODE \ - FIX_MOUNTED_PROBE Z_SAFE_HOMING AUTO_BED_LEVELING_BILINEAR DEBUG_LEVELING_FEATURE Z_MIN_PROBE_REPEATABILITY_TEST \ - BABYSTEPPING BABYSTEP_XY BABYSTEP_ZPROBE_OFFSET PRINTCOUNTER SLOW_PWM_HEATERS PIDTEMPBED \ - INCH_MODE_SUPPORT TEMPERATURE_UNITS_SUPPORT M100_FREE_MEMORY_WATCHER \ - 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 -opt_set I2C_SLAVE_ADDRESS 63 -opt_set GRID_MAX_POINTS_X 16 -exec_test $1 $2 "Teensy3.1 with many features" diff --git a/buildroot/tests/teensy35 b/buildroot/tests/teensy35 new file mode 100755 index 000000000000..09e8cee58ef3 --- /dev/null +++ b/buildroot/tests/teensy35 @@ -0,0 +1,110 @@ +#!/usr/bin/env bash +# +# Build tests for Teensy 3.5/3.6 (ARM Cortex-M4) +# + +# exit on first failure +set -e + +restore_configs +opt_set MOTHERBOARD BOARD_TEENSY35_36 +exec_test $1 $2 "Teensy3.5 with default config" "$3" + +# +# Test as many features together as possible +# +restore_configs +opt_set MOTHERBOARD BOARD_TEENSY35_36 \ + EXTRUDERS 2 TEMP_SENSOR_0 1 TEMP_SENSOR_1 5 TEMP_SENSOR_BED 1 \ + I2C_SLAVE_ADDRESS 63 \ + GRID_MAX_POINTS_X 16 \ + NOZZLE_CLEAN_START_POINT "{ { 10, 10, 3 }, { 10, 10, 3 } }" \ + NOZZLE_CLEAN_END_POINT "{ { 10, 20, 3 }, { 10, 20, 3 } }" +opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER LCD_INFO_MENU SDSUPPORT SDCARD_SORT_ALPHA \ + 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 +exec_test $1 $2 "Teensy3.5 with many features" "$3" + +# +# Test a Sled Z Probe with Linear leveling +# +restore_configs +opt_set MOTHERBOARD BOARD_TEENSY35_36 +opt_enable EEPROM_SETTINGS Z_PROBE_SLED Z_SAFE_HOMING AUTO_BED_LEVELING_LINEAR DEBUG_LEVELING_FEATURE GCODE_MACROS +exec_test $1 $2 "Sled Z Probe with Linear leveling" "$3" + +# +# Test a Servo Probe +# +# restore_configs +# opt_set MOTHERBOARD BOARD_TEENSY35_36 NUM_SERVOS 1 +# opt_enable Z_PROBE_SERVO_NR Z_SERVO_ANGLES DEACTIVATE_SERVOS_AFTER_MOVE \ +# AUTO_BED_LEVELING_3POINT DEBUG_LEVELING_FEATURE EEPROM_SETTINGS +# exec_test $1 $2 "Servo Probe" +# +# ...with AUTO_BED_LEVELING_3POINT, DEBUG_LEVELING_FEATURE, EEPROM_SETTINGS, EEPROM_CHITCHAT, EXTENDED_CAPABILITIES_REPORT, and AUTO_REPORT_TEMPERATURES +# +# opt_enable AUTO_BED_LEVELING_3POINT DEBUG_LEVELING_FEATURE EEPROM_SETTINGS \ +# EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES +# exec_test $1 $2 "...with AUTO_BED_LEVELING_3POINT, DEBUG_LEVELING_FEATURE, EEPROM_SETTINGS, EEPROM_CHITCHAT, EXTENDED_CAPABILITIES_REPORT, and AUTO_REPORT_TEMPERATURES" + +# +# Test MAGNETIC_PARKING_EXTRUDER with LCD +# +restore_configs +opt_set MOTHERBOARD BOARD_TEENSY35_36 EXTRUDERS 2 TEMP_SENSOR_1 1 SOL0_PIN 29 EXTRUDERS 2 +opt_enable PARKING_EXTRUDER ULTIMAKERCONTROLLER +exec_test $1 $2 "PARKING_EXTRUDER with LCD" "$3" + +# +# Mixing Extruder +# +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 +exec_test $1 $2 "Mixing Extruder" "$3" + +# +# Test SWITCHING_EXTRUDER +# +# restore_configs +# opt_set MOTHERBOARD BOARD_TEENSY35_36 EXTRUDERS 2 NUM_SERVOS 1 +# opt_enable SWITCHING_EXTRUDER ULTIMAKERCONTROLLER +# exec_test $1 $2 "SWITCHING_EXTRUDER" + +# +# Enable COREXY +# +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_CS_PIN 46 Y_CS_PIN 47 +opt_enable COREXY USE_ZMIN_PLUG MONITOR_DRIVER_STATUS SENSORLESS_HOMING +exec_test $1 $2 "Teensy 3.5/3.6 COREXY" "$3" + +# +# Enable COREXZ +# +restore_configs +opt_set MOTHERBOARD BOARD_TEENSY35_36 +opt_enable COREXZ BACKLASH_COMPENSATION BACKLASH_GCODE CORE_BACKLASH +exec_test $1 $2 "Teensy 3.5/3.6 COREXZ | BACKLASH" "$3" + +# +# Enable Dual Z with Dual Z endstops +# +restore_configs +opt_set MOTHERBOARD BOARD_TEENSY35_36 NUM_Z_STEPPER_DRIVERS 2 Z2_MIN_PIN 2 +opt_enable Z_MULTI_ENDSTOPS USE_XMAX_PLUG +pins_set ramps/RAMPS X_MAX_PIN -1 +exec_test $1 $2 "Dual Z with Dual Z endstops" "$3" + +# Clean up +restore_configs diff --git a/buildroot/tests/teensy35-tests b/buildroot/tests/teensy35-tests deleted file mode 100755 index c729f212a427..000000000000 --- a/buildroot/tests/teensy35-tests +++ /dev/null @@ -1,123 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for Teensy 3.5/3.6 (ARM Cortex-M4) -# - -# exit on first failure -set -e - -restore_configs -opt_set MOTHERBOARD BOARD_TEENSY35_36 -exec_test $1 $2 "Teensy3.5 with default config" - -# -# Test as many features together as possible -# -restore_configs -opt_set MOTHERBOARD BOARD_TEENSY35_36 -opt_set EXTRUDERS 2 -opt_set TEMP_SENSOR_0 1 -opt_set TEMP_SENSOR_1 5 -opt_set TEMP_SENSOR_BED 1 -opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER LCD_INFO_MENU SDSUPPORT SDCARD_SORT_ALPHA \ - FILAMENT_WIDTH_SENSOR FILAMENT_LCD_DISPLAY CALIBRATION_GCODE BAUD_RATE_GCODE \ - FIX_MOUNTED_PROBE Z_SAFE_HOMING AUTO_BED_LEVELING_BILINEAR Z_MIN_PROBE_REPEATABILITY_TEST DEBUG_LEVELING_FEATURE \ - BABYSTEPPING BABYSTEP_XY BABYSTEP_ZPROBE_OFFSET 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 -opt_set I2C_SLAVE_ADDRESS 63 -opt_set GRID_MAX_POINTS_X 16 -exec_test $1 $2 "Teensy3.5 with many features" - -# -# Test a Sled Z Probe with Linear leveling -# -restore_configs -opt_set MOTHERBOARD BOARD_TEENSY35_36 -opt_enable EEPROM_SETTINGS Z_PROBE_SLED Z_SAFE_HOMING AUTO_BED_LEVELING_LINEAR DEBUG_LEVELING_FEATURE GCODE_MACROS -exec_test $1 $2 "Sled Z Probe with Linear leveling" - -# -# Test a Servo Probe -# -# restore_configs -# opt_set MOTHERBOARD BOARD_TEENSY35_36 -# opt_enable Z_PROBE_SERVO_NR Z_SERVO_ANGLES DEACTIVATE_SERVOS_AFTER_MOVE \ -# AUTO_BED_LEVELING_3POINT DEBUG_LEVELING_FEATURE EEPROM_SETTINGS -# opt_set NUM_SERVOS 1 -# exec_test $1 $2 "Servo Probe" -# -# ...with AUTO_BED_LEVELING_3POINT, DEBUG_LEVELING_FEATURE, EEPROM_SETTINGS, EEPROM_CHITCHAT, EXTENDED_CAPABILITIES_REPORT, and AUTO_REPORT_TEMPERATURES -# -# opt_enable AUTO_BED_LEVELING_3POINT DEBUG_LEVELING_FEATURE EEPROM_SETTINGS \ -# EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES -# exec_test $1 $2 "...with AUTO_BED_LEVELING_3POINT, DEBUG_LEVELING_FEATURE, EEPROM_SETTINGS, EEPROM_CHITCHAT, EXTENDED_CAPABILITIES_REPORT, and AUTO_REPORT_TEMPERATURES" - -# -# Test MAGNETIC_PARKING_EXTRUDER with LCD -# -restore_configs -opt_set MOTHERBOARD BOARD_TEENSY35_36 -opt_set EXTRUDERS 2 -opt_set TEMP_SENSOR_1 1 -opt_enable MAGNETIC_PARKING_EXTRUDER ULTIMAKERCONTROLLER -exec_test $1 $2 "MAGNETIC_PARKING_EXTRUDER with LCD" - -# -# Mixing Extruder -# -restore_configs -opt_set MOTHERBOARD BOARD_TEENSY35_36 -opt_enable MIXING_EXTRUDER DIRECT_MIXING_IN_G1 GRADIENT_MIX GRADIENT_VTOOL REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER -opt_set MIXING_STEPPERS 2 -exec_test $1 $2 "Mixing Extruder" - -# -# Test SWITCHING_EXTRUDER -# -# restore_configs -# opt_set MOTHERBOARD BOARD_TEENSY35_36 -# opt_set EXTRUDERS 2 -# opt_set NUM_SERVOS 1 -# opt_enable SWITCHING_EXTRUDER ULTIMAKERCONTROLLER -# exec_test $1 $2 "SWITCHING_EXTRUDER" - -# -# Enable COREXY -# -restore_configs -opt_set MOTHERBOARD BOARD_TEENSY35_36 -opt_enable COREXY -opt_set X_DRIVER_TYPE TMC5160 -opt_set Y_DRIVER_TYPE TMC5160 -opt_set X_MIN_ENDSTOP_INVERTING true -opt_set Y_MIN_ENDSTOP_INVERTING true -opt_add X_CS_PIN 46 -opt_add Y_CS_PIN 47 -opt_enable USE_ZMIN_PLUG MONITOR_DRIVER_STATUS SENSORLESS_HOMING -exec_test $1 $2 "Teensy 3.5/3.6 COREXY" - -# -# Enable COREXZ -# -restore_configs -opt_set MOTHERBOARD BOARD_TEENSY35_36 -opt_enable COREXZ -exec_test $1 $2 "Teensy 3.5/3.6 COREXZ" - -# -# Enable Dual Z with Dual Z endstops -# -restore_configs -opt_set MOTHERBOARD BOARD_TEENSY35_36 -opt_enable Z_MULTI_ENDSTOPS -opt_set NUM_Z_STEPPER_DRIVERS 2 -pins_set ramps/RAMPS X_MAX_PIN -1 -opt_add Z2_MAX_PIN 2 -opt_enable USE_XMAX_PLUG -exec_test $1 $2 "Dual Z with Dual Z endstops" - -# Clean up -restore_configs diff --git a/buildroot/tests/teensy41 b/buildroot/tests/teensy41 new file mode 100755 index 000000000000..fd89512ea57b --- /dev/null +++ b/buildroot/tests/teensy41 @@ -0,0 +1,113 @@ +#!/usr/bin/env bash +# +# Build tests for Teensy 4.0/4.1 (ARM Cortex-M7) +# + +# exit on first failure +set -e + +restore_configs +opt_set MOTHERBOARD BOARD_TEENSY41 +exec_test $1 $2 "Teensy4.1 with default config" "$3" + +# +# Test as many features together as possible +# +restore_configs +opt_set MOTHERBOARD BOARD_TEENSY41 \ + EXTRUDERS 2 TEMP_SENSOR_0 1 TEMP_SENSOR_1 5 TEMP_SENSOR_BED 1 \ + I2C_SLAVE_ADDRESS 63 \ + GRID_MAX_POINTS_X 16 \ + NOZZLE_CLEAN_START_POINT "{ { 10, 10, 3 }, { 10, 10, 3 } }" \ + NOZZLE_CLEAN_END_POINT "{ { 10, 20, 3 }, { 10, 20, 3 } }" +opt_enable EXTENSIBLE_UI LCD_INFO_MENU SDSUPPORT SDCARD_SORT_ALPHA \ + FILAMENT_LCD_DISPLAY CALIBRATION_GCODE BAUD_RATE_GCODE \ + FIX_MOUNTED_PROBE Z_SAFE_HOMING AUTO_BED_LEVELING_BILINEAR Z_MIN_PROBE_REPEATABILITY_TEST DEBUG_LEVELING_FEATURE \ + BABYSTEPPING BABYSTEP_XY BABYSTEP_ZPROBE_OFFSET \ + 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 +opt_add EXTUI_EXAMPLE +exec_test $1 $2 "Teensy4.1 with many features" "$3" + +# +# Test a Sled Z Probe with Linear leveling +# +restore_configs +opt_set MOTHERBOARD BOARD_TEENSY41 +opt_enable EEPROM_SETTINGS Z_PROBE_SLED Z_SAFE_HOMING AUTO_BED_LEVELING_LINEAR DEBUG_LEVELING_FEATURE GCODE_MACROS +exec_test $1 $2 "Sled Z Probe with Linear leveling" "$3" + +# +# Test a Servo Probe +# +# restore_configs +# opt_set MOTHERBOARD BOARD_TEENSY41 +# opt_enable Z_PROBE_SERVO_NR Z_SERVO_ANGLES DEACTIVATE_SERVOS_AFTER_MOVE \ +# AUTO_BED_LEVELING_3POINT DEBUG_LEVELING_FEATURE EEPROM_SETTINGS +# opt_set NUM_SERVOS 1 +# exec_test $1 $2 "Servo Probe" "$3" +# +# ...with AUTO_BED_LEVELING_3POINT, DEBUG_LEVELING_FEATURE, EEPROM_SETTINGS, EEPROM_CHITCHAT, EXTENDED_CAPABILITIES_REPORT, and AUTO_REPORT_TEMPERATURES +# +# opt_enable AUTO_BED_LEVELING_3POINT DEBUG_LEVELING_FEATURE EEPROM_SETTINGS \ +# EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES +# exec_test $1 $2 "...with AUTO_BED_LEVELING_3POINT, DEBUG_LEVELING_FEATURE, EEPROM_SETTINGS, EEPROM_CHITCHAT, EXTENDED_CAPABILITIES_REPORT, and AUTO_REPORT_TEMPERATURES" "$3" + +# +# Test MAGNETIC_PARKING_EXTRUDER with no LCD +# +restore_configs +opt_set MOTHERBOARD BOARD_TEENSY41 SERIAL_PORT_2 -2 \ + EXTRUDERS 2 TEMP_SENSOR_1 1 +opt_enable EEPROM_SETTINGS MAGNETIC_PARKING_EXTRUDER +exec_test $1 $2 "Ethernet, EEPROM, Magnetic Parking Extruder, No LCD" "$3" + +# +# Mixing Extruder +# +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 +exec_test $1 $2 "Mixing Extruder" "$3" + +# +# Test SWITCHING_EXTRUDER +# +# restore_configs +# opt_set MOTHERBOARD BOARD_TEENSY41 EXTRUDERS 2 NUM_SERVOS 1 +# opt_enable SWITCHING_EXTRUDER ULTIMAKERCONTROLLER +# exec_test $1 $2 "SWITCHING_EXTRUDER" "$3" + +# +# Enable COREXY +# +restore_configs +opt_set MOTHERBOARD BOARD_TEENSY41 \ + X_DRIVER_TYPE TMC5160 Y_DRIVER_TYPE TMC5160 \ + X_MIN_ENDSTOP_INVERTING true Y_MIN_ENDSTOP_INVERTING true \ + X_CS_PIN 46 Y_CS_PIN 47 +opt_enable COREXY USE_ZMIN_PLUG MONITOR_DRIVER_STATUS SENSORLESS_HOMING +exec_test $1 $2 "Teensy 4.0/4.1 COREXY" "$3" + +# +# Enable COREXZ +# +restore_configs +opt_set MOTHERBOARD BOARD_TEENSY41 +opt_enable COREXZ +exec_test $1 $2 "Teensy 4.0/4.1 COREXZ" "$3" + +# +# Enable Dual Z with Dual Z endstops +# +restore_configs +opt_set MOTHERBOARD BOARD_TEENSY41 NUM_Z_STEPPER_DRIVERS 2 Z2_MIN_PIN 2 +opt_enable Z_MULTI_ENDSTOPS USE_XMAX_PLUG +pins_set ramps/RAMPS X_MAX_PIN -1 +exec_test $1 $2 "Dual Z with Dual Z endstops" "$3" + +# Clean up +restore_configs diff --git a/buildroot/tests/teensy41-tests b/buildroot/tests/teensy41-tests deleted file mode 100644 index 8d32d131e91c..000000000000 --- a/buildroot/tests/teensy41-tests +++ /dev/null @@ -1,124 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for Teensy 4.0/4.1 (ARM Cortex-M7) -# - -# exit on first failure -set -e - -restore_configs -opt_set MOTHERBOARD BOARD_TEENSY41 -exec_test $1 $2 "Teensy4.1 with default config" - -# -# Test as many features together as possible -# -restore_configs -opt_set MOTHERBOARD BOARD_TEENSY41 -opt_set EXTRUDERS 2 -opt_set TEMP_SENSOR_0 1 -opt_set TEMP_SENSOR_1 5 -opt_set TEMP_SENSOR_BED 1 -opt_enable EXTENSIBLE_UI LCD_INFO_MENU SDSUPPORT SDCARD_SORT_ALPHA \ - FILAMENT_LCD_DISPLAY CALIBRATION_GCODE BAUD_RATE_GCODE \ - FIX_MOUNTED_PROBE Z_SAFE_HOMING AUTO_BED_LEVELING_BILINEAR Z_MIN_PROBE_REPEATABILITY_TEST DEBUG_LEVELING_FEATURE \ - BABYSTEPPING BABYSTEP_XY BABYSTEP_ZPROBE_OFFSET \ - 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 -opt_add EXTUI_EXAMPLE -opt_set I2C_SLAVE_ADDRESS 63 -opt_set GRID_MAX_POINTS_X 16 -exec_test $1 $2 "Teensy4.1 with many features" - -# -# Test a Sled Z Probe with Linear leveling -# -restore_configs -opt_set MOTHERBOARD BOARD_TEENSY41 -opt_enable EEPROM_SETTINGS Z_PROBE_SLED Z_SAFE_HOMING AUTO_BED_LEVELING_LINEAR DEBUG_LEVELING_FEATURE GCODE_MACROS -exec_test $1 $2 "Sled Z Probe with Linear leveling" - -# -# Test a Servo Probe -# -# restore_configs -# opt_set MOTHERBOARD BOARD_TEENSY41 -# opt_enable Z_PROBE_SERVO_NR Z_SERVO_ANGLES DEACTIVATE_SERVOS_AFTER_MOVE \ -# AUTO_BED_LEVELING_3POINT DEBUG_LEVELING_FEATURE EEPROM_SETTINGS -# opt_set NUM_SERVOS 1 -# exec_test $1 $2 "Servo Probe" -# -# ...with AUTO_BED_LEVELING_3POINT, DEBUG_LEVELING_FEATURE, EEPROM_SETTINGS, EEPROM_CHITCHAT, EXTENDED_CAPABILITIES_REPORT, and AUTO_REPORT_TEMPERATURES -# -# opt_enable AUTO_BED_LEVELING_3POINT DEBUG_LEVELING_FEATURE EEPROM_SETTINGS \ -# EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES -# exec_test $1 $2 "...with AUTO_BED_LEVELING_3POINT, DEBUG_LEVELING_FEATURE, EEPROM_SETTINGS, EEPROM_CHITCHAT, EXTENDED_CAPABILITIES_REPORT, and AUTO_REPORT_TEMPERATURES" - -# -# Test MAGNETIC_PARKING_EXTRUDER with LCD -# -restore_configs -opt_set MOTHERBOARD BOARD_TEENSY41 -opt_set EXTRUDERS 2 -opt_set TEMP_SENSOR_1 1 -opt_enable MAGNETIC_PARKING_EXTRUDER -exec_test $1 $2 "MAGNETIC_PARKING_EXTRUDER with LCD" - -# -# Mixing Extruder -# -restore_configs -opt_set MOTHERBOARD BOARD_TEENSY41 -opt_enable MIXING_EXTRUDER DIRECT_MIXING_IN_G1 GRADIENT_MIX GRADIENT_VTOOL -opt_set MIXING_STEPPERS 2 -exec_test $1 $2 "Mixing Extruder" - -# -# Test SWITCHING_EXTRUDER -# -# restore_configs -# opt_set MOTHERBOARD BOARD_TEENSY41 -# opt_set EXTRUDERS 2 -# opt_set NUM_SERVOS 1 -# opt_enable SWITCHING_EXTRUDER ULTIMAKERCONTROLLER -# exec_test $1 $2 "SWITCHING_EXTRUDER" - -# -# Enable COREXY -# -restore_configs -opt_set MOTHERBOARD BOARD_TEENSY41 -opt_enable COREXY -opt_set X_DRIVER_TYPE TMC5160 -opt_set Y_DRIVER_TYPE TMC5160 -opt_set X_MIN_ENDSTOP_INVERTING true -opt_set Y_MIN_ENDSTOP_INVERTING true -opt_add X_CS_PIN 46 -opt_add Y_CS_PIN 47 -opt_enable USE_ZMIN_PLUG MONITOR_DRIVER_STATUS SENSORLESS_HOMING -exec_test $1 $2 "Teensy 4.0/4.1 COREXY" - -# -# Enable COREXZ -# -restore_configs -opt_set MOTHERBOARD BOARD_TEENSY41 -opt_enable COREXZ -exec_test $1 $2 "Teensy 4.0/4.1 COREXZ" - -# -# Enable Dual Z with Dual Z endstops -# -restore_configs -opt_set MOTHERBOARD BOARD_TEENSY41 -opt_enable Z_MULTI_ENDSTOPS -opt_set NUM_Z_STEPPER_DRIVERS 2 -pins_set ramps/RAMPS X_MAX_PIN -1 -opt_add Z2_MAX_PIN 2 -opt_enable USE_XMAX_PLUG -exec_test $1 $2 "Dual Z with Dual Z endstops" - -# Clean up -restore_configs diff --git a/buildroot/web-ui/data/www/bootstrap.min.css b/buildroot/web-ui/data/www/bootstrap.min.css new file mode 100644 index 000000000000..387b56b2ccf0 --- /dev/null +++ b/buildroot/web-ui/data/www/bootstrap.min.css @@ -0,0 +1,6 @@ +/*! + * Bootstrap v4.5.0 (https://getbootstrap.com/) + * Copyright 2011-2020 The Bootstrap Authors + * Copyright 2011-2020 Twitter, Inc. + * Licensed under MIT (https://github.com/twbs/bootstrap/blob/master/LICENSE) + */:root{--blue:#007bff;--indigo:#6610f2;--purple:#6f42c1;--pink:#e83e8c;--red:#dc3545;--orange:#fd7e14;--yellow:#ffc107;--green:#28a745;--teal:#20c997;--cyan:#17a2b8;--white:#fff;--gray:#6c757d;--gray-dark:#343a40;--primary:#007bff;--secondary:#6c757d;--success:#28a745;--info:#17a2b8;--warning:#ffc107;--danger:#dc3545;--light:#f8f9fa;--dark:#343a40;--breakpoint-xs:0;--breakpoint-sm:576px;--breakpoint-md:768px;--breakpoint-lg:992px;--breakpoint-xl:1200px;--font-family-sans-serif:-apple-system,BlinkMacSystemFont,"Segoe UI",Roboto,"Helvetica Neue",Arial,"Noto Sans",sans-serif,"Apple Color Emoji","Segoe UI Emoji","Segoe UI Symbol","Noto Color Emoji";--font-family-monospace:SFMono-Regular,Menlo,Monaco,Consolas,"Liberation Mono","Courier New",monospace}*,::after,::before{box-sizing:border-box}html{font-family:sans-serif;line-height:1.15;-webkit-text-size-adjust:100%;-webkit-tap-highlight-color:transparent}article,aside,figcaption,figure,footer,header,hgroup,main,nav,section{display:block}body{margin:0;font-family:-apple-system,BlinkMacSystemFont,"Segoe UI",Roboto,"Helvetica Neue",Arial,"Noto Sans",sans-serif,"Apple Color Emoji","Segoe UI Emoji","Segoe UI Symbol","Noto Color Emoji";font-size:1rem;font-weight:400;line-height:1.5;color:#212529;text-align:left;background-color:#fff}[tabindex="-1"]:focus:not(:focus-visible){outline:0!important}hr{box-sizing:content-box;height:0;overflow:visible}h1,h2,h3,h4,h5,h6{margin-top:0;margin-bottom:.5rem}p{margin-top:0;margin-bottom:1rem}abbr[data-original-title],abbr[title]{text-decoration:underline;-webkit-text-decoration:underline dotted;text-decoration:underline dotted;cursor:help;border-bottom:0;-webkit-text-decoration-skip-ink:none;text-decoration-skip-ink:none}address{margin-bottom:1rem;font-style:normal;line-height:inherit}dl,ol,ul{margin-top:0;margin-bottom:1rem}ol ol,ol ul,ul ol,ul ul{margin-bottom:0}dt{font-weight:700}dd{margin-bottom:.5rem;margin-left:0}blockquote{margin:0 0 1rem}b,strong{font-weight:bolder}small{font-size:80%}sub,sup{position:relative;font-size:75%;line-height:0;vertical-align:baseline}sub{bottom:-.25em}sup{top:-.5em}a{color:#007bff;text-decoration:none;background-color:transparent}a:hover{color:#0056b3;text-decoration:underline}a:not([href]){color:inherit;text-decoration:none}a:not([href]):hover{color:inherit;text-decoration:none}code,kbd,pre,samp{font-family:SFMono-Regular,Menlo,Monaco,Consolas,"Liberation Mono","Courier New",monospace;font-size:1em}pre{margin-top:0;margin-bottom:1rem;overflow:auto;-ms-overflow-style:scrollbar}figure{margin:0 0 1rem}img{vertical-align:middle;border-style:none}svg{overflow:hidden;vertical-align:middle}table{border-collapse:collapse}caption{padding-top:.75rem;padding-bottom:.75rem;color:#6c757d;text-align:left;caption-side:bottom}th{text-align:inherit}label{display:inline-block;margin-bottom:.5rem}button{border-radius:0}button:focus{outline:1px dotted;outline:5px auto -webkit-focus-ring-color}button,input,optgroup,select,textarea{margin:0;font-family:inherit;font-size:inherit;line-height:inherit}button,input{overflow:visible}button,select{text-transform:none}[role=button]{cursor:pointer}select{word-wrap:normal}[type=button],[type=reset],[type=submit],button{-webkit-appearance:button}[type=button]:not(:disabled),[type=reset]:not(:disabled),[type=submit]:not(:disabled),button:not(:disabled){cursor:pointer}[type=button]::-moz-focus-inner,[type=reset]::-moz-focus-inner,[type=submit]::-moz-focus-inner,button::-moz-focus-inner{padding:0;border-style:none}input[type=checkbox],input[type=radio]{box-sizing:border-box;padding:0}textarea{overflow:auto;resize:vertical}fieldset{min-width:0;padding:0;margin:0;border:0}legend{display:block;width:100%;max-width:100%;padding:0;margin-bottom:.5rem;font-size:1.5rem;line-height:inherit;color:inherit;white-space:normal}progress{vertical-align:baseline}[type=number]::-webkit-inner-spin-button,[type=number]::-webkit-outer-spin-button{height:auto}[type=search]{outline-offset:-2px;-webkit-appearance:none}[type=search]::-webkit-search-decoration{-webkit-appearance:none}::-webkit-file-upload-button{font:inherit;-webkit-appearance:button}output{display:inline-block}summary{display:list-item;cursor:pointer}template{display:none}[hidden]{display:none!important}.h1,.h2,.h3,.h4,.h5,.h6,h1,h2,h3,h4,h5,h6{margin-bottom:.5rem;font-weight:500;line-height:1.2}.h1,h1{font-size:2.5rem}.h2,h2{font-size:2rem}.h3,h3{font-size:1.75rem}.h4,h4{font-size:1.5rem}.h5,h5{font-size:1.25rem}.h6,h6{font-size:1rem}.lead{font-size:1.25rem;font-weight:300}.display-1{font-size:6rem;font-weight:300;line-height:1.2}.display-2{font-size:5.5rem;font-weight:300;line-height:1.2}.display-3{font-size:4.5rem;font-weight:300;line-height:1.2}.display-4{font-size:3.5rem;font-weight:300;line-height:1.2}hr{margin-top:1rem;margin-bottom:1rem;border:0;border-top:1px solid rgba(0,0,0,.1)}.small,small{font-size:80%;font-weight:400}.mark,mark{padding:.2em;background-color:#fcf8e3}.list-unstyled{padding-left:0;list-style:none}.list-inline{padding-left:0;list-style:none}.list-inline-item{display:inline-block}.list-inline-item:not(:last-child){margin-right:.5rem}.initialism{font-size:90%;text-transform:uppercase}.blockquote{margin-bottom:1rem;font-size:1.25rem}.blockquote-footer{display:block;font-size:80%;color:#6c757d}.blockquote-footer::before{content:"\2014\00A0"}.img-fluid{max-width:100%;height:auto}.img-thumbnail{padding:.25rem;background-color:#fff;border:1px solid #dee2e6;border-radius:.25rem;max-width:100%;height:auto}.figure{display:inline-block}.figure-img{margin-bottom:.5rem;line-height:1}.figure-caption{font-size:90%;color:#6c757d}code{font-size:87.5%;color:#e83e8c;word-wrap:break-word}a>code{color:inherit}kbd{padding:.2rem .4rem;font-size:87.5%;color:#fff;background-color:#212529;border-radius:.2rem}kbd kbd{padding:0;font-size:100%;font-weight:700}pre{display:block;font-size:87.5%;color:#212529}pre code{font-size:inherit;color:inherit;word-break:normal}.pre-scrollable{max-height:340px;overflow-y:scroll}.container{width:100%;padding-right:15px;padding-left:15px;margin-right:auto;margin-left:auto}@media (min-width:576px){.container{max-width:540px}}@media (min-width:768px){.container{max-width:720px}}@media (min-width:992px){.container{max-width:960px}}@media (min-width:1200px){.container{max-width:1140px}}.container-fluid,.container-lg,.container-md,.container-sm,.container-xl{width:100%;padding-right:15px;padding-left:15px;margin-right:auto;margin-left:auto}@media (min-width:576px){.container,.container-sm{max-width:540px}}@media (min-width:768px){.container,.container-md,.container-sm{max-width:720px}}@media (min-width:992px){.container,.container-lg,.container-md,.container-sm{max-width:960px}}@media (min-width:1200px){.container,.container-lg,.container-md,.container-sm,.container-xl{max-width:1140px}}.row{display:-ms-flexbox;display:flex;-ms-flex-wrap:wrap;flex-wrap:wrap;margin-right:-15px;margin-left:-15px}.no-gutters{margin-right:0;margin-left:0}.no-gutters>.col,.no-gutters>[class*=col-]{padding-right:0;padding-left:0}.col,.col-1,.col-10,.col-11,.col-12,.col-2,.col-3,.col-4,.col-5,.col-6,.col-7,.col-8,.col-9,.col-auto,.col-lg,.col-lg-1,.col-lg-10,.col-lg-11,.col-lg-12,.col-lg-2,.col-lg-3,.col-lg-4,.col-lg-5,.col-lg-6,.col-lg-7,.col-lg-8,.col-lg-9,.col-lg-auto,.col-md,.col-md-1,.col-md-10,.col-md-11,.col-md-12,.col-md-2,.col-md-3,.col-md-4,.col-md-5,.col-md-6,.col-md-7,.col-md-8,.col-md-9,.col-md-auto,.col-sm,.col-sm-1,.col-sm-10,.col-sm-11,.col-sm-12,.col-sm-2,.col-sm-3,.col-sm-4,.col-sm-5,.col-sm-6,.col-sm-7,.col-sm-8,.col-sm-9,.col-sm-auto,.col-xl,.col-xl-1,.col-xl-10,.col-xl-11,.col-xl-12,.col-xl-2,.col-xl-3,.col-xl-4,.col-xl-5,.col-xl-6,.col-xl-7,.col-xl-8,.col-xl-9,.col-xl-auto{position:relative;width:100%;padding-right:15px;padding-left:15px}.col{-ms-flex-preferred-size:0;flex-basis:0;-ms-flex-positive:1;flex-grow:1;min-width:0;max-width:100%}.row-cols-1>*{-ms-flex:0 0 100%;flex:0 0 100%;max-width:100%}.row-cols-2>*{-ms-flex:0 0 50%;flex:0 0 50%;max-width:50%}.row-cols-3>*{-ms-flex:0 0 33.333333%;flex:0 0 33.333333%;max-width:33.333333%}.row-cols-4>*{-ms-flex:0 0 25%;flex:0 0 25%;max-width:25%}.row-cols-5>*{-ms-flex:0 0 20%;flex:0 0 20%;max-width:20%}.row-cols-6>*{-ms-flex:0 0 16.666667%;flex:0 0 16.666667%;max-width:16.666667%}.col-auto{-ms-flex:0 0 auto;flex:0 0 auto;width:auto;max-width:100%}.col-1{-ms-flex:0 0 8.333333%;flex:0 0 8.333333%;max-width:8.333333%}.col-2{-ms-flex:0 0 16.666667%;flex:0 0 16.666667%;max-width:16.666667%}.col-3{-ms-flex:0 0 25%;flex:0 0 25%;max-width:25%}.col-4{-ms-flex:0 0 33.333333%;flex:0 0 33.333333%;max-width:33.333333%}.col-5{-ms-flex:0 0 41.666667%;flex:0 0 41.666667%;max-width:41.666667%}.col-6{-ms-flex:0 0 50%;flex:0 0 50%;max-width:50%}.col-7{-ms-flex:0 0 58.333333%;flex:0 0 58.333333%;max-width:58.333333%}.col-8{-ms-flex:0 0 66.666667%;flex:0 0 66.666667%;max-width:66.666667%}.col-9{-ms-flex:0 0 75%;flex:0 0 75%;max-width:75%}.col-10{-ms-flex:0 0 83.333333%;flex:0 0 83.333333%;max-width:83.333333%}.col-11{-ms-flex:0 0 91.666667%;flex:0 0 91.666667%;max-width:91.666667%}.col-12{-ms-flex:0 0 100%;flex:0 0 100%;max-width:100%}.order-first{-ms-flex-order:-1;order:-1}.order-last{-ms-flex-order:13;order:13}.order-0{-ms-flex-order:0;order:0}.order-1{-ms-flex-order:1;order:1}.order-2{-ms-flex-order:2;order:2}.order-3{-ms-flex-order:3;order:3}.order-4{-ms-flex-order:4;order:4}.order-5{-ms-flex-order:5;order:5}.order-6{-ms-flex-order:6;order:6}.order-7{-ms-flex-order:7;order:7}.order-8{-ms-flex-order:8;order:8}.order-9{-ms-flex-order:9;order:9}.order-10{-ms-flex-order:10;order:10}.order-11{-ms-flex-order:11;order:11}.order-12{-ms-flex-order:12;order:12}.offset-1{margin-left:8.333333%}.offset-2{margin-left:16.666667%}.offset-3{margin-left:25%}.offset-4{margin-left:33.333333%}.offset-5{margin-left:41.666667%}.offset-6{margin-left:50%}.offset-7{margin-left:58.333333%}.offset-8{margin-left:66.666667%}.offset-9{margin-left:75%}.offset-10{margin-left:83.333333%}.offset-11{margin-left:91.666667%}@media (min-width:576px){.col-sm{-ms-flex-preferred-size:0;flex-basis:0;-ms-flex-positive:1;flex-grow:1;min-width:0;max-width:100%}.row-cols-sm-1>*{-ms-flex:0 0 100%;flex:0 0 100%;max-width:100%}.row-cols-sm-2>*{-ms-flex:0 0 50%;flex:0 0 50%;max-width:50%}.row-cols-sm-3>*{-ms-flex:0 0 33.333333%;flex:0 0 33.333333%;max-width:33.333333%}.row-cols-sm-4>*{-ms-flex:0 0 25%;flex:0 0 25%;max-width:25%}.row-cols-sm-5>*{-ms-flex:0 0 20%;flex:0 0 20%;max-width:20%}.row-cols-sm-6>*{-ms-flex:0 0 16.666667%;flex:0 0 16.666667%;max-width:16.666667%}.col-sm-auto{-ms-flex:0 0 auto;flex:0 0 auto;width:auto;max-width:100%}.col-sm-1{-ms-flex:0 0 8.333333%;flex:0 0 8.333333%;max-width:8.333333%}.col-sm-2{-ms-flex:0 0 16.666667%;flex:0 0 16.666667%;max-width:16.666667%}.col-sm-3{-ms-flex:0 0 25%;flex:0 0 25%;max-width:25%}.col-sm-4{-ms-flex:0 0 33.333333%;flex:0 0 33.333333%;max-width:33.333333%}.col-sm-5{-ms-flex:0 0 41.666667%;flex:0 0 41.666667%;max-width:41.666667%}.col-sm-6{-ms-flex:0 0 50%;flex:0 0 50%;max-width:50%}.col-sm-7{-ms-flex:0 0 58.333333%;flex:0 0 58.333333%;max-width:58.333333%}.col-sm-8{-ms-flex:0 0 66.666667%;flex:0 0 66.666667%;max-width:66.666667%}.col-sm-9{-ms-flex:0 0 75%;flex:0 0 75%;max-width:75%}.col-sm-10{-ms-flex:0 0 83.333333%;flex:0 0 83.333333%;max-width:83.333333%}.col-sm-11{-ms-flex:0 0 91.666667%;flex:0 0 91.666667%;max-width:91.666667%}.col-sm-12{-ms-flex:0 0 100%;flex:0 0 100%;max-width:100%}.order-sm-first{-ms-flex-order:-1;order:-1}.order-sm-last{-ms-flex-order:13;order:13}.order-sm-0{-ms-flex-order:0;order:0}.order-sm-1{-ms-flex-order:1;order:1}.order-sm-2{-ms-flex-order:2;order:2}.order-sm-3{-ms-flex-order:3;order:3}.order-sm-4{-ms-flex-order:4;order:4}.order-sm-5{-ms-flex-order:5;order:5}.order-sm-6{-ms-flex-order:6;order:6}.order-sm-7{-ms-flex-order:7;order:7}.order-sm-8{-ms-flex-order:8;order:8}.order-sm-9{-ms-flex-order:9;order:9}.order-sm-10{-ms-flex-order:10;order:10}.order-sm-11{-ms-flex-order:11;order:11}.order-sm-12{-ms-flex-order:12;order:12}.offset-sm-0{margin-left:0}.offset-sm-1{margin-left:8.333333%}.offset-sm-2{margin-left:16.666667%}.offset-sm-3{margin-left:25%}.offset-sm-4{margin-left:33.333333%}.offset-sm-5{margin-left:41.666667%}.offset-sm-6{margin-left:50%}.offset-sm-7{margin-left:58.333333%}.offset-sm-8{margin-left:66.666667%}.offset-sm-9{margin-left:75%}.offset-sm-10{margin-left:83.333333%}.offset-sm-11{margin-left:91.666667%}}@media (min-width:768px){.col-md{-ms-flex-preferred-size:0;flex-basis:0;-ms-flex-positive:1;flex-grow:1;min-width:0;max-width:100%}.row-cols-md-1>*{-ms-flex:0 0 100%;flex:0 0 100%;max-width:100%}.row-cols-md-2>*{-ms-flex:0 0 50%;flex:0 0 50%;max-width:50%}.row-cols-md-3>*{-ms-flex:0 0 33.333333%;flex:0 0 33.333333%;max-width:33.333333%}.row-cols-md-4>*{-ms-flex:0 0 25%;flex:0 0 25%;max-width:25%}.row-cols-md-5>*{-ms-flex:0 0 20%;flex:0 0 20%;max-width:20%}.row-cols-md-6>*{-ms-flex:0 0 16.666667%;flex:0 0 16.666667%;max-width:16.666667%}.col-md-auto{-ms-flex:0 0 auto;flex:0 0 auto;width:auto;max-width:100%}.col-md-1{-ms-flex:0 0 8.333333%;flex:0 0 8.333333%;max-width:8.333333%}.col-md-2{-ms-flex:0 0 16.666667%;flex:0 0 16.666667%;max-width:16.666667%}.col-md-3{-ms-flex:0 0 25%;flex:0 0 25%;max-width:25%}.col-md-4{-ms-flex:0 0 33.333333%;flex:0 0 33.333333%;max-width:33.333333%}.col-md-5{-ms-flex:0 0 41.666667%;flex:0 0 41.666667%;max-width:41.666667%}.col-md-6{-ms-flex:0 0 50%;flex:0 0 50%;max-width:50%}.col-md-7{-ms-flex:0 0 58.333333%;flex:0 0 58.333333%;max-width:58.333333%}.col-md-8{-ms-flex:0 0 66.666667%;flex:0 0 66.666667%;max-width:66.666667%}.col-md-9{-ms-flex:0 0 75%;flex:0 0 75%;max-width:75%}.col-md-10{-ms-flex:0 0 83.333333%;flex:0 0 83.333333%;max-width:83.333333%}.col-md-11{-ms-flex:0 0 91.666667%;flex:0 0 91.666667%;max-width:91.666667%}.col-md-12{-ms-flex:0 0 100%;flex:0 0 100%;max-width:100%}.order-md-first{-ms-flex-order:-1;order:-1}.order-md-last{-ms-flex-order:13;order:13}.order-md-0{-ms-flex-order:0;order:0}.order-md-1{-ms-flex-order:1;order:1}.order-md-2{-ms-flex-order:2;order:2}.order-md-3{-ms-flex-order:3;order:3}.order-md-4{-ms-flex-order:4;order:4}.order-md-5{-ms-flex-order:5;order:5}.order-md-6{-ms-flex-order:6;order:6}.order-md-7{-ms-flex-order:7;order:7}.order-md-8{-ms-flex-order:8;order:8}.order-md-9{-ms-flex-order:9;order:9}.order-md-10{-ms-flex-order:10;order:10}.order-md-11{-ms-flex-order:11;order:11}.order-md-12{-ms-flex-order:12;order:12}.offset-md-0{margin-left:0}.offset-md-1{margin-left:8.333333%}.offset-md-2{margin-left:16.666667%}.offset-md-3{margin-left:25%}.offset-md-4{margin-left:33.333333%}.offset-md-5{margin-left:41.666667%}.offset-md-6{margin-left:50%}.offset-md-7{margin-left:58.333333%}.offset-md-8{margin-left:66.666667%}.offset-md-9{margin-left:75%}.offset-md-10{margin-left:83.333333%}.offset-md-11{margin-left:91.666667%}}@media (min-width:992px){.col-lg{-ms-flex-preferred-size:0;flex-basis:0;-ms-flex-positive:1;flex-grow:1;min-width:0;max-width:100%}.row-cols-lg-1>*{-ms-flex:0 0 100%;flex:0 0 100%;max-width:100%}.row-cols-lg-2>*{-ms-flex:0 0 50%;flex:0 0 50%;max-width:50%}.row-cols-lg-3>*{-ms-flex:0 0 33.333333%;flex:0 0 33.333333%;max-width:33.333333%}.row-cols-lg-4>*{-ms-flex:0 0 25%;flex:0 0 25%;max-width:25%}.row-cols-lg-5>*{-ms-flex:0 0 20%;flex:0 0 20%;max-width:20%}.row-cols-lg-6>*{-ms-flex:0 0 16.666667%;flex:0 0 16.666667%;max-width:16.666667%}.col-lg-auto{-ms-flex:0 0 auto;flex:0 0 auto;width:auto;max-width:100%}.col-lg-1{-ms-flex:0 0 8.333333%;flex:0 0 8.333333%;max-width:8.333333%}.col-lg-2{-ms-flex:0 0 16.666667%;flex:0 0 16.666667%;max-width:16.666667%}.col-lg-3{-ms-flex:0 0 25%;flex:0 0 25%;max-width:25%}.col-lg-4{-ms-flex:0 0 33.333333%;flex:0 0 33.333333%;max-width:33.333333%}.col-lg-5{-ms-flex:0 0 41.666667%;flex:0 0 41.666667%;max-width:41.666667%}.col-lg-6{-ms-flex:0 0 50%;flex:0 0 50%;max-width:50%}.col-lg-7{-ms-flex:0 0 58.333333%;flex:0 0 58.333333%;max-width:58.333333%}.col-lg-8{-ms-flex:0 0 66.666667%;flex:0 0 66.666667%;max-width:66.666667%}.col-lg-9{-ms-flex:0 0 75%;flex:0 0 75%;max-width:75%}.col-lg-10{-ms-flex:0 0 83.333333%;flex:0 0 83.333333%;max-width:83.333333%}.col-lg-11{-ms-flex:0 0 91.666667%;flex:0 0 91.666667%;max-width:91.666667%}.col-lg-12{-ms-flex:0 0 100%;flex:0 0 100%;max-width:100%}.order-lg-first{-ms-flex-order:-1;order:-1}.order-lg-last{-ms-flex-order:13;order:13}.order-lg-0{-ms-flex-order:0;order:0}.order-lg-1{-ms-flex-order:1;order:1}.order-lg-2{-ms-flex-order:2;order:2}.order-lg-3{-ms-flex-order:3;order:3}.order-lg-4{-ms-flex-order:4;order:4}.order-lg-5{-ms-flex-order:5;order:5}.order-lg-6{-ms-flex-order:6;order:6}.order-lg-7{-ms-flex-order:7;order:7}.order-lg-8{-ms-flex-order:8;order:8}.order-lg-9{-ms-flex-order:9;order:9}.order-lg-10{-ms-flex-order:10;order:10}.order-lg-11{-ms-flex-order:11;order:11}.order-lg-12{-ms-flex-order:12;order:12}.offset-lg-0{margin-left:0}.offset-lg-1{margin-left:8.333333%}.offset-lg-2{margin-left:16.666667%}.offset-lg-3{margin-left:25%}.offset-lg-4{margin-left:33.333333%}.offset-lg-5{margin-left:41.666667%}.offset-lg-6{margin-left:50%}.offset-lg-7{margin-left:58.333333%}.offset-lg-8{margin-left:66.666667%}.offset-lg-9{margin-left:75%}.offset-lg-10{margin-left:83.333333%}.offset-lg-11{margin-left:91.666667%}}@media (min-width:1200px){.col-xl{-ms-flex-preferred-size:0;flex-basis:0;-ms-flex-positive:1;flex-grow:1;min-width:0;max-width:100%}.row-cols-xl-1>*{-ms-flex:0 0 100%;flex:0 0 100%;max-width:100%}.row-cols-xl-2>*{-ms-flex:0 0 50%;flex:0 0 50%;max-width:50%}.row-cols-xl-3>*{-ms-flex:0 0 33.333333%;flex:0 0 33.333333%;max-width:33.333333%}.row-cols-xl-4>*{-ms-flex:0 0 25%;flex:0 0 25%;max-width:25%}.row-cols-xl-5>*{-ms-flex:0 0 20%;flex:0 0 20%;max-width:20%}.row-cols-xl-6>*{-ms-flex:0 0 16.666667%;flex:0 0 16.666667%;max-width:16.666667%}.col-xl-auto{-ms-flex:0 0 auto;flex:0 0 auto;width:auto;max-width:100%}.col-xl-1{-ms-flex:0 0 8.333333%;flex:0 0 8.333333%;max-width:8.333333%}.col-xl-2{-ms-flex:0 0 16.666667%;flex:0 0 16.666667%;max-width:16.666667%}.col-xl-3{-ms-flex:0 0 25%;flex:0 0 25%;max-width:25%}.col-xl-4{-ms-flex:0 0 33.333333%;flex:0 0 33.333333%;max-width:33.333333%}.col-xl-5{-ms-flex:0 0 41.666667%;flex:0 0 41.666667%;max-width:41.666667%}.col-xl-6{-ms-flex:0 0 50%;flex:0 0 50%;max-width:50%}.col-xl-7{-ms-flex:0 0 58.333333%;flex:0 0 58.333333%;max-width:58.333333%}.col-xl-8{-ms-flex:0 0 66.666667%;flex:0 0 66.666667%;max-width:66.666667%}.col-xl-9{-ms-flex:0 0 75%;flex:0 0 75%;max-width:75%}.col-xl-10{-ms-flex:0 0 83.333333%;flex:0 0 83.333333%;max-width:83.333333%}.col-xl-11{-ms-flex:0 0 91.666667%;flex:0 0 91.666667%;max-width:91.666667%}.col-xl-12{-ms-flex:0 0 100%;flex:0 0 100%;max-width:100%}.order-xl-first{-ms-flex-order:-1;order:-1}.order-xl-last{-ms-flex-order:13;order:13}.order-xl-0{-ms-flex-order:0;order:0}.order-xl-1{-ms-flex-order:1;order:1}.order-xl-2{-ms-flex-order:2;order:2}.order-xl-3{-ms-flex-order:3;order:3}.order-xl-4{-ms-flex-order:4;order:4}.order-xl-5{-ms-flex-order:5;order:5}.order-xl-6{-ms-flex-order:6;order:6}.order-xl-7{-ms-flex-order:7;order:7}.order-xl-8{-ms-flex-order:8;order:8}.order-xl-9{-ms-flex-order:9;order:9}.order-xl-10{-ms-flex-order:10;order:10}.order-xl-11{-ms-flex-order:11;order:11}.order-xl-12{-ms-flex-order:12;order:12}.offset-xl-0{margin-left:0}.offset-xl-1{margin-left:8.333333%}.offset-xl-2{margin-left:16.666667%}.offset-xl-3{margin-left:25%}.offset-xl-4{margin-left:33.333333%}.offset-xl-5{margin-left:41.666667%}.offset-xl-6{margin-left:50%}.offset-xl-7{margin-left:58.333333%}.offset-xl-8{margin-left:66.666667%}.offset-xl-9{margin-left:75%}.offset-xl-10{margin-left:83.333333%}.offset-xl-11{margin-left:91.666667%}}.table{width:100%;margin-bottom:1rem;color:#212529}.table td,.table th{padding:.75rem;vertical-align:top;border-top:1px solid #dee2e6}.table thead th{vertical-align:bottom;border-bottom:2px solid #dee2e6}.table tbody+tbody{border-top:2px solid #dee2e6}.table-sm td,.table-sm th{padding:.3rem}.table-bordered{border:1px solid #dee2e6}.table-bordered td,.table-bordered th{border:1px solid #dee2e6}.table-bordered thead td,.table-bordered thead th{border-bottom-width:2px}.table-borderless tbody+tbody,.table-borderless td,.table-borderless th,.table-borderless thead th{border:0}.table-striped tbody tr:nth-of-type(odd){background-color:rgba(0,0,0,.05)}.table-hover tbody tr:hover{color:#212529;background-color:rgba(0,0,0,.075)}.table-primary,.table-primary>td,.table-primary>th{background-color:#b8daff}.table-primary tbody+tbody,.table-primary td,.table-primary th,.table-primary thead th{border-color:#7abaff}.table-hover .table-primary:hover{background-color:#9fcdff}.table-hover .table-primary:hover>td,.table-hover .table-primary:hover>th{background-color:#9fcdff}.table-secondary,.table-secondary>td,.table-secondary>th{background-color:#d6d8db}.table-secondary tbody+tbody,.table-secondary td,.table-secondary th,.table-secondary thead th{border-color:#b3b7bb}.table-hover .table-secondary:hover{background-color:#c8cbcf}.table-hover .table-secondary:hover>td,.table-hover .table-secondary:hover>th{background-color:#c8cbcf}.table-success,.table-success>td,.table-success>th{background-color:#c3e6cb}.table-success tbody+tbody,.table-success td,.table-success th,.table-success thead th{border-color:#8fd19e}.table-hover .table-success:hover{background-color:#b1dfbb}.table-hover .table-success:hover>td,.table-hover .table-success:hover>th{background-color:#b1dfbb}.table-info,.table-info>td,.table-info>th{background-color:#bee5eb}.table-info tbody+tbody,.table-info td,.table-info th,.table-info thead th{border-color:#86cfda}.table-hover .table-info:hover{background-color:#abdde5}.table-hover .table-info:hover>td,.table-hover .table-info:hover>th{background-color:#abdde5}.table-warning,.table-warning>td,.table-warning>th{background-color:#ffeeba}.table-warning tbody+tbody,.table-warning td,.table-warning th,.table-warning thead th{border-color:#ffdf7e}.table-hover .table-warning:hover{background-color:#ffe8a1}.table-hover .table-warning:hover>td,.table-hover .table-warning:hover>th{background-color:#ffe8a1}.table-danger,.table-danger>td,.table-danger>th{background-color:#f5c6cb}.table-danger tbody+tbody,.table-danger td,.table-danger th,.table-danger thead th{border-color:#ed969e}.table-hover .table-danger:hover{background-color:#f1b0b7}.table-hover .table-danger:hover>td,.table-hover .table-danger:hover>th{background-color:#f1b0b7}.table-light,.table-light>td,.table-light>th{background-color:#fdfdfe}.table-light tbody+tbody,.table-light td,.table-light th,.table-light thead th{border-color:#fbfcfc}.table-hover .table-light:hover{background-color:#ececf6}.table-hover .table-light:hover>td,.table-hover .table-light:hover>th{background-color:#ececf6}.table-dark,.table-dark>td,.table-dark>th{background-color:#c6c8ca}.table-dark tbody+tbody,.table-dark td,.table-dark th,.table-dark thead th{border-color:#95999c}.table-hover .table-dark:hover{background-color:#b9bbbe}.table-hover .table-dark:hover>td,.table-hover .table-dark:hover>th{background-color:#b9bbbe}.table-active,.table-active>td,.table-active>th{background-color:rgba(0,0,0,.075)}.table-hover .table-active:hover{background-color:rgba(0,0,0,.075)}.table-hover .table-active:hover>td,.table-hover .table-active:hover>th{background-color:rgba(0,0,0,.075)}.table .thead-dark th{color:#fff;background-color:#343a40;border-color:#454d55}.table .thead-light th{color:#495057;background-color:#e9ecef;border-color:#dee2e6}.table-dark{color:#fff;background-color:#343a40}.table-dark td,.table-dark th,.table-dark thead th{border-color:#454d55}.table-dark.table-bordered{border:0}.table-dark.table-striped tbody tr:nth-of-type(odd){background-color:rgba(255,255,255,.05)}.table-dark.table-hover tbody tr:hover{color:#fff;background-color:rgba(255,255,255,.075)}@media (max-width:575.98px){.table-responsive-sm{display:block;width:100%;overflow-x:auto;-webkit-overflow-scrolling:touch}.table-responsive-sm>.table-bordered{border:0}}@media (max-width:767.98px){.table-responsive-md{display:block;width:100%;overflow-x:auto;-webkit-overflow-scrolling:touch}.table-responsive-md>.table-bordered{border:0}}@media (max-width:991.98px){.table-responsive-lg{display:block;width:100%;overflow-x:auto;-webkit-overflow-scrolling:touch}.table-responsive-lg>.table-bordered{border:0}}@media (max-width:1199.98px){.table-responsive-xl{display:block;width:100%;overflow-x:auto;-webkit-overflow-scrolling:touch}.table-responsive-xl>.table-bordered{border:0}}.table-responsive{display:block;width:100%;overflow-x:auto;-webkit-overflow-scrolling:touch}.table-responsive>.table-bordered{border:0}.form-control{display:block;width:100%;height:calc(1.5em + .75rem + 2px);padding:.375rem .75rem;font-size:1rem;font-weight:400;line-height:1.5;color:#495057;background-color:#fff;background-clip:padding-box;border:1px solid #ced4da;border-radius:.25rem;transition:border-color .15s ease-in-out,box-shadow .15s ease-in-out}@media (prefers-reduced-motion:reduce){.form-control{transition:none}}.form-control::-ms-expand{background-color:transparent;border:0}.form-control:-moz-focusring{color:transparent;text-shadow:0 0 0 #495057}.form-control:focus{color:#495057;background-color:#fff;border-color:#80bdff;outline:0;box-shadow:0 0 0 .2rem rgba(0,123,255,.25)}.form-control::-webkit-input-placeholder{color:#6c757d;opacity:1}.form-control::-moz-placeholder{color:#6c757d;opacity:1}.form-control:-ms-input-placeholder{color:#6c757d;opacity:1}.form-control::-ms-input-placeholder{color:#6c757d;opacity:1}.form-control::placeholder{color:#6c757d;opacity:1}.form-control:disabled,.form-control[readonly]{background-color:#e9ecef;opacity:1}input[type=date].form-control,input[type=datetime-local].form-control,input[type=month].form-control,input[type=time].form-control{-webkit-appearance:none;-moz-appearance:none;appearance:none}select.form-control:focus::-ms-value{color:#495057;background-color:#fff}.form-control-file,.form-control-range{display:block;width:100%}.col-form-label{padding-top:calc(.375rem + 1px);padding-bottom:calc(.375rem + 1px);margin-bottom:0;font-size:inherit;line-height:1.5}.col-form-label-lg{padding-top:calc(.5rem + 1px);padding-bottom:calc(.5rem + 1px);font-size:1.25rem;line-height:1.5}.col-form-label-sm{padding-top:calc(.25rem + 1px);padding-bottom:calc(.25rem + 1px);font-size:.875rem;line-height:1.5}.form-control-plaintext{display:block;width:100%;padding:.375rem 0;margin-bottom:0;font-size:1rem;line-height:1.5;color:#212529;background-color:transparent;border:solid transparent;border-width:1px 0}.form-control-plaintext.form-control-lg,.form-control-plaintext.form-control-sm{padding-right:0;padding-left:0}.form-control-sm{height:calc(1.5em + .5rem + 2px);padding:.25rem .5rem;font-size:.875rem;line-height:1.5;border-radius:.2rem}.form-control-lg{height:calc(1.5em + 1rem + 2px);padding:.5rem 1rem;font-size:1.25rem;line-height:1.5;border-radius:.3rem}select.form-control[multiple],select.form-control[size]{height:auto}textarea.form-control{height:auto}.form-group{margin-bottom:1rem}.form-text{display:block;margin-top:.25rem}.form-row{display:-ms-flexbox;display:flex;-ms-flex-wrap:wrap;flex-wrap:wrap;margin-right:-5px;margin-left:-5px}.form-row>.col,.form-row>[class*=col-]{padding-right:5px;padding-left:5px}.form-check{position:relative;display:block;padding-left:1.25rem}.form-check-input{position:absolute;margin-top:.3rem;margin-left:-1.25rem}.form-check-input:disabled~.form-check-label,.form-check-input[disabled]~.form-check-label{color:#6c757d}.form-check-label{margin-bottom:0}.form-check-inline{display:-ms-inline-flexbox;display:inline-flex;-ms-flex-align:center;align-items:center;padding-left:0;margin-right:.75rem}.form-check-inline .form-check-input{position:static;margin-top:0;margin-right:.3125rem;margin-left:0}.valid-feedback{display:none;width:100%;margin-top:.25rem;font-size:80%;color:#28a745}.valid-tooltip{position:absolute;top:100%;z-index:5;display:none;max-width:100%;padding:.25rem .5rem;margin-top:.1rem;font-size:.875rem;line-height:1.5;color:#fff;background-color:rgba(40,167,69,.9);border-radius:.25rem}.is-valid~.valid-feedback,.is-valid~.valid-tooltip,.was-validated :valid~.valid-feedback,.was-validated :valid~.valid-tooltip{display:block}.form-control.is-valid,.was-validated .form-control:valid{border-color:#28a745;padding-right:calc(1.5em + .75rem);background-image:url("data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' width='8' height='8' viewBox='0 0 8 8'%3e%3cpath fill='%2328a745' d='M2.3 6.73L.6 4.53c-.4-1.04.46-1.4 1.1-.8l1.1 1.4 3.4-3.8c.6-.63 1.6-.27 1.2.7l-4 4.6c-.43.5-.8.4-1.1.1z'/%3e%3c/svg%3e");background-repeat:no-repeat;background-position:right calc(.375em + .1875rem) center;background-size:calc(.75em + .375rem) calc(.75em + .375rem)}.form-control.is-valid:focus,.was-validated .form-control:valid:focus{border-color:#28a745;box-shadow:0 0 0 .2rem rgba(40,167,69,.25)}.was-validated textarea.form-control:valid,textarea.form-control.is-valid{padding-right:calc(1.5em + .75rem);background-position:top calc(.375em + .1875rem) right calc(.375em + .1875rem)}.custom-select.is-valid,.was-validated .custom-select:valid{border-color:#28a745;padding-right:calc(.75em + 2.3125rem);background:url("data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' width='4' height='5' viewBox='0 0 4 5'%3e%3cpath fill='%23343a40' d='M2 0L0 2h4zm0 5L0 3h4z'/%3e%3c/svg%3e") no-repeat right .75rem center/8px 10px,url("data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' width='8' height='8' viewBox='0 0 8 8'%3e%3cpath fill='%2328a745' d='M2.3 6.73L.6 4.53c-.4-1.04.46-1.4 1.1-.8l1.1 1.4 3.4-3.8c.6-.63 1.6-.27 1.2.7l-4 4.6c-.43.5-.8.4-1.1.1z'/%3e%3c/svg%3e") #fff no-repeat center right 1.75rem/calc(.75em + .375rem) calc(.75em + .375rem)}.custom-select.is-valid:focus,.was-validated .custom-select:valid:focus{border-color:#28a745;box-shadow:0 0 0 .2rem rgba(40,167,69,.25)}.form-check-input.is-valid~.form-check-label,.was-validated .form-check-input:valid~.form-check-label{color:#28a745}.form-check-input.is-valid~.valid-feedback,.form-check-input.is-valid~.valid-tooltip,.was-validated .form-check-input:valid~.valid-feedback,.was-validated .form-check-input:valid~.valid-tooltip{display:block}.custom-control-input.is-valid~.custom-control-label,.was-validated .custom-control-input:valid~.custom-control-label{color:#28a745}.custom-control-input.is-valid~.custom-control-label::before,.was-validated .custom-control-input:valid~.custom-control-label::before{border-color:#28a745}.custom-control-input.is-valid:checked~.custom-control-label::before,.was-validated .custom-control-input:valid:checked~.custom-control-label::before{border-color:#34ce57;background-color:#34ce57}.custom-control-input.is-valid:focus~.custom-control-label::before,.was-validated .custom-control-input:valid:focus~.custom-control-label::before{box-shadow:0 0 0 .2rem rgba(40,167,69,.25)}.custom-control-input.is-valid:focus:not(:checked)~.custom-control-label::before,.was-validated .custom-control-input:valid:focus:not(:checked)~.custom-control-label::before{border-color:#28a745}.custom-file-input.is-valid~.custom-file-label,.was-validated .custom-file-input:valid~.custom-file-label{border-color:#28a745}.custom-file-input.is-valid:focus~.custom-file-label,.was-validated .custom-file-input:valid:focus~.custom-file-label{border-color:#28a745;box-shadow:0 0 0 .2rem rgba(40,167,69,.25)}.invalid-feedback{display:none;width:100%;margin-top:.25rem;font-size:80%;color:#dc3545}.invalid-tooltip{position:absolute;top:100%;z-index:5;display:none;max-width:100%;padding:.25rem .5rem;margin-top:.1rem;font-size:.875rem;line-height:1.5;color:#fff;background-color:rgba(220,53,69,.9);border-radius:.25rem}.is-invalid~.invalid-feedback,.is-invalid~.invalid-tooltip,.was-validated :invalid~.invalid-feedback,.was-validated :invalid~.invalid-tooltip{display:block}.form-control.is-invalid,.was-validated .form-control:invalid{border-color:#dc3545;padding-right:calc(1.5em + .75rem);background-image:url("data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' width='12' height='12' fill='none' stroke='%23dc3545' viewBox='0 0 12 12'%3e%3ccircle cx='6' cy='6' r='4.5'/%3e%3cpath stroke-linejoin='round' d='M5.8 3.6h.4L6 6.5z'/%3e%3ccircle cx='6' cy='8.2' r='.6' fill='%23dc3545' stroke='none'/%3e%3c/svg%3e");background-repeat:no-repeat;background-position:right calc(.375em + .1875rem) center;background-size:calc(.75em + .375rem) calc(.75em + .375rem)}.form-control.is-invalid:focus,.was-validated .form-control:invalid:focus{border-color:#dc3545;box-shadow:0 0 0 .2rem rgba(220,53,69,.25)}.was-validated textarea.form-control:invalid,textarea.form-control.is-invalid{padding-right:calc(1.5em + .75rem);background-position:top calc(.375em + .1875rem) right calc(.375em + .1875rem)}.custom-select.is-invalid,.was-validated .custom-select:invalid{border-color:#dc3545;padding-right:calc(.75em + 2.3125rem);background:url("data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' width='4' height='5' viewBox='0 0 4 5'%3e%3cpath fill='%23343a40' d='M2 0L0 2h4zm0 5L0 3h4z'/%3e%3c/svg%3e") no-repeat right .75rem center/8px 10px,url("data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' width='12' height='12' fill='none' stroke='%23dc3545' viewBox='0 0 12 12'%3e%3ccircle cx='6' cy='6' r='4.5'/%3e%3cpath stroke-linejoin='round' d='M5.8 3.6h.4L6 6.5z'/%3e%3ccircle cx='6' cy='8.2' r='.6' fill='%23dc3545' stroke='none'/%3e%3c/svg%3e") #fff no-repeat center right 1.75rem/calc(.75em + .375rem) calc(.75em + .375rem)}.custom-select.is-invalid:focus,.was-validated .custom-select:invalid:focus{border-color:#dc3545;box-shadow:0 0 0 .2rem rgba(220,53,69,.25)}.form-check-input.is-invalid~.form-check-label,.was-validated .form-check-input:invalid~.form-check-label{color:#dc3545}.form-check-input.is-invalid~.invalid-feedback,.form-check-input.is-invalid~.invalid-tooltip,.was-validated .form-check-input:invalid~.invalid-feedback,.was-validated .form-check-input:invalid~.invalid-tooltip{display:block}.custom-control-input.is-invalid~.custom-control-label,.was-validated .custom-control-input:invalid~.custom-control-label{color:#dc3545}.custom-control-input.is-invalid~.custom-control-label::before,.was-validated .custom-control-input:invalid~.custom-control-label::before{border-color:#dc3545}.custom-control-input.is-invalid:checked~.custom-control-label::before,.was-validated .custom-control-input:invalid:checked~.custom-control-label::before{border-color:#e4606d;background-color:#e4606d}.custom-control-input.is-invalid:focus~.custom-control-label::before,.was-validated .custom-control-input:invalid:focus~.custom-control-label::before{box-shadow:0 0 0 .2rem rgba(220,53,69,.25)}.custom-control-input.is-invalid:focus:not(:checked)~.custom-control-label::before,.was-validated .custom-control-input:invalid:focus:not(:checked)~.custom-control-label::before{border-color:#dc3545}.custom-file-input.is-invalid~.custom-file-label,.was-validated .custom-file-input:invalid~.custom-file-label{border-color:#dc3545}.custom-file-input.is-invalid:focus~.custom-file-label,.was-validated .custom-file-input:invalid:focus~.custom-file-label{border-color:#dc3545;box-shadow:0 0 0 .2rem rgba(220,53,69,.25)}.form-inline{display:-ms-flexbox;display:flex;-ms-flex-flow:row wrap;flex-flow:row wrap;-ms-flex-align:center;align-items:center}.form-inline .form-check{width:100%}@media (min-width:576px){.form-inline label{display:-ms-flexbox;display:flex;-ms-flex-align:center;align-items:center;-ms-flex-pack:center;justify-content:center;margin-bottom:0}.form-inline .form-group{display:-ms-flexbox;display:flex;-ms-flex:0 0 auto;flex:0 0 auto;-ms-flex-flow:row wrap;flex-flow:row wrap;-ms-flex-align:center;align-items:center;margin-bottom:0}.form-inline .form-control{display:inline-block;width:auto;vertical-align:middle}.form-inline .form-control-plaintext{display:inline-block}.form-inline .custom-select,.form-inline .input-group{width:auto}.form-inline .form-check{display:-ms-flexbox;display:flex;-ms-flex-align:center;align-items:center;-ms-flex-pack:center;justify-content:center;width:auto;padding-left:0}.form-inline .form-check-input{position:relative;-ms-flex-negative:0;flex-shrink:0;margin-top:0;margin-right:.25rem;margin-left:0}.form-inline .custom-control{-ms-flex-align:center;align-items:center;-ms-flex-pack:center;justify-content:center}.form-inline .custom-control-label{margin-bottom:0}}.btn{display:inline-block;font-weight:400;color:#212529;text-align:center;vertical-align:middle;-webkit-user-select:none;-moz-user-select:none;-ms-user-select:none;user-select:none;background-color:transparent;border:1px solid transparent;padding:.375rem .75rem;font-size:1rem;line-height:1.5;border-radius:.25rem;transition:color .15s ease-in-out,background-color .15s ease-in-out,border-color .15s ease-in-out,box-shadow .15s ease-in-out}@media (prefers-reduced-motion:reduce){.btn{transition:none}}.btn:hover{color:#212529;text-decoration:none}.btn.focus,.btn:focus{outline:0;box-shadow:0 0 0 .2rem rgba(0,123,255,.25)}.btn.disabled,.btn:disabled{opacity:.65}.btn:not(:disabled):not(.disabled){cursor:pointer}a.btn.disabled,fieldset:disabled a.btn{pointer-events:none}.btn-primary{color:#fff;background-color:#007bff;border-color:#007bff}.btn-primary:hover{color:#fff;background-color:#0069d9;border-color:#0062cc}.btn-primary.focus,.btn-primary:focus{color:#fff;background-color:#0069d9;border-color:#0062cc;box-shadow:0 0 0 .2rem rgba(38,143,255,.5)}.btn-primary.disabled,.btn-primary:disabled{color:#fff;background-color:#007bff;border-color:#007bff}.btn-primary:not(:disabled):not(.disabled).active,.btn-primary:not(:disabled):not(.disabled):active,.show>.btn-primary.dropdown-toggle{color:#fff;background-color:#0062cc;border-color:#005cbf}.btn-primary:not(:disabled):not(.disabled).active:focus,.btn-primary:not(:disabled):not(.disabled):active:focus,.show>.btn-primary.dropdown-toggle:focus{box-shadow:0 0 0 .2rem rgba(38,143,255,.5)}.btn-secondary{color:#fff;background-color:#6c757d;border-color:#6c757d}.btn-secondary:hover{color:#fff;background-color:#5a6268;border-color:#545b62}.btn-secondary.focus,.btn-secondary:focus{color:#fff;background-color:#5a6268;border-color:#545b62;box-shadow:0 0 0 .2rem rgba(130,138,145,.5)}.btn-secondary.disabled,.btn-secondary:disabled{color:#fff;background-color:#6c757d;border-color:#6c757d}.btn-secondary:not(:disabled):not(.disabled).active,.btn-secondary:not(:disabled):not(.disabled):active,.show>.btn-secondary.dropdown-toggle{color:#fff;background-color:#545b62;border-color:#4e555b}.btn-secondary:not(:disabled):not(.disabled).active:focus,.btn-secondary:not(:disabled):not(.disabled):active:focus,.show>.btn-secondary.dropdown-toggle:focus{box-shadow:0 0 0 .2rem rgba(130,138,145,.5)}.btn-success{color:#fff;background-color:#28a745;border-color:#28a745}.btn-success:hover{color:#fff;background-color:#218838;border-color:#1e7e34}.btn-success.focus,.btn-success:focus{color:#fff;background-color:#218838;border-color:#1e7e34;box-shadow:0 0 0 .2rem rgba(72,180,97,.5)}.btn-success.disabled,.btn-success:disabled{color:#fff;background-color:#28a745;border-color:#28a745}.btn-success:not(:disabled):not(.disabled).active,.btn-success:not(:disabled):not(.disabled):active,.show>.btn-success.dropdown-toggle{color:#fff;background-color:#1e7e34;border-color:#1c7430}.btn-success:not(:disabled):not(.disabled).active:focus,.btn-success:not(:disabled):not(.disabled):active:focus,.show>.btn-success.dropdown-toggle:focus{box-shadow:0 0 0 .2rem rgba(72,180,97,.5)}.btn-info{color:#fff;background-color:#17a2b8;border-color:#17a2b8}.btn-info:hover{color:#fff;background-color:#138496;border-color:#117a8b}.btn-info.focus,.btn-info:focus{color:#fff;background-color:#138496;border-color:#117a8b;box-shadow:0 0 0 .2rem rgba(58,176,195,.5)}.btn-info.disabled,.btn-info:disabled{color:#fff;background-color:#17a2b8;border-color:#17a2b8}.btn-info:not(:disabled):not(.disabled).active,.btn-info:not(:disabled):not(.disabled):active,.show>.btn-info.dropdown-toggle{color:#fff;background-color:#117a8b;border-color:#10707f}.btn-info:not(:disabled):not(.disabled).active:focus,.btn-info:not(:disabled):not(.disabled):active:focus,.show>.btn-info.dropdown-toggle:focus{box-shadow:0 0 0 .2rem rgba(58,176,195,.5)}.btn-warning{color:#212529;background-color:#ffc107;border-color:#ffc107}.btn-warning:hover{color:#212529;background-color:#e0a800;border-color:#d39e00}.btn-warning.focus,.btn-warning:focus{color:#212529;background-color:#e0a800;border-color:#d39e00;box-shadow:0 0 0 .2rem rgba(222,170,12,.5)}.btn-warning.disabled,.btn-warning:disabled{color:#212529;background-color:#ffc107;border-color:#ffc107}.btn-warning:not(:disabled):not(.disabled).active,.btn-warning:not(:disabled):not(.disabled):active,.show>.btn-warning.dropdown-toggle{color:#212529;background-color:#d39e00;border-color:#c69500}.btn-warning:not(:disabled):not(.disabled).active:focus,.btn-warning:not(:disabled):not(.disabled):active:focus,.show>.btn-warning.dropdown-toggle:focus{box-shadow:0 0 0 .2rem rgba(222,170,12,.5)}.btn-danger{color:#fff;background-color:#dc3545;border-color:#dc3545}.btn-danger:hover{color:#fff;background-color:#c82333;border-color:#bd2130}.btn-danger.focus,.btn-danger:focus{color:#fff;background-color:#c82333;border-color:#bd2130;box-shadow:0 0 0 .2rem rgba(225,83,97,.5)}.btn-danger.disabled,.btn-danger:disabled{color:#fff;background-color:#dc3545;border-color:#dc3545}.btn-danger:not(:disabled):not(.disabled).active,.btn-danger:not(:disabled):not(.disabled):active,.show>.btn-danger.dropdown-toggle{color:#fff;background-color:#bd2130;border-color:#b21f2d}.btn-danger:not(:disabled):not(.disabled).active:focus,.btn-danger:not(:disabled):not(.disabled):active:focus,.show>.btn-danger.dropdown-toggle:focus{box-shadow:0 0 0 .2rem rgba(225,83,97,.5)}.btn-light{color:#212529;background-color:#f8f9fa;border-color:#f8f9fa}.btn-light:hover{color:#212529;background-color:#e2e6ea;border-color:#dae0e5}.btn-light.focus,.btn-light:focus{color:#212529;background-color:#e2e6ea;border-color:#dae0e5;box-shadow:0 0 0 .2rem rgba(216,217,219,.5)}.btn-light.disabled,.btn-light:disabled{color:#212529;background-color:#f8f9fa;border-color:#f8f9fa}.btn-light:not(:disabled):not(.disabled).active,.btn-light:not(:disabled):not(.disabled):active,.show>.btn-light.dropdown-toggle{color:#212529;background-color:#dae0e5;border-color:#d3d9df}.btn-light:not(:disabled):not(.disabled).active:focus,.btn-light:not(:disabled):not(.disabled):active:focus,.show>.btn-light.dropdown-toggle:focus{box-shadow:0 0 0 .2rem rgba(216,217,219,.5)}.btn-dark{color:#fff;background-color:#343a40;border-color:#343a40}.btn-dark:hover{color:#fff;background-color:#23272b;border-color:#1d2124}.btn-dark.focus,.btn-dark:focus{color:#fff;background-color:#23272b;border-color:#1d2124;box-shadow:0 0 0 .2rem rgba(82,88,93,.5)}.btn-dark.disabled,.btn-dark:disabled{color:#fff;background-color:#343a40;border-color:#343a40}.btn-dark:not(:disabled):not(.disabled).active,.btn-dark:not(:disabled):not(.disabled):active,.show>.btn-dark.dropdown-toggle{color:#fff;background-color:#1d2124;border-color:#171a1d}.btn-dark:not(:disabled):not(.disabled).active:focus,.btn-dark:not(:disabled):not(.disabled):active:focus,.show>.btn-dark.dropdown-toggle:focus{box-shadow:0 0 0 .2rem rgba(82,88,93,.5)}.btn-outline-primary{color:#007bff;border-color:#007bff}.btn-outline-primary:hover{color:#fff;background-color:#007bff;border-color:#007bff}.btn-outline-primary.focus,.btn-outline-primary:focus{box-shadow:0 0 0 .2rem rgba(0,123,255,.5)}.btn-outline-primary.disabled,.btn-outline-primary:disabled{color:#007bff;background-color:transparent}.btn-outline-primary:not(:disabled):not(.disabled).active,.btn-outline-primary:not(:disabled):not(.disabled):active,.show>.btn-outline-primary.dropdown-toggle{color:#fff;background-color:#007bff;border-color:#007bff}.btn-outline-primary:not(:disabled):not(.disabled).active:focus,.btn-outline-primary:not(:disabled):not(.disabled):active:focus,.show>.btn-outline-primary.dropdown-toggle:focus{box-shadow:0 0 0 .2rem rgba(0,123,255,.5)}.btn-outline-secondary{color:#6c757d;border-color:#6c757d}.btn-outline-secondary:hover{color:#fff;background-color:#6c757d;border-color:#6c757d}.btn-outline-secondary.focus,.btn-outline-secondary:focus{box-shadow:0 0 0 .2rem rgba(108,117,125,.5)}.btn-outline-secondary.disabled,.btn-outline-secondary:disabled{color:#6c757d;background-color:transparent}.btn-outline-secondary:not(:disabled):not(.disabled).active,.btn-outline-secondary:not(:disabled):not(.disabled):active,.show>.btn-outline-secondary.dropdown-toggle{color:#fff;background-color:#6c757d;border-color:#6c757d}.btn-outline-secondary:not(:disabled):not(.disabled).active:focus,.btn-outline-secondary:not(:disabled):not(.disabled):active:focus,.show>.btn-outline-secondary.dropdown-toggle:focus{box-shadow:0 0 0 .2rem rgba(108,117,125,.5)}.btn-outline-success{color:#28a745;border-color:#28a745}.btn-outline-success:hover{color:#fff;background-color:#28a745;border-color:#28a745}.btn-outline-success.focus,.btn-outline-success:focus{box-shadow:0 0 0 .2rem rgba(40,167,69,.5)}.btn-outline-success.disabled,.btn-outline-success:disabled{color:#28a745;background-color:transparent}.btn-outline-success:not(:disabled):not(.disabled).active,.btn-outline-success:not(:disabled):not(.disabled):active,.show>.btn-outline-success.dropdown-toggle{color:#fff;background-color:#28a745;border-color:#28a745}.btn-outline-success:not(:disabled):not(.disabled).active:focus,.btn-outline-success:not(:disabled):not(.disabled):active:focus,.show>.btn-outline-success.dropdown-toggle:focus{box-shadow:0 0 0 .2rem rgba(40,167,69,.5)}.btn-outline-info{color:#17a2b8;border-color:#17a2b8}.btn-outline-info:hover{color:#fff;background-color:#17a2b8;border-color:#17a2b8}.btn-outline-info.focus,.btn-outline-info:focus{box-shadow:0 0 0 .2rem rgba(23,162,184,.5)}.btn-outline-info.disabled,.btn-outline-info:disabled{color:#17a2b8;background-color:transparent}.btn-outline-info:not(:disabled):not(.disabled).active,.btn-outline-info:not(:disabled):not(.disabled):active,.show>.btn-outline-info.dropdown-toggle{color:#fff;background-color:#17a2b8;border-color:#17a2b8}.btn-outline-info:not(:disabled):not(.disabled).active:focus,.btn-outline-info:not(:disabled):not(.disabled):active:focus,.show>.btn-outline-info.dropdown-toggle:focus{box-shadow:0 0 0 .2rem rgba(23,162,184,.5)}.btn-outline-warning{color:#ffc107;border-color:#ffc107}.btn-outline-warning:hover{color:#212529;background-color:#ffc107;border-color:#ffc107}.btn-outline-warning.focus,.btn-outline-warning:focus{box-shadow:0 0 0 .2rem rgba(255,193,7,.5)}.btn-outline-warning.disabled,.btn-outline-warning:disabled{color:#ffc107;background-color:transparent}.btn-outline-warning:not(:disabled):not(.disabled).active,.btn-outline-warning:not(:disabled):not(.disabled):active,.show>.btn-outline-warning.dropdown-toggle{color:#212529;background-color:#ffc107;border-color:#ffc107}.btn-outline-warning:not(:disabled):not(.disabled).active:focus,.btn-outline-warning:not(:disabled):not(.disabled):active:focus,.show>.btn-outline-warning.dropdown-toggle:focus{box-shadow:0 0 0 .2rem rgba(255,193,7,.5)}.btn-outline-danger{color:#dc3545;border-color:#dc3545}.btn-outline-danger:hover{color:#fff;background-color:#dc3545;border-color:#dc3545}.btn-outline-danger.focus,.btn-outline-danger:focus{box-shadow:0 0 0 .2rem rgba(220,53,69,.5)}.btn-outline-danger.disabled,.btn-outline-danger:disabled{color:#dc3545;background-color:transparent}.btn-outline-danger:not(:disabled):not(.disabled).active,.btn-outline-danger:not(:disabled):not(.disabled):active,.show>.btn-outline-danger.dropdown-toggle{color:#fff;background-color:#dc3545;border-color:#dc3545}.btn-outline-danger:not(:disabled):not(.disabled).active:focus,.btn-outline-danger:not(:disabled):not(.disabled):active:focus,.show>.btn-outline-danger.dropdown-toggle:focus{box-shadow:0 0 0 .2rem rgba(220,53,69,.5)}.btn-outline-light{color:#f8f9fa;border-color:#f8f9fa}.btn-outline-light:hover{color:#212529;background-color:#f8f9fa;border-color:#f8f9fa}.btn-outline-light.focus,.btn-outline-light:focus{box-shadow:0 0 0 .2rem rgba(248,249,250,.5)}.btn-outline-light.disabled,.btn-outline-light:disabled{color:#f8f9fa;background-color:transparent}.btn-outline-light:not(:disabled):not(.disabled).active,.btn-outline-light:not(:disabled):not(.disabled):active,.show>.btn-outline-light.dropdown-toggle{color:#212529;background-color:#f8f9fa;border-color:#f8f9fa}.btn-outline-light:not(:disabled):not(.disabled).active:focus,.btn-outline-light:not(:disabled):not(.disabled):active:focus,.show>.btn-outline-light.dropdown-toggle:focus{box-shadow:0 0 0 .2rem rgba(248,249,250,.5)}.btn-outline-dark{color:#343a40;border-color:#343a40}.btn-outline-dark:hover{color:#fff;background-color:#343a40;border-color:#343a40}.btn-outline-dark.focus,.btn-outline-dark:focus{box-shadow:0 0 0 .2rem rgba(52,58,64,.5)}.btn-outline-dark.disabled,.btn-outline-dark:disabled{color:#343a40;background-color:transparent}.btn-outline-dark:not(:disabled):not(.disabled).active,.btn-outline-dark:not(:disabled):not(.disabled):active,.show>.btn-outline-dark.dropdown-toggle{color:#fff;background-color:#343a40;border-color:#343a40}.btn-outline-dark:not(:disabled):not(.disabled).active:focus,.btn-outline-dark:not(:disabled):not(.disabled):active:focus,.show>.btn-outline-dark.dropdown-toggle:focus{box-shadow:0 0 0 .2rem rgba(52,58,64,.5)}.btn-link{font-weight:400;color:#007bff;text-decoration:none}.btn-link:hover{color:#0056b3;text-decoration:underline}.btn-link.focus,.btn-link:focus{text-decoration:underline}.btn-link.disabled,.btn-link:disabled{color:#6c757d;pointer-events:none}.btn-group-lg>.btn,.btn-lg{padding:.5rem 1rem;font-size:1.25rem;line-height:1.5;border-radius:.3rem}.btn-group-sm>.btn,.btn-sm{padding:.25rem .5rem;font-size:.875rem;line-height:1.5;border-radius:.2rem}.btn-block{display:block;width:100%}.btn-block+.btn-block{margin-top:.5rem}input[type=button].btn-block,input[type=reset].btn-block,input[type=submit].btn-block{width:100%}.fade{transition:opacity .15s linear}@media (prefers-reduced-motion:reduce){.fade{transition:none}}.fade:not(.show){opacity:0}.collapse:not(.show){display:none}.collapsing{position:relative;height:0;overflow:hidden;transition:height .35s ease}@media (prefers-reduced-motion:reduce){.collapsing{transition:none}}.dropdown,.dropleft,.dropright,.dropup{position:relative}.dropdown-toggle{white-space:nowrap}.dropdown-toggle::after{display:inline-block;margin-left:.255em;vertical-align:.255em;content:"";border-top:.3em solid;border-right:.3em solid transparent;border-bottom:0;border-left:.3em solid transparent}.dropdown-toggle:empty::after{margin-left:0}.dropdown-menu{position:absolute;top:100%;left:0;z-index:1000;display:none;float:left;min-width:10rem;padding:.5rem 0;margin:.125rem 0 0;font-size:1rem;color:#212529;text-align:left;list-style:none;background-color:#fff;background-clip:padding-box;border:1px solid rgba(0,0,0,.15);border-radius:.25rem}.dropdown-menu-left{right:auto;left:0}.dropdown-menu-right{right:0;left:auto}@media (min-width:576px){.dropdown-menu-sm-left{right:auto;left:0}.dropdown-menu-sm-right{right:0;left:auto}}@media (min-width:768px){.dropdown-menu-md-left{right:auto;left:0}.dropdown-menu-md-right{right:0;left:auto}}@media (min-width:992px){.dropdown-menu-lg-left{right:auto;left:0}.dropdown-menu-lg-right{right:0;left:auto}}@media (min-width:1200px){.dropdown-menu-xl-left{right:auto;left:0}.dropdown-menu-xl-right{right:0;left:auto}}.dropup .dropdown-menu{top:auto;bottom:100%;margin-top:0;margin-bottom:.125rem}.dropup .dropdown-toggle::after{display:inline-block;margin-left:.255em;vertical-align:.255em;content:"";border-top:0;border-right:.3em solid transparent;border-bottom:.3em solid;border-left:.3em solid transparent}.dropup .dropdown-toggle:empty::after{margin-left:0}.dropright .dropdown-menu{top:0;right:auto;left:100%;margin-top:0;margin-left:.125rem}.dropright .dropdown-toggle::after{display:inline-block;margin-left:.255em;vertical-align:.255em;content:"";border-top:.3em solid transparent;border-right:0;border-bottom:.3em solid transparent;border-left:.3em solid}.dropright .dropdown-toggle:empty::after{margin-left:0}.dropright .dropdown-toggle::after{vertical-align:0}.dropleft .dropdown-menu{top:0;right:100%;left:auto;margin-top:0;margin-right:.125rem}.dropleft .dropdown-toggle::after{display:inline-block;margin-left:.255em;vertical-align:.255em;content:""}.dropleft .dropdown-toggle::after{display:none}.dropleft .dropdown-toggle::before{display:inline-block;margin-right:.255em;vertical-align:.255em;content:"";border-top:.3em solid transparent;border-right:.3em solid;border-bottom:.3em solid transparent}.dropleft .dropdown-toggle:empty::after{margin-left:0}.dropleft .dropdown-toggle::before{vertical-align:0}.dropdown-menu[x-placement^=bottom],.dropdown-menu[x-placement^=left],.dropdown-menu[x-placement^=right],.dropdown-menu[x-placement^=top]{right:auto;bottom:auto}.dropdown-divider{height:0;margin:.5rem 0;overflow:hidden;border-top:1px solid #e9ecef}.dropdown-item{display:block;width:100%;padding:.25rem 1.5rem;clear:both;font-weight:400;color:#212529;text-align:inherit;white-space:nowrap;background-color:transparent;border:0}.dropdown-item:focus,.dropdown-item:hover{color:#16181b;text-decoration:none;background-color:#f8f9fa}.dropdown-item.active,.dropdown-item:active{color:#fff;text-decoration:none;background-color:#007bff}.dropdown-item.disabled,.dropdown-item:disabled{color:#6c757d;pointer-events:none;background-color:transparent}.dropdown-menu.show{display:block}.dropdown-header{display:block;padding:.5rem 1.5rem;margin-bottom:0;font-size:.875rem;color:#6c757d;white-space:nowrap}.dropdown-item-text{display:block;padding:.25rem 1.5rem;color:#212529}.btn-group,.btn-group-vertical{position:relative;display:-ms-inline-flexbox;display:inline-flex;vertical-align:middle}.btn-group-vertical>.btn,.btn-group>.btn{position:relative;-ms-flex:1 1 auto;flex:1 1 auto}.btn-group-vertical>.btn:hover,.btn-group>.btn:hover{z-index:1}.btn-group-vertical>.btn.active,.btn-group-vertical>.btn:active,.btn-group-vertical>.btn:focus,.btn-group>.btn.active,.btn-group>.btn:active,.btn-group>.btn:focus{z-index:1}.btn-toolbar{display:-ms-flexbox;display:flex;-ms-flex-wrap:wrap;flex-wrap:wrap;-ms-flex-pack:start;justify-content:flex-start}.btn-toolbar .input-group{width:auto}.btn-group>.btn-group:not(:first-child),.btn-group>.btn:not(:first-child){margin-left:-1px}.btn-group>.btn-group:not(:last-child)>.btn,.btn-group>.btn:not(:last-child):not(.dropdown-toggle){border-top-right-radius:0;border-bottom-right-radius:0}.btn-group>.btn-group:not(:first-child)>.btn,.btn-group>.btn:not(:first-child){border-top-left-radius:0;border-bottom-left-radius:0}.dropdown-toggle-split{padding-right:.5625rem;padding-left:.5625rem}.dropdown-toggle-split::after,.dropright .dropdown-toggle-split::after,.dropup .dropdown-toggle-split::after{margin-left:0}.dropleft .dropdown-toggle-split::before{margin-right:0}.btn-group-sm>.btn+.dropdown-toggle-split,.btn-sm+.dropdown-toggle-split{padding-right:.375rem;padding-left:.375rem}.btn-group-lg>.btn+.dropdown-toggle-split,.btn-lg+.dropdown-toggle-split{padding-right:.75rem;padding-left:.75rem}.btn-group-vertical{-ms-flex-direction:column;flex-direction:column;-ms-flex-align:start;align-items:flex-start;-ms-flex-pack:center;justify-content:center}.btn-group-vertical>.btn,.btn-group-vertical>.btn-group{width:100%}.btn-group-vertical>.btn-group:not(:first-child),.btn-group-vertical>.btn:not(:first-child){margin-top:-1px}.btn-group-vertical>.btn-group:not(:last-child)>.btn,.btn-group-vertical>.btn:not(:last-child):not(.dropdown-toggle){border-bottom-right-radius:0;border-bottom-left-radius:0}.btn-group-vertical>.btn-group:not(:first-child)>.btn,.btn-group-vertical>.btn:not(:first-child){border-top-left-radius:0;border-top-right-radius:0}.btn-group-toggle>.btn,.btn-group-toggle>.btn-group>.btn{margin-bottom:0}.btn-group-toggle>.btn input[type=checkbox],.btn-group-toggle>.btn input[type=radio],.btn-group-toggle>.btn-group>.btn input[type=checkbox],.btn-group-toggle>.btn-group>.btn input[type=radio]{position:absolute;clip:rect(0,0,0,0);pointer-events:none}.input-group{position:relative;display:-ms-flexbox;display:flex;-ms-flex-wrap:wrap;flex-wrap:wrap;-ms-flex-align:stretch;align-items:stretch;width:100%}.input-group>.custom-file,.input-group>.custom-select,.input-group>.form-control,.input-group>.form-control-plaintext{position:relative;-ms-flex:1 1 auto;flex:1 1 auto;width:1%;min-width:0;margin-bottom:0}.input-group>.custom-file+.custom-file,.input-group>.custom-file+.custom-select,.input-group>.custom-file+.form-control,.input-group>.custom-select+.custom-file,.input-group>.custom-select+.custom-select,.input-group>.custom-select+.form-control,.input-group>.form-control+.custom-file,.input-group>.form-control+.custom-select,.input-group>.form-control+.form-control,.input-group>.form-control-plaintext+.custom-file,.input-group>.form-control-plaintext+.custom-select,.input-group>.form-control-plaintext+.form-control{margin-left:-1px}.input-group>.custom-file .custom-file-input:focus~.custom-file-label,.input-group>.custom-select:focus,.input-group>.form-control:focus{z-index:3}.input-group>.custom-file .custom-file-input:focus{z-index:4}.input-group>.custom-select:not(:last-child),.input-group>.form-control:not(:last-child){border-top-right-radius:0;border-bottom-right-radius:0}.input-group>.custom-select:not(:first-child),.input-group>.form-control:not(:first-child){border-top-left-radius:0;border-bottom-left-radius:0}.input-group>.custom-file{display:-ms-flexbox;display:flex;-ms-flex-align:center;align-items:center}.input-group>.custom-file:not(:last-child) .custom-file-label,.input-group>.custom-file:not(:last-child) .custom-file-label::after{border-top-right-radius:0;border-bottom-right-radius:0}.input-group>.custom-file:not(:first-child) .custom-file-label{border-top-left-radius:0;border-bottom-left-radius:0}.input-group-append,.input-group-prepend{display:-ms-flexbox;display:flex}.input-group-append .btn,.input-group-prepend .btn{position:relative;z-index:2}.input-group-append .btn:focus,.input-group-prepend .btn:focus{z-index:3}.input-group-append .btn+.btn,.input-group-append .btn+.input-group-text,.input-group-append .input-group-text+.btn,.input-group-append .input-group-text+.input-group-text,.input-group-prepend .btn+.btn,.input-group-prepend .btn+.input-group-text,.input-group-prepend .input-group-text+.btn,.input-group-prepend .input-group-text+.input-group-text{margin-left:-1px}.input-group-prepend{margin-right:-1px}.input-group-append{margin-left:-1px}.input-group-text{display:-ms-flexbox;display:flex;-ms-flex-align:center;align-items:center;padding:.375rem .75rem;margin-bottom:0;font-size:1rem;font-weight:400;line-height:1.5;color:#495057;text-align:center;white-space:nowrap;background-color:#e9ecef;border:1px solid #ced4da;border-radius:.25rem}.input-group-text input[type=checkbox],.input-group-text input[type=radio]{margin-top:0}.input-group-lg>.custom-select,.input-group-lg>.form-control:not(textarea){height:calc(1.5em + 1rem + 2px)}.input-group-lg>.custom-select,.input-group-lg>.form-control,.input-group-lg>.input-group-append>.btn,.input-group-lg>.input-group-append>.input-group-text,.input-group-lg>.input-group-prepend>.btn,.input-group-lg>.input-group-prepend>.input-group-text{padding:.5rem 1rem;font-size:1.25rem;line-height:1.5;border-radius:.3rem}.input-group-sm>.custom-select,.input-group-sm>.form-control:not(textarea){height:calc(1.5em + .5rem + 2px)}.input-group-sm>.custom-select,.input-group-sm>.form-control,.input-group-sm>.input-group-append>.btn,.input-group-sm>.input-group-append>.input-group-text,.input-group-sm>.input-group-prepend>.btn,.input-group-sm>.input-group-prepend>.input-group-text{padding:.25rem .5rem;font-size:.875rem;line-height:1.5;border-radius:.2rem}.input-group-lg>.custom-select,.input-group-sm>.custom-select{padding-right:1.75rem}.input-group>.input-group-append:last-child>.btn:not(:last-child):not(.dropdown-toggle),.input-group>.input-group-append:last-child>.input-group-text:not(:last-child),.input-group>.input-group-append:not(:last-child)>.btn,.input-group>.input-group-append:not(:last-child)>.input-group-text,.input-group>.input-group-prepend>.btn,.input-group>.input-group-prepend>.input-group-text{border-top-right-radius:0;border-bottom-right-radius:0}.input-group>.input-group-append>.btn,.input-group>.input-group-append>.input-group-text,.input-group>.input-group-prepend:first-child>.btn:not(:first-child),.input-group>.input-group-prepend:first-child>.input-group-text:not(:first-child),.input-group>.input-group-prepend:not(:first-child)>.btn,.input-group>.input-group-prepend:not(:first-child)>.input-group-text{border-top-left-radius:0;border-bottom-left-radius:0}.custom-control{position:relative;display:block;min-height:1.5rem;padding-left:1.5rem}.custom-control-inline{display:-ms-inline-flexbox;display:inline-flex;margin-right:1rem}.custom-control-input{position:absolute;left:0;z-index:-1;width:1rem;height:1.25rem;opacity:0}.custom-control-input:checked~.custom-control-label::before{color:#fff;border-color:#007bff;background-color:#007bff}.custom-control-input:focus~.custom-control-label::before{box-shadow:0 0 0 .2rem rgba(0,123,255,.25)}.custom-control-input:focus:not(:checked)~.custom-control-label::before{border-color:#80bdff}.custom-control-input:not(:disabled):active~.custom-control-label::before{color:#fff;background-color:#b3d7ff;border-color:#b3d7ff}.custom-control-input:disabled~.custom-control-label,.custom-control-input[disabled]~.custom-control-label{color:#6c757d}.custom-control-input:disabled~.custom-control-label::before,.custom-control-input[disabled]~.custom-control-label::before{background-color:#e9ecef}.custom-control-label{position:relative;margin-bottom:0;vertical-align:top}.custom-control-label::before{position:absolute;top:.25rem;left:-1.5rem;display:block;width:1rem;height:1rem;pointer-events:none;content:"";background-color:#fff;border:#adb5bd solid 1px}.custom-control-label::after{position:absolute;top:.25rem;left:-1.5rem;display:block;width:1rem;height:1rem;content:"";background:no-repeat 50%/50% 50%}.custom-checkbox .custom-control-label::before{border-radius:.25rem}.custom-checkbox .custom-control-input:checked~.custom-control-label::after{background-image:url("data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' width='8' height='8' viewBox='0 0 8 8'%3e%3cpath fill='%23fff' d='M6.564.75l-3.59 3.612-1.538-1.55L0 4.26l2.974 2.99L8 2.193z'/%3e%3c/svg%3e")}.custom-checkbox .custom-control-input:indeterminate~.custom-control-label::before{border-color:#007bff;background-color:#007bff}.custom-checkbox .custom-control-input:indeterminate~.custom-control-label::after{background-image:url("data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' width='4' height='4' viewBox='0 0 4 4'%3e%3cpath stroke='%23fff' d='M0 2h4'/%3e%3c/svg%3e")}.custom-checkbox .custom-control-input:disabled:checked~.custom-control-label::before{background-color:rgba(0,123,255,.5)}.custom-checkbox .custom-control-input:disabled:indeterminate~.custom-control-label::before{background-color:rgba(0,123,255,.5)}.custom-radio .custom-control-label::before{border-radius:50%}.custom-radio .custom-control-input:checked~.custom-control-label::after{background-image:url("data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' width='12' height='12' viewBox='-4 -4 8 8'%3e%3ccircle r='3' fill='%23fff'/%3e%3c/svg%3e")}.custom-radio .custom-control-input:disabled:checked~.custom-control-label::before{background-color:rgba(0,123,255,.5)}.custom-switch{padding-left:2.25rem}.custom-switch .custom-control-label::before{left:-2.25rem;width:1.75rem;pointer-events:all;border-radius:.5rem}.custom-switch .custom-control-label::after{top:calc(.25rem + 2px);left:calc(-2.25rem + 2px);width:calc(1rem - 4px);height:calc(1rem - 4px);background-color:#adb5bd;border-radius:.5rem;transition:background-color .15s ease-in-out,border-color .15s ease-in-out,box-shadow .15s ease-in-out,-webkit-transform .15s ease-in-out;transition:transform .15s ease-in-out,background-color .15s ease-in-out,border-color .15s ease-in-out,box-shadow .15s ease-in-out;transition:transform .15s ease-in-out,background-color .15s ease-in-out,border-color .15s ease-in-out,box-shadow .15s ease-in-out,-webkit-transform .15s ease-in-out}@media (prefers-reduced-motion:reduce){.custom-switch .custom-control-label::after{transition:none}}.custom-switch .custom-control-input:checked~.custom-control-label::after{background-color:#fff;-webkit-transform:translateX(.75rem);transform:translateX(.75rem)}.custom-switch .custom-control-input:disabled:checked~.custom-control-label::before{background-color:rgba(0,123,255,.5)}.custom-select{display:inline-block;width:100%;height:calc(1.5em + .75rem + 2px);padding:.375rem 1.75rem .375rem .75rem;font-size:1rem;font-weight:400;line-height:1.5;color:#495057;vertical-align:middle;background:#fff url("data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' width='4' height='5' viewBox='0 0 4 5'%3e%3cpath fill='%23343a40' d='M2 0L0 2h4zm0 5L0 3h4z'/%3e%3c/svg%3e") no-repeat right .75rem center/8px 10px;border:1px solid #ced4da;border-radius:.25rem;-webkit-appearance:none;-moz-appearance:none;appearance:none}.custom-select:focus{border-color:#80bdff;outline:0;box-shadow:0 0 0 .2rem rgba(0,123,255,.25)}.custom-select:focus::-ms-value{color:#495057;background-color:#fff}.custom-select[multiple],.custom-select[size]:not([size="1"]){height:auto;padding-right:.75rem;background-image:none}.custom-select:disabled{color:#6c757d;background-color:#e9ecef}.custom-select::-ms-expand{display:none}.custom-select:-moz-focusring{color:transparent;text-shadow:0 0 0 #495057}.custom-select-sm{height:calc(1.5em + .5rem + 2px);padding-top:.25rem;padding-bottom:.25rem;padding-left:.5rem;font-size:.875rem}.custom-select-lg{height:calc(1.5em + 1rem + 2px);padding-top:.5rem;padding-bottom:.5rem;padding-left:1rem;font-size:1.25rem}.custom-file{position:relative;display:inline-block;width:100%;height:calc(1.5em + .75rem + 2px);margin-bottom:0}.custom-file-input{position:relative;z-index:2;width:100%;height:calc(1.5em + .75rem + 2px);margin:0;opacity:0}.custom-file-input:focus~.custom-file-label{border-color:#80bdff;box-shadow:0 0 0 .2rem rgba(0,123,255,.25)}.custom-file-input:disabled~.custom-file-label,.custom-file-input[disabled]~.custom-file-label{background-color:#e9ecef}.custom-file-input:lang(en)~.custom-file-label::after{content:"Browse"}.custom-file-input~.custom-file-label[data-browse]::after{content:attr(data-browse)}.custom-file-label{position:absolute;top:0;right:0;left:0;z-index:1;height:calc(1.5em + .75rem + 2px);padding:.375rem .75rem;font-weight:400;line-height:1.5;color:#495057;background-color:#fff;border:1px solid #ced4da;border-radius:.25rem}.custom-file-label::after{position:absolute;top:0;right:0;bottom:0;z-index:3;display:block;height:calc(1.5em + .75rem);padding:.375rem .75rem;line-height:1.5;color:#495057;content:"Browse";background-color:#e9ecef;border-left:inherit;border-radius:0 .25rem .25rem 0}.custom-range{width:100%;height:1.4rem;padding:0;background-color:transparent;-webkit-appearance:none;-moz-appearance:none;appearance:none}.custom-range:focus{outline:0}.custom-range:focus::-webkit-slider-thumb{box-shadow:0 0 0 1px #fff,0 0 0 .2rem rgba(0,123,255,.25)}.custom-range:focus::-moz-range-thumb{box-shadow:0 0 0 1px #fff,0 0 0 .2rem rgba(0,123,255,.25)}.custom-range:focus::-ms-thumb{box-shadow:0 0 0 1px #fff,0 0 0 .2rem rgba(0,123,255,.25)}.custom-range::-moz-focus-outer{border:0}.custom-range::-webkit-slider-thumb{width:1rem;height:1rem;margin-top:-.25rem;background-color:#007bff;border:0;border-radius:1rem;-webkit-transition:background-color .15s ease-in-out,border-color .15s ease-in-out,box-shadow .15s ease-in-out;transition:background-color .15s ease-in-out,border-color .15s ease-in-out,box-shadow .15s ease-in-out;-webkit-appearance:none;appearance:none}@media (prefers-reduced-motion:reduce){.custom-range::-webkit-slider-thumb{-webkit-transition:none;transition:none}}.custom-range::-webkit-slider-thumb:active{background-color:#b3d7ff}.custom-range::-webkit-slider-runnable-track{width:100%;height:.5rem;color:transparent;cursor:pointer;background-color:#dee2e6;border-color:transparent;border-radius:1rem}.custom-range::-moz-range-thumb{width:1rem;height:1rem;background-color:#007bff;border:0;border-radius:1rem;-moz-transition:background-color .15s ease-in-out,border-color .15s ease-in-out,box-shadow .15s ease-in-out;transition:background-color .15s ease-in-out,border-color .15s ease-in-out,box-shadow .15s ease-in-out;-moz-appearance:none;appearance:none}@media (prefers-reduced-motion:reduce){.custom-range::-moz-range-thumb{-moz-transition:none;transition:none}}.custom-range::-moz-range-thumb:active{background-color:#b3d7ff}.custom-range::-moz-range-track{width:100%;height:.5rem;color:transparent;cursor:pointer;background-color:#dee2e6;border-color:transparent;border-radius:1rem}.custom-range::-ms-thumb{width:1rem;height:1rem;margin-top:0;margin-right:.2rem;margin-left:.2rem;background-color:#007bff;border:0;border-radius:1rem;-ms-transition:background-color .15s ease-in-out,border-color .15s ease-in-out,box-shadow .15s ease-in-out;transition:background-color .15s ease-in-out,border-color .15s ease-in-out,box-shadow .15s ease-in-out;appearance:none}@media (prefers-reduced-motion:reduce){.custom-range::-ms-thumb{-ms-transition:none;transition:none}}.custom-range::-ms-thumb:active{background-color:#b3d7ff}.custom-range::-ms-track{width:100%;height:.5rem;color:transparent;cursor:pointer;background-color:transparent;border-color:transparent;border-width:.5rem}.custom-range::-ms-fill-lower{background-color:#dee2e6;border-radius:1rem}.custom-range::-ms-fill-upper{margin-right:15px;background-color:#dee2e6;border-radius:1rem}.custom-range:disabled::-webkit-slider-thumb{background-color:#adb5bd}.custom-range:disabled::-webkit-slider-runnable-track{cursor:default}.custom-range:disabled::-moz-range-thumb{background-color:#adb5bd}.custom-range:disabled::-moz-range-track{cursor:default}.custom-range:disabled::-ms-thumb{background-color:#adb5bd}.custom-control-label::before,.custom-file-label,.custom-select{transition:background-color .15s ease-in-out,border-color .15s ease-in-out,box-shadow .15s ease-in-out}@media (prefers-reduced-motion:reduce){.custom-control-label::before,.custom-file-label,.custom-select{transition:none}}.nav{display:-ms-flexbox;display:flex;-ms-flex-wrap:wrap;flex-wrap:wrap;padding-left:0;margin-bottom:0;list-style:none}.nav-link{display:block;padding:.5rem 1rem}.nav-link:focus,.nav-link:hover{text-decoration:none}.nav-link.disabled{color:#6c757d;pointer-events:none;cursor:default}.nav-tabs{border-bottom:1px solid #dee2e6}.nav-tabs .nav-item{margin-bottom:-1px}.nav-tabs .nav-link{border:1px solid transparent;border-top-left-radius:.25rem;border-top-right-radius:.25rem}.nav-tabs .nav-link:focus,.nav-tabs .nav-link:hover{border-color:#e9ecef #e9ecef #dee2e6}.nav-tabs .nav-link.disabled{color:#6c757d;background-color:transparent;border-color:transparent}.nav-tabs .nav-item.show .nav-link,.nav-tabs .nav-link.active{color:#495057;background-color:#fff;border-color:#dee2e6 #dee2e6 #fff}.nav-tabs .dropdown-menu{margin-top:-1px;border-top-left-radius:0;border-top-right-radius:0}.nav-pills .nav-link{border-radius:.25rem}.nav-pills .nav-link.active,.nav-pills .show>.nav-link{color:#fff;background-color:#007bff}.nav-fill .nav-item{-ms-flex:1 1 auto;flex:1 1 auto;text-align:center}.nav-justified .nav-item{-ms-flex-preferred-size:0;flex-basis:0;-ms-flex-positive:1;flex-grow:1;text-align:center}.tab-content>.tab-pane{display:none}.tab-content>.active{display:block}.navbar{position:relative;display:-ms-flexbox;display:flex;-ms-flex-wrap:wrap;flex-wrap:wrap;-ms-flex-align:center;align-items:center;-ms-flex-pack:justify;justify-content:space-between;padding:.5rem 1rem}.navbar .container,.navbar .container-fluid,.navbar .container-lg,.navbar .container-md,.navbar .container-sm,.navbar .container-xl{display:-ms-flexbox;display:flex;-ms-flex-wrap:wrap;flex-wrap:wrap;-ms-flex-align:center;align-items:center;-ms-flex-pack:justify;justify-content:space-between}.navbar-brand{display:inline-block;padding-top:.3125rem;padding-bottom:.3125rem;margin-right:1rem;font-size:1.25rem;line-height:inherit;white-space:nowrap}.navbar-brand:focus,.navbar-brand:hover{text-decoration:none}.navbar-nav{display:-ms-flexbox;display:flex;-ms-flex-direction:column;flex-direction:column;padding-left:0;margin-bottom:0;list-style:none}.navbar-nav .nav-link{padding-right:0;padding-left:0}.navbar-nav .dropdown-menu{position:static;float:none}.navbar-text{display:inline-block;padding-top:.5rem;padding-bottom:.5rem}.navbar-collapse{-ms-flex-preferred-size:100%;flex-basis:100%;-ms-flex-positive:1;flex-grow:1;-ms-flex-align:center;align-items:center}.navbar-toggler{padding:.25rem .75rem;font-size:1.25rem;line-height:1;background-color:transparent;border:1px solid transparent;border-radius:.25rem}.navbar-toggler:focus,.navbar-toggler:hover{text-decoration:none}.navbar-toggler-icon{display:inline-block;width:1.5em;height:1.5em;vertical-align:middle;content:"";background:no-repeat center center;background-size:100% 100%}@media (max-width:575.98px){.navbar-expand-sm>.container,.navbar-expand-sm>.container-fluid,.navbar-expand-sm>.container-lg,.navbar-expand-sm>.container-md,.navbar-expand-sm>.container-sm,.navbar-expand-sm>.container-xl{padding-right:0;padding-left:0}}@media (min-width:576px){.navbar-expand-sm{-ms-flex-flow:row nowrap;flex-flow:row nowrap;-ms-flex-pack:start;justify-content:flex-start}.navbar-expand-sm .navbar-nav{-ms-flex-direction:row;flex-direction:row}.navbar-expand-sm .navbar-nav .dropdown-menu{position:absolute}.navbar-expand-sm .navbar-nav .nav-link{padding-right:.5rem;padding-left:.5rem}.navbar-expand-sm>.container,.navbar-expand-sm>.container-fluid,.navbar-expand-sm>.container-lg,.navbar-expand-sm>.container-md,.navbar-expand-sm>.container-sm,.navbar-expand-sm>.container-xl{-ms-flex-wrap:nowrap;flex-wrap:nowrap}.navbar-expand-sm .navbar-collapse{display:-ms-flexbox!important;display:flex!important;-ms-flex-preferred-size:auto;flex-basis:auto}.navbar-expand-sm .navbar-toggler{display:none}}@media (max-width:767.98px){.navbar-expand-md>.container,.navbar-expand-md>.container-fluid,.navbar-expand-md>.container-lg,.navbar-expand-md>.container-md,.navbar-expand-md>.container-sm,.navbar-expand-md>.container-xl{padding-right:0;padding-left:0}}@media (min-width:768px){.navbar-expand-md{-ms-flex-flow:row nowrap;flex-flow:row nowrap;-ms-flex-pack:start;justify-content:flex-start}.navbar-expand-md .navbar-nav{-ms-flex-direction:row;flex-direction:row}.navbar-expand-md .navbar-nav .dropdown-menu{position:absolute}.navbar-expand-md .navbar-nav .nav-link{padding-right:.5rem;padding-left:.5rem}.navbar-expand-md>.container,.navbar-expand-md>.container-fluid,.navbar-expand-md>.container-lg,.navbar-expand-md>.container-md,.navbar-expand-md>.container-sm,.navbar-expand-md>.container-xl{-ms-flex-wrap:nowrap;flex-wrap:nowrap}.navbar-expand-md .navbar-collapse{display:-ms-flexbox!important;display:flex!important;-ms-flex-preferred-size:auto;flex-basis:auto}.navbar-expand-md .navbar-toggler{display:none}}@media (max-width:991.98px){.navbar-expand-lg>.container,.navbar-expand-lg>.container-fluid,.navbar-expand-lg>.container-lg,.navbar-expand-lg>.container-md,.navbar-expand-lg>.container-sm,.navbar-expand-lg>.container-xl{padding-right:0;padding-left:0}}@media (min-width:992px){.navbar-expand-lg{-ms-flex-flow:row nowrap;flex-flow:row nowrap;-ms-flex-pack:start;justify-content:flex-start}.navbar-expand-lg .navbar-nav{-ms-flex-direction:row;flex-direction:row}.navbar-expand-lg .navbar-nav .dropdown-menu{position:absolute}.navbar-expand-lg .navbar-nav .nav-link{padding-right:.5rem;padding-left:.5rem}.navbar-expand-lg>.container,.navbar-expand-lg>.container-fluid,.navbar-expand-lg>.container-lg,.navbar-expand-lg>.container-md,.navbar-expand-lg>.container-sm,.navbar-expand-lg>.container-xl{-ms-flex-wrap:nowrap;flex-wrap:nowrap}.navbar-expand-lg .navbar-collapse{display:-ms-flexbox!important;display:flex!important;-ms-flex-preferred-size:auto;flex-basis:auto}.navbar-expand-lg .navbar-toggler{display:none}}@media (max-width:1199.98px){.navbar-expand-xl>.container,.navbar-expand-xl>.container-fluid,.navbar-expand-xl>.container-lg,.navbar-expand-xl>.container-md,.navbar-expand-xl>.container-sm,.navbar-expand-xl>.container-xl{padding-right:0;padding-left:0}}@media (min-width:1200px){.navbar-expand-xl{-ms-flex-flow:row nowrap;flex-flow:row nowrap;-ms-flex-pack:start;justify-content:flex-start}.navbar-expand-xl .navbar-nav{-ms-flex-direction:row;flex-direction:row}.navbar-expand-xl .navbar-nav .dropdown-menu{position:absolute}.navbar-expand-xl .navbar-nav .nav-link{padding-right:.5rem;padding-left:.5rem}.navbar-expand-xl>.container,.navbar-expand-xl>.container-fluid,.navbar-expand-xl>.container-lg,.navbar-expand-xl>.container-md,.navbar-expand-xl>.container-sm,.navbar-expand-xl>.container-xl{-ms-flex-wrap:nowrap;flex-wrap:nowrap}.navbar-expand-xl .navbar-collapse{display:-ms-flexbox!important;display:flex!important;-ms-flex-preferred-size:auto;flex-basis:auto}.navbar-expand-xl .navbar-toggler{display:none}}.navbar-expand{-ms-flex-flow:row nowrap;flex-flow:row nowrap;-ms-flex-pack:start;justify-content:flex-start}.navbar-expand>.container,.navbar-expand>.container-fluid,.navbar-expand>.container-lg,.navbar-expand>.container-md,.navbar-expand>.container-sm,.navbar-expand>.container-xl{padding-right:0;padding-left:0}.navbar-expand .navbar-nav{-ms-flex-direction:row;flex-direction:row}.navbar-expand .navbar-nav .dropdown-menu{position:absolute}.navbar-expand .navbar-nav .nav-link{padding-right:.5rem;padding-left:.5rem}.navbar-expand>.container,.navbar-expand>.container-fluid,.navbar-expand>.container-lg,.navbar-expand>.container-md,.navbar-expand>.container-sm,.navbar-expand>.container-xl{-ms-flex-wrap:nowrap;flex-wrap:nowrap}.navbar-expand .navbar-collapse{display:-ms-flexbox!important;display:flex!important;-ms-flex-preferred-size:auto;flex-basis:auto}.navbar-expand .navbar-toggler{display:none}.navbar-light .navbar-brand{color:rgba(0,0,0,.9)}.navbar-light .navbar-brand:focus,.navbar-light .navbar-brand:hover{color:rgba(0,0,0,.9)}.navbar-light .navbar-nav .nav-link{color:rgba(0,0,0,.5)}.navbar-light .navbar-nav .nav-link:focus,.navbar-light .navbar-nav .nav-link:hover{color:rgba(0,0,0,.7)}.navbar-light .navbar-nav .nav-link.disabled{color:rgba(0,0,0,.3)}.navbar-light .navbar-nav .active>.nav-link,.navbar-light .navbar-nav .nav-link.active,.navbar-light .navbar-nav .nav-link.show,.navbar-light .navbar-nav .show>.nav-link{color:rgba(0,0,0,.9)}.navbar-light .navbar-toggler{color:rgba(0,0,0,.5);border-color:rgba(0,0,0,.1)}.navbar-light .navbar-toggler-icon{background-image:url("data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' width='30' height='30' viewBox='0 0 30 30'%3e%3cpath stroke='rgba%280, 0, 0, 0.5%29' stroke-linecap='round' stroke-miterlimit='10' stroke-width='2' d='M4 7h22M4 15h22M4 23h22'/%3e%3c/svg%3e")}.navbar-light .navbar-text{color:rgba(0,0,0,.5)}.navbar-light .navbar-text a{color:rgba(0,0,0,.9)}.navbar-light .navbar-text a:focus,.navbar-light .navbar-text a:hover{color:rgba(0,0,0,.9)}.navbar-dark .navbar-brand{color:#fff}.navbar-dark .navbar-brand:focus,.navbar-dark .navbar-brand:hover{color:#fff}.navbar-dark .navbar-nav .nav-link{color:rgba(255,255,255,.5)}.navbar-dark .navbar-nav .nav-link:focus,.navbar-dark .navbar-nav .nav-link:hover{color:rgba(255,255,255,.75)}.navbar-dark .navbar-nav .nav-link.disabled{color:rgba(255,255,255,.25)}.navbar-dark .navbar-nav .active>.nav-link,.navbar-dark .navbar-nav .nav-link.active,.navbar-dark .navbar-nav .nav-link.show,.navbar-dark .navbar-nav .show>.nav-link{color:#fff}.navbar-dark .navbar-toggler{color:rgba(255,255,255,.5);border-color:rgba(255,255,255,.1)}.navbar-dark .navbar-toggler-icon{background-image:url("data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' width='30' height='30' viewBox='0 0 30 30'%3e%3cpath stroke='rgba%28255, 255, 255, 0.5%29' stroke-linecap='round' stroke-miterlimit='10' stroke-width='2' d='M4 7h22M4 15h22M4 23h22'/%3e%3c/svg%3e")}.navbar-dark .navbar-text{color:rgba(255,255,255,.5)}.navbar-dark .navbar-text a{color:#fff}.navbar-dark .navbar-text a:focus,.navbar-dark .navbar-text a:hover{color:#fff}.card{position:relative;display:-ms-flexbox;display:flex;-ms-flex-direction:column;flex-direction:column;min-width:0;word-wrap:break-word;background-color:#fff;background-clip:border-box;border:1px solid rgba(0,0,0,.125);border-radius:.25rem}.card>hr{margin-right:0;margin-left:0}.card>.list-group{border-top:inherit;border-bottom:inherit}.card>.list-group:first-child{border-top-width:0;border-top-left-radius:calc(.25rem - 1px);border-top-right-radius:calc(.25rem - 1px)}.card>.list-group:last-child{border-bottom-width:0;border-bottom-right-radius:calc(.25rem - 1px);border-bottom-left-radius:calc(.25rem - 1px)}.card-body{-ms-flex:1 1 auto;flex:1 1 auto;min-height:1px;padding:1.25rem}.card-title{margin-bottom:.75rem}.card-subtitle{margin-top:-.375rem;margin-bottom:0}.card-text:last-child{margin-bottom:0}.card-link:hover{text-decoration:none}.card-link+.card-link{margin-left:1.25rem}.card-header{padding:.75rem 1.25rem;margin-bottom:0;background-color:rgba(0,0,0,.03);border-bottom:1px solid rgba(0,0,0,.125)}.card-header:first-child{border-radius:calc(.25rem - 1px) calc(.25rem - 1px) 0 0}.card-header+.list-group .list-group-item:first-child{border-top:0}.card-footer{padding:.75rem 1.25rem;background-color:rgba(0,0,0,.03);border-top:1px solid rgba(0,0,0,.125)}.card-footer:last-child{border-radius:0 0 calc(.25rem - 1px) calc(.25rem - 1px)}.card-header-tabs{margin-right:-.625rem;margin-bottom:-.75rem;margin-left:-.625rem;border-bottom:0}.card-header-pills{margin-right:-.625rem;margin-left:-.625rem}.card-img-overlay{position:absolute;top:0;right:0;bottom:0;left:0;padding:1.25rem}.card-img,.card-img-bottom,.card-img-top{-ms-flex-negative:0;flex-shrink:0;width:100%}.card-img,.card-img-top{border-top-left-radius:calc(.25rem - 1px);border-top-right-radius:calc(.25rem - 1px)}.card-img,.card-img-bottom{border-bottom-right-radius:calc(.25rem - 1px);border-bottom-left-radius:calc(.25rem - 1px)}.card-deck .card{margin-bottom:15px}@media (min-width:576px){.card-deck{display:-ms-flexbox;display:flex;-ms-flex-flow:row wrap;flex-flow:row wrap;margin-right:-15px;margin-left:-15px}.card-deck .card{-ms-flex:1 0 0%;flex:1 0 0%;margin-right:15px;margin-bottom:0;margin-left:15px}}.card-group>.card{margin-bottom:15px}@media (min-width:576px){.card-group{display:-ms-flexbox;display:flex;-ms-flex-flow:row wrap;flex-flow:row wrap}.card-group>.card{-ms-flex:1 0 0%;flex:1 0 0%;margin-bottom:0}.card-group>.card+.card{margin-left:0;border-left:0}.card-group>.card:not(:last-child){border-top-right-radius:0;border-bottom-right-radius:0}.card-group>.card:not(:last-child) .card-header,.card-group>.card:not(:last-child) .card-img-top{border-top-right-radius:0}.card-group>.card:not(:last-child) .card-footer,.card-group>.card:not(:last-child) .card-img-bottom{border-bottom-right-radius:0}.card-group>.card:not(:first-child){border-top-left-radius:0;border-bottom-left-radius:0}.card-group>.card:not(:first-child) .card-header,.card-group>.card:not(:first-child) .card-img-top{border-top-left-radius:0}.card-group>.card:not(:first-child) .card-footer,.card-group>.card:not(:first-child) .card-img-bottom{border-bottom-left-radius:0}}.card-columns .card{margin-bottom:.75rem}@media (min-width:576px){.card-columns{-webkit-column-count:3;-moz-column-count:3;column-count:3;-webkit-column-gap:1.25rem;-moz-column-gap:1.25rem;column-gap:1.25rem;orphans:1;widows:1}.card-columns .card{display:inline-block;width:100%}}.accordion>.card{overflow:hidden}.accordion>.card:not(:last-of-type){border-bottom:0;border-bottom-right-radius:0;border-bottom-left-radius:0}.accordion>.card:not(:first-of-type){border-top-left-radius:0;border-top-right-radius:0}.accordion>.card>.card-header{border-radius:0;margin-bottom:-1px}.breadcrumb{display:-ms-flexbox;display:flex;-ms-flex-wrap:wrap;flex-wrap:wrap;padding:.75rem 1rem;margin-bottom:1rem;list-style:none;background-color:#e9ecef;border-radius:.25rem}.breadcrumb-item{display:-ms-flexbox;display:flex}.breadcrumb-item+.breadcrumb-item{padding-left:.5rem}.breadcrumb-item+.breadcrumb-item::before{display:inline-block;padding-right:.5rem;color:#6c757d;content:"/"}.breadcrumb-item+.breadcrumb-item:hover::before{text-decoration:underline}.breadcrumb-item+.breadcrumb-item:hover::before{text-decoration:none}.breadcrumb-item.active{color:#6c757d}.pagination{display:-ms-flexbox;display:flex;padding-left:0;list-style:none;border-radius:.25rem}.page-link{position:relative;display:block;padding:.5rem .75rem;margin-left:-1px;line-height:1.25;color:#007bff;background-color:#fff;border:1px solid #dee2e6}.page-link:hover{z-index:2;color:#0056b3;text-decoration:none;background-color:#e9ecef;border-color:#dee2e6}.page-link:focus{z-index:3;outline:0;box-shadow:0 0 0 .2rem rgba(0,123,255,.25)}.page-item:first-child .page-link{margin-left:0;border-top-left-radius:.25rem;border-bottom-left-radius:.25rem}.page-item:last-child .page-link{border-top-right-radius:.25rem;border-bottom-right-radius:.25rem}.page-item.active .page-link{z-index:3;color:#fff;background-color:#007bff;border-color:#007bff}.page-item.disabled .page-link{color:#6c757d;pointer-events:none;cursor:auto;background-color:#fff;border-color:#dee2e6}.pagination-lg .page-link{padding:.75rem 1.5rem;font-size:1.25rem;line-height:1.5}.pagination-lg .page-item:first-child .page-link{border-top-left-radius:.3rem;border-bottom-left-radius:.3rem}.pagination-lg .page-item:last-child .page-link{border-top-right-radius:.3rem;border-bottom-right-radius:.3rem}.pagination-sm .page-link{padding:.25rem .5rem;font-size:.875rem;line-height:1.5}.pagination-sm .page-item:first-child .page-link{border-top-left-radius:.2rem;border-bottom-left-radius:.2rem}.pagination-sm .page-item:last-child .page-link{border-top-right-radius:.2rem;border-bottom-right-radius:.2rem}.badge{display:inline-block;padding:.25em .4em;font-size:75%;font-weight:700;line-height:1;text-align:center;white-space:nowrap;vertical-align:baseline;border-radius:.25rem;transition:color .15s ease-in-out,background-color .15s ease-in-out,border-color .15s ease-in-out,box-shadow .15s ease-in-out}@media (prefers-reduced-motion:reduce){.badge{transition:none}}a.badge:focus,a.badge:hover{text-decoration:none}.badge:empty{display:none}.btn .badge{position:relative;top:-1px}.badge-pill{padding-right:.6em;padding-left:.6em;border-radius:10rem}.badge-primary{color:#fff;background-color:#007bff}a.badge-primary:focus,a.badge-primary:hover{color:#fff;background-color:#0062cc}a.badge-primary.focus,a.badge-primary:focus{outline:0;box-shadow:0 0 0 .2rem rgba(0,123,255,.5)}.badge-secondary{color:#fff;background-color:#6c757d}a.badge-secondary:focus,a.badge-secondary:hover{color:#fff;background-color:#545b62}a.badge-secondary.focus,a.badge-secondary:focus{outline:0;box-shadow:0 0 0 .2rem rgba(108,117,125,.5)}.badge-success{color:#fff;background-color:#28a745}a.badge-success:focus,a.badge-success:hover{color:#fff;background-color:#1e7e34}a.badge-success.focus,a.badge-success:focus{outline:0;box-shadow:0 0 0 .2rem rgba(40,167,69,.5)}.badge-info{color:#fff;background-color:#17a2b8}a.badge-info:focus,a.badge-info:hover{color:#fff;background-color:#117a8b}a.badge-info.focus,a.badge-info:focus{outline:0;box-shadow:0 0 0 .2rem rgba(23,162,184,.5)}.badge-warning{color:#212529;background-color:#ffc107}a.badge-warning:focus,a.badge-warning:hover{color:#212529;background-color:#d39e00}a.badge-warning.focus,a.badge-warning:focus{outline:0;box-shadow:0 0 0 .2rem rgba(255,193,7,.5)}.badge-danger{color:#fff;background-color:#dc3545}a.badge-danger:focus,a.badge-danger:hover{color:#fff;background-color:#bd2130}a.badge-danger.focus,a.badge-danger:focus{outline:0;box-shadow:0 0 0 .2rem rgba(220,53,69,.5)}.badge-light{color:#212529;background-color:#f8f9fa}a.badge-light:focus,a.badge-light:hover{color:#212529;background-color:#dae0e5}a.badge-light.focus,a.badge-light:focus{outline:0;box-shadow:0 0 0 .2rem rgba(248,249,250,.5)}.badge-dark{color:#fff;background-color:#343a40}a.badge-dark:focus,a.badge-dark:hover{color:#fff;background-color:#1d2124}a.badge-dark.focus,a.badge-dark:focus{outline:0;box-shadow:0 0 0 .2rem rgba(52,58,64,.5)}.jumbotron{padding:2rem 1rem;margin-bottom:2rem;background-color:#e9ecef;border-radius:.3rem}@media (min-width:576px){.jumbotron{padding:4rem 2rem}}.jumbotron-fluid{padding-right:0;padding-left:0;border-radius:0}.alert{position:relative;padding:.75rem 1.25rem;margin-bottom:1rem;border:1px solid transparent;border-radius:.25rem}.alert-heading{color:inherit}.alert-link{font-weight:700}.alert-dismissible{padding-right:4rem}.alert-dismissible .close{position:absolute;top:0;right:0;padding:.75rem 1.25rem;color:inherit}.alert-primary{color:#004085;background-color:#cce5ff;border-color:#b8daff}.alert-primary hr{border-top-color:#9fcdff}.alert-primary .alert-link{color:#002752}.alert-secondary{color:#383d41;background-color:#e2e3e5;border-color:#d6d8db}.alert-secondary hr{border-top-color:#c8cbcf}.alert-secondary .alert-link{color:#202326}.alert-success{color:#155724;background-color:#d4edda;border-color:#c3e6cb}.alert-success hr{border-top-color:#b1dfbb}.alert-success .alert-link{color:#0b2e13}.alert-info{color:#0c5460;background-color:#d1ecf1;border-color:#bee5eb}.alert-info hr{border-top-color:#abdde5}.alert-info .alert-link{color:#062c33}.alert-warning{color:#856404;background-color:#fff3cd;border-color:#ffeeba}.alert-warning hr{border-top-color:#ffe8a1}.alert-warning .alert-link{color:#533f03}.alert-danger{color:#721c24;background-color:#f8d7da;border-color:#f5c6cb}.alert-danger hr{border-top-color:#f1b0b7}.alert-danger .alert-link{color:#491217}.alert-light{color:#818182;background-color:#fefefe;border-color:#fdfdfe}.alert-light hr{border-top-color:#ececf6}.alert-light .alert-link{color:#686868}.alert-dark{color:#1b1e21;background-color:#d6d8d9;border-color:#c6c8ca}.alert-dark hr{border-top-color:#b9bbbe}.alert-dark .alert-link{color:#040505}@-webkit-keyframes progress-bar-stripes{from{background-position:1rem 0}to{background-position:0 0}}@keyframes progress-bar-stripes{from{background-position:1rem 0}to{background-position:0 0}}.progress{display:-ms-flexbox;display:flex;height:1rem;overflow:hidden;line-height:0;font-size:.75rem;background-color:#e9ecef;border-radius:.25rem}.progress-bar{display:-ms-flexbox;display:flex;-ms-flex-direction:column;flex-direction:column;-ms-flex-pack:center;justify-content:center;overflow:hidden;color:#fff;text-align:center;white-space:nowrap;background-color:#007bff;transition:width .6s ease}@media (prefers-reduced-motion:reduce){.progress-bar{transition:none}}.progress-bar-striped{background-image:linear-gradient(45deg,rgba(255,255,255,.15) 25%,transparent 25%,transparent 50%,rgba(255,255,255,.15) 50%,rgba(255,255,255,.15) 75%,transparent 75%,transparent);background-size:1rem 1rem}.progress-bar-animated{-webkit-animation:progress-bar-stripes 1s linear infinite;animation:progress-bar-stripes 1s linear infinite}@media (prefers-reduced-motion:reduce){.progress-bar-animated{-webkit-animation:none;animation:none}}.media{display:-ms-flexbox;display:flex;-ms-flex-align:start;align-items:flex-start}.media-body{-ms-flex:1;flex:1}.list-group{display:-ms-flexbox;display:flex;-ms-flex-direction:column;flex-direction:column;padding-left:0;margin-bottom:0;border-radius:.25rem}.list-group-item-action{width:100%;color:#495057;text-align:inherit}.list-group-item-action:focus,.list-group-item-action:hover{z-index:1;color:#495057;text-decoration:none;background-color:#f8f9fa}.list-group-item-action:active{color:#212529;background-color:#e9ecef}.list-group-item{position:relative;display:block;padding:.75rem 1.25rem;background-color:#fff;border:1px solid rgba(0,0,0,.125)}.list-group-item:first-child{border-top-left-radius:inherit;border-top-right-radius:inherit}.list-group-item:last-child{border-bottom-right-radius:inherit;border-bottom-left-radius:inherit}.list-group-item.disabled,.list-group-item:disabled{color:#6c757d;pointer-events:none;background-color:#fff}.list-group-item.active{z-index:2;color:#fff;background-color:#007bff;border-color:#007bff}.list-group-item+.list-group-item{border-top-width:0}.list-group-item+.list-group-item.active{margin-top:-1px;border-top-width:1px}.list-group-horizontal{-ms-flex-direction:row;flex-direction:row}.list-group-horizontal>.list-group-item:first-child{border-bottom-left-radius:.25rem;border-top-right-radius:0}.list-group-horizontal>.list-group-item:last-child{border-top-right-radius:.25rem;border-bottom-left-radius:0}.list-group-horizontal>.list-group-item.active{margin-top:0}.list-group-horizontal>.list-group-item+.list-group-item{border-top-width:1px;border-left-width:0}.list-group-horizontal>.list-group-item+.list-group-item.active{margin-left:-1px;border-left-width:1px}@media (min-width:576px){.list-group-horizontal-sm{-ms-flex-direction:row;flex-direction:row}.list-group-horizontal-sm>.list-group-item:first-child{border-bottom-left-radius:.25rem;border-top-right-radius:0}.list-group-horizontal-sm>.list-group-item:last-child{border-top-right-radius:.25rem;border-bottom-left-radius:0}.list-group-horizontal-sm>.list-group-item.active{margin-top:0}.list-group-horizontal-sm>.list-group-item+.list-group-item{border-top-width:1px;border-left-width:0}.list-group-horizontal-sm>.list-group-item+.list-group-item.active{margin-left:-1px;border-left-width:1px}}@media (min-width:768px){.list-group-horizontal-md{-ms-flex-direction:row;flex-direction:row}.list-group-horizontal-md>.list-group-item:first-child{border-bottom-left-radius:.25rem;border-top-right-radius:0}.list-group-horizontal-md>.list-group-item:last-child{border-top-right-radius:.25rem;border-bottom-left-radius:0}.list-group-horizontal-md>.list-group-item.active{margin-top:0}.list-group-horizontal-md>.list-group-item+.list-group-item{border-top-width:1px;border-left-width:0}.list-group-horizontal-md>.list-group-item+.list-group-item.active{margin-left:-1px;border-left-width:1px}}@media (min-width:992px){.list-group-horizontal-lg{-ms-flex-direction:row;flex-direction:row}.list-group-horizontal-lg>.list-group-item:first-child{border-bottom-left-radius:.25rem;border-top-right-radius:0}.list-group-horizontal-lg>.list-group-item:last-child{border-top-right-radius:.25rem;border-bottom-left-radius:0}.list-group-horizontal-lg>.list-group-item.active{margin-top:0}.list-group-horizontal-lg>.list-group-item+.list-group-item{border-top-width:1px;border-left-width:0}.list-group-horizontal-lg>.list-group-item+.list-group-item.active{margin-left:-1px;border-left-width:1px}}@media (min-width:1200px){.list-group-horizontal-xl{-ms-flex-direction:row;flex-direction:row}.list-group-horizontal-xl>.list-group-item:first-child{border-bottom-left-radius:.25rem;border-top-right-radius:0}.list-group-horizontal-xl>.list-group-item:last-child{border-top-right-radius:.25rem;border-bottom-left-radius:0}.list-group-horizontal-xl>.list-group-item.active{margin-top:0}.list-group-horizontal-xl>.list-group-item+.list-group-item{border-top-width:1px;border-left-width:0}.list-group-horizontal-xl>.list-group-item+.list-group-item.active{margin-left:-1px;border-left-width:1px}}.list-group-flush{border-radius:0}.list-group-flush>.list-group-item{border-width:0 0 1px}.list-group-flush>.list-group-item:last-child{border-bottom-width:0}.list-group-item-primary{color:#004085;background-color:#b8daff}.list-group-item-primary.list-group-item-action:focus,.list-group-item-primary.list-group-item-action:hover{color:#004085;background-color:#9fcdff}.list-group-item-primary.list-group-item-action.active{color:#fff;background-color:#004085;border-color:#004085}.list-group-item-secondary{color:#383d41;background-color:#d6d8db}.list-group-item-secondary.list-group-item-action:focus,.list-group-item-secondary.list-group-item-action:hover{color:#383d41;background-color:#c8cbcf}.list-group-item-secondary.list-group-item-action.active{color:#fff;background-color:#383d41;border-color:#383d41}.list-group-item-success{color:#155724;background-color:#c3e6cb}.list-group-item-success.list-group-item-action:focus,.list-group-item-success.list-group-item-action:hover{color:#155724;background-color:#b1dfbb}.list-group-item-success.list-group-item-action.active{color:#fff;background-color:#155724;border-color:#155724}.list-group-item-info{color:#0c5460;background-color:#bee5eb}.list-group-item-info.list-group-item-action:focus,.list-group-item-info.list-group-item-action:hover{color:#0c5460;background-color:#abdde5}.list-group-item-info.list-group-item-action.active{color:#fff;background-color:#0c5460;border-color:#0c5460}.list-group-item-warning{color:#856404;background-color:#ffeeba}.list-group-item-warning.list-group-item-action:focus,.list-group-item-warning.list-group-item-action:hover{color:#856404;background-color:#ffe8a1}.list-group-item-warning.list-group-item-action.active{color:#fff;background-color:#856404;border-color:#856404}.list-group-item-danger{color:#721c24;background-color:#f5c6cb}.list-group-item-danger.list-group-item-action:focus,.list-group-item-danger.list-group-item-action:hover{color:#721c24;background-color:#f1b0b7}.list-group-item-danger.list-group-item-action.active{color:#fff;background-color:#721c24;border-color:#721c24}.list-group-item-light{color:#818182;background-color:#fdfdfe}.list-group-item-light.list-group-item-action:focus,.list-group-item-light.list-group-item-action:hover{color:#818182;background-color:#ececf6}.list-group-item-light.list-group-item-action.active{color:#fff;background-color:#818182;border-color:#818182}.list-group-item-dark{color:#1b1e21;background-color:#c6c8ca}.list-group-item-dark.list-group-item-action:focus,.list-group-item-dark.list-group-item-action:hover{color:#1b1e21;background-color:#b9bbbe}.list-group-item-dark.list-group-item-action.active{color:#fff;background-color:#1b1e21;border-color:#1b1e21}.close{float:right;font-size:1.5rem;font-weight:700;line-height:1;color:#000;text-shadow:0 1px 0 #fff;opacity:.5}.close:hover{color:#000;text-decoration:none}.close:not(:disabled):not(.disabled):focus,.close:not(:disabled):not(.disabled):hover{opacity:.75}button.close{padding:0;background-color:transparent;border:0}a.close.disabled{pointer-events:none}.toast{max-width:350px;overflow:hidden;font-size:.875rem;background-color:rgba(255,255,255,.85);background-clip:padding-box;border:1px solid rgba(0,0,0,.1);box-shadow:0 .25rem .75rem rgba(0,0,0,.1);-webkit-backdrop-filter:blur(10px);backdrop-filter:blur(10px);opacity:0;border-radius:.25rem}.toast:not(:last-child){margin-bottom:.75rem}.toast.showing{opacity:1}.toast.show{display:block;opacity:1}.toast.hide{display:none}.toast-header{display:-ms-flexbox;display:flex;-ms-flex-align:center;align-items:center;padding:.25rem .75rem;color:#6c757d;background-color:rgba(255,255,255,.85);background-clip:padding-box;border-bottom:1px solid rgba(0,0,0,.05)}.toast-body{padding:.75rem}.modal-open{overflow:hidden}.modal-open .modal{overflow-x:hidden;overflow-y:auto}.modal{position:fixed;top:0;left:0;z-index:1050;display:none;width:100%;height:100%;overflow:hidden;outline:0}.modal-dialog{position:relative;width:auto;margin:.5rem;pointer-events:none}.modal.fade .modal-dialog{transition:-webkit-transform .3s ease-out;transition:transform .3s ease-out;transition:transform .3s ease-out,-webkit-transform .3s ease-out;-webkit-transform:translate(0,-50px);transform:translate(0,-50px)}@media (prefers-reduced-motion:reduce){.modal.fade .modal-dialog{transition:none}}.modal.show .modal-dialog{-webkit-transform:none;transform:none}.modal.modal-static .modal-dialog{-webkit-transform:scale(1.02);transform:scale(1.02)}.modal-dialog-scrollable{display:-ms-flexbox;display:flex;max-height:calc(100% - 1rem)}.modal-dialog-scrollable .modal-content{max-height:calc(100vh - 1rem);overflow:hidden}.modal-dialog-scrollable .modal-footer,.modal-dialog-scrollable .modal-header{-ms-flex-negative:0;flex-shrink:0}.modal-dialog-scrollable .modal-body{overflow-y:auto}.modal-dialog-centered{display:-ms-flexbox;display:flex;-ms-flex-align:center;align-items:center;min-height:calc(100% - 1rem)}.modal-dialog-centered::before{display:block;height:calc(100vh - 1rem);height:-webkit-min-content;height:-moz-min-content;height:min-content;content:""}.modal-dialog-centered.modal-dialog-scrollable{-ms-flex-direction:column;flex-direction:column;-ms-flex-pack:center;justify-content:center;height:100%}.modal-dialog-centered.modal-dialog-scrollable .modal-content{max-height:none}.modal-dialog-centered.modal-dialog-scrollable::before{content:none}.modal-content{position:relative;display:-ms-flexbox;display:flex;-ms-flex-direction:column;flex-direction:column;width:100%;pointer-events:auto;background-color:#fff;background-clip:padding-box;border:1px solid rgba(0,0,0,.2);border-radius:.3rem;outline:0}.modal-backdrop{position:fixed;top:0;left:0;z-index:1040;width:100vw;height:100vh;background-color:#000}.modal-backdrop.fade{opacity:0}.modal-backdrop.show{opacity:.5}.modal-header{display:-ms-flexbox;display:flex;-ms-flex-align:start;align-items:flex-start;-ms-flex-pack:justify;justify-content:space-between;padding:1rem 1rem;border-bottom:1px solid #dee2e6;border-top-left-radius:calc(.3rem - 1px);border-top-right-radius:calc(.3rem - 1px)}.modal-header .close{padding:1rem 1rem;margin:-1rem -1rem -1rem auto}.modal-title{margin-bottom:0;line-height:1.5}.modal-body{position:relative;-ms-flex:1 1 auto;flex:1 1 auto;padding:1rem}.modal-footer{display:-ms-flexbox;display:flex;-ms-flex-wrap:wrap;flex-wrap:wrap;-ms-flex-align:center;align-items:center;-ms-flex-pack:end;justify-content:flex-end;padding:.75rem;border-top:1px solid #dee2e6;border-bottom-right-radius:calc(.3rem - 1px);border-bottom-left-radius:calc(.3rem - 1px)}.modal-footer>*{margin:.25rem}.modal-scrollbar-measure{position:absolute;top:-9999px;width:50px;height:50px;overflow:scroll}@media (min-width:576px){.modal-dialog{max-width:500px;margin:1.75rem auto}.modal-dialog-scrollable{max-height:calc(100% - 3.5rem)}.modal-dialog-scrollable .modal-content{max-height:calc(100vh - 3.5rem)}.modal-dialog-centered{min-height:calc(100% - 3.5rem)}.modal-dialog-centered::before{height:calc(100vh - 3.5rem);height:-webkit-min-content;height:-moz-min-content;height:min-content}.modal-sm{max-width:300px}}@media (min-width:992px){.modal-lg,.modal-xl{max-width:800px}}@media (min-width:1200px){.modal-xl{max-width:1140px}}.tooltip{position:absolute;z-index:1070;display:block;margin:0;font-family:-apple-system,BlinkMacSystemFont,"Segoe UI",Roboto,"Helvetica Neue",Arial,"Noto Sans",sans-serif,"Apple Color Emoji","Segoe UI Emoji","Segoe UI Symbol","Noto Color Emoji";font-style:normal;font-weight:400;line-height:1.5;text-align:left;text-align:start;text-decoration:none;text-shadow:none;text-transform:none;letter-spacing:normal;word-break:normal;word-spacing:normal;white-space:normal;line-break:auto;font-size:.875rem;word-wrap:break-word;opacity:0}.tooltip.show{opacity:.9}.tooltip .arrow{position:absolute;display:block;width:.8rem;height:.4rem}.tooltip .arrow::before{position:absolute;content:"";border-color:transparent;border-style:solid}.bs-tooltip-auto[x-placement^=top],.bs-tooltip-top{padding:.4rem 0}.bs-tooltip-auto[x-placement^=top] .arrow,.bs-tooltip-top .arrow{bottom:0}.bs-tooltip-auto[x-placement^=top] .arrow::before,.bs-tooltip-top .arrow::before{top:0;border-width:.4rem .4rem 0;border-top-color:#000}.bs-tooltip-auto[x-placement^=right],.bs-tooltip-right{padding:0 .4rem}.bs-tooltip-auto[x-placement^=right] .arrow,.bs-tooltip-right .arrow{left:0;width:.4rem;height:.8rem}.bs-tooltip-auto[x-placement^=right] .arrow::before,.bs-tooltip-right .arrow::before{right:0;border-width:.4rem .4rem .4rem 0;border-right-color:#000}.bs-tooltip-auto[x-placement^=bottom],.bs-tooltip-bottom{padding:.4rem 0}.bs-tooltip-auto[x-placement^=bottom] .arrow,.bs-tooltip-bottom .arrow{top:0}.bs-tooltip-auto[x-placement^=bottom] .arrow::before,.bs-tooltip-bottom .arrow::before{bottom:0;border-width:0 .4rem .4rem;border-bottom-color:#000}.bs-tooltip-auto[x-placement^=left],.bs-tooltip-left{padding:0 .4rem}.bs-tooltip-auto[x-placement^=left] .arrow,.bs-tooltip-left .arrow{right:0;width:.4rem;height:.8rem}.bs-tooltip-auto[x-placement^=left] .arrow::before,.bs-tooltip-left .arrow::before{left:0;border-width:.4rem 0 .4rem .4rem;border-left-color:#000}.tooltip-inner{max-width:200px;padding:.25rem .5rem;color:#fff;text-align:center;background-color:#000;border-radius:.25rem}.popover{position:absolute;top:0;left:0;z-index:1060;display:block;max-width:276px;font-family:-apple-system,BlinkMacSystemFont,"Segoe UI",Roboto,"Helvetica Neue",Arial,"Noto Sans",sans-serif,"Apple Color Emoji","Segoe UI Emoji","Segoe UI Symbol","Noto Color Emoji";font-style:normal;font-weight:400;line-height:1.5;text-align:left;text-align:start;text-decoration:none;text-shadow:none;text-transform:none;letter-spacing:normal;word-break:normal;word-spacing:normal;white-space:normal;line-break:auto;font-size:.875rem;word-wrap:break-word;background-color:#fff;background-clip:padding-box;border:1px solid rgba(0,0,0,.2);border-radius:.3rem}.popover .arrow{position:absolute;display:block;width:1rem;height:.5rem;margin:0 .3rem}.popover .arrow::after,.popover .arrow::before{position:absolute;display:block;content:"";border-color:transparent;border-style:solid}.bs-popover-auto[x-placement^=top],.bs-popover-top{margin-bottom:.5rem}.bs-popover-auto[x-placement^=top]>.arrow,.bs-popover-top>.arrow{bottom:calc(-.5rem - 1px)}.bs-popover-auto[x-placement^=top]>.arrow::before,.bs-popover-top>.arrow::before{bottom:0;border-width:.5rem .5rem 0;border-top-color:rgba(0,0,0,.25)}.bs-popover-auto[x-placement^=top]>.arrow::after,.bs-popover-top>.arrow::after{bottom:1px;border-width:.5rem .5rem 0;border-top-color:#fff}.bs-popover-auto[x-placement^=right],.bs-popover-right{margin-left:.5rem}.bs-popover-auto[x-placement^=right]>.arrow,.bs-popover-right>.arrow{left:calc(-.5rem - 1px);width:.5rem;height:1rem;margin:.3rem 0}.bs-popover-auto[x-placement^=right]>.arrow::before,.bs-popover-right>.arrow::before{left:0;border-width:.5rem .5rem .5rem 0;border-right-color:rgba(0,0,0,.25)}.bs-popover-auto[x-placement^=right]>.arrow::after,.bs-popover-right>.arrow::after{left:1px;border-width:.5rem .5rem .5rem 0;border-right-color:#fff}.bs-popover-auto[x-placement^=bottom],.bs-popover-bottom{margin-top:.5rem}.bs-popover-auto[x-placement^=bottom]>.arrow,.bs-popover-bottom>.arrow{top:calc(-.5rem - 1px)}.bs-popover-auto[x-placement^=bottom]>.arrow::before,.bs-popover-bottom>.arrow::before{top:0;border-width:0 .5rem .5rem .5rem;border-bottom-color:rgba(0,0,0,.25)}.bs-popover-auto[x-placement^=bottom]>.arrow::after,.bs-popover-bottom>.arrow::after{top:1px;border-width:0 .5rem .5rem .5rem;border-bottom-color:#fff}.bs-popover-auto[x-placement^=bottom] .popover-header::before,.bs-popover-bottom .popover-header::before{position:absolute;top:0;left:50%;display:block;width:1rem;margin-left:-.5rem;content:"";border-bottom:1px solid #f7f7f7}.bs-popover-auto[x-placement^=left],.bs-popover-left{margin-right:.5rem}.bs-popover-auto[x-placement^=left]>.arrow,.bs-popover-left>.arrow{right:calc(-.5rem - 1px);width:.5rem;height:1rem;margin:.3rem 0}.bs-popover-auto[x-placement^=left]>.arrow::before,.bs-popover-left>.arrow::before{right:0;border-width:.5rem 0 .5rem .5rem;border-left-color:rgba(0,0,0,.25)}.bs-popover-auto[x-placement^=left]>.arrow::after,.bs-popover-left>.arrow::after{right:1px;border-width:.5rem 0 .5rem .5rem;border-left-color:#fff}.popover-header{padding:.5rem .75rem;margin-bottom:0;font-size:1rem;background-color:#f7f7f7;border-bottom:1px solid #ebebeb;border-top-left-radius:calc(.3rem - 1px);border-top-right-radius:calc(.3rem - 1px)}.popover-header:empty{display:none}.popover-body{padding:.5rem .75rem;color:#212529}.carousel{position:relative}.carousel.pointer-event{-ms-touch-action:pan-y;touch-action:pan-y}.carousel-inner{position:relative;width:100%;overflow:hidden}.carousel-inner::after{display:block;clear:both;content:""}.carousel-item{position:relative;display:none;float:left;width:100%;margin-right:-100%;-webkit-backface-visibility:hidden;backface-visibility:hidden;transition:-webkit-transform .6s ease-in-out;transition:transform .6s ease-in-out;transition:transform .6s ease-in-out,-webkit-transform .6s ease-in-out}@media (prefers-reduced-motion:reduce){.carousel-item{transition:none}}.carousel-item-next,.carousel-item-prev,.carousel-item.active{display:block}.active.carousel-item-right,.carousel-item-next:not(.carousel-item-left){-webkit-transform:translateX(100%);transform:translateX(100%)}.active.carousel-item-left,.carousel-item-prev:not(.carousel-item-right){-webkit-transform:translateX(-100%);transform:translateX(-100%)}.carousel-fade .carousel-item{opacity:0;transition-property:opacity;-webkit-transform:none;transform:none}.carousel-fade .carousel-item-next.carousel-item-left,.carousel-fade .carousel-item-prev.carousel-item-right,.carousel-fade .carousel-item.active{z-index:1;opacity:1}.carousel-fade .active.carousel-item-left,.carousel-fade .active.carousel-item-right{z-index:0;opacity:0;transition:opacity 0s .6s}@media (prefers-reduced-motion:reduce){.carousel-fade .active.carousel-item-left,.carousel-fade .active.carousel-item-right{transition:none}}.carousel-control-next,.carousel-control-prev{position:absolute;top:0;bottom:0;z-index:1;display:-ms-flexbox;display:flex;-ms-flex-align:center;align-items:center;-ms-flex-pack:center;justify-content:center;width:15%;color:#fff;text-align:center;opacity:.5;transition:opacity .15s ease}@media (prefers-reduced-motion:reduce){.carousel-control-next,.carousel-control-prev{transition:none}}.carousel-control-next:focus,.carousel-control-next:hover,.carousel-control-prev:focus,.carousel-control-prev:hover{color:#fff;text-decoration:none;outline:0;opacity:.9}.carousel-control-prev{left:0}.carousel-control-next{right:0}.carousel-control-next-icon,.carousel-control-prev-icon{display:inline-block;width:20px;height:20px;background:no-repeat 50%/100% 100%}.carousel-control-prev-icon{background-image:url("data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' fill='%23fff' width='8' height='8' viewBox='0 0 8 8'%3e%3cpath d='M5.25 0l-4 4 4 4 1.5-1.5L4.25 4l2.5-2.5L5.25 0z'/%3e%3c/svg%3e")}.carousel-control-next-icon{background-image:url("data:image/svg+xml,%3csvg xmlns='http://www.w3.org/2000/svg' fill='%23fff' width='8' height='8' viewBox='0 0 8 8'%3e%3cpath d='M2.75 0l-1.5 1.5L3.75 4l-2.5 2.5L2.75 8l4-4-4-4z'/%3e%3c/svg%3e")}.carousel-indicators{position:absolute;right:0;bottom:0;left:0;z-index:15;display:-ms-flexbox;display:flex;-ms-flex-pack:center;justify-content:center;padding-left:0;margin-right:15%;margin-left:15%;list-style:none}.carousel-indicators li{box-sizing:content-box;-ms-flex:0 1 auto;flex:0 1 auto;width:30px;height:3px;margin-right:3px;margin-left:3px;text-indent:-999px;cursor:pointer;background-color:#fff;background-clip:padding-box;border-top:10px solid transparent;border-bottom:10px solid transparent;opacity:.5;transition:opacity .6s ease}@media (prefers-reduced-motion:reduce){.carousel-indicators li{transition:none}}.carousel-indicators .active{opacity:1}.carousel-caption{position:absolute;right:15%;bottom:20px;left:15%;z-index:10;padding-top:20px;padding-bottom:20px;color:#fff;text-align:center}@-webkit-keyframes spinner-border{to{-webkit-transform:rotate(360deg);transform:rotate(360deg)}}@keyframes spinner-border{to{-webkit-transform:rotate(360deg);transform:rotate(360deg)}}.spinner-border{display:inline-block;width:2rem;height:2rem;vertical-align:text-bottom;border:.25em solid currentColor;border-right-color:transparent;border-radius:50%;-webkit-animation:spinner-border .75s linear infinite;animation:spinner-border .75s linear infinite}.spinner-border-sm{width:1rem;height:1rem;border-width:.2em}@-webkit-keyframes spinner-grow{0%{-webkit-transform:scale(0);transform:scale(0)}50%{opacity:1;-webkit-transform:none;transform:none}}@keyframes spinner-grow{0%{-webkit-transform:scale(0);transform:scale(0)}50%{opacity:1;-webkit-transform:none;transform:none}}.spinner-grow{display:inline-block;width:2rem;height:2rem;vertical-align:text-bottom;background-color:currentColor;border-radius:50%;opacity:0;-webkit-animation:spinner-grow .75s linear infinite;animation:spinner-grow .75s linear infinite}.spinner-grow-sm{width:1rem;height:1rem}.align-baseline{vertical-align:baseline!important}.align-top{vertical-align:top!important}.align-middle{vertical-align:middle!important}.align-bottom{vertical-align:bottom!important}.align-text-bottom{vertical-align:text-bottom!important}.align-text-top{vertical-align:text-top!important}.bg-primary{background-color:#007bff!important}a.bg-primary:focus,a.bg-primary:hover,button.bg-primary:focus,button.bg-primary:hover{background-color:#0062cc!important}.bg-secondary{background-color:#6c757d!important}a.bg-secondary:focus,a.bg-secondary:hover,button.bg-secondary:focus,button.bg-secondary:hover{background-color:#545b62!important}.bg-success{background-color:#28a745!important}a.bg-success:focus,a.bg-success:hover,button.bg-success:focus,button.bg-success:hover{background-color:#1e7e34!important}.bg-info{background-color:#17a2b8!important}a.bg-info:focus,a.bg-info:hover,button.bg-info:focus,button.bg-info:hover{background-color:#117a8b!important}.bg-warning{background-color:#ffc107!important}a.bg-warning:focus,a.bg-warning:hover,button.bg-warning:focus,button.bg-warning:hover{background-color:#d39e00!important}.bg-danger{background-color:#dc3545!important}a.bg-danger:focus,a.bg-danger:hover,button.bg-danger:focus,button.bg-danger:hover{background-color:#bd2130!important}.bg-light{background-color:#f8f9fa!important}a.bg-light:focus,a.bg-light:hover,button.bg-light:focus,button.bg-light:hover{background-color:#dae0e5!important}.bg-dark{background-color:#343a40!important}a.bg-dark:focus,a.bg-dark:hover,button.bg-dark:focus,button.bg-dark:hover{background-color:#1d2124!important}.bg-white{background-color:#fff!important}.bg-transparent{background-color:transparent!important}.border{border:1px solid #dee2e6!important}.border-top{border-top:1px solid #dee2e6!important}.border-right{border-right:1px solid #dee2e6!important}.border-bottom{border-bottom:1px solid #dee2e6!important}.border-left{border-left:1px solid #dee2e6!important}.border-0{border:0!important}.border-top-0{border-top:0!important}.border-right-0{border-right:0!important}.border-bottom-0{border-bottom:0!important}.border-left-0{border-left:0!important}.border-primary{border-color:#007bff!important}.border-secondary{border-color:#6c757d!important}.border-success{border-color:#28a745!important}.border-info{border-color:#17a2b8!important}.border-warning{border-color:#ffc107!important}.border-danger{border-color:#dc3545!important}.border-light{border-color:#f8f9fa!important}.border-dark{border-color:#343a40!important}.border-white{border-color:#fff!important}.rounded-sm{border-radius:.2rem!important}.rounded{border-radius:.25rem!important}.rounded-top{border-top-left-radius:.25rem!important;border-top-right-radius:.25rem!important}.rounded-right{border-top-right-radius:.25rem!important;border-bottom-right-radius:.25rem!important}.rounded-bottom{border-bottom-right-radius:.25rem!important;border-bottom-left-radius:.25rem!important}.rounded-left{border-top-left-radius:.25rem!important;border-bottom-left-radius:.25rem!important}.rounded-lg{border-radius:.3rem!important}.rounded-circle{border-radius:50%!important}.rounded-pill{border-radius:50rem!important}.rounded-0{border-radius:0!important}.clearfix::after{display:block;clear:both;content:""}.d-none{display:none!important}.d-inline{display:inline!important}.d-inline-block{display:inline-block!important}.d-block{display:block!important}.d-table{display:table!important}.d-table-row{display:table-row!important}.d-table-cell{display:table-cell!important}.d-flex{display:-ms-flexbox!important;display:flex!important}.d-inline-flex{display:-ms-inline-flexbox!important;display:inline-flex!important}@media (min-width:576px){.d-sm-none{display:none!important}.d-sm-inline{display:inline!important}.d-sm-inline-block{display:inline-block!important}.d-sm-block{display:block!important}.d-sm-table{display:table!important}.d-sm-table-row{display:table-row!important}.d-sm-table-cell{display:table-cell!important}.d-sm-flex{display:-ms-flexbox!important;display:flex!important}.d-sm-inline-flex{display:-ms-inline-flexbox!important;display:inline-flex!important}}@media (min-width:768px){.d-md-none{display:none!important}.d-md-inline{display:inline!important}.d-md-inline-block{display:inline-block!important}.d-md-block{display:block!important}.d-md-table{display:table!important}.d-md-table-row{display:table-row!important}.d-md-table-cell{display:table-cell!important}.d-md-flex{display:-ms-flexbox!important;display:flex!important}.d-md-inline-flex{display:-ms-inline-flexbox!important;display:inline-flex!important}}@media (min-width:992px){.d-lg-none{display:none!important}.d-lg-inline{display:inline!important}.d-lg-inline-block{display:inline-block!important}.d-lg-block{display:block!important}.d-lg-table{display:table!important}.d-lg-table-row{display:table-row!important}.d-lg-table-cell{display:table-cell!important}.d-lg-flex{display:-ms-flexbox!important;display:flex!important}.d-lg-inline-flex{display:-ms-inline-flexbox!important;display:inline-flex!important}}@media (min-width:1200px){.d-xl-none{display:none!important}.d-xl-inline{display:inline!important}.d-xl-inline-block{display:inline-block!important}.d-xl-block{display:block!important}.d-xl-table{display:table!important}.d-xl-table-row{display:table-row!important}.d-xl-table-cell{display:table-cell!important}.d-xl-flex{display:-ms-flexbox!important;display:flex!important}.d-xl-inline-flex{display:-ms-inline-flexbox!important;display:inline-flex!important}}@media print{.d-print-none{display:none!important}.d-print-inline{display:inline!important}.d-print-inline-block{display:inline-block!important}.d-print-block{display:block!important}.d-print-table{display:table!important}.d-print-table-row{display:table-row!important}.d-print-table-cell{display:table-cell!important}.d-print-flex{display:-ms-flexbox!important;display:flex!important}.d-print-inline-flex{display:-ms-inline-flexbox!important;display:inline-flex!important}}.embed-responsive{position:relative;display:block;width:100%;padding:0;overflow:hidden}.embed-responsive::before{display:block;content:""}.embed-responsive .embed-responsive-item,.embed-responsive embed,.embed-responsive iframe,.embed-responsive object,.embed-responsive video{position:absolute;top:0;bottom:0;left:0;width:100%;height:100%;border:0}.embed-responsive-21by9::before{padding-top:42.857143%}.embed-responsive-16by9::before{padding-top:56.25%}.embed-responsive-4by3::before{padding-top:75%}.embed-responsive-1by1::before{padding-top:100%}.flex-row{-ms-flex-direction:row!important;flex-direction:row!important}.flex-column{-ms-flex-direction:column!important;flex-direction:column!important}.flex-row-reverse{-ms-flex-direction:row-reverse!important;flex-direction:row-reverse!important}.flex-column-reverse{-ms-flex-direction:column-reverse!important;flex-direction:column-reverse!important}.flex-wrap{-ms-flex-wrap:wrap!important;flex-wrap:wrap!important}.flex-nowrap{-ms-flex-wrap:nowrap!important;flex-wrap:nowrap!important}.flex-wrap-reverse{-ms-flex-wrap:wrap-reverse!important;flex-wrap:wrap-reverse!important}.flex-fill{-ms-flex:1 1 auto!important;flex:1 1 auto!important}.flex-grow-0{-ms-flex-positive:0!important;flex-grow:0!important}.flex-grow-1{-ms-flex-positive:1!important;flex-grow:1!important}.flex-shrink-0{-ms-flex-negative:0!important;flex-shrink:0!important}.flex-shrink-1{-ms-flex-negative:1!important;flex-shrink:1!important}.justify-content-start{-ms-flex-pack:start!important;justify-content:flex-start!important}.justify-content-end{-ms-flex-pack:end!important;justify-content:flex-end!important}.justify-content-center{-ms-flex-pack:center!important;justify-content:center!important}.justify-content-between{-ms-flex-pack:justify!important;justify-content:space-between!important}.justify-content-around{-ms-flex-pack:distribute!important;justify-content:space-around!important}.align-items-start{-ms-flex-align:start!important;align-items:flex-start!important}.align-items-end{-ms-flex-align:end!important;align-items:flex-end!important}.align-items-center{-ms-flex-align:center!important;align-items:center!important}.align-items-baseline{-ms-flex-align:baseline!important;align-items:baseline!important}.align-items-stretch{-ms-flex-align:stretch!important;align-items:stretch!important}.align-content-start{-ms-flex-line-pack:start!important;align-content:flex-start!important}.align-content-end{-ms-flex-line-pack:end!important;align-content:flex-end!important}.align-content-center{-ms-flex-line-pack:center!important;align-content:center!important}.align-content-between{-ms-flex-line-pack:justify!important;align-content:space-between!important}.align-content-around{-ms-flex-line-pack:distribute!important;align-content:space-around!important}.align-content-stretch{-ms-flex-line-pack:stretch!important;align-content:stretch!important}.align-self-auto{-ms-flex-item-align:auto!important;align-self:auto!important}.align-self-start{-ms-flex-item-align:start!important;align-self:flex-start!important}.align-self-end{-ms-flex-item-align:end!important;align-self:flex-end!important}.align-self-center{-ms-flex-item-align:center!important;align-self:center!important}.align-self-baseline{-ms-flex-item-align:baseline!important;align-self:baseline!important}.align-self-stretch{-ms-flex-item-align:stretch!important;align-self:stretch!important}@media (min-width:576px){.flex-sm-row{-ms-flex-direction:row!important;flex-direction:row!important}.flex-sm-column{-ms-flex-direction:column!important;flex-direction:column!important}.flex-sm-row-reverse{-ms-flex-direction:row-reverse!important;flex-direction:row-reverse!important}.flex-sm-column-reverse{-ms-flex-direction:column-reverse!important;flex-direction:column-reverse!important}.flex-sm-wrap{-ms-flex-wrap:wrap!important;flex-wrap:wrap!important}.flex-sm-nowrap{-ms-flex-wrap:nowrap!important;flex-wrap:nowrap!important}.flex-sm-wrap-reverse{-ms-flex-wrap:wrap-reverse!important;flex-wrap:wrap-reverse!important}.flex-sm-fill{-ms-flex:1 1 auto!important;flex:1 1 auto!important}.flex-sm-grow-0{-ms-flex-positive:0!important;flex-grow:0!important}.flex-sm-grow-1{-ms-flex-positive:1!important;flex-grow:1!important}.flex-sm-shrink-0{-ms-flex-negative:0!important;flex-shrink:0!important}.flex-sm-shrink-1{-ms-flex-negative:1!important;flex-shrink:1!important}.justify-content-sm-start{-ms-flex-pack:start!important;justify-content:flex-start!important}.justify-content-sm-end{-ms-flex-pack:end!important;justify-content:flex-end!important}.justify-content-sm-center{-ms-flex-pack:center!important;justify-content:center!important}.justify-content-sm-between{-ms-flex-pack:justify!important;justify-content:space-between!important}.justify-content-sm-around{-ms-flex-pack:distribute!important;justify-content:space-around!important}.align-items-sm-start{-ms-flex-align:start!important;align-items:flex-start!important}.align-items-sm-end{-ms-flex-align:end!important;align-items:flex-end!important}.align-items-sm-center{-ms-flex-align:center!important;align-items:center!important}.align-items-sm-baseline{-ms-flex-align:baseline!important;align-items:baseline!important}.align-items-sm-stretch{-ms-flex-align:stretch!important;align-items:stretch!important}.align-content-sm-start{-ms-flex-line-pack:start!important;align-content:flex-start!important}.align-content-sm-end{-ms-flex-line-pack:end!important;align-content:flex-end!important}.align-content-sm-center{-ms-flex-line-pack:center!important;align-content:center!important}.align-content-sm-between{-ms-flex-line-pack:justify!important;align-content:space-between!important}.align-content-sm-around{-ms-flex-line-pack:distribute!important;align-content:space-around!important}.align-content-sm-stretch{-ms-flex-line-pack:stretch!important;align-content:stretch!important}.align-self-sm-auto{-ms-flex-item-align:auto!important;align-self:auto!important}.align-self-sm-start{-ms-flex-item-align:start!important;align-self:flex-start!important}.align-self-sm-end{-ms-flex-item-align:end!important;align-self:flex-end!important}.align-self-sm-center{-ms-flex-item-align:center!important;align-self:center!important}.align-self-sm-baseline{-ms-flex-item-align:baseline!important;align-self:baseline!important}.align-self-sm-stretch{-ms-flex-item-align:stretch!important;align-self:stretch!important}}@media (min-width:768px){.flex-md-row{-ms-flex-direction:row!important;flex-direction:row!important}.flex-md-column{-ms-flex-direction:column!important;flex-direction:column!important}.flex-md-row-reverse{-ms-flex-direction:row-reverse!important;flex-direction:row-reverse!important}.flex-md-column-reverse{-ms-flex-direction:column-reverse!important;flex-direction:column-reverse!important}.flex-md-wrap{-ms-flex-wrap:wrap!important;flex-wrap:wrap!important}.flex-md-nowrap{-ms-flex-wrap:nowrap!important;flex-wrap:nowrap!important}.flex-md-wrap-reverse{-ms-flex-wrap:wrap-reverse!important;flex-wrap:wrap-reverse!important}.flex-md-fill{-ms-flex:1 1 auto!important;flex:1 1 auto!important}.flex-md-grow-0{-ms-flex-positive:0!important;flex-grow:0!important}.flex-md-grow-1{-ms-flex-positive:1!important;flex-grow:1!important}.flex-md-shrink-0{-ms-flex-negative:0!important;flex-shrink:0!important}.flex-md-shrink-1{-ms-flex-negative:1!important;flex-shrink:1!important}.justify-content-md-start{-ms-flex-pack:start!important;justify-content:flex-start!important}.justify-content-md-end{-ms-flex-pack:end!important;justify-content:flex-end!important}.justify-content-md-center{-ms-flex-pack:center!important;justify-content:center!important}.justify-content-md-between{-ms-flex-pack:justify!important;justify-content:space-between!important}.justify-content-md-around{-ms-flex-pack:distribute!important;justify-content:space-around!important}.align-items-md-start{-ms-flex-align:start!important;align-items:flex-start!important}.align-items-md-end{-ms-flex-align:end!important;align-items:flex-end!important}.align-items-md-center{-ms-flex-align:center!important;align-items:center!important}.align-items-md-baseline{-ms-flex-align:baseline!important;align-items:baseline!important}.align-items-md-stretch{-ms-flex-align:stretch!important;align-items:stretch!important}.align-content-md-start{-ms-flex-line-pack:start!important;align-content:flex-start!important}.align-content-md-end{-ms-flex-line-pack:end!important;align-content:flex-end!important}.align-content-md-center{-ms-flex-line-pack:center!important;align-content:center!important}.align-content-md-between{-ms-flex-line-pack:justify!important;align-content:space-between!important}.align-content-md-around{-ms-flex-line-pack:distribute!important;align-content:space-around!important}.align-content-md-stretch{-ms-flex-line-pack:stretch!important;align-content:stretch!important}.align-self-md-auto{-ms-flex-item-align:auto!important;align-self:auto!important}.align-self-md-start{-ms-flex-item-align:start!important;align-self:flex-start!important}.align-self-md-end{-ms-flex-item-align:end!important;align-self:flex-end!important}.align-self-md-center{-ms-flex-item-align:center!important;align-self:center!important}.align-self-md-baseline{-ms-flex-item-align:baseline!important;align-self:baseline!important}.align-self-md-stretch{-ms-flex-item-align:stretch!important;align-self:stretch!important}}@media (min-width:992px){.flex-lg-row{-ms-flex-direction:row!important;flex-direction:row!important}.flex-lg-column{-ms-flex-direction:column!important;flex-direction:column!important}.flex-lg-row-reverse{-ms-flex-direction:row-reverse!important;flex-direction:row-reverse!important}.flex-lg-column-reverse{-ms-flex-direction:column-reverse!important;flex-direction:column-reverse!important}.flex-lg-wrap{-ms-flex-wrap:wrap!important;flex-wrap:wrap!important}.flex-lg-nowrap{-ms-flex-wrap:nowrap!important;flex-wrap:nowrap!important}.flex-lg-wrap-reverse{-ms-flex-wrap:wrap-reverse!important;flex-wrap:wrap-reverse!important}.flex-lg-fill{-ms-flex:1 1 auto!important;flex:1 1 auto!important}.flex-lg-grow-0{-ms-flex-positive:0!important;flex-grow:0!important}.flex-lg-grow-1{-ms-flex-positive:1!important;flex-grow:1!important}.flex-lg-shrink-0{-ms-flex-negative:0!important;flex-shrink:0!important}.flex-lg-shrink-1{-ms-flex-negative:1!important;flex-shrink:1!important}.justify-content-lg-start{-ms-flex-pack:start!important;justify-content:flex-start!important}.justify-content-lg-end{-ms-flex-pack:end!important;justify-content:flex-end!important}.justify-content-lg-center{-ms-flex-pack:center!important;justify-content:center!important}.justify-content-lg-between{-ms-flex-pack:justify!important;justify-content:space-between!important}.justify-content-lg-around{-ms-flex-pack:distribute!important;justify-content:space-around!important}.align-items-lg-start{-ms-flex-align:start!important;align-items:flex-start!important}.align-items-lg-end{-ms-flex-align:end!important;align-items:flex-end!important}.align-items-lg-center{-ms-flex-align:center!important;align-items:center!important}.align-items-lg-baseline{-ms-flex-align:baseline!important;align-items:baseline!important}.align-items-lg-stretch{-ms-flex-align:stretch!important;align-items:stretch!important}.align-content-lg-start{-ms-flex-line-pack:start!important;align-content:flex-start!important}.align-content-lg-end{-ms-flex-line-pack:end!important;align-content:flex-end!important}.align-content-lg-center{-ms-flex-line-pack:center!important;align-content:center!important}.align-content-lg-between{-ms-flex-line-pack:justify!important;align-content:space-between!important}.align-content-lg-around{-ms-flex-line-pack:distribute!important;align-content:space-around!important}.align-content-lg-stretch{-ms-flex-line-pack:stretch!important;align-content:stretch!important}.align-self-lg-auto{-ms-flex-item-align:auto!important;align-self:auto!important}.align-self-lg-start{-ms-flex-item-align:start!important;align-self:flex-start!important}.align-self-lg-end{-ms-flex-item-align:end!important;align-self:flex-end!important}.align-self-lg-center{-ms-flex-item-align:center!important;align-self:center!important}.align-self-lg-baseline{-ms-flex-item-align:baseline!important;align-self:baseline!important}.align-self-lg-stretch{-ms-flex-item-align:stretch!important;align-self:stretch!important}}@media (min-width:1200px){.flex-xl-row{-ms-flex-direction:row!important;flex-direction:row!important}.flex-xl-column{-ms-flex-direction:column!important;flex-direction:column!important}.flex-xl-row-reverse{-ms-flex-direction:row-reverse!important;flex-direction:row-reverse!important}.flex-xl-column-reverse{-ms-flex-direction:column-reverse!important;flex-direction:column-reverse!important}.flex-xl-wrap{-ms-flex-wrap:wrap!important;flex-wrap:wrap!important}.flex-xl-nowrap{-ms-flex-wrap:nowrap!important;flex-wrap:nowrap!important}.flex-xl-wrap-reverse{-ms-flex-wrap:wrap-reverse!important;flex-wrap:wrap-reverse!important}.flex-xl-fill{-ms-flex:1 1 auto!important;flex:1 1 auto!important}.flex-xl-grow-0{-ms-flex-positive:0!important;flex-grow:0!important}.flex-xl-grow-1{-ms-flex-positive:1!important;flex-grow:1!important}.flex-xl-shrink-0{-ms-flex-negative:0!important;flex-shrink:0!important}.flex-xl-shrink-1{-ms-flex-negative:1!important;flex-shrink:1!important}.justify-content-xl-start{-ms-flex-pack:start!important;justify-content:flex-start!important}.justify-content-xl-end{-ms-flex-pack:end!important;justify-content:flex-end!important}.justify-content-xl-center{-ms-flex-pack:center!important;justify-content:center!important}.justify-content-xl-between{-ms-flex-pack:justify!important;justify-content:space-between!important}.justify-content-xl-around{-ms-flex-pack:distribute!important;justify-content:space-around!important}.align-items-xl-start{-ms-flex-align:start!important;align-items:flex-start!important}.align-items-xl-end{-ms-flex-align:end!important;align-items:flex-end!important}.align-items-xl-center{-ms-flex-align:center!important;align-items:center!important}.align-items-xl-baseline{-ms-flex-align:baseline!important;align-items:baseline!important}.align-items-xl-stretch{-ms-flex-align:stretch!important;align-items:stretch!important}.align-content-xl-start{-ms-flex-line-pack:start!important;align-content:flex-start!important}.align-content-xl-end{-ms-flex-line-pack:end!important;align-content:flex-end!important}.align-content-xl-center{-ms-flex-line-pack:center!important;align-content:center!important}.align-content-xl-between{-ms-flex-line-pack:justify!important;align-content:space-between!important}.align-content-xl-around{-ms-flex-line-pack:distribute!important;align-content:space-around!important}.align-content-xl-stretch{-ms-flex-line-pack:stretch!important;align-content:stretch!important}.align-self-xl-auto{-ms-flex-item-align:auto!important;align-self:auto!important}.align-self-xl-start{-ms-flex-item-align:start!important;align-self:flex-start!important}.align-self-xl-end{-ms-flex-item-align:end!important;align-self:flex-end!important}.align-self-xl-center{-ms-flex-item-align:center!important;align-self:center!important}.align-self-xl-baseline{-ms-flex-item-align:baseline!important;align-self:baseline!important}.align-self-xl-stretch{-ms-flex-item-align:stretch!important;align-self:stretch!important}}.float-left{float:left!important}.float-right{float:right!important}.float-none{float:none!important}@media (min-width:576px){.float-sm-left{float:left!important}.float-sm-right{float:right!important}.float-sm-none{float:none!important}}@media (min-width:768px){.float-md-left{float:left!important}.float-md-right{float:right!important}.float-md-none{float:none!important}}@media (min-width:992px){.float-lg-left{float:left!important}.float-lg-right{float:right!important}.float-lg-none{float:none!important}}@media (min-width:1200px){.float-xl-left{float:left!important}.float-xl-right{float:right!important}.float-xl-none{float:none!important}}.user-select-all{-webkit-user-select:all!important;-moz-user-select:all!important;-ms-user-select:all!important;user-select:all!important}.user-select-auto{-webkit-user-select:auto!important;-moz-user-select:auto!important;-ms-user-select:auto!important;user-select:auto!important}.user-select-none{-webkit-user-select:none!important;-moz-user-select:none!important;-ms-user-select:none!important;user-select:none!important}.overflow-auto{overflow:auto!important}.overflow-hidden{overflow:hidden!important}.position-static{position:static!important}.position-relative{position:relative!important}.position-absolute{position:absolute!important}.position-fixed{position:fixed!important}.position-sticky{position:-webkit-sticky!important;position:sticky!important}.fixed-top{position:fixed;top:0;right:0;left:0;z-index:1030}.fixed-bottom{position:fixed;right:0;bottom:0;left:0;z-index:1030}@supports ((position:-webkit-sticky) or (position:sticky)){.sticky-top{position:-webkit-sticky;position:sticky;top:0;z-index:1020}}.sr-only{position:absolute;width:1px;height:1px;padding:0;margin:-1px;overflow:hidden;clip:rect(0,0,0,0);white-space:nowrap;border:0}.sr-only-focusable:active,.sr-only-focusable:focus{position:static;width:auto;height:auto;overflow:visible;clip:auto;white-space:normal}.shadow-sm{box-shadow:0 .125rem .25rem rgba(0,0,0,.075)!important}.shadow{box-shadow:0 .5rem 1rem rgba(0,0,0,.15)!important}.shadow-lg{box-shadow:0 1rem 3rem rgba(0,0,0,.175)!important}.shadow-none{box-shadow:none!important}.w-25{width:25%!important}.w-50{width:50%!important}.w-75{width:75%!important}.w-100{width:100%!important}.w-auto{width:auto!important}.h-25{height:25%!important}.h-50{height:50%!important}.h-75{height:75%!important}.h-100{height:100%!important}.h-auto{height:auto!important}.mw-100{max-width:100%!important}.mh-100{max-height:100%!important}.min-vw-100{min-width:100vw!important}.min-vh-100{min-height:100vh!important}.vw-100{width:100vw!important}.vh-100{height:100vh!important}.m-0{margin:0!important}.mt-0,.my-0{margin-top:0!important}.mr-0,.mx-0{margin-right:0!important}.mb-0,.my-0{margin-bottom:0!important}.ml-0,.mx-0{margin-left:0!important}.m-1{margin:.25rem!important}.mt-1,.my-1{margin-top:.25rem!important}.mr-1,.mx-1{margin-right:.25rem!important}.mb-1,.my-1{margin-bottom:.25rem!important}.ml-1,.mx-1{margin-left:.25rem!important}.m-2{margin:.5rem!important}.mt-2,.my-2{margin-top:.5rem!important}.mr-2,.mx-2{margin-right:.5rem!important}.mb-2,.my-2{margin-bottom:.5rem!important}.ml-2,.mx-2{margin-left:.5rem!important}.m-3{margin:1rem!important}.mt-3,.my-3{margin-top:1rem!important}.mr-3,.mx-3{margin-right:1rem!important}.mb-3,.my-3{margin-bottom:1rem!important}.ml-3,.mx-3{margin-left:1rem!important}.m-4{margin:1.5rem!important}.mt-4,.my-4{margin-top:1.5rem!important}.mr-4,.mx-4{margin-right:1.5rem!important}.mb-4,.my-4{margin-bottom:1.5rem!important}.ml-4,.mx-4{margin-left:1.5rem!important}.m-5{margin:3rem!important}.mt-5,.my-5{margin-top:3rem!important}.mr-5,.mx-5{margin-right:3rem!important}.mb-5,.my-5{margin-bottom:3rem!important}.ml-5,.mx-5{margin-left:3rem!important}.p-0{padding:0!important}.pt-0,.py-0{padding-top:0!important}.pr-0,.px-0{padding-right:0!important}.pb-0,.py-0{padding-bottom:0!important}.pl-0,.px-0{padding-left:0!important}.p-1{padding:.25rem!important}.pt-1,.py-1{padding-top:.25rem!important}.pr-1,.px-1{padding-right:.25rem!important}.pb-1,.py-1{padding-bottom:.25rem!important}.pl-1,.px-1{padding-left:.25rem!important}.p-2{padding:.5rem!important}.pt-2,.py-2{padding-top:.5rem!important}.pr-2,.px-2{padding-right:.5rem!important}.pb-2,.py-2{padding-bottom:.5rem!important}.pl-2,.px-2{padding-left:.5rem!important}.p-3{padding:1rem!important}.pt-3,.py-3{padding-top:1rem!important}.pr-3,.px-3{padding-right:1rem!important}.pb-3,.py-3{padding-bottom:1rem!important}.pl-3,.px-3{padding-left:1rem!important}.p-4{padding:1.5rem!important}.pt-4,.py-4{padding-top:1.5rem!important}.pr-4,.px-4{padding-right:1.5rem!important}.pb-4,.py-4{padding-bottom:1.5rem!important}.pl-4,.px-4{padding-left:1.5rem!important}.p-5{padding:3rem!important}.pt-5,.py-5{padding-top:3rem!important}.pr-5,.px-5{padding-right:3rem!important}.pb-5,.py-5{padding-bottom:3rem!important}.pl-5,.px-5{padding-left:3rem!important}.m-n1{margin:-.25rem!important}.mt-n1,.my-n1{margin-top:-.25rem!important}.mr-n1,.mx-n1{margin-right:-.25rem!important}.mb-n1,.my-n1{margin-bottom:-.25rem!important}.ml-n1,.mx-n1{margin-left:-.25rem!important}.m-n2{margin:-.5rem!important}.mt-n2,.my-n2{margin-top:-.5rem!important}.mr-n2,.mx-n2{margin-right:-.5rem!important}.mb-n2,.my-n2{margin-bottom:-.5rem!important}.ml-n2,.mx-n2{margin-left:-.5rem!important}.m-n3{margin:-1rem!important}.mt-n3,.my-n3{margin-top:-1rem!important}.mr-n3,.mx-n3{margin-right:-1rem!important}.mb-n3,.my-n3{margin-bottom:-1rem!important}.ml-n3,.mx-n3{margin-left:-1rem!important}.m-n4{margin:-1.5rem!important}.mt-n4,.my-n4{margin-top:-1.5rem!important}.mr-n4,.mx-n4{margin-right:-1.5rem!important}.mb-n4,.my-n4{margin-bottom:-1.5rem!important}.ml-n4,.mx-n4{margin-left:-1.5rem!important}.m-n5{margin:-3rem!important}.mt-n5,.my-n5{margin-top:-3rem!important}.mr-n5,.mx-n5{margin-right:-3rem!important}.mb-n5,.my-n5{margin-bottom:-3rem!important}.ml-n5,.mx-n5{margin-left:-3rem!important}.m-auto{margin:auto!important}.mt-auto,.my-auto{margin-top:auto!important}.mr-auto,.mx-auto{margin-right:auto!important}.mb-auto,.my-auto{margin-bottom:auto!important}.ml-auto,.mx-auto{margin-left:auto!important}@media (min-width:576px){.m-sm-0{margin:0!important}.mt-sm-0,.my-sm-0{margin-top:0!important}.mr-sm-0,.mx-sm-0{margin-right:0!important}.mb-sm-0,.my-sm-0{margin-bottom:0!important}.ml-sm-0,.mx-sm-0{margin-left:0!important}.m-sm-1{margin:.25rem!important}.mt-sm-1,.my-sm-1{margin-top:.25rem!important}.mr-sm-1,.mx-sm-1{margin-right:.25rem!important}.mb-sm-1,.my-sm-1{margin-bottom:.25rem!important}.ml-sm-1,.mx-sm-1{margin-left:.25rem!important}.m-sm-2{margin:.5rem!important}.mt-sm-2,.my-sm-2{margin-top:.5rem!important}.mr-sm-2,.mx-sm-2{margin-right:.5rem!important}.mb-sm-2,.my-sm-2{margin-bottom:.5rem!important}.ml-sm-2,.mx-sm-2{margin-left:.5rem!important}.m-sm-3{margin:1rem!important}.mt-sm-3,.my-sm-3{margin-top:1rem!important}.mr-sm-3,.mx-sm-3{margin-right:1rem!important}.mb-sm-3,.my-sm-3{margin-bottom:1rem!important}.ml-sm-3,.mx-sm-3{margin-left:1rem!important}.m-sm-4{margin:1.5rem!important}.mt-sm-4,.my-sm-4{margin-top:1.5rem!important}.mr-sm-4,.mx-sm-4{margin-right:1.5rem!important}.mb-sm-4,.my-sm-4{margin-bottom:1.5rem!important}.ml-sm-4,.mx-sm-4{margin-left:1.5rem!important}.m-sm-5{margin:3rem!important}.mt-sm-5,.my-sm-5{margin-top:3rem!important}.mr-sm-5,.mx-sm-5{margin-right:3rem!important}.mb-sm-5,.my-sm-5{margin-bottom:3rem!important}.ml-sm-5,.mx-sm-5{margin-left:3rem!important}.p-sm-0{padding:0!important}.pt-sm-0,.py-sm-0{padding-top:0!important}.pr-sm-0,.px-sm-0{padding-right:0!important}.pb-sm-0,.py-sm-0{padding-bottom:0!important}.pl-sm-0,.px-sm-0{padding-left:0!important}.p-sm-1{padding:.25rem!important}.pt-sm-1,.py-sm-1{padding-top:.25rem!important}.pr-sm-1,.px-sm-1{padding-right:.25rem!important}.pb-sm-1,.py-sm-1{padding-bottom:.25rem!important}.pl-sm-1,.px-sm-1{padding-left:.25rem!important}.p-sm-2{padding:.5rem!important}.pt-sm-2,.py-sm-2{padding-top:.5rem!important}.pr-sm-2,.px-sm-2{padding-right:.5rem!important}.pb-sm-2,.py-sm-2{padding-bottom:.5rem!important}.pl-sm-2,.px-sm-2{padding-left:.5rem!important}.p-sm-3{padding:1rem!important}.pt-sm-3,.py-sm-3{padding-top:1rem!important}.pr-sm-3,.px-sm-3{padding-right:1rem!important}.pb-sm-3,.py-sm-3{padding-bottom:1rem!important}.pl-sm-3,.px-sm-3{padding-left:1rem!important}.p-sm-4{padding:1.5rem!important}.pt-sm-4,.py-sm-4{padding-top:1.5rem!important}.pr-sm-4,.px-sm-4{padding-right:1.5rem!important}.pb-sm-4,.py-sm-4{padding-bottom:1.5rem!important}.pl-sm-4,.px-sm-4{padding-left:1.5rem!important}.p-sm-5{padding:3rem!important}.pt-sm-5,.py-sm-5{padding-top:3rem!important}.pr-sm-5,.px-sm-5{padding-right:3rem!important}.pb-sm-5,.py-sm-5{padding-bottom:3rem!important}.pl-sm-5,.px-sm-5{padding-left:3rem!important}.m-sm-n1{margin:-.25rem!important}.mt-sm-n1,.my-sm-n1{margin-top:-.25rem!important}.mr-sm-n1,.mx-sm-n1{margin-right:-.25rem!important}.mb-sm-n1,.my-sm-n1{margin-bottom:-.25rem!important}.ml-sm-n1,.mx-sm-n1{margin-left:-.25rem!important}.m-sm-n2{margin:-.5rem!important}.mt-sm-n2,.my-sm-n2{margin-top:-.5rem!important}.mr-sm-n2,.mx-sm-n2{margin-right:-.5rem!important}.mb-sm-n2,.my-sm-n2{margin-bottom:-.5rem!important}.ml-sm-n2,.mx-sm-n2{margin-left:-.5rem!important}.m-sm-n3{margin:-1rem!important}.mt-sm-n3,.my-sm-n3{margin-top:-1rem!important}.mr-sm-n3,.mx-sm-n3{margin-right:-1rem!important}.mb-sm-n3,.my-sm-n3{margin-bottom:-1rem!important}.ml-sm-n3,.mx-sm-n3{margin-left:-1rem!important}.m-sm-n4{margin:-1.5rem!important}.mt-sm-n4,.my-sm-n4{margin-top:-1.5rem!important}.mr-sm-n4,.mx-sm-n4{margin-right:-1.5rem!important}.mb-sm-n4,.my-sm-n4{margin-bottom:-1.5rem!important}.ml-sm-n4,.mx-sm-n4{margin-left:-1.5rem!important}.m-sm-n5{margin:-3rem!important}.mt-sm-n5,.my-sm-n5{margin-top:-3rem!important}.mr-sm-n5,.mx-sm-n5{margin-right:-3rem!important}.mb-sm-n5,.my-sm-n5{margin-bottom:-3rem!important}.ml-sm-n5,.mx-sm-n5{margin-left:-3rem!important}.m-sm-auto{margin:auto!important}.mt-sm-auto,.my-sm-auto{margin-top:auto!important}.mr-sm-auto,.mx-sm-auto{margin-right:auto!important}.mb-sm-auto,.my-sm-auto{margin-bottom:auto!important}.ml-sm-auto,.mx-sm-auto{margin-left:auto!important}}@media (min-width:768px){.m-md-0{margin:0!important}.mt-md-0,.my-md-0{margin-top:0!important}.mr-md-0,.mx-md-0{margin-right:0!important}.mb-md-0,.my-md-0{margin-bottom:0!important}.ml-md-0,.mx-md-0{margin-left:0!important}.m-md-1{margin:.25rem!important}.mt-md-1,.my-md-1{margin-top:.25rem!important}.mr-md-1,.mx-md-1{margin-right:.25rem!important}.mb-md-1,.my-md-1{margin-bottom:.25rem!important}.ml-md-1,.mx-md-1{margin-left:.25rem!important}.m-md-2{margin:.5rem!important}.mt-md-2,.my-md-2{margin-top:.5rem!important}.mr-md-2,.mx-md-2{margin-right:.5rem!important}.mb-md-2,.my-md-2{margin-bottom:.5rem!important}.ml-md-2,.mx-md-2{margin-left:.5rem!important}.m-md-3{margin:1rem!important}.mt-md-3,.my-md-3{margin-top:1rem!important}.mr-md-3,.mx-md-3{margin-right:1rem!important}.mb-md-3,.my-md-3{margin-bottom:1rem!important}.ml-md-3,.mx-md-3{margin-left:1rem!important}.m-md-4{margin:1.5rem!important}.mt-md-4,.my-md-4{margin-top:1.5rem!important}.mr-md-4,.mx-md-4{margin-right:1.5rem!important}.mb-md-4,.my-md-4{margin-bottom:1.5rem!important}.ml-md-4,.mx-md-4{margin-left:1.5rem!important}.m-md-5{margin:3rem!important}.mt-md-5,.my-md-5{margin-top:3rem!important}.mr-md-5,.mx-md-5{margin-right:3rem!important}.mb-md-5,.my-md-5{margin-bottom:3rem!important}.ml-md-5,.mx-md-5{margin-left:3rem!important}.p-md-0{padding:0!important}.pt-md-0,.py-md-0{padding-top:0!important}.pr-md-0,.px-md-0{padding-right:0!important}.pb-md-0,.py-md-0{padding-bottom:0!important}.pl-md-0,.px-md-0{padding-left:0!important}.p-md-1{padding:.25rem!important}.pt-md-1,.py-md-1{padding-top:.25rem!important}.pr-md-1,.px-md-1{padding-right:.25rem!important}.pb-md-1,.py-md-1{padding-bottom:.25rem!important}.pl-md-1,.px-md-1{padding-left:.25rem!important}.p-md-2{padding:.5rem!important}.pt-md-2,.py-md-2{padding-top:.5rem!important}.pr-md-2,.px-md-2{padding-right:.5rem!important}.pb-md-2,.py-md-2{padding-bottom:.5rem!important}.pl-md-2,.px-md-2{padding-left:.5rem!important}.p-md-3{padding:1rem!important}.pt-md-3,.py-md-3{padding-top:1rem!important}.pr-md-3,.px-md-3{padding-right:1rem!important}.pb-md-3,.py-md-3{padding-bottom:1rem!important}.pl-md-3,.px-md-3{padding-left:1rem!important}.p-md-4{padding:1.5rem!important}.pt-md-4,.py-md-4{padding-top:1.5rem!important}.pr-md-4,.px-md-4{padding-right:1.5rem!important}.pb-md-4,.py-md-4{padding-bottom:1.5rem!important}.pl-md-4,.px-md-4{padding-left:1.5rem!important}.p-md-5{padding:3rem!important}.pt-md-5,.py-md-5{padding-top:3rem!important}.pr-md-5,.px-md-5{padding-right:3rem!important}.pb-md-5,.py-md-5{padding-bottom:3rem!important}.pl-md-5,.px-md-5{padding-left:3rem!important}.m-md-n1{margin:-.25rem!important}.mt-md-n1,.my-md-n1{margin-top:-.25rem!important}.mr-md-n1,.mx-md-n1{margin-right:-.25rem!important}.mb-md-n1,.my-md-n1{margin-bottom:-.25rem!important}.ml-md-n1,.mx-md-n1{margin-left:-.25rem!important}.m-md-n2{margin:-.5rem!important}.mt-md-n2,.my-md-n2{margin-top:-.5rem!important}.mr-md-n2,.mx-md-n2{margin-right:-.5rem!important}.mb-md-n2,.my-md-n2{margin-bottom:-.5rem!important}.ml-md-n2,.mx-md-n2{margin-left:-.5rem!important}.m-md-n3{margin:-1rem!important}.mt-md-n3,.my-md-n3{margin-top:-1rem!important}.mr-md-n3,.mx-md-n3{margin-right:-1rem!important}.mb-md-n3,.my-md-n3{margin-bottom:-1rem!important}.ml-md-n3,.mx-md-n3{margin-left:-1rem!important}.m-md-n4{margin:-1.5rem!important}.mt-md-n4,.my-md-n4{margin-top:-1.5rem!important}.mr-md-n4,.mx-md-n4{margin-right:-1.5rem!important}.mb-md-n4,.my-md-n4{margin-bottom:-1.5rem!important}.ml-md-n4,.mx-md-n4{margin-left:-1.5rem!important}.m-md-n5{margin:-3rem!important}.mt-md-n5,.my-md-n5{margin-top:-3rem!important}.mr-md-n5,.mx-md-n5{margin-right:-3rem!important}.mb-md-n5,.my-md-n5{margin-bottom:-3rem!important}.ml-md-n5,.mx-md-n5{margin-left:-3rem!important}.m-md-auto{margin:auto!important}.mt-md-auto,.my-md-auto{margin-top:auto!important}.mr-md-auto,.mx-md-auto{margin-right:auto!important}.mb-md-auto,.my-md-auto{margin-bottom:auto!important}.ml-md-auto,.mx-md-auto{margin-left:auto!important}}@media (min-width:992px){.m-lg-0{margin:0!important}.mt-lg-0,.my-lg-0{margin-top:0!important}.mr-lg-0,.mx-lg-0{margin-right:0!important}.mb-lg-0,.my-lg-0{margin-bottom:0!important}.ml-lg-0,.mx-lg-0{margin-left:0!important}.m-lg-1{margin:.25rem!important}.mt-lg-1,.my-lg-1{margin-top:.25rem!important}.mr-lg-1,.mx-lg-1{margin-right:.25rem!important}.mb-lg-1,.my-lg-1{margin-bottom:.25rem!important}.ml-lg-1,.mx-lg-1{margin-left:.25rem!important}.m-lg-2{margin:.5rem!important}.mt-lg-2,.my-lg-2{margin-top:.5rem!important}.mr-lg-2,.mx-lg-2{margin-right:.5rem!important}.mb-lg-2,.my-lg-2{margin-bottom:.5rem!important}.ml-lg-2,.mx-lg-2{margin-left:.5rem!important}.m-lg-3{margin:1rem!important}.mt-lg-3,.my-lg-3{margin-top:1rem!important}.mr-lg-3,.mx-lg-3{margin-right:1rem!important}.mb-lg-3,.my-lg-3{margin-bottom:1rem!important}.ml-lg-3,.mx-lg-3{margin-left:1rem!important}.m-lg-4{margin:1.5rem!important}.mt-lg-4,.my-lg-4{margin-top:1.5rem!important}.mr-lg-4,.mx-lg-4{margin-right:1.5rem!important}.mb-lg-4,.my-lg-4{margin-bottom:1.5rem!important}.ml-lg-4,.mx-lg-4{margin-left:1.5rem!important}.m-lg-5{margin:3rem!important}.mt-lg-5,.my-lg-5{margin-top:3rem!important}.mr-lg-5,.mx-lg-5{margin-right:3rem!important}.mb-lg-5,.my-lg-5{margin-bottom:3rem!important}.ml-lg-5,.mx-lg-5{margin-left:3rem!important}.p-lg-0{padding:0!important}.pt-lg-0,.py-lg-0{padding-top:0!important}.pr-lg-0,.px-lg-0{padding-right:0!important}.pb-lg-0,.py-lg-0{padding-bottom:0!important}.pl-lg-0,.px-lg-0{padding-left:0!important}.p-lg-1{padding:.25rem!important}.pt-lg-1,.py-lg-1{padding-top:.25rem!important}.pr-lg-1,.px-lg-1{padding-right:.25rem!important}.pb-lg-1,.py-lg-1{padding-bottom:.25rem!important}.pl-lg-1,.px-lg-1{padding-left:.25rem!important}.p-lg-2{padding:.5rem!important}.pt-lg-2,.py-lg-2{padding-top:.5rem!important}.pr-lg-2,.px-lg-2{padding-right:.5rem!important}.pb-lg-2,.py-lg-2{padding-bottom:.5rem!important}.pl-lg-2,.px-lg-2{padding-left:.5rem!important}.p-lg-3{padding:1rem!important}.pt-lg-3,.py-lg-3{padding-top:1rem!important}.pr-lg-3,.px-lg-3{padding-right:1rem!important}.pb-lg-3,.py-lg-3{padding-bottom:1rem!important}.pl-lg-3,.px-lg-3{padding-left:1rem!important}.p-lg-4{padding:1.5rem!important}.pt-lg-4,.py-lg-4{padding-top:1.5rem!important}.pr-lg-4,.px-lg-4{padding-right:1.5rem!important}.pb-lg-4,.py-lg-4{padding-bottom:1.5rem!important}.pl-lg-4,.px-lg-4{padding-left:1.5rem!important}.p-lg-5{padding:3rem!important}.pt-lg-5,.py-lg-5{padding-top:3rem!important}.pr-lg-5,.px-lg-5{padding-right:3rem!important}.pb-lg-5,.py-lg-5{padding-bottom:3rem!important}.pl-lg-5,.px-lg-5{padding-left:3rem!important}.m-lg-n1{margin:-.25rem!important}.mt-lg-n1,.my-lg-n1{margin-top:-.25rem!important}.mr-lg-n1,.mx-lg-n1{margin-right:-.25rem!important}.mb-lg-n1,.my-lg-n1{margin-bottom:-.25rem!important}.ml-lg-n1,.mx-lg-n1{margin-left:-.25rem!important}.m-lg-n2{margin:-.5rem!important}.mt-lg-n2,.my-lg-n2{margin-top:-.5rem!important}.mr-lg-n2,.mx-lg-n2{margin-right:-.5rem!important}.mb-lg-n2,.my-lg-n2{margin-bottom:-.5rem!important}.ml-lg-n2,.mx-lg-n2{margin-left:-.5rem!important}.m-lg-n3{margin:-1rem!important}.mt-lg-n3,.my-lg-n3{margin-top:-1rem!important}.mr-lg-n3,.mx-lg-n3{margin-right:-1rem!important}.mb-lg-n3,.my-lg-n3{margin-bottom:-1rem!important}.ml-lg-n3,.mx-lg-n3{margin-left:-1rem!important}.m-lg-n4{margin:-1.5rem!important}.mt-lg-n4,.my-lg-n4{margin-top:-1.5rem!important}.mr-lg-n4,.mx-lg-n4{margin-right:-1.5rem!important}.mb-lg-n4,.my-lg-n4{margin-bottom:-1.5rem!important}.ml-lg-n4,.mx-lg-n4{margin-left:-1.5rem!important}.m-lg-n5{margin:-3rem!important}.mt-lg-n5,.my-lg-n5{margin-top:-3rem!important}.mr-lg-n5,.mx-lg-n5{margin-right:-3rem!important}.mb-lg-n5,.my-lg-n5{margin-bottom:-3rem!important}.ml-lg-n5,.mx-lg-n5{margin-left:-3rem!important}.m-lg-auto{margin:auto!important}.mt-lg-auto,.my-lg-auto{margin-top:auto!important}.mr-lg-auto,.mx-lg-auto{margin-right:auto!important}.mb-lg-auto,.my-lg-auto{margin-bottom:auto!important}.ml-lg-auto,.mx-lg-auto{margin-left:auto!important}}@media (min-width:1200px){.m-xl-0{margin:0!important}.mt-xl-0,.my-xl-0{margin-top:0!important}.mr-xl-0,.mx-xl-0{margin-right:0!important}.mb-xl-0,.my-xl-0{margin-bottom:0!important}.ml-xl-0,.mx-xl-0{margin-left:0!important}.m-xl-1{margin:.25rem!important}.mt-xl-1,.my-xl-1{margin-top:.25rem!important}.mr-xl-1,.mx-xl-1{margin-right:.25rem!important}.mb-xl-1,.my-xl-1{margin-bottom:.25rem!important}.ml-xl-1,.mx-xl-1{margin-left:.25rem!important}.m-xl-2{margin:.5rem!important}.mt-xl-2,.my-xl-2{margin-top:.5rem!important}.mr-xl-2,.mx-xl-2{margin-right:.5rem!important}.mb-xl-2,.my-xl-2{margin-bottom:.5rem!important}.ml-xl-2,.mx-xl-2{margin-left:.5rem!important}.m-xl-3{margin:1rem!important}.mt-xl-3,.my-xl-3{margin-top:1rem!important}.mr-xl-3,.mx-xl-3{margin-right:1rem!important}.mb-xl-3,.my-xl-3{margin-bottom:1rem!important}.ml-xl-3,.mx-xl-3{margin-left:1rem!important}.m-xl-4{margin:1.5rem!important}.mt-xl-4,.my-xl-4{margin-top:1.5rem!important}.mr-xl-4,.mx-xl-4{margin-right:1.5rem!important}.mb-xl-4,.my-xl-4{margin-bottom:1.5rem!important}.ml-xl-4,.mx-xl-4{margin-left:1.5rem!important}.m-xl-5{margin:3rem!important}.mt-xl-5,.my-xl-5{margin-top:3rem!important}.mr-xl-5,.mx-xl-5{margin-right:3rem!important}.mb-xl-5,.my-xl-5{margin-bottom:3rem!important}.ml-xl-5,.mx-xl-5{margin-left:3rem!important}.p-xl-0{padding:0!important}.pt-xl-0,.py-xl-0{padding-top:0!important}.pr-xl-0,.px-xl-0{padding-right:0!important}.pb-xl-0,.py-xl-0{padding-bottom:0!important}.pl-xl-0,.px-xl-0{padding-left:0!important}.p-xl-1{padding:.25rem!important}.pt-xl-1,.py-xl-1{padding-top:.25rem!important}.pr-xl-1,.px-xl-1{padding-right:.25rem!important}.pb-xl-1,.py-xl-1{padding-bottom:.25rem!important}.pl-xl-1,.px-xl-1{padding-left:.25rem!important}.p-xl-2{padding:.5rem!important}.pt-xl-2,.py-xl-2{padding-top:.5rem!important}.pr-xl-2,.px-xl-2{padding-right:.5rem!important}.pb-xl-2,.py-xl-2{padding-bottom:.5rem!important}.pl-xl-2,.px-xl-2{padding-left:.5rem!important}.p-xl-3{padding:1rem!important}.pt-xl-3,.py-xl-3{padding-top:1rem!important}.pr-xl-3,.px-xl-3{padding-right:1rem!important}.pb-xl-3,.py-xl-3{padding-bottom:1rem!important}.pl-xl-3,.px-xl-3{padding-left:1rem!important}.p-xl-4{padding:1.5rem!important}.pt-xl-4,.py-xl-4{padding-top:1.5rem!important}.pr-xl-4,.px-xl-4{padding-right:1.5rem!important}.pb-xl-4,.py-xl-4{padding-bottom:1.5rem!important}.pl-xl-4,.px-xl-4{padding-left:1.5rem!important}.p-xl-5{padding:3rem!important}.pt-xl-5,.py-xl-5{padding-top:3rem!important}.pr-xl-5,.px-xl-5{padding-right:3rem!important}.pb-xl-5,.py-xl-5{padding-bottom:3rem!important}.pl-xl-5,.px-xl-5{padding-left:3rem!important}.m-xl-n1{margin:-.25rem!important}.mt-xl-n1,.my-xl-n1{margin-top:-.25rem!important}.mr-xl-n1,.mx-xl-n1{margin-right:-.25rem!important}.mb-xl-n1,.my-xl-n1{margin-bottom:-.25rem!important}.ml-xl-n1,.mx-xl-n1{margin-left:-.25rem!important}.m-xl-n2{margin:-.5rem!important}.mt-xl-n2,.my-xl-n2{margin-top:-.5rem!important}.mr-xl-n2,.mx-xl-n2{margin-right:-.5rem!important}.mb-xl-n2,.my-xl-n2{margin-bottom:-.5rem!important}.ml-xl-n2,.mx-xl-n2{margin-left:-.5rem!important}.m-xl-n3{margin:-1rem!important}.mt-xl-n3,.my-xl-n3{margin-top:-1rem!important}.mr-xl-n3,.mx-xl-n3{margin-right:-1rem!important}.mb-xl-n3,.my-xl-n3{margin-bottom:-1rem!important}.ml-xl-n3,.mx-xl-n3{margin-left:-1rem!important}.m-xl-n4{margin:-1.5rem!important}.mt-xl-n4,.my-xl-n4{margin-top:-1.5rem!important}.mr-xl-n4,.mx-xl-n4{margin-right:-1.5rem!important}.mb-xl-n4,.my-xl-n4{margin-bottom:-1.5rem!important}.ml-xl-n4,.mx-xl-n4{margin-left:-1.5rem!important}.m-xl-n5{margin:-3rem!important}.mt-xl-n5,.my-xl-n5{margin-top:-3rem!important}.mr-xl-n5,.mx-xl-n5{margin-right:-3rem!important}.mb-xl-n5,.my-xl-n5{margin-bottom:-3rem!important}.ml-xl-n5,.mx-xl-n5{margin-left:-3rem!important}.m-xl-auto{margin:auto!important}.mt-xl-auto,.my-xl-auto{margin-top:auto!important}.mr-xl-auto,.mx-xl-auto{margin-right:auto!important}.mb-xl-auto,.my-xl-auto{margin-bottom:auto!important}.ml-xl-auto,.mx-xl-auto{margin-left:auto!important}}.stretched-link::after{position:absolute;top:0;right:0;bottom:0;left:0;z-index:1;pointer-events:auto;content:"";background-color:rgba(0,0,0,0)}.text-monospace{font-family:SFMono-Regular,Menlo,Monaco,Consolas,"Liberation Mono","Courier New",monospace!important}.text-justify{text-align:justify!important}.text-wrap{white-space:normal!important}.text-nowrap{white-space:nowrap!important}.text-truncate{overflow:hidden;text-overflow:ellipsis;white-space:nowrap}.text-left{text-align:left!important}.text-right{text-align:right!important}.text-center{text-align:center!important}@media (min-width:576px){.text-sm-left{text-align:left!important}.text-sm-right{text-align:right!important}.text-sm-center{text-align:center!important}}@media (min-width:768px){.text-md-left{text-align:left!important}.text-md-right{text-align:right!important}.text-md-center{text-align:center!important}}@media (min-width:992px){.text-lg-left{text-align:left!important}.text-lg-right{text-align:right!important}.text-lg-center{text-align:center!important}}@media (min-width:1200px){.text-xl-left{text-align:left!important}.text-xl-right{text-align:right!important}.text-xl-center{text-align:center!important}}.text-lowercase{text-transform:lowercase!important}.text-uppercase{text-transform:uppercase!important}.text-capitalize{text-transform:capitalize!important}.font-weight-light{font-weight:300!important}.font-weight-lighter{font-weight:lighter!important}.font-weight-normal{font-weight:400!important}.font-weight-bold{font-weight:700!important}.font-weight-bolder{font-weight:bolder!important}.font-italic{font-style:italic!important}.text-white{color:#fff!important}.text-primary{color:#007bff!important}a.text-primary:focus,a.text-primary:hover{color:#0056b3!important}.text-secondary{color:#6c757d!important}a.text-secondary:focus,a.text-secondary:hover{color:#494f54!important}.text-success{color:#28a745!important}a.text-success:focus,a.text-success:hover{color:#19692c!important}.text-info{color:#17a2b8!important}a.text-info:focus,a.text-info:hover{color:#0f6674!important}.text-warning{color:#ffc107!important}a.text-warning:focus,a.text-warning:hover{color:#ba8b00!important}.text-danger{color:#dc3545!important}a.text-danger:focus,a.text-danger:hover{color:#a71d2a!important}.text-light{color:#f8f9fa!important}a.text-light:focus,a.text-light:hover{color:#cbd3da!important}.text-dark{color:#343a40!important}a.text-dark:focus,a.text-dark:hover{color:#121416!important}.text-body{color:#212529!important}.text-muted{color:#6c757d!important}.text-black-50{color:rgba(0,0,0,.5)!important}.text-white-50{color:rgba(255,255,255,.5)!important}.text-hide{font:0/0 a;color:transparent;text-shadow:none;background-color:transparent;border:0}.text-decoration-none{text-decoration:none!important}.text-break{word-wrap:break-word!important}.text-reset{color:inherit!important}.visible{visibility:visible!important}.invisible{visibility:hidden!important}@media print{*,::after,::before{text-shadow:none!important;box-shadow:none!important}a:not(.btn){text-decoration:underline}abbr[title]::after{content:" (" attr(title) ")"}pre{white-space:pre-wrap!important}blockquote,pre{border:1px solid #adb5bd;page-break-inside:avoid}thead{display:table-header-group}img,tr{page-break-inside:avoid}h2,h3,p{orphans:3;widows:3}h2,h3{page-break-after:avoid}@page{size:a3}body{min-width:992px!important}.container{min-width:992px!important}.navbar{display:none}.badge{border:1px solid #000}.table{border-collapse:collapse!important}.table td,.table th{background-color:#fff!important}.table-bordered td,.table-bordered th{border:1px solid #dee2e6!important}.table-dark{color:inherit}.table-dark tbody+tbody,.table-dark td,.table-dark th,.table-dark thead th{border-color:#dee2e6}.table .thead-dark th{color:inherit;border-color:#dee2e6}} diff --git a/buildroot/web-ui/data/www/bootstrap.min.js b/buildroot/web-ui/data/www/bootstrap.min.js new file mode 100644 index 000000000000..c3fb738094f2 --- /dev/null +++ b/buildroot/web-ui/data/www/bootstrap.min.js @@ -0,0 +1,6 @@ +/*! + * Bootstrap v4.5.0 (https://getbootstrap.com/) + * Copyright 2011-2020 The Bootstrap Authors (https://github.com/twbs/bootstrap/graphs/contributors) + * Licensed under MIT (https://github.com/twbs/bootstrap/blob/master/LICENSE) + */ +!function(t,e){"object"==typeof exports&&"undefined"!=typeof module?e(exports,require("jquery"),require("popper.js")):"function"==typeof define&&define.amd?define(["exports","jquery","popper.js"],e):e((t=t||self).bootstrap={},t.jQuery,t.Popper)}(this,(function(t,e,n){"use strict";function i(t,e){for(var n=0;n=4)throw new Error("Bootstrap's JavaScript requires at least jQuery v1.9.1 but less than v4.0.0")}};c.jQueryDetection(),e.fn.emulateTransitionEnd=l,e.event.special[c.TRANSITION_END]={bindType:"transitionend",delegateType:"transitionend",handle:function(t){if(e(t.target).is(this))return t.handleObj.handler.apply(this,arguments)}};var h="alert",u=e.fn[h],d=function(){function t(t){this._element=t}var n=t.prototype;return n.close=function(t){var e=this._element;t&&(e=this._getRootElement(t)),this._triggerCloseEvent(e).isDefaultPrevented()||this._removeElement(e)},n.dispose=function(){e.removeData(this._element,"bs.alert"),this._element=null},n._getRootElement=function(t){var n=c.getSelectorFromElement(t),i=!1;return n&&(i=document.querySelector(n)),i||(i=e(t).closest(".alert")[0]),i},n._triggerCloseEvent=function(t){var n=e.Event("close.bs.alert");return e(t).trigger(n),n},n._removeElement=function(t){var n=this;if(e(t).removeClass("show"),e(t).hasClass("fade")){var i=c.getTransitionDurationFromElement(t);e(t).one(c.TRANSITION_END,(function(e){return n._destroyElement(t,e)})).emulateTransitionEnd(i)}else this._destroyElement(t)},n._destroyElement=function(t){e(t).detach().trigger("closed.bs.alert").remove()},t._jQueryInterface=function(n){return this.each((function(){var i=e(this),o=i.data("bs.alert");o||(o=new t(this),i.data("bs.alert",o)),"close"===n&&o[n](this)}))},t._handleDismiss=function(t){return function(e){e&&e.preventDefault(),t.close(this)}},o(t,null,[{key:"VERSION",get:function(){return"4.5.0"}}]),t}();e(document).on("click.bs.alert.data-api",'[data-dismiss="alert"]',d._handleDismiss(new d)),e.fn[h]=d._jQueryInterface,e.fn[h].Constructor=d,e.fn[h].noConflict=function(){return e.fn[h]=u,d._jQueryInterface};var f=e.fn.button,g=function(){function t(t){this._element=t}var n=t.prototype;return n.toggle=function(){var t=!0,n=!0,i=e(this._element).closest('[data-toggle="buttons"]')[0];if(i){var o=this._element.querySelector('input:not([type="hidden"])');if(o){if("radio"===o.type)if(o.checked&&this._element.classList.contains("active"))t=!1;else{var s=i.querySelector(".active");s&&e(s).removeClass("active")}t&&("checkbox"!==o.type&&"radio"!==o.type||(o.checked=!this._element.classList.contains("active")),e(o).trigger("change")),o.focus(),n=!1}}this._element.hasAttribute("disabled")||this._element.classList.contains("disabled")||(n&&this._element.setAttribute("aria-pressed",!this._element.classList.contains("active")),t&&e(this._element).toggleClass("active"))},n.dispose=function(){e.removeData(this._element,"bs.button"),this._element=null},t._jQueryInterface=function(n){return this.each((function(){var i=e(this).data("bs.button");i||(i=new t(this),e(this).data("bs.button",i)),"toggle"===n&&i[n]()}))},o(t,null,[{key:"VERSION",get:function(){return"4.5.0"}}]),t}();e(document).on("click.bs.button.data-api",'[data-toggle^="button"]',(function(t){var n=t.target,i=n;if(e(n).hasClass("btn")||(n=e(n).closest(".btn")[0]),!n||n.hasAttribute("disabled")||n.classList.contains("disabled"))t.preventDefault();else{var o=n.querySelector('input:not([type="hidden"])');if(o&&(o.hasAttribute("disabled")||o.classList.contains("disabled")))return void t.preventDefault();"LABEL"===i.tagName&&o&&"checkbox"===o.type&&t.preventDefault(),g._jQueryInterface.call(e(n),"toggle")}})).on("focus.bs.button.data-api blur.bs.button.data-api",'[data-toggle^="button"]',(function(t){var n=e(t.target).closest(".btn")[0];e(n).toggleClass("focus",/^focus(in)?$/.test(t.type))})),e(window).on("load.bs.button.data-api",(function(){for(var t=[].slice.call(document.querySelectorAll('[data-toggle="buttons"] .btn')),e=0,n=t.length;e0,this._pointerEvent=Boolean(window.PointerEvent||window.MSPointerEvent),this._addEventListeners()}var n=t.prototype;return n.next=function(){this._isSliding||this._slide("next")},n.nextWhenVisible=function(){!document.hidden&&e(this._element).is(":visible")&&"hidden"!==e(this._element).css("visibility")&&this.next()},n.prev=function(){this._isSliding||this._slide("prev")},n.pause=function(t){t||(this._isPaused=!0),this._element.querySelector(".carousel-item-next, .carousel-item-prev")&&(c.triggerTransitionEnd(this._element),this.cycle(!0)),clearInterval(this._interval),this._interval=null},n.cycle=function(t){t||(this._isPaused=!1),this._interval&&(clearInterval(this._interval),this._interval=null),this._config.interval&&!this._isPaused&&(this._interval=setInterval((document.visibilityState?this.nextWhenVisible:this.next).bind(this),this._config.interval))},n.to=function(t){var n=this;this._activeElement=this._element.querySelector(".active.carousel-item");var i=this._getItemIndex(this._activeElement);if(!(t>this._items.length-1||t<0))if(this._isSliding)e(this._element).one("slid.bs.carousel",(function(){return n.to(t)}));else{if(i===t)return this.pause(),void this.cycle();var o=t>i?"next":"prev";this._slide(o,this._items[t])}},n.dispose=function(){e(this._element).off(p),e.removeData(this._element,"bs.carousel"),this._items=null,this._config=null,this._element=null,this._interval=null,this._isPaused=null,this._isSliding=null,this._activeElement=null,this._indicatorsElement=null},n._getConfig=function(t){return t=a(a({},v),t),c.typeCheckConfig(m,t,b),t},n._handleSwipe=function(){var t=Math.abs(this.touchDeltaX);if(!(t<=40)){var e=t/this.touchDeltaX;this.touchDeltaX=0,e>0&&this.prev(),e<0&&this.next()}},n._addEventListeners=function(){var t=this;this._config.keyboard&&e(this._element).on("keydown.bs.carousel",(function(e){return t._keydown(e)})),"hover"===this._config.pause&&e(this._element).on("mouseenter.bs.carousel",(function(e){return t.pause(e)})).on("mouseleave.bs.carousel",(function(e){return t.cycle(e)})),this._config.touch&&this._addTouchEventListeners()},n._addTouchEventListeners=function(){var t=this;if(this._touchSupported){var n=function(e){t._pointerEvent&&y[e.originalEvent.pointerType.toUpperCase()]?t.touchStartX=e.originalEvent.clientX:t._pointerEvent||(t.touchStartX=e.originalEvent.touches[0].clientX)},i=function(e){t._pointerEvent&&y[e.originalEvent.pointerType.toUpperCase()]&&(t.touchDeltaX=e.originalEvent.clientX-t.touchStartX),t._handleSwipe(),"hover"===t._config.pause&&(t.pause(),t.touchTimeout&&clearTimeout(t.touchTimeout),t.touchTimeout=setTimeout((function(e){return t.cycle(e)}),500+t._config.interval))};e(this._element.querySelectorAll(".carousel-item img")).on("dragstart.bs.carousel",(function(t){return t.preventDefault()})),this._pointerEvent?(e(this._element).on("pointerdown.bs.carousel",(function(t){return n(t)})),e(this._element).on("pointerup.bs.carousel",(function(t){return i(t)})),this._element.classList.add("pointer-event")):(e(this._element).on("touchstart.bs.carousel",(function(t){return n(t)})),e(this._element).on("touchmove.bs.carousel",(function(e){return function(e){e.originalEvent.touches&&e.originalEvent.touches.length>1?t.touchDeltaX=0:t.touchDeltaX=e.originalEvent.touches[0].clientX-t.touchStartX}(e)})),e(this._element).on("touchend.bs.carousel",(function(t){return i(t)})))}},n._keydown=function(t){if(!/input|textarea/i.test(t.target.tagName))switch(t.which){case 37:t.preventDefault(),this.prev();break;case 39:t.preventDefault(),this.next()}},n._getItemIndex=function(t){return this._items=t&&t.parentNode?[].slice.call(t.parentNode.querySelectorAll(".carousel-item")):[],this._items.indexOf(t)},n._getItemByDirection=function(t,e){var n="next"===t,i="prev"===t,o=this._getItemIndex(e),s=this._items.length-1;if((i&&0===o||n&&o===s)&&!this._config.wrap)return e;var r=(o+("prev"===t?-1:1))%this._items.length;return-1===r?this._items[this._items.length-1]:this._items[r]},n._triggerSlideEvent=function(t,n){var i=this._getItemIndex(t),o=this._getItemIndex(this._element.querySelector(".active.carousel-item")),s=e.Event("slide.bs.carousel",{relatedTarget:t,direction:n,from:o,to:i});return e(this._element).trigger(s),s},n._setActiveIndicatorElement=function(t){if(this._indicatorsElement){var n=[].slice.call(this._indicatorsElement.querySelectorAll(".active"));e(n).removeClass("active");var i=this._indicatorsElement.children[this._getItemIndex(t)];i&&e(i).addClass("active")}},n._slide=function(t,n){var i,o,s,r=this,a=this._element.querySelector(".active.carousel-item"),l=this._getItemIndex(a),h=n||a&&this._getItemByDirection(t,a),u=this._getItemIndex(h),d=Boolean(this._interval);if("next"===t?(i="carousel-item-left",o="carousel-item-next",s="left"):(i="carousel-item-right",o="carousel-item-prev",s="right"),h&&e(h).hasClass("active"))this._isSliding=!1;else if(!this._triggerSlideEvent(h,s).isDefaultPrevented()&&a&&h){this._isSliding=!0,d&&this.pause(),this._setActiveIndicatorElement(h);var f=e.Event("slid.bs.carousel",{relatedTarget:h,direction:s,from:l,to:u});if(e(this._element).hasClass("slide")){e(h).addClass(o),c.reflow(h),e(a).addClass(i),e(h).addClass(i);var g=parseInt(h.getAttribute("data-interval"),10);g?(this._config.defaultInterval=this._config.defaultInterval||this._config.interval,this._config.interval=g):this._config.interval=this._config.defaultInterval||this._config.interval;var m=c.getTransitionDurationFromElement(a);e(a).one(c.TRANSITION_END,(function(){e(h).removeClass(i+" "+o).addClass("active"),e(a).removeClass("active "+o+" "+i),r._isSliding=!1,setTimeout((function(){return e(r._element).trigger(f)}),0)})).emulateTransitionEnd(m)}else e(a).removeClass("active"),e(h).addClass("active"),this._isSliding=!1,e(this._element).trigger(f);d&&this.cycle()}},t._jQueryInterface=function(n){return this.each((function(){var i=e(this).data("bs.carousel"),o=a(a({},v),e(this).data());"object"==typeof n&&(o=a(a({},o),n));var s="string"==typeof n?n:o.slide;if(i||(i=new t(this,o),e(this).data("bs.carousel",i)),"number"==typeof n)i.to(n);else if("string"==typeof s){if("undefined"==typeof i[s])throw new TypeError('No method named "'+s+'"');i[s]()}else o.interval&&o.ride&&(i.pause(),i.cycle())}))},t._dataApiClickHandler=function(n){var i=c.getSelectorFromElement(this);if(i){var o=e(i)[0];if(o&&e(o).hasClass("carousel")){var s=a(a({},e(o).data()),e(this).data()),r=this.getAttribute("data-slide-to");r&&(s.interval=!1),t._jQueryInterface.call(e(o),s),r&&e(o).data("bs.carousel").to(r),n.preventDefault()}}},o(t,null,[{key:"VERSION",get:function(){return"4.5.0"}},{key:"Default",get:function(){return v}}]),t}();e(document).on("click.bs.carousel.data-api","[data-slide], [data-slide-to]",E._dataApiClickHandler),e(window).on("load.bs.carousel.data-api",(function(){for(var t=[].slice.call(document.querySelectorAll('[data-ride="carousel"]')),n=0,i=t.length;n0&&(this._selector=r,this._triggerArray.push(s))}this._parent=this._config.parent?this._getParent():null,this._config.parent||this._addAriaAndCollapsedClass(this._element,this._triggerArray),this._config.toggle&&this.toggle()}var n=t.prototype;return n.toggle=function(){e(this._element).hasClass("show")?this.hide():this.show()},n.show=function(){var n,i,o=this;if(!this._isTransitioning&&!e(this._element).hasClass("show")&&(this._parent&&0===(n=[].slice.call(this._parent.querySelectorAll(".show, .collapsing")).filter((function(t){return"string"==typeof o._config.parent?t.getAttribute("data-parent")===o._config.parent:t.classList.contains("collapse")}))).length&&(n=null),!(n&&(i=e(n).not(this._selector).data("bs.collapse"))&&i._isTransitioning))){var s=e.Event("show.bs.collapse");if(e(this._element).trigger(s),!s.isDefaultPrevented()){n&&(t._jQueryInterface.call(e(n).not(this._selector),"hide"),i||e(n).data("bs.collapse",null));var r=this._getDimension();e(this._element).removeClass("collapse").addClass("collapsing"),this._element.style[r]=0,this._triggerArray.length&&e(this._triggerArray).removeClass("collapsed").attr("aria-expanded",!0),this.setTransitioning(!0);var a="scroll"+(r[0].toUpperCase()+r.slice(1)),l=c.getTransitionDurationFromElement(this._element);e(this._element).one(c.TRANSITION_END,(function(){e(o._element).removeClass("collapsing").addClass("collapse show"),o._element.style[r]="",o.setTransitioning(!1),e(o._element).trigger("shown.bs.collapse")})).emulateTransitionEnd(l),this._element.style[r]=this._element[a]+"px"}}},n.hide=function(){var t=this;if(!this._isTransitioning&&e(this._element).hasClass("show")){var n=e.Event("hide.bs.collapse");if(e(this._element).trigger(n),!n.isDefaultPrevented()){var i=this._getDimension();this._element.style[i]=this._element.getBoundingClientRect()[i]+"px",c.reflow(this._element),e(this._element).addClass("collapsing").removeClass("collapse show");var o=this._triggerArray.length;if(o>0)for(var s=0;s0},i._getOffset=function(){var t=this,e={};return"function"==typeof this._config.offset?e.fn=function(e){return e.offsets=a(a({},e.offsets),t._config.offset(e.offsets,t._element)||{}),e}:e.offset=this._config.offset,e},i._getPopperConfig=function(){var t={placement:this._getPlacement(),modifiers:{offset:this._getOffset(),flip:{enabled:this._config.flip},preventOverflow:{boundariesElement:this._config.boundary}}};return"static"===this._config.display&&(t.modifiers.applyStyle={enabled:!1}),a(a({},t),this._config.popperConfig)},t._jQueryInterface=function(n){return this.each((function(){var i=e(this).data("bs.dropdown");if(i||(i=new t(this,"object"==typeof n?n:null),e(this).data("bs.dropdown",i)),"string"==typeof n){if("undefined"==typeof i[n])throw new TypeError('No method named "'+n+'"');i[n]()}}))},t._clearMenus=function(n){if(!n||3!==n.which&&("keyup"!==n.type||9===n.which))for(var i=[].slice.call(document.querySelectorAll('[data-toggle="dropdown"]')),o=0,s=i.length;o0&&r--,40===n.which&&rdocument.documentElement.clientHeight;!this._isBodyOverflowing&&t&&(this._element.style.paddingLeft=this._scrollbarWidth+"px"),this._isBodyOverflowing&&!t&&(this._element.style.paddingRight=this._scrollbarWidth+"px")},n._resetAdjustments=function(){this._element.style.paddingLeft="",this._element.style.paddingRight=""},n._checkScrollbar=function(){var t=document.body.getBoundingClientRect();this._isBodyOverflowing=Math.round(t.left+t.right)
',trigger:"hover focus",title:"",delay:0,html:!1,selector:!1,placement:"top",offset:0,container:!1,fallbackPlacement:"flip",boundary:"scrollParent",sanitize:!0,sanitizeFn:null,whiteList:F,popperConfig:null},Y={HIDE:"hide.bs.tooltip",HIDDEN:"hidden.bs.tooltip",SHOW:"show.bs.tooltip",SHOWN:"shown.bs.tooltip",INSERTED:"inserted.bs.tooltip",CLICK:"click.bs.tooltip",FOCUSIN:"focusin.bs.tooltip",FOCUSOUT:"focusout.bs.tooltip",MOUSEENTER:"mouseenter.bs.tooltip",MOUSELEAVE:"mouseleave.bs.tooltip"},$=function(){function t(t,e){if("undefined"==typeof n)throw new TypeError("Bootstrap's tooltips require Popper.js (https://popper.js.org/)");this._isEnabled=!0,this._timeout=0,this._hoverState="",this._activeTrigger={},this._popper=null,this.element=t,this.config=this._getConfig(e),this.tip=null,this._setListeners()}var i=t.prototype;return i.enable=function(){this._isEnabled=!0},i.disable=function(){this._isEnabled=!1},i.toggleEnabled=function(){this._isEnabled=!this._isEnabled},i.toggle=function(t){if(this._isEnabled)if(t){var n=this.constructor.DATA_KEY,i=e(t.currentTarget).data(n);i||(i=new this.constructor(t.currentTarget,this._getDelegateConfig()),e(t.currentTarget).data(n,i)),i._activeTrigger.click=!i._activeTrigger.click,i._isWithActiveTrigger()?i._enter(null,i):i._leave(null,i)}else{if(e(this.getTipElement()).hasClass("show"))return void this._leave(null,this);this._enter(null,this)}},i.dispose=function(){clearTimeout(this._timeout),e.removeData(this.element,this.constructor.DATA_KEY),e(this.element).off(this.constructor.EVENT_KEY),e(this.element).closest(".modal").off("hide.bs.modal",this._hideModalHandler),this.tip&&e(this.tip).remove(),this._isEnabled=null,this._timeout=null,this._hoverState=null,this._activeTrigger=null,this._popper&&this._popper.destroy(),this._popper=null,this.element=null,this.config=null,this.tip=null},i.show=function(){var t=this;if("none"===e(this.element).css("display"))throw new Error("Please use show on visible elements");var i=e.Event(this.constructor.Event.SHOW);if(this.isWithContent()&&this._isEnabled){e(this.element).trigger(i);var o=c.findShadowRoot(this.element),s=e.contains(null!==o?o:this.element.ownerDocument.documentElement,this.element);if(i.isDefaultPrevented()||!s)return;var r=this.getTipElement(),a=c.getUID(this.constructor.NAME);r.setAttribute("id",a),this.element.setAttribute("aria-describedby",a),this.setContent(),this.config.animation&&e(r).addClass("fade");var l="function"==typeof this.config.placement?this.config.placement.call(this,r,this.element):this.config.placement,h=this._getAttachment(l);this.addAttachmentClass(h);var u=this._getContainer();e(r).data(this.constructor.DATA_KEY,this),e.contains(this.element.ownerDocument.documentElement,this.tip)||e(r).appendTo(u),e(this.element).trigger(this.constructor.Event.INSERTED),this._popper=new n(this.element,r,this._getPopperConfig(h)),e(r).addClass("show"),"ontouchstart"in document.documentElement&&e(document.body).children().on("mouseover",null,e.noop);var d=function(){t.config.animation&&t._fixTransition();var n=t._hoverState;t._hoverState=null,e(t.element).trigger(t.constructor.Event.SHOWN),"out"===n&&t._leave(null,t)};if(e(this.tip).hasClass("fade")){var f=c.getTransitionDurationFromElement(this.tip);e(this.tip).one(c.TRANSITION_END,d).emulateTransitionEnd(f)}else d()}},i.hide=function(t){var n=this,i=this.getTipElement(),o=e.Event(this.constructor.Event.HIDE),s=function(){"show"!==n._hoverState&&i.parentNode&&i.parentNode.removeChild(i),n._cleanTipClass(),n.element.removeAttribute("aria-describedby"),e(n.element).trigger(n.constructor.Event.HIDDEN),null!==n._popper&&n._popper.destroy(),t&&t()};if(e(this.element).trigger(o),!o.isDefaultPrevented()){if(e(i).removeClass("show"),"ontouchstart"in document.documentElement&&e(document.body).children().off("mouseover",null,e.noop),this._activeTrigger.click=!1,this._activeTrigger.focus=!1,this._activeTrigger.hover=!1,e(this.tip).hasClass("fade")){var r=c.getTransitionDurationFromElement(i);e(i).one(c.TRANSITION_END,s).emulateTransitionEnd(r)}else s();this._hoverState=""}},i.update=function(){null!==this._popper&&this._popper.scheduleUpdate()},i.isWithContent=function(){return Boolean(this.getTitle())},i.addAttachmentClass=function(t){e(this.getTipElement()).addClass("bs-tooltip-"+t)},i.getTipElement=function(){return this.tip=this.tip||e(this.config.template)[0],this.tip},i.setContent=function(){var t=this.getTipElement();this.setElementContent(e(t.querySelectorAll(".tooltip-inner")),this.getTitle()),e(t).removeClass("fade show")},i.setElementContent=function(t,n){"object"!=typeof n||!n.nodeType&&!n.jquery?this.config.html?(this.config.sanitize&&(n=H(n,this.config.whiteList,this.config.sanitizeFn)),t.html(n)):t.text(n):this.config.html?e(n).parent().is(t)||t.empty().append(n):t.text(e(n).text())},i.getTitle=function(){var t=this.element.getAttribute("data-original-title");return t||(t="function"==typeof this.config.title?this.config.title.call(this.element):this.config.title),t},i._getPopperConfig=function(t){var e=this;return a(a({},{placement:t,modifiers:{offset:this._getOffset(),flip:{behavior:this.config.fallbackPlacement},arrow:{element:".arrow"},preventOverflow:{boundariesElement:this.config.boundary}},onCreate:function(t){t.originalPlacement!==t.placement&&e._handlePopperPlacementChange(t)},onUpdate:function(t){return e._handlePopperPlacementChange(t)}}),this.config.popperConfig)},i._getOffset=function(){var t=this,e={};return"function"==typeof this.config.offset?e.fn=function(e){return e.offsets=a(a({},e.offsets),t.config.offset(e.offsets,t.element)||{}),e}:e.offset=this.config.offset,e},i._getContainer=function(){return!1===this.config.container?document.body:c.isElement(this.config.container)?e(this.config.container):e(document).find(this.config.container)},i._getAttachment=function(t){return K[t.toUpperCase()]},i._setListeners=function(){var t=this;this.config.trigger.split(" ").forEach((function(n){if("click"===n)e(t.element).on(t.constructor.Event.CLICK,t.config.selector,(function(e){return t.toggle(e)}));else if("manual"!==n){var i="hover"===n?t.constructor.Event.MOUSEENTER:t.constructor.Event.FOCUSIN,o="hover"===n?t.constructor.Event.MOUSELEAVE:t.constructor.Event.FOCUSOUT;e(t.element).on(i,t.config.selector,(function(e){return t._enter(e)})).on(o,t.config.selector,(function(e){return t._leave(e)}))}})),this._hideModalHandler=function(){t.element&&t.hide()},e(this.element).closest(".modal").on("hide.bs.modal",this._hideModalHandler),this.config.selector?this.config=a(a({},this.config),{},{trigger:"manual",selector:""}):this._fixTitle()},i._fixTitle=function(){var t=typeof this.element.getAttribute("data-original-title");(this.element.getAttribute("title")||"string"!==t)&&(this.element.setAttribute("data-original-title",this.element.getAttribute("title")||""),this.element.setAttribute("title",""))},i._enter=function(t,n){var i=this.constructor.DATA_KEY;(n=n||e(t.currentTarget).data(i))||(n=new this.constructor(t.currentTarget,this._getDelegateConfig()),e(t.currentTarget).data(i,n)),t&&(n._activeTrigger["focusin"===t.type?"focus":"hover"]=!0),e(n.getTipElement()).hasClass("show")||"show"===n._hoverState?n._hoverState="show":(clearTimeout(n._timeout),n._hoverState="show",n.config.delay&&n.config.delay.show?n._timeout=setTimeout((function(){"show"===n._hoverState&&n.show()}),n.config.delay.show):n.show())},i._leave=function(t,n){var i=this.constructor.DATA_KEY;(n=n||e(t.currentTarget).data(i))||(n=new this.constructor(t.currentTarget,this._getDelegateConfig()),e(t.currentTarget).data(i,n)),t&&(n._activeTrigger["focusout"===t.type?"focus":"hover"]=!1),n._isWithActiveTrigger()||(clearTimeout(n._timeout),n._hoverState="out",n.config.delay&&n.config.delay.hide?n._timeout=setTimeout((function(){"out"===n._hoverState&&n.hide()}),n.config.delay.hide):n.hide())},i._isWithActiveTrigger=function(){for(var t in this._activeTrigger)if(this._activeTrigger[t])return!0;return!1},i._getConfig=function(t){var n=e(this.element).data();return Object.keys(n).forEach((function(t){-1!==V.indexOf(t)&&delete n[t]})),"number"==typeof(t=a(a(a({},this.constructor.Default),n),"object"==typeof t&&t?t:{})).delay&&(t.delay={show:t.delay,hide:t.delay}),"number"==typeof t.title&&(t.title=t.title.toString()),"number"==typeof t.content&&(t.content=t.content.toString()),c.typeCheckConfig(U,t,this.constructor.DefaultType),t.sanitize&&(t.template=H(t.template,t.whiteList,t.sanitizeFn)),t},i._getDelegateConfig=function(){var t={};if(this.config)for(var e in this.config)this.constructor.Default[e]!==this.config[e]&&(t[e]=this.config[e]);return t},i._cleanTipClass=function(){var t=e(this.getTipElement()),n=t.attr("class").match(W);null!==n&&n.length&&t.removeClass(n.join(""))},i._handlePopperPlacementChange=function(t){this.tip=t.instance.popper,this._cleanTipClass(),this.addAttachmentClass(this._getAttachment(t.placement))},i._fixTransition=function(){var t=this.getTipElement(),n=this.config.animation;null===t.getAttribute("x-placement")&&(e(t).removeClass("fade"),this.config.animation=!1,this.hide(),this.show(),this.config.animation=n)},t._jQueryInterface=function(n){return this.each((function(){var i=e(this).data("bs.tooltip"),o="object"==typeof n&&n;if((i||!/dispose|hide/.test(n))&&(i||(i=new t(this,o),e(this).data("bs.tooltip",i)),"string"==typeof n)){if("undefined"==typeof i[n])throw new TypeError('No method named "'+n+'"');i[n]()}}))},o(t,null,[{key:"VERSION",get:function(){return"4.5.0"}},{key:"Default",get:function(){return X}},{key:"NAME",get:function(){return U}},{key:"DATA_KEY",get:function(){return"bs.tooltip"}},{key:"Event",get:function(){return Y}},{key:"EVENT_KEY",get:function(){return".bs.tooltip"}},{key:"DefaultType",get:function(){return z}}]),t}();e.fn[U]=$._jQueryInterface,e.fn[U].Constructor=$,e.fn[U].noConflict=function(){return e.fn[U]=M,$._jQueryInterface};var J="popover",G=e.fn[J],Z=new RegExp("(^|\\s)bs-popover\\S+","g"),tt=a(a({},$.Default),{},{placement:"right",trigger:"click",content:"",template:''}),et=a(a({},$.DefaultType),{},{content:"(string|element|function)"}),nt={HIDE:"hide.bs.popover",HIDDEN:"hidden.bs.popover",SHOW:"show.bs.popover",SHOWN:"shown.bs.popover",INSERTED:"inserted.bs.popover",CLICK:"click.bs.popover",FOCUSIN:"focusin.bs.popover",FOCUSOUT:"focusout.bs.popover",MOUSEENTER:"mouseenter.bs.popover",MOUSELEAVE:"mouseleave.bs.popover"},it=function(t){var n,i;function s(){return t.apply(this,arguments)||this}i=t,(n=s).prototype=Object.create(i.prototype),n.prototype.constructor=n,n.__proto__=i;var r=s.prototype;return r.isWithContent=function(){return this.getTitle()||this._getContent()},r.addAttachmentClass=function(t){e(this.getTipElement()).addClass("bs-popover-"+t)},r.getTipElement=function(){return this.tip=this.tip||e(this.config.template)[0],this.tip},r.setContent=function(){var t=e(this.getTipElement());this.setElementContent(t.find(".popover-header"),this.getTitle());var n=this._getContent();"function"==typeof n&&(n=n.call(this.element)),this.setElementContent(t.find(".popover-body"),n),t.removeClass("fade show")},r._getContent=function(){return this.element.getAttribute("data-content")||this.config.content},r._cleanTipClass=function(){var t=e(this.getTipElement()),n=t.attr("class").match(Z);null!==n&&n.length>0&&t.removeClass(n.join(""))},s._jQueryInterface=function(t){return this.each((function(){var n=e(this).data("bs.popover"),i="object"==typeof t?t:null;if((n||!/dispose|hide/.test(t))&&(n||(n=new s(this,i),e(this).data("bs.popover",n)),"string"==typeof t)){if("undefined"==typeof n[t])throw new TypeError('No method named "'+t+'"');n[t]()}}))},o(s,null,[{key:"VERSION",get:function(){return"4.5.0"}},{key:"Default",get:function(){return tt}},{key:"NAME",get:function(){return J}},{key:"DATA_KEY",get:function(){return"bs.popover"}},{key:"Event",get:function(){return nt}},{key:"EVENT_KEY",get:function(){return".bs.popover"}},{key:"DefaultType",get:function(){return et}}]),s}($);e.fn[J]=it._jQueryInterface,e.fn[J].Constructor=it,e.fn[J].noConflict=function(){return e.fn[J]=G,it._jQueryInterface};var ot="scrollspy",st=e.fn[ot],rt={offset:10,method:"auto",target:""},at={offset:"number",method:"string",target:"(string|element)"},lt=function(){function t(t,n){var i=this;this._element=t,this._scrollElement="BODY"===t.tagName?window:t,this._config=this._getConfig(n),this._selector=this._config.target+" .nav-link,"+this._config.target+" .list-group-item,"+this._config.target+" .dropdown-item",this._offsets=[],this._targets=[],this._activeTarget=null,this._scrollHeight=0,e(this._scrollElement).on("scroll.bs.scrollspy",(function(t){return i._process(t)})),this.refresh(),this._process()}var n=t.prototype;return n.refresh=function(){var t=this,n=this._scrollElement===this._scrollElement.window?"offset":"position",i="auto"===this._config.method?n:this._config.method,o="position"===i?this._getScrollTop():0;this._offsets=[],this._targets=[],this._scrollHeight=this._getScrollHeight(),[].slice.call(document.querySelectorAll(this._selector)).map((function(t){var n,s=c.getSelectorFromElement(t);if(s&&(n=document.querySelector(s)),n){var r=n.getBoundingClientRect();if(r.width||r.height)return[e(n)[i]().top+o,s]}return null})).filter((function(t){return t})).sort((function(t,e){return t[0]-e[0]})).forEach((function(e){t._offsets.push(e[0]),t._targets.push(e[1])}))},n.dispose=function(){e.removeData(this._element,"bs.scrollspy"),e(this._scrollElement).off(".bs.scrollspy"),this._element=null,this._scrollElement=null,this._config=null,this._selector=null,this._offsets=null,this._targets=null,this._activeTarget=null,this._scrollHeight=null},n._getConfig=function(t){if("string"!=typeof(t=a(a({},rt),"object"==typeof t&&t?t:{})).target&&c.isElement(t.target)){var n=e(t.target).attr("id");n||(n=c.getUID(ot),e(t.target).attr("id",n)),t.target="#"+n}return c.typeCheckConfig(ot,t,at),t},n._getScrollTop=function(){return this._scrollElement===window?this._scrollElement.pageYOffset:this._scrollElement.scrollTop},n._getScrollHeight=function(){return this._scrollElement.scrollHeight||Math.max(document.body.scrollHeight,document.documentElement.scrollHeight)},n._getOffsetHeight=function(){return this._scrollElement===window?window.innerHeight:this._scrollElement.getBoundingClientRect().height},n._process=function(){var t=this._getScrollTop()+this._config.offset,e=this._getScrollHeight(),n=this._config.offset+e-this._getOffsetHeight();if(this._scrollHeight!==e&&this.refresh(),t>=n){var i=this._targets[this._targets.length-1];this._activeTarget!==i&&this._activate(i)}else{if(this._activeTarget&&t0)return this._activeTarget=null,void this._clear();for(var o=this._offsets.length;o--;){this._activeTarget!==this._targets[o]&&t>=this._offsets[o]&&("undefined"==typeof this._offsets[o+1]||t li > .active":".active";i=(i=e.makeArray(e(o).find(r)))[i.length-1]}var a=e.Event("hide.bs.tab",{relatedTarget:this._element}),l=e.Event("show.bs.tab",{relatedTarget:i});if(i&&e(i).trigger(a),e(this._element).trigger(l),!l.isDefaultPrevented()&&!a.isDefaultPrevented()){s&&(n=document.querySelector(s)),this._activate(this._element,o);var h=function(){var n=e.Event("hidden.bs.tab",{relatedTarget:t._element}),o=e.Event("shown.bs.tab",{relatedTarget:i});e(i).trigger(n),e(t._element).trigger(o)};n?this._activate(n,n.parentNode,h):h()}}},n.dispose=function(){e.removeData(this._element,"bs.tab"),this._element=null},n._activate=function(t,n,i){var o=this,s=(!n||"UL"!==n.nodeName&&"OL"!==n.nodeName?e(n).children(".active"):e(n).find("> li > .active"))[0],r=i&&s&&e(s).hasClass("fade"),a=function(){return o._transitionComplete(t,s,i)};if(s&&r){var l=c.getTransitionDurationFromElement(s);e(s).removeClass("show").one(c.TRANSITION_END,a).emulateTransitionEnd(l)}else a()},n._transitionComplete=function(t,n,i){if(n){e(n).removeClass("active");var o=e(n.parentNode).find("> .dropdown-menu .active")[0];o&&e(o).removeClass("active"),"tab"===n.getAttribute("role")&&n.setAttribute("aria-selected",!1)}if(e(t).addClass("active"),"tab"===t.getAttribute("role")&&t.setAttribute("aria-selected",!0),c.reflow(t),t.classList.contains("fade")&&t.classList.add("show"),t.parentNode&&e(t.parentNode).hasClass("dropdown-menu")){var s=e(t).closest(".dropdown")[0];if(s){var r=[].slice.call(s.querySelectorAll(".dropdown-toggle"));e(r).addClass("active")}t.setAttribute("aria-expanded",!0)}i&&i()},t._jQueryInterface=function(n){return this.each((function(){var i=e(this),o=i.data("bs.tab");if(o||(o=new t(this),i.data("bs.tab",o)),"string"==typeof n){if("undefined"==typeof o[n])throw new TypeError('No method named "'+n+'"');o[n]()}}))},o(t,null,[{key:"VERSION",get:function(){return"4.5.0"}}]),t}();e(document).on("click.bs.tab.data-api",'[data-toggle="tab"], [data-toggle="pill"], [data-toggle="list"]',(function(t){t.preventDefault(),ht._jQueryInterface.call(e(this),"show")})),e.fn.tab=ht._jQueryInterface,e.fn.tab.Constructor=ht,e.fn.tab.noConflict=function(){return e.fn.tab=ct,ht._jQueryInterface};var ut=e.fn.toast,dt={animation:"boolean",autohide:"boolean",delay:"number"},ft={animation:!0,autohide:!0,delay:500},gt=function(){function t(t,e){this._element=t,this._config=this._getConfig(e),this._timeout=null,this._setListeners()}var n=t.prototype;return n.show=function(){var t=this,n=e.Event("show.bs.toast");if(e(this._element).trigger(n),!n.isDefaultPrevented()){this._config.animation&&this._element.classList.add("fade");var i=function(){t._element.classList.remove("showing"),t._element.classList.add("show"),e(t._element).trigger("shown.bs.toast"),t._config.autohide&&(t._timeout=setTimeout((function(){t.hide()}),t._config.delay))};if(this._element.classList.remove("hide"),c.reflow(this._element),this._element.classList.add("showing"),this._config.animation){var o=c.getTransitionDurationFromElement(this._element);e(this._element).one(c.TRANSITION_END,i).emulateTransitionEnd(o)}else i()}},n.hide=function(){if(this._element.classList.contains("show")){var t=e.Event("hide.bs.toast");e(this._element).trigger(t),t.isDefaultPrevented()||this._close()}},n.dispose=function(){clearTimeout(this._timeout),this._timeout=null,this._element.classList.contains("show")&&this._element.classList.remove("show"),e(this._element).off("click.dismiss.bs.toast"),e.removeData(this._element,"bs.toast"),this._element=null,this._config=null},n._getConfig=function(t){return t=a(a(a({},ft),e(this._element).data()),"object"==typeof t&&t?t:{}),c.typeCheckConfig("toast",t,this.constructor.DefaultType),t},n._setListeners=function(){var t=this;e(this._element).on("click.dismiss.bs.toast",'[data-dismiss="toast"]',(function(){return t.hide()}))},n._close=function(){var t=this,n=function(){t._element.classList.add("hide"),e(t._element).trigger("hidden.bs.toast")};if(this._element.classList.remove("show"),this._config.animation){var i=c.getTransitionDurationFromElement(this._element);e(this._element).one(c.TRANSITION_END,n).emulateTransitionEnd(i)}else n()},t._jQueryInterface=function(n){return this.each((function(){var i=e(this),o=i.data("bs.toast");if(o||(o=new t(this,"object"==typeof n&&n),i.data("bs.toast",o)),"string"==typeof n){if("undefined"==typeof o[n])throw new TypeError('No method named "'+n+'"');o[n](this)}}))},o(t,null,[{key:"VERSION",get:function(){return"4.5.0"}},{key:"DefaultType",get:function(){return dt}},{key:"Default",get:function(){return ft}}]),t}();e.fn.toast=gt._jQueryInterface,e.fn.toast.Constructor=gt,e.fn.toast.noConflict=function(){return e.fn.toast=ut,gt._jQueryInterface},t.Alert=d,t.Button=g,t.Carousel=E,t.Collapse=D,t.Dropdown=j,t.Modal=R,t.Popover=it,t.Scrollspy=lt,t.Tab=ht,t.Toast=gt,t.Tooltip=$,t.Util=c,Object.defineProperty(t,"__esModule",{value:!0})})); diff --git a/buildroot/web-ui/data/www/bootstrap4-toggle.min.js b/buildroot/web-ui/data/www/bootstrap4-toggle.min.js new file mode 100644 index 000000000000..8e67abcdeb08 --- /dev/null +++ b/buildroot/web-ui/data/www/bootstrap4-toggle.min.js @@ -0,0 +1,10 @@ +/*\ +|*| ======================================================================== +|*| Bootstrap Toggle: bootstrap4-toggle.js v3.6.1 +|*| https://gitbrent.github.io/bootstrap4-toggle/ +|*| ======================================================================== +|*| Copyright 2018-2019 Brent Ely +|*| Licensed under MIT +|*| ======================================================================== +\*/ +!function(a){"use strict";function l(t,e){this.$element=a(t),this.options=a.extend({},this.defaults(),e),this.render()}l.VERSION="3.6.0",l.DEFAULTS={on:"On",off:"Off",onstyle:"primary",offstyle:"light",size:"normal",style:"",width:null,height:null},l.prototype.defaults=function(){return{on:this.$element.attr("data-on")||l.DEFAULTS.on,off:this.$element.attr("data-off")||l.DEFAULTS.off,onstyle:this.$element.attr("data-onstyle")||l.DEFAULTS.onstyle,offstyle:this.$element.attr("data-offstyle")||l.DEFAULTS.offstyle,size:this.$element.attr("data-size")||l.DEFAULTS.size,style:this.$element.attr("data-style")||l.DEFAULTS.style,width:this.$element.attr("data-width")||l.DEFAULTS.width,height:this.$element.attr("data-height")||l.DEFAULTS.height}},l.prototype.render=function(){this._onstyle="btn-"+this.options.onstyle,this._offstyle="btn-"+this.options.offstyle;var t="large"===this.options.size||"lg"===this.options.size?"btn-lg":"small"===this.options.size||"sm"===this.options.size?"btn-sm":"mini"===this.options.size||"xs"===this.options.size?"btn-xs":"",e=a('